From 9c2470582ac287935f1ee723f0f6571095ef48e8 Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Mon, 15 May 2023 14:38:29 +0200 Subject: [PATCH 1/9] Added the example panda_kinematic_control, which uses the DQ_PseudoinverseController() to perform a pose control of a FrankaEmikaPandaRobot(). --- manipulator/panda_kinematic_control.m | 60 +++++++++++++++++++++++++++ 1 file changed, 60 insertions(+) create mode 100644 manipulator/panda_kinematic_control.m diff --git a/manipulator/panda_kinematic_control.m b/manipulator/panda_kinematic_control.m new file mode 100644 index 0000000..52120db --- /dev/null +++ b/manipulator/panda_kinematic_control.m @@ -0,0 +1,60 @@ +function panda_kinematic_control() + + % use the namespace + include_namespace_dq + + % Create a new DQ_kinematics object with the Franka Emika Panda arm + % modified Denavit-Hartenberg parameters + panda = FrankaEmikaPandaRobot.kinematics(); + + % The controller is given by + % u = -pinv(J)*gain*task_error + % where J is the robot Jacobian, gain determines the convergence rate, + % and task_error is the error between the current task variable and + % the desired one. When the task error derivative is below + % stability_threshold, the closed-loop system is said to have reached a + % stable region. + controller = DQ_PseudoinverseController(panda); + controller.set_gain(100); + controller.set_stability_threshold(0.0001); + + % Initial configuration + q = [0; 0; 0; -pi/2; 0; pi/2; 0]; + + % Integration step + T = 0.001; + + % The task variable to be controlled is the end-effector pose + controller.set_control_objective(ControlObjective.Pose); + + % Generate a desired end-effector pose + xd = 1 + 0.5*E_*(i_*0.5 + j_*0.3 + k_*0.4); + task_reference = vec8(xd); + + % Prepare the visualization + figure; + view(70,25); + axis equal; + axis([-0.1, 0.6,-0.4, 0.6, -0.1, 0.8]) + hold on; + plot(panda, q, 'nojoints'); + plot(xd, 'scale', 0.1); + + % This is actually the important part on how to use the controller + while ~controller.system_reached_stable_region() + % Let us calculate the control input + u = controller.compute_setpoint_control_signal(q, task_reference); + + % Do a numerical integration to update the robot in Matlab. In an + % actual robot actuated by means of velocity inputs, this step is + % not necessary + q = q + T*u; + + % Draw the robot in Matlab + plot(panda, q', 'nojoints'); + + pvec = vec3(panda.fkm(q).translation); + plot3(pvec(1),pvec(2),pvec(3), 'ro'); + drawnow; + end +end From 23c1db6557a18a80c151aa5621b536aebcd71faf Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Sun, 28 May 2023 10:03:42 +0200 Subject: [PATCH 2/9] Added the missing license header to the file 'panda_kinematic_control'. --- manipulator/panda_kinematic_control.m | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/manipulator/panda_kinematic_control.m b/manipulator/panda_kinematic_control.m index 52120db..ddb7ee2 100644 --- a/manipulator/panda_kinematic_control.m +++ b/manipulator/panda_kinematic_control.m @@ -1,5 +1,29 @@ -function panda_kinematic_control() +% panda_kinematic_control() performs a pseudoinverse pose control using a +% Franka Emika Panda robot. + +% (C) Copyright 2011-2023 DQ Robotics Developers +% +% This file is part of DQ Robotics. +% +% DQ Robotics is free software: you can redistribute it and/or modify +% it under the terms of the GNU Lesser General Public License as published by +% the Free Software Foundation, either version 3 of the License, or +% (at your option) any later version. +% +% DQ Robotics is distributed in the hope that it will be useful, +% but WITHOUT ANY WARRANTY; without even the implied warranty of +% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +% GNU Lesser General Public License for more details. +% +% You should have received a copy of the GNU Lesser General Public License +% along with DQ Robotics. If not, see . +% +% DQ Robotics website: dqrobotics.github.io +% +% Contributors to this file: +% Frederico Fernandes Afonso Silva - frederico.silva@ieee.org +function panda_kinematic_control() % use the namespace include_namespace_dq From ca8f9eefd45b6e1f8b7be1696ae43ccbe410c8bd Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Fri, 16 Feb 2024 15:39:49 +0000 Subject: [PATCH 3/9] Added example 'cuboid_inertial_parameters.m'. --- .../cuboid-inertial-parameters.ttt | Bin 0 -> 251664 bytes .../cuboid_inertial_parameters.m | 73 ++++++++++++++++++ 2 files changed, 73 insertions(+) create mode 100644 vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt create mode 100644 vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m diff --git a/vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt b/vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt new file mode 100644 index 0000000000000000000000000000000000000000..8a549b33ef93479ae7e2c94220f49e866bb6a9db GIT binary patch literal 251664 zcmeFad0dlszCA7?S^;rEKrN!UK&gaC6%hfUU{w^PrA782xMD2PAOr{|Zb2;ylxTv0 zpaNFeS7Qhv2r4oW5R^rhM218VNdjRBO9;RBgPl%$Z|}_9*W6Zr-`D&xnE=U?=lMM6 zbKd8i_d9j3%U547oiSs^68N8z>Zl6*-;5dY$ukzrn6W@<`iK8K{AUIJvjYEbu7KAg z8=qBQwM@KDdMXJBaC_vq`}3bRF62IYxM#!C7K=yTS9USfzTGdb-moq1L5PT_Y>vIP zedi{WE5_){=<@nca(nNs9GI`Kq`zw<`E<$RLw2kKy~!lPsu@<55zeR@=833?ovYhV zk+o)K?F~`C8XudtcUGXvTMMVDd2RhO)?L>7D(NpqQHs>F8}^>FF-%(c#?UF?ZIFhJ z{T+h+j7Wp=FH`C1j&AkeT%0qwTlssfOS=rP!Piz*Fx!Y1_GcZR^;ItI>*kr3nollzU6ugk7-k{^$xO%ZKZpfv5T?Rm}7cyKdkBwcIg zd5PUSYp1;-I&=F{#^=xfHbL#2S8vb7*hmIWYqwzMw#d|P?!G)~w(QFG|2+B6BK!vl z|Hdw`Iuqqzb^pqIw|#bR$>P|?hrTBN#?k(dwxkO~`*FSecisR(_ZE5-k$lkG5Yh+ zxv0rIr`FMb*r#95425`w6GhCnQ-{a1z`m)TkV~3XThn{kCl&fgH0*rMJ> zd)+M?Fyg92->AnARS#`dxXB1Z4YS)FO%0i z`B1m*=!%uK0V9nIqQ z=9!fF+Ab%)<1TE7_cab&7tO@Q*G?pr?Nr&_o)G;`Gg-&4)WgGuL~po7d>@*6M?nK>zX?7Tk8Fq8Bv2%bY+=EKNl!lTz6t1wVP=&rhyDUVSM}d61#tE`MmVJxg0FNn95VQDU^COReVp&F zdAG#kz^oYx%&l~awBhFF-NN*J*tgzA$!}9I?$K8(#=?{WuW_IEz72X$cX3KCGISge z0X*1Np%m%0UkdLUrt^)>T*!9+TO$5HtYJ@=+&8uh*4eRAQFc}+jh{Won|;H`1V8rm zA-L` zhub&;buVrGEm5hlWZy6GV~)zoIi8NQ7ZK>yyOYjw_ocJM_@>^?x#;HYr?z5V&%2X! zU)3wG*4J@ny4ZKk^usLV*{n0s?pDaNwGAhl(G02M2fIT%Voi^^pNGN}w#w7tJx~9N zqVFh$&7sYo7iq=lM_1_FtTYT(uwXsv{7txs!v8um3O#irOwngY8xGHxWrxVS_ z`^OAEkdC0_`bDhc(z6z|L`?D@XO(M{2t4-oDXjEV@AhKVS}JoN*{LSRnZiF@m)0P`to^Pw>y3p=sDNdTg>||<#|Gkt=_o% zN^JUny{wikhsLFqC0QXK28D?Be`NU0$)M^*4SO(_>b~75dF2dqD6PtR)4~V6zHt(Bz`Vea4EnLy*v^MO-(msu&#rL9joVd^%h_O^!$)WW!RTTJXe3$L={+VUp!yQ?36y{?)^PsfxM0)hl z^Z&l+b0RDCyv8E;NBin4&$Z+pG2F5P?eoPx{0HNeU)9ndzN=czY&hk_eQb4jp0r`# zdTQzPa!-?`vEHZZVYoL-qb(w0Lw1ue4x8hovYuH8Ej{@Ka3AQ&u6O}qi}O8Z=uekB z%YLPsrV)Ow(k}*x-?R!Hr%{dLRvRwDcsdUk{xi1v^*;JTF3aVP#qwGzAl#^HGtit8 z#1K-K*ZaA@J!xY-jg~s@QED_FWjOxogU7-M6?Queo1+&GB$;y^PFL)aPK$(TulK70 zw1=i{b^oM-DomU5`W3={#Z7<6n*P4f`0DfhKeoT!dPn%zzzR5O*neQB_8xobj(E!(hA-PozkPC?k1{~$LXciw^`5++tmNq8`R}0E z7l$8O5*GfJsvO(sFgf@C2M8&%o4E9mG2fNnLS(ugzL$td4)b28NPV49V_|Flx|_?t zxj;G_74?TR#P6f|@8vx;YSW{;ONZG%%opcQoBvABPE+CE z{nFfqhZktIDGd=tDen&biKO={nEY~ITQ}?9dii?3FzZbQX72B%8E&zigDs0vKt*>hdiHkw4TZ{rHl@^IVHPQ z8km7`RAmOLZH2Qib4k{a)tL{Ng5K@CHA{WQp@rP48B5RO%PZBZK>CrPbd?Gv(xin@hbpGGu`)%r&@~zFRv~nRz>x_4)TWpCNsv)IE zMR@K9zB8>tHiK-e_NpOl-)rlJFu&_JwYYu^!Z*ezzW5+8+kE6pW#ncIl+X6lExXpx z{uA_XY+~pAePM5#7{3Z`eCYSYKW`oVW&Xu^+*9jG3HWi^6*J+G=1N~wgS*K!t`bu% z9p7Q@s3FX=yu2w~&-MdkP{*I2osHa&uG8uj7W=+F-<}tfTe5{lXje z$-}m3PX3*Jf=YM%(>8s`^Rr7L@7(yAt!_S};(Pz6J&M5OM}E=54Mu2VjeT!ZP(uS3 z=K`i6y_&uyX$UXBHCk_p@5mog{Ho}$N_R@qoVD5D6NJwV{!jrax;4vmo|7d#+O&Kh zzWg6v4gk)`CU(mr%aL=JXP32?rC+uUbe~uKgybdeduvseUYI5wY8+@B^GkmCHqcAN z{7KsKS5vgi``eX$?@sH`Dwix*;9K@9Lmp{ze(j-;=&IoUZS(dhc$ay$^77+-Zs>da z7kv6&1N>4n&z+Vz2+I;Ps=V_aM?P#uq1U%;5#~LaLr%&I2`<;Qc{N*8-&rd0>g z@04C;2qTB84a4?v9ODQyx@k=${$bnlt{hLNia)RsYQG`3DkATZ*+wyDvtWU>Fmj(R zxwPb8bE>yh@Sq}POO`hY&-TNz-(ONL8GOGxD)(tVwaQbAZaHi`v+Mp+u2Q~J0~04Z zAOGLh;_o;4-}{q#EoZs3a>2_NOurv6$~^Z&!G~r4;_bLAT_C=Dt}tf?#!G!4VT|i{ zS!2rL{cTWkX+-18(MHgjRuQf@1RBvs9uSe){Q8nJ)ttpBK`{1v+FH{7X;C_N6+!`O6pIg$Iq*oW{x)w^H4 z?N2zf>5sU*tf9e z^9$C41%2fj)m|A@~h%{F80_&E2=O>p}V#j|Q}to`_afrm4(6kVyY{V0TnMUNzYJ zXIEIIbmo7I=|0rWUGVJP0RLz6t*kv$c;?IN2Eq?@GQV@PFCGdWmC)X&Yr1FWl;$BS_Ej@igA?^KmMDw-{TjT_;y8XAHO0AFue5M>D{+Kp!^f)sN2e{5nPf)DrPE0nUizOdxM+>_Dnn~{_E`&#v_ZeE*s{ZGa-(`!#l$Em6QDX6J=VbYE@ zx>XSj?A`BwZ!qjnzk;utPgeU^+|;>gRq8r4K%iCJT-#vb$7uK4<34vr&X3&30xEoG zy1zLEy?kq8&c~9!UmR86T&p%PWjv?kYhz*8%|$)(>9s~L9jdP%3+2WB$kj|rtE82m z79`RTaQ&mA@~4$v7f9b{s+D+M9Se->?VHaHKDF^A={>+{qqUV0>3mYqY3Lf@)5`r2Dau1|myiPFF^sUYCY1KlIDlKDI3l z6248Gxq|+3%TChAk_vuh2;-hczE`6&Y0B#X3=LiCetW!9XPi%@tsT0P^z$V6pSG9& z5!{StD96ZtIZK#Q$MhKQ=V}(QDnA}BK+gZGX47E*@qoa}h@uCTrc=i2VI9l9?m7HX z6o&VnY4z*%C3_RL#GsuPb*14e_gp`Vf7wC$@QUGYY1T9QTDrd+Cez+ zh03{j7FVnHyMMIXfA`J*;JE+ppKcF%+bu0WnES6zU;asJ8hv}Y$;Y%zf7_w|?sEU< zI3I;}{eKo()<#q0O5a_FZJ9nN*_m}{Ru+$vW}bU$XKr@L5y1g8&wP_ofq-Wl(c(FKA49; z2~aq@kyXnDqn>uUEc>`4p8O|QQ^uypxi{yL3W^ECNmVYcomNxs_EtD&(BbkrNnWf`oTZeTcWpPF${KLJZxju6y`3Dl1Lgsx@K-FlGu&LQ zy}zJlH@c_b)8cnNI!qBUxtZx_T{l*y^_(bze_WuHtNRt4lI-|`tPO?X#5s?|b4p!hhax#7Wy zYBQd5tGBpmU9rffBK9fy!nTvi_neV~LgF}}% zMTOs-Gwlcnuf4=>3~|gT7|-m>KyKW=SEr==huvNU93BoLx9(>aQ!PEnYBrsw@VD0e zliI$n<|DMD8w(UozO%}H+Jl?$J-p4FKs~H*O76|v2*;Z>4M!(ZP91_nS+9hAp5LEXH#cSk z`3yZ=SIu^jc>&Z1HZaDAtpq5OCG08CNCNB(}@Y z1{D@@Yeh%#(GPF>1s5L9H@leSAAxp~Dp0P44s+shV#y zamN(btI?X7BJ=n)a)bz5XEH_>%P*KbXSXgF_28Xj0xg7w882i?UZV|ENmQ9t%8!DS z@Qwjtt8V@Ri9aD5u-aeTLP>irb-rR`1JvbJrUM8$m8-sl-KqnW7oleJ2{AZWm7mez z+VZUwP#vbL0+c+U9@ z^(sOeZ16BWW4~Z=f^N!#`8MiO$pzXF%3$>_i5p6;Ldc9ef)}az^q0nHQ#-4zG0smL z82v?)!23GXMl8poqkr+0u&2#Q$+x^Ja}8EhZ?$4I?~=r<8EqoOU= zS-~x?pbmshl&3Z0ZFg6X7Prd9@-RXdyXDKB9>SJA_8VzGcG0m+bssE8m+`LF*)7hj zd-d08p+bI?L$6fg7B+E#NLF)_6ZycDQRq%UB|q;_7QjHwY*XR4STiktM+9e5XNrAN9ZaOCRRWu#l>QOKTtW2)pN~kOHj=hQ~Jm?b_@944b)uiiGPr-pjM{701 zI?X4uIJawP^XMZ00M4v<`J%cB4|y0zba3*HVy@YECc1}>Ef#wkSR7&31#r$fb)V-E zsX*BiPLsQB#EwC&-{%N>+6@#n;{CjCm>n99)?se76Bg5}5VJ0eK&bGT_Vrs3RfVRKxNpvy?*X6OfuX?WGwI;lC_A{JRz z-!$5Y4T)LvT#K#Y^+d(LBNw-WHiR}X<$?g{FXmhb+o*!Grws)$E+fT!6lmA|oNmco zjMK8chH5PgKf&|GDH;wp*M%<^KLJWCW-qILCrD9id#-hfPj^*otIy`E0WBKnbIBTB zk5GnBt|sVGMb%K~p*pMbF084qb=+aOP{|9(cezN8Hq2;tiw;rD{4p~w!h-PTYDzTF zyn3UEKRklwwbbYqr9I&_(wf{~|nl zwHwN=Tipjh$;i>-C%9pm1`pgc^ZKyP0*=AL0sAT75er zA`2S0L1dGfNwJZ*pYgXp$8#)Ty{trY|AihI=>Zz$q$#5)Syz z;uP^4pOG45)>&ma+zBUgF@4D6E)>{1HUZ|zqN$!T?rwCac|X+q!im{+qfX+?_<{!9 zYdR+){!0D95t?tn;mJET6}SoNip<1umVSw`A_GpO>|y+sS-@|6q%QM&5`hSz9&3ih z0AQzzswSMK)S6hB?jn9w;y9gCaV$_MCc`sk3^7?G-d}S?@7Pf~voO3dv3*J{z8`*_ zKxZ1kq3TmB-qgJFM&tE}bV<-8hyq~|FBBsji#`e=O|piU zdfrn@?lU2?$Ky_A;~dv5ICPDzE1Jv>-j32I9~Ok+I*ALFoI5B6r_)|EIc;>fEG6x* zEK)%*$!43QCdUlnzXGZgm(!lVKj%OhS<^_LuI?*3#hmco2G7t2w~k*h+9uVi(M z3i;7KqwLHiL1;1ZteAhc<3ji0lAP*m#@E{;#hs^|vY`4tcv!gHhu-Q@Se-DLp18%h zZ0_L^D!F3+u<>=k2k5w-4sG86^T}Lt(PxdvnPOfyGyG-fH!RGQ8vh<5->M3pg@LX- zD8;=--Zz;WjA_sS3)%QE#0OkXIoZGTZvCJa&r$v0= z)aLB(*igDFo?^|Jg~WInRPBUVK%LxR^^QbERC}XcJ{h1Tvwl^Ym&l!4dcEN2Gu|#c zffYiBhjh>tR}Sge@QT~n`DAOy5jO-I2W`Z0=X@d~yMrrf;6y3pY!we}EAd zi`_B#6|%MZcs-fOV6fglq?nVJlVO#=FdYX51{h9<1sV_x2{(LZ+^sXt)wu>6yvX5g z6P}Mcd5>%n6iKQ#&S7Xr5k)fUE-D?s}4A`(Hv`hgFYGWJwM+DR~x<3-28MZt&f zh=R}Uswz+(@=HRkt}4*!o_Emuagy=%*6M3}y)y1(tnr8*iwGvjl#E{n9QX?}Bf3zEC)L>FXiDNd1oSs$fAP7)B|+}+}9H}X-=e!I^a^5@2`dU zx|xqqR}=wB@)3-4B{bi9({bwl9f>t*d_L?Ja~YSPnK(K~){{-xbyFlGZ2uZb73I^S zmS%2!iGj3LW`!nG#G!U?GIZAO^zC7PdY=E1tq{Ts>+r)lI?VZiuO=3Qxgi|b?+;^)1gL%F!{^=56a-37lEU z-RIY71vObZ_~GLY;rqSd&B%{iUjg9oqemX~&KefA`C ztq-ehf{?%2^U?OJDOjJIRtY+c-g!1BL~KxZLjKH-TiLBD`LlsCdA!rv@-W=?YZoa1 zU~tOgZ@ntBq0+CK$>^2%>vKaN|0GZ$RK*=>a@-Hc&z{V+S?v{WQCFeo^?U>>cDN38 z2hBKzDqB{aTD{SNQ0@}W^goW`xE1J(IJ<>ed$Sq^>unkS*3{;t6s4Unjh2=Em`V4a z3B1|5TrljpBj&(S3E{4b6{gR!dKsHKa0Tczz+!b(n2i$1N9QV&TqUnz{G$az&ISFX zpnT;)YV!?VrZdmNK(pF9tR)%Plg*Eo0a_PHvAH3CZPrj*X>z6Y-Oh%vmHL5|rLn9w zj`oj#ZLkVcpI<9+(@(bS08LvNr=wkmlv(QM9;eb1QN~vVufBL#*x`1{b|)5PtjMVw z*UwmgOt!*UcH+uZnG>l2t8jcwqj_b0x^~G1Vupld)l&aPVJ&$H&c_##e^1J$4HUR) z(3^^8POGffgZvege{eEom`N#O&-cBG9y0|TwHrKvw`lt!u8169T7$6lsdJ{|EOeR^ z$jvg$y~~HDC_Npyq%m`aV;jl<LYudl5PiOh`Mzg17?vZRP8uVIf$rzPQg{0wm*DJPNS6yT%R*4RYmGZ- zigw0`#3rOjet{US8+R)iG-SS|=i}I-YbS(_uh$i!4Xa{fv}0Ga?0>+BumBiB(e5{z zsEP~ECS=l&sEPpi){I-CM!RNL4H>*b6gI(N9O=f{?nSliU1d@C6fg`@()j{$A-Hxa zFl_i{s)(2$hD=6=zWNBQaXJBMB^fDSnC@{MwREXaWYVGD^6fjW^U zNO;{GUP=YeZF2l^6KfzqPi1v^j+JNEV-TH79&C(J${7Yn)0X$n3#v01oo<7Y1`v&Z zZT7P;d~>Z;ymM}VhQ-lE&4HGcy4~t01gB}N6FmFq{tG1h%6>&V3<$Mv zOEY$m<-JVenxo?>s-hzw8(`K{*xp+0r0v*wxWvlrMs7h)^^L6S6^dS#4Fo<8;BdcH z)9)`hd<4K+*1+w}B^OH`8a(MKP>3Y2*vrNa0*8sz66gSvt&Tk0+x(1N5SP7@?cjyM zVwFwP`%5>4i1Ox z`kXyFLUujee~J#7kPkQ^$e)V9k(f_7k>*Yt4la=PV3@e3IDiqwb(Po=yK)e}fL1`DJaW4x!buHzj}1Yq$=@9?^(s=b#nK$era{;R#Tr*%M|(bfuTpH&LU2VPF{ znouQ4b~*ZkEDa_~MQU|V;jpWEQ+GWA##}DW*qA+@i+gD_0a<|{+KM$DSeZe_q^+=G zEldXkU1rAWj7p)D z`=M5v5SBTwF_8dt)dqh|6HuCd?6!Q*n0OH(%zE#SU2!_9UA1`S!AKJ!?M;(C07uPW zN5Z{g2#Jh}X+3M{4~@%m_R9^7J2%zpWObS;G<_jR$_4Sc+3t-MZ$A$)@~X{P{ypMk zt|#I@_J^>a5&1wVSa<;NRp87Frl8UmjNjt`B%gEYk)*T!fH_FKM39D!HB)Lx1{1}H z58u{2>hXm&y{Z79TW_kkbpIsc<}(WwP2_1Oqw3{3=RK z{9aC?VgXZ(d1D0>Y#|0j@rZWaMW5AolB~c1JtH<{fT4cpjRZVLt)aqSX&t^RV~WC? zvF%scbs@tUvDpe813xeMx?{ZiHDX6zvCD9b1TQyntSD|ztPA0G@!nWV`jLS0B?Zeo z=^3-h9NXT{=E|6)?{kqC`sN2#R=Y(AUZ_5DA}(Ck_GA_BjJDyjwo$3$K4J#=8aZ|Q z{egs*8`IFTLruPQxTAG3g*G%+*TIA+XA~o$bc=_wCn+{7*J(R@EmZ5k$dOV`$iCD@ z|L(9Q+m6+U^FrI|3y8*5PZD)P(wJ?S z85hnp(0{rQ5sSXRap%EC$R-uUYy_-eTKxB^&u0UvOx`cOAsICT26iBGps)M>Ctv8R0Wh!(~ zZ3y6y9V15vRp6}e4C)OXrKcW;Z3Fbi1t$)vfEYM29sD{M$hHoDNGnIMPFLT(Q;oVl ziyY4HJS88_&tsAxK6)<@AR1L`X8?Est&_VU!iPXqjFkAJ&R%kvsc15Htq;Y&Bip~y zs-#o}STQ37WME1xgp`aC@Ey+W*x;}AoZU<^ARW(zzvo9gcQ6gxXhRiLyB9JfUBdOP z3x^&N1Vi}VTVZ2>&C0gtdcCPp3qc+xrKs)v#A8gYI+Yt*Ma*m+8HjfHcH|lu8W$bL zKsrvs)npj&X=aSDIUM6{SexTud|EEz0erW(p|v4HD4Uf=TeTUtgr$IA-IU_l5KboO z)cA$vZ z1V*45p^FQd==phsZcDZy9g08XO=Hyq^{hrAg4i%n1f(F4e^UYT4yGr++r23SS})YDLf1<69~wCdkV%`){T3QWh4~jAYot#n>z@J`WHDkh>g;~_neZ- z-fD)GVTxygTjJ#5NIBfTPr=0k21TX{I8@?zrhzM_;2~62h!hcMnonxmyFS|v2HYoQ z$ccO#*P9#U3V59=LVOeuD#Yn!R*gTtv1u<*T)Nm8v;qQ7%@sw3kRN3|BNy>oAuJGw z0|0fbZ{aJr)^`+X=zg|BQ@1LyE+9X(=1K)bRaYuxR{EYXYRQnKv#}I9z#ZG3hXD0z zB9p>i&d5|CNJv8V75*6YFxxrNNJ68jXm`#m4yf&` zC`6=1DQe!wiy`;Fj3+IT7*^6&sl?@M*|bWV(JSP*b|$MCR#|MdsD{_UIWOK&i$`E5 zh!4J%kbB~;%Vx~>5|{8XkeE7{-g$zX$86tRbj1X(LnL%P^?&DcUf2eT)?3_6JdrliNr;erm~`f9pas%_>-rb!JGV<3ok z$K1DCx1Yx-ez*KitB5!p1bw2EH-m?8*16lyf=)0wI&FxYzt9`be>14(?3z~U%*v2_jU^`&Z(v)Rjtxbl$FFkbaQp=@{ zC*X*ytV&Wh=UXlW|9*)d_uZ9sniTO}kO#Vu2W^#8?Wxcw+5y(Rw_j_zBkv%~W-EC; zvIq{A_Fk0sL03t|@UBZlm|+!F27Q2PYahX*AZlY@^6idM6fei#$`g1INbO(}b;^4mnyaU;5+}#b|?+EavSD zx&aycT*2uQ^J#}fvaIeEB$t51FwAH;LZCMCU?qpOaebenrN^$f*4)r`1eFKr;XxoH z;INX;q@1bpZ%g^JHK?(4R4IYyrQD1NJWRj8P`Lf6WVQIgFo;NZ`gU$=+})H_Q9LO=#uFg2@=Xn0 zhK5+(i_U~2iGV}}>5{6*Lg*M_gwvc_p_RElo8aeu&zg(Z$^jvKFoD(HpC8x^7z4W^ z6QlrLK87v~KyI3_x^_KUDr7@LhRrEMb(t|_S@QMPrTe17XE{H`JHh~IUe-1_w8=MG z_^;-MZ-yh~TOxp5xNNU67$vim2U0#Cu*B!xU!?<0JCbdiCbVw44NL_o8eY$fWB-ucoNk zn}tCM_ZzEJW>xnB^gv36lwIRTwKZe5Wip5jO*LDNBVQ8v-5xBlLTwDY9>A%n$~=Zl^gS z>13vToas(pF^olAX@y)~PPFMH_X1545i*o@)gW>*e$t2Dk4$c~)+yr+is2+Q)ODndgP>oVTp{bVlM|7S=^f}X5*eIBvZ=%gbLKtspML?dI(X`PNFN6R zRV)miOw2~)CHyOkyl%=npIi7t!#SGT4=`5_4QHBz64md{jzN<6KLmlDkchBg5AE zOAHBPc`3x`syO4?yD z!7$#|4)Ope0s#8l3Y*{<3Yr-|fmY~qvSSR?k~*umB0YM3>kBF9+5rRTnS(%RVC~or z4qqOI>*8vWCV zBq~*g^nsSXxq8Jg%tjY{^u{FkJvrL>p%r6PDyhmVr^IR!0uLHI*q9RS)r{xqSd3b> z6+cGuA6{ECF+^wcVd(YDGpw>?Lj^|~ti8qT;GZP$L6?(r4`pmby3oj+1F0r)Gh%{8 zP&SXQON0^&kbEu zXCcRfV9|-pL;{(uj-(8Kt^-H>ij2oWb|f-g_T$0fy~lbAmRZ01+95xqk8|F9)T5xm zA8Ae=hGtF?zZFx6Jix@zNa8^U&b@1r?teOYY#D@sk437Mi; zkR1Ze#HbKq>3(YeN>^{AI+yJz-DmC;d@tM+nyk$+b{w$qz+7TeqcquUzFE# z3GOv?9&>X2An0*Y@|uv6L_EkEA#*&Z9hcJt%=ws#-^Bv{ya8F#5OkD)Bz^h?r<17t zUPv<80IhQ#rSHpR_Zv)qbAXh=uQu~ZdPd6cHDjYy~5n`*E zj9b{u7MCO7u6R6{euA_W=82pyP^A!kdh*NN+$cYZwW(l0V)Trz`LwsmCMy-BgP9mxg9D(d;0N#P>v`(S-biB1@4c>S{&nr*vI6oq) z3zQRAKS8F9b{eU%Ds?>h>9tOTygHRwR*U~Td!26e!PF4_zGRqU@^rK{Ya!4{R*|72 zOJAD-9g=VR*It57;y2RoX*9>o!UK!y2-vk+H6GxIToXUPV+{P}Drv=BsRvFZ<;Z&P zOx@PHJLn5TKSDZWKGTytpe$9*zk*N&gg~nfGU)?daRs~>n&?OyCK8WRJ%(3soBvn=<;YLqL$*Biwv6 zIzub^qW1;%QLA-CXZN#q#o(5n?#)1QrFJx#Wu9oBy@SF<8bQ^&+pi`I(vUcm8QvTs zvwrFuqm~eh{26IZdMb#t1;`9sGYi>SkB}ZH>;!bo+MNxM<@ElP&EWtWx?f!C9}<vLnJX^zOKDH%E*=y7j(Uiq~d)kpB++4R%$-Te| z{7XrxRsI1B|KrFz7OFwCL_km_3P$q5;G9wDl4HY_vbI^laGSq6IHl^(9oO9=H9Z15 z1S6c%$5bgG@bQCgDB{pA56|}h1lmmv3`pF&5XG=+W=X0xwJRw_w_9LMwQGPEtX!7~ zrf4R00gP)vdy^MUaJx|0PXZnblw%2%US)drX0ri#oLYiE#7y%Dm2v*igMvmk*cLVh zJW+yNJgjXS4ewYZCmMFOakhK`T^|;m6vUbUIQyQWDSOqPYbKq4u70b44+ZaOc-&yt-C)2}UA^e66Ms^pA_rEeiMmG+gpPsEi zi^5^1s2yBT)yWmap@jW1u1y*SFb{pkhPqM5AUD&xfS3`==o zhahs=Ya^I9l|Z|ZNJk{a0!Yr6<>-tew*Rc%qz{BkSV)*C%dFPe17-k^_Cu7322IQ1F zW+u@`?TXte+`%T}I=mi&<`H(aH@XDcLRMT^76Ip_H=MJ8X{5R_j02HwR-W5|JJ63o zG#x<@UuS}J(6cY`3S7aHm{xB@8Mf>lQdzqbG2EH0GFR)sTxg+75%CB7iHC8bdKldW zCWR5qZ5B9Nmm>`@h0%N2lZTA2;p}0G*LV*wAJ1;)j~NY!C(%!aSo|ljIoq#+lpK{h zX~1!yAHT{9YCgZk&8=AQyts5fO)-?+H4~}*Fv}EX5M$Vx0P{$V@Bw%yjlup4Ylg#c z3yK?Icq9N!e+q=0T1d8Td|J^lR?pIa3LOWZRvut|GHn#^{56)8i;@SGlt4>f60-UR z|8xV%+^~|HC*C=j6r)!S;__kOa8Jkiq68QWmi8H%RDhRI7s*+Oe8(I$`>-=kNg2$GoS5Z5$OAF!7B~DGyK5bcu7^vYsoe)YXVl}A11IKie+0k991KubjXW$9P3P#1f=zUrJK+f3Aeb?s z0Iv>C<3(K24O_$ap_EI&wvSvrqR2ban+v|EX1ZBEAG%e{PDqhb35GCf87qVN$}29= zdCZ2%4~Uj1)jPeb;=3sjdUnHHn+_BHmG&2qf5C6ypVFp?!}UGInEMUD@j>m-p>l)~ z(&wqiVU)w4kPfkAnVca@H-rhFrW6(traMkC5mcgszb;LIL3Js=RqD!PfK&O-0=ERF zZ5>i~!N}xyXe4(cdDROqUO5Ji2I0>>50HX_N!~T^Qloen3l7(1b=_zQ7RaR}4Z&nZ zGYqF!$il~9;`<1JaYx93v15+O-8$oKawPiiAL+e?1?jpC?SH%|J~&&hjHI9aY&Ohz zEKY#5RgjPtTtM`nC8l(vC_2=E?!E zyo_KU^yz6g=D-jcnDtCc7y+ujaYwey9YV@^F6l?&@V8`#T#tZFwZarWy097y7ScQSt{MlI!xb4k zfw6Pwbkc_$ziS=7k-I&UUAK+j=m`1KYh(a!ga)0>BjBmSo7MP`unSrmjX6kH2{4Ha z(#<=V){K~V0Cyp%W*&s#KwsSUmlO!b`zf-)_WKFZV;c&b$OkT!jwFJ8dBv`iWsy}| zW0^*3G!ZhVULix}1|5P%5MVTp4zzj+@ZJJHt<$IdYA|KDK8V6yYNzv7y?tqtsO&v*61U zrIU~=J#t8mBKyMtT<|x@K;xc*a%WRLQjW+SyXe%H0?Xd#7ee`{_?X!x4fWvRYe`ik@;1y zG*Gv_F;h5!T#N5OUz|qo5*hD-Zz|9sIeX#iU#nr`vr2EjN*6f|)lJYqSK(oXtN8k|3z%xCoy@>qTbupBTkOs1h) z;GZvpyz=Lq6$-Qg4x%BCXFqzK_FK40Dk5Xcy+qGcfbQ(Y+bYo{Hhz zPP~g&Zl@>o&Gmz(2Sip^2${r0bLb4|cLwR{n8FJn9)*q=IQUNgO5N!QThH+@ZDrk> zCus1$$W-p)l8ANPCgxf5cqy(=2Bn;qPka$^L4g7h&70G2uD44s8z$P zhHDypzk^{Y2x6qBA_F6oEcbn3TXk3qU_=k`J$laVXdE&$C%Itq=;VP>Pv_Hv{WS-k zL$eC$oa?YUv21S`9-f6FRJP?w4okGD12EEVKg)_bU)ZX*)4r|DqIy&?nMp@ROV};P zv3c)&dgrZng=#D!P^GV%{n{f3+D-)OF<>oC-=czV@y7z2_IpAD`*9MI zI}X`<)E{`dme%Ev@x!f*b)2&-vlYfKk->BLDh?TonBRN34-xy^ih(H|ABcv)2#G@h zH1z&>nAv@qI6C44enHz;Pp6M}#m)57;*=2%d@(2@K@J(vG@AGjkT$38D1d47=?+l| zP~THrUzt@)2Nzm^1Cs6ckaR}``H)Qox9b&oE{r1&K*g3#Aj4^)9;bYuy&oyE{@x)! zmG@?@ISsl$1*0;i;uzLEn@og!yaMK#gY*DB$b<3qdUKd|(}O7u{N%gkx$q1P-NyF& z6!^vuC!8;Fhj|XrC-+$xfi)zZ_pPR<;M(Aot?(XqF^>VW?VZpmhry6-CP(2=I-@`~ z{)ESkONC&0AZlNQ#EWq`V=YN){>LFRq^&H^+J=U~N%9dG!AMXB0|ZSWFG`>Lp{w!) z>8Xn)ccqUXAOcY_%othKD?`31cCm>Bs!+xMsT5j4J>Nhasrtx1j)dCq^yFXq*RFXk zgzqwh7MZHSXgTy>9>IJvcY*&1;_X+WXR&^>y61}UZZ%Y8O`C@!JvsXiut-Cxy5Rz@vD~T8d-an+-hd@vN>*RnrFi| zE!KB>$vt~>r$>vmSv~^FSSzL0b`RwD&X2Rl2Vo!{2?3hm{~hh=;pZI21o5ZVg$9ep z-y#v@0Q%EC(4w>vnSCRzd#kyk%xUtR>A~;X&@{)Qgu)kPmgD}l zQBbvQ>S6YhQ?G`EpW<)>#ayIW9RSmn$9mY~Ur8F!q=)f^@GYQ1sQw3C>0=wn0p_eC zXed1qf!{~^i;f=P{EZ`f61s15!PI8}2VV&YH^J#4{N*&e) zeuRBNoP=(q&IE)^JRD2_fli((u7_4*s9krl`5b#^nYs}rGJ32xmUrjJY< z>%8=Itn^{V7I!SsT*)APYJ z|9?Ea4O|ZP{{R1Fb4IzzOifEP)NiBGA=Z>OOm0t`tx~BbL_$t&rK0Q{mz&cFZ89du zWQS5o(o&bpNu*zryKZ!IU7}>Vxl+2*-S7FneEF-T5Q10Eo`FSgbun&#W{_+lWs@{2ifgnz=cwX6t1SHok5hlq< zENnXy{Oz$v_UxfgYC$L80Z-HkKBDvyNwVJ~$D}ESW}d>eMj^4gJBv0{J>x{le00U0 zdG=SXBs-c32d>u9W@sbRfWjnUF)Y zWFLzf{o*QX>}~2RD)eR?=NC$=WcM!#UMp4RK5 z>CKDxcwjx_b$@!W*zQ)_X(20nn~fsO$2Z33)Wq9aB*k_f=;)uBz(aFD1kNd*U3#KB zt5OIg2}%PA-YH$PMJKbs`FPpI{jZ1o{_lda&{*4bCClCYkzO{ce$P(k4HYdpYYXUm zeNR=sBH)b~f$|hil7^{^L<;t+AI9g)vXex!?ABf+Ft|`bRD@?B%9|cIf5&UI*leQBt5V|9g4qIfc z)>9i~ZSgY6TpeWEo*0)La>df=if~UxfcwX%XEl8nWIFa=GMg40{YsU2x?pbJ%DoGE ze;CslUVdWl;e-I+;ZO2}Jmfoulfr#u$28##b=wWAj!HGT=RTz4tAG%kV;*@;wMTC> z{n_Aa4xLk&2wa3gDB$~rLn&S*`i#;g2XlTlQ@?1zBxHdVxJ&QpmnrsPpJZONeO}pB zdgIU;$4P}zrZ{uIU+BNsZHp(fYq{HoAnCpVBA=gA*)z)5%&?y)yD-Xl#Rk2Fr#zB- z5|P1!lL9bB&{%;N?~YX+2yXrKui?>-8!sJI{HHef(Di~Ix47-p&Jpt@1XP;bQuCz6 zm?VCnfHd*9y!NZUOlfa*_6}WLijOkmzxXjcd+P&7wmR>D!;H^q>PPY(q&e#rX&IVO zi-9fWy*(z`K1-Ha1qCRD22Hi<4HNp@HCz5+?e%2y@&0q|u7C0zr%oVSu0s1z+0}_E zN1#a_&x;Nx#kEtgJoQ}0@sArHx~%Jbm9PCXro_GPpF5li2mIICdTIX)(z&K@Oc?MY zn34MkH`}6w@@m!^^y6@uE7r7|P$(Te|t6H}-wDZd}_c%xCf=k(Arav7w{lynsiI2c4?UHn?%T&7-7#{wk72zVR~JvEuZ& zUqsYyu41`H09axP~LuAzSGn!^WtBhr}&Q>28Kj5k13sVA-OsC^6jZn z@s|^(Zk(6a+i6{lq!=x_?Fi=KLC>xR;K zw%PBC++yLy4Wu2QlJnhK7fo@|za+Py1Z*4|TG8gdms7mc&dI)-s*D)<#43f_?=1#|7Q4R9OB zmKBbH9Cd?p+Lxp(8JV#URXZ3`nC+|N{xFNw!w5Id;-U;06Bp@_@v>G?-P{}G^uwZu zQ%Oe1vzz47jA0J6pxbd$fpM0gm{M1crbQV@9}Kwo z%?@y^86iA&;cN5rw5-x)HQ_VEaymqgac`EbSM$cy;BVEvVS7u^7>!LS0~U=RGdi*H z;@igy{)x83XN3*`5_4OIJmE&TYH6ybNO(MIX2(C6K-V3nIyY-}2#RC77@J~RFe9dQ z%!q!YfsB(37y2U8qgZ`ym&!uUP@sKuv1yp`bwemmW%y_uWP+Hp zTFBUGpwtyE|G!UTjKtammtreAB+`9~eF@a9Bkr zn<>x{$b6K*n!P&%MvG@RdU%JXvM`)VvI{IJ98F3`(2YaMIeZN_n$O;-P0C>F@w{mn z_}SN;#;z|-nx5Bx|0RMv|8AY0Zsg*IJ9#7Pa#(r5ui)WBMbI<}Kr$8}QeQ$kNbDHo zg;Hhw2c#;v?ZNPEQR}Z$Cf!f7_0BVR?_{)RZ;;yLqq*aeZfd=0#xhTu65?Tz*czUS z8-&dYulQG6%7|k?aH;#SP?R9{^#Z9wVye7Kws?& ziZtj@Pc&xB9T>)9%NW?iG90z*20bdbkmk2Q0PP2xlCFMwF6Pb5DNdfI^@uY7Acbrv z^Z+D$6YnU7S2Q7&Z0NkeWgzf0$_3@6=yi|xk6H8G@}PSH6X!y#m`YEgIe9h}hmI)&S*uJyFVi5R_qgh0f=E%z*9XNB5pC1m-3Vi(0$4^hF zzS{g6_NI<)rss{f5?bCFuX~gHv&$%pW~PFww6)e4-x7BM)5|Va6A-2ET#bGtV%yI1 zpX(P_q?+?}<+g68$reZpFI0Y>0uKLWLa$!lNUh`0dUMGDVSQ(rvN+)NWwRI3jRSz6 z%N!Rj-x{DY+-=n=RFUC}y@2}DVur*TbVM4oE}K&r#gfm|P&j&&WiS6-)F?xt*b+_` z4Gi@;hje!u-(`k3Ar}Lz|KYt~Y&lYo-WTt0KEb=+-~8a?$q&39?o;&#qG%V;r~iQo zM)U+(iK453lYWz$hq4p}FeOA2ezoPn8keFzygbK?hvEa?Ut#26fC9N+)*MMZD4Z2* zqLEbyEL1n9?n{LeJ)`Y7y5Dr8ZNiN&wpQN=0Rd$c{q9|4oDcC~#A4t0eM}Td8F#au zA1@rbNngjBK+Mv*{GnLRkwk550nRnh;T6n0^#>uFqV zzGe}IjrKpAn?hXQ$R3Swcg$5VB%KJOz9zc5Ly&fha29jkelW|(#s$4%_sP?GQdk`s zI^Sf;(}KCVfa1r%xAh265k4C@=sjNEyvC2ZZIN`cXGfbAj@g-9Q%WPw`F6#Idf0gl zkG~>hqNfU-(WvjYwW2FR>sb?Fh$Ta}#2dU9V<>?&B8^XE7aNSP_eCcrWLIE;wOG~t zXF6p580NUOZr{zzecO>7i}Wtc;(8@cOjP$QP63Nsro|_Dc@K_lJAs388(h(UnqbYx zDx)m>!$Kbm`|~m&GNr9W@t-D)Zff|VRO4!LWVBY-vqGPAhG&ILI2~Bx-%~VI>3S$> zrC)M&_Z{c_$&i!KpoUucJ2igLP|M!8yk2ymIq4k9e0ML~8?^-dwVw_^$wj$8%nF=*LoaLZ;3K;;#6EaNyy@49?g4ytgfT#Q1y2=EI4L+McMuRmy+4hh1Tr|8sssp zK;sqNl+H``9P+V{dxpH+SxR!pDe@6$DtVCRgS<`^borJ75N*vlW-E@`oMv?4Zs6_N zqwla=V1C!V(ii&1&4pA)*#WEB8s6YIR1d)%&-`h3eilxt1y4*4ED4Ch#9^3u`a}hb zzNPQq>-JsynrZe_Vd8Xjdy>A;^0;*3o(Kb{BQ5=v?X*3u1!Cf?z)@!cN4^)IwDMS+ z2&NgHzf8E^4Wd+1Lo`Up&XluzB9yD(u6k}H*92$3EX=6dy{%OXm|4Xy+UQqzT{_ka z0i{W`>v220{VfI$nl9-K{KqI@T0o}Bp7>O>MbLe#030Jx1;6p{47^F)Kqi!4fi6Rn zAd^5Me~ICB=k*7=q_6g^vVN%SZ2GkCOy2pq36 zUHoDiRt?WRRw*e=sCl2+?&A{-j(s>a5p7&YUP;7gHfvFC0FOQh%4_of*lCX8ywZuh z>x3M1IRCKuc^D4mmTPc_nzJiVy4NqvqnKe?Te0N|EQBwzb31H$p~^nCZAsG&vKl7s zu^Q~*6z`Rip$2a1Xtdt!`jC# z{u;`A`M~={PPMn6FS^)M*Dz7UA>#L?QG!eTX_V}Ol=pe{?*k&d%=osb_P+1zFIb&} zE2v9k6?|V;nYZ~B+5*JeFh2gVyjC1+*lp>wZsE3P*okoUIGn$V9pi|Pgn#%%El2c@ zt`yZ}dRI%ytlei*06O`Kf$gbobRO;Rq6{$VAtDEHw8{m_^wHbOqNSzzDClzXv0dDI z71r!294pqyU7Zsbt-?+In-Ru0oF%z+U8^1`1G-lI6o0wsUZ;P<#(J`jGE5_m1d~sb z@wSphZHaf<3h++ko_yBRxtUoGA1JgffY&pJ;+d4TdH;&?r6U4PBq^9KK{KJYUe8KJSkWruMyEN&#@A=Y=bCsd zJh;NhLt8WzO`Ir-Z?zcXRPPOXnt#zgA~e-bk{FZ%mNEn{ZUIwGxSq96wC5r+s=!T2 zhkRqNKp=OO9ezyIw?%#bT-P2fBB5veTZ~#w2s1xW9NFf+{*rnlTwq~v?1%}mk`Q#o zOlC!v8@O)dW^0PDH!Ncon=QSu^XcuVtPwH=u%@tL=d&HVW+RjcpS{5qo)Hr*=#SYS z-hH?u=(P)DB$x(cZ9+bX0o3QkfL)?95?lGC&}nU^x3=7+Gs9u!8cl=7CXk^`ScBk- zv6ub8#@l(IZTpQLzRj1?FdDiNG6xQ6npO1pQ=Y(}q;iZ+tMQ~+&ZeQJ<)XyQ+5+eE zye`XO1z9^muW~-@&UHYNn(x+zwymQJoT4A8~r# zINkSBh{1Lux;(qKy)N4<@)-I5eoW?_l7Y8 zjDeNXd+KuPS4)fhxa|SJ{s;&1>_Apu?3Iwh_Ara2LZw&pbp51qnNEr27o#QMh7x_-j@N|44ghnE%e3FUavbofK-x7i2VOfC^b z)WFyChC#>H!+Nvk($sI`l9QM;*HT7_D1n~BCxY_GUc$z$s0Y{S!NiMyqGY}jo#)*V7S|v35IZx(Tu5|H zZU@-T(-WHiA@D7@fY4Qq{r+KJn4ZE>AdgKk}6f;8$){80+R=ExfV9z;K3 zp-)O*>N`sw4WAewbKLdAwn3noJ#Jx+Bp}gLCo>?X{1l&5a4KTkjpjtO{b60}`A8;O z3~(tI!xfY=>0LDiJs69g-|`B$@GBvj*nL9}7P)4>Y^rEn+wRdgN2yEZ>`S~K-UcBw z<4$l#l5@o?5wCSEi?k<|fK8^xX8o{e?B;St>-pc8{2>NM6KBZ+Haw~kZgq6|SVc`QrS8W`*!fn;s9bkc{%i}fAF z3WQj)P`~OG@4Zpakxk-FinQ0TEB*_2e2obuBnO zs6Ia;6-KkxC%a=8Q)Q&22EZt4%5C@3(j>iw!L3J+Ej)2Xw86L0Lu;O;F1#XFVihRZP15rF>o-X#$Ye?IqqQRhJbPxG>Yjxcox# zw7<2VJcJsADN`$~rA3lblCXf$U0>OK|K$kZtu#bP8t0vitRS!3hlETj+;**#BpTDj zE#d+hv-3YqlH%gbA|DK#4^QND`Q@m!ObTG3xar8~?6<4z_14}A2D55^<6U!BB=;lE zr!nfiAb!z*aZAogMe3tC3b?Z{bxV7Y^MRmnWo!-Eqa@sJx08TBLI&Oc&oCPxNmAS-Vz7lQ zwj<3CCd5bpF?OC|!YB%reN~4K?TcXuy)Wcs4H8Nukssh0e`dEC$}x)6EVLGAGiXKy zM}1bDpxx(5*zZ!5m<3BuA0ZfPUY+7z;RY0JLA_I5=;N|leS}}K>S27; z&<|L*aaqPCf6g0DDyGU!|IJ(r>Rv{P;uLBTW&2Nx%|~4)2_$s0+C=5Ruc+(;L&EbH zbW)7ph!cZ(1eqL`4LrbAKPj+MW&kJ|iJ#4AA_EDL#0-Tcz=M$Dqrd+$12@ma{Amj; z9YeH^SRb6;-SOwjec7_-C>4&wnLoP&mq#R_Kv%BqY1Oa}k&Zy5TR}I(HmK56QV%Rl zJ#Si*v@pf1?Qnu+pi^w?TLlcB83=W#(VTCgH7(RX@2kYNfd`0akMF;JqTboLJxo%# zMB_oD?hykVu^t6&fKymFL{J>|{g=_D|0?AbNe#+brvHk`V{%m z3K`F~A$eDDGW&Aax1qU_VzA=8p@)9QC%(=LAH`oC;yTgr0vh(rhH7m5K={NlKF{9( zL;^oSQOl}>E_``yf=0w0DlEjQ!7J7XP%1kV)z5+gRKu2$r5|6X%V{e}iJry=?nS%- z$i1Z~OG?zxmCaBAReZ^F?X`MKts|_iMbMZ3iPRBETJ$p$mWtmso+ZBh5MZo zmkN?ek0$Gy;SrQ5aD!{U&hqodNWoIgrj20J6eLLul$``==Id9f!pkd5C*{IUMjSkk zZrFb6W~v(fMsoUW5ef{S5Qr~9hsm$Q-oUZ z59u>7o8!bJi3VvRvLZ$R$=+NYU49YFlZ2!Wi^#<*SgpXDJn!!7CMJofSiZS03QXyfv|-cXizl{tQwB^gOiJp;*yYd<|xU?hW9syh)Nz;y9m z!W1K5A^!$U5FG2Y@P#znk4QWwbVd>QbcwUuw7>DigCHEH=O3h(j;tk?T_zPkdyuZ}mXo}L!gEmRktHt_y1&Cb zWq+-pK15opc~T{JfUFFnEG6enUiL>q!N^N4awNEsHR`%uq@O+m5ob{qD_0X-V-%4s zfZGxA(N!H6Klsgew#2yzG1Py?2SRLK@^Lj)rZ^BI%6c zrGSpw@YNsl_WLpFf^QyeTjQiG_z+7bnCZ58b-(fIN9~&GliM3n)oJFDu79uvzeJ(f zhcOi=DFeU24^+=oOqY!~*m6G9LLT6|5aXFyf}4-hyRpcX*1L#i$;&<;;YP#gnw6lc zn0;1zBA4T1BAV|ep99RCI$F%WXpXBC1a#~n8?j-m8C~A;mQUz4%dFKAzXsI+MIiTIEd13)!Ie{-hIocan=t9s^C5tfZSiml%vK z54EDe1Z$U2`1fI*CX*9_I7tT!G^u_}elnQAg>F(iGjbOGT)s0Q?2O~kQq46f>>7WE zRT3jNZ}%i7lfx+_zfO((cWK`$SAjcLPt7edlfhkOB3#4?B7Evs`}sFLw+U>+!&Ne1R5$qRZwoAfKvqYXvF({-sw0q zq6mq}_bB)VQLYCbNoEI7ax!42OkhVhIVRIakSQ<51ANtQZg- zaFpTjf#B!&J8gp}@Qj~JOEwGY({@@UN9mOuW!z+tys*f%BmVO3ml+oOW9$Q4lGF8W zET$xbaxs=`+!gIdeVi0)x-bO?293SE{=B^9@}?)nXRL^btN(GKWX@Qo5{2}<<+MvN z<7tlBj^56y`s8$e#Lh>_Qj{ykNY!MhY#1Lb=pkeGvI7kQI~O-PVoCbatCYKzY($33 zrW#7?q#ZUr$F|$_^i8}w6CVrx_g^YYu%MI1rA5#rn7dA-j5x%s(2$HTylDtY&Wk?j z#^D4z1onqd!DC`MGZl`9$Dk$@u1 zeE&Um{oXkRrvk2;h+l*tE(vZO{!*>s^(k<4BBq@{Wb`v z0KS&4QNHhZYrR9=zD$q+!`P0bf)=g$q!U6RAS(z^dQ-)!oeAx&U`0qs6yQuE=TzV- zvJEo}l?>yW!pIa*qoaE!U(X5zvj< zY}yzL;6pbH(4fN*hMKg4ctU@V2mB@>2@cv$zk#gTeU;M&*7sH3$@!5W?GTqv#4%PLK2;Q9Eld?jmS!D)J`%Q5^mCB&^jG~O z(f9t~lZt^@a<2)HgX%2H;wyr7m%mGr{I&u8*jlS_i>%GkA)96)ZPUHxzd-!7=UA{< zYioAM##5Vs3&XRDUuK%*AEFf0YxBIGE-?6qVUi`cBK*cL4I7 zQ1P7dR#h85M96fnU~$8m+{{azmj7XHShLG&KAsA4+Qy_A!stLq8?dt{_q8$Hmn?^T z@$zz$NpVeVX8=i-H+I`i@#-cU3nk@E6u)|CJCUq`mjl~NGL1C7R=SZzq~}d}^+%g{ z-u*BS#MG8z+sA-9ryPPE@Q4&xCOsrh-An=B2t5S1ghF(=DmH#jVx-8%6Khw^9|3`C4z6p&jTY}5HodM7)1qvRiGJ54m1HqZr%65*h{F~Q;d6FU9~Y>%+Q*v?8sMmyy7iID3Qg4$4>4IjUCA$4X-yhSTGUG z4pIY}P5xH)za$G2HtJ%s8}KI+R9z9MPmaQ-ZLZYYiF<{e zPGW^OvMl_qaz^RHc$?g@%2PW`A&1bmTUM4j%8UPzEKENs0+>95fIF%9lhXKvMTGD{ zToe^hexkv*;7?JNInBA+p7~>a;QO_`F}%u+?(l(wS*`cRkTnCaV#6692Gp>b)*+01 zWWHDmZHX>^up}EWB<5Z@_s^9l6bRK4?JB!M1#Vh+8HM~DZw==zjIJmVY3PhdV^yfy zXsF3FUvlA!C*PBU0Z&oo29>$gA}+23IfXx$b_dK^+sCDW!91W>0l^`?&3?6;v?p%E z8uLAw+ri^`n6sS@<_!rktKIKi{bGc8cho5D5SDheI>j$)nVM#@xcf{se%t^sLBWjwzp5Tx#)1sjGD zfdQClL?I;I)Vt41OFmZjY=n~Tq9tm2BO{Wabzo1w6tYs;-rGYZCnE&<9fniV{wXac z*xwL;fJ8M3MM`B4JFupx@A$p!bpGTXXF)(8?ZAF1qyUEAgon5*VX{e#p}r+6w&kMn z?b*6m1J^#U?q~{L7fthv~gZN${=NQ zXdRRf?d=}f0?xPUL7d?ZyXpyN9c_Yx);Y#1UZ-DeKXUYOo0 zmx6Q_aD2FFV@4xdLSsStb%!YfLiqOPM5?@-?#Kh%$;?NH!WYQi{|Pv6XHlut5Kbc! z46a!8T7p(aez)n3eFJgE5pW;yQ3S-6=w=Lk z;YC-9>evtfe!uHMGu;Rn5t={e(sx^cjVRiBjA}f#+#jlmxN34JV}(gAX|+3E`%>6cngU`1ME3MLI97+F2nGvq!Mw>MCu zA}5B#d_w2p-VPZWe-%0V2>3`=YSbO1{dI8_$T}T1h017AO3Eo?UKLTB!&HRyTcdI~ z+OZ}CNyg~xSRb@QklsWM!+c9IN z&5NW!<5-#KmGJ5_s9Ydd^T3tq4g}Nu6rY(L&U8A~B5O--U3Y^C+dGz>8`)n(hkSS= zdz9GHd})GEKINiJi*p&wL5WDM`_R@#0zCFhy}aMbz!^2l>h7gob{xF8N7KR+ycU9T z5GSl`q5H|Tm)$@60nfHKwBsC@}qxPIBB^>*dHAAio1pq2( zMz$1vjtml6QqH%wh(HAnCEd{SIUEvu)%RcBAp{PK*_WI`<5E=$uD2hy+&i;%XG$V^ zI`_FVPyH&9?%ORxCRIjZXRNn)JhSiY#YkI1+l1&;SUkZJCm~D%ITGU@X&G43R1TR_ zKiuHG{jS*$-7!zR#6fX#mxDMea++#NaiLRqd&49)=4!#7dZ@_h0%Z<=XzUbYl}GfK zRr`J33}ez|1C(FHK6JM+Y5e8wC|D+251}9p3tCKm;p7~MK?E-8{4d}C7@5<*m zMCYcfx67*wROb*6rzI}W$Sr(9Vtd|}x;V0-AsyFHN91)qT2EU;G4y7Y&&OFr>=5$! zDsUfFlTBA=;${(A{_mEhvtqJGEml3h`hT-$ZN*g~2Tt%nAcp5_$iMjdNR%m`klC_F zC;b55nRbD2S=KU4xEbb-->PY9mjh7?_eh|E0;Z{aPJyvig)s@ps9BZqmq3sqh(EJe8#H10_msckiCO>UVB z+tg0z{lyF$(qdJ>;>nZlghD291R!FPBnMM@crsR3%ZU0V=h=prFmQrq9vk0$J(*BK z-$4m^b`qli98}OXKW=q3V8n2cAvqX>53W5d#KiN0*6bgKlHaOBg?LAeRNyl_q2kj? zWwoGpa*r=~!W*xddZp~$IBP4`bPU)0m!8_3nDvR!T6d`7sX}G37xj$UpB97Q=MulEvy%_5oSwX2xoLBBpf{pSG4wcE_BCL7{9Bi-<7k85 zmrE6Uxk$!gu?m2iFsSm^h|So5Rvzn~XknEH9EgB{V|XkHiH6u)3Aw&nl}%S9bDgHC z1nI$8aink6?sq)qv0v!KzwqfOGTsqo25b`s39Gv~KbS5mDZDg<^a6vNlUwkeh32+y z0ILLIoU#f~l)_uNH#BzP#WgZCMh$9Q@OR&#IL>4#cba2>%Fd;>D@aRe8{x;bF_kkL za>a#{E^`gJi$I(`-fn$3B?ZFrv9Xq!MNjKvWlvH5 zhw#H6Tb)MEv-NO_Ui5H*qL-hT7}G@tT8519oZTDoupP$9yGL?A#7yMI*~$i@SC+FB zKaR_qit}e$i}E%5Hin1^IM9u4+%{qTE%nJQNT~(BL|O^FhzYzX zl5}+$vVKtxXd{b2gZdJzOLECmZIL%R*XYH(zT+jc&2JJyJw`Wz(l{l>IE-!nflQ8Z zVkl2#C*lE*!%!CJpVNYNE^C80dD(03o(>IUga9e>YW^0CR1ZqBMfB%f6IkSW{)1^H z-mmX>TAo^oDp;;XlBLjG#Nu>r7VUNfT7=R^z?Gnn2#BYt(|Rk%g736vSR}`Um$QB2 zvfQQ)=CLl92&2FDPMx5>e7ilTIeG&66a9wiSBZWv6|r!Z!=|u?sQApD)7tv0{hgZJ zo}Mwv&3${*<~&)Ft#c)|3mgeDsUk*0m>EF5Dhy|w+^LC(TD|zxhV=&kay06TBu1C` z8>em@^Qenu$S|9{4OxIxKNz{W)YnSnu*3;Mo3jNkB8os_+N1R0*{3W{1yt1NSMM#w zu)`Ho%(QReKr0v72GX8;=a1f~y{qMg{YGRNH@%1Ak)!gYamE*nhyn|*9an4^8{ z=vqZp#(gBex}tI&Ab6&JA{x&<*=3%}`L{~KOwolLek=RBeNf~}fBeWyrq>dfKVk6) z(~{@TlwaAIf{4lm3@NbZvd`ND6u9F`!v~`~3|a6iH+Cf2m3kCnhZ?Pxb>t2Hf&oW^ zgA7Zy=q6Lh^Rs)dycH%b%!tk;A%NH;Hz)FZcJh4o7YjNMp0mF?olnGePW&YYtUgd2 ztVRLEKkla-353L40ULNMFqkScLr)yD=nGDN?X*3G!eZzFKQMKm5Z zTA>9e(Oqvz6&EaqMSuBPNFOt=7f?CIIw==g$xWEBFU8biXK0<=? zV}n_9X9AuGQ4SF(OqyXW+~VO4t>bR~bii=;)>ifSfT%(9-%?E4GkIeMog3@g_yT=& zlm(8q*)O-PA4G@7JMj)uQSf+YpUE5Fi!sS=D{%NeyR5*G6&sVq;ulJl594*?y!%q) zlzhR?F1INbQ>h1PL8{ z^HhI4j~9GkRz=*^W_8+%@QPT(?I&wi_P1x4?Jymy%FXz3^t@;CBUUNpk{a1wb?*A?Ynkxph#-l(OT#Ek%f*ZShL=NRRt1?{^x z)>YUaRGdNs239?USpU96phY?7_etiz9rg-(EO{K5*;s&%jhFap>}{BDKk6YYgR2y+ zkrMQRW`Zld%!7P1-bEYJMGG_G{>UqW_H$_h;siq+d@}oqnl6g2vZ)tCnI+R)covn1 zvJD>6G!nFF1{>0$#7<+F70S^SKgA22?9e?bcquFqKsIbVz9b$n6C$Vh<7I(aJPEjqQjK#ZpB=TZ8OSbj?9hv+q+CQ82B; zfgkM(UfxmfAw7dfI10Y~TJlq*z`VVa12}!gJe99HO`jN65(A3|19{sbTuSH-y>g{HH1)9W_+~a|gW8>1D{MPA9%Gq! zX#82|#q9{`loeXG@<}eJD;We@(13dF@z(lac|!oATtzNtgC(>{c{Q9(-~a+JP#d-x zS#Ri;x63F?*ltck$U2PDyYR&`=x^afO0%U#9v_LSzz;#k8j;H_paE{;rT5J8AsEel zJJ7q|oiRR1>A;#!z?z)@L5PVkT=>bJ#W@-RT;g=I8mwAZ> zn3>V+qu8{$0kQj0pD2elzfN5f=y``XJI!ybs`{I*li6T{1uG&KyKTtqyaB5C@>s#? zeRE0uGhJ?6Aj6mLlHPJ-;{1QM033%%PP}&CUN4fXWVFBt->t+0MkJ;DoHPGOzvwJ@ z2k+(_o5_QI%=X~;LgjWW{(|qE;aKTR6pM{Wh3DtY5FuvMNS&%7VJp|mD{qoRbN=WL zo1Y9y=t8~rpXOf47&JykO#F0}CGiAqF3l-Ph%ykLb(l8s6@8fZ8M39Rmn=mGF~srj z=lfFM4d0u&$NL5_{*1!NBs@mMByP})G`JMc?eHMyYXSg0B?&v*=hqqeVWu1t__}2$ zh7kPa%#tM$DpOK{HK3xwq|$J)_ZpDoyeCz5oUUlK5Bq!4!J_XN5+lo&NbA>{!ya-f zdvg0|^9k;kzftteD9z3U<$-!hs9ePcOkBUC+Z#0{pihS6S_rmC?gqH|ah_Gc7Z{rN zKpfeof9D#SJn$U+;SSKUCcirmCZHM4O63{nw94(^Md{=M4qPk_T63_CB=wZ0BN5a) zhPDBJVFcxz$?a`lozImGoIe#g$A&3rGoyA1+ahUcfKO8BsE1T8Tt@S8TYHC(>U1#R zpyQh+YHx*%7dHj~70pysbwTZCTX?%!UVfp2{dQxqNP^^YDJr$gh$|~y$vVJL&V=YA zDMXtI$4nOiP?sxPH9lT}{(oU2rY7sUapgiwaWCLZLzFVGC2M_nerIxhL|k*s>D8Wo z;_B9E#k5OE?Z;W8#Gd=kNsMMrM?QSpv#ZqkLdzYl<$|r~>^b}L2 zdqBlvu+?GdUCS17AkC0N6rY-LFYWfWRj7@k5yJ_7Sza}*-=X2F^r&90iqhpwNg~iR zvzP}u{0?Vxw9V(7z(^d`p`7?_Y@8T zaN_6iA0lO!0~LaKgNutJceOrxwk^)O%neA>NI4sDE<9iUj&o@>`Y+;GZz?%So#2t=Ka&%9j!FofB)s3FWgL1{)@QIv|^j?@Gs|}hTmfg|jd&0U$c18wc zcDPDVC8#yU#qFPMij*E$yojsz*+AZd3BMMD59lMp!~&{k)Rud9v^SgE>qDRB^pXCo zKk2J2?cB4^Axj7YA{QP6_c_MB-Z|wzaIQY$(p#KE=bQ^Criguky@AONiX3^#1_X3e z$eziv_H>4)id>F60)T{nhG4Z3X(Nppm9zsK2-0jgtYs zMu#v;DhS^61#$=gSa`Z*83q06Y+pNd?>0_{%;t#}5xGCC3FtQ?;IJ4WLipYTdUtci zh7+Sbi&I}MCuUtfF5={~0m*~ek)SD`fu%>7Y^mXYaP0|8cW=bB{CMJ@!CauQNmHFI z(_VXGY?vG)iyRg{Thd-Q3K}q*^Jz!hCN!%driqDbT6a?GSuJYGqA#6x1; z`V6J|3g;so<{iSB69y$kxclEA8nqz@5I{2RZmU%wyT~yM-S%mf)+A_j>S3eS<)M@L z>ERe8*r-4D2%ldS>RToL`pFaL7@=Sw4_dN&t)B;uuIsiwwu zppiL{?>p{nplT|F>rR)BulK*~0rCgA7zJ1^j;}d@k0NJeXcX3)FhXAX5$isLbOz7t zVe8qPBKPRw{hEt->|6sq&T&WzP?2y;m)!c_)*LC*O$q>!gaYe>p|>oxu9;O9(w-7s zb(wQhqL@9Sd%e|s8mUA1?HAV*21C~+w*vwm;2p{+f(sO!gX+;By)a5n=QNKdJz}6Z z*e?tR_*O+>h@@AMGMJ@*v{MDRl#Uzha^OncrSc}5z#tM=p{AEC=Uj@TvfvjgnM31I z@xVGJX5_(WqzsXlw6WGy#L*;GYG}p@2-Jlk&rjRJHAjDPfpOW&1s&}PNkJU~%UuG_ z?2C$3i*mu*oF!IDgIAYq_IExen*1AhNY$ZLqH2CWV=HCe?w$ZN=IWkA{21^ z2V(%ybxLf*E6V7QiSE;PSMT9gm}RckdZvP1yYVwy90a;#Rm`qI=*K5Q_%NJ?1&+Q4 z9fDL+V91US4bu#A#Ce8|rsLHRbCz&7wi`J3l7*Syd`tEpr`6bcFq$Jl=U6Wb^PHT6etq%yJ97tGM#I4e{bcYq@~C6JT-_vCt;&0)zQ&6XAY)w^0t^27AAtE>Pf z4`$z5A75OhADZ;YI2spjd#Uq{=Jtq5`LgZgN2GDO$DaEy;}WS&b9};|>@rX{vUUEG=+o1jhdFC>kxOM;o}JTJK%(%$HIIb6)+uI=xZTaRWCS42Bi^!%kguCSDO@<9|v z+OHWw3zl+4oM{#shFha@!Yp2T-@(aPhAyJQAo)%7YQtjW0)`5iCgn_oOV|uKiy}v- z%s=+#p~hjhLf+cV4n+x8E4>US73<6pSu=K=VE%=pKieIy9z&I(;+2P5g}%p{S9*!F zr(Zbs8zlsgejI(VSO+_%k*NS!DO*lA!(?#?AJYl6)H~I1{rONRJ}Ohv*aC{Lo5X6P z!&xxS_--|2l;e4pKz*-&f1xpjEF5{^@`vH96FRs%unej8n0?)j*Lc)PL2F;g-HHa_m z$+CqPZDmh7->9r949S( zH2bd-iEen%WU7y8mDQz~!2}Ab>nJph7tsARkaBuNM6%F1V5xS8J2b4A+D1r`s5>Y8H5{=`sV@SBr#q0Z2FsG=SY$a zsz}aF$Y<28WM??8r|PwCJKC2pH5__d*qUZ_U3c_XY|-+DCrBQ8PK9g%(fia!D6fP6Nn3J;x!%rTyT2HvQHnh zHZLM+ipx4UU+S*^xY@iT&4AleN-j;1qyacTsX+hLTCCUv#gN1LpjFfuiOAI;3Xz&8 z$YZ_uH1)!>IZ1b#nLHJp@)s(|7|NULIopSD=FIxeV+*VC>Q$d~l!V4bw-GL2^L=gD znNSGqj)ifVrt9C@l88vs1`Q@6$3@~r46>JlCssEbKe4?Q8lf6r6CWJgHdSR>O+>U@ znBdpT_r&>{%6~z$m+q&n%i{%8Drs$cPBDItxy3y`Uw_d%{p#GZ7XKYz1b@8Y>Tg*o z%|?&jK8E6!Oc%KpszPxKjZE16K--!qPTR0iu;~DeBh)bmmu@0BlEG1O`X#{k!Dgq6 zMN6wP@xc<-V#lyLEbR)3r{a7>7pd%-j!}`#2}u$AlIYkuy+A zJ*~@7k>C7@T>Rd@quDjU7Dk3Zq2XsMT&^E^#aoWLktsm}dPm(srG2c&G3<^8E3AaE zIfmdp;|faSf;k1QDXWGwsdffj&|3ETFDhHoM7+9(b7n;NVB}t$JQV}a;um98J5%yl zz0d#6D7(#5e3oKDH@L(AIX})cA|$&~Wp`^-)04tQ!y5NnT-af@d3(g9#f3YM5#6!e zq^X}S&7o4K_*-SCL$A%8;d1I9CWp?tnR4UQ-?kemuMpIhh$C(F#+}U!?;ifLwvW@0 zRit3s{7>0xE}k_is!&X-c+^Gnk%!eG#n!OEsc_2JM|}yu|6gs*Z$%47^xYiMZtQ;U zx7#5{HqLe5@lUzD5)^|nP-h>;BFld%=ABeQJ< zuHLBaN1Ly@59klv^DA81HB+^F&eh*_3p}e5vJ1}qT_U`2Qxg^Z$du&&;0l4UihvI( zA3B)2zFYpjCAnUov~-%Mkto~{ul@9>WPW4+FB6E5ThA^;jF6kd#uVWZR|rAqH#U0q z7tynwB*w)EJ9>3IVSzl^l6u7_f`k+_$vjZDap|B@Tvbk-QAkO?3Ip9i%)Rnk*AG{F z-gLk|u;h={B_vVcpGEA2T~Lte0MSo^=CE^UxxphgEF}uAI?Vy#zc&HXXtBRT7lA0E z&z0~sar4lK;CoIe|K~oMgq95TZ`bXSGmZ%4`k32gye?%Y;8qgh|GY_qwk^%v)8V}P zVz@H9qzOOw=_T(IGz|ABTd~ftc0vJ(l&GksVFCd_oX2f{YvqaLz^A|VVi7+O+&OX) zcY8qQ$wyaAim`edS$Y8*%1h2dEPkP#_?cUHw_^ZbGxhHD1KH@BBpo*XCc_BU(Kg75 zPoW)NqRVdk%b~Mh7Ht;@$YJ+Z?WFu|ekmO-&A7_MBleth5Rt3>g|*7r<$!34m_ zp@dcNnMeQ}##x>HE6AWm1SvjQC~V5qeAAw&B|)EK<|*94j9=h>EN-q*vPRoykGwR4ypuH(Ke=$n4s35Y zxA8{u{>`}AY#0!ldU1P1$oOQ9oWw(6EB=GZ3k^ujkeo@v0I|Q~G$+NfmoJHBj0o%` z^-sO5J*Y6)%dqzL2woX0sTf2fEq9IeIZ-i$zGkcl*>iXUIcdy;sE;DsxZLd3a3(aV zz*OHN>2TznY7Psypf?M>jxzVUy|=T}omWHcPU3x`N}KsvacM5|SRNT7MsJ7gmX&^~ zYq!BP&bQa&TImloPl+F#cYlNTix;%hg%Z5RjlBp`{fxWWv?ny#uKyzTQ}a%jBKHb{ z`8F2Ty?hv9&WaI$gyxUfpe)o)a}BC`C0gJa;3#H|t|t-?-?0nOeFM_QBlv?jmPbwp`A zzAxElrr66xjvhSWg5M+m^}qz|-h{aq^({3!Uqs_XE=Q3V&GH+7qSO|7R3g0s9@-ap4=ZC=J<{roUjkw z-M6$y7ssD3LdD#oFG7|z*{mnO>d}nf0trL?wkY&F!GKstPNB)MWic;j<@6&;eTL{S zUT3K|RYn6-;#-9G`;D=0;8OX$XO8}}kN<@il@*k_R<=sY$df4j@u7^4*3F( zYET?0QQp>#w{_h0gcvU4W+y&tahdh|T|Ul6j-+z9lnmn7sJ8{EYB|0Rk%rQ^h`;cs zwjgCBd6Qa~HJyvgtTaSc`SJL!JSRrmbEE?jAMH7B;EVX?2cORL`EP=z1eq`Vw~oVk zcAJeS&9D7m2Zd|YE^MYDQt|;A|NrJgLo6)Kjzs_uvoIs#=#+-97zy6MNIo3n!7<&{ znukLg16aXayW(7vSg*PggAC-b+$rUt7z+>fFpz0xM0|)*qy-gT8cP0YXTYudVQ+WZ z-8{c;uKgdg-nFeCUWQ(mnEvAGRHjNK=czP9aR^LWvJkhF)*{tTtXG^TiAWp&!Bt9L z5Bk|5e74J|X`hdDR$H5A6Z*{V(S_tubmSTVTLS0j9Q*XI8!#SNG~05sF=t*|CnLdo zGj7y&@#c2)@wlpGy}lGPJjyro{e^~V?@O!l6tmq{6dF$eNsaP-kjqg{p zrJEd7%}LYu%DOYJ81g#w8uvvnhUdh}X+E>)@-;z{0Vl| zDXk<4@$+{r!Rpe^D}Q|}*(_?yTR9xEKu>P&;Zwc+*g#MrD@>4_1(6sEN80i zz}Pekn1#{Nn)V>kQ`D7ZA?ieVLs@b?iAyztWZckpFOl4|PDkC609DOaAOJkR!}?v7 z^9CMWHK2dA1(rQ|iFbW>!y3Z-^pBL0VI`}J z!)wl!hC?5*J4aXjti~x$v_-F#y9mO`6dH=_do%4?X!0%UjOuuygA~5hKLYre7RBvt zKK%IX{fg!egf5~le333JLG9-4-v|0n)J#x$m!0dR3@Qg7m)6NhNGnc zGlB-J<2%K65#>;Xsb4M8&qVVyjIS(hQQUeL-yb|OD#i{effhNhtg@F8P|IbC&VtL| z`Aoq60AIdws&Xx~%luGdpRdl47~Cv}&dD!WNm>?z#egIkY!A!f%<>mvbQM*SxNM3^ zPXQxG+JgZ>jFbcd1Q}VDuevOM6eDK{&5h=W=e4I)rG(=CcsXQDL}qeScvA-w*aVL;B9`=CXUa&yituH~3=D(WdW z>a{~r;BZVVLw&_95>t#k`>5MQ{U}t>U@if%-Y7r+PcyznRGUa~JbCJU3a0nU85Yh( zVb&&y*UjqstF?G50mZWmU~rNMg5LC+Ld^yR=M1Y$?5(xx;BeWWLnbW_*co3n(qRn}x0~()$1eF{?y~y@LqpVpw+dt>O@+u=&s3>OZ z1tcViyfoYS{dD`yi@y3p#OPfF|H9Y#;Hl~G0g*|Kw3lBKdmw!+eO-K`dXpSdIu>j4 z%Db*R=OLPIQ9?LCk|2+rq|R{B1sJhCUA#X4VR>)u?4etV5C5mCS_a{k;PZ_JkXN%r^^Rij?`F~)+~a!bH}QLOn(?J zp$gvh3XN&y-3*ly#X%(ZK@78N800qNUU=E0F{vGDxNKf4s-KbwGV{*C)#&9l+8^D& z1sEBPc$nivW5S&J6LZ|po0wm0j`TTpBsRY=ZPXTgH^+p#Q4KkCz3`Gl_WW{I0@VN4 zbNCZr{kTeRisljh!m@c~k({c{GM{kbW=hK)lRq9BKXplYOR@1vY2T`o|HRGTX-X)7 z#9BnAuH|?xxiB>WhL1m*UcYx39Hr@y;V%oOH*$8|;tYlQ$kCKP*Xe)CeC;%x z59fvUkNy-fE~l8;z1d|9MfF1_e$pH{-ORV+ZWb<@^H)=JuXz=IT8=`9dG$=Qk7SD$ zhLBMj6`+X$HaxQNS$|4#k9!|kq{`Pxtkg_=CF=BD)`Eu1^Qt?JR|C(y3ZX11(73d? zPUmq>e;~J3{NQBxl=*{J_MK^P30dyq`BwRg)t3#%ty?_n7x(5wAr)~i4paU=n%+Gi z2fP3O|6n%cwA&O(^s(jMt-~5g)bh#sbho)jD;ARCM}2UYFnRpM7?-TKjlk@AvEQd_JBvdKa}@9?(GLnLFtE z8P}jO3-}sDmqopEy^W7IhfdmMIc3@bxH`1BtGZ`4Y0IL$E#!XOFq}6IbET{Hn=r?wJhPe& zjPxZSBnAZjhaZ|pxEr?)zsv?3wIbxRY*M=I5Q2*^7l^?ij6gK*_{u7$H{Kg(=bL&g zK+(J8=vy4F9oxfJGC(XtE@4T)38M4Py{5?2QJr^C-r{-X>2CYX;~hBY$S8RKG2aBH zopa%(ei$0>l_po}7zfEC+L52QLM?v zri!Zxq4%?viu)F%;I?1;?=&7g8`-?j_Apx_KrgEN2M<5IwNY>zx zgu0or_Q3R@(gE$NQqJ%d1Q`{DST^>fS0G8*KJNW9t`#WS{&y` z0vVlK&f|g>@i~U=7_k~UJ$Enuf;bbwTna49b_+?O#axWc43mN?v9hcL!?{Q9e3rvZI8}xSi$lg0` zfS;8*8Ks71OHJsOd@PBKBbWUM*$?e(+2F9m-lusCY;;^d3#)p`*hj;Jk(m1NtH1-G zkVI&RG}iU77Ig~qhqJdQ?=M^PT>YO|>3IYe*7=Bq2K1WW+ASq}J$avjmw!ZzJSeD` zpg&hOR9#`t!*-^7kbO-_unln4+bfn&!7|vDRepk@J-Iwdi&PtRN}UUi+>H!p zzKzBB&Mm_({n>#~65qkA`vlb@^ahCXE;8P$18z0#X_bcHP3<4oe&bxbpqoYMCnA)L zpr?BKRJOv-t4Xzw>sD|pZUH(!{7=n5hWm*_!=MlveH-u9Ic3JlT5;&?eq1syG{ZGK zAtQaf_1N|~8)`I;e&ws0?jF6zMm%HvaG)&dI@t#mMI=RuK{t7e?$5U>KI+%F4qP9d zum0iff&iKtkKe=Qv!D6T*Nhf_!YxR0Elv=Bl&7Yiyr=@#n zN55L7KCjjOo1@K@(GHVEN&;?N@Afs-LsqeKLn^(Q<{*qj+hNr`4%{@nEE8kv^E~U+ zv=IB9#UX>(b{vCmHPa(E#5fQlH9?pyG%}Dm|JA^y|2o$E<$tFCk=i)loqgk^kjkAW z2q&*)tysx15z7K6QRa&0$J~jfVniiABuYoR@%7xFXn<{huiDmQi$)EfO_dkfIzhF1 znIG}nf=PcxsyJ2#?aW*of(!dfGp4ru5}LUGV4Ahcvh~^F?j%(~3XAd;RF{U*C{ZzB z*L-@VQVcCJ)`PK zr~TfLEjo%?7Iwac>B8DJ=;NSEV}Vm}XL=6P@j=YXO`HnVG}v_34R411T@oPC3&e#~ z``VFNGZ#%Yv=*t4iV>teFL>wFhWud`S?&+*ALqHYL`=(Yy;Rw@(|%X^s+Q0@87@vb z*^$?nJw>Y14Q&qwrp|RVI-VW%K)76@&*~5w9>{MT6Z&3jEig1PAPmu^Ar~UI9(qP$YmoUK z3Q^gETat4tWh(Eg59b3!Fu@`!1}rJc4Xfug7-EO7$FUZGAe#Yd55xK)IbSk;n- zzKZ_w>Lp_qhPFu|uhd#9U~X)mRc5dca_|tEZdzvqw-XTPGVY`#4DPYyE@Lrh_JsrE zOUv2F$m2BJ$W3s43P{!?ga_A{PF=mN*dI4D2!bX^G+t_G!BVqLQiBFM?4xmdh^=v2 zCbNVuG(nYFWtWUAwMpZ&^%^vF`M+LWXyjMba+2p;Ojue9$T zEXUh;eMDY;;C9ZjgpJ;7JYs;%f;|j;$6HmYdjJR33DL3z?-%!v>FW-khD~WXKgXN0 z;cjnY9QC>jTz=c9-Gc;IEZO^w$II@vo15co4vs3x zD9s<1gAY+(l{LN%U~=CEOq~L(P^xl6K?vU;X5Fr!xgm( z&BOiPDz`k>Cat8-e|iflH71ePm5J36)|Cgw`RXl)++x!_wnIKL|X-|^H9fsBi!Q|LG(c@z3%!4nWPt%SEwW|{=KemEA zu7H2F@bY64o6}zvLK>4+lqT4}!!GD|8G9BtRP0q8!OZnPc&e?A^U|^%hu61pTUYh5 zaP8DjuGvl7c4ixQ_VY|Oo+ZV$FxH5fV9wW=zgEN!J-Iu$Ghwa>$h|Gj6jHBVPA+t* zB|)H4DAbi~{1{2{RBsa$#dOL-S_z#7*Lya>HKazk>tM(1 z%F(k0&ExvH0=Z+qxt%`{(@zTlkpw_|I3}*(-rM6AyjYTF7+KdCQ-2Zz0f-&p#*V}Y!Ccvd~ z;3uKt1X)dpEnjAUt)f7+@t|+&5rQewYX4PY^L9qp$w&5R&^}sp)FyzLB#kqGf`pp( z#t6fjKW#EF#|CD&pS=59Ui&7se)WR8;~S>KGNr7?2kbctiP7w4XiCo% z(i#u3TcNKfF6tFsNQJyX1m46-Wq@A4m1Ar0&&rZ1~KeR$= zE)=bhN~~t%?!%@69%&`H=I%M%ody*uulT>-uXk=0TLKW@16Wx%^_#iFrGNv7w!I8h zhW2TFnK(%?LGDd%$#R4~*oaV`Lmsk6Eva~6pp^8=o5P6tbPiKDkYCP*YgtxXq^9OaActWBC1p$tnN8Xg16p8q3 z1LoVLgY!J!irL{-j}Xpzh4xIzD4WI4IxbpqTDhUywMHq6X11Xq#GvKx!&!+#H)v0L z80>o!aiqD}`ZH&OA9!znKcQv#ge;wj58t66RAM)qZ1j`R`K}COmKC9!QQDLk9T3cN z6SCP#CX8jgv&V#sHT9ON?)zKwGV@q_y8Q$&pxsF)#Vc!?<3g(=AI_X@bo}owo_iu6 zCF{8@{`<<3X0L_;_uD&Uq4# z0%OQe_BI?b)u5hw{fk|Vq6H#jQN`{%NTz(qBI9#y;A8k;R1{|gs30^!fTyem9=e|& zV<|uYE*>U4$7C`+S{YXs;)&k){spLxz%c9tc0Kq8d(F)x6w1su;bL3C2}T+G8mm9Q z$Gn2QQ>yrAHg5lQ7xpf6W(d*x(kT>)b3{^J3nGBwJ~Tegn~YAgBC(7S1=Zj40iC!` z^qxOtgpO>8VxR|UZ;xqJHN#EpIk9;=xn_xp`Zd%$D~JzT1S9`TzHm-gXVAseKKp6R z>MZQiCywQs^?_e;L--mjM6|l`-2;l6&)Bt)=j{vz_1y_(x0U`FyfHMJ&Q4ks!kF9> zHM&M;RY%dYGw31w_Kt9Ubw6ujcHC))O7a{?VCIq)I@&Xgei#)}6=NIn?XVH3Aga9n z(-r9rwwo8*HHv&%W2WZj{@2Qhx&iaU*K(3obtkySnSB~sQVUWi;(-Vb2nKJZs%%~L zyr>qHkR^LW&hN8snvQ-3SxmRy_sZtI?d@*MP4>>T3!JRJLwkKL0IdZPB$r=1ZqA`w z8;&gK(>rC6kJ7!fvlJ(9m9-iuN4XZT;95?3Amgq zJ(ESi`(|miNv4D5j3~l`KDOK%@VHYClMWz1Z~_&TeWu12MOUsqFXD6IRFRoj5!*L+ zMg$^_eX*bwQw;W)w1s4b?7TRrb##qJU-9n6TOqHq zhpdiAZS|E=KUD$nNa*{5^a+i50oMS{lYSxJD180o1n^WeG}V^@{t7IW)~HRqWSf`E zaEOVhR(eEI6s?eXaJ(5Lp;#`)(*?R34GWV=1QD~W2Kuw~xE{Y6NZSEn3Or=ZXD1qO zWy5tOo)%369q_+|EHM$IgG~Hn<5;6jSq{ON{T^GrGgT@DQ@gc`XnFY#gEr~UIG$2& zZfIm(W0X(&?6byj7rZQx9Y5hQC4GjglHko7?oRT}y%*{7e``8KvI*EWF?eO#A~9 z|9SkmHdvk^0mP}{h;<9NNjsRCi^st_uWP~bDAhSP1d}V`Y7Pa^jE8@dXfvih;OKCX znCk@`3^WNH$m%*XtJve6r?(b7Mf&EDt4ynPO}dYEC?rf4V!rPI%Nq(El59>b5OUC# z!^9Q2g5Eo1J>u?t@wtEMx_|jcu+77oi`tF0di_?;V^;|46UaN}l6S|2*t4yYkS>GsEM`6Rg1zk#%IvJwT2vnNQuP)HxTDfXw@m08iWhv&04A0pQko$+vGI! z)K$OhT-Y}UpbYvtewK+S$GbO^E_y+};uIVE$xL&$2^I)dx?zu<;4s{;SqDq6HNl2w zpgoix4#i~rOVz(AA}J$8&~zza+g&*7eD;Ku+2cc}C4}rf_kA=_mQDU%0|DyUX~iej z*mS;Cira6}X0mA@VU` z_-%G8lu=G#S{?qHaS&GmwN}Lkb1t{NPg~5-0-q0l%*u(4-$4XY_|B+ux5Z_?JiB#7 z7g=IzL#@v{V3+CG5*hO7yG|vNq{vUNdH3Uchj#BW@SD&OV`%N$I&Rjg7K?!NVai!I zciA|XetSA@QC>%_eSduzWpKWJ*zBBg^?ebAR~G)_&s8KiN2cE7+sVe!9asg|lISr! zIdB#0efpwiJQev*D+>;8&hYgGHYP)Kq>PAI3H3D%AqCdUoUqNxQ}~ZIwX7z4E^2fJ z3dGIb6#Xnq;%r?bYjmB&t{CEI$!7t4&oQJu()d6=zspqIU*?S5QJB$W(NyNN%LxLJ zZ4$pGNhSprZ6N|emq&SBn&R4~t zC>HyZZT2ulC)zjjyaXsSq}Qni7UT!F9PA76pr6Nml{uz-)W)o+vJ3XjsdEDDUzY@y z?{FWKJM&9qNb;;hQ>P3;6x7V{(yb{J&ScnF^gE>9VK?;`rt?G8iNq|kEWw?Z-*??_ z13X=Fb8s21>TYE4L+C;;{@Nl$8hE+~Ts2@K@BUI3mIp@{$a8kTv`j)@Lt+C$R8l;z z-x`sPwMQ(7G6wo+g|(qA^OLnJ7F~YskR#wpZWqY^l7I+ zUiog()C4FiKQ~+3ArVpr`XU`)e$hkG5=X>{(qFw`%kz~behsT?>u)3)IM)X#Wx1`X z`)OBs_mqkA_QyFNFnOfT7_~F^NY5}^rsMOjeN=3H%Mwg#m3kPKT1HZVo%{tLB{PCh zG-RmBfJ*$BbQ7JJC3mC%S7h}l7bq_@jj4!!5PRXvL0kLU+=*ziq>w(LL#Hw#4AC;2 z!|YOz4|EdvCES){{eSThpeflU_#kZYR}`MS$O)I&PYI@_vXtsi(1CWSb=Pt1jNuP` z6&F@Vh8|yo!XxuM#|wm7OJPVRpi_0dRZl_Lg>_V=7WMF8?my|QezRf3fac4!Ob71V zio-I<%Kvq&Bs=0edja`cM8*e5j-X``kQ#18aVn~`bt9Xb3n2M1g}?COrPkx<-DjQD zs&s%LEQ(24g}$(VQb=`7!K=MPy+ra3bDv zFscG`%`O;7?3m~(s2OYLp6EC74o*PeJNw4GV@Cqs2zC<@@S;2ewf{(;C3P=SZfLl( zav3H^O(+tP&!StF&Ehc3`A-imxO3aak8VO|(-yJ2cfQUfqt=f7P4`r0>Oj;lefzEM zoiv3cK!wjyx!^I6Ds9SMl5aPq=9y{T5i}iKiZ25Ip|lkR1YKg`R(lMyHL^YsMMoJ>h0QMJ)Wt_e8eN z$-4WEKh@D=O38Tz2#|7k_oM{EYGA@pC0)Z(amy7BvGCcFWLj z()l7ALz(eMuq}BdAvz}HhG>A1!a_q=mMNLHj;M%$_%c&x#>r-KD|w3Agk(<%)}a(g zly&=W0tpiFIIdolK3vH=FJvYvwS!Bk3tDjpRkt7KUZxVo3ZaDp;+B|}_WZLa)Cw<+ z_H294D<%_zWPI&b;`Q+P^18AJ+7avHd1TYND>=QmblH0gVk!_unxr`7=oxR%+|Er2 zc~ZjBgk#Qpo)e}cSN}k(@-jR>m)) z*}eyhNSVN$x&d`#r7VeTr5trQ6cfx9w&*&hLu5i8lmh$+VXOYMAr6^7=2qxfu0Ld$ zue5ni-~|vdis-Hur{d-^%v~yAs&5M=*X@?2g7MAfTGwZj@5U^z4-UVvM&yrr2LmT3 zU9Yxz`#@moOyhKYs>#k4yYyh409+60GZ$E*GzN`It!jvvqdvfF_}gflbh2s{MWwrU zl{+tws?brP+zbXhDFDpJ+8>QiNLTD@z$@Fa&nBdNbvCAwm)W*PS9#5(;=bkU^ARuT zaqKh}9+2`e&dROIHHey=#(D6b_SPg4@ule8sIKUd{g)unt8=JR9W+8xe)alz7I z7nt;za8>rM3;tOiYk^+Lq)94K3Ih(Pa8)SRxR`L7$-!XKiN*FZ-6;5-4Q5H zDBM#*5fJ0pmkqeNJ{w2qm8gt@C0BZFuNFBjqx%qJ$T`1oRt!GonFc&s?j!M^PLy=-{_6BF+aD55FEnh{ zQ61z<;&}vOuzW8p$2->1lvBS%ui0q#t`Vw~zBMhWDK&2;|HIo(h(N!}BU@3Kf5JQ^ zEq0+fQQ!nC{EzYAXv@APqQJW#SvhigcvLaa;;SWiHq5oart}ZI*DSnWJh4Mj4#-q6 zs0pzJo)I@Cruk7cH|4--wWo*W4;IB3aI_VHY}ugH8;rvC5`ZFxumf12I)6z2YtstcGOp)X4fCkcsfP^YJ|pBCpiPn0brb%BJ} zMVJ9-%su)pi*$zYSsj>gg>RdX|A`^@(-gh*EjS~_v@9%sV*IP zP79s(ro29%_5#76?qK5=S;>Y`XAL9&BX2>J3)B<779Wl?2Gb-AeuV zG?qe*AyGLv%kt4zB!H2-bO_Au8xPKF#_v5WS`N%{P1%2FmXN!2HkS^W%lV!-nIo@fBf^B z^=A5b32XeL$EMz|NUYqv`Y52dXL;5c&b#x4?)78lDW1Dl@F8f*l&HsU$@!sbO*LDs zX&6T0$kF&53d^vuWA0@6-L@}7UOu*j&^jQ}*<0kkdNhYf`9*#Xhf+Gh?*^nF#z&C8 z0adxcNClKj_rrp+WJj~z?xJ9}K?s1!%z@+_vjKEkH!{Y+)LD104jPh#M8H>{Jh;GZ z+YTiM>)5f{+Z&IkVW$2%9c*1>&)40>dlP?4bglbwZ5R#(|EnZ;giB!B-Rwp#%Ye%_j#ZVv%^Jo=F{>CCL(Maj z2*YZAmQ_2x3@|dZVfqs>y|rB7|Ce&_KUa1rRSI!7o=eBJ^Xe=LP;WLxNA-BGV|22= zSN?|a@xfnL>@PRe+1wNq=ODwBtCc zN}@Z{&zumsI1hT&1#VfX4=1izUORVn!=1!is`TD8^=F%p|G+cI9K2U6nE-57!rRPB z8Ixqb-N-AJ(`Mxw#eqgCP$9Gk+v3}~)=mUOfHT-D?$~yE<;2wMQPYBSPh}|te?=Z? z2{q>U#{I3Xy%0=$SbE1#&Uu_e&JqU)>$bwkKY8AFiA;SO9@@8gnD>1e9mxRXHI${U`T8!6p0=zo9}lvOocpP# zepgoehg{O*I~{1pQ$wqdr5q?dVe-JR_gT__YwX`z(!X(<`&)kW*z#{(N>Bc-uJq!N zYUbzlT-dC9lg~(p&T$-YsjFNUTr$}F_kY+YJo^NO3$41Hq0cj?bED@TG7^x+Tq^{R zL^ZIS;dGm8ET;9Dr);zQ6@pN3;)`7x?z=r)oc~eK)A(;a9xZdyAGKK$g6nUw61Q25 z48TK}gLbd;jrC5GFL^7pfc8Z4@w_Bjc?nkR=kA4RHB^u!!_yc4%63VM3oiScJ#5tw z)lmJO{#p<~^F?}&j4keU{2VU_OtnXvgvNr~@g>R2b7fDIE2{Weh}~XBG+%16;XvC# zoMb)83SJpihObjTSz^f5bNk>QUJ z=9;*??0h@hh@5eAVENMB=9p}$+pzItOEPJyLdLfjX&as(_)v)8!xeeN7dLpA-CZ0U zUi%xvZLaY_!{X|1JiOmTZOgjR4-I(#7zxKw&MMy7KT>u;<9oK~N$#vCg2&p^E73{p zqhm(K!QzsYP)$yYN8sJ54RkWqo+Dh$@5_y;8_D)?;m0=3-j5s&t!EYaC%o9{__QXm zZKmBKwQXb;&-c&qsr%zrj@BeZ7>(aUbxEQa5oIB}^mL``hmTQzJd+$peH!PowGkK? zPnFP*Xzxa2e}H|ZF$KoXBrFuLMD%~*g+c;gD*ZQ!Nm~4PnLAgeQ@`S5(YjOg9tY~` zO#aDoa8<&>58k4_))E~89Pi2fPgaGD*Lw$CwPUCWV>DUQ!{THKIis^qEhy z;$by9`+>-Y{#L)I1|1UrOyL^N>J`Ju4ACVSS@Prs3RG9W3Fm_k5P~GxHDUwbKBf*a zkc5pKQWfuTXD`pjT(vbz2)!w`y*(?8n%SUZ;2?l(zUM+!>1)V2PCcc+5xo(jj+_#hdkK-nx(5Ss11=eneUSV( z_LEBE=@$pEy|M-BW|9;XN(&Mf>`+`>*+-0mYF`#DSi-79Z(|)Yo^gg{42_K1TK`XY z&(}G_sB?|fb7>iyV=^-ZB=6D z;x)YWxnV0yz~@stAM^EAFSH8E&K|W1nQ-%R`++H2FfC$7J7^Xkp)ca0LH=^<*Sr$t z*pe|*upRQL7575dGw!xLvVc3-Iq{Kt-j8KPYjAMr#vd`x?uiwG94IE7ZOF7nu^$Y7b5n z@jCIL+CjNFb{ah%@xBVpdfb|6Kd7P68jXtgx%)EzGEaik(|LheCY15fZX z2)wXSH)e{-EnPH5HnVB&ML<-Ku7ie(;#b*|j~wG;`Jc2;lD^`@kHmi#4yA61y$nWz*(Zna4 z>?ibL_6t;R??`y9YAOcFYEz%`6a5BG zpNxzuKVvsaYe>@x;2&_`bqh+rw+e?N2mC(D1_#IFpfEzeKAGOyukcbcE!2cyJ>X9~ zc%&~buz88M2oLeIah?JJL-(NBxY-F6ufDzXJgX+@m%0eCV~07^jtpq1uwWU^TxeB$ zTL4OqOJfPXaa-BZctkgHddvP}AcI1yId=~h%nN;$|4hZ=RL=ELo42!d&Unf5EeZ4% zcz|*6G)x_D8S^wOaANXvn~X0u?a!<{(7htU!~A~aq^kX~D3o+w?6P?(!^)G>RGXNS zgCKxtrX3A39oi7}x0a#Q@;;}J6Z3!B1A<~;65j1BS!xe9mbXwpR#!5*k^DvRSl89> zJNY}Z3*#uoJkrDJB)DM@xW7nx-nbUdq}OPjmjO(9NS*c9_A1GeF=iDzf87e?6G;z} z`_|m&_=qBmh0Pc18f|I=C6xKzDv2`Y^@&l0f*Z8&nFHb22DNld!y z=jPuAx;;CydUY0Y4+TMn#W~jbKlzd1J*bTto{ADk`L3bs=cYt~@xDv=BCaiGUenp$ zf<6`FZ4i7w1@VkMMeAs8CQEG1n7SPN`L_u)v_Be;8vC0{#g}PS8#x$#0ZGdj2Q$-Wj~_K2DFzqUEJuay#`MGN8oeV7^GfseFYV4LyKWmfqr%Si zpt+{9ztyIBR`ITv&W{#syl$J;;q5;BpjS5iidoYQ=k@cVBePUFgOy2|#K`pHZbfF} zbe_IH_GK*6B3J1AyW>0Si~LXPKr*y>n#W{;Owbp6fGoG`*wIbM0P%%;jpx3|HFjis zC#9sFq6>HY>RKY8fnU-7%6jKni#oOLrtw{(J!Psm@B_?qep&mhGtudh8Ot(+6@Q?o zi7ob*UCBU952T8qQdAAG-lV?ksSUm38f%r2>grg13P)Xc_J>cpYJlsTDWl3NL_9&a zRL&w@W=s}CE!X3jN~Yz!$3MD$OA&1pbbUq2HufsUo1I%Fi4WLYmx0zsRsjbXgAk8* zj}IUtOJ+l$`=R(k!f?%V$&K@fe|fH}>|aqbaD>Fd<;X}}I~NBx1de4hht$|7n9!Yx znb+NL;Zk*o|62-GdABzak|&bPLC!Zw7mq&#hTe|XqjXBzk5w^_>CrEgJ`ePtiE^m( z_7r%yM^Aspa2T2?={6vLUccHhb1AuA*a?XWCWQvR9xBU%>v$uZ{rATcKo57^Tea_s zW%CCs$K1B>Y7aeq!W?wUf-%Am2XQc&v5W{baQX`eeNWbsf>f(n8&03Fje6w7rJ5%P zmA6#}+SW+Cu@L^SvWp`Zm{q}?yL}vXTH7!3J6gh*{qU+~#>VtGWk62(-VsX{=n^*@ zY(2Jw$nAJ@q!J*sfMod_q0Y#$bY6ZvuOmyPK%riqYwC)JCtoKuqkZRvwq2Iaiv!Yw zF8NNJ$H382F&3%DH@oz_vDHS*yX2_wel$;%zD+r8I~|*S8>Z!+`u<7xqlM)ypCMI5##jFM&4%|1HsSef;NprEM@QpWjKi#4qKyae!{n*&)BnGG;Cy$fD*jT zB2rsKw&sNA=rIb|;ljZ`uR}KsRr)t+LulyPvw3$D64T-deb*JX0!`&;#D?{}+b5Vh-F**q2=}qU{@^q?Hn-KY+@IcOZ z&a&=EXHX`Ob1?B=wNs3|Y0AmvR@{OG#K})%2X&agL+tj^!mG#u*qPGF-jWUa|985w-*`8tTqw$t2@H2OrM3?cVeKQ)Jrn^5n(b%Gdwf z(z9X7=OD%RY|tmr3;!+eZ5*--$+{y4*=d~CpPQ*1D6pK2nL?b7%UT1SwrfM^|6o;4 zw_*qq1EvNmo1FJ{^qldH)sF|9F_db?M$r{7cL>gM*uYyih{!VaSn?}85LAj7!giWm zzln3Py7Uj}^68<>zF?M}C(SzJeC_3oLPJ}P9_vzwepl^?SWSU+=QP=k(Jgaa3!qct z>19c{Q#u=sGM0cTlJ2xEw>GOp_CJF=feNE*w-PGL0QVua0A*vA99=L(t1yT&ET^Br zKknK3g#+|dnAZ|7!FCBWKgp(24HHjw_Q%{sx{Ejdw{=yY690|*5TY?88FDNcLK?KJ zV{q>05Wcg)CW?`z4QaA={8Q;hhn+RD%*OkGCw!D!tr2<+*+EC9a+#9jusHei2oFWk zT0**~Pg8wS?R9qru?b_QHYZyu{CV)919_)@v%PiUTwLJ&ihy%WGK(vPD*nL8UHRNj)4(+*9GeBz%t!B^ed-#xy0(f*UIdSe=H?$T52K3lXr z>LD#rV5fbXSwEbEwN8dRPl%Kj)lVkr$d4|(K5l;gxBQb6%bcBB=Owdxsl;sU^TLVa zBLQ}z;yK>Wn%bU|fksU4j1%S^Sdk54)ftioI%f+IXLx+8u4Ga6A!_KGtB~a7V2ZO8 zM8txdpuq{gfI>K#W2_o#J%X|^=jA$tn+Sc*e6u!$jeAq;*V+}g1a-O~Y8Y@#b)CJMcxpMPzr&nTW$@Vr-fjit4&^!d~BRB0jQp*DWRX7(GBd9WUN z5{7yf&A&23@8Ya^AE^3_z9Quw_<=D9?6M*+R*Eo`wZnrU&OO zUT0Nzi_?Efn)>oZ=&1`jYb|OS>D+_5JDKB3>`0P#74$uw{C~{}8crP3AlX^Yw@W#% zWYsc?>_7DWT~7iQgJ`~a%quK}uOZu>#aCH|KhS48y})nEtdq5gJ&?mYvcfkVP_!Je zMv^2mP+QCvbqyi}dQ~JF#w%&%C*qQ3w+;KZMp1)ccmgkRrX7Ien(iPyIbZKd%Q(olP8xRR$4wJ^#L*L3xS&Af(?M_dwF0QQQoea9~%l( zvo9CAL{3aM)bV~?c3sD4_s+dftIfvwPpT5<&3lYEUjasC=00k4LHNu>2$yUjqpBRI z0K~qrcGvLrntgLZ%hOzI?c3frFIw!p zo>QmY@;ph@GyNSG<=Sa1qv_34aEynD0L1<2F{VmNq!|@o^_i%HDkCNEi#-wa0fy=^ z(8@7&Z`!73Qjc|;t)tBM{VI2+8L{7ig+W!x(p)goY}jq2J*WQMO#N#~_KF~bs5b}R z*ezUt?_ycrp4qI^(frd2=)~&vXhmuDm#|7wMz=^m1Rm8?o9&s9Lp%)$h(e|!o>O3Z zKga zbrZHXe&f*_5IIB4uz@DveiDw__%Wi~YdVX+e6#&ge`C2=Cf-p{TN)~7B95@ha@mBY z`0$vvqJYgd2j4QS`K~HWeM~MjNirB_q$(QSaJso8MAc8pSkY-*?({Cj{cg4JGDGuspUz%q0m#r9J=Ic zOpt?v-**J~1ElXY?=rbcAxm>vacg%!I2yPxzZR*lxVC@qaSU^A3>L=RS;SeX!k_XV>Hf%vmLW_Hd4WHJBIG2`&&Rl#P6p8LC z62`QOA9=UavsjO#vEasCPs06^!l!k$GGWjuTV$VpU=H4ii#g1pln^|6`t14gwK-|f zsAnVJsHM=9)>)TH`E4|7^Zrd?=)oXe!e;~TG@jdjH0Y3Q3?FVB*a%_G7ICwg}VLnMg58QDX?6ob}_xCHcK8l6L^SZ((iNs|aYAYPay?VA7BP zO0N3Jd3n<2?_iIDEz5FkJhi`UNSCJB!7W_9A->33CE&}C-uUg~S{Eq9z&@$|gp*L}h?|zgXYrj!K1~fz=juw55b%ZYA_!hjH6oYbxJpVU#T}o)o1MW9L z7&PYgrDw92VHr*7RyU*^s^t)37o%yR531966wy2vHy~xtoj;aA`*r?ZoG==hCue2a zR3<8;QSMJece=JZbE5LRq7-w5PDQrd%8glW11?NBWqpodNp!Z{ev?(w__9N%FZRqv zSK-GJyeZ3yitxjrhlJVzLPxk!pkw~MppYtnsh2HEM|Kfq#kxlfjXlQOtOvK0!#>g( zs>KoD2kA}l z9x-{5am%F9wb$fS#IAlue1YyA7>vuXICdLlWug zZs8?c5?=GHb9sUbklrJ!GF#@Zx&(*j)(a@146 zV56XAVyatf-If30Dk>^kmeSDMXT~(~eaeTi06@`!Olvz&;Sgy4E?) z6-QtMJ$Oi}d3Wrzw6+S71=YL}V4(8wq+>zO*wK>mM(E2mdx=ysUH5Ipd?%&E@Q~F5 zgb#6}X%fpAce(MHLH<#T4R+z7ir(&x3s_Jl3a2ypYE>4gt=^{uTw-u&%nXMH-9S8y(}ghYhPV%%Sg$udAU5!Gif+%O$G!ZRQ+P->ZFeIV)jQ5B0QkKJ+rJ;2Y754miK@CI zLSD(acN-l!Qbw1+>?79sJ#2bp%5>urj-67?jewc;HV4ewaFBzOW?dM%`_cLlm&SIT z+5KqVtUIl@6|)L=I=YqLX|)-%A}p_~AoRq6w>r!3T-xj0waR-#S(TOmFmU(vk<500eu2>KW4PTc`J+5^hV4q6r@pzD+xJMFguTO9lxx`XGfPPHu`)O+S2Sxds+?R(qj zgMiH8ZY2B-^l{YchH7>ohm_Q8dg0ay`QONZ+J21>e=V6NkX#n z!=%I9XGn*wWDT);WKxg}&fId<;hOwxfP-u1e@>%C=xNLo>$xb0w}x-5%MS$jW2L7|0G60MUD6z!#wAvdYlFIgLtI68Jh z%Z$4p<6iwXQ4gSQqKz(PWH9oag3#9=TfUvuQ4pMvFSsFx%1lvfj&MGt+p@46k?*tY z{ofy06t+8|;uAn@(>3)qXmh=oYliu&tqo0Q70v-?dKPd-xlUI`hxd&*Cf))Rka{lIO+cjc!7T9${GUr)|b)Pll!) z`TGCkvM4*vy^0Z3y}YCUm(_RN=)y-||0-%q+nS5N<`j_0$+Ikdj#PReAR~IVX=59b=XHN!42bBZ$GZ{L-Y!m-1DN`(pF3zx? z?=`_=Vb-&ch_IMnR4z6y`r*wG|2VeQp<59~%&%f%BV(J*A`fPaIFY|&EB-m#AS%*L z>*WXStF8$3DkNjs8i`22B|p_r8@M&X1NazVx?mCtsRdaRxc*|MuFGUKL~Xf_M}LUV ziXaL`xs=u-Ra0JNz^@u-H^fDLWUHV3OTVrz z857KkMX7t}seLp=*3oF666y-QIu_W8@FD?zW1Q_MS}TkSJMKwh=R7|#tRfIj{*HKW zI&|#Zxr?q_=e-N;JP(s~*zShx(CP!`nuh@jyJ3mt7`9@NayL}qcz9KWu?PM6o%nLU zb$1ZrW|TG_fA0Dz5m3&x(>)DGxE@G7{sNK&Ewra>!iXQ;@L*56T#ape87Ecz?{F1 zVI0B+He%O$PtC?QJDI(pVnw?ysd7OMV?K3d+%VT+zfj5-p~F z8cJ)l{>8qeN2o9v?BGUYf!^!HH<6GgW9F4QeP`Ff|QjaK&BQa2iqbdyMf5N%)v3TnEWoeq|NVZh2-Dv?RL1E9BhI7YY8SFlW;eecbdt8 zAMR{l?@(*~tz$DeBO_E%rH#bq1*QAXsxY*b_9)IZ>1^Pmd5;Hk^f;a9dMbN68*X%8 zO9JROyqQv!N-)C`jGtcfJG&c=a+CF%$Bxop9+Ny=xBSK>N57VtT+oZ{Arg0`)9u*B2*4nS`ql|G;f|Z=f!E@I`#D^X9xzrkkkq1Q!vt)z^KJ9dI>Mm{5ip~wGh9VjqbVjc#64VoP@vepNPFCC z3dPydx#3PcL!jJb=08vd;__d$MBu;zF10CqS;mB-`fuakN~?S>TOBi5l+1!gB}~Txr9pO2TD>F=QIG8%JQbhR{VUXe4bi<9i+0fi8xqO%@ zN1XO#<)+YDH*>5v+B2(kU-+>ehaVLr%JO#ocOT!Qv39Lp@qP7MCZRQr%!f`+HQe)a z(&ZbkZdrEQKd#udBl$DexMt(t{@A{7^K&<^pK0oN;dCx>s6F|sPM>Ejzj}&nH^-}p zzw~f*8A3eu6NRIsBTrJKd_|OZjSN&Ch}{ZY1QWU*yNZymt;-98^C%L88@&Z1L$=MLf&?^~Mj6RPhfa-wL4r{UriA$bD_UV_2?qnH+C!J_ zP!h(3P=&&W`QvKw@W2z6kw7d&x8?Vxf$vp8PNTWSy1kt03iSARn3YkT20V;?xzWZ6gnisDRUqdfx^4xw{`|!3 zWQgy0itI5PlsE*IgH(~C-DBHmVt9AJ!DBJ*=FmnSvmS5 zVDVB-ZGsDFVU96|(vhRVC=nlPzk+72IRFqz;vVTBXf_yZf?Lkl{xcLGWMLj@ptFYqVcQ>l^Dl{ zS!7UCbU}5AFu=XzOOaq|6#P?YO?{lrsUI$hSV(KBH2}AE;l!_3H#m*IQ25Knub-+j zN}%k2T_1w9>?U)ZtNsK%$TX7d*<;}hYXDzhtCfmh7JFVW!y{ymt%$%MJ}7=M{rI{e z$%P;yk1nMS!_AKoh%$avgEaUNVh|6zuztxtLMF-n8)@b~m)gL!Ql>H{Vnh6>5zHyq5M?&B!~KmG>8qiNeX&DGFZ2L!;K9yS`H-nt#h9C~xT@Mh>+B%hifs?x zN-h>PdD>h24rO7leZQiuXLB%Rqj|`I+O3?bS})XdGMpqVH}*9LTlfX%tuVkHUr8a33-n$CaQIo9XcM-pOjm_ivjULxi-h>ELu>Zs08S!E|=6yOsZH!pzr~MwL<| z;NQJ6eiM9xjz-86qcsipFS`stzvoCjdoO%17Zy}gPjYYg9bfbxM1 z*A}FeWvBY4__)=r zIZ9um#sUtQnZ$li0^?dE4^QRph61F*Od*eSVlN}RB2^MYQ6#bYseCM$^Rg`WlXVg1 zt)Flm4n8S=P&xSgZEs>o5|Y1ijR9r945r%l(d5vk{O0q`UqmX7SckBL!W1o5lKTV4 z4Y#4py6X@&wm?fmf^c5)=WU}Fti!YbHbBQbLPnURMUaE@|H&|z?X?BRn+4kA)A3p- zgPD91b@m1lnT;+I(QFSkEOg>Z*`eTza8$Ohipb^T5oT(R@3x_KfRa>ZjOPV)r6p2K z7*p!Loj71P=@@p$nh!&qmNsdGH) zjpj%rBTp9i9Cz*HDX5%paGIZ&J2X*d=GtANmP3zc}pt zti9>Sgy;eLsD{dXS`=fMm*92v!AM$f>opYVJ`=*2(OpR4q=F=;fRNZY76bFP1rx~`c zNAu#cTO|gGr}^lD&bnOORx4P^vAN3+h&W2W&A$tPc)qQhLuFTbM@!sqd1%4)`9^CO zCvWD^HA};OBs@1RZ^HeI(VCpcw`}}y&J0u1vzVA1Z!@bN(c5Y?(p^D`z(+^Sl>( zc***RRPV*~HCYq87w`5-ezk33R>K8GFbyQptg$W6Kc_LSaJ2Y}r3|SL@>EOo153Sj zMm>7`(Tv9KdRJm;)a2xdsSD;`Dh5OI)L6KwoaeJ((gyw;Fa;&!vy1=4$IYR#?3=&j zb1orR8|<_R@|3Ew*M49Pi<^P`#MNznlE{qd#o`IQN}p5m1tOKB%SsQyz zX5r!*CoW#rm)qD+E^l>kZk72Xg&^o(oHbZmxqMM~4{+9*ZM&mR+n9y8ktFD9nVqxi zrX)OWkIoDY`iGorlI&5?b;mu4|7)r7-8a%8k+)xFI)wbEw@Wej5}O(4@eicL+?wGs z9ZL7%KLQE|E+GFwiDz|CefSBg9m%x0mj)XJ5Z^?VdjG|BF6r�+O!2AV4mjyiJ{3 z?;=r4KOBHgeDy(VAC1CxZ`AUuFU+?XDgO3oPQs0UblPM+vgzMX-eykgs*bbpczPFA z*bxiTZ2X79>0XN2nK=HwBfV<(d3(6jkwl5R8KF2dmF__SLQX2^DTx3Hxt zQH%{}_PSOcH&W4{I)~(Z9CORi9O?snkm846K$-IxStMmHE{8RI6l65+*Y`IRJ{9Li z1Lgf-{`LP$u#0CimXEVxLj}8PE&2j*vV}+1+ExgICoWy;Ui&}XsbkF~$R ziryE>u|t-)i2aMiz+tC0gD9jDus|eO&UE^;oGap`hc6 zX^7dJLrPeSeJ4jG*9h~>OJ4x702tGOFBD7RsP5@JK%$b5lxU{7RyB| zkxCTfO<-xm8J0)AGH=HRG2JPG-S25(Ok(UGyM1)R0xUN9=ekL65X&uUAy$7wPmrHS z*oxpn^IXuWN3h?-o6}WTNg>ycf?`ON-$M13NE0u1KSo*6OIY;5E@Ln7CuK8P;?sVTL#RJ0h)ThJHDI6A$OXo1RWco0OIiQMqk)} zaj8%T0MXwHMHCst5VEO~ArUNlq7H9-3!oP{j#t{8#wEz*%Xw>JvGxAo1RrXH4 z8%1oH&<2R3BS2nGF(TUx9p;bOqrKe?T^8JJSjBp%GO1|dUpj|thx5%`kaOKYSkW4> zF?{aE$+XUACPqR;5;;1-BfTFpuijG7bn2$jMFQ+}$e%kOdOSAD{k$bRLLSQK5K(-+ zdyNwR&dEs-`=IpY40Wp^tJqRue&!lwY90Xx4ZhX$h3o*eKsL6CSNO89I*kSVssvi- zO&Ahsg^mxnww10+k)o}5G+S>#e}e#~SqRdebL;x`wD9`YD$_Yr&4|zRGJ^|f*GGfX z!x4+lXVO+Dx|E$Fc2k^3i<_-Q?_v_vO2K8ubB4*IF#3t!wwH4#uld%Tw93inr1uvT zQ3U<_J*JBTNtB#z8)Ne1E&;T9B##06gKhJ5ywC1$7;~A! zMyw;XK@z9GdsPEx_q(0_N+}9KEsv>dh`b~A7dm!%rt`*|L@fMRJgo@NJOa}m7w@Dr zw}u{`=Jb==;`083m5HX615?>AH^h8r>IJ|#uKFFNHW*pvF*c{NaV%^;o=FBgmE>s` zukPguD_Myqc0x(*U<6NfiuVD;q?WYOo2Jfv->kblH{H;NdJ>f+dC0S4c8&CEs0yEr zjeBDA@<+xW58paUr$XOhS3geM7{igCCdijEx*qzxSn~P(?bj0Z3)V2^{_87V!l6{l zlfPd?|G*fKm?Q=twm1%oHO3b;7BY6!64pd4?)kqzRHUSJ-0W6H08K^e$lc0&jKI-p z8#aY9cTr;0K5rBN+JD?(Oy!5oe3f8ol(BWHWX+bj--kjqbl_nfch}bF|0sq#kWL#1 zfihV?{x;hiG~o6Y#<d(qbzr1Fnq7jknWw*huL#$M)nfc18a zw~AR%_(n2xP=_QXFK~tleeP^GD#stMI?IdQyUwXH|K}%v+evf$?wLX-!#uA{rruP7 zmL_VMkic1!L-sXE5OS;r3ZBhTU%SBg&=gDI?~L4ZG=2$Qxs>u5A^935EB;lr26SIV3%_H+mRl zb0ovlR$gF*ch)k1gMzJiybk zFrT9*9%>7Dg>#&7DB~iMnuuDm=WcanX+s=@u>8BKFC!yn!s8{M3PN&1n5kpephd#b zjn_5?thNlXSJmP)U;-U|Q;&$}y9ozDFy>z!RlCwvnb z^n`DYQ~KfndoJ*w{#HGR7$pY$N)@~fkd+4d{97j!El;G2z(&1q%@9Kz*eSBL1Kfv? z2FJ~>_qXMBuihLIu*wbh_|tC%69hLPP?AUWW6*~jSI%8jS%o(^*%VJ9DAJ~pOd8Hhfh{d5-VE57G>TNwk z$QAWztW@250Ra{tEyWFY|Vy9&VS+1n&EMMT#vsvraU0#nC7Yzm+%AG-#(M~&+ zt(w-g70I?Sx!kQ~S?PQe7zRw!llU;$K6Hng`lPE`lowPM;D>bx0IlxXbxYE-)%*Y5 zs+-G7_*Yb~x?o2(TvL79vm zZ!f7z$Xyh|0d~WD_&MJptrSr?x(hZythLep^b&Tg42&R0&O!bMvzfzScO6e<;O5Ei z+kg6arbKA}i6h)coHZ-UPfQ0tDs9pZ@k+4aIkIwsgv!2q*1w@D6d89K&5q4hEG=PK zmAy?5i86x+G|z$-3gdLi0>7y^Udmvsku;aP2q?jWziy9P^^E%QfY*Bw1`?N?9ckdy z_y36c5^yT;HSU{A$xu@_W~`Y?x3aWYvo%^MR8t{ar>3mOa!?K-MVJ{`N>SFSw2@^T z$I`*+Ft&s!WT#_k#IaPzetf^b`M&3Sp8IrfQ>nSV=l#F$@BJ;Di@sw}|6?hK=dQ7o z;XF?*3C0y=SkA#tv&aZJAT&fz1HegKfS{HDDZQG~CZ`+nk9V=1v(yaH-WJCcA|_Nt z*IF76b!h4$Sc)!gy9JVM=yL!MHR{m=uhehwFFeb*fqM%Z$T;KFK~joN9-z%2v8!#~ z-yk{&v0#rE>Ykjo6eHSy$g#-A0BYD~AGA@j^neY+CR{OtvW7X*I5Y6qiH8uZGnk%} zlQv#UqQW8ey7BCjz`NP)k_L6)B;ry>HeL_WPPXVb1kP(Bdbv@f8loLgba5DjN{n?D zQ({o4REs2OoiMi`Y!7Gz4+~tLw4%!4H6^(4O%~vVbj4fVi<(q+n1n8SY^?<8(2g@{@xb2e$JPt`i%odfSV?m+p z0%ZXNFn;>*g7#BW1v-wpyNT3m(ztNY9w5R*VBZ9!zJmPtqp)FK%1cIku#v=9c&x$0 z3RDVY;#>(O&J=QIf+b@|w(q`f)A$%aC}=6T>F03(fI8%<@a;pW(|GaxwWo+KJgbgM z#5L$3$mQGh)ngR=i7T5jELt)$;zhq;<$&a?x!dSE%=Pgmvfxh!N8DEk-fS_t51So` z64)}Z5D+bikw3csG7k+6EAXWF1}|McN~%=?nwNQ?NQSyz;)N$=yu`V2FOL~F`^l}u z;3xG3(?GAHW`c=zR`InyTNU6)=*!i1H+R#Var>E|qF%@Ks;=9r)*JGSJ&FD>z@PTA zNm3ZUCC)US7qMAO5)25xso1L3Hp5#0h}RvCe{W7aB~dIC!2sWf&C2W83_^|pNM<$c zK9HqV`|JU{kh_Ic9T+-9FeBha7>ov*dYA5FkyCeC)sk^34$B*Y%1E{YJk2pX5-|?+ z2>nZvRj`8w-*lKO9A?0tj6B0rgn}bUjCa8A1{lbm?*QxO{FRFP#rI2o1(J9iq(y^n z_zwU8!U{wXoJBBqz>K5TNgquF^}S)eTGPKUH}UM+5=)ZAolqxFwMFM9{Iim ztVbw(bUW;_y__}be~(^-M~?1=UlscADp0>i>`W7m*$Hq;sRc7<;_nokX9j)?&1!5U zY)GmHAW6_ANnmBT#WFid4*_XFD% zUATRWOC2t?U3C_)WH=1aY<>S5c?l_?o@b zE5m^W*bn^v240a<`uCvWf?P(8+~#W(t!xSJ@}t};6}9Akh-ktKWWdX?B)qfQ(C!}l z$%bi)AYvri0fAsf5Nv6HnJa2AO5AR7wU#)#_TrOwMA*`yN)~RE8A{GMJwX*5UgB2; z15@@5b%cO6I(}1{+DJJ?Rjw3^f1gObq5ks-drtLJ*g{&>GzDBCZjZc3@^x&aSQrF& zoq?n;4TR+G$5_)0sD-pR7c+Q9AepPP#HEfHLy~tA$4J0RCod#wP)MG`7btArxzQcI zoUC2M2#5!Cm$7XDd|MELhtYr#))($)5Te{7kowjlp4s3V60RfX7CorU(5UjMcH&z- zN5@3ow+30m2_`v(+cZmap^c3o-PN}L5+;a7_P}}X1)LYX99*4XOTLD@^W@0=9Cn3B zxR@B!2JU!j{JQHwSn!>Nb_;$!kB*XJT6y`G{#5iX0OU*@si$Q6-;TjGvP7z87|y4> zblqEJlk1p0?nnM4g$Dy^zsrZwRf|bYiypa20yl8*o{|CtLP+CSS&;Zi5O656KXv_P z4aOtfQyaFF&me0A$^v*yo*g>@L|C5QZ5@s}U}fTpZRz)26E5Y@*^=0I>xn7_;6HYwmGN3e!QCpANJ}2y zj=}>HF4w7o^AWsZNEB%HCjC1EEs87EB{1O%#`MFU023k?5RkJ6iRe)3F_CI* z$6LFE91ay}#(Z%Lf|hHkau$7D-ACi6NJ1jFjw$yIjgDuCn0b;Kfma*9)g!)v1tB5fp~0ZE1j~wlY|u%MMRe;&r->?T2?NE= z@(u8L-03e6B?Cm;MI>h&i#`mfkt7e6WG(lNcV_|SAmqR`AymuB>u*w0&NJd?l9BKZ z?I6nWx5%9cj+y@NLRFlg^{?*-nvK>wO%6YRYZ{o4m@40vw4<9M1qqhoYC1Kz9+qrZ zD`Sz!5d#;P;e$J_0wY}ss0@e@)oXwFZB#O`yadcNYp&%Mm9f=dl82&Ipa!%<53BwHVgI>4e_CO#kb853o1wpFTIE>7 zMb!~HqKgvl(HIGjP01|>v0}f8v8_#LN6dyc(JxF9R+TW3enpK}KyyQl zUWVB2b!@o!`eYQBR&R}Or#K$e#9|DFnPi(K)|Q1%r780|vSnNC4PA_Og!40OAnV}t zGmKo>_;L2U>Y~r=HORj9=gyE^%wd80SGw6%z0~&%0t=D5N}lR?38=VO zfyn&^)epYV20tD-ZjUZWt6})JfZRoUxak8)9Q+~&^L>WHudQGFNGwAS4_XIyG^pjc zC_{9+bSWH&A1Aa8wAqNpmw?tkbk+QoewL8J;kXC+7Bc7WgIJ4~wdTlQFUoKT2brhH zKBd3I!o#}@OmU*RCXA3l5t89^@>>*A@CXRM9a9PTvVli^38HIP)R24?;kg;gjT#D78Hk4nZmJl z@G?E}pc_B&Z(<36d-SwFGQfL2PF>Xlo0XUVc^Ayo|1GX`&$HlHIoLJ(D2yb?9f3Bs z0j8$kLFKP?5&`ofwahZYvXLnKa` z{|ym-DAd<_eKGI*Od3q`xN&Q0Xysil9Q0L87?d55im)8*H?l4U#vUwSzAC z?{046eJZVQU1WaS*v13320WL|; zy93_k1=MUJ0G>LSv=CEE5ZBW*)oDG1MDfTRM|V)d2Sv!gg9AuzFc2ndIlh4|jgUm@ zm?x>Y=WG{EV0Ch^>(naaG|(;?!?g*L>2GW#%x}XMxTbu9D}}Z`w1oZlu6n_8TRiU` ziQKgN(+VV7yuoT&zbv5iQFrGeqDu1f=~6V!<&t8pA{n*FmpQVs78{+XY}f zP_M`o!Ul5or1}s(59Vld9q`hl78i;uS7y5fNc8H|Mq1#4^CK*GDzbFF`mm1Zg5v|{ zTsb(Kih;$rYR&%3(8d@=S!XfJc$4@!71=U$rsn{cRgx~~R8dlBfYIJM7L@*Ow*H&8 zlMbc)YP_w=a$-U9#PuKqjuXqf&8hFR)r z6xqiUUn!2F+)r4$al!Hb6D&#CMkCb*qoxo3Y7dX9PxFJ?-%w4In!C|t=iujujtD1$ z8@OwKA!H3=vW9J?cxh3w%AEzZF%-%Lm_&XFf@i@XG68Fril|G2zDq_oAnG_{ zLg@we&@{0rK!G~IaXMv#Oxry$DR9;FL%%-EAk;OO{`eD&QIr7SfM*~nt3{}2qlTKV zEo_Jm;z)QHz>NrWIWWK|1C;~e4Vp_30glsPfWTTJ1@|VRU0a$cqV2z_dOPo)6Q0un zRk<^VB`)SNHuo2%d@9rkzadL=(rJyML@YtL|IJ`sSw9NN0EDQ}?;!w;T0~x20>6Af zU?)gmcHw8iLqvrEtU(SpYx{VH^IjNpc7tjMqNfy5vD9 zqx*>iTQitLWx_-hovr>RxV89-vDLVZxJ2y@mnS7b?8 z{~&qT46NR~O`E7y67j3uvf_C%{9YCMGJp7$(%3rYUmtf$G&h_Fds6ffZ3B*+-P-lz zTfrTFzX=}*TW1|O^eWJ(gol;m7u@$=SrC|I3<9z{N1gn>xIc%!Q5M zJg7^VSrLE8tB)7DUc9#q2$UEUQ#686xkQlMoQ_T6&eBK14VUe{Nm052*ytv($CrGO zp1>P*cpXPMNnLyc9NOP1&^*3J>AvOKV6*Lvth4j$!SV&8;x%iL$hJx7$dk%w|J$q{ za=-H?iJtdxadA1jVA~BgSP@iPhvEK+X*FR{BntodNWOVnpdE1@5+$J}h?U5dzR`-w z;$iJ5L8GP=NhT7+XQa4zXLI4(V}|6!#zA&hBHUA>|2;UVD?&ffmMa*k(r_&W6*y6< zX$qMq2wB2u9tf*Cx+eG+f4jG$7?Bah$IaXW-h6B@e_>a-q*cQ`pdW`fTtJCxt&tT| zuUAZSg^G`ui<5j-;KoRjgPE;O&c~WzlAZb2GLp0oVU-u?u*28Bl$ z!~)9s6g}d{Lnu7^uTk?5TSy8TFQQ*p_@`>|$sb9f-ohdR#UHo{kVE0P3{$?dUGU$D znz~AYLUGp?f^oAqkq%}YAVyH}S9QVC!CZ-1ci$c?ID~o#kfkr^qB9OOXiSi5!8-`3 zph)#To-MS~bcuBvAd!9`r&G2(6PZzR+MXFDRZ+%v)DtOZS1<=}PhHn`>9u$Xy`Zn* zXTX+2QHVq)7AwqWcG95>h2u7sD+^ceycQqZ)C6bK6GiPaxC+_&DnC1}B5B=6quOoD z&suIM1JUaPIq#SaCC`po-{ALg+-yH}u0Tyv93gOZz`Gr~(3Slhk2e&53w7DNX#0t= zXS%N=6f5UWU0eRgY4_114vR=iJ)i~b|gm?2?UaY}TqkaR(k z*!jr3Jcya76Bl$+8eFkCgXiQT8JapCwkYzf#kCU4^9Tt&7*r-JGwv;@2a@0c&e^b8 z#;rNDKNRhRWQH1K|e9%kLU|Kti){C%HxM8qsyNq+_X#~OT$AW=B_ z4L_)Mz+pQt1@-A=YWRi!03s|{pe;#6VYmasDKDfNgZa~nlsfzv#!#opQBhL z00D<*jO1;QXD9a)`}*b}#22Sy+Zl3M-+Eot1yS!1xQ_X*%g@q{0el2k7hpQK)qrDm zl&H|c<&0O`_!@FLPxf8TQcGgeY_6rWzYtU5)}BcDxlCf5yywIgANWu5D_fqBHTMV= zE73&v?7ah4NL`Td{{xXVxMR;{$L>%o)nC_Dx4|5}&pdzz!HQ}$bE2JcasA>~iv3TZ zl?fiBFaBb;P#Hg7xmU}}waU^#e_e~YRUjer=87O_(KG{+0fVn21x8`dL-}-9K{}cB z;HHQ>5I2v_z-A2(F}(bsmg^F_c3KZ{R!arf>x;ag+9h6)_Mrz0IDpTE7YvAR0GksZ z)eR(ryMy#oAm+$wa!9MfIf+;iA?|oL*bi7;{&qnoBGSt)(3TusO2E)uf={9Ahv=+x z{N7NJ<2Qm4@j#HM)rB$dzj-;JbWnRTaxbnYFcc3CS6G`Mzh?L^bYL4_NP~y3;PI!P zH^eOizbDBc6;*y9wl-9XV(izkmqZl95=nW*T_KqeTNykiuVzg1xi9e}XS+N&?o z|3-9*Q?Elj(~gq}PBu2>**>!5G6-2BoO+KQ4~19r7;&ZoksQp5X+A-R{5GGZQ;U4$ zkN(Ilj^Q-|9LcTnk2D0rb8U>| zD@Xz_@=Ie@Mg8C7^UaIS>V=dx@iA2yiDrlXm7`@qvzg^d#FA&+=0p)*=83Km*0t6I zlb=`Q;lHoz6^jgTlg4C_-g#SyZz$*l`1rGR*2Y)#Em*j|B<;0~d!Qb}KFqDiW?+fN z4X>?Tz%{1sQw3d|*W$VqY{OAVciUUU{I&}n&tNoY7FWAOtplga>XNf_o2Eykxq12L z*qN!ar!&Xp-GkK<7|g{y2B?q(urvS{BLbIe2o{z^FECbd_D29G5s+$cS9=ovjpTkv zn4%s>*ib7FSq+Xj2fO`EgNig4yCaE)U=Elg=FmVw2uENJ89oDTHOZZ_XQ__$#>VfF zmPV#gcv}+CkpTcd8oog!pK);z{TD7Rs9pTC()!==GZ&sHjgtP`_5V$zm8$MVb|Fq4 z{2vm=hr|+rE?#p2`GXn~Py~kUjJeOs8%q5@ds|@cA>rKg{gq4y=B_# z$87CoGu6$te~H63WS34YQi`A~!Rmp({(t|k2g2dY{1D1RG|gH1l_KI$PqKZ>LpL`l z$mxJ(2xg;!3=2y&lq{Gxx1gm-5VC^Tej1K}bZ+t9DwTO;b`WXT^yJttj=kjFUe;L% zcP0>Wbh@VVh&l^wL$BqTL{2rfndtM2iT1kZt<5C+U;^JB6VH&!sKf@^QI^s2hc_^-0+f7!6LML6EdXbP=at6B~ z0)vW8MM=EpC^uSFLOA3_rCsGf=cn32zBsqTQl{9GYAMHQk-&GVR)ULmqNq$r82Gr| zHsydd-*a#4dZGA{B|kwu5qe+tal*CuDZI^-f;D5$nx@C%-#dfuGaDU0C1v%Txllo` zvUFrU6nr+ODk}kQ{N-_?vg)%Lhd;Nx4}83l-A36a+Ymism#}xZ(bc?c2mKFt9l%h*%dEQ#QP?+P?*?Qw@G*eaAgbOQr8Y9q28jS(nunT} zOv%6ro-BsOYJnMyrceAjNa`6brsM<)W5N~+$yz33gVJIswvu^2kQ+hAhAY^ZN_jEz zh;TJ7n*xIs)WC>MTA+XZ04>u>Xz_GW4e@d?hp3U$y9HN9u&C++1>a;|<6!)WXOp zcj@8^F}UVR+4lD7A~J>sXJt_uqefhh=~;Lnh0`KUE6jgsCmp#hKco1@3jTf*>%z%q zj)%|?NQf!QF09&D3EkSGAG>P{u@gmRuxu*Ai@iIlN}sIjB6DRzf-27~&`iR`iE+X&X=BIE{`QS&O<5*sM^irtF55o&XTwbE zvWt%n#|04?gY@%|a;6suMfXiWD@1i!RA{d zQ?vv|=r=W7jnqkp9|kyu#~`&TY<_*i+yS~8J|P$(@aRv&CD?IcU9+0iUMB3^7DHn? z6_q~SLu4tu5Mq%)Pifpe&3A<*K{n$d`B(sO!iUP9aNv>D*aLHP?0D7g?}8fb6Ij4w zBqe@CNC(J>^jI*oM2+7|9nP`~w?1BfGX=@jlRpj}hJzw3>OK?Bbd`UJMVQMNJsXS) zABF03SLvVe$GWCW^u94&}3_5bh?&! z5);lc+JJ(vci;@7U5;1}AkKgrlQAr+-D}UP$|imetIcy??OVVhU!33k#|dQ8#e^v`FVm3?90n9`}GoZj7D$RAhKj1paC^GJo! zQSnkUYRp3ho$!oKO1Dzwm(-m7-L)_Hc8;X%toqsdkslj83#+Vd zvO+wB_)AT+TZ=#OCez||bNx-(1`ioOm$CZ3dU_P;xK(o2AX76o2d!KO{-~PcgqXQ_uwv;{L?X7y%AbYP$kntS5(Y|mNF*(m%}jt=0)n3w zQw$9)#2Wnt`L5)YHMr{_aV#EM%m_n0v6!)&%dJQUbj=InLA`?##yha|)2K)z!$bia zfAY;z1GR0AIg&jN2O0lDGrD=(0#W9IYJ%189R+O~iI0SySBCIip#8Hfl<5M{2m-aE zzizm23HNKF11L@f1!8O|-1s~0(gH03i$^L8{t+Z~3n4LLK5(eFh9L>`{m|wYAsLBG z07IK$=Im_u=XO22p-~Kr|Gm}+2H7$wmH`D$qR|2w9CBe*>&K{FE5d949V!v}`~Rk1 zKd}5CyXpSD#2LJt{5(AN7#VdT%f2niKY(HHdZwYjLRC)qN~Y({@Rfx$sr|>#!yvE8 zdfm&G2g}K<2;_z(9opRK<{6uCdhTaY6>haoQlGdU z?Ci};imhI}eB&X(pQxwVF60%>X*aZ8E~-~j+ED6~;qR;`L7&p*oay$K5KTnY#Sbc{ zx1H6h^yK82Tov)~kf8c&IEr?PtUVTO+F#xM~Cm8G{kBNQDp5VntNnz>(@NqWqhB!^VuV7@3j4NYE|vDzG>9V|Mq1}@4V0X z>6b_830{<=7BjECwe%^nwwl5*%^Q2VR*-IcKF}=t`9o3>IS`Zu-nDECD6NlJ>o!-^5g_raV>oTo|P@@y<*u=7g>mA`}IYyUWL zGa_a$R`V~U=l(KTcgVuE)M~-*n>-LFQg?Y^WiXh0ANE4_B2`_Zv>wJq7%uicY`C<3 zZl6*cZd5HUYNTktouUMzf>S;gW#~{)Wf{41CgjAlfr4z57T3Pr7?WW&ENajvMrxm! zvx7kYqRkRhvq3PNRhR5DFs1Cx1D4OYu|&a}5eiY^hyMKB$VLHjN@^s(5>{h98hxMTpAys45HwETzrrZLY$9b4LJY; zjmqTOG^I_dZk7@d`-3%MOD-|8JYBD`6It_KV;DKttRrEDeY9-QzyQr?!APMb4iq`YZm7%@Hg{ z!L^yATvoMC^d_FD3U3mhjaXK-imU4~?LGH)+~JtBf}baCMDG;TDf$GUKhjs#B+0Ax z&IIAVHy(AXVLy5*#xbAh!9NNJlzi_Ta2d82*n*zT>_IclW5_=ZJY@Oa5^(1nrdKJ9 znYax-XYwzR_9+isUaI~#7p(n_Vqkn=jcOv}TzdmK5q(>RB^*NoX4v|OxlE-t$h=5x zE@^hkNV8n}-)~!h^-vY@1u-DUx$G$2cZh$5*7ZI@;}XU3&|=-S>tCMvQ?IsFjrfN!Z|d#ee8V7CHHyZSYr5j1ThH2HFu1-QEW!cEG!{W zwdX^HS0cm3{@EU7_vO;xH9eDTkrZ2*J-wvaefDGoRV=)Q8|> z0*Ho^3{*!1xFPmz1jtpzJ@CG%s5%-uDVLGaczS9cdnpSEEiv>xKTxNxGt& zvv-$md#w^*#DS5-Pj2Dcowx72up*}*O1D^KM3&4_ZvG6KVe0xKF_P3 zrpQyd=`bKTwIYEmQSBE4CCAV8I8x`*2Ua-;(M3l_gXmP;f8-CLN*$@nUF(`j-4bh+ z2n`=}wkh-S)9rKn6dvUzJkM)B9BXmODgXu-(5DfOFm(})5B|HUm@3mW$Ku->v0VW+ z?ZI#?#`#Gg1$*k*NW~Wb$Xi@?GTQ9!&Ejg`hJqx!*vKdbhsB42;S9azQ?jkKb1X_1 zX{7iKuyipKwX7IL_5&+(Ur+RP4*vP z1EyB(n0QI~1F^y$=Yg4nuvG$xqaI{gy(jTa*;|CeLF$*Sf{nc4qKd|T!!j9%K96#! zpnxKhl^bqPzC`7)!^d_+*p-&=M^!ZnA#AE$#unWPP8H#sf|2V0nR9$)a`)VFUA`Z$HK{ExMLV@T zq=n(Uu46L1%Ok33dQ>&4X*O9q>(dr>U`|eJzppNiMYX=gQmD)h{Y#ncO@11c!*CY^A8gC5pG@qD=oS50`ib#{K z3l)}A)(5VNIDSJz{XMz|4bJ8D^YrMr3zH67UgryUFixx&@P5zO2Llz9=A!6g`}8!d zh3(_w-!}%)- zR~3&|>N%qSx{q(UmSIA7+n}Sy4#q);>_)<3EXI)}`K`Om0}sbnnFsiYEmVH@WDWLq z{H6UeDfK#o>^OOhE~M5T`u2k+{(il2Syx0;9hnKjW)%?j{Gk*^%|@IrFXW-~e%ttl z@o;*0W*6$K7Y7FetdBFD<14^GNk`lsb3w@i| zFOR?duy+S8r$?gsj4o$L*ok6@B&qBrV}pEbV0`WHr7DT{ zJ2@7O`O|b?D>V~oFhYJlFDIdtHt9HfF7D-l^AVw|DMyV`uqllJyad4l@tmn}JbS#^ z9H1vOuf7A>Nu!s&4wo8>_ea`7R=7;tWk}~$98A!DSeJ{XT%2#aEnd#vg*_(wg}l(V zJjo%Pq$6#ZcKzgr=v~}AFqBe8TpzJ40RktM<5XOBD9KgPDndg(>(n-2B4s`^`MKQY?cYMUy(yyWiMqLKAIAw_q&_kLcX;mM`hwzr#z1=BA$ zEAhQk2a@I)Hy!CK?JBs_5lfos+S?(e&9v+AE78Tp{g3xO$SiTjl9 zpA<;r#n<$loW*nh5GN(NQ2`B)Jc_-*D99@M9RsEL!`{syW4-C89KW#`v(uwWjxurwKc0S=?+XZo1M0FoL7y?n*C!ew@Jn)R;SR4>@T#QJRIR&N5xJZO8I;w zyGP*#+|(Z@?o(tpdU*;|UhjlGQ`RZR+TG2j&vaYq)ZrcX?d=xRbEO~Fq1PXI@jf6? z&;kntlxZHLv%k)2RonJ=xsC^0XH^*w1)sJqf}9e8n#M+imHq*{Z1H{RYnTz|x};C( zkxdKs1Na=>Tcm23w;|eMN+I1T476vM%E2|ECP`6g$%l2xvN-QU7w)DP7S>;3)l6@M z=c5qvu!$PwdoZqVUx9Oza{I@c&m-4me-tf7jyj%DE>NON7hwtt2grJabO97iCmtm* zKZ`JKCOR$^B^FB~qZrA;y0A7oDP(PQ?QI1o3)G6jf~ehv;vm%8LcAReB2VZ{=Zea; z2!#DiF3t_^y8fGVVj8r|a7knp!*xGf8EzdKrY z5ktf zI8*QY-}J6U;{`HBo=?g5Wp!rR(GO9#oJm3FeN!^Nnl9t>27kwj<(huVK@3EsF5^3G zla6kZsLh8NbD65SO|$nXFctiY8)x8MAJYsp!r`^pv)~&8^L;_<;=@G{J{4fF4rks` zF-N$jQ#u>B7m5U}Jf*XP9enWhA5V;yhQ|IL^moh^PVAz*KZnPjKWqRx8od;Qw$NJb z{@G;M%VS}3ZU>rWgZIJaB-LC_>Fek043I(=GwwTzj*yGyV(4P9Rqo8i`ganvTuz8s zXF%yAW0yz;RyOe5-B1lfR;&ofYgCaXS#n{l`{5~@BBFZC7R zB&$h+jFA!FQ66CvU;ZVP3Afyv*VwB)Z|<#%7u{V*_lMfL^#~v#I1Z343GD4hbTGW_ zc;Dzm-{Oty3^(NBDt}MV%)c<#BDJePbWS12UADd2yKR|n%*$4M!}_3Qa#o9(kp#h@ z0%)~Gw3k!M%5IU!2BU~FA?#lS1^_Gtcz?Xk;?^s~#Ufxc<&s;#kY5^qd|S-1OZF`i zlzRnHz*V;?oai0W81CAUmK_nTI^a4zn`im^MaNc)!86XyY2p`1D`w+9!Q$}2Z- ze7!wSYg9?i%fY9=BhetUPDHJ~OWW-3f!?ex&gAqQrPFzjj_}3HC+2qC|7G%*LnlK@ z@k5>Rhgc{Vu?;)i0`Ge7*uiE!bo55qjPW4J<&-ukV)Ga`KbN`S?s^NyP{97D4xv&{ zIcI%_|0%^W7UwB)mo(8JWHw48pqzO)Wk}CsjGP*NQ96TlJ8V>awutx&w3r4Tpl`H# zw)TFfakz}UdlX!+sf%qcR=7W~)s9pD2oe+~3lXeb!h}$!-JQIQQSBl{+a5!59o|4#gz|75C z-`%Y;wmEu>3)pDLnCVrxh?R#0iynwzqP3B1_{_w*sJ_+M=0pOgOafXNT$C_4C`AU| z$}ad-=GHTdjAABs`jwv9I=F=5qY_Ggbs}0XWajS2-losR#om|@Mh*Q`3i4xd1=3i@ zl{WAGxz%r#t<9?@^M{cTK zw}~E~enpAVdK+NWa!q9{P8F)!f{C6sx?K0l(KKM9-tmK-Pu4u4IlK2}VfutKZu<`O z&$SPJlE3&{px9P5@;z)O0Y33l+Iw~W$n46ad{{3a#JE%Ft7~4goxH#b<=t0PShQJ>1vEF$cwiE;5~Iv9ZR}%V3N|* z8H~|jAZwWSV9BTBqG`{^RToWsq!0hvU;_GxP0VOkk$=KPnVT5khKefy#ol}|J#kJL z+z?W@WAnZq)mv(JjPbT$f&rGX71O%&9{qQlKb7vw7zRV8(Lra{ z@jn6evO3=1c^5!=#KW8q!i_LUEV)fEXauN0uBw=DLiPt1F$REs1&L0(Q_2xX7)Xw~ zVvdL6hT}}118siRB&8!<6BlQiS6VBK1wdUMXm7*t$dpemKwKWhK24J*Pllc7px*eY zOGw!i>#_{G91?W-G2a@L3Bkt!DRX2-FKWgcP!rl5&EA<&7HQ>uM56b|8yvrdFpU9 z-zihjF14j8Kl<~5!QFRDFO8j zF7Uyh`fU`2{D2@EwV*R?3v;#2HE=-1d^g04 z7J<8mOB*h1LQD~-{kHup2Ffur^&`Az70w<O9S~jW@U!03;0-lDS9_n zD5rzrQpx2Mh?W$JgU(>Qb}rfgP&GKNvlgY^VN|Hx2|rNxRxk9$xkx0q4sQmov0EAU zqVpw$p%WIYbu(DDTJ#wGgVxxi zNOQ)$j&F>=^`)&eNceW58aw1jz7fGe^l<{{;Uloa;5lHsX(6jz4(uQVgTEK6S@q@V zhn{5apQe(rJn*hX5K(RIWhU-Zc#(%+3pF8wxd4l1OEDPn;5yeBm<*_55v#6U*oR7# z@!U(*=gdVOG>8Tn_c6?1uJI{-(sWPlzU+cKaL1KC(w9cmcCd4cl5cO_6@;=5@_anO z$B_t`1xWAU-hk}ww!TImv=X<4?QuK z6ejz0`-j10T7tLFn-Apmcc`s;byLnP#ONDiaC^Iym#ftB(c8Q0J1v&&8g5eH$Sddf zcSLSHP`brN%{bgC-Qt+~&rBF^WUZ4W;9L{|IO*Q2gY7(;DR^KaK$AM<98@2rv? zwUwBtilNivvOeOLimrbmv{0mX@O7Fkot8x!?~r_A*@3YEQ()yyTZUgG^WzWj+007&xi>Q@OQ~XRS%R^wJF(#41B@ zS88+SM=fyy@lvP9$ks9uUSPdHJnm(2Awi|9C%U1}3$X6hsR5q?ztrMZ8jNq01HkA{ zu8cptj%#D5a9+-v`6U@PVc`BEx79XAfm*6fu8pstWcsDa{Ye^W%b^SK9$?z?q1{Fs^ zx5^)t{ZYo7=x{BF8VrILE2#*W%@3Q{NVv0lMxDKD0EcI2f4+ ziJR81K~EH{c|zY<9@Qj}xu2YX>`Sl}(dTKnxAqVyZd#3DZ`+*wf?Wg(_ffSwPJ#rl zlT2Tw=t#6vz^Wb~GQ^Z8Xn1V# zP^^}XzL!UDIu;7v=pOxuxk%Md#`yu2n&a(`;>m#Xsw~~3(go6{pPU`Ewk}-%qIGFt zS9`g5GAp>)xPn9^nrs3@p)zNnaK0zi$^&*^eaUcN1WkL7xy2VOi&P5CKC3B@ATotV3Ginu zs9vz6rNY5j2h}{$-F*3RtDon`)~hQaD!IZ!s%sV4u^Y?AwyffF8%P3{-H41T`FxmT zYc>MXa={Z$juJR7){$g{)MRP4T$zltZ*MM7FQjN>7dWsI`(c-M)(Bq*oVT>{%uOm@ zy6#3HfH%i1VYx$$0brO0OTYeAVE#HG%?lB8plQIZ02We5exoBs4iPqRk(NYAQ;8q+ zhLzb{eEEoOJ>6foaJqW_p8Mz7>3=|SG0aV`6*o)yPn^rnJFny&!xaTGiRwS>!d*kw z?jDfjnZUzh-_#EHSc-jE-{1{KV_+OGSvXSoXR7k@3XJ;O_RN50-GQ4JZWpSHUeuS5 zQ$bQ}g=XeSi)%EBc!{nEvV-9F3>|VRi&SNVE;Pg8tnQGv1&y%LbjToG-{Q{#!izB? z8LXfOg=&Oe%qjZnYr%ZF(C; zvF)j%(>vMnV3cjrJ=(#D!<~utE}8fAw0xpJdmAZsT#T^y_;lHqho9GRU?4Xy!r|I< zAoir14LUpTV|!nFJ8=g)#Dwm80aJ67cQDQ72ySTp&RUgrRrwkIzC5LuZ7>IW2@cET zgkyddp-xqlpgNa%7mH3sZC{PZKGE-1+mxuDUk1u*k^)^tat(C!aDQOu3L%KqUH5`Y zZ^89T7ZJ{JwoDdK2;b;FdC8SM!PNl(^JtR}oFVp`dB|1}UJju)%Arh1B^@WobcFSE z9!_^4q51G2*y9!x>L6Mqjww*1P~_SRF?`T)@w2s|tb}_6Y#~ItA=-xm`(-N@+mCPQ z+MUk21m_5DKZXNf(zOy61vYuNvJb=L7SjE-_2iBJ5^tADLK`{(;H2@P?~=0Z|7Jb1 zUkzS6uxg3iE{CL!?!(2rzqJ*wO`b1{ZLTdbyp=wQNg+;UK;LhnCE4GlG?|bRx5q-Zu4jmu<6``f0By_dPP)|)FUWn@M{pL5JX)B z?STxC`tML!dqd;lMQWF*1=JX}Ds6HuglGtgSH?b2Ys60Y@8;u%0+z$eeHn9qjNEA? zoQRD*rw%0~Vgyj1eIE5$xX!3{WYisS%tzMnPT2Gbpj-aFGvQ7!dl1-)J1h>?*cV=%`#N3Vo+Nw9bxAyFN7MQB& zW9jZ>?ke&w&#C`|kilaO<8Vxx`d)5g+8TB1m87;DZT9-na+}Pk*m~tP9R8dCCUDN^ zw>_FYWuz$kFvC6|(XimF{!RM1#sw$x>y~4nZTZi&Ifv+f%!>Bz+h{tH)n@&CTy8kC zF2Uv=&`xvwbszIbQAI8Pxf9F+)MH5K2&)i1DE^EU-4o4rqALG^|7y>ES)^Kh0m%hjNdBJ4)f6BLFJESoj`Y@fiSiuz4C5%mfiFi{UbU#MgFP!FO#+ZNSFp= zwZamV!ZqQhQ8;#>hvAky-na(~)((R8eJ4GwPbtT3r3W&?CB=+SA`Ae2&~R}B+`u;v zS_OQ#4NM(VrK+;odscl9mpoJ)>LpzJ9E)UcKd!Dy(b+)baX{XF*) z+A*YpVFv^W2h{Wcg2dqSu&Pua&A4F{d*|%6_%>&Uhp>{q|4JUe*?7C)Kfr0wO{*H+ z`)cmU$D%I14**BUod?r^yhB_=vbI?&2GzY`zvFJs+U4M5?v|s^IjfV?SQFm%I4smc zYU3H99XZZ5Ip-!_r3^B~N^zn$5hduU!>(a8LK z?(_53-~dkabW|Up~E5$xu16j(*`z}9#wjTJ3L?PJe zE71%gD8P&2yY;r#UZE9(?fE8LkOo#+Jy^p zIG%|UxlGZW*BJODRbyuTQn=bxq0(Kp0vjWHB~1NZ8FnkrS?-Cq0$m3~^}51*2oxl9 zFj%auAFHR)_Yl4@q-wP#SN34*n#L4OVv}ucpfE)2M-!B-Ky>k)eb19`gHD5S70g9@ zyO&z}m;+|DHOJ4D(>M0W6W-Ro3?wS?&`u-fqT}0^ipH3oi^Hu|ZkFJ)$p}cZl5J&# z3K@VCay$ow8qm(>(nsDCPiF)>upUnL#%ienN`8U{s>bMCL3oyKfrn`5qK=0aD#a#x z6dq-;gEQuUN8{KCiO>B`9K;_y$}2TcoE|2_vzTfx=RSyVs8FaOff4Ox420FJPux*( zN&mnn=j}OLp1k>yRH{Dk@lM&F99Kk$$%J)U#2&z&u4e9`AN=6b;Wr0uRTuSc6nJ(Ohm6Ku&+*ir7x3$$Hb(wjjn? z2y#!V53e!ZN3SvuGEx*=3tXBTPz%HQgbWr5s282D%5n)haHt&sIBY~XY40r%koR3}+=?hR-a(Xm=vD6%+UljaRld()fCSe!r_)`?yM<1tc}{`lgu+iLR&5rQMR@^ME5iArVr>C zKK;f(F&|9eJeuWL?9Ms8HvhCBKLDH9mX@f*EY$Oz%!!4arv;>>&7*u?|J4<2Xm*Zs z*<$TIo-BUNqgi?TlL=%~OFUpocXw@)$Cb*mCSKTI>pQ;ZP>!L%ZfHnbAewk)TWT#Tt? zf%Ofb*0w9aX557I)eX`oN|++GuaZKtCXpH=TEeuWns+iGasWjb!XNDZ>)1LJ(z-?G zXp;FEUx*j|!VibzP9Pt9LoIWLq{x0C3)i()x#h;(wqRtqG~YUEl`nGDSFK_>$( zWAl*_WH*V5`qjN)-T%2$+BYZv_8WH(YwP1u99?OxabKO3+8avTH@zw9L_3y@Q)waP zgF`H>L9cM!25NJW%#276T|Q0&F8zDY`VfJ`dLW<$=H*6>j)mlYi~uHNJCLr&O}``i zcp(*}iR}+;wKn&w(Q9YdD{b8J4kbr;weRRdxV_-msTC32G}Do__%H;CN%Ad&@cndrNaoboxfoeT z^t*J#MAY-I1u_m5RwqF+F9T+}#lqeFe8mmSQ4Y=hcB&}#|lM^&2478G;5Do{J3It(kpTag$ zqD#NUXn9JR#B10B*-EU#S=*o1n+uZxRUCjuuhQsJ-Kven-a9SziajHH?S4>kb=1b4 zd=2==s*Oy$#Lz_=%Lee>>NEQdJ69;bvO~1kjTK64{Huym)0DX(_T8hNjSdqIV=^Rx z_C!(b3uSJhI*?d~FPP-dvZlx4E@Uud*5e_M zx)rn{;o?=(>f!8#$1kyoIgyGj1?KQg%@nX-;?{pwwoTZUqT8i*GcBT z#Ju1~TZfA?0<8}Om&y41O6F(z`xfNK7;@$%nrTk^kE;mz!_e_WN_*iXd@C?f+SQVz zY)r8#lJpy@jW>MZ86H!ZLo88|Uz1;|4ZfP4N+c*kFh0jO;Icazl4*GzD;}2wf7q#V^w>6zR6( zoa5=i`M@ao2ge9oWY$%XER)erXZ08s&;b0j>j(~`<0QYKHryw7{!1}j5kN65ja3C@!oV0^4z zzu*anZi4JU=CCi=-J>+_td8oI)p3(aL>CM`sJS#ObP`Zh-myCHE&(4j!1n@Z0Huv5 ze16|)sok+?YO_@2Si@OR6O7461M};_JQA!KWF-(FAjD)&A9yO>(~I=4^=lt*4@tkn zv3=5T``%7=ZpPBQBB+rBlC`SFELFMdF3@0nIHGHC)Clm28*GT7KMHdd3_ zhGSk7{4B6YLwd_maqu#4ooCF-8!2MY#9<*gFQM&WhU2Ti5Ytn4-U$~u+cWoOR#X!gIEcXv(; z5_a@!gzlfAY*oCjjTtv1rf&UuXNsBP_4T`NzKeaAZ(QXQmAL%%jBc3ayMB!u;pR@} zQKJc4T3)BNgdT%xqF*EY?*zbQKXSx{?=Y z>wuy`xC7M$MdAkWa51*sE~o0*Yf-9A98iyMQLX=eNC&iH-62mfiow))kdO%rBUo3- z-UN2_C29B7$n=lZq8&LUOk20IMVS7P8K8!^=kvKoSm9D-GW_={H2TW;!OHP%IkW_h zQssn4*-}jNyu|(k?m!MIvSpwxDiGZrBdNViuh<5N#I5Z72coN+{5&6nq1+nb1_wi_ zBHs;d__&_2!2?pL1muG!sP&ds89Z^B5l?ev-K;H|i&VL(fX!8xNt5b@O@aZY6iW&0 zX}GMZg`(3BX}C+i?(^9d4pWc|DnlUQhdpb;>ZY!S8vsn+rZh^mw!(TEtK3646j|YB zi%8}_9`7>$pUwcQFda$E@HC9IAPrkTua}iQbA47(wDI*o=Mxp%!VPcXP}M zbdeVZP5Xb)UiV@!$++M4_}Whg>l<$W(WLwe1LCI&?PQD~c{YFaY+bfqq20@^bED0p z90w!(^g~6#&wu`~YZ_1irVVecooK-I-$~Q$PbTj27~!zPk2#(TWL?uIfL+!pXzm(G z`HO5&mfyOOE4|WL?a7CyOXakDG{N8nUU-M-&kmxqZ4(00C)Y;*V{Uz3B2z4LYi?sQnKKRERzS-yVkbdvwfd8;JJ$uhxE<2;v>+aO%8ds1YG zkyMc+EYSokP44G1uko$fYAI)(y$fxn#*C$qDYE&KBR zq>M`iDjNG)|1QFa!{QH|_hXa#8jQmPKmeZ<_Xas_bj9nMG*&!u`hdZ7KX6_^u&l0d z5avNnf}-1${F5Tn$6UvcWCt%Fivo+BrHpN>5fmJ~3i9^Db{HJ@*7s$E-TT9yd%N5^{|`-P z0#0?_zyF6w2u)3tC27%=tpyR$P*Kr-$gZbk-{UZrqlBlCEk)T%mWnK62^}2r%NnBW z#}=ZptCQXT{+R23UC%YoR2(Ls^ZCA)`+nWRW?i;qh!)-p2hV$q!Z3f>Eo>0l+~|5@ zsjBX1w-CyN>%jwgrAM&4TAjm|K8t3de2#{nqhrT1_l5=e2Nfp*15sprae8aXmlbv= zwJb{DuAqS5+_969M}&?1vE0xuaM#Z6xU4iU>7>6GF6MT{5y;iOvp=Mj8x5v5j`;k; zOntw_=bwAzN=M`=8b1FCS8Jj|(Jy+RX1L zUtev0Gvu%JqiHcxcca6lTd0Vi?-A?TZ`R6F#FzN&#O=IbPRH+&q1~5XPA%;>Yp1J0 zd0;P&OST9rvx6zdf!?@yZ+(^jAYN@*Mw57g+giWIN6NzZ@iWb|n48@$dUK(!C(ag0 zQEJ_5i}-G5`y}cez)0iDs)!-u)<#?OdrIq7$A4Mvd9yuXjN{kL?J%X8nXvtFYZv=o zS(G&J#&)Na4~}QA{+)AdP!v_Fbl}mn}t!iZ{DKrgGQQ= zl>l)+pW*FdQWaGy=b6%!Z;Xe&24oFxPw~xrr1Twzb`)df?Q)Ky*QD1gPF41Yy2cI9 z`Cfy16&;{S-Mcx2w|uU56vPznu;?fMjE275ne2egVbq;(hUvBnr8VM(!rRY1O082@ zvEU&Uh;V1og8r5sC00u#RB6|rOV0a6>OmIJM*NMKzqbDdS&K0gk`VHK36{GJLJjI> z!s((D4>@jQ%QtgA4}uq9B5A22eI4-B2d$aYqq;kSFLeScFkHeo>>lofKe z<2D=7!|umQ;bITu$qEHuEq@X3kbMs>f6MrwRYUG`+G)E;GfYSVKdMNf9vMgv49jZ} z(Fx`LLur>ti^JCgp zK6tS7+}=*~enx$2IQQOzj8vZI3;QlFKTN}?t9NN+>b$&^_OR3?Ze94dlw-dr@`H@$ z4QG}fqE5k0&QYl}jK{%{H9ws^74C~S=Nmt_`}q5)`08e4b8_o{!oKr8G(?rXKgseH zb$3F3)bF0~>m)22WZtccz2A5!p=9y@tbVCe?e{$HQIhF1#ZRf(dFb=Fu@a*2Wb}u* zz+`3So2djW6`OTne=vDPEj(u)SJMQ%aBt4RoXf=Y&!C3b0vuRyI4r0LVfaJCWM3$FH?=9>6TCLhiyx+9d0fNwGv zq($Ig11C&A1{P04qoirOU&5#DiQ5zQx;HXSotT(eI-5+DOC*&VyeMZt%+E8byw~=R zj2)H^I%?fYJ`ai4bO1&ajOwzxBE5YzA@`bEi~~EKO2785av%7t zYyL6vYT^?Ay5$ES1RkbUxfD=Bhn=3}HA81UclL?) z9EEwOP?{cQ(TW+>AUzloJjaL&?!x_=MbW&RY{R+Z64i%2$40c_zYY^Q#_IY9#=EDQk$IeOc z^SW<}w#8+f`F7Y{sNgE^I&Ryt1Vf~qbJ9P7j%_U0&~^p}C2ZHQE#_SS%NWhvjr+}i zo&9A?XL>fYo$5h-VJz5ERe&~*kt2_}-%#>^NYxgm^6as5+n1HM@7YD*oFSbP*Jb&f z@DRyx5>ggEYYfuj9uJLfk)W*vltaIAq^ynYXf)Lpq(+7)mVfY6Wl!w#9Hj#??=UKH zU6y5XBRim->A^DbbuWciVQ8sdaGX#2aT99YUpFImL+xGfFQ=VFv4&-WOkt+6Ab5CKIw|ho(>|r)j zjTtD0dl>7CCV#jJE}45PeH&Heg18~O!{0muwR*a<(b~a*1m(u@OFnxq9V6<+4^7h@ zhUq8o1iNz8xoXaLduzYe-dJ?PJC@UCb!j(s7As{A>zaq@6nQ*99;pVFPwgnbor$he zBQM50`C1(JN3537FG9g{HZJ4&*$){@QdY|k^W5tGbM{h@cjdvnd)Hk5k`_APD7Z+E z-&*B<=uL&CsF!m6DETeW5IP(U>t?)Ub6tbIJT}$U6XTo5=jQJiOtIQd4G}H;u*U|4 zzB8uE4W9@K4wXRTwm%oWJX6LX#BX!iBA(=o8xpalg1_}$R9Xuy0dY$qx@AzdvfsG? z7|tnMq?)!^qY)d<_WNEvbGo038OC}P&1*ElP#ivqkSaE8GLk$8qS6Bp4IHH0Bi-6e z$ROp?OoDz@AbHHfJNq(P$BAqPb1t% z!7V~6`p}Q<#RO37p6GU4eZl-M_37n~g4fVHBHs{i6`_-uV^n!FprG&6z1#_TJM3+L zG}}BY3jLNY(-RM>C*xUt#1}eQvMGpL{|!qM_9L10QR@*5%%JcQp*w>f5ZD-H#sOCl z$>#tOY(7NNiH0>@;F7<$o4Z|JY0??gAi9E@=`o?@fqip6XXBp5t6-t0CN${{s>Ct| z5%;J*sVYGqmLa5tijB$KtE0Ql+|hO7E5TcB|9K*K0)mY`V8g-e<2?73Ghn%g>%u?B;5qvM}6y zt;n$8XCO0Hlk2$^gctH(Yui<0E#F-Xiwo>{zPBvw(eS>n)A6}yb#t|TtoyhHYRWDt z?`)328qt6snWqhJjlNtS7*#o|b0j%t%CU!|6`HaJ&xXaN_@4aRSL{<7_o8F}qB!Mf z(KEzZ|48LYF&Pp=IN|q*=~_DzYox!0sS<+z=1XK3Wv;w!r1LA}U)U><=R9fh@c8Fl z02T+ffPuQOZN?rGP5?{=uW#!r<-{nB4VXprYfOlEAsh;}g#zu`p1#+mH?M9}K|eM{ z#U>j(agfmvBT6iRz%wuMXx#%F=;Zwm^>|&pm8Lh)MS_IES)?R%&a!kdc4J|jt7_Qy zFFlt9aRmm0!w_+-Uw1{L!rmAo@DBL(eodZ%h@*pw`xV5*0^T2p5k&45f?=`oOP;_3 zBJ{xRD;xP=3-K07Vm-(!QGPWzW4qkdP+kIXR$hk%N@sUw<(PYR<2Ga4hBniChqQ%T zs-iM^QO?v+Pechs=@4*8$Hn=3ThpaQc0=83vbfn`34|rU!)V>5YMV^TN5Qi}3)oFu z$`KQ}0gy<*D+-qf;t_I?5Cca1rfXEWusaRhn?ULzNB5vwTNMYgWl}#E{mIHMpSHl( zZVx6wI zhQEqP2Z2=mDwGbFYtb}anxD^$v2?f;#Nk$Bq(imRcB`3M&c2&^VABgH9V&D?j2vuS ze2(AMf&Agg$76r#{?TNT%ee%}S;g($8Hw;Axp?kZ-4;nWe$PrV2LAE!IrbO-jn64| zjj@Y7_jinuly{K#snomN@=dp~c&@hFoRX1yJm$mdy83c@Bn0WNNf+1daQS5*Y6~m( z&@?eql_0VdL{lh6Nt|li?f8Z3iTGPL^QJbLhskGN$y5Xzeg(VcP?)-EwP*Q>+n%Gt z>OCsCvbhJpAB{6=$L^VUIx$kkWLRieX`D~){goq)j_jT`8$UF%7m~ne;5>H%CnZaD zka5$%oH$3-P-C$_7?8XSZ-~Wrc?|WkcTY882Ejl&7D`nQnEYVWGV1^_0{*^cC7&})*)i3;(`zs$Y`fYTk@8@_M1gHE-lqw? zwkc!1w+suh$d3MGUVF7B*TSE#yU8aGK{6}pAUgp?H_O7V4e*(M%fja6fwi!l0&x-r z@eH!J#-(z)^{>~`N8t&51t7@}nAWcmAY)(6c z>zh5z8IWC}s!rJWx=u_@LcfC!veCj%~KYf<**&M))y9rH?iIPHAa;xvaO%M*IMsroPJ){FRez;TDb>Y-sW0M zGdG1as6qgYjUCaXRbtA@8Qd5}f(Zl+)hR1;n{o5J6{Me1c5YS{d=J~WDj z#!~Nqwd@fXsKZ?yz~dV{<~6}aQnbUX{np&}kG@OCZyB<1%V z-5ti)X39*P&7cff%OEu=|1FH#P!)SNoQzyuydbqsQxv^iSHYI<*;b9^>PaIS8Ieq) z44&@Wokd7Ibx_ubAukEWbOlA^8XX?!2)VH`3AU3YY0YrJ0BFu7MZgGxl;lQYEt0#A zDhH#>BR(CH9Adk|d@N=%)qeOB?Ch`YUi!pIy3;Ue6INSAMs2guf!l6@t}_lAZ}2y( z$KsG{K?q4ylrJ}_{Ef9T263}ifT~=l{#<&0sZ`~w*@fk<*s$;4uw_Z7YMfXiVl$d+ z_AxFZH^Ndd&p3h!occeDM@lvMUs7^(tL-)t zhXgi#y&uvp7^b8C74TcIton(%z@J0h{NwLKj{QW>`CXTrNM>9C?)O}wlYpx3pF zj6u-L>CMqj1}{hzDAG)&-%kY}tUC}tx8O0*zQ_A%l%UB~N9ACT3A8I)c0X!RZNR1~ z)WH-wNNJgYFj-N-V`mKuWs<+RC#ptM8(L_N>=2pPu*s|=?9ee3#2W!_bS6UB7V3Q= zDyZEhdg#!I{$&hu!>k8>0TEvw5ZMlZ%*Dn4C>wjQenU71@$j#oLKICh$KWHX>`x*% z=Q7mjYa=(VHE)pwO-7$e^z7rmLUCBJBnATz!RuU}PGW;dZa^!@xm`&=rpSXH9lXHh z(OvN_lSu?YKVAB%_pvC??h4|BIucRYHW1QN;f95{teD;w=XX0$7AnZ*zlz|qMfoC! z^3|cD2uHKTr|^>zFw!>p02Z2zm7N2HXwQr6vZ78Te}Xg!4ZZ9=!0_QO84!Usr<-C4 zq$B0{ZG=CPrfm_NZx(TPT4q%<`c>%LDEz$om-XighZ4PQ2|a2l)+ zo%`#E?m_jvu;HZ!{YdSEoscOujXQmk5C(#qqr+I=S?CGG zJ-3Spb$MiesIb}6asg)^uz*SHtBE^Ae*>*8MfjS?!Y<8pY-0u+>SgLh;P5FolkDz_ zB(9v#FJb)YyjJwkV_Xk+^OJ5iY#XvWT8!+Lvzw~z-+4fz^A$v+?hoG*TasIO<`h4d z>iTm<+RX|CS+O17Bih{QrgJ##b+_X0*?JKIiPKnE{x*YxVTZWJ3pdBFC&RuksAr9) zRcNGJSZ@eATKre#%%cwKJ@Y6?7#x+s5*dWulyeM>5#}(LbI<=L(l?40&Zt2D@I~eY zhNfOz&JgPq&)_F)>`Ar?ZSj3rIP=U@$pL2HcTvb?%f@EHfu!bR%Yi)g-@&f{&>U$9 z#UxI~WPEnmNsNv(_1U4UTX0UCgF@0}^vJZ*^nlqeu4%1XaL#Tc?}I83>hqvUgMy9p zN`cnUNVI0cpq3Zni3J><)L4ih@S4C_w?eM4DB)c2m(F!gsM9p$6A-3=Cqkd5gJ6SM zf_u6z2m-=0^nL;@N1pe<>TRC)B-E&Fc+clH{VLfXcpvcXLEs`MX&D*YB^-Xlj|=e- zgAx&(`Kktbj`iNd@_GZ^06C8>BsW=sbrSq+K8R`Hu16k*>SM+#km1IH3PIz77ADEK z*ywgDSS8Bq5%8lhKKzSQ3?_vwu_G_FxKb1W9gmce+_x{*(mL~76s?IEC`--Y*1zf# zpTSgQyh(vY8SZ5O(S$WGQ!E362l{Dl_=VYpWQB)LEy8eTL#IAV(0*i@O;7;?L!hhl zKl@Prl^K0`WO7U#@*$nDnp?uCaMNs|t%NXgxj>O(UhbW@4>BBB!(Mo^v9_q;NY0LK zjRO-C;>edq!;<2fLq$nAMN5PTb0ccJT{F*mACZ=%aK?1ol5NdZ@fR}5>P%z^3TJY)(dsnU4_J{CA+LhsCOQ^2sPgt zFWl|^IpzEwUDU~!RdD+r|DV$_AJh`BYXr;UVrTKKMjX2R!p-~fFsNX+>t0oIe+xgu zOAw(&Ju(eOu_C7&E#`hWh|P7rl1V34dbBcZyb_fYqP8~Zf{yxUG_9J+jJZ5R)=39y$RhQLRWc(3L@Z6!4z1{P`?mmZ%)6Ooq&oUoY zv1zv@!REFNS;OJw{7{UA7#Ft1?N^7E7@%s8-xJbL&4QW_`43^M(8D+(R)^I&%&&^MsA>xMeE{>0 zHSpHM)PeANQ{>$jYa$T z_-L?|p-ebRoX_x0fSv4P43H!3IQ;QGDNp7OiI)=K;w+jofJs1&g7~*{g;ju{riFs# z%=(8=PvXv1hXxp!zz%qxsV6X9d;Iq23F%K@PKNpDK(7wlGwU)`Z$HH)oy^~lW_Eud znw~2CgGp;IVDD#M3yfgy5;h=Ux5by80@sCnOa%11n3)YQQsWXd?PkAalxZ0USw&uv z(zj1++pc@-*WNe5nYH)DPm7rzc%m#VaJ2?r$Q5&~nXjjB&0DCgnL68XUQKWLor=Z3 zYqWyOsK9k<9nW;xrQUVjh*w#ASFm3BV8{{ok?m?_zb#!&dN8C|*$WAc_xaqQ^MvBXT3E7INc_%@$)aIuZ2@~8TtLF(U2 zyo#4eN=d&@RCqUFkZ%!A{7W8Xv7!@nk2jLmzISt_G2vGS002-3e1h$0sSZrRx#pRdvB3Q-V?0qkw{-hydAJpalxwq9YIaq5qF2}$zp1HGFH*^@y zccA6Bu6eBor#eo2mD8AbYdyR^e?uAZ{YKoQ-!AH^sll2~;cwa@x+%Qk_Abpdw@YWw zBsKp150i+1tpsk#yVyTu;4qJFX22L1^r4xlmj=ZoUcZa$XHjBGI^!fS?7@u|w}KM> z@s0_h<+ibV#s+K{dqU@6i|kI=6D~MZ1jFNlc4!hSE5j`0Gaww1sCp43 z1)zvbuV=Zi#2cPte@(i2;{-h3l0wG2)3hu;eZ2*Fh-k(k9zLN zRAQ{c$E{EWyuNY>h3~fs1AWx3ie^CML@#IJydFG?XMVT7!YWQ0z1-${DhL&6q&C&( zL(8?fx5CO+h1}fuu)!|>Qlm6AV5bpSM!ZMXup@zP_DA_+j4yOk)2!gRjQKkY%H!G> zHenzHpLW=#15>bywoR;=xXXDTvanOp0pINh7=aDnwVhjP&2a^%_u-lB;y5aR#V}4R zPqV}i7khz6m0enr6`Xn^Yx;leYL0b@f3t2Gb|50B+2OCt23n-+lE^g2l#iQdL*BW6p?K?c13nhIW6m1PB^6qKZQnd||Nh-7&e?HP#t z1@rDSAVGM-0*@6p{u7aSqX9iNnLunA%eJ13+`8>1BxLBMIlToh4V_vtwrYh6S)tlU?YrmDHoSdzVgjO^>+*X{GJk)< zTg{)Bkac|>PoL6jFFJy>MzbBkM~gLE{?I!{8>ly6KFTdRa0zTX96-5b3=>9QD$GY2 z0eY6dg3M281|1F`GxH9g6l5vQN7?L!4jq`(O9Wg-@|jDKEQ+^|Z>e0KIJ?Xz!J_dDF!V}H!D>WUyscbWab!n2zqT5hvhrsyPx727Y?{7wOzo0pTK0!Xqu857ZSY>` z$C3Ptf6u$b0=wX{#fLww+`ro4+}`ZF&t6?L+?;*a@Tmd51U3?w80QrHyj}3KDCs$W z#^r`G*o76Q<_;M@XvjGw+_d$gel8HN_N6c2O-ucSbt{xGbg}A9S;44tpQ{U1x}ml7%-9L!CL8gyXo-LW%Xtf<%OFERKvLk2WVG$Nz#dIJ|a>6XSlVZ3*s^altp%x zcy@np&`PL*^$nh3l$$ado*0w{EJZ+0V}e-~(?fBfa$FSys~q;V$f!l4J-y@$JoO|U zr%%F>xY=JP%0O2^nd{+TZNMQMLAyxSba@ig*Xi(UW|xhhnw?nxTf_gM=pdVAjB!=H zu%{C)j!0u=5=d9s8Dn^t!mcBpAOTU5s7nAVsfrf%*W^$|mVqsS%z>@5LZ=N>AZvjD znpcrb;PFHrk?iQSU6flg?vjzic?PoV6(fKQRXOmmCmABhR#<821%U>e1>S{N18>jF z@sE01xwA87{g%J#B;6k~LG(w{bpveD7BePEi$vs4#Kbr|+Wt3co1{sE#X<&5b3{Se z33zW<-YPeZ#&sd6d&7nW6KjMo1>&1#=PC4T?eHJG6GgugpOO-y|JvI5b!aAbG z>{8?(DoeQ9m>tG2Q2YQwK_AW_oTRHcSXpd>V=i~dZ;zz7g&t4)eoPTYpy`Q#WeDwm z9vs3C(_W(@euYbxl6yROZCF%o(fW0>%TI)NXWY)q&$Du?!xT))n+8v2ncuRedHR-$ zyi*x@YdMQ@;F%EQncF|V1^-jzY0()?W0o(sTU9Cwi%To&^RJuZ$gN>+EvjO~eQ7o6 z4jCv!suxU&r@CMD9WrR}1@Vq!9FEK+4GX?up0h z4zR8DA1VMJhT#1I<;!?u@lu;>!Jp&g! ze7{w})%-h-Id5DuN6mcL%Zqu07QeQ}w5s7mBjHZatJQ;z5!R*>Rf>XPFGwQkm|sBU zrizOEz;tcm9=L1!u_;>dO!@zFeDrG)!T-i*0zK}jdH8Bh4owDZ4RZm7ovNdrrv ziN_L22+`jd|=kl1|_6IPGyecr6tpQW}dBoigk&Q??B+-c<^=@ijCd1ZG zoeL^ao?$dM%1SA~3XFcspExln4@wa*PSSJYg?^zF*rWsyfBNjc2VxYK69W`e^Lntz zTy3eC7W7}Qp0TmNktzh;uWst)Z5217ywWDnvN;p?nv*ps?hd1%E8LBL2jUlW5wHur zm;>INMe#WvGy4^K1x8^6(S=#TBwYP1Rg2=#*IZ$K#{6ttdSvSP9oasC+=3!57D&;+ zhPN;6!gI+EqqJM{>Roo?(rE96!5K@zHEQAb)#$8Fmd19WD}`1 z8y{iF*4%X?a#**`5;EJ|D|?PcyLJG6UxArj%w7IG_I6<^x%Cj1CZ-p*u%wZhyf*MXch?dS{6HGuTtfAh*Oh3JbEF4hg!U-Qx ziMUkk-dct_F;2y}4Bv^U;27@wZCF=@vSli{XbH%;jW9ttl(W~kMnny)7MxDs9aKM>TM@T`;OH(goy}Q;caJSY6fdGQyeCU};ex}g7oPh-B`KVdMn3o5P^9qnAF$*O z`+=L3MR^aY)|kYr^cXmH+z|4Oq1W!s7++zUMFSe_Mg!_wOY9mzAq`$3J6oFd>zkTX z_rN6+)@7()fY9>?pBg;6m6w)NkcuH67bJ6LX~RbU+qgX~=jC8V2K~vN#x@ZKI4UpT zOUuEdc@N4jSI<^9@(E!%-~^Cs>$Noa9C&^nJ?^7Tdw(z-~+1d$ZA_eYiBm?FB{b1zxxEOx-(@uh%UfbAhx%Em!O!_Gxp~ zh{jQ++Qs*ArMyBB&C<;?ac+oov!dMBeiQ=&mV2GoSBv1Z72Bq!_p(F zvssbs5WeVF+heXEuBq))w12_HPSHC^>~g9A?(hQK-R%2<+QqLX37IGOI+Hk%)o>An zIdqDfegug4=eH29a!~<`%s%T279}b}Yt(R~L0c+7+8}9lyR237r-u4W>*!(V zvx1AbsD>LhK-wag+-jyR+z->4A-Zl3mhl#&5M%$$K?!GQ!boZr{0K8aO zuc{8OcTHMvEUfVv!_b}O*Wry&(#KUj6Q7w0xfcXgWQK*Ve*mh4VeAmnZ&y2qR4~Sj zJ#9911++%=oo^)XmjXcysoce2p`gCdE0w|8Le+39ZrcOow*hQdUPlC31VQpHF#(xx z_Z3`b^dTVg5H&*d)^{+t`<4*~2%jbsZZ?S=Ap&zU+fvP69O4}=;i)DzKFj0V2K#+C zxF86W$=CzdPQS?%QR>XPoJ==Zv1WuFxbDg5S3HdH{@H5E)Y2sybJjta|w0F)bh(o2R=P_~gQBK#c+X<~+Ra1b{cy4o2654&&O8-HO(S zfL$Q_vP%~3JnaV`$)f;X=E=xAGW41mDDDtnR3K6C=Yg|g5FyT{VTN@fX-!48iM!?X znDS@3QdV%*+#KEPk8xDH`&~i4EeG?0e!P@evU}Oo-{}$$aR7oZbG0Z?>gKV746;je z3_M4F5JCRz)alE_gTdXr*2=p8yye^>cu@pLdX(}Yk)11vHW=$WN8)RShq~MA=*7jj zN)wEg8;%|O(D-izbIFTy*p?F=Nwa@uN!c0j5T|@YKF?|6s4c?*HU)%Xer6;jT!A+5 zm$$L;;%vcOjw{X>^U3f+dB4T}ZEFl?NhLs#9uQ5TF<~catANhVJ2F*aySS*}Vf&(G z!8`zwg2)SG2Stp8P1~>#bYD0<2`hr9L{)edTZV?M6WxG!0Zuhv)k2dYIMn)W!?tyQ zlj+Fq~3Ce^DQ4wg!aOP*?+rb<|4!Wms0Bmn;G9F?XS;2;xMDR5`-QtWC7RcC? zDyPa}mn$BgRe9q76*BVCO&F;SKKW0Zw<=v=sB>|=qG-EHNl&85WPY#c_^jbEx5VJ0 zo%$ZO`@S%6fIfPTDb!QKTU@VEbaUqZYPcJBAY|#`Y4hdB7j|?#51kkl0JYo;0Xys< zCDBO7ztZ{MA^7O0V2Mtg;*v&NfTy#5==hf7{>50pl6PfWef%b4ak4EEH;9?u4mq+^S$J4Ss4nCLcE?@Gd!s3axYH#jRb~)vBh+yaDS}U+c&S*l}+7vpwt@~@~`#pS=jv3oqJYO3U=Obt)DrWx@gjXpWx?)`hbxkqW)?>MW8^^^7>ufC#~ZG zUv)MDdDaa$ecoyFX7L-5jKh&}j7%czmQZ?9{a8b z7^KhN4Feibx!N{p3_$lyZ?XC>bTGqIl3y+f)H=d`k(%nzCWw#mC`N)?BA8q_?LA~XqC%lLNAB?#wW>~aX8uz z3ma6!W3k5Y8&<(4v%eprByKxe*w)2RN1wM1(D@Gyf|31W?S6P`)O;HZ(IaMrF}`j{ z0!&wq_kJo_Zew)T96N(nNNLw6Z!DdV7qIlC?UTO3C3gZ-Dm8eS*G6@*{VBOpggA0& zwh%CJ2QAslI|}jW>={2L7&lg`fMh({orO^8A7;!>`}hq_<YiPaZ z>~rV4IQ6>r+bN<~l6;s(J3Vic*eOpaAyyImm_mJgFvdqzSn?T0^Lle|CESEyM#{Pd zi!w8a3hHmo;QIcM#%veIZcRtns8G#_4zvlx3fLl(;3IEjd?k-hn>bo9Z9T?YC*^=I z7wb)u&F*kxcp!i5=pAcbj1Yr-siCg<%_Hcd%1rT49B8bb3hBLtQ9eejCijR1(e_*NOUBr?{LS&yt}T#qa*_*j_q4bvXgyOPqXoSXt~ z8`xq7j9>t;5=-)@#`=7n{*RYhQHROxq&)^+-=e!ujc)~0mb z&hi{{vOXZTb^pZmSzzxjDtN7C$2n@Lly1{8*!JIsArd~?O5@0#r>}r|p1RD9LH}w^ z`lMVkjmV_ByR09w!C6qFn~FrTdAcH{9vNnTN_Oabq0-GqYqjLhcVWkQG~@t%Le`bT z-1Z)1=OzUV_wf{m*k#F*wI0zw|;_<-?)GE{=TLSJEV*(G~}_%&}b6)_RS??JEXA zYVrQ!Es)(*N316c?;b~d(GT_Aut`K;1cLk)UniOw_gb*CkTj(F5FeyzppVY8Wpp9I&a#8G8axtyfE}{Uy$(K)sWIs zZh#P?zT>Fp0t0I8qnjeX-|mxk&g`$1XCh0R)HxWeC>x|xQkHJ9JV5y*a50rZg_Dsx z`ypY0h-(X&v;g0|ETYY#SWr;RC8Ai1Uv-VJEmmcU~4iQ+?(m%|NqJ5wyB z2%fQ8d@T#b!Cvt#y%%?X5t>}3Pio%;0;oE!R9w( zC`mC^eO-3fmOo1r0Nhvd`(AhKz%mR+R?P6YTBzgUQo)O0VqrP!Nv*;rXaEXAql0c9@F$|vIDT66q~j0 z5s7n60<;T;K@J=-!%Ueh3`-3`)p+}v>5(T6UC08YDZaGZYef()kp}JG0xVfEhyq%> zIt_AAh5R4a-WG|v5>rjYTtg0(ZfrYLSv)v9>@MDM^knshX${ecbR-SdO#U9?iA>dF z2F9|ACeAtIzEjZh15x|%g|5B#HRp8bU?iybA*N-Av&>o;N3r^3dgojNwn*s<9zxkP z!F+;lT5mEM^SSd*C4Z@VVkJV}O+1nDvJTl@bg-4tJ^4MtBY~(EhuRSq3^0Lc~AV>{_-bdg?A`0Fv)GPa%7>mL7FWL1VSBy*s0dJoyr_v zm8N5SA4U9maPeskQ-(o+-VyS~MUcX|E&@x6|TVHrDOkI!-JYk`pWp+?l zTDc4R(Q)Ad#SZm00@Q&SgZU;NM{{bD*k^erLes7zQV%mKwEi&flAzzgHpD((T&cnp zKJSm{T_74U(XGmvWzj${O*QZix?oZW%P!Vp*5sm8(;U0!h_IJJY-K^}|3ZbYvD4DR zeFP{b>%D%vsxe!@ctG$=(9gtYx+o+8V+`a0zg}+~f&wt+1}jF;q^n(#vNi`}aorp{ zyPA=dcJ>E>Aian`vc$k%b^+zw&2a<<1@o-mv7BxF0?Ya>X+;>=GcS?94Ey?rS0Dy+ z2LzgO@LADAHc9Gcph~+tj8pk`GreR<{6h~>P)~>oq7Fdt;*Epf59AxE=pO{`3J~so zZ=6yt0RMh`_Q(=EdJ2m>R zV!CDt@-7p5CJ@%{f(Zir22)7Ajv@p+12)VcaC9IfI0-s_UdW%BYly{$aWsF@fUQTn z#mZ9nBH{+2#A3s^2_o^;#V(sGf!+tBxd;EzSXe7m6O#s*bc?8c`rc6F!lugv*Lkt8 zA0`_^{@^M9J5C75EsC#Cr3#ygio^bWpwp~;X|?*R7^}ALE;_vO3_@&VmP6BW zDh%}}7FLK&S+IAIq8us;z*e8;Ua#9V+D}`2oc1@0*p@itT-AMpOhwTh&H_nR{mV_ z61)n4gX%3nlRd99 zWt7G%xv%ClZjCmueRnHM)RPmuE#%azM)Ste6Mz*8l zfOl+X~b9QL+qW0yeViN(5sk-Ob z+hx2*p#1vx8Z2Ua7cOC~ri#pkEjYgH5y*TITD1#Uw1FBa+vc@rpak33pKI~3FBPO~ zKzr5uw#{2^eT!F#27SYz-?+*5G31FLrPoK$3%N|z*Pp#CX{(b<%k9<<42?7^6US9F z&NG1#)qfU7(}6ff`@QskXl>g7P|`uGZi{`uoi_MsNl;@B(W_kWM|-2NKNk8FMKmRL zO_%@8%WbKr-Rb=VaiKaW2+4=3$KN4m4@nG&T=>^oZegqtzX4HdtVk6w=xGS!MPdu2 z2K{^}M@AlB@W0WpiF8xeaR_7^d_Rs+Y;y&u@ej?)lT$&}M>M4w;e{WeQ(+y4JAnPP z01_}Ci}MbQ9lBi}-VaQ)6C#8z%-&CI zWSin!{MyHIlt#Lz8n6K4hg*PY13W=jo+@2SS&cn%!yo~Od+szvx(E@6WJo_C3OsT- zzGBoM<5AJjjH!(gJLJ!A5CTJ{?PLR=2B)EJx8N3RoJjWX1Uz}i8pn`#O!C2nS34cw2o3@8YRy7?;YyolIV^d@(AM_^@sPll8B=*2bBOFXv2Yg#?)zStXnwQTI^K56xbgqv zBnB^hVa3v;;bJuh(C$p1Yj9uELuO7eUop3}6KLQpf(npELPEbMrl_Cxs)-^!K^V;ey5Jc3kBf>Wq4cx5c^W) znn|!}25ps#r;Yf@Ad98~hL?Hdn@1{PNkw>G>5?~1QLO^G0SFTEuoA`zWPIhgg6<|k zEvN_>xrdiJV2(wBz(VG@4tk?h#>EAd>=rh-4eR4DH6Wt`E5}L1nX9KWSkWs1kt#;} zv@z_5aAmyNKOJfmXb8*wNvc%u*iwVeVW*A4O1m0(zPOu%{tN(Ed2)jY`lbT-xe)HU zQ37Fusdsf_061UV+(qAqH9X`i)f0pk)3F0sTb4Hw3D#yjoVEv5DFlS?q%$|rKou#% z*3Hv$MPB=H(>;s*-a+Nb1VcmFn^QzMWKd1pHOA&o!{i`y2vPV_IpjY}R5_3|jh zGkd#A^)YIWg3A{AeNkwgpdKJO!K82{tZ;23{ey^&s8X)xjXR`mR3d>d?OY~LS{$gS zBYy)y<#4lc3dXd)TY zTnI7?9vGv!J_mztYTk8cDItk=O1gU&?6*cP6A>4V$&Cym=fl4KzRZV{>#;8d@LS6J zREl|AEWj9?)(SAZAT8+-+y)QZt+2HRDr{qnFd~zdYbW|^pj$wmgwpOuvu5JfsRvGF zJY;ma+G9lq8RDdb#amCVW+XYUMG{wf*i|;yJIW0$Rnak~b$3|&pIb@ta~IOD_+fGC z0T?YMrJ;}HgF6iX{Yn_GBTT@FbR2~QwfvfeJUxb$jx?~+XK)20ZJiwfxE-+M1F?d7 zGye|QoP_b_E-HMk$`i|X_yCKljsMU@@U%*2=1`ea<{IQ}U9))u7dJY8GB<~RiVuA{ zE{fk}8!?{(ye2dkR8-%=;5Er`Ht6jQ3j< z&RMY5cOgPNAa-ZHZ!?xVBsM7)^CEbr?+SHT?}b8+C##R-G*&@F8b!ki&7$S?c0#Sv z+dz|Eu&L2}JL`wR_(;j@4DI3yM@h6)cC9xW$Cyfx^(D`IObHI74dWq)7hwVR&s z#@%ew3nWxb8pd0?w>FhDKFvee+B zRZgMpK=iG{vO+oI-~Vhy8zfHv7<)Tfbs{ z%TYc6F!?a{LT;D=;3@6*b*k5cJ>@SDS;$Dzq-Q`s+8e?@m;wy5Fp!)cRY!sXNyk2K zrG+l;Ksb=f0M9Bz{E81+9JDD8(R-5bX*)cw+R##8S0Z`%DgYG_R3UePx67|2VxaiY zDO+0Db-7u~5Oh-{d_fgL68WNvH7Gr5FpZj=SpP{XZ;eS(T*9-Osj*%*)EeuItmn{) z<#)1WrU||&R(2eyk>@1R6ADfU66p{{K82uq$G%8GGr1R;#En0FgTYZ+ix8PC*hOFBr{#*ViJ_fOXT$m+20O4P&Sd10xEMzPR;)PduM-k)ON+X|yo73|6VOL~NpIInT zS<%Pvem+Jz2qHfHU&@C+0pLYH(9$brjGR`W>|=EZ9K)y(p(Gfj>-3dp>os?GB$H%? z&e;W{q!GqXSEZZ%tSXg-HA9Ld7Ty)z6pSjh6JyUV!M6<`?3@5F;g)s(IflVJ1=(HV zT3Gape}H|P4+~-e$Ve(iyb<~FfPF|S~ z3nvH&&9LEpK$}j^Y5$d{6*jQFt(p%-%bA49Qj+y z`hKqv4IsFVnqY&!=k3Q|yqc<>)G|z~(3ho2K!JC7X%l>UzT66+r~EKDNOC#`l8LCf zZY_2wpS%OZ;AkEqh!o2AeW{=H|5}x!uAGQ&=~*)FEeBo5c9mW6DQ97A-2@5ptfjAX z*2JfRVlfM&0K!dKQJOamXjYC@jHNF8a_QCb(I=g{OU8(8BubTBi&N<`a#;PN)1Q}M zG(oWa3rVQ~(UXjy(klTh_tK{`O7;hn&Wx6#|Hg6c*tW25qW@X_pZ#fSMtJl-X(&2W zI7i|g_uF^J;7Wb^ZFKYWjho ze*RQGh?kJ3{P9ZsP|k6HG2VO-|0831RkupOMm6#c*i7-EmD-yW>3|sd4-uI76WdD) z{!%Ke9KN55=Xu_6RwcV#9FzoDx#l+mPBkg(e*Z1ps6@)-kF<)NsH^@`%mhF^&Mz+f z&4-ZPDNIjUdb`TKtNai!T%TN&n^T9BEp?pXJ-0ii62oH1b? z2ce~^5Qjw(9RB*peDr{pmGoiWh7`1y%1zC(C!)f_SfuR9Mv^F^-Tr?2ao(R9eZ!VRZ(;& zdt|?@94>Tbe=+Ln&y8+#*+-t4&I}A}MX>gJ#eZ{2a67tcofS)!?RvUu zXf_8r7M8oTOZ>Wvs4LShX-PbQ5_OatFu=V*l9&GDlf82uT!5>I)1n*1|5%r1X`#<52+z(JH*=sFn$nq(`aL+pZ}Mr@Pu z!1ifRj_B}uW2pc#BMlM^r-z4__HaHNxJ{a@-5DA#Z4F@eItaNSk_+zqzYeqY7-r^I z1!E?j_PNJ%EDPA-{4deUP6>vnfj4bA0!x6)0Lls6gV7j?u0HHBtG`{oxHg|3rf6!g zjK`*u&l58G7%9XBybA<4o~(v?F}vDQp$ec7a1wWHCLn?KXp3~lR8zR-+m2Dq`&ORl z`-ME$yY6MPkU(@^u+8T-WScG8!f*2C4D?xFBBODx3!pvZGO-rU*m*wjR$HJa;kevl z!Xb^V?Kc)FRy_$j$P;~>(@-aSctGZd{O>#88@z3V4eBD!7sMSawjez{#Q!bqcLWH{ z&EMy2Jb*wKlI7hXmJfWHrvR~DyCSU#3(=K)c#{|b(LXT6jBcs-ojXiq(<@_GwU6ha z&ym9g8flguvy}1#Iw!oQ`Z%m8S&&t?n!QC#G%f#06&x$-V_1J;#$|b8WduVd1vb>8 z^-+9Ft&S+Eu7_#k{#ozJ5a&1W zlI4OGCQ)|FsB6GZ#ti>+zTOuS0R|K-2|&7W|B;$e>^@Ln0&8C>R#7LpI>zM@d2&Ik z&XrT2W$j~%`4mz}V8)Woo`x{5;58;q#A{bfz2>y39ikAwTN%jglDKZY29&=kDj=wu zFu*YoqK@B$Zx5CYNZ-Q|hse7QzK|Z!CtDES#yX~R9pM3UOlw}?^T1H29w8U9K^;O3 zQU5*ao_kmYP8y4dGN${K&btB6h9!A;y&;6mSxEEngesscs+fCFq7q~Ht?2uKoI-1b z8dHruqAxq3tB^k*F->og;tW9+L1PIP^0$t;UyU)XAoiv>alk6zA=$c3*%|UZ88U}* znJ~kcbHeY{aZU;7Vu<(8X4^5pU%?scrfQtxBECFq_jOVAbQ)GV867Qr_7?z#X1`YD zD0n4?(n&Bh19qA@EUu+b5!Keu)o)1|!E;q?#_L?RrWfD(Pn)mnBUFi(PDFR=<{U+z zWT1~NIiu5d@)Tq2MjfQRiZ%%Q(zby&85d*#LHST10a>8y8oYH}$fYqK5lyNW>jnei zT?RK)dnZ9yL+ieP9TLa20o7&VWgHA*IjYH_EY)+Lcp_f0}@7l{W8?0y5r7d zSYtMiZNY_UV6d?IL^cx(%WfQ597y-a7LZ2)-x3oR-Zbyj{Z7xu3d+$25rVOZih{fE zNTC%%MCPEG_jWr!FO1+rkp-9dpKRpvFB2E=hwE9nU7oAfZjR>g|5!Q~a4gLJkFQp( z6193$lay6@Tcj2uq_GYbudOCS(pgf7A`uWin za{Pa8`(M|4?Y-8P>~cT%{ri27=la-jvU8SG>v?&|L=)yqp9eZm7F4#o2umP5f8L}H z9|>l{qraT|pBZ6({O?N8xm03Nwyx24BgEzGt7$~epNqinv}LdBOB6GfCZftSbB?HhJG_lhpX zgR(8{Hdyt1CXsXKP{XWNt6b+<=kv*mq7xy%T6~l@TK>l3J z@7DA!n$#%sODY(p9o_9&DvY7Go+nn;>zGOXsD!bL&Q0tN_3D4PeP)R)R4nztPA+w& z1EYdlGP*kKRh;?~dNKBEcg>1^A%d%#nE(bV#Hz$Hr06HYs{*KxPg5;^V(kMrzo=W2 zMM+9Z+mq!uN}7ISw&;Vl8gT1xB%n>`pd3XF*ugI6x^4`m?GsVH^dy|w$v-;Y6aL-K zkMiGpg|wMn9h)+-HHxB5=cZ6HE4NQ~d`D{?(Xe;l(o zr9JJ!my~GT#(P@$BbvXakN-^w-AN;NVIR}x!VBc8bg#idg$!@(*=LPcJn9kQi;N*? z3~*0B`JP~w0i`ITiXFxqHt0_UyT*xC391o2(~b0n3Jw(s5Tx%o`5D}# z==X&NiC@S2ez4P5zcK)+zO&FjA-=EtD6KwUq1iJinhw^ha&%9B?-Zc&aJTdx=0JoX z$d^?aVhie4wXi*LR|;SK{Z1iS3AjC5&h{_E(AuUzG))cFhp|f6Vm?6yMPCeI?#gOk z_dcKWH6)@P5iI$?%D6G#CW0JQ5~^zS zmJ2kvgG+N~t@rr}yMB!9StO~<7!E z-7IY_H;(ICLd@ii%E=GNl=>ISDuZ^dtN?@KpRt!M8X~JbdZi+=%ji0JZVF~g#=hI? zoHp!cXV75JtU7IE(r6&nVcxEHz+dOz>#d)c{D8PrD}UE?rV9f_GkqaUE|yBL>uZeJ zEv*U#TRKX{)#SW)((1!G!{lZJxstrv)v+R~HX+1F&$xtabYFp+j|TZJ0wt?oXytW#k2xjpjk3PW z5eGx3Rtnit3n%L~nx#dhf_Wbpx#Pr??uqseBV9Vxg+UL@T~e!EX|?~+x78gP!1EaP zaXf8}NUN^(jtJfCx2VH~kb)Vder|bDY~->sb8Ad~mr0z0i0UFa1dY0UI7$ zJ8tb&&m85@ak4toI%sU-nouH!*^WvJ9Xj(8kVzHl6ik3rO^knXZd@_3KSfW7shY@5 z#`eS;`-2^pe%)F0BQ}e$xBu#!e$(x)54=?W7(|pqHt5VNZ56GDK6@X!u4r3)(`Rw| zWvf6h(S z_oM=dVT^dko|?u^=Q+}s)UD$B6I&gEf|qRjNf z0#CRr8s||%AInNGP^??KNM(Vr?ZFzIyw}g=Z6P?I_ZUO()71U`f%7CM57l}CATj|p ziJoLt;xreH@YkdFn;76^IyIsWo+r2mm~>u4SuNQ6p&{ZTNA%}Crno*@0sFs9wA0rL z#D1y&qT|Qa+jdU77c&wb_LMbY&*Y#q2Q->}>$DT1r=mUfSh{WhfeAF`jy&VXxzC>fMA3PWl0`di5|27nLVcZJu# z*dBGXhks&GK6L5P>Nd3h<(k4Gg0i%d7LESblSBzJj8+56%e16?eR2LKR*L~)Fuc8I z`WZe5ce6w|B?Q8tho89><6p-xiU0Gj#v+EHED@idf?0vQM&&8BJ#ITEw(h#Up?v4Z zuYr_q#S%%eW~)`3+ZX5PgCE;bnKL=ZwL$m5Cq43aJv#~y*u)8ONC@Qn-ob#AZQ;!{ z!c4uQ53{7~+4d-q-a3hhiodSoBjN$(O8kF`()s^ypeTHo&jF~>9hA5&NFQmv7Z+#` zWo{STkLt>+dTJQI*>Okv?_R0T=o)=ua0K>wXx)yCTtYz8DS~+KbZ98M&4VyunW!rr zs(7au*0FQ{hm+H71MQj%uOCub`C=|hj3^Z1iun_~o3&hk^+k#b<5Kp2KrBRxwZ_N$ z5oKM(I@kY;nG)kKD9nNrP(#Hxs^aMLMy>*7{<-v3z)8TNdC656rmASQx?hf@Zpg19TCI2N{JBZ)X(s8>W9PLq zF(m4Gd*+lb(W`7}6^eZ;Jg+ro+xkZdK&U0-sa!=zBwGuDqc|M(AeXnc!NPvt|gSk(`4bN(#h;O2&X3arEV#hFs*j$`_}^>gI^@_HB?+6ljIhpnFkhb z?bY-KBO=-L#+M*1I8F9>wWcGB6@F%B$DBEbs8gmI81l$bQc~=Dr^f zEc?D#CsTi=(_-~b(QC`cqUMY}#W8~NxdON$4@u!TWqtu$kqNOU$H% zq;>Znv+AgS{MPjH5Iy-+I>)Ck=}u|yixyEi!$e0eB2j2f^XR66inHHTQ@urEdm23F zlgsn1#$FIPC}l)S2mkZFcyYr`BeR4WvQ@G&^+#X^3>qvY0PNtC5-m@HY zC*3Oj@orU>E&(RDlza&QIWAQ22a9|^we9tG zspXaDo{W|Q)%;WG`+L33?L}#I-^l`q*A1Rpd!G4`Yw1EnI@g@cDr`S`Vec7MiP|=@ zEa#GrFOZ#Z;kgVIjXR2)U8h9_8i&L)`T2il!ywUa)3icQ#5Lv_`h>pE&#-F-m(SG? zT;}g2E&H4KQKVD!z1qDoBI6E`mWvk!8;xw4Yl-Hg{@8s6XQy;*)JjW{WAXKt`ihN8 z_(8)6P-{s)B$uP@X12J5F%x_9xi3`Q(~4{??#1U|#hd;v0p6+0#v;hm$I-MAf0h64 zf-iE!^vSVRb-MY^qGGtm)CQb(f9cJReW{VF*R{B0|3{-89Nn42r2;B)4Dx0#XVWo@ zOI))oBGTN`@`*bMsOGnhRu@0^JDS@Cmfvm;bHrun6({ngld2(vN+cqwXAyxs$kw)AC*#2(@$SW%cu z7amUQ*#*{)9=<=wtOQNx(j_^dl(^sp0pwt^il`E@{-p~FD!2cm_;LTQHw~x!8whgCZPU)xZRvSqAH#+xYSO4&n1OidQTuiykfuEMFL5doe zxkRyfihTu&5pkOfBeUf8^XY-JQXBT&vJLRdR#t48opJ~b$zT9KKXsi<@SWwdf)mlC zGh8h?|9um$u0kdy%k`2=g#rS@0s0gwrB5?L?%m|%L5zMl zcMlxMX2l^^x4It$ZGJzVkO`J2FIUxu2XQ94HpL$EpAH|4_aU_*csNP@LNXPm;^lhB ziX`d@6b_Wdv%K5=K1W$ogr%eEn`f}ub*dl>_7UOkrIb2-snzjg(6&Q*LrqQ%bF^zr zU&s#RrN-Vq+QKrX-Nqt!rq^Y(FV$DItKyiuGxaLpUshEx{`4QAXsJSwq{)kI-505O z4MV0zu@$6ZeqSV;5Kxl!0n6xW5mr(Yc0Gw@gy$O!vktvSZVz=T zdmxOrS9#iF&Ukv*{QoflWKy92p!6Sg?1}GzeiEDiu~5+!@GppO)NEhrhYNMlo%p;J z`9>U3)8&C071)}xr){;uuOC6D7EMG~W1sG|M9=bHt}5BpQGR=4AU&@F)~>sPh&5zk zikg6lR-P^Wvhvlmub1eby$9A#nl4*C5$gF}T7>dlIU2FO|NgARbiWNZ+Sr*0P1h+K zKTFAN7mb;XS)Ik1zZGCC8B25z?b(r=Cm%?azdJH}mePDfs<<~CsdVE|?g2ynN^E9% zim!#qk8Fw_s=_hX+4Y^KTp74&VaosTC;t6pL$fm_OrN>h-jBR9ime!Ly!qakUPX%l zf)5D9kqpJ$bJRVp*6Gi&1RntJP|KS!B@=SpDM=5hI+2f-F*{nnNYLGeg5t*DUQ+Ts znIt(9UE_BY0n9Kxaqv)#m$c?5n>!V%l}^bYE5PWFf76zVx9_fO*E*7(i7^!$)8;Wu zbx4@3RpcSq!SUyH2&4+Ly!PMHhjr(&iO_2bo`hDF$9aDSfqp_Tzn&;3V5O-|2m7;e z_6OO;Yp_3Q+wf%xS`*P|BS%_Ocrq>OJPM`c>LA1>46V zJ{#S%RQpvhxm9M1i?(~s&MDQ>@L;_kyPzr73@eQskog+qk`8T2y${*@fhsPbPO+W6k(^*2*I^Msv5)tzwY|Y1b7{O%YNhQk z(rL~FKcC2_a&>i6)V#)27gzD-leAMJDFpij&WGxB#S<#>o3tVUw754Lug@R*%LETOBs7(mw>3&)jGUyLUs3UrIVqq%g06iMR2lR zA`zvL3_e<{R`tZf&Ldt8KH(CCteD&oBoA6V&QDgA7AS?pi>lAs~P?jQrU-p4=y$J70`DLb?QAMiypmD zO9@&)J`Nb+hjLVExG%{~S5Vl>B=?l$|u&@Iyfe^hbB=vK7m~>t5e3Lw-l-c*R zP_6|Cjptu_Gmb%+&yLG88qN`#Jhh>UfX7y@KrTl@`P11gCgf>2bj$+|=OnvdNHE3dYSh zDNa2E_W5Q^Av(9{Z6zmpNX(9;V8hUnO0rd#c1RMny^UOxCF?z{fCN6Z`&dYcTXj$? z!8#Z}71Q1~1#J+AzSb#I5q+vQ_-*}pNl4t3KNVIY*z>Azm3aht?(dnMlc)9R%DQs4 z`0c0yPVN5?`ocE33U<62hNnc5J&8+m9j8>1d}ed0-!j=C?^Cwp%JXSZ_t$^R&cj<2 z+gTIp2Z*@}5~$t7-X~+qMW?o3Bu8Y+W6U9y2AL&{A)~x8GP8b{qz+Dn|-3+@*FhU^*?IR`YJ`o2P?_gBYh03 z8_Av4U$yJ>tDW!8OrA+)ONx$I;GK7J+4kW9nKtZ~kYb3?imcY0PY$H{FUT}fTeD3* z2DfKK{y*OPggEHPQA*RDOE#-|d~MLNJoDiT+YGPDc=^FhkCOF)uLPu1`A%AE&>}hFDvrcEw1W;2SO53_NQ|$4T)mzuoyH? zikMGWZDe!!Gl>IRzhZEkM!f{E(^{R7=qop-*6CoMC<0W-cy(Zo;kvZ3mpuaKs2HTx zl^O|an~Hn#NNXC{uCCS|y*z<7v*;5W&u>LhN;0mmLE3J>F`~z0hn&0kWX*I<5_!{P zQ|@}@k6>i>y|w*{q3@-Vf)nS{>vtqYE8|hF3gDCF`uEAFix(*!vHRK0cU%MCpk33U zv8v}Ck&9-?ng0G?hoR*U-1#0B;GyrRvy6Y%knW(z9Scd{x+18+|$uiV* z7dz{!dc7pqD4Dvw$ILf=0Extp_rvleN#Thh+CN+lU99PM(WQrkl2FD%6e5b&Z^Hw# zJG<5o$bmEUO_H$qi}O}y{wArqTGKaPEccGu+>g*zVw*<{b@|=&(4B;q7PYU)ua?Sp z&FU-mu%#Nsa@(V25uC;NuI^c%5z|9;RYY@)^};+vs06AC@w6kIgZ=MDupiaLKOvR( zmCj~Sv9f2c=Zj(Jo6-(1OS=YX(bg;KsTTzNkGAa5v%*w%TtHEpN-z?FtH#6+!!npiwvpfz^ z(ju31krd46NRqr=l}X{r%H|8AR6^!H9N|*F1eDWe@>CEkQ243~1m+kirZgr?j{PB1 zF{QcU;C2Tj%T0mb#I(CvovVs7eOItNVas0zp`RCq*49TTht@h89!UAwO%^<_ z>!pm5^gq2pp1#_5DEA(oHcsZDipJ1m>WRMWA_H%PSmJhV3Q`U=F7h!eckU{I>FXCiXV#HkPva~m4S|`Rn z6-ey>p(U#f3q`K!50>GwjwvkbqYz(-UX?8MT$QdaN~SJmniY(F*YznyZhq*l8*fxh z{BC33*{MJ3_D1fUX#Z@~0o(5WinC{at!;xlZAHxN{0YskH=hk`Y}*`lrQ#1~s(vmU zSs3uYX~y9AzdfVK^~ZuwKAMepa$lh;Fs4xx^xZaAk5_H`RMs@GZI2jGuArUGlF%w3 z_1n5SP*11%>ASAYU+}`a+G3@nfb4P;=FB)!6t&TgSXNbV(H*jBO#WL&XbyZNX1}vln5Bhc`NJKu#!GBgE2xD>~!OM0jj5 zQ%LIVx-{OLaDnTw3iFlon1S>IUTZh)OsSPe%UV`ulUh*6<(l9;X^P;|rle7L z5|P){Av@@3XqEE5z|5rl<~!SVo8=erD*q{G`;6DZxz}w))N9bD{t3HWGoHF_?#n}e z=Qq+xeTq?BB4>{WyJ**GcfV|>v?NS(*OPd_o}4$2h+uzuS`#`gDIzhJ=x8CR1Fhsn zI~6D>DXDtq$3+~sf1dPlI8lwrQ1yKzuT(Y7T0XmTfo$*+hFBt=FJH|%QIG;o9cTQ? z26C}^65pubfC9N0x&2FWropWM7f@S8>f7VFJB|GW^?y)o|KH2{3d}LEAyt;nn!ob5 z(mwd1@As~)k)1k{L_E(LgrJWuaHmlQ2)52Lb6KcC``L4FY+f?Hb}s3=xf{x3KYsmd zw`Xxo31*PBAzv5%SP&F-<;g6qT^mLg6<%m9-yl+Qk1X}Mq8zzv>_1UTKh4BPGWKTH zmlbgE2Sv(*s2}9=2DU0X7H^Vx}=e$Q|UZtoXQA9k4cAZ)peyn6F%`+ed`dO|e8BUx0~nf9eiQd)Y{otCX#K z_$IuVd^c7$_p;~DYad<54zDP_H_9wimI7m z+N8^X;lD5G*vE%OUVQ6IdB`0>I0^N?K$#h?r0@XM!^-HDv=G(5Y}4?}#>!bMw0C0w zxxR_vqcpj)Mc$L|E1g`Q;>k%7VzLd~6aSYXcBY%}urXPzcLUq~a87b)o4C9}{R-vI zm)!V9ZHA|&ui=^fYI@feoo6fn!<%nME_O&}>%zUX;R#uzrOyKrD|Z?l(dV4l@BCopI&1h8`)D|ymXZj;r_&?o+BtrOyQKl{Qw5OnQ{kH%iCn97zft(c~+HS@VHwI?BdTYka) zhpU~McE~2O_3E#b&C>B67W$RAgz&siGYFEvo3y6s@kw(tjQ zoXvanzK&d6e=&J=7!69w5-ig#E-YD)goXX z5NWRJc?49>sUl znvEbV6FmD-!J!iw25usS71@zGm&B^Q_aIB03+Y^S~g;KJKNf zgssSmS)k{dxGK+Gp?zd2_FH80gqYeFl38wa*!NwV_|u-lgmpf4e5&JH8<&2j|paP&#@5 zFsGrQj()pAoa~jyuaTdCqIn6y&7_ZIt%;TVKEA(f*8H-{AJ+X|)3e9pOtX@@mKKgW zEmD>W=iqX?9gt<|FRX6tJzpnGr3i(H$lOA_$y+=qfiGzjF}hE8s^W;gtHeOrbVgbLE=zn*}eEK8zMeYg3O-B{++v=dWB(zTyvuFE@{3=X_v83 zb#&E-?~U(u`yxRz&(i{Uy2H$uFbRNj5tL_5@RZ!!x_n zXE>mzkESOe)kUdNWx(j=@dSuS3_@!RxZbyWy9Oju@H3StXZ&~%;_N;aSXiAbP-b#S z8gAr?GAgF9et`l3j@jh-POSdq*^_0Y==R)ImEhmJy5nHzPSV0W{K}NT%86Mho00}! zo=L;BN9M)U_{P*Y&3_W!2Sys|&(d3H_i{|h-qy{X`PzeSjDOo7*L6 z5e*g|!%*G1BsXH+qg!lLARbTU5qLdchdx|PXiP`({Ts$!W2gnGK$GM{!$G;kfOI4Y z%g-CnoN|zP*QB6HbS7r3W4*3EWcLm)B($cz7HT|ZNgosz25EwM;>u(n*(bw`ez3o+ zF*#SxME4CDVnaS=)9I0`vDfXx_wm}EaEgSJkE&{!6|WVQRzxrLb(Wt|C#GhR#($^C z2J?~b%i4m#2e_2IUEepUKDe2?H@@xeBBvhLo3GTShXuK(Ti4&MsClP-$Gro8>NvvB zcdhf*ZGQPa_onCMviJ@K($X=uSR;JdA%KZ-8u;S(f870dtAUMl?*%!7P-2_1?~H1Q z{YV;$9gY_yO}8(|?VFG<0xk?sPRLVQ#g&ZOV7n)~6+>^YbJL0xrSvIOj%z$SKrF6v zQsS2JPxrPy#!F{~w_|4s83PgL32gX9u8%JkSdMRc@(E+ zW44?nN`R&9Yd(*CJ-`bu;7=>z20d)zmsHZN{+pF{g-CMjnko2zJ>z%afDY753_(xd zNtaon{M5@4kq}4@jY0&4N`uhSlf@!2a&Huhe23JFtkfQsUtemVFzQE@?{~j;wOkmW zrtF#j$#T@lsx4*Hc8TD+Qp-CxEDzrvbH)Eu#CTS8D$V*w*S2Y$T^s8_ky$ye~V9`MV0M)mwb{pw!)TxfFdlJ)u|4X^-=>r1{1r+Z9&~!J76e;MAlMcZ$7~HJ#YN)-R7o15kCU$ms?rJ(_G? zP<8>e6M08Rmd;4+9x}mpd+m#M5NWg+v~|46VW^Q*{Hy}!2DF{RTF3B&92Q4 zgd0V1DKURu$hjD&H=^GX_p*TvTG>fVCvY2r`>~W&tM$j`8(!(ZETh<&sWZ>~dZt0S z1~}zo>+HN`?)HL(#6xdXxUJy0=3)H8yUtBmOA@~5;05AL65>13o{1PI<=N?O{HEV$ zg?`0Cg{{O4WuB8J`}}juiI0&*x32}>M`EYJ^7VK}+yH%Lgh{BjeW%bLx%Epy_`JiMU!soMat}lP{J2_+R(I z9x5#FP4f|Nwt9-*!Wj^f&-Jw=sTbD_JMIaB6uwZOmeMSy%QeQS>_|J~r{Vc`^c(K3 zOJ4cqySlUdgYa=&@hGdzig_pn?4ted0MVfnpG-9RqhsF9n1s-v*BwCPe#Y8Abrq`uyfcS}FtUyYmFRLaBe(&XXMWOf zG8wnKRc9CZ=((7j@|82%(b{<7#Odj_`&Dea-lzr4Zq5!h3G*@FJncH|d0m`27$V8a z3}H6P6H9wOk@!XVjjspD0=u3WJAjr1$S5zQDKma^=R>E(YCrm%t#sT*gnlgzchK3t zvAV1Ek2>(}&maJrNhFm^q=QZn*$WaIZ11XlwQ#`?rni6OhOPi7Sk}B>4W}py>7yk* zVWry~+?|^6Nj3E9+ybTV32U3b4Og)c*(DG+S_X8#?c$&aGr4{KZ&SbQKBwRFD@7&N z3K*luN6y7(Nxk#pKv+?<%~+~h92egH#SGK&sExNw&qdh7bv|XYC-Bq%iMo#CoWo*) zXN)ADOxk)j7hB@2RMS<8wd3GA_Iu{N0um2klKJ60N|jT zSm-(YDU)@kV2X{sGb%FoKX*pjTIp5cpPS8dMqf>`knq5h6W}d3-6TJAa^WN{Nz1jpSLQeyuZA6pPTRJ zg}^ai+|%YC1lWjtBe5QDcazGAEoCf_xZ1R+2-y}?8f+WuW#7lZX$tWMf53{Nc`fn) z2OFy@X&eilm-7LAp6YHPyt17`h~9+s0OdQLHt!$H6bouycCAzVu&#ON>g8cK@8bkP z)5Ir^AV^wo;+@y&oi6Ktxcfxl?6AQFO|vN+%NxcM?R#b}TDR})j=U+tqb;d*Q2abb zq~jBndW^8USH7jLQ^;$Qpw|KkuzIixnL_H zNKA%_TaRd0uFTAD=&(V5q}?@hQICnQpvHBuBZpv2dS6_6AZ8J~x+Sts9m;SmIl50y zuQj{5&4?7{>%W!dEf2Mv$a@UzWPj7eH`b-5r#j9bRG-_Gxj}KKD0*}e=Fh~Q`rLmM z?S~QV@OiAY&-nbtCLpe^&eAfaM|WJX**O^rPgCO(B1#d+o7MD#YUMXxq3s;j8wP3E zZ#jP;1oeOQhp2w4&Y?AdAQCLt=nwzj}inj|78xfW6n{FNijQZKQ-o2q*=|!IloUEoA@oe{rq7m9wNeV z>+eg}?DX{87M7*AsKW<}336#{qWRalOS&+e#Is)ITKZtyvYcy~M-L_YkjjE|_l`^h zdKo;2Cy$b5%Tz_oJZet#mDBahd6++xvVgN#VW%*S(@4hiXPxDZYs+uL8RV%?L@SoOJFRW6?l~BBI&z+wrq!JD(z})LZtp#UI?1xAGMcox+UcA2aLgsp3AhtCERB=D$z8tT@!;G9Dz*6E}JOoCTj0?GF^hIhEgT zH7vy(kn%sr&TLn#&N;Q6Vp`VTl$MDS%jUm;9`iGYpPYIEMu^axVAY6Yv$2GrcB>C& zJAv|Hh=^bZqdDfglE=*@PP60kV*}zF*8st&U87gX<>-#C`~E`2joI0qLnvD~ z)vsUSbXhHU-e3B8KNGNwwy*I51aI>D8&&Dj?vI;X8>%u9naIBXqgh$lL*z(i?hTx? zK)JcM!(8D*r!yZKqM!XX@)4{$cp=IlvTLT$!lzzEAD1jECSX}Jj(O33P{h=lj|1s) zhov=R|2t70zV))$WPV}F{JLm!nh(t^%U3#UoyDQQJvTs`-2n5O!ulZKwJFLj)AIEyLwH0pktgzL`Zuh^H zL?Rw-ktB<+$ct}&xnmc*+jXgrNXEq+B2;;T<`m_Rr;Z4%GqU<=gB4|te#2m$?0>l2 zJ|A^xUnP6m>)4_8Q`aqd`cFu)HGJfwE3Vvj9>quJ&JY>0_Rh5WFBO$Byn8PpD?Ci)${ZseKAB%jdDesl6wgTZ}z2GAJE*W zVvr8`$VUF4G$_!GiN;90Om@#PSbf90yg$}&v+H=*t`%qMFp;hhBpb^B9PtD zX2#g<7`uJ+)PiRg7FYxYRv#?de?!D}l@YGoA3p_s$6K72w>@wbO*?Ge_vMrGQAkDr zciy7@<%fB|GE}!YzwrWTiy|KMRHU_YFfZ!>l}#m`I+T7?mgL20ur)1e_ZSQdt7b-h z?pL^tT2T}rjtLM@AF{A~$WE_=*b!`_9ZA=*Xcn_ovQS?@7YjJ*(|*=0hv6Kv;!w zNCQryPlnn`7oQAZRg5%ai>u6u8oM;gxP+&)uH0_Dv4LC3 zQx^lTF=Go)&Um$f3*D3K`xSxs*s6m`abT_M?WnCrwU=^8j=;VlzO^Kv8>EYDT4E=H zhYJwl1bIw5YHr6Fa5Pbp6nX8AX|2uL;wWG-E?n6BnAW8h^LpJ72pnu)DIlciWJL?B z+waHDmJJ2b*SxlfSG>$+Ao3~qR^pUYQMrUNQ%K_4-MxaLaP)An+nwjpezkB~tQZqP z9!E*8E%>2z*XcEiHr9Qukelc0`h=oby5&(S|EPb`b)j)89VQZ(fZWY}iMHh`WS!|j z9-6V0^ah8PRTXXKz2hgLkUAzC*g8-xvT9*9iC$i|cHf?+7lkB-#u@nM_k@bA3>Y9% zpRAp24_jVZmO6iRYwMT7=mD0Bm5%~vc7G@Z!@kN3k_!JsLnx@LhJ17u9_!d+-RmWh zYCC*e&`j@{pQl_;xOMHt{z1LRaL<Nil6)5{K;4!%dT-L+Yaun%gWr$o49P@TlwN_1M%Zt=4TdTl})m zE3ffC!IMI=TbRLoG+dUSPB%Hl@2@M*I3TtML(06^WN1Bzn<92+0ReTXAH+e#p6%)D zo`NCsH~_kt?(Mz+{$@fJESnDtibn{8n&QAO#mRo9e?1zr{ zR{sCq>ir*iRnhkaP<6o4#aBNc_bSRg^aY`0C+}w?qsHIyA*%1{YI2>h1$(I-1-4~< zli1Ie?ulpCtvkgRdVRX;uCQrXF{gZybL!J$NRS?2a!=GF=XNw<~YerY+b+MaEgkVW>@u}f;Vrd_C_T!5e zH)z>YZBL0HjC#G&JJ5=1Hrw|LF1^vd0!p@JrS>@GdA+y&p{DeQ z+GEdrZ8oise!JIcpXA%Ac5pJRoWRV$|5pg{XcWGA+HK(PgW;tTFNcANO(N6zT)vJq z?G2^bO8KV2ZDv1`P2$vZsk)LcKCZCMn${BY3HEV`-|ust68b}NX;8e<;<#B8tEb7; z#YsqMhL1ng*-~FkU&ELwhA+c9=_*HpfLzewuEDXFFoFWeaa6j2FdkXwC=mzDy%;ca zq7^``%S*fvpvmmWGOKt(IvK-885;sP&pJ|6nTOL@`ammiEoUih@Dg&Um5c`}0_lu9nFYw1 z6g}3VUejaxf45~!kxbz(yIHrT%W0Eq$Nf8RHqBsum?tjsdg#gZZrj~_jav_-l|O4J zu65e?WNwh+puUrlSa7QkHz}vp*=Fj78h7&FQDglPM&3Kg%caitb7hN%>&@kasIxSZ zp7<4sRBqXGbOv56^efwSnw5oCD5S#9v~}sLy3J z8YbXU!pOpKm1gnf^F7`28%2^HlZWH+#UjU4U|tAM2K)5N_19lZs;cSOw{hFzG>!YH zN5p-Zbt@}Id$~M##E)h9yCV&BNPfEiKl4*j;nbU6JJy$EM&{I=5FgL{#;i@5VI2A)ie!QhQ8Z!H<_#Uf6rW~X zvI%w1Dde{wN~y-)?j}2S;b%9C?}dtu*SUTnz6Ljbve;V@P8_>Y+xI7VM8$)NZmquK zl5>IG^OLyVmdn;I+Jua)RrbB3u&a$o>B8C@-;M}a-e}|q&cVK8F3H`R`bV*yF)L$0Z$N+D#{V9!jYssy8hoU3axF;!36irq+GF zZu?V7@_ITXzW0$iqoUZ>667k^4^8=fZfx+(XDYs*H%PvZkEebqX}&&2GJ*x zZdyFFFua(0cE28P1@yvuVd(5?s8(9jIRySMxFwv$qa$(3 zG4f~FyQP}$mfn5iXw=Gw)xo)@nS>ZFn(+{Hb5j93yLQhA7um_`BTZaR)Qr2Y zuRWwQHF%qmYUY*W)rZCYB1Q9Feb}5=vle|Z2c{SwoA!X(K((4A8{c~0^-TDAz>u* zzk%pRSzShT2p|(&Gpj zS&%xCtonKFZ}Wae&F-k8hahu_0eZOoD&?fgPEO8{`zcDprDpEFz%A%EzmHE)FkP)k z;Jn45E$rndM)Npaa9mQs`Q5La(n0vFcKYW02>}|lmD281mtrSBIomF`D%HICwP@ua zvOy)KY7eB`d(GY=B7u7+jnr74X%-7bdn}hvZY4*~c~=8 zS^jt6G+-&}n#qB?g={q8TGADOMoUV%8pnS9d&iEsJojsVjI6ZUl0V`Jl}Sm&i~|!m zAat5Uf=*bzYMIH8K7@ybcWc&O%=eVTritGqoA3rn^7+57#p#>(MXG(H-U(SX3RNlI zkGd(E(rs5>ZmxAmO@=&O$T{a`jg9194E>5rc#H6QZqe=RoThgDFqwSq6Y0U2*mOihuvk724cTvG zBwK#EY*Oe7_%}k;GYNt3SOHaDu$)`0zAv^_n-_UryPI^#O8z~A=;XgGL~PLtTt?s} zh(ab)VxTwONOuGN8_$!+Vn!-jaPz#GzCusMOBLi3l2d?Dh9S9n3x?+X%;PVh?;tl_ zcqL>NSjiMxzYu(jC)%L^Jd}ACs(exDeV}9;!v|w#T)JS8s(8h7GNO+HSXRN$pd*Pb z5y(`cj{#@+3t~3|&di=VWkQfgzg{`+$$M+thN~TnVJ!naYLFaj`k!*j1xGD@t)oqI z)0mfySHAp9mjAiouD%4^rm@Fvymgk2+0x~$rfln*pwSQWqmC-nSHqtbnq4H zh(wbdM~nQlxC|$<6s!}oBKwb5<6OVEi!;ReUZu8&r#kd2`wF~qrSdBI!s+WG)b$+v zDaV?3h$8S7|K?iqXk@vW1r4_!UHOso{CuL0|1CIm(fpmggYr-z4Yd~~H(~VJVg-fo zht>Z!;_+UOeOifR7uK!np+?cNx>DuIX?01@fXbktl-!U;Eq|(QZY32{X(M(VY@0fa zm)v=$HLpG{jxOz6rBQi3H(Tk^nVq%h1g>4&@q33~C5oq-c&Ec@8oBvhGwttQ`vVY|0A~0CL;<$);d99;BknAx!vAGnppB3oky+dRJ zJi_)|oA1YnKe1Z5zFpDcU<-@+`vytwJTfqVA@xLfH6tP!>nZPVWT=Q{LeWUnv~(?b zF#OaNOat7ibI$bZRsLL*^6vgGC?Y>K{dsiL;vygY!HwdSkH#!x|6?m4mazwx+&XtnLH z7lt>*ox!~D(~{`-=n{hWzUb$6m5L^B6Q}<87j6tkxa#*sPEAJ;#&_&N*i)d}geWmti9YE2{NZ+z*<>zoR z?j7-VFpz^azci~Oa&KLs(5kH{;tCvLVE}!IZ_AyR)8jGqdblr^BTpxBmY`;8w5S*O zkVi>-?RJMDV1qKC%>6oj%hEoSXY5}De2%0^tW!O~8ofyFlIE|_8>+Ihq*N(`o3IJP z_zh2No)=$5Y4A|bZ$?2HxPIL}^@Uc6x=w0AC!*!}mENgUzI>lp^4zKdG;kAdMgG0!Hx;!~56 zhGtIu_X*9>Xy2u4+cedJQAbv1Y5MY>US}!bC37MS6G0I+uKzS;#)@s@+uWY@z252^ zt8ZUbULUw9?2$Z~qmJwH<2c`#R+p4Xj~u^<)9p%s48C?8ZMoc`RCFROI*dDxHyR>x zFhwaCi(5ZBIo@~TW+XAfTXfBvB!;88P)bflQUZ=i!#rXtiA(IJTS2{3M+lNcdV`O* zQ83}Q)exEqP@R2xA;mZxBYwS}8J}->J<~8cH{up`bLK?VzlazZMMQ*1386cow6DXH zRfwkK=8bdwsY*aG0?JwGcp$7j;#ZRu2u`oR$j;xhZ^x0G6;@mC#7?2I_C?}W)1c<# zhLs6mNI_-=Pc#wL)2sQM($FiPKsGT~gTNw@YDsIEYqt*Aabw$sh_oEAmRJP8h}Yo> zivv9iA1rb@N`e4Je)i^(6&iXk}}OmX~NK9t|=n@coq0kW?36-eQ4uS|Qo={JV2wb_mrRxGz$~9@Jru z&hZ-*xlQ`%;Q_ZgGI4oIP${?i)}H8H7}cxVP#p~YH#?WIn3$Xo{_{j7!6ciSSweq~ zxVdzR;z?}l@nnN7PuQsRAq~J=1KTIL+AZpR5c6P<Cg;Bv|)r<=AOB`srC4?a# zdB!ZfRPdod9Zml?PFo3XQw&saUGnGOVBt+5%P$uxHS9m zUZUj|-fB4iwuOe;&LJNZJ*aBbxrmo;OM#;IrRuI(eAJ9+MsQ*qSN7JPA5k-k@|%6z zZ^2+{5lh0^q$&Y>I=;G_J0%yHX$Bls#DXJKWDkv-*XxQjfp)h#{N=J45RB`^T_936 zEUa#IFhydk%rjhH8P7pD5xBfEz-i2fa{I4CXnLV`prg9(%zHW0pS{#nr4j%i8-idI zxM4X$gm4>hGChgy*wN8sV!K~2uaS9?%WDDqx6Nc#@kh1rPx6$GV*xj`4INwHONG(Z z#7&b0h@PT0gK`7?46kw)BYL-Z#79IQHAovLP<1NdN$oI5E>aYggn`Kl1b=EBe79b+ zkXjJr%u2^S$vF@;u*=!H($k8o%-M|GqwkEC*)t`&7(Z{hCx*)*3?BQDI=fXZ@ZPT+ zeKHv^@}c*vm7afY(Q|n**Z23A?^$kapix0HH{rQY3aoHa_<(@tq z&92HKAYIgMC9(3Rg>94|2;nl~_O6LNJFGz;)y06*z&|;j_B0kdk@xB`*r7pg!U4O8 zUz<`^Wa0~EO^VZ5t)3an!c%I=YO?wKgtgy*Ha*^vDmiSnV&$#wWzp3TKhW>NZRXUx z_n}}5L;lfsWNW)?WwD1n$mw-}O>7zhbqXtfToZDDm8Os;TJGa3$8jiiaz4kZ6->uBhNv@hIGKK(TxAF>x%Z@lr;C*^uFC8$eS z-pcEw^5srlyBzLZe&50p6M|l;P#!4Nasi>@UF`4YUn_pM-5-10R=bFUVI1fK*ITT% zEqPWf*mbwLD)pA`j$LY>0P{5zo4W%j!QOoY+yt9f2^D8v8FvY${K) zl|!;yKTXTg_TIZ!JjnZxgD(Chw>truY^Zq5@*362TVeAJKmRZ;M`GNc`#egn56ti`s(p&>Cy4 z1z3i}5?+5kzH^h}opH%!OpzH6(rcsi#1UQpkfIBNlhds~!nu#8V?83n-|JlN`G;en zKI@ry?+e8`cHrT&uUatxyeDtV4l7UG!)<6s2A|_~gM%TcD|=bM?S92S^+#7%{T8iY z`Q>y`ifyg;gA!pjnuQ9Z360R!%b^C5 z)dKhKi4`xfRQ>EfPZC4CJM*h=Zku6Q>Oed^_iz5*%ShqH^31C(@{_ChzF65gaLDRH z_05rx@BQ)qGEaoM9pr|WUP}(ur2mNTLUPfiOL&oL&U`o2d_`IRquR6xwX{fU1;fU0 z^J_`>&++D;$*JaCZgfaJ7T#lDzN`fmNSV@==a$fy@o4#e%YJy^`U@+cy~KOVZ#9km z6+≺j7zaVf1I+8&7~u4+amBkHl?y@ml;l)7!29qhNASYH|6=RZx35Y57>W?C8f# zvvcgZ&vF}b6^B-1ySBCbm8%T_$jw(W1riT0=i&pi25g}^xR8kn6q~o1jVi@`Y zPw&H$OJfu|q@R>*_f|uHr;Ound3t@X*QSwgJRkff3?XkeAxUyVifP>wIOnUTIZJw@ z{q@x5E19iGcn&J{)5NRt)W zyI|L2do(${j}MHiJTyyZrTBBlYc^4NtSQZlxcYHx+H(OsSXK?lWz70RHnqO@&GdPJ z4^EXRVZLo$5!F1D0C!}F#Q7mVtaa=%$D_t>mUSWaQ#OOz|#Uj$nTzd+|?}O7B zLri~Hs#=i$=kYvJ5cr$9Ng9kZP)3)|Rdd6S)%aWKRYY2)oz>m+Jv+boCQT1$m{+&U>kFpGqJq__&~b9J710*MQhV_l9e z1#BWLi6cl%-F0l}!UwbqQPJS>W*p@=GOqc_X;l2HjdQ1}kd$t55-m?wUXft)HTS*T zK?~Pq^m3Ruba4!C)3$@4!DF$U&yvE(er`PeHP|2S=5@$Hh`3K;dlr=W2Sv-$tMNVh z_AEq|5`WYsj0g+b2oGmF5}YO8%uP#5UZ^}-zD+{^vH!K?lRam?o1>lMm^?os@yW?L zWSIT(s=Uzt$Q#G)cns+a#> zB*w!N3q>p;>M^R$6AFCaJN5(s8qSVOk47PsT&>WmOE9{KVNv)`I032tLTKAU^l7cje=pgjLYZ*HP&hm-?=fOdv}1a`ss%sPuQB`TYM)O5M!_L_ zJ<|vS5geee7)Q^?3nyd1%xALc%YU1%YlX3hn893uJ+)|5lQ}pdbewGO-l7!lvs@ng zr`al%>s4O;{KkcWmHdODK(NKe&pYC6b3V>m2L+k&^T8Xv?xA((2>FgxCK#b=f#b)q zyXp)=jXMNrG*J@ZeY4i|_c>a_H;ozn-JSJ~?+WgplyMwm7vz7g-1MzM=n8%G?QfP> z6IRkQyS#kA-qR}WwBi#H%7THnOt1zLnw0uBa_f)PS*m_XorV|O%OlC^quRWmy~H9nJgJze#>unU^kh7|C1iUGYjU3)L4q5uWnF#JQROM$K6X zy&GR$Z0Li^c=BW@&ZT?~~PY745&jIsE-jQdYC7Fe65p5A`PD;o!s|MVr?`z52z|@ zix<^Dt#vDH?I%~vdpVfnYK({6X^dT-9E**k!k�J!%J?GWDKT zAkeT4WUET9RHuSp>NeZ0zr~$>TqL z_q3}B5T(b?^)ERikEGs!Gi~lEKeGvWZDO;_JkiVNBPm*GZ5so%MuswSJwT-Sz0%%6 z?YpRem?K37Bee{ zGKp?irM($%dl%JgOr7lL0w?l+$y$DE4J-gi)z{(r>r7>JWwJ<-x+KC9c00EglQGLA zJ1;CIT1>K+$?}3$Z;jNnw_StYldzfCZ^5MC88^fb1xm@{fTsJ4ly7|vt4I+Q3!nyr zOlsJvrzw@?TWznl=~AT~TG0AtF^gKt2~SF4pLa|tHd^DE8x*x9F@;WosYWdU{*-7S zHvKEZ?|Ii2*oC(02-dr~e^qo!r!OO&z1cx?2`dDd7~i;_dB)}fSnZpp!svSAA9&A7 zL!tgiP0!&~^5?v=+=(NJJ#&v7=d5JgGBlV69PmE{i|?)AsuC4+6OI zsuSBW?+6xOH81Zi+V{X4<3PxLLp0M51|y_wTHKC@XWWE&_pkn|GP1UPml<6}pa=2G zS7PANu-bN$@p+BN#)&=_u(1LVb37aoE}wsb?8{=lZSQM-$D*ZL1v4ZiPhoHh2a@Zo zkTrc%r@rAfjzYX+^q_`?_={xfjIC!O;o#DDneE=T!ir_yV8Fr*@kOSwkh^=`9wE;0 zuGnvvwwA+cMnJhQef9Zbk`5xE7-fR+6TvY|oXT%v`rCWI)Khvh5a{D}`;I9!>ZRPo zl=8Six>-qOp%C6G;eSaTUso(}N!_n%3D^JL@e7c8ksnqh2_L= zD*sQbV^K){ys4>Xo%&@}AXfToQdzd_@}jog-V^{N^=bw z`EtD?5Ca9HXvE!p4YY~YYO94xG>1+6eVOpUS77wzPz)`sv`BB8fYJz)4o~)-T;hhN zOcLn1in$PM@d_+C*=$_CeT@Q^bS6tSV@%hgAcA8MK|b5&{neC~OC+{PD((%_2U28# zKDk+n72z$^QzNvw+F>49+yv16RuC~(9|YKHtg5sWbAtD(N|C}rVbw%M@sg8k_9P{m zKRff*D!A^fzhBX#P#fqTt7)^|j$xoAv#3V$6}psDyNq_MzTjV+FVm^Jw@HXh4n}q( zlDkRQ{H3-1J0i!i`INdLrEgXqJY~;#3!8LQ=@Qrtlb**Y(D%JZ5$HXiNrXw81Mqr7 z&Xlio^cF|0#^aGtSwbOqliKm3Dw$hNyjJ-yud20hD-#u)SeDhXabBIGDOcZb9T|q(l^$i2R$6Wq1b#*@kWUL`!-KM#p9%n-@ z@-%TO-EkqRh1}1z%jd_wyPS+wZG`Cd_$SM@K+aQo(ZZWBP|!J-w8gKPK|qYNlSQ!+ zYR-&AaRd4qMHqVpY_&cW&y@!wPky4O)xSEUMz?msOyMv)MjE%K%#OFbO=v5j>sPj{ zbnF8J9V7<jSpp0}upja<*$xC{GBFIuwp4oi&h#$kIcz9K(c;HD; zt-YUg&s-fwgwYT!+EJG!??E8SIh8L_vU&8e8j*XIM;II=37R;tBRLYFh#8$Os%f(o z&M4ZEH6kw~_qD6_STMI4R__k^heZd5yH78q&Q+i?8qn^jkoy8?xO@f7y>V~pe(yj? zfC$}ei@!5%gm<$(k&-P+jKArquWpb-w4&X z);DZs;^X_I(FE|xx?>r+2-FDoW;ru3A19$s7k15N27xS=@zR|1joCaMijcWE!=SpX zMP$=~Iqf9Q_lb0eP>TaQC(Lu6Wjq$douy89lmEDO?m?qwW6Ffpoq^!qBOny}omFc0(BD~8RbEju}5;%3%oa1_6_ zt4QTsc@wh{9~d?=lxAX>eckjkj4D7tH`8Y(n9-d?s3jTCc#vyV%;m6_7YIR3rZ`g> zuv#C}1!6m85s4xzub^tWwMNl9k6+p&PF7UZmdmn@)GG~WlYCzo{IyxIujRNJjU4B=%=Zxzp^lN|LCX7R-;~0wkU2 z*>@3MkVMZ@7O)ec&WMB)0xBJ?KgIWkhS+b2wYXrl4gQ4NM+7F2rjE_~>;P5D=2#bV}mfeMB`;wiYVnnjZ*FR$IZ)lhTW(~e(kIqJE zjJznrB_$!J3GI;J%^jHZkQZ@j-bCE1L@?Pv9wsklQr>CwLj3jjeKgR5#)uVIym^#l zxZB_pC+7&!TuzFIB!YDaGO63d;J`q>RT;a`500MVz8h>({;j%{G;2h6t%P~^wCX=q zmO_O=6*@|mZ&aSXRuNuAa^Ea%HW~yiQj&N?-Ijl#E`fF3+mxxx#32@gM_F{Av>K9# zwgi&o2LmQETwLIH@ghRec%VLJ-@}{b-_^z@RagAFsT20Km;~?|k3XV(LI>$O<~g_} zjW1}47+sm2yS*uW!hx0n{(zs)XNR{R9^Dd}XT2qTO=?wn-qN5A)WU*n2IpiCXzRt( z9tP~itV0LANO?LoKZ(V}zNJq{6%~ugjj}&|+CQMlGs0w~y|Psq1GA%AzN*Q1kfIXT0xsTs>q})iwVb zWJ1Bf`h*wVoJY%Fmhp~jYXz7ZGW7PP_4l679v{|{th=G;ny96|Ff(UiVuZ()gEQ_X z2f>3$cKo}pKgS%M=kwW$rDroVn--+(3cMjSA>MOa@f)c}kh;h1)fM?g@u~(3qi%oB zVxLi%kw&6@^n5p4{NRZG}oy}TJF32u8|v||Fa+cv&c zUY4@Jcy2w>8ahJSpBzY@K``95iT>bzQQ4*isU)UBY5%!U!W7uGK^fyp+sJ-Ns1~#6 z2}aMlN7|gn(Pz=aiK%m&qSsWWi@43IhKAwlW@#LkD5vs34PnMg(hOV%H@nuDKKgS@ zjq$hMVrRRRM_iE15&eTejPVAQ8XVr9hd%>!j0$> zPvYmv0Syv@fB^p<0>EA^0JSwSW6faz^CROPVlwrvhQ-I!7j_Q6^JQkTct#>}qEo?= z_#V8DEw*SJg^=vF!^TRGMrOLPj~tU5gX9FViMC17-w5(QKuWs{(uY;qI&$`CE<6Zp z2t+5Ju2M1#ERV~}hE(z^S2;v>>oEDBO>6X)p0AA!?EXi|;L!9os(P5v&=iG^Q&h(} zzf@H7OcHIy^{8u+QJYWLZ(_;qFwxDcBJTCU6~bW`VOhk-cC?xt4`O2%cwTV^w$_oi zX@^psB_n5HeR5O87joxjD02#g_KD=~9P4IeKe#Q^l(YnBKrgjLpvNd)lGht{t^ci6 z&;<1!6n#J8ajS2F!Mw1#dq(8 zt7{MH86?||1t7UgUMNBd5wW+saiJm?wqus;A>C3XP1Skh(s;fziOgUw%1msG&S#4q z>9L3dRqQs6Tusl)lU{(8;dj^Ai~R-jt-jLR1VaTf-(9H%YebQH2ZjoQHd%<4u{QM? zq%xbi43bkMf?Yv`{&ricFVJ4wqvg29G4qt|{m6WtNS=Ef|2^(tXwkn_B!W8!+6>?n z{)~BzumyymjW=^FHC<6J<>Nnk2Td)ganF22bJA*bM}NvNLgZVel8gW-^wQR`eCwGD zQ|B+=Tt4t{vc<>$`|=l`vMw16B%D`_m-W+vP=%zv>Uq_;0% z2)(@j>F%pJc7;1uSbSX8^rUb!QssiBK>~R15Z}>5S=zH;39)XjGd^&6y(6i|g;9|% zzWd2je*dM#a=*95@r-oeaJ|rg&_H1!oCuS%mtf!kHLyuG<({zP@<|%u+osfoJ8&o=L<$nG^2m1k#=Z9mB%G*+qm~F(UiQ5@H8J7bkrZI+f1&lq;=kz0+%|6h zyd1Q`-;mQqu(h}4+Vr+Am6{G+lE+%~ctSMvcdP%ztQed(vlt-a&y?!|pf~F-0}L3( zXAG(DFSEXyk18~BNz@zS8W?~9l9ZrF!RhBD^FM%d(gi6cib?X8Nt4>at$mcJpN>9u zq#xlP9|2TI0(g|7>57s@O8gk!c)t525lGGo!~#KtkQD!!fczfRFhp+1LRH%#+l8#1 z9Bbu%^t*RX$auP)a(Y~jKI&AeK!;!qFETH3wcHO6y?!UrykXv4H9ko1ck{inDi zIp$g>dK>JJiA>qI>2*z@UH3~zul?0e@8q)hi*gO28>WF^0j;cAV4Gsp6|xKj%%44R z%VkE0^^oF918sNW7JevEMtDBrcN0Q-hFxkkMpxQtFX)nHIQq>`t@QRd4@|A}5HdN}z;4XZ9b_3YlU;?uczE7=(Y;<&W3*5e*4e*#OhS1JGlXVuURXk>|Re$!>9aU!)5-HxUOD9v(EcOd~u< zKFLJ2p>yO!dA`y-*BQa?@jKfJzrYrgc3;#{ske{w#0^lL@|8Jg-Kf$sOLDc+@aH1; z_&0qmk&Dtp!m+MWweDJ>)FwI`WP6;D|AhQ^8MtI2{0#9dTsw(fx36ti#|Wb}Pm@er zkglzuj9qDtJ~;TwhCR)G7Mji5{YpJ+i5WC)B`^rfut#4olJe@`(j5*)B8zOh88fB% zMWg?cr~$6$Rx3T<@#!G&AT@B`3j$ugesr%HW5=&80PQa-Fp2SC3tFeG?yRH_Y%J5*S79!C|C`tFi{ zIkz0|oH%-6xwNjJhjfjQc7BV~OO&K?q+M?cnEZ{S-wz1hXmArT1rLMm%VwnkEb{B# zU;;YT&A|he9~^NbQ7s&izNXTkI)@>#=(f@2JY}Z?;C?UK_wL?X;yVhb$*Aj8d=Mo@ zYOH`eH7>le+@(>@k(|m6Pk4MvmAwaLtIxSZ4;(u|A7#^%#j>d3YK`e1a?4E9m)Cc5Z(dG2xvyXi>L*R2K+$pl4nTqj zi7=cZ>>-JJsAHg4@ioB%;nNE@#w^a=UN>!Kx<;=ErzT889r{Bk)e{=jS5zp6!HsiP z_6OcRSCXD&Ko};O({X6k)!C7guH+L|(4z?jNZLdq40j~jM*Ck|z$4e&3Tt_ESY0P> zE|Mznm-QL4nzrWLdOc>@%L!tRjHi^Bg3m2xN&bkn;8q3z0hXV=F5&Tww7z55K)5UpO%RwTg5hR?)E`Ib<$6V;f;pg&RU3B@@$4sFi-pK z>c8-pEf+EDb$uYNW63dIMgF`nO`w$D9Dpp2M>?)l*#`|xd_fysl}v>F0`^7;L_Yws zn3Td1H!_GA@JE%?F|}E2vUCEv4jl6TnoJa=cXT<+4(c4JBc9odLQM0Hy?hnP|1w$kx^IBL*N%i^_LUZi?_ly_S1 z>J{9udSVz3GDQRq8O=EibPBh0$<^~v-gIRv*|v8lpq#EowM z=SlgaFUCiBo{w^m*ll|?r#$aOgB$@URUN`euWaV^7{meVWZo2}5^Ji4P@Xl?f2zw^ zm`6IL(pqGtS}>^LFWlK>^8?dk)50?CHy%EQ&w`=`1>^%xiAM5a0uvweq%jg5^p8C+ zpi-V43wmSBfwUoONKlFgX()5##k;$Y$_lYUJgWXJ#SI0mK^zPu!9MF-AD#;j557{? z>u|i#^2C)q?G8fM_v#S)z6jTPFW?X#5hR=voV%)|_5Z5%ANmJj!jJ3lYEI7^QhMTU z1xyiwAE>2~_ZCTI+H1uniMa=d`m=-AAL){Bs87HG-zzqdnRhEf2ZY0I2AAx3vue0~UXrj!KNo|`bBT<;D-Y_uTY9ynyM90z0o zYVtc4&q_RjSk#IB;NyR;j(-?xVYVZ|tZ5P^Rj_WM&9LIVWPR8KNCe5E#VKkA@}@&b zK;mfGJIcHDw;bR_)>7iD5EYe^(_T~>$#5BpA+N}cf8i}{TgFiM#S@>4<@mb1Ds` zBK9C9(Z6XjiV@~gT|(!czE9M`+HEObL3vRK<3J5J$d4DbrB-IcK$h9LXNL9P4=#gI zt`3@2?H@W-2b;=U1m zB?pMFHqU*ky=WIIo9SS5zoWtge*1u^X)2xL`D|EFDs!mK7r`ze5(#&AtD4g4lu+OSu*8P}DpUbfEhl`}aJDITl!H7ZV6a z3H411DbIGn%|8k|KYG--3CE_?eIR&3q?%Jy)!2SIh~Pqr@c=XL zjK>O^`CvdT&K?lZq)%3VW7NP9K0Qqf%7&Pn_^X}1i)$W`jbU{Fm>S=(lSA-Kz}5jb zN&foBVC`si+Oc<7n10y&q0_^$I z^#%NjTmCOWyF z-(C512q9|)woH*E#M`S&RLSWgUale0PYBs-OnS}YBcQN3e@$hVY1fLB>GJ(-;m7K# zpB_lvU-7w1ish^6suYXzSlgCa*w>%xPR>k=8*R}2WsrM>=Pzwl4`FL?3i-^&;*rcU zXYZBqd&c(qOU{#(n(1#JSw}K2QUpfCZqm)LY?Nmfl4%RehNzQNj1RnDvWSepGTqGw z-ZyOyN)O#Mog|;3@((XeTXNEuU7{H=&7EP046Db^;B5YohkzohZs!By)-)6u&h$xf z#A+SVwXX%~%vKJK9FvCK_U=AsB4Nb-fjS66owH5NWB~u+kWPk`kRuU(&3(;kMLWcbMkwO99o{e|EDQi}65c$cY2gi+MZ!DDK738i}PO z?;Pblk>l$6xFXl9AOOYu+_}EG9H?MsO*jQFp@34yf@b>h1Y>S&%Q`mnER8!wEIrkRe(gnd*)B;$TUY@+xl4m(lzTw~r!#iokW&{s$_+X5 z?=-JgT{sNfVBzB6BNpmg9#&-1rgQ<+Gy zX9y6L=Az3&vNr2{fvuKu7jTWDD!&BTlfWvW0GM|T2r1@h+I2UT?T)3QeV0U0jJgeM zvMu{vTA-9hVQ-Tu`%J$oSyF?Fg9wD51-|a8TM!i~cC>`y5^5TB{s?`I0@nHMg_(bm zc~OANXvSn+)*QS)YzM0zt8Xn7$$t;)@{#Q2!`F4kE?_Q zK1i;VGvir~dGBhJJF8rdX4#~ZhgIAZfm^%F`YM~Wb+X?*b1beh4QIjQWz=|oWe)Uw zbT~6a?f*RGOO^BMskW!cz-0(Y$K)-VH@{ePL|gF++K7 zVZQs;BOyWew&&M6YWnb?`y<@lyS48Si$e-q!amU27WR(uQ^c?9x<_~86F2)>V2T>3FsSnp6Tq`7)=)C_IGJod zfSTNXgK|ii4&hE4c*wLSURsdM!JsWZk&+rQ2NHrMP9(ph9Yd@Vn}qVfli2w}dsGur z8j$OQ{D^;xObKxkU6f{VT4Yvq5(*oAX~gKqiEdvV@|$dH<88d!SvYBzzFG*ywA&Vg zTu$x7&;*l}dWjpQeR})>${_KJCt!Xk2@2a3TO#v}H*GnZEIU2hDt4-`VZph?tt2C% z=e-!t2hh>M6n!O&{GXaZsU9qFyU%FK90LQGK|&~=)bA;+w$dh5Tq+kVUv;yBOMAI`b;$(Qrmb#BMcPf8qm!>{zlf`8t=cio*(wf2?7QPiT`dDWYxQr)3B{D45yg-y_GgXCYVK}R=E~-g7yn#cT>b1Lv1lU- zBc`M9rL9aZte65Cl6fcXgb9xjWasV6p9qCS`4Ss@k^%>bY-{*jq!E@0WNDsQ@BPMl zex@Baobp>zRdjDJ;%5${n zi?yWNpI#r0WVmO8iu4d~uo zAf2|zM0Ka?Wyz|CbrK+Kzk9hcpxe+FgbgJXtTO84YM0=UeMA7A6hjnWzt)O5R%}# z!S;x60c~zZKRSA7?uJB=`Js6LH->K8+V25Rj-6QtWJ7>2eS@ob@pZ_66<7C|ZhQEp zx)@!=PUSkFJohHn3plbpw08L_u3cV$s87t9CH=XW`J!V9V0#(Qe?8?OW&qW(fHgvw z8C#H0-4<5pt3GkuPPHn|Lz{TR-w(@&V&-oet#9LbEyIf)x&nf$!_C%x0 z9=Tnvo`nLX7OGAslOGQYe0}`X7l1@o*Ec54Md$(7?GvzNpx~@pwb3F5j)CqbHn{s| zE|%%KJ!&cq9&yVtI_04lCN0c1t#yAP9{x)4{{fQos|W3fhbge-bf$WVO3Zot%cDus zLTBH??*$uWvgv|KG076M0q{w}&Mq+LorceX(}!%uz%u;rpndt6(W9K!x&J^U3>+)hW1=Bh^lq*XpoXMsj)!E%GX@FvcEO2^3z2urvZ7+JH^ ziyaDj@>GZd<$|bABT)+S&-taH>O984rUh%;22ed5!$nI3!Z#F6JIo*`2EB*D**%ZL ze$IG(O_f>RW0*rEuqA|KTrxzTKBTmS+EH9!0*b+~)xU{%D|0f1};&*sV#9AE_NbtPQU{^}e>L9}a&pm#(X>wsm8 zf0SdhX{k41SYll#3&zUMzo{V9;+|i4^&OGR-fhrfrw(8_&*5Aa?$R;b%lX)Om*O8B5abOyqZ#ar5UJG<#Zn`9? zPD=iw@FY>MB?l+6< zOt3oI?eg_6R<*LArzx+qQs1iu-$6TxS@9*o2pb;L?w6EE>H%jDV=X`s$-Fk;>d4ac z!^rO!HpU_9U^UWF-GVQucNYkt>Sqr2W7ZuCPCpW$nmhZ$AlLZQonmWmut5 zAWj1wx_znrjX$|*;58h>)DYF5PNZEGNu%51gP1N=Qf@FU6QclLJwPCXw%Gg;Svkll zI8%iIT80(er4J>^Z7Dt%TGlZ_&e>qwkd*7kUJXQ<#`z{O$dnlqsm=(nyFt}ayKYne z(1gy!<4U_Xe!!C?W{5KgCN9F;0^RYp_*O@ZG>J9nQWS1>$_Xn(hbtcF^WD#n^OkB~ zcu`fsnH7zIxMl~_qF&%26TMcnt7b#0JK71!xEjadodXn5OmMn=Fy?O;po8ztnEweeL zlvv4siFCdnj^pp`z*14PaS&?-g-T>usn+ZX2Pdlb}f>@iNiIr zdG`=tDJ5B5cN3=)@6O(DiZ^?nuR4UgrV)bpdJA3OinT}`Ekzo_D%5J|b#C?J@)fGJ zUFP(ph(Y!wlueM?#Mj{qU%a^FH68^7 zKYzAkN)J5CIHsQ8PD+3vkG)+;*|Bi`}Tt ze8QusYCZKa<6>3|AklvOHJ7mXd@oQc=C$Hm%39pVY8!YHwQ563W^s)=5IYFv$ zHHoc(+5VQfPHka5Z6HxSE_J;8DZKn(k0q`w^5_?lSZD?*dQcD%c?rjjlH#)IA5n1J zxWATyR(|moE_}-s5X7F=NJ$GXJ6Rnmma&l6;xiC>;Zzx$3K1ErolnN-XKeLcxGec; z3{`87W+Xk_wxYJ#b3xY$UNx_LX>MUXr{?S9(!BQ)bu20E4PcYTrpnSH9rydh=)KU!T&&SH(w zmHNMK!jpAxi9(f3P3@j04{s@(jt^A%oX%j}Jga_(i4;o4c2pDSAqzcx+82cpgI~*G zLbXN~8(BXl+`Rchw9(#bFYxWKq{0O$0%EN)ps#PwfK=uMq| zn$&gq@%yS}J%;721Xc$T>nA4DUYF`CSy*yHG}Tl~{!Pmp)ymJIZN zcvjT#Ac7Y$ew!k1pO65Jg)+GA&Xb8w1puRkF_=NT%q2j~vNUeL>w zCz=*s``#G4@iewrwI%gT_0Zhs8x%_+uqpApAx;CUH=0PGMnW}o$tkMkjG`hp3)Psm zFi$&^)3-T*Bl|c_^-F085pUMC0K{3yvE_WpwR~W>M1T6}xGcZ`k)Z}yTA^@pZYv>c zkny&yl|d43kbS~%E?sL8emxT1Fa;HGlq6PSQEV1n%$RcDhDREr!vP{Kq5;Dd;sfVp_SDgIUU6l=YM}Gg9U1fO}8zhUUaP8MsB(Zc1pXg|JTsAD~!Y%DmSvM z$G;5Xu(ccCnQwoEahvj-J>GGKT=jXk^B;^(m78^W8UUYbE{VWZyL_u>{EC-&a!D8x zX~I0_>MFr)<_D&O=6OBslWKE4kEcLq10_qQS&3fy zaCz=)1hrdt`9kTDnL;^@C^7N>u&MvI>jfCQk3NgoxVJ*>JP?|-*GT@QigjXd{w;+H zc@S?4(cmLe#7XzDfZUd7XU@DLQq<`3{5P_3C?w$Ty8>+lvP83Hz!|Rb4Xdj28BN|g z`KvVB#G~Obk%1;*e{78sbIQ691bT$C0+WsO50akgqn0HJgY^aL!&d8j8cu)_yXj zX+yg7LydKZ*57MZ-9N4%7V8tu^dl1gW~zeH+Z2Z)5M`>;FmL@THkm_C2jff=SVQu= zGefm{7x&x0DDff1zerAEnZAW7-*87iNeK=zGOoZ$wG z+4g#Y|n1 z@%g2LSm|9K@j0MTjbnZ}Xi6?S3w~KbPb3;7W6bFZpwm%neRJrMFqJ3-QCc_eNHBWz zVM5m;*AtEDo7rqnLDs=(pRQp+{~ZJdaPe-v{?z!O+m8!%t6myJ2U7t}*JAYrYMQpdc*L=r9|(ad8^T6B5j#adbz-T5^Xw1{PLndM`7f;-{~Q+F$nRO2gX`iY zS(GLS)QrRVZDfAk_Wvk#xDFJwJY(ej<7we~zM3`C57~iO#@BwL6}iY^V?Y0gh?5r! z7V^?r=U|)%@XcazmU3Nxa7ojBvspaXllRZrxwtW{#b z9&w}2S@mggB7td7YF5= ziDEy=4dKUP^Z(^k5_@0YW=IvdL!QULyQl$ah1hLjq(V z@(%)z?#lDj;@#Jq7tuqBVQq$_NRCcU=YS7_OD|g|Da#kO-mWImPko)LTE$ZCOz{Xx3>I z=-HXnRN-V~-NJC&;$FscpA(xO;QtbCiEjp^hFcO2GgXjDhZ!x!iDa)C6o@uTG2A~N zb4`Ncc#XIfZ1B{M8b17z-CG{ic)bZXy6$OEqtSm3-5qOpw^CQ+AN?F|kUiM7av*;& znoC$T_pWZ^HayX7Ku|`NF1ir=xhYcvw(QPJ+$X|57Q(5Etb;FMGK_ap@lhq} z5ai`Y;#nPMCel6H2l z06~Qh*}%#@u3jnf1fLO?3F4}YR6RuN#)lXDaZ>0&ncu6)|B$eKg)-f+|C(D>$Bl)E zB(MG}n}7AP3tieR5cywb^HX|Ukdf~))QB4|xe^PZoZ(Wxf3|b3diNH`B;9|#dbJ5s z3_MnH>&?jFIC}c?Z+=E*v(+*B@_9DfqvcyRcV`ZC8v##Nr-qmT^=uOPl>(~%yXy(0 z23tdavMiG}k|^n^_%$L-?TzCuDa*zGSVl0>m!Q`mO8G(lrk>LsV|&`-gZ)DvR+Hox zAaEk`)@(&8fdZ(p@(xj^x@5mFYYJCH+9ZXC1pDl)w5VF_js|7r@1l9$l_Eu)z z+?0}eOj|#3w!RA5TEL_Ngi5R%zPbV0H=202?$EY97h93{+?b ze2bt;_CyIHkGZlQ88?SGM9!Q|o)F+umTWkz6-$Tbt;Jb;k%8ID#iEsa;fz-z4_$F#eb(k8A?9Fxb$U;wu^$7j5%ZI0*$?I!Q1$ z-*Y}!UyjHpfVLAi)|U16c>d*xidnHjlVNSr<4;E;7{a{$XS)#hV9e#>8&`iA0LYgh z>DKEBY}(p(?mCgpQdx-IE+eZ^?Jtk~jR~pc8Pdc(SHG6**!e_Um($M_FQI!%DnsOJ zMCR2RH=rM}W5*W^ejpBHc7gTi7Wla!El_R%$S|?#3OYp$lSp;SV%-W_mg6n$Hmdf{ zi}gJ(uFn3J<+gRa{ns-G+}Vc_)JDpxqIvG&vN2x^E?Y=^8$cD41G2RYlS3_x%G7#s zjn_5SsUu5+khM)*(9)SS-W~Z*_cfV75`|ce)%!ex4Qg}w8t*gLs_l{Vp7mb@9|Q#w zh&_rAR6Glb&Y%kQ>I(pE5e5f5ncthrZT-@P3FR^lU;)35--0jaPkS?cD>ZG|;VP8l zQIkozy0<%djh*jp(pI8;HtyP;ufHZnSREoi6v;y(xVOlJ<_RJ(h&`kpC8h;aF-dF) z*zQM-nwN7DtKOpkGS#@!=_3Htn%+tkB#Y=jk z795VN@tD?uoevf**;Gk+WALtF`cw1o=n?@KoKUY6p2bKfM_hay?=QayQQ%!%}|l z9T}oUXU^Sl|1qOyQWpxGIZMZIR4w^{)@t77!0;D&43J{FPzZ;2@TJr)QeHK!&*zRa zI3@@~r2ryFVRg`nM0Md3T8cI8#<))qSUdoklFBxUj8w(!koo6Mdpmd47f)0inwL*i z#Q5u19Zl-4TxabT36?fd24PoOea5Ft<{M$|As}&$p+=t`4`*`gdL$FQm2D{npZG)D zsMQi5xT5J1N=OSKBJ*)+ND_=r|JkS4ze|jLcQSUylYQ;}gCFcZi}#c`%BGqzm-T=C z{S&nTHW?Q~xKXNSzFD_T^iex^Mu6Vx0rx(=fXct8#~$_I$YrHv(a=75Q`8}7gEX$< zd^mFeNisAZ%HC!@MSOh2y~=#4}%(?lR}N z&}^uee`8Fyu7=*O7A^Pf2pFB@HTkZ?4tzk$0Llm^(nUuSV7SjrvNFHBAi!pfGcWP! z77XF+_fIlhmp|Fr{@T;@&M?XIfA9GH+}={++aBEEXVSO;Oq7$(=qfVWXpSYZ+yzAb z!0`1p>|{5?Dn;S#!rWT$Bg!33+^5;3?}8LBB~zL3&b=-%+3CwNSRJrB@mhmJrk$G}p3t z;>U;fZgJGE=xuM-bv{xuaqma&3s{^!Z#@$pM2bJp`ypc$AZ_cQw7;SA+id5&LsezRd<3lHno=0xuh+VMV2jVGYmSP-4oN6l@+$9727}tAYko z|3M6@Txtvlh&mdkuZi`|6jLUTv`b^AG=^XAF7TfgAD(@KZhB1IabO5avB45C+NKpS zhvcJd+PB*#e^9q~Azh#s4+taJAYaW&*L{%lEr1}^VE5I5?!nl>rompLdI8n{obFVx5}vzL|9Ej4KJkA&dP%&gM^$fybk!@)-Sv zM-6`T_EDw}A$~GDtn~O&?L?G)kCk z$uymsBaI-6==41MB(3!w(JAxegvn>lwnClA(mWke))bmm2eEyhc=AzC9ks(|sssLs z^9$Q{=cnu%Op7+hR+Y=EdWcF9pQYjng?>jRK~*ib&@oyTsApQ%@u0UXDO}$|1pn64`t5ezhGnm| zJPfExpKo<_$baWwn?9l8h}M%-alU|N`lMEHF5@MsW@j4)i1QQmqg@JZ(lahTNEMhk zsz)J;Y=%ZOiU3%N;GrLvc{!w1!}K;bTT<8gw=HD;ohn~xUBe+2zamnHQd4i9_YOPY zMJwzFT4lOSx0ln%)-79;+q*L2d}Y~%xQUJ_$kr9_#1Q)~Qq~8R-fO0|bG(bxw2AIt zc4Z-BY{{BfuMQu-f{5Nv=PJGp=-#nRQ7I_Mwv^Qgh?#Vx#$74@{s^IH6E?Do@sA*G|mR z*t}?OI{G(Sz5nfvQevC|i3BDua-Tcu1ZLpg)?GaGMXp9g*!}&Irg^R&J4bIP$U>72 z#b#FjEFSa+k*8=KCs1n`sagsb%I{#wF;cJ1crC%7TYLKGZYp!;i55Pq?e(O)(Fj?4 z{E@{8YRHK9e@|Vhi{kj37pjJbfSce}vAde`>xs+W(^0Wuf9kVmo)F zs2-tvkW0<=bi}X|jjco7w~Z6;DP{7XcnX%Bc&Z^tlUK4yA8wE4uU#0kc zg#C8AkdvRNog6WlT1D%VkAFLjsdf~TDWPg*+6ua*hKej!91r|%d!AUls5MVb@k1`XWNbzu|Q&(8NMrHcO_1vDhtK+j-WGsx<<6F>NVw0*4fo@3bwoFF+Yng04 z;BR6SSQ%ZvU$uPIhN?JL93Z5xD-0&tJPaQCdA<3!{ofz%8+fqJzgq8VVob{5mNHqY zy9hkFve0#tlTrEd%@0g{wo;-e;ozM@SMl$UPygHl$aIl#NScKeM-5m;NMnw3 zryuXWCiD`LmX(41r?8wgsdkc=Sz)i=&OF?7=Yj}{89}(fSK*(|O`Qr(dFK(Wid+7S zoVRC&QJVq*F8=b?z$(yjWc1wSf`?gSxAn9^`h3T+=ksvWZZstr^*^rPjyTj~OYi-6 zBLrKX3R4;NjJTD~rAEzZuiNfi96zO~DSgcyqR&NT*{9kts6??GB#$LwPCeC(T9RP} z@^2=W_40NGP?8A6!e1xZ%}~n~O3Mt_b_+pHD|K_pNKw}#Hd?QGbhMnfl;-N6MLR>f z{b;6d6xGr9x5h9 zpOVFce>)yW$d$TPuLx*P7qRHA;G^m`il%A5*1xUldCZcBy!hqK#FV>)+ML|nZp-FAvK5_$(M*cf2XsTNEQ`UFV5I4Zb&ZN3Iu3?iiHBO$oW)qh8jj+J-X!8UX2!{@d z_rmpcEhuHM2KAZ&u;QD|9q!wrK{?kgPSZt9 z4{nihp@wlH;RBM{DFyA_7J32YA0Hc+Ig8C-G8W%!Z;Zi@n8)%>NmL!D=F$hlVyCMb zE<{nCA~YYQ?m>7Kv}}3EC&P3UH|;LSdC@p}U6DWHn0q!RV9d85K|<&D*0_>-3V9a{qr`c#b~epUd@ z=IOld-B*7Q$*X57*u0<8Mjoy&MCPBGf`RrwKyqYE7z@k(VZboV?nh@VeB-Bs>+6)8 zPR5uCds+n^2vHL*9#Ayi!5dX5b|y7mzyB=PX~WSF(<}`UHHLIjs3t?rv5SRDQ4k$n zdV&*4yvi9?9J2J2)#{#-*0t%{H)yL@ER~Njm{(Z!GGShhMA!1b&MLyCF)N<0=o6gy zp61-wSGhc$$>t^bA_u{y_YjIBk7mDRA`PpQKM|S!ZH_~~oEyPb-((z2mbDPa|4>*S zZuJ4II90P7Ng#0b>-;0MhBr0}?ayxxn@7GpmoIvm0#Hoo`Q9APoDxFt;DkOdP{p(R z&HdEo2rOMh7G}jz`BySf)mR4sK08qzVWgLzXzY8XBC;*#6i4ud%e}=VGskZETEi_E zYj}Q$&W(iu)fG_&FIE8vmVJl|FMyLF0L` zd@~T*HezJpe3x8<4kyKTJ#W#v^|^p2k)EhU!Oo>yXne zRPL2OsTwR_RIB=z-MDQOfGU`bHu0IE{zT8ZMRk<4eWY$0od7;q7)`hROk487Hx&kx z$w963#@QQM@CxXt`)X>)#rjtZ9Cv@?n#$|XrjuczdKu|6%j1to=c+u?c`pg>Tr*e% zEj;B6mdLmybg@#M&Et$^Nr$ao-Yuo1+eoJpX1j(lQdM~)0i@}YZCGs zj!2#r*tKDG#K!Pz`tmZXiQ-VwYJ#lIu>3Dle1`N>D!hn*aat4?iYm_f>N68PvugIf zy$iymjv1$td2QWr_y0*SuFkcx=Gi7oy>_xE(VGiZwi2t83hp zBYXJrr^9|vDwU3E)5c&nQZxPKXmQ6A6Eqrfn*f+!EaI*dR>I@NyKO^8+1wwdkC@11N!+tDa*!M=g0g7& z3#cwHd3}u6x&N*r%dKmm^JG%#jqxMzwJyJZz6(uK3F0sTPQ13b7Iys*JW0hO_ny2A^hR#Rh}YjDz2z98q2A3!YISkq(v~d+Y5gtkg^0zeUS46r58H#1YU5Eg=qNHN zKw+dP^cAv7-^v_?uaIc;J9F*9$V(Tqf4LWM-pPLBf+u@bmd#x(U@g~gzb^e=+CxM> z6%&qMSX4}loSG;CGDLFW{WH&eV!7)=m=23HI^lrSuA%B?ig6;aK#aKYG&%x_W{3K- z7X1CnHRb+0+B?r&dEhn)+*bT?bybmGPRdYC zIuCn<-Qb{*9uf=`MOADF>9WD z@0!S@;_humiqz4qA>vm$rPHVg55{b39ht8r#i)pHAli|k)JLz0jfdK(w)*OSl=QnS zJNQrH+d{HHZhA!nkI2H%5g8Sj%5;FxeQZ}S%wnGbZML>p9!6-^yt@>qW>zTQ$$#L%0|J%EvH<)CPU4fB{>^85z zXREr`?3);?P^LBgU--JyQn$N0vAH{)()B_UKC9FV)I}c@P$Z4gx@M#Bv6$mtkX9L+ zPiS9kA#yTz$QtUHV00?Wq8Trj2sQa-!B;0#bB5A?I&zDlyGbbw5=4yfao1T? zplq|q8B7^$=pf=CHXq4Fh)J~5Q)qGnBq40&8Zp8aNa&R(v{C&38DYRV-VI5P*oQs+ zPx=4~MRZ`HMkUD^H;IKAyopE%$p0ymBMAlo{yEW?g-qz@Y=*}>Y6AVwsWog+Xfxh% zY8`U7SEX1lg!5LW8duqET?v?KG(Z;w61KCdl!xX2LDsyLY6v?}CAEGnajR)=$CTfj zx=qOwazos<)dLl<99!g;?F~7)ThGvZ7W;3h-tYQ}TgAm^UZpM!3k}30OHgm9MP#Xf zu`L3g&WyTaC}vA@PFfABjdy|^KO`B2mv&ES2$d0&Wj}DKHZA(L9lxo!t~9tIz_)jl zM*Q|G!s5NxW1FFp*HtKbXWq?XAyHSA_H|ifV-PjVcNN$itCQ11dPyc2O6q9SF{F=&%-aOE*t7m#4NMH`3|no7(`D&LUeIo;IyfgeWG#})n*7k)4h|5IG)EzJ zQ_WkBLgUIa=}tQFh)NSLcz>8x@CAKi)Eeu~yb^0Uo^KjV)4K&dWMG^>&OMUctgep_ z-#z7!)}#!>+QkBndu40uprv{j%3D#{?TJCgs$g)$A;=k#xF$RQZcmis3wW4#8PB|R zqsRGE%D)lB{s6Lx$AwzXkG+=#p<(@IDthBr+Y{T4uEjYSa&7u=zG=-QDvih&&eN}Sy zxM&AO|AUUg=>1g3`Jy+PPgM@-F5xt-J738uF5k$UB`#)s6SyWmdPj=AQ_uJ zE7@orVTpq0X;@yg(?LZch6ud?J1u>GS#Ob2QP`FlA@pjY(BGJ|w-hw?mSl=+^T$}< zG>&zBFRyLhvSaH+n9%dc%Cfln{d3kMmVDzkUY6}1*QAmu^4o-Nu5ON_Dy=Fm&9n1T zm!pvWAYe1mlgXuL8{jdesWNq1-w0*%XXoWsZ!mge9|{m*=V_i=pE6(qwX&s)I8?v^ z5oArpDbt`8G3HFHEMAR0_}(B#Xx}%~j|8W4HNL#r51u|6i?_n*fTRcl zr#i7@khw0`lU61T;Vv-Jr?-|4W5=)XbIrn`@Ung75*#euZo_a9*a-701*8fG-dJM@ z!MeC#kfmXmIO=kD0eGf1G9iTvwad@K65!)&eDCPMa_drPhK((<3(*OwTH=nff zyBjuqcsb*__qS|$qZs0hki)z%~k=4)E4)lp82_sge>dPWBz#+s;xM;O4PrY$neL+|l zH?NhaE33lPf1g4H^AJfRx!c*}DEoc%JEl#|D=t%+;gKj*tsnTcVA0V0&ZJ8RIaZze`HOcc&7 zAsphZQDB;c$UL<-y%^qf$946ZXC;v`dnp4X#baWPQo9$6RV?5Ln!tSEkW$lLacPM} zs)6zD!T#0}rZC{buraj;H!b79AWETIHeujI>K|<(cc7{YkIvR8&%sPl6e+|SRw6s0 zMTAaPu>?&*sQ&5j=#&dD|Km93LhOPij^1AK^E5xTd3!t>FHLMH^EM^(w}yrgQlu#I zcB!1xK2cr)M9vBm&UH4F94T`Ils;8>63CueA znjd3Hx9!=nBv^>^HikDF0q+30{9X4C81Y8Sgz*+Ra-&t%%Ln&hB!$=l2|4zLfo%Le z_m6*a4}Z5t1t|rZk&EX46r?!Bj`SA6c?e7p<0h{+g7kY$vp!!ro2HU~y?vJAyYBEc z|EAgFJa18qD?}R1r985!cEn8GNp$<;>r&H59qQtJixO+NKcObkE{bZ18vgRPu2JNB z)8o!c0($9*4{NX~Ro7onAnwNMvF`8nI1UFc8^*1x+3<#3gOy@sDRyaiBG9F5E$&(N z+&Cef2r+9@Rxv4ZqzA$DWlfVVRqDqF)5uBxvg|xP;@cd?W<)OkEO9c4FXX8HDFMA= z`$pv>P8?yB1V(dV_By7F*tH`_CSoTcy4!?eO;}{F){J~~NYMJpV(vw{v9d;^OMUSR z?gz8xN=MzipA0D7`{mO}QVUuZ58{q6UcJI_^oKy3v(OY zg3^?Cf;X>6CqdT|*?T%Nz_a~XO~iF#}YuG z3sKyWzD2k7t?bPRC736TLpF&B;>J}~!^1htc|P$Z2BL1`-;KP#qVh-d7hIvY3R>11 z1vp4?*^Uj#@hvgPuFups-j?YnG;*@Ix`(q@x2{hG%i)>UYemcZ|FnGvR8v{Ic0wr9 zouE<#1W81YsvsH#gE&eE5Tpo#k?JVwfM9}%Mgk%ZN)6RQQA3k%1EVw*5Jw$IXrm%1 zs3a%|2GJn;zX#`=JIuP{b?&?LV1 zk^rN!UWhI^y7d;&l6$wCf{~G?@(fWbSk%D=4h%YXhWUf86DU~0-xuVu5bk*<_RbqP z0fz3*6G-Sgzk&tf%d+~p!L)-X4W5n^o4ahdvyTkX?BCw{Rc?t622-o4c@x1xGeeLM;DFGEgn`|6G6NQ^aRAHfZffbu_!4XK0 zf=BK8`as|b;z#fSkKEH!9pu%F$S}clC_=0%0MX|3^_;vSh0ypyK-{aH5QDAVQAd!UECd^Za-lpe?L7gSy7jYk<@_RAV`}@s$5P&aAS_$@N z2HIe11YZ3hcxq-QiG6yEd|o(MuCLGl9=>PY0J`v-sNk{{Xq za$O*7&RZTWWa5*7S#1P(Dj;Z1LLe})8oY^=uNW~29)X#Q{TO@&D zfae!5M25HbG^qj@hseg4<$G^IguG#b@m2``0OSe~qM{x)(-j9GES@yb2fE(6dl(!c zz}e^bN54w!12*f%qd=_+!hV-MQ$I)U*y5#sMuYtbc;60RzMZ=BGSKhGRdqgiowDQT zU<)0n;TP6g1D6`I-$o>XASuVZ14H1`3#;QH5Mrw-OiBwVp!x=uz)Ncn0>jVRA#etR zH|iZ&?E$kraMOeD{_9N}DX}AWVB+lA2`MCRbpQTQ6A8%(c4=S?R|{VMZ3bWnto#bx zFV+u#&IQk>b*g!dn?1PMNy_fU}RA@j!<8UvwFmseh9{b6wL>O5q@nSL+}oKVUrm)o5ZhkV+>lKw{sn1+Ro2;AVkPo#4(078JRPumuXKxCGmnfwL>X z{&H*z}90% zd-yXriM8JVghf0`Jy>i3F&aQ=u7uDEko%Gj zg>!47YJ zNj!jX54D;he&N3WcLsnECP~s;u#oepKH^cm$K#iSey#5~wO6YoA+G4IZI9N&MrFFS z9!!E`nvxk1EA&PdsGO@f5F96X00fv|-3waA;zOAruz|&5C@9roZaaj`a%a>mhuw@p zHTl&njts_=4}c;KVZ(1n>@JdI5y2x8>qHv)2J6w2;GBby|82i24pIQvW3e)?KMNWf zd~l>(S^F7~6!d47ffNT}$8Q13@iWG$s}uw7U9SgI5|9J^5vXy=IwWogghu?Z^%H0T zA;_dM*ds|_MK8H%5*!JN2FIGB2Czj59|CMgpg??kt<+fIFa%U zI5Ya+ZGL|mG5K9!^9-cu3us$?Qg+mQlwTw}^)p2O?!5wpF!CDXA4W4<+U1`>Xy&$d zp?Bl>p37tiW3O=(2rEIe4$MQB5uS5!#f1=zza~kfzWd!0IEN$=;!$8n+xccaY`$L; zxQK6!LDGtpm(CCk@5Vx)GVkz8T8>bwS^}NrXyeXN#D|CZdgmJk=wxz{piWOswwlSx zJsZpgvMF$rWdY5=jHaBL0M-`UypHueszH3tjouG5>;dICn5u&d8PG)E^#N~mh^#cY zyLmlGo-RO)C!qZ^e?M@){F8t94G$na-De0S!H5B-*BwJxbs`kfFa<)?CUePHsUV6w z_yr~FoCN`<<&Uu7K)f=5%Qs92QT8rRf&zyNy2J>v+!UZ6SUpvb18yNx;1)vGm#|q! zf``WSxV&uw8;#)CYCuCUeWQ2#6L8+FPXOl~kE3FU&Bpp}w;2k9H#4$!Fy;sq6pZ?{ z-hjpF`oVH#2rGgt@L)&tVS54?Qb0U!)BD)q4`7)wFKF)d5eG!AgKV@EI}0h2=Q$NHBAmkz4sz3Kd}FuTYpPg@Tx3~vl@iv zKLJA^SasY2Vd$rD?`N_g@d2T^l7ATD@6!?sWWhjh1ro^7OCN!n+}{m|HISYC$Cc)6 zqut;O+42T#G!8+y2nhWE3MjCx1U>pAcxC4b!N@204Jd?wGW+teGX&7d|C|C&9J!Nw zPdSTDI3)Cf={s;xi*Bq816w07*Vs%d8hB8AEN4Us7SiBZrnWUP1vKe7h$+#YSO6>H zCyr>xH@956y(>uljQQ%7;rdyxxxa=i-h1Tiov@7E5XznnOGons5YY?PgZ-d2sgZp* zDfct@PlE^%G%LO*Yk_|VjDx}I5*&4>fmiaaR}vU>WXjgYfJQ*l_S6AL*tXkS zrR6H_9Faiy{UHtz73k6-8k4E|$ftv_N3znSJb{gM7vh{aLpTKD%J;xPjkuISl%4vk zgKbwJR^${wwe^D^WJkIBhF_ukG##{xj-O`kcr_SEI(HCEgPQ{>tw7jO`0O+Y?!l*0 zseZ3xSCyn8?281T>*-tbgJ!SZm&n_;MtrgS@q=EkU)y1=19h1$1wP`L`K^|cB!NQP zvXmwpg)_}!>upn0P-un$PS-)2;KL%}gq8s;icJ>@2j6G@T0~)IQ$?+-zBuw&ky~-8 zZ4)e#rQ+8w?((P=+$uJ!LnE**dFK9#zoh&#i~shE{KT3=Ql+dR`VUL-jDYms71Pbz zFOko6Y{*NWV7W{5oHG)&F80o9?f87@kCNz~8@9tb$0Xk+$svc=EWGrpPYYTHBW$Ij z0&;R;XfTD~@G1{YNGLyz^{iVc>5gm+bm) z%)|F>g*%*Bq_w}~NJ+A618^M34XJm?=j_5D`hR6j!o?vE%Gtzj2+v{-#Tl{T7i5`Y zd_O>m&T?0nx_PvVg#FaK5i^WqMQC0k4;V~DwCWv5@^5wDir+^)fvw-FyNLg2p8;IA z&G_2-q?v3|xw(^{%%VqBZ9bQhz{(|r?Ip~=zyV!R$R{U(mxBInk0O)TK8+6 zaL~lixHCnZ`BJWi+L`Z9!WR*E46T_Y-v5>I&n*7?FAD`>?-jS=+XRc9>_n~0I6J4} zYXdTEisG!74dcpXtJYH|SR3k1Q;VSwzIGD8Ee)41t)0wLg+ppja>`PY&pt2R6uy?G z1S>+0g@f|{2XcS*tDVPd32AA9e~JJV>WN2oO1u@wsP#*x**RF%_$e*uTSaxCHqfpB5e|`JQT@ji$x3@H?shgpGvukFN zo#+K3>zRcAX|S)k{PU6G##`5=+VSSKW|dw$?fB!FZjCHmQT%vj0RQDA9p#bQ6aCsL zli{=M6DoVfJ5@sNpOb^oGH^W%F{HoYU>PTkjY-}{`d^G>sPoKh^`Cj?mf4#%j=U?c zCcTQp?&REouDAiXCfQ-3JCz#xxiEEPI?uG*wI86Jps~JVK>w!#;=MjA1d3+X;M@B?#_9d{bS$CvKzUwbmlwAu`7>)2t8n*6|-N>oW1IB-j zZOGw&oS?Nd;s?hqahQfn6l>Oo7#0bCB9)8xUKvi&(9 z&D`j?4(ZdcQ|2ht55JUz%h^D|93|nFW2s18prXhtsu~$_f7Weg=KKFQj>)S%)Q9L; z=LRi3qgGsOpR{}(BO@Xp_Rb}n;M^TKr?jhY+4y$RCvJ(=&f3iN#D&dUs7+4ybMuD*W?lK=cR`SDBp%RIP|wGcc0pRBk4 z=hWdRJ95r{y$jwjSR`SUaY#l)+)N3!!?}5tb7U|i98xsDt-9*1@^#pS*w$4qXG->g z)UwSYERO$sAT8ORn*XGrkiv+%u#GUaupQSR?P)OD8{I7#ri>2JUPbN;WN zkvpR3i~e%|g+KB^J~xw5%+h@V66vhv%CT@-N~iEPTG)f7Sgzgi!or0|t9NS~&0(Q7t;Fy-`xIY{6Nx_!S)Hb$8I-}OTP~_M)2>R@;lTESDB3HA{_tQhs(6)@ zi1FiN^i%SAfyaZvO5KfvY~~v7hkCwH3FU9WlCA0^3q_bVxx=BfyTQh+GF@+htw1qP zk-(T&`eK}_?O`Zv-2cgE5x)0W9Dy;nlTOl7my^o22#k^@1SRrwBPqrGmduY@Oi!1> zdny-s5&!u|A*P;^ zn#jNmM!(vQCxqYQS2^J9(xYD4ubOK|>s2-Ei=-q|$4IR$PYVe~IjHb2&enQua^Av* zpI5ij#?p5p{C86O z*72GiuFn(&6Erus4jHz%@Fc8`VI7?^df@5-x~1ic-;ISWjJ2VmHspCFECH=OAcd(i zSBf^aUwK-JC$-X+MDW&Zd74G=J$E)+OFDujX7ZfQ^UY!pS>+V__;*BXH8ky`%&YnJ z6;2ubJ1#N*0!rkYth~B)%h2QE#ajY%^az3M{e%4bE9bDJyWN-~Ki8>` zy`);Jl&)&LhhHi#UNXJmUE$pb4UsfCq>l~`MRAmLWF)s;L$VMDZvG_I+0EVD2^L?}k^EwwW_PvWBXt48>( zq;q_hNe{``D*E_X@&~khm_cXIt8NEs%|D?cTkyqsG&v&BtAk3%NmMOW(Xg}=~h*Z8px%jF{Wt}AtRFmIBB(M2_49Vk%KE@>y3*7Q4a!f(%O z>~@IpFQlb>p%FEBeMx}bdD&zVu7zQsrm@zqk$>bgm5_^d`20MxAmd5C9ZmSk=1#In z2xVUFO6Kc`pv#zY)|x|OWS&x~yZX&c$4qNn!iL6kygx>MB!O1iyr$UQTG)$c5;U{4 za;8K+wcQblMfrC)^oLoyGPgAwtd!+uuN0RJTvwnF2rYT1a-QOZW~CV~pSu*rhPQ0v zSN1I)>ba?w=aE{V>ea*vzk{pi(Q4+}(bawLD%{|a`hPh2X*=yc21{$0h-H=Mn9>(J z=B(p~=yecR3#$$kC_Fo(K6WU_nEQo->bS#yp5FPJy*cu5O`A5)9XuZ`Pl>FX4Zc?j z?d`bTkq(B~eZsy^0hs9xikg+{?B|+?q$=n3R9g$jj_6W)tul7w_ybl(!bO`=BkS=D z6BoXWmxXsS%y5l zsn#R7;EN^AG>K@vFO44^_4`y|dmwij8ZRb$gJZ8ry6_gmtJ%OzR=m)jEO$Wo(Kdr% zl(m!nu7eoqg%NUh+DkR^wT!UYCSg3r_S|LY{!!l093w1U)7m$0E01qMu5XASo`t7+ z4?U+fIC-HGPkY5)sqctD3DkD*d^K?V#%UBk>htMsB-5a*^b)BfIXX9r1xDAF(x2wK z+~7qGJf|&kh`x2Rq(Brtydcu525EqeCU^MEogQY^{X05)DHMl;>Y>8PiPaqh*}SL1 zYRV!0^H-EbYmeJEemK`=X+rN{RTmbVII3l7Xrt^j7#kFY54Oi-OQQWXqrL#fsJu)cUtR zicdRgBzn->p+m^6;^`FLBU-8UO2kKK9_8~B#0Y`32C@Blxi9tji8;%kXKv5c4L1}j zjYvBg3b~z26nRbh3{2Cj_muj=_|>+H3VMp=45t&F=J50Tw=F7=Dy7Q#Ni~jMC{R;R zo;K|*KPnaLyL6Z~#%QyQ2)A*qg1 z(UXbQ4$G_`ihP`Q6Z$QW32&6~cCpscdW}?6?r5qQziQ|4QH~W9)@}Q_hl=uj#A#!B z;pwz7dW?znYh#N(-k|cs;|1yU&06o(7r>h;zJ`V=Pz`ytO{%hdH9zspg1G=54{-_q zx&x5bAQcUF*ccW^XGKEJbKHyH9cqu^YD3d;W4UTu7rD@2!4(Cnp zPct`B@>K3Dr}gTp)P2qhR_zHcT#+OS&kv)qQ;tz-8t_$4&oP&n9^GfZvHSv$R%frr zlgrloLQ+`(iS1WpVZHfvl96QLM{+^D1&_aXj|}ajgrRdgu7xAc7X=2#KX*LsDzZ*3 zOeAJOtxb6{v|j7>z$+>G0UETPJ;{oc0zs=|Rt7(08UMwJjq~7r?V`ZKUqDF~Ivl$S zQ_TKF`JZ!EN6cA38{3CY5;1J@v#+GQ3zy_SPnM!mD3*=76#FcR0;|Z zolQYKIm%NiGdjv2OpkUvBOlmvgGZ+dr3xCD)qV} z{LI?hMFGnBk8Fpm-kS0RK}>1KtW{qKiiI67G4!W7TE=wEoD~FV1JY_+Rp&{2^yBk< z_J|(wi^F@d>;nZVDsMU>f;ru3aZ64QBwF(?p;4ne8<{xAEXEq;2!?Krz|zDs?5K=w z!?cq;&sQ`@Llj)o@bF}TtSGmDYT=Mrb)fK`D0P&CS!;LHrGUTh;gF(3tQA3+Qi8OE z5g~gyKkB$h6>F`)8{!{FuWBh!$@jpW!dzaP7Vm7b&f!iqT~F6gm>X%oBJ4I}ZMKFn zJ6??DtH+Z!KGzWu&Y7x}WUb4!R}}Wyt^{~sOYLxp8T31a6lJP+9@Wa}i$*}QTorkG z?cs^aLI+);cL+{xINC8wQh++dlj7Lq<4#D1rxs9e18R@D9b;$z*e#xIR_3ELhtKTS z;I?Wh1i%{SM*Qgm6lJs9CAhPG0+)jHqfxIYSyJ@nwtR&&DUqKe3-d77=H6Jet-`de z9gRDz+;EU5wNQRuDw{Ac%AdN6I>__W^{6A6-Ey=_%q32mjbusrTUlX=>JoV!{2{xn zO%9XdZxu-Mg?TLnVjGH?9G^*^kD9H3L!Bh}XmCIL%6s{yQXbb#<7Jsr9 zmbqHnSUywSzQU9Kg;f5)s7;46@h-YSw_r3r5g@p;mzI|7$jMpAf1a31e|p;cWhQo` zM!VH3hspdPBVhy0jzz~cJ@-eHgsz&8*RNRoz@gE%f<8qSesBnOB_eE3c*31hX;Nk@+&?3E5Rf2W0cj>>)VOVOYFhvcQh{s{2mf~1gPwM} z1JOvi;DMR&1SsqHl{AXd`Pt_X!6Q-*z4frkb^ZvOdmHVq`%*>Zng6NpE(u90XPlD%+sC-*`A&{C4kVPuSYjg_y!WvrrL}xmQ!yDTB*raUV_fAevK%fNIy)K~9D4DR-8LN4 z*>*1rP13@_L2qAbK}@m?iMQTX8pl6}H^PRTg)?V&;+QPQ6)fjxc*E9J4@u-uxSW3- zE_=ALG6pl|!)3AzT-McqGpUJjS~xi9?PCcB&(cVA#=^8htuU=ns}n5ZL0zPnj{1;QGIGND7V_K}xL2%I z>lscKdCmg3n8St>mbNT05*#w6jX5O2hRj~LN*+NT+a3pJXh@kkrbq*9g);^Qa5o$> zrM0wJw_4#KMuJ18^s1XAwD{TW$a9UM!n%2JaAs&RBo_VviJbwmaDbm|q#OcVT5@U! z^aLEB%n7&&tfLuZwTcVf1j1r=&Ly~Y0%;mDd~85|#RWh@zIcj3Dpwj3a;2fw7vhA` z(5Fy_eW-aE=K<6#5^X+=O4g7*e8so9!dG%$5sQS&wB8J7jH1u~!&w}QDzO3X zV>YQtMsSDKZg0cY2BqFbUr4}M2GSFJ%dy+5NrR~N=BS)2oaV}IX=5+;IBM4b@i$MZ z{{cx83s2L;<>L`Y^G%d>_xWS!7gPp}b&Cit=+OWDMemm@JdRX9i`$#5a5Vpt&8Ox) zid~;f4O!?m+BMtAtOvfLzF7PvB0(XeRq>r_={m2scdpq=S#y8a{_JmleE5h;Mk{KF z;DuXv|EJ37;M>^WwKSy20a3>G=vsf%SI$N1%?kNWnFXk)Rax(fT^0PLoQudjRItbW zgB=&8Opg}3;`vOA(x27}+%Q><9T%~}hJ{@#H0kUPybmB`Bx<2b| z%IATIQ}<~l>|PrUee$hMQwf5drrh#Wx*V<8SbEWjMe*4dJB~w#DVKc{7g_VPV84bw z-@>WI?wd(V@`ZPe$o)jmawG|i95eL~OJ%;`Sb~?A`VUYy?W%6yGtMLMsJK3M`?W6!w?Jb1gmpP+V zc52~FvbE-x0A!0%@hg(CDvrr>+!C+Zbua**Rs_CJ2mKm{B_Qa&SAP{7u z0g<)-l7WFaO&~EhJ5rv;Ea~kO%-*EUCscDqTlqK%dm1p~qx7G{(yntF)*( zJLd82#aTgeK09oiSKVXLrR;ogsQ_*Lji$}6sR*=jXO60|YXw5fD-X!)?Df6HeWycXNZzC33g`XEuFB z)^G&^XL|lKooQQubGJ8%6H6Edbc<3t9{QKp0lMj3nK4NdI)H8}V~IdzxB?K1OL?nh zTmiV`hyaSDMPg#24?GR>|L#($1pifnZ>4ARkt+bp-@3$v@0u$CrRzNH_I$$o{ibtR-m+VTf4w&8JL| z37H<63K`RWJ~Y*klDbr}VTnpbDQd+2@Y)30PM^%K%5v)>rTNESE^VZnN&FwU6{|Ju-RU_w*p{e1YBrs3*7ITT;>D^DP{b1>#?Q?pX{ zi1eWXwDU$T>iZiuJfBpx$wPC%Xt_|tJoQm$0sn}5mk7j;wmj79)Qd+~8&V^;6WTJd zrXk(vpPjzdM?MGimDWW)OLBHg)o(FZLH?qgKS4W_IcLyxo%9&r4eGNycIp`?>y`W|*B3VL%@D z+y>RKcLVeGz3}^PT#`pRjr)-m-5s7(>r^$b@HPE&0?`_<`-v={n@xGo!z4s|C)_ef0`7XQqw@0&~Xr2?oJIn z8HZYPZ>8IJ;&%-@*?#){N(rt+ngHvYG2nwxUL)n0)8$WNSlr zTY6AlGJ4v6>cqcj+lcV=N<0Y_smww@QABgg8Z0zjhn{6R2)QUCN&4rGm^V(@6GqNL z5xOw;BJp30;eGNg>4a4~cnmYX| z3ii9-Y94>fN#T4$c%xJLx})38f|m0y5+!yP=|90_@7?X+6gyRY=9rPlh?c8sU0eNoZqz9@*)mZ+=lZMt(k;a`l4fkD!}&cI4@-H66R#V?jv zXiA06cYE#=>^1Ehua_X_ad>xunq7l;S8-QZRo?fP_-439kDGg3RBiA?tVw~nF*7X7 z?c{5!oMlj&z;f-LBCAZTi#+w>c23`zp<&3s$oNVf`jPJz<0_iT1jnUFIF={B;)Pi} zL!#f^Bllj6zsDTY1GbTQpPlLKxSeZveSg=Lq6-ceq$K6tlo?j~=oG&vdtS9I?NOza zmr)-7aIn2ymUwc@IeJi?x0av(zgUk1(VTm=dAl1l_HvHqkLB&?8e*RgyyxfE#b=n) z<$_jtaJ&j8pSyM6+NAYwvi12}M!Te*3mpCFN~J&1kH$;HB?t~UH*peI4H}@kRC{6B z+x9QU+~2Zldh=R6*pp&6?Q>t3tS0&V9oyfVyePJ=HjSe8trh9tmT9xHS(ubeQ&Z5sxo3yvge7}-eU&pL)49Q8TXIB`9UCN>>O~r~GoRcF>uM){ zK<7#6OHr46nIAY>!Pr3Dg}xWnO{#D5JT%<5d9E5NH1AspX+1TVV)Yn~m6-;?M%tBM zwNJ`z8S73)?hd#8?_;Prcf~E!y+d+K$SRS9NVpr&Jl1WIpOTI8* z&10LSJDyQS(RGqDH#HwEwDr|z4P0!pIzJh)#h-X!Ug-bj&!g5xh6(heoFmnnc|M+b zZRC^wRG*RDvJP6$f+92Q^PX;xHHE`;jg=A?<;82RnRhAhMZKFGqIQ2Xp`A&aa+gAO z?>euNam_%n&9Th7O4OhjpPP31W~ywHYfh|CVuLMaS0+LrFz zJcROD_wY(GN{U`LG;c+b5M{FHm8UHV!|9{RsDheXMe$u34u$Rw=19m1EKzb&AG=s6 z)JS!&SS($WDT()S6NR z*u%WO?IJ%6QQ?~js{w#(5&(}}GypK?|M2IP8bKAM0KkhwjVv9E;38N))64fr#?)L$ z873!|%o7D4$oC^EJWt$IW<)4;;nzM*hc(lQ)tcW<3V^(1Q>wwch`@6qHhSAuZGdMd zA@Piu=(e?yLGrK^O^^*>W%%Z0F0ciZ(;Y7qG}KiB%5j9oUP2*Y-rHjrzKNybGm`C6 z#IH04qnWk^MF2;-W5wNr0~-L2yQ6qF3S9xKIcERsi{`On*XKJ1;r%uu$o=vEe{K zlf-jidIeZ>1?at?0228KPM@;@w)zN)DS2q-7tk@FR=bQu*$@~2(+|af+IzVGVjcqV zCK4dt6&V1zL=5_~KI2pIMPiDO5L7Alb4W#fy16aZ>bOG}%AwqRa=f5eY*QPb(;$7d zIX~ErA;ZbZByNbEFI>^N?>T>A-rPP)@zGTj*SetqxA?5PEF4W-F7_(rpEIfZ?Aobi zE7Gv=K(DNMs!r9Ri7n($nCz4m#2O9p(b1okSsAoE=e%EU)TEr)UMQJlZh8OD znk~J^reGMgq+1OoR&{IRviQ-F3-Krusf$vyo5eVvl~TNIyRuOYnjnUeHsb76&X!8x zIjndglN+hOI~m7NI8%x`vu)4l3kPTMq;otvQ)y4atUBb4WTt~PT7zg$f>NFerc+)( z*qJ~p+@oq*@m4Y{9Tk&ANHlMFkkIT;dNu6 z{k{9;-sszPZ+yJ4!}Pbj@V4vY`c>T|{{gkB=_VsH3{Fy}a8@P%`3bwXa8~v_JqI?6 z&BuOAab2R4DdI}e)psfFPdjmK^V(etPd-dZU>F=x>$Li7*UoOkS=n#6js4gk`AYZ?wP3AVC@4y+%fZG*D=l9~MBXt3-yzY2W^!+_8Eq1P{ zaqfDAu}%1nkXo@9W_2a=?Q##4EuDxOtF_jxd;Z-Ocf@aF4>zf2Zf+LJrg25=67`!& z9(yoPqXukNDXq7W-lZlQyC)b)N#OfQ-LtRZfb-0_`&nAvL4LtRUO@Zyyd1 zsd-86-R=D=x!`*<{aY^N3t)dc{DfRR)v;erJJC#D>FkBFwig;w38XGHLFDFH@cza$ z!dX*@`doYGMr7?KlUphS`_cX7SI)K&pCsS?!b!A9?^o^J^E~gs=19@p#^!Gf%UQLU zor!sOB`UZ3-f9&6jRv>vo|H@J1X4My%tz^Q0a^NlzcXkZ!?~Ydn5`&%1KT zNbhBKZHsNnQHwThKZTE~C|ed1kfLMHy0V=9y#@8o-nT;Z(Q``_R%0JZM7X^SGf-Z= zr>xr<-Ed39U>JzR>#pRaXMMC~=x!wU27l)~+IFwu!*JQ7VR{F1pGjS=*GOf{k6l9z z0jgSJ81%7;@vICh9yYdQnvDze)Pi7R5jIU+|-G5 z&d%;q!fQ-(+_VX;cmkEo>zdWS-+;bS*_yPhw%_==Ph87*R<*$mD_rdKxBM zqDvqOtk~>>UGH@fV^ofx`0jpUg7NfSIds9rm?0^GY?YLBbM3(( zW1nk0^@Z9`B`Wo8AG#BZyIgfr7;gJt*h?k&SUALYB&^me*v&ed_;U6l;TsJ+)=9V* z6KZ_1{BSXItfD}bA5<(v#qX}5UE!(Ch_qPap3=KHHYIeq?=GhBwxwaG74wG#w~>s~ z{^3d@X_q-Zp1X?;L!N!quCyrDCz(1KI#-XJ>-YwQX2JfZ^t5*z19y{MYI@>52t)=67{5#+DdqxF^WLtTkWQ>Dv~>NybyvX(bI@ z1$`-!J6;QS7W3V!oSHjgb*D=S^4-qjB^MIY@v~QulFDtF>3(^i4ztlC#?rf){V2UQ z#$f(^4>^50CC^b`=`_mG+{mxN*X1HZEX3(-n^;Kk{skDBY?mRW6EQEDN(tnwN)=Z@ zF7d3Zt{Lj=?rlxXTZOJ7@#p7O=ZOzEzci4XPbh5DoiF_WrMoZz%O7hYPFW)Y#xKnJvXP$R!v&-HeF5ms!HG|f$ zS$_!cc>Sj2@R&ZC;IlNHhArIo6hqJ7?bh)+SerC$RJ6cvKy28qqola!>H1U=)ybf# zS)wbw*xjY-<}qC%CvWS?c-gXL&gF&v2W2RHI`Oiyin8aHe5zyf_`F=MAnGS06Qe6- zcAV^lLA`bPonrU5`A~OP1!WGu(9tZ!`3anq=@*+g-W6%_5oc3Q789vmC7_b2b2b%( zZZyhAAMh;o$`^gKZ7FV5;iO6QeluzJ$x_)oPE$(|2q#)QP(e4TK2(V=qc!xP3k8mO z82a;Ju_2?XkjEu-jpcOI!U|;%Wo!D$#9pr=erge_H=NVJkuBX8Cg|N{pG}k;Zt9X~ zqxub0ZxIjz1Skt{vg8T(;jjkF=>$5}_^Czy(I1yh-0;!-+{`J@99_t5JfAM=tyGNk zr@E6TVKLTjHyzX?RbN$Jl0VfftlX7xD?ja%Py}!a?Lc^>Xfiax}=p)>D$;2jSn);Y_ zAxIqtRNJiwq_%hgs`r;V?n3KH1FAJ(Hk5u?1;AzFzm;?&;M4!0`jK=IS2NzWIjZ7y zFyOe})22O6rOkXgVK7AGK5QFds-q@ZUv(4kJ{_pI5$8|res7V|!uKxI9=a31OYL*> zI6!=YZK;w1c%;vrXUCB(>$YItyJ^RIcpd>Vo%8aosyhI=g9uBo8J6a=l9tB)cNWWvvFJ9;pQ6N;@M+ zwMCFAY6PU>NuKHS)jG-S&zZv#Sv3v+V{!mzXJ|^2OH~bk^Ip1NuTcpAIXj`LBhSbc zfK1=U_V0Kd1V9eW_oyacL_qH!LSHJIuHVF=y6dS-tXT-4-&VZEkSn+jDDQbfwG(^c z0Z5c~s(I7Ni2&p+F9jTn7a_p31l+1_F{(6*c12*FbBe%}D?wnaudKnTrXa9&Lk2;* zETFm&0lhwgV!LB7CU`tuCv-XufJk=)T(UIW$?sDT)OM}`5ZeN#A8kS)?)rv#=%aQg ztv*o0KuwS80w^6k4xnX!Gbs^3nvMd@&JP3#$Dshxu4o(OCvF9z#M3y`Z@qd>0LqXp zfYDva0NH#ZAh^jB0Db=3Nki*O%DN^ChV|uYEw;KZ6L5NiBZ4mF{mP@K&${GN5+(2` zDU#fN)K#j~L~OtV3yUuToqX5juzrgMK24p7Ng6e+5w%@>5uQ&z!L(IFb9(&Q1iI%w0$M-YBtw<( z@t<><{eVTD^S4#ZD-Lmz#tJCrnae0!sLf96GHDpC@wl1|5@Me&hhSwSyh}} zxLKE~DjuHFHe6&g>N?yv@TDtFaAXyK;J#CGgW`wWF8oC@AI;1Z$-5gk5~{ubxwB{E z08hwGB!s`4hcm%^)}5FL5qVCi?^EMqOr4RH>`UeA$lEU@Vm#MxTy6R}x9fvyzg&7J`DuKMy zdNN|{!O5on`idM9puXWWdYUvfrH;U?u*+|wvxl-eLr+W z+&1H@bdPUsV;nv?O(rzNOQJ*aRFL8T}qc2rG%%R`Grdj4;^_?9SMp!z=#p;@ELRSgxre_@|XZcz0Wlr-1of|Y>O z;q24Sx4P+_;jE$BogciJSCx(*=3Upqrpy|Ov+|ieN*&{;igh=Wj&5R$#*S>Y#YkJ! znw9axP{Uh|=M(Yj`GX_u=txgb=>hEO@2$NY?x~Plo!^5g3%Kcqsqs}}A20S)i@1GJ z%C0IiZOoOap_Eu()}C!^cyadR_RsTP-T}GAwB(6pHWUv!k?*c$A}O$`KFQhBUEotY zIe*=APfvDWqU%s^P@ZU8^z0Yg^=}j#&9rdVxJl)0uU#QAT2rJPYh3FhCYMxSp~^%( zD%@*#qTG6LZcByK(}lAe?Hlb$ylKi1WX%m=Oo!h`Np_;oy71f_PaQiDQfs5y7vfIl zIQbRlWLO?S5r3Zjx|p?Wn0@K*nP?H1fv&e~v;C?0Xl^0z1!s9)=aAXe=2)=ba{ER; zvoFocr9ioDFRI9q`72|CxYa3FL4-?%YePf*{AQujki^w*)OXe;*IOca=6vZk)!-uL zah`t6s0!_L;ls>feqDLmy-he-rB0KJUU-t0cxBt2#DDJX*)Kq)o4(xLxdiWu0ujeW zPY$(&k&b?^#xpylAtbA2x z>EclYY6TESL`Pb)b~CjN#H9J_9jJjmb17JC1j|EQNhHTgk4LxLwQR^hi+|dQi|gA| zB>k6v0^VoO`7M&1|L!9v?MwY=kr7|zaxqR_sX>9w5;HxNcU}FUuF6)NQX1`&ce6rG z1K#6>U_W{drtsto($)?Sf`Z;;*X3;ie8W}dzYMo5F*lZepyk~@Jh=86iqX)?Co$fd zS3aUXKh57C>8(>3mxcIRAj~Y_Ff!{e!lwE}kv={@27M))2fLDxv+H<`?wP&f!?zlaJ@y zVQKBgK$m5@SsRz1*s#x*q~~8Li^Y;Zzo}~l51!~(Jt&}0B8!EIu|DEB`li|K?O!bz7*SLl=!(N#oag7`>bNA4rcbCzA%7Chl+97$Qnu=rrhcVW$^pNh z%x;Plc0D-sY_}R1u^I@OTof{?hV%k1=Mr-3Oz&6*ut-`i(oI06X2w!$^cV-Ov*8&U z9{f^Wm3<-YSkhwTUT@d*$3UEfN1Agxc=r8QbJ_%7uC!kwCdP8=kg z^uCBs<%YLQ*1i^~g`Y`}8|lgd?@M#44#l?-JQrJyN;9(V|1kjU`twjb(K#?ae1^d5 zF>?#q{wJ&Qmc4Ui!tnc?P%D^s)nNerL#hnkUV>Aqt3=>64ZvvT^n0Yu3>5zuB(^{; z*Qkwy4^)*lu72e4Yv@Q@BL)+3;;hv5(K7}bITAXS4#(I-2CRsU zCMX!Ljb}h8tpadw9Mx=Lm49UeJaP#kpX%QV*Ha9T zt|AS&Aq@$C4(@i5eUlx^wD?dC%erwb3LJ`clsU2~Ev%4Za6`JN_3M8pmbC05RJ!VG z2D&M{JNJ>Vf6@;kx&85Hsr|Ug!xx;DF@q^<|Cr3NSmHe5_FN!4R9XuQ12JMi$qR}#CrO`1(A{eQH`%rqdh zWav1=%0L0MPrVPzeFmP&Ao~#GdIiR$DNEZsVXRV10#9$PSC{-r<56TxrXxwt_{NF4 z5q$+(>;g&V=j2-=r#Vf;$i=!$Glc(8m+g-dgRwl^d(K3iBsWfejcP^}`l!k?Yreh( zZWm6Voc2nzWS>5CMf?T&W;nW__jGumFWkRZqKVcak2y&Exn~NEULTYvBZkTgIvrI@ zPLmwlnA?FSx>P-8TzRW=MU45@A}y4;y7Q>_;wf~{FR8A7@Bn^P?op==vh1kIkLCX9 z^{}ela3ZWP0Pz&39=fKRFO6dj_uh0vW}eRXVaUsZLCq>kW(mCAeOBRcaf_&HrABde zoFn=ytjET);Gr4HNi=fbjBjiH;|1}zNgrM(3b+{X4ZX?uf9$;pSX0;5K7KNg7)U?^ zN{~@a1Oy={3WmX;R0&}c2dEkeU{w@RXh0m$L=cK1Vi;AxsEiI6lsW{#ARd%xS>@ArS6?|EVj8P2%(+H1Y*UGJ*?De4BiLOi!d#+}3J z|H|zA2t+O452!Rx(JRVH+UyB2gf3&MfFeq0d#3;Dqy3tgz@{G#+->}@n;X1cCv=c; zYh+eXlg!!Rk9J<~Of~R7tj0JzVTNCLxY)Xd15M2nE|Ko$Im8^v}mjzja3JG&#K{CqB0D#(BQ@me;rPMk!SJW_}4 z)`y{h!g(Ht2?Vx2eA~d30e3B>xJf0RK>LW?Xra@$-4MLQ3hYp<9YT(+78cAWQ2Rds zp@lJri@ti)>5)0Synppbg)v#7a@lA5@;q$Kv*XSltS(+)tGpsgZB{>*djH+2JyLmpO~$B3en_BEAvOf?)&ylq$V5w862Xe!9WLl+mw-OTmm921fp z9Xf#0`z{-TT~2ED!32mf&wVj$g+r+`Z+)`DZBo+g?)pk~Faeyz+6ECp&+9b7giyFz zxp5IO6=Lo2^Kj8-B=ZZgl{qiEs(6o4On>TR!!XHrGoOP-uS9snpmfbkv?8j z13gBS$;48p|0{_q%9>ALu z==UY4(1d+1ZK?wtib3#*HzSVDUquhfl6vp)s4#9 z?N1-8C5)9W8aDk;^-ko@{q^IYEj06&r7{k%!e`7|cF*_XZ{~$c{Eo!zss7*y5kW=d zn31Ce2MZo@^~cjHffMgyNR4lC+xnovx|cpW3~{fy{(6HO*&B>WoM$5qeGmUO&7LbZmR8w_Pg`#0#UPjQjV`rkH{Qh+X?Y zv6^&Dk6z;HcqLjEc`5n8rA|)s6rC&&*XWt*J#(+I^Qi)^y>|F_r-JA1%y_;fF~AYS4zTw1dE{d^ys-ECzxG8#ak4Q%nj+cr)UYbnmNiK9eNf#=FdL=au8qV z0;G|voMS+g0*5Ccls9()Ufcx`ty6_+N4aQVe9Q?=sz7K}E)`7yK}$TrvH;Rbq23F# zc;d}#R~o)Pizd^%WW-B0J_y_*g*y0-M2Edrig|QvI7As-aD=D@rsVvY-HO>E#+;P8 z-?S{%SW)K8JT3fHk&$)A@WVBL9u91$xU9Y2`(5uqWsP zvB~v*aORxt7lD&Z6%Lly!nWP=)cNs1c!=HEjR#8HQ@Zl`@7qCWUgbTHJ*J+&a20UU zz>-4+@w+0B0!us`N5K{uj?qEPRdGE@$UfGHtTaC%-kS1L+hkunE+iXxnCK_q+HCzBqWoA8N+-*#U+LEiIpe76pLu8SN+c$-!aq50 z7~x%We`ywVuvA}cWZHzc<1+u`^9Qnr8{@#p*)qD{wI@F|e-dpb1rFJO)w0Y_hhXH3(>5GMX^1s*-;$$a$?%kSM|ihZh++VCICl* zc@ULV0%n(=4}1e8>Gztz9hkhZ(GxXv%d+U`-kg}Uarsc6Ii* z(M+(l?T82AKbU-$CtZ8sn*+y@mekzVPjTciAmKe#6UZl<1gi`qRUwON7+@;FqVG{o zTU%b8}QmG%(l;ie$J)l)PyeAQ>=zwKrfSGGb#mGy*ldq_|0yO!nR# z8i&^(2RB66c8fLu!UkmFESaj(o^s{WGOsmz$PRlA^gN)E_{Wvm5cirn3qb_*0c2@@ z&e5jj&G~{yr?jES@gS2MwtfI(lDDpz0A9j5hfi-SzLlNS(|Vc?Lej>iQp_U=Qm!-cWCSOG|NBFP%@y^fpa&?;!Ke5iBwvi|WT05vbmL7XNXE<* z1X*61qF>%I?6@7A1N4%nVJbDei4I0sOqL6Mz_>x}OO6{HrXh=gAkzon6pAhZ|d9)XUDNxsQvfaM+8DK$20F1%tPy#{oyr#}WVl8O(6 zF6qC_pc^Xs<@o8WJ$0YOzOvoGRdUM=G{*o4vBK{J%ak*6Hpa(bK{)s^ivt|7rU{2) z%dF~FNAHeAH3*ptEP2{f4p7_FsA3V92kAFycsy9FaZ}^uiuLOFCGXUtJYAosb#4ZQ zh3Wc+xzP@0=q_qJ*ZbCr`>Y*LnRja9sVSoLzhg?|0^Ld25z})e&!0q7%!TGDIn<&@ zpJf{rL*88mM>3z~E!SWx2WAp9d5K?2v1D0?gRtfH5+nnuM<#=K27Nt7_z_8+v5YRi z0vQadP@2WhDQ8(^{zDlS%j%o!%SB_a?RV}9=dUa|Wys%UgmO9*r@*3_krP#7$6mvg zize-n&^1sk_IjFGY|vt4A{-_q%dGeS5I+fg?n8|%bM;TwZTv%jiwb*`%t@@}rrHU4 zcP4iDnD=C=U=m5zXz2A0pcU;S+H0E(XPvVqf4{II+=M1h!M5zqtu^bg5vX zinx3cI6%G5in9l!ihVp3+N4NuG*<${+`zL1t#D>pgyH=rcUKozfT8TCfCV<(2cGyb zkTDy*^avB4TFj#9)T|7Ne98+s_b)O_yXdvK_doapsVkLT8STS9-hao714z5sFl0eRp3>0Qz1TxCoXQN^z zCkVE}f~q5a2dTWaf}Sx(l{KGhGQtx`Tm%sIj{q))v z%HaVf@+I?t8$0I_+VKm^Zbe)!0tFfCd4yu+R3DNi`OU+eSzX@`=H8?-(JAc;`HVrYGkG>a)Mk6B#5M=?fd(1m6~5 z$}Ka-%%ne8ByRoXkdYdXD>J67Q0oNjv@#7lAt6F z!_ZJm{eiX@c(#PUx}CuZnxc_7XTHJlnP&?jSJthn>sPb^X6C;txdVNi-O5y}S?UZZ z5bVDrYp1pvmbV5GD-G@$Ce47C#I=oo;BdGN3Tm6i^^^U!jzFuo32~ik$Wx=XeVO>w z0BptoF7avdmb`#1_s|S6w>A0HzDrjimUTVF@z}7#;m5O<%v96lugkPT>gv>}EC;#gDf*BsSVS z8!hjK&GHN%6^P+R$h&^q76oFlLX&Y#s;-0Ei)p}@@Un4d?t(WZ_4cW6jyD-Q8_9g* zq|mXM1PJBkI0J>@nyCSt$g8qcU(}?EgUMB}kHTU?`Ea~ELBFX-v7I^?o_$nujk7xv zlN0Sbb|yl;QaUXwmypm+ekLQ}Qq!q?AQum0)>*LMe6$&43)O*jrdjkJPM?E0doUuf z38oP!+rfR`1+q|ezsdNq7KEiwguMk*Z(5iy_&Jsy9@C;&{uDVg@bLw80~)t zg?$2uUyoT)ymw1M*d3aa8Du={ZFB_Aw>6tMMt;Y4O8)O7bodxYPK(%bdL8%@H!<@Q zz)V&3w>{}4#0ls7ni+uQ(;+BOtVN~fV%yZ!8IxIvwl}*|SQ><2aqHaFZka}YLJmzf zzKS5kNSWTi4IN=&rGzDd==}Ykg)BLPDlPON&A6!$| zH^OM}EaoyePbp;WdJ+tvjrxV&|LZxH@?Y9=qi3v;C#%Y1ie|bq)XIz+>x@QFVTae- zk~HM{lLq{`M%IF&{d>zhGNZl(XJzq((osxFP9C{iQ>sq|w^mvtf{8F&n~VkezSd%p zKbVbV?_rDzC)E&-qt(yGs^g>_2gI}jrX8Loux>gO2LWEzcp4gT8vHyXs3ImZ{WXwH zeX<}R0mE;Cw5IwSL8fsxm>^{F-vRJ2%9g+qU4(hbtTU{^1eriuJ%FQmZIl^-*#i+7 zY_TWAOWJ_OZAO6U#Tp5GCLnPNL@U%l&RhwiJsQtzPxl6GBb1#$LC7M2DMz`FXL>&~ z3h%SHy&b07!9*=Ev(w5pohp7vCOaP(#k({$sr7F2UX+=8<5{B5g04?!!xzal=`V?$ zoK3&zG)SaAZxcPv!Bg?KINCo&5*Px2N~sbUKYH%Yq9OAEL*zd--B-R7Y`Vqfn?U!@ zpEfzBdeG8%a39f6o0z5V-RP^bOGcZ+|Cf-n##p?C5iwqprI~2oEgk zKN+~Z885rVX}}))UB>o{_#WJ3^~2J?0nh+^Km_CKzYLmdO#aprf>0bl2C9H#E>7gQ zhyJ|>AMCY$VU$@fg&?0P4VU$N3d4-tLGD99UPK4HAjV42J>=k=d_DvfeF@XZ&e2iw zfT#)v9sJ)PvKs2X7@RPX(Ios2D0DzLE8dHXu5Qvyg7Ol}%)~}n6Aq6+;3#O)09txM zTgLFRRS`s)cm$N0;Qx#{T2G&9R_7RP>;{q{-*n7i0+a`F&w9d%i*EKAZJOK-;8S4R z)!T~AtxI7#p&H8`o&6OJO$$?;i{jaHkRT}T{-(O4Ypp0l*Wkv=or%cIF?PqEVjG2$5@CImYlM&js#yp!;+&aiZ!F&p-u6^xR9Y@KO&venjT)Yxa5w5Q z3$SQDsZN%9dvkxO)}^gKgJ;K_3}=qFy?a=~+ojA^e1T10_sGXmdy+BG0%f+Q8M zdP)P-UIb1tr5t<xMQ!&@Cr#l14RB-|0cLo|A0VlDgx!vI0zmq6Xkon-vP~p<0pYz>Y z3wI>1{O)K1Bpco(_)Ph5(dx0AH_z1%oh1TQC1lt*p(S6NwMsjF2M;Q5?8r|QFT5oS z|AzV{&~d7~4`JQ{o+dTZ3nD&;%QD~=T(%-eM+#`^fCAvns)C@}FS^|wGyc%)c2Fz) zoET^!_=lFz&}6-$E81mI66R`5HxB#s9H!83gpA?99#1rS<|@}H(2zru_VD@E*8L)z zFQIz?)J+03@l}TeRx7<7`*=S->|8T3svY1KW091~!%oVHgYC@6Uo`=;KNvrFhFhp| z4V4mpvxd@M>Qq#%kN>RJzy~nT-;~!Id(c3`DO2(-8k|KZ|H37!9aA^{lVcjQ~t^fxpiph#V0 zD2PlXdB#{sXB#mIz`&?Jb|JNu53LQes0Nf&B>opjD%lr6cs4mAS!&wu?KRnFc;8?n zM{9m}MOK1-@BkWMls~r&7kZp6-PimZr-If7CKOzEqu7pdYMV3<&K@fs&R2pyb2`dJ z_)T#5fP6d&G?bs48g?;wro>mM+{MT*k$tTm-Yhk>0`3g&AEyWVqUz;O%Ho_)8B|a#hV0~% zYZ3499ifYyHCFRJjbQ}G0N^YXC1oH3gPaizh5wt2;9oD(0p#lYo8o zcd{%n-aq#d08-K*R*P1jsmVAquyMsh4?iB1NWlv(FkRH50wIe7*8rp)VuXUWcK#XO zG(dlusp?$r?7kNip$_^AuxJJmDO%tWv>bo-jT1kY>WxI^ZeXrXBEX%e+;|s z$b(lged+L|Ws7eEOF8@rs5#Kt^O-eM91OiRVJlqSHS!o`FsSs_xDBvLfDM@GJ zK+e+!DSfGzHV+d)&+d|JxZm~U`QZV{>!G}|)x%^^o9^=sJAZIk2>wI%fjIXH;sYL4 zz2USTUcX4ZSua8YAE@z{zWi@S0)Lr)1BU`zl+~!en+hYd7dhzPWHOLT_208DA7v$v zkB($&bI9HVQ|$2NRn$8T-#kB#y&j7&{1#S+Rs#UpCP^EjXr=2ffY!uP9{*8`Z@6wsy?X;C{VDY+>L zL?GPFD*!vl$Up^d0}D5eglpJFLl{DZWn}~&?1aL6sB*Z(6WJb8>;@MnAOixp0kFlp zWKl)f0>}Lzc=ViXEU18c+FIm*?*Kawa{?b_tyUfl{4>OkA?&27a3k14@D{vT_DdaX z^Xk;f@?VXRb2!LXMs9C@a9DK?&^Vg9hF!O@|tO~*qxS9v9(pBM|^LZLS?+Z1vprq~g=B~hJsRP@xg^Y#M zG(jU2{%dx0<&@&r-h+!`7&~3YJVhOoajT5CI$+Sn^DzN|ot`XmtryBZPK!=A2fWDt zyhad(JzR7!U)<^iE~@2OuPO+q=LwS(5OiyBfanGJUw;9dQn1vnrk0n@*McaabH7YU zAp9XCA*KBDVsYn~FH)IMimUh^)G}3hCxnJ}skY5B+bW5*;4?VhU*`#i6N}rDpZD|4 zJy5~s^l1Lv9LF*jdVKYQKV$Xfaov_^Fo;<*L51J3y48OavVgH2n+~%xoO_JI=Y@!IWUX!@u(o0$`+ zuZ&8yXit1qKSIWCe+DxK%yT|Q)h2H>5TaVXhO|^*98$LZ^mn}S2FEMC9Kxq9kFFU z54#2P)t(DPZ6~0(1t|R~h2h2vFrmw|Wplnz4 z{!J;PHSj(ARJC>X50#9#%eMm=hkG=n25jqCJgAIST=JxPP`EG;aFDhdB%^-L1hpSX zt^k?G0MVa<0@E1Gd0KDUwzAbJrPamlrxgCWACegWN>N}tNJ2okZM?H$o5@RIlWM)Y zz2r+ZVr-~*t1>|f8w(+e_4v57>D7$3ey}OTytsZ{0~sf^#^O}6{*HowKc}gu;Cg=s zHTp8GQDD_#WHLr57aL`&*y)Rn;X+Fu3m?Wliw*>Zfq)0Xb+QE^8Ajc{Z;`X(?HrQX?6KnC*>CGL!+nZq&BLYP^u#FOlv*6y}0Z;xV>h4ONDN zQAX|!&2RxY$8=y6@{_mg(&hcUJFm5^iVl5f{pAyh9Lx@@8=sz#J3We?f##Q~-2e0h zpE&UQzMMb)$2cbcq5@_cG5KbHh6b?}lu9X=Hh8eV)S+l7P&&(m^Y^*{{{~)PRx5CD zBwR&G*c516avcByk=uH>2;c}UK5W{S6?$ZKLJQuTg`$+ztxU8}PB2f-cw+G=w79sB^bOlsXUF>tK5(u1t0P$iX!SaQ$OPcXwtQMBVYZ~hTYWtcr4+6Rpkd;H#HfidS z{eJ%ajGC<6!k5Tqys$sadi|!J|KOy5DCgxnfScI4(^2r_fL}=7jU}g96jDRq{9!GO z{?k6={kcYT!cL7^_RG2!%KxcLvwuiSf0nBQjQx1>VVTbNF-g#nXeUQ z|DCQ9FD?%^U!nb8ffyg0_B+HF9wWQz+(-ukE#@v<;eZ{nh+zJe6s2>foEFk@c@nuk z7+{Hx!`oo)1np%WZUl!&&8{?Oj;++xxqFYyfg&*as3k)| zCr-5`=REN|b-&Xn=R$bYoY=wj#dox&>zC1*rt_9UDU#}Y%yqX@$$xecjSX{8Fz>b)wUTH!g-9n#pyI-KL|r8T`R zi`4*~b#S>g@dGFcr@ZRujJM$1p%VEg@fegjG->y=)2r$)HG`JNZ@teI|D%EM(aTBW=hwjcFM9Rug9n^Yq@oFng# ziaWrE5ych8`m_VycN@h-{I*KL>*gx^)pGN1yD*ev0=n(Eht-bC8xjT3%qJXs(l9}{ z?-yLB{bhk9F)N>O^laPAGMDN+|m1B|I6w%$VZ>3NXRSXV*gM0NPihU|B#y3Kdh$l zJG5c=W+Qi3ku({((VxBe#~_AWz8m24t(+x`f7w5aIF=|kn?`(b7r!40Z2M;AzLIX9 zGjPTeq0nDPVtb(?BcMpGD+xhB7>O_lA5St|I_4(j<52xNMu3YE)t;RWilf$g`pXvC zk5L`AG^tI5*|;u}1*~y)FHDibv&;}1gq5FjeNVLlhGu?{TWFm@xyvD`y1U>)7s==A zJ^J}FR9E}&O1JRXB@5=5rED{!Zm$3Mu9pmpV!HariPKSay@_~Mpm)aQmdVcfLl?p77 z_HqKI*5^LUFDI74IPS91G?9V1uR-!z$X>W;f$L@0yHiosBA>6k45BZxaNiVf$#1OF zzP*xIaS{{0^q;phsX@4c>8)=sF6tsaTY{nt7U)$uUir3T;<9tJ;&6jMF*J;b%+B{a zfVGMLgkQlroG`uy#yPwMDHw#n&`ccU&b-(NtW6Ly1OCs@{8hDq|34U-ejVe~oJ#;C z1cjt6I5?Xaqd*H?y+)FV2s2MnXrA1K$gX(8rMnyi%>!T|oX!5y3>HVOmoSzy_Rd&Z zvn-yj?tqp|^BIT; zw4i^(7BJ@ETmX4me;mL8{k&%8i{+q}RYl40F%y%6N%tpmVDa6PN_LNn_P!7BbT;@I z&QztGcHvc=l*SYov!|RDQGQ66&)uQD^*)9l`L^b#D4X$w$ntiddOax!qLjYcu(?rq zX6?>R$KaHvTGdChF6!9>o25~!g|5q})GOjy)f>R?fMQJDnx~Z7Yem!8Z}MgSK}i<9 zK1@OJ+Ml9|U+huZ7^)!h>eHyzslCsUAP012*_4L6)DxJ29q8B4$Av6P=$_VkY^rI0 z#`4u_SC$^AQ2yMr0QCqiCq_h(a2Xl=2lzW z$*8N`YxT>7;UB|W`MpOOb=g*;(o)IyTyZK;Y*nYu&uzjEsM{Pd37g81+Cq4O1 z_F=@h8~_f&@lVNz--v`N@EOZIj9t{u$nG1kr9qD7H+2#JCOq@km8L;ml#f!sBzf42 zfgP|F*?Op5hHz^yrsh+J~};9KoSuoVEq`m0xn$IZOr*9TmLH?N7X)N*dXJoXQm zl@Z0a(c5}o4^NVut9zrSPB?`Abv$p3?u4l7M}}iSUA6~O4IkNpHyHTDLtax+B{wzs2WoinvBXTDqOX>iW3A30|atI5PKNr+gyinFq_Dl?sWf%96n*8 z>-*KexkZ2UXVR0!7scCdS;Q?O?*>+l1FCbr>7q*Xom~lV$vpy`FaW0-ehD7^4ngyP zN2#MA7B~n&z5!F5nY}QFA2|WgwE^o(QTaGJ4+1p&L1mvjabW@K)=F@8i1ISBEhQTa z*)*Km|IkG(Qji(I?IC~~`1qF1L4ZF!OcqcO5JyE=LXf@yzy9B4HM10?W(RP~`|so) zeX#|Ieuuz{`Y;@KT2=0J#sU`L&2j-*CmNzDQcnmJ15pv?P^W7Bc4fKLpHwzT^jCwE z{KP`^_@u1=dm-3QU;f7ejQ;&|0o5X-uUuFUmuJFbT+R&h<*@9(%N8P}zK__F;<$R* z+o|^79o>8NnsW4*4FLU$BRuD9zLiSzj<}TLTkcQ1)Gl|t*yyR*JkGdVY;oe1uQpsX zHg3*d#-Y1p_;&!}8r*o7JX{b4WOsCB*6)_W@7O*$R|~jm`w@DZu^WKN0k_;iso8D+ z-4VnGNK?n`ALuj6hY7nt1?Z+UDg?;hIvz3x_}Pe(MKxdFO({6XEK>;1A#YW9Tu*%% z70m^rC}l1{U+zS1Aj#%WXXJ{B&eD4P{Uk+C{=EmTip*%w+c z9IatV{w&WfP=W#%ZOjHr9B_(7SuUaYtR9=>h=}e)d{nEM2le3IIq$X-eCZK#?HG>kpp^%we;LHO*a@5Cjj>;H zAcJZl{x7gOXRM>aCM9aVr%O1J+x@j52%W_;2AVR1U(5KRX4Vy^YgrJsLzu=(L+tGM z1gj-QtX)l^u;d(A?IWUBgZiFuXQ69n{BRXebL2QghZ`XcyR26j3#1UGJ(O?ePA~-{ zN!SQ71RE4c2%woM^;m&#+J8QWkLI!13^pvWMOD2)Iq5^a+HDK_Abp;bhwPlrfnQ62 zIwIJqlHnY3Weg(IhXAyFi%F3&YtFVZ!tAfY* zk*rXSgViScY^CG#0MZ100xl=@dqvC#q&5{&foB!Bl8ItabF*lOY^_QlajBWm@0Fe> zTzm3Q?GSPVJtXAja6^M6GfF_=O5sOw>o&MjtIzU$i7q%?xJd@g{)T-oa3i~<6Ya+-^U@%eA@li zuA2?U;xL09#+I|=&NK@2VXZ@jj%@7lKRA#7@G_+T+n3?p=$Z6C9N2~Jpz{V*xEwge z)3*(4*(s&_|CYC5vPc>)3A3bJdCfcGjh4}?yf4!}`XkcITeTlNBmuJy-*|ZZC>g)u zEel~HvVvqWso>Mi|Lm+mb>P1{ozcay(^79)4ygmCwnYvAS!(No!R{3W3kn{OgT{)p zXgkfVOibp(7=Pcl)N>BUm%?)FJs02c{FoobR9KB_)B0HW8ChnWj)|TD=SIjN@ zowDE@A>NLf>E3`C{;#d|=%0VQ*#>z{GKLEr(#k+aYZbE2!M$;YxxxSSw~;t6feR}( z!vOYs0m|w0OacMO#{e&tHMKxF>k<_Mz(oZGnpuEAY2x*3!1Az+yfVfl$0Skc5bryZ z&k~e#o~b_n)mvYJT>atc#l-oTTuHJjeaQZ6UeXMLFX{v;a63xke$UQVl6vXK2AjM~ z-D7A@i8E*7H|sZzxyI1C@_E4a;zHCVetNf#{(fGDgxjRKY{7@Kbs&u~0QHGn=NpmB*}ftM@BJKt+8(4LMbOgim`bhA+* z@Dt-L$rvcig%(+@O~#7RiI=EbFkA5{xWQ~xPv}tJGLTG837?yCCG)78NAW__ep|WQ zW_7tOmc5GEG1bAcp-Iw1<=4gwigym~j*e`PvRS5EH;HkBvC}fkDWM8f~ToFGJOtxjhyiUp`>3`mKBaSd}QyM%4TE(ubNE&2%Y!*^Gb}!Fu7r zy}dWv4%YJ_F?}#{sHS(P3M$DXsZ-;uQ2_t??DXPy(kPXLZEjj8-lMALON;p?=$R^S z-m;r&q_Z{Y6M;Vy{Wut{~ffmu=2*mIAn3>Pu+~-;d0l2$!_tsmVsOFwF~k+S_Zq z=$&Km;ub%b@T1QXW+w@+GQ>DuH-_Egw`M#BYQYAhLR~B61rv<*C+we9U(CdDolffq z9(I{1*+$VhXyzoh9ImYiT+l;W1 zOBg-TrYZMOp--G}vYdnW7z<49q{_P(-vpZ&_cJ$-m#E&8wR$j76(*>k&g`+;nHsNg zNiAcsp}AA5SNszfuA|`BU1vqw14ek`Lb-3JL_H~CUL~qsSI5pEq65l14lJRmU zku>Y{%A+oJgbv-0H4M&cXq6x=aUPav>Q{K#oJg@qBelMK$4d{I9y-Vjb`^$BKWx3V z&S54*JCEw`{ZSw7`kt0>Ns@M29c6UeHtVWnN1V=bCTgxBkY&uiHZ|kN zYU$W!PvVl`nYjL&<385E4JjJrxYvyh6-ZY)7xF_6#n2>7&6480BW+2(6z#qVP-mDc zQKy2RUIsak+AJ5pb)_)$zi#9hn{$Zqq0>V@SOlF?F`7Y_`VO*|V|SHlzoD@r@Q31= zkoix$60ca3x98mmumW-;TfJ23Lyp(@PGss^<{js%S4qcosh|XwT6B_`ICGW1gO{u_ zHW~__TL^{h4)-^~LG#ggw=uKCE%_S^Ee_nL$y1Ya8m~$mMp-@9oiP2yU zK+DIh8}o6o@Ih1OPtcZNgJhz*XfWQnSGHJ(W9Yt3YQwazx}hcKGY+`ox1inm9OHer z7MI>Y6*Y~U-pqHXPaMj~)#P6_bok12_llSvtB64_yXdzoaw~UST&a?Ow{DzCl5Rc5 z`P~|ET+@u8^7IZ>4kL~!<+&0fe`LM)bpbAl+W#7~R6TYQ zL-0+)$nH&-+RlJ(n^4+*ZrrK@3=nDG3j?W}y1INO5yiJlm2{oRec$McD&EoE-u7W> z&X8y(29@SZ7)m)7gOg81l?qyzJJeBp==@1(u=lH(P)HtE!p{npTNaRRo{@FW+V{Fa zOP3U&Z=7GV(mPBqk}fE7d)t(1)(J5%3F!7KJN)wu3-9DfH%>IIv!d&eERxbh@jlF$ zX5%^w=NWC!r;3W4$7;-RZ-m}VZ<8+L^4AtdkG++jdpPdKN^ea3W_KBRD7V>pX4bY9 ze1@-MX8I3nQ^P1x2Dfc(pz{_8gl!fA;!r!~8^}gH})N};} za>?Iuc}3+(2W9?ZUgzWpsdRRfe{pv1lf}JRZ!L%xdyIqDMYhk{X}t7}dz_AL(W~4LAB5gH*>9aNE@HOY0P40RHnIRu;8yI`?6$V{ zlj=VFVFKD-(w z>2>MsCh$v&qeQM5i{iLZR*63BV7cuJ(#>dw`Hn#C1}zNK>WP6E(iX4jxJtDG^gA43 zRYwLr_ZQUM#;7>|W=MlOYhx%o;rJq1H2VX^+~8CnI|2I&Uq!DAM}dxe&bNZ{WOq-z zeWh9T!Hy^`yRR9))^vG!GO91#=!uW;8Xu^ZKV$h1uF$96R*`Yc3U*7>w4;rg-p%#7 z+>LKd)TFO<_zaz5S;*OYByPuq%UGO_Oy9{YmWf`$f5=>x5x&E@^v33gySEqDbuM>9 zvzD)mkac7GA&;Y;l*={bx>?x7G)>T4^*r4>;3 znl>XMEr6+k@eM{>^S(ILKwHeho2}VJ-a$#Eeb3fX zZ4%}f%)`*>I;)AiBPDgn6mJtut9nsKfz%jhdmCf%blt)X3z7VKo7@Q3?v$l@yy|Hb zMCSX}S>;(bp4i8q`BC<3UJ6utT|~+Y3ZUdZT_0^q_G+uULWJ76m5Cao6eW@Ay;r<5J@@v<&&nN_)|g~ovn#wQ!%KI zbIe)~?y-u_k;F|?NgP~V8BEkA?+&$?Tb*Og*{)hH^$mEqvdSa_Ey(npK}B8SyIXUa zTbxQaoz&0&N%MMvOZQW%ZWMuNSAc3U$6 z)n;a)*qa}}cCC)$%+()=9W=<%aJ@T?U6fWWd|>fn?9iKf$K*SO-*=4JP){w1n8mXx zm88UChe(*8R`$v=)_P%V+v}S{zEfFGVTL4k?(|PLy62xCu)Ik9c8BH_Z=96Y09`8Hd?q+GpFo?0asnW_oEAI zFz5iUJZ>fGHfXD1^@#Z5QEu}^AC-!e#!*m*aotDB`4a?8$T68=?deLZ$O)A}QM7ud z^v0UGD)}2S)FpKFKFoXanb~PS^W_qmhsVr#L7h1i$A*rE#vWnaN1?NH_15b+%k*g$ z{3&|90}txHJv9LFK0+_tYkYh)oF14t?KJJPr&X^+`Ndr1Ko;s@&L0ZakS6Hw%zYiS zc@;#GtZ;{HJu74xq`39i>%?&t8z}sDtGPSEBYY#53t??N_q# zv2I*i;!0Qx72Gb>c%W9ML zSfOLKB{kmcx#XfB+s-L-Fc`Iuw&kN%&`A$^eGXkZR*hwgeLD3J!*&cxpDJuSGrLX$ ziX?%BNn_U_u2LRlE_W(6>1feE7A*_On4SLC-1IJ{^Q~tA-AHwC`Fb6z)Hu{utiEuF zxU*%)cAehJ;~iq6-7iN_-FC!w{m1Fy}HeDt#w7i z-%>=!Y=rE!C2>q)sHONRzt_jB>dkb>-^S@V9fL0r$Nhw+t;1e@Bf<0@YS|>R7~FpH z#tu+7C@K5uUKo_Bb`u>Ea!3#@=_RbgZmDNpAqS>{Hp)3!FH#R121i_D~o^bAH;R=iv(bKbgeC}EN`k&^%pmgd!uSVpg^#g zA)&8r1C0C$(f)fHP`g+>qU&X5O4YMBa*KKrI%A#9eKcbbTc2@554uJnO)@6uNcrRM zN@@2PIj1|&?3<^s?WXIJMHjl+Wz!+@H9mC)fnVf(NzF;5-c+mlbjmw_cRL;Z$O+gk z=xlC+R3khjX1033%fem#^*MutJyEV}YZl(!ca7P!Syo9|XlmsuFMb|!WI}b_wLv$t z2C1&0ykMP#?hq4ST+_+eq*aunhowKyYT$@}NEGmYwtK*@w6)#_F$W%AcY$6_pl!!- zA0I-`ZRx4uCQ6?$Id3P757#=S1FacLY3bQiKbuo@V6wEfPV{|4k4=WzlG2T`^lG6z zHeGJjTfhoUnsC`Q?Z7z~H4OKRgBO(=pe0cAd0lr;2qtOHMEceXG)=R+FFpd`gQR%|dRDL)LyJeKT!Om1c5Nsocn zpTsvO3NE^m9MG6;UZ{sG<}~+PPc4boI+w@U`P_oeUcwybPXCCxfx|rC=fSnvl=^C# zM>N4VE4JB8=a{V7vVTzJK)40PB6CKdnL7Hae0gEliTFk@(p8#aOMuylZei}F)t!TB zKhXJs0op2eKOBpo3+W=u7~e**MraO7emeD28={LQOT8D3V^l|^l-bybQL zhr4+TD}ze}F;62$-}1S{3tn)H4g1a*H={Br#B);5pK^&tHY_^nCk-^FWit^{$y$a9 zNH5O7gwIrIz;>-=Rr5ofb?yeXQOZRk3Z5KELDdmZx5J=2AKB$c7Z0LA%!4YqqfK7O z)PUw{?OuEu8!pK9s*D=DxTKPUA!@tGTx&&B>&?IIT>E-j2ehfM*gby|d!aYJGNht3 zG11r~r6~n0Iw+|}5{=v@p4B%fnv=Kyt3&phvu7LEE30j$`}`=CeYNLN@jplB`4?N} z(z|2rhzF#OQRYTt=uGPL4lCeJEV@@yEQBFCzI0IWsE|!6k;faNl zm&bn}wT(-Qn)z``j#|cU3I68An#Z`!QPwQKHmEX)CyX$Tnx8X?#!KW&GPi3>i2=F~ z?$NN_9=+X*N&HrJ#&k*WYHn=re3au+HtN~YPTSj*vpO5J8yN`7Y@WI+}lLwj1;@w9G9Px|5Tg-C69VHH+zQ zMuxU6&%K1lF?IG}^mZ_QHIgtHsN$WNCW4@%d8$93jt{%Y;qk6Ydp8I=S}y(m-16L$%h64SPlF;#wS%<@3m;?28HtW*j?8TyyM=EU9GSlP;3bIs zK70~i7@eoRm&`OsZ=T`~)hweYMT9@UU@5CjBhP(vswc6yUlnREsjsN8oKW@Ag?!N) z6GS&Vt4Rs8BdA>Y7G1m}?Rgr{>X-f7GB8!@=^pik%p*A$$%11C0@Jk_M{CARj}6}1 zz##FDhAi%F2yOBGwLxlOWZM%z$T3elmUYb+=etv1Gs>;XcojYCu8l~$@oj==28Wtp zf|A7AOh7vZU0b+}CBdcQo^(2K)%k5d0We~|nY5~&E(++5vM8{lTR2-=OEs#7PTq*+ zj%|A>m%I=<_ipu5PtlPtEws#8qNe%i%SJq&S$;)un8CW517Zck(rh`sj$4m5G zqau1d$LfW2`}GSDajem}>05nC`=ka#gp!Bl*~hN<1*9KTDdO@SEa-WTp>^Zy@PnN{ z7uMh4rm)|oX?3)=7-jL(8_-wSndMe58#taz??V;MmN#Rc2oF6MYfxgpBke=Q)pZD> zH!=C^bcoYF$N{ADatz7xSoD4VBcjUg2zB{-sa{^CWU~f4)PzE*rTJe8kcK2DzFlQ@ zxkeV%(6Vb0%kP&X?fANhl*=;T+f~ws%L46+TCN%3998VH9U5BI7FMX*WyE9gEU&|f&PGJWn z6?CVBfi|91zm^6%@R=T;(Rrk~+a}R%2c5!gGpJL&p?>1P;Gy?5E7z2|IZE*h$>N(I zGy`W&#dWBz2oeQgx%h=@BF?0{g8CAj%MOwQ-W_xs12WYyNvpF(PJhB=l*LB(KY-D6&15@PFUo{0~;Q5|N-u??QPde`J@(09dWvrS@1>HR^sX~rrfdD4`R z`$TgKg`y_l28E0$jCaQ<5`i|DCqqutFSuAQso|Yv5|f@?*tHUuZLGvmVNW!*Xup zWt1gEyLrA?bz|SR&}`if{L;lAhT=m~cQ1Ntdeqc#fh7SGdH$3fm2{^=V{+y0*KAbe z&`rHPP1wK$QG}`WJ?9iuBK8#oeaQJWL6CX(xJO_+y3IuM;L}c2Oa9|jQOhR1<}GJr z+qUD@uF5dH;Z@t=%T0~FXV<1Bc|%MSq4>Yp`M(dptR`3xs?e*4WlZPQ^fwxv^q$U`J&$Q&JE+U6k~r8e$W%JI;d9z^ExzKSC@ zj#ZWwmY&2py^z9>#X9P0M%uYdJJykzM0Y40-MyUGdA;sGaPR-{{eC{5_rvG?SuE%% zfk%bYnE{NKeb{ya=>Ofq;7jV=_!;z4i0OT;VSyuH+Zq%+z{RUAGtgP_{|E*nrDEFi z=!S_^{j&jGzPhRy&Nc`&4&5sBZ!&_3mm)y2ZsZ`?AorZ|r#GV3IJePlD?$r+4R?{zsVIxIxcG-|+Z1CVNX=JVdA z>N+$wk!uw{ z<`?0ri2OD#PQYcOG$7h=7+HH)$4mz50=O#M+IrfLLu9Inj`$Oj^on73BVBdW+UGn` zqK&mPSs7>5t%o5XC4%YPr!A`l;4j)VH>^;Hc_8O=b>$~xqXfX}4JuCij8rehltxQu z=k(ZV-C*<4=>IveiKtBY?G>fZ56E@UvE|^v4I74$UP{p=d>1P^oG0+V#;IQo&)DQ2 z9B|IY0!XQYgf!kSLu#Pv6%F%&pS?~0JI8cBl;F12oLyQqbf$fV6?kO-To5EQwd}5u zrnVv8Nr~T|l8x3Eta0CLiR^*0A;2&hjmN)XI*0wxJBLHm|8y|^y?yowPSPG+#81V4 zC_*u@QQP!@kWfPJJ3)9T=rU*Wh@#FS5iQ6J)G6}M^*um!R+pGPl=j zjY2QZSBH>K&k0n#Tb@%k_pIuaM}dl(iwx*Jip?D9yKN}hg#ox&IC<3*vyb$n2 zBc?Koo?};Gw5Mhf^Eu5Npa@iQ5kbA@=A^oL#c30-*W{g3nmXVAeo$Y0lqwzANAb^3 z>9_(uGyz)>8Ci@NHW)_Lh#EU&XG8wNG?Zc8MF%YB2en^W zxblld$!h7Lqy{u$=ykt5#@kS8pa)D=31_O1tyCLf+A&v)gv_824%1*PV-N$m1ash= zfsob0LN^ZPB;>sO_fpvuO5!+m`fN!Xii0U8cSR4kd|LpB$pHR`RJQkoR)5R+y{X@1e*r(BIE4Eek2C$wz%3>_HNr@wuEs)y6D1To*0GKo`3 z@Qm1+=@rzID;Vbfn`57-+=QHt8L+bswIB`pzLf1dyqxXevP1Mb&B(No@$Ak5`#Azo zS}s!MpP;>(GQit1?>mnvJT`-~FJiu?9*7QO0{u`TBsSjfWl`T`wS4IQMtR8m{43E_ zR7zdhAgA4!=rzO2DwM>5QW(!IQe-G{InU-;$Bf>G!X(?t%ehs_33ohu4)sFp@u{Oe zY9EC|)7G(Y1E$`YVUFBS=u@AOzdbH*prW>s?7Y`Je%4`OlkRhW*piV)Q?C{dKD#$8 z?+R{yE2DmFz}m{_EXJtOo;gQC38w{mGSDTIExI3x8d)EICSrCVGxst2vi&MLLP3%< zBH*BUqI@vl-~@&;`set_ira-L!d@n;)a{;ER9l;Ee_hj>x_zjk$+6$-78Av_xyoey zuK@45rgXLm7@KIrqLn(R%4lNNo!M%+6E%^zTZ+A1*GAkGsptBjcGgcqB6}3o$Y$DM$8Y!!JxrzLY8TgV5ocGAI>1u?+`4&jzkH z!4SpUl0pY?G?`i&lK+jPsdd`!lH7aR=Af$<(U`oGeDa3rkB?VeC!!kMtT$t1zz7nK zjp>wPm2JCABnOIJ4Oe?&h&T=G0n;9elDr6d-DQZ4?9H*Xbp>bbzc9@y{xMvW*{$vy zmIu1V=uF%0}t$nPa$s z(jlF?-V5d-`_AW{j^CyNIxY># zwI8$6%p#gNJ*SSWot&C+9J&z&5Y z)UP Date: Fri, 16 Feb 2024 17:01:18 +0000 Subject: [PATCH 4/9] Added LUC child script file 'DQRoboticsApiCommandServer.lua'. --- vrep/DQRoboticsApiCommandServer.lua | 188 ++++++++++++++++++ .../cuboid-inertial-parameters.ttt | Bin 251664 -> 252171 bytes 2 files changed, 188 insertions(+) create mode 100644 vrep/DQRoboticsApiCommandServer.lua diff --git a/vrep/DQRoboticsApiCommandServer.lua b/vrep/DQRoboticsApiCommandServer.lua new file mode 100644 index 0000000..1e5666e --- /dev/null +++ b/vrep/DQRoboticsApiCommandServer.lua @@ -0,0 +1,188 @@ +-- (C) Copyright 2011-2023 DQ Robotics Developers +-- +-- This file is part of DQ Robotics. +-- +-- DQ Robotics is free software: you can redistribute it and/or modify +-- it under the terms of the GNU Lesser General Public License as published by +-- the Free Software Foundation, either version 3 of the License, or +-- (at your option) any later version. +-- +-- DQ Robotics is distributed in the hope that it will be useful, +-- but WITHOUT ANY WARRANTY; without even the implied warranty of +-- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +-- GNU Lesser General Public License for more details. +-- +-- You should have received a copy of the GNU Lesser General Public License +-- along with DQ Robotics. If not, see . +-- +-- DQ Robotics website: dqrobotics.github.io + +--Contributors: +-- Juan Jose Quiroz Omana - juanjqo@g.ecc.u-tokyo.ac.jp +-- - Responsible for the original implementation. +-- +-- Frederico Fernandes Afonso Silva - frederico.silva@ieee.org +-- - Generalized functions get_center_of_mass() and get_inertia() to allow arbitrary +-- reference frames. +-- - Removed unnused inputs inFloats, inStrings, and inBuffer from functions get_mass(), +-- get_center_of_mass(), and get_inertia(). Also renamed some of their variables and +-- added comments to make them clearer. + + + +---------------------------------------------------------------------------------- +--/** +-- * @brief This function is used to test the DQ_VrepInterface::call_script_function. +-- * @param inInts. The integer value of the handle. Example: [1] +-- * @param inFloats. The float input value. Example: [2.0,3.4] +-- * @param inStrings. The string input value. Example: ['DQ_Robotics'] +-- * @param inBuffer. The buffer input value. Example: [] +-- * @returns inInts +-- * @returns inFloats +-- * @returns inStrings +-- * @returns Empty +function test_inputs(inInts,inFloats,inStrings,inBuffer) + print('----------------') + print('test_inputs') + print(inInts) + print(inFloats) + print(inStrings) + print('----------------') + + return inInts, inFloats, inStrings, '' +end +---------------------------------------------------------------------------------- + + +---------------------------------------------------------------------------------- +--/** +-- * @brief Returns the center of mass of an object. +-- * @param inInts. The integer value of the object's handle. Optionally, the +-- handle of the desired reference frame 'df' (the detault is the shape's +-- reference frame 'sf'). Example: [1] or [1, 2] +-- * @returns the vector of the object's center of mass +function get_center_of_mass(inInts) + if #inInts==1 then + -- Retrieves the center of mass in 'sf' + _, H_com_sf = sim.getShapeInertia(inInts[1]) + + return {}, {H_com_sf[4], H_com_sf[8],H_com_sf[12]}, {}, '' + elseif #inInts==2 then + -- Retrieves the center of mass in 'sf' + _, H_com_sf = sim.getShapeInertia(inInts[1]) + + -- Retrieves the homogeneous transformation matrix between 'sf' and 'df' + H_sf_df = sim.getObjectMatrix(inInts[1], inInts[2]) + + -- Expresses the center of mass in 'df' + H_com_df = sim.multiplyMatrices(H_sf_df, H_com_sf) + + return {}, {H_com_df[4], H_com_df[8], H_com_df[12]}, {}, '' + end +end +---------------------------------------------------------------------------------- + + +---------------------------------------------------------------------------------- +--/** +-- * @brief Returns the mass an object. +-- * @param inInts. The integer value of the object's handle. Example: [1] +-- * @returns the object's mass +function get_mass(inInts) + if #inInts>=1 then + mass = sim.getShapeMass(inInts[1]) + + return {}, {mass}, {}, '' + end +end +---------------------------------------------------------------------------------- + + +---------------------------------------------------------------------------------- +--/** +-- * @brief Returns the inertia tensor of an object. +-- * @param inInts. The integer value of the object's handle. Optionally, the +-- handle of the desired reference frame 'df' (the detault is the shape's +-- reference frame 'sf'). Example: [1] or [1, 2] +-- * @returns the inertia tensor of the object +function get_inertia(inInts) + if #inInts==1 then + -- Retrieves the inertia tensor in 'sf' + I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) + + return {}, I_sf, {}, '' + elseif #inInts==2 then + -- Retrieves the inertia tensor and the center of mass in 'sf' + I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) + + -- Retrieves the homogeneous transformation matrix between 'sf' and 'df' + H_sf_df = sim.getObjectMatrix(inInts[1], inInts[2]) + + -- Expresses the center of mass in 'df' + H_com_df = sim.multiplyMatrices(H_sf_df, H_com_sf) + + -- Formats I_sf for LUA matrix multiplication + I_lua = {{I_sf[1],I_sf[2],I_sf[3]}, + {I_sf[4],I_sf[5],I_sf[6]}, + {I_sf[7],I_sf[8],I_sf[9]}} + + -- Retrieves the rotation matrix from H_com_df + R_com_df = {{H_com_df[1],H_com_df[2], H_com_df[3]}, + {H_com_df[5],H_com_df[6], H_com_df[7]}, + {H_com_df[9],H_com_df[10],H_com_df[11]}} + + -- Expresses the inertia tensor in 'df' (R*I*R^T) + I_df_lua = mat_mult(mat_mult(R_com_df, I_lua), transpose(R_com_df)) + + -- Formats I_df_lua for proper return (as a 1x9 vector) + I_df = {I_df_lua[1][1], I_df_lua[1][2], I_df_lua[1][3], + I_df_lua[2][1], I_df_lua[2][2], I_df_lua[2][3], + I_df_lua[3][1], I_df_lua[3][2], I_df_lua[3][3]} + + return {}, I_df, {}, '' + end +end +---------------------------------------------------------------------------------- + + +---------------------------------------------------------------------------------- +--/** +-- * @brief Returns the tranpose matrix of A. +-- * @param Matrix A. Example A = {{1,2,3},{4,5,6},{7,8,9}} +-- * @returns the tranpose matrix. Given A, tranpose(A) = {{1,4,7},{2,5,8},{3,6,9}} +function transpose(A) + local result = {} + for i = 1, #A[1] do + result[i] = {} + for j = 1, #A do + result[i][j] = A[j][i] + end + end + return result +end +---------------------------------------------------------------------------------- + + +---------------------------------------------------------------------------------- +--/** +-- * @brief Returns the multiplication between two matrices. +-- * @param Matrix A. Example A = {{1,2,3},{4,5,6},{7,8,9}} +-- * @param Matrix B. Example B = {{1,2,3},{4,5,6},{7,8,9}} +-- * @returns the multiplication between A and B. Example = mat_mult(A,B) +function mat_mult(A, B) + if #A[1] ~= #B then -- inner matrix-dimensions must agree + return nil + end + local result = {} + for i = 1, #A do + result[i] = {} + for j = 1, #B[1] do + result[i][j] = 0 + for k = 1, #B do + result[i][j] = result[i][j] + A[i][k] * B[k][j] + end + end + end + return result +end +---------------------------------------------------------------------------------- \ No newline at end of file diff --git a/vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt b/vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt index 8a549b33ef93479ae7e2c94220f49e866bb6a9db..135832a398fa5351f6be4c26ae501822f005ad16 100644 GIT binary patch literal 252171 zcmeFac|6qn{s)eB3MWOUq!i|KERz#S)=-gf(kVNkO;b&c!WfKBiH?(Hrh~GzXticZ z(-O$TE|RC5&M#V;#TON9W$#y}x_E-+RCJo>RZy`3-Js{fDQS>+Y{@Ur^7?DXWk z^+Pi2_dEQ2`=N!?Hw)V$ecD;J4>*hW4>H>CU+i1!^O2ZS!az)-uZ8TZvMj~^$XLD6-H*wt>*s9+Y`&=zqvB+L`S}GdRuq?b(s|P z6B+7H{b|pvoE1Hdoo-0wT-zlx`XMFQRk|8!Ge3??jfzub?_s?6J@>-*so-gZdM?tFQj|oBv*f|03bvSp`NekzSQg zuFC8`WFEyIkYD`VL+$e~u3gsh711&>^D*L~gyXg8%M1Nc3g>Z-+@dAYZh~{?O7yuu zZf?Socu1TcIWDxI~4@^H=oBNHZUzTo@JZ z*+iv1P9`bWxfjFti16qe6K!bKa9jx*w?n%GODa52p}&D1A;Z|8UNT@kpcV4D&f(A{ z>g(9dRrA*^4=qYx#^ulgN z=bG+wMKMO6;X+26w~hj3qu2^bTySOKUhZJrb~>rs@d%@2Z75pxd&RP#YeT+*fAcc` zpI^T7#cJyf&u<35F^pSAG}`j5%tyPc)P&uq)GdpR6bk?Zv5 z>qbB0;(x&fo}Zx`Ti@FL9?J+~z50OPHX>ESCyALJU(W3)dCuZq3H{UQB$GxK;{w-u z{5pMY!tXmlpx*2~fyI)oG7L+pP%N^qoqo$XYXG#Btt%tNJAR|jz1t`$jo*GnZ;0FdlXsN0nD*LrsI>VDv8WjF zU04+**r=-Mh$tGe@%A4+XA`_#f!_X@@kV^Yg~a(`(P`V5xCH`#LHr}Z*?n)yQ&qK! zH~TW`t#U$acaWC}4s?W`XM7Obm&o9Xi^B%_uA;>BsDOBNJ8~+4TRtPTi$3_i>G6`w zq^i7zcU1BN@}cQ#H|3X4Y}~9u!NPe!MMQ9AYwGMSIJddkgZs1C_nSUB4=(a!h!rtT z|Jx5PXxAEU-GruXOx{XT2QGPx++@8aC!7TY3_WsA2LzLIf_U0Oc{4wy)siV zCg9{|E`3L%KKEx_&WewP;*+KG=k+s(yNZ$(M+G~kv!nDkdVIdKLg-|<+G^{KRm)$v z+Zrxi8}dn|8wm~9!0l+y0d{mQpqr$&ee)WI!yB<~lCmgStTUS5N3N2Xr$??sdQX+u z&HW@9WHSSgk)|&+X@AZW3oMkch}f$Ww>w7l=c1&5RokcIxwD7hFs<9ep(yKnlVp}% zR*dhvQ)w8h{W_Grr#NAeVRGR4TB-S}?4RpRuk!DPE>h(~={CI&rQ7tr>LgTh)eCQA z!c`2UD?d|*ZFu@b!^|@+*YJYI5riZR3p}!ZUMRpX3EIpRET7fDojtR?(s1sqQcMjN zqENf-h!g71<}H+8Y)$(bSvd-=uG3LVjWlo;<;7d@8W)mX1#(gI^ z`|i-h#I~nvy;JNg7vn1D?h!fi0<0yv+p1;Ui_cpWDEg{pLk#QUCx3Pl9F?_3jy=3w z@#Av-u0KEc2Y&PZa6K>j-D$h^)?eed4Q>vaPI8rgT=VhR>m(E(L#OOh6nK#Dh!@2K z7ywero1_y7Z`B^YH7FH%sF+23je9b?N`W ztNf{RwBlCOZkw=5k*%TF%|22Y#dBCNhxrsUkItx%$WfS=;mZiIg>|uG`yoZa`4249 z&&^ZjNX6Zyxa}vkOyF`aSmYYFmMN3^5#MtQ7pbzp!5z8g-%fsMM;=6po=(F5TJrz8 z=$3|CSK&Oeq7?=Hj?mt%EgrwYZy)Kq`R9`Jhu4))7=ry}{k6uf0GDsy4`NAb;=5LT ztdny+d;MUOCnMyUp)Z3wFUJdqv%Zi@rkg4wW$AOu4Fv8#eP6lpJ~LsKQQ_*oOkh#+ zO_}0f5U!%MW~n}!wL1#vk>65VTdOl$1or&Q&q!TAuF%`pw5vV{x&Yx03KxT7H%o3t zL|>Wo+_L=3L9ZY5s~E8U;c1BeCjZ9j|A0RGv_AanV1rV4Zo+rn#J2Rv=f#!@3s!l5 zBngOI{iFf?c>at&H;;Q}BYT)umXxnNna_lBeCquJO{}AfS zVBL2U%Q187`Tqh!1`4OXw90qluOTwm59g}hoI&=Hr^I}?aD~CpS{PzGBNm>1_N3## zx03z?t3uJ~iK?l|x#^?>74JBz6NuoL^IR^Ld4{V__6*gaVx*scJmx)aqj{gvdbql? zC~w=;o|7H|{JD6;G_IiMaET3L@`-rx{Dbx;iWEjjN2t_C{`WV{X3@nbXlOR!9i;f+ zlb`pBQ&;AGov}U^XR7Do#|=IGgvaQVP|yH|gH@4GLlw#cNlcd8ki z9#dHonz|Ohe(!fd=ec*c$#rC-&MilEkjkFjlmRXao$kE02^XRB+?|m+D-_sS| zZ6Pzyo?$W$O&+3>8#d3QY@Jp0g{?;>WbdjLJ0`dJOT2RWwE=Em@Bw{<^2BcZR{BYHaN{+{$T+{x%XJm4ChlF(WI>jX1JU0cE#a?3uIQNy3CpP(~2YzQT z@FVK*G47Q`mwr2)id9Pp4B}TM1GYx*7UA4`hBlEPTS5KLrCLJEm#A)gKI7Nf1ZwUy6{FZZjIdXS=5R{s(jUp zAATIL9*2#kV#%V@b`DE%Y&$K9?IG5RyVO3HbVVapK00Zi)TfWnSoEm1opjdy>C7t6OoZy-Ikm=b9N;Az98_PmiUBL zf=uUWyB}WvIvumPN`Y~%QNmqd8r%p_tE^i<(F*NYs1%+48KMwHo%I(?0a)9(a6)!= zOTCW$Ek3?Fdz5)gOIq6aml2WO4;3XQDvP*YLX;BR4!a-TzQJqVD6s}`HLZ1HwB^hb zS)xw->edSm=pU+UwjJNm8S37q|Bp`tblq(&jko6u7lv5I1XwF3oqbjol(Y{Pdz{QY zDGIs+Hh(J2%PWyGw)t_n*B^NjeziZYk{C1opU(jn?_G9gPZj^!;^f#=lGNty-lQ@w zFAwhJJr4*R#wx2>vSEJ#?Z%{cecRUB`$-&AIXoy9G7CKRehZCpNGP+>1!b7Q`~*45f|CaSNW&FhBg1hbRBEApb6 zWzEHq<gk# z`8s2{)$!|${~fPLJvgWO{Q10+9jc7V9HP3wT=fv|BePk+gGycA=2>isz3=Ev>UjQ>wkjWU(kr0PA5lskSoX$|GMZS z8Te&F{0d{)NZ(T24wh|Br7Bu*@ecRm6T?cy*ew?}|GgXipCN9S^(vzEl|#{|lahRy z;*pG{!HyxW|F97J4c6aGNSKpmPlxsicGPZLFkpS>+@c!BxznK&6UxQ=1eGd_y(@P! zBvuW*7MKPdux48e-tGO*9QEJ19_DM_SAM)7mWQ^OE09(VIZgc&(3%5?L56|!`u>TV z<{uY=+nSrkA(q=eG_K-a5HtF^C}zDFM1zaPWH&K7)hqYnOq&TXg7EUh-&~FVWnupF zXTB60sf3$b_R68vOWiHKD~|F1>9*hz_wuC|8FD+~Yoep( z08D-|@1LtCzh8;_bk8GWQqlU`I)^(tNUN6CR&aTtpR(w`vmSq+tMut1ee$M8Mn87E zvejR}d-DY!o#)m69^JoMBklRSzT2rWFW!vX5x1%h8Wq$-+ook-&bs|8i3#9q_4~4x z#$TBdhB*u7nUF(g{@MQiuimZy!m~~$hD1HEo*vn**Vvb_L<~%!&8iskl&TQ|7(X`X12ImoO=J`-Ia*? z0`Kl8LSD1?-8_c%L;v(IsPDFzEj}dGH2%+s^v{67xua|O?e>0X|9LO>lb-y!YxKV^ zo&U%qHZpiqRCNf*C`z#-<|TJz@P!)gGu**{L~AXyN5OWQqWqL|8` zYQCro__vbsvf;rH!535mci+!(#WO0=sp}Ny?l9`U$A>Rzg+$vOdOA#w+Cli!@ts`w z1rhswANm!PaA%oIPlGE5>jU*A9o_A3o`#{_7AdqQ;mX$h<_EQi-}?vd!XLS6e|xV# zN3a^&&ps~SK(t@>0TeNC{ff1qV|pIQugnRf>{$`poua$4?fKBlto?6N=Z{{3$e`UiG$*S{DV z|B+W$Ir@Iiz;DXv%ap!-O z`Fea6_ovZs{>T;b_uuPwJdEMQt!pS*M3QbQDsxTR_hwxmY1I|twbq!Hnaf0##j2wH zxE+4qh~YQv7$TCy=NHGL;=Rnz|G#G5{y|~;-7A>tCx%T&U-9a?nyi%|SpVQ>;-G_|m6T((DzDiEZs~)=GUT0n6?ZpNeu9EyXw`sU=C*p2Y{|e=b~n+R)}u9;=L?{6ogp9vGGF zJp9{nD_@Cx`8DH1lzltng|UocyrX!_7vi_ve!dCjm^%G;$ep${Sh#T^&iwSxTPC!A z?AdS%CPqZ}RTR$eTKnZBGm*DU>dMzX#$TprB_M}rJpf0mv9&DN0FHJ+E4NrB-L~qZTrmQ!(d8JSl{S0zLqS%s1%C@X?KkIKguQlrP z`DMy)Rl!476sMK2>gTTkrjQ@*sL}LcwDqe6eIeL{qr7cAZ;!hmZy65ngwDaLSdEmR zRBbBX{A)?+?|HqEnfJQ!OPBk&mr?4QS*kPQg_yR+vr6Znvpu5n?3Z+zuKw%og-*f-(1^>TPRsm~fcDZZe%4ZMvr2H_k zJ(Z!NXuKpS=Cz8B-CnWF{$o}lhhq(-sN$FIm(1TX@b3FnwhI?&C+5#{8!X^Rxr}#vEtBMM$UO~d<2^1f!mvENF)Q`^VeD>$VhQr@xS?nE``Eu+ zX^Gz_?q-2EzNt<;?Pj6xwO&0?fxNnCibD#fV0naq23}7iKN{6$_IN(tYa>&BHSG!~ zZUo~OnmLn+UGs_^mR7sshQj4r3}boHr3L2=7N&k*K$B{Uz?0j37UOu*R<|(3)%HP) zsIoMgwAGzGdQEP_n}o?$K0m+`u-7p|(iszXQ4j2OCHuEIcurIeG3g4a<`bx_ z!Vvt%0|V3Ub~RcoJk^a!S4=gh_&s&NWcw{=dHPb%QfcU89Q`u$O#hB}&&JCU1ph~M zftjeX_`op#tY0`%ZQ});sIIror;_i@hLH_y^1?`od!6Rz9=S`ps&T!!=Ijp*@sa%k zjoGTaabqT5j_9CADIlZePmW|1*VXXU>U46aD)=Kdvlvc(?o>Ia*?oGskf$cfV)D?$ z`-fj$i5|;4;uhb)o;kpO0ec|@PpPzWoo4RFv(+}OcFKKJGww9I^TtmZBa;VDe4BXW zK;pL<*L@B%t+(RkJc>L-thYXgt5oWP;H9~<8>)XfNL&SPc;l*?i4S3nOgx}B7DsHx z%qUQJgqdt&7=J8x%8H(zIAv{;P6~D-+1wk3-)7LmdiSDzOPRVF^xF(IR^~bP?t%e= zd*>ygA&PQJDn>|G66&ITm4t@MxKg2-C+_Izqxj6-VN9QaJ!S=^*eRP?soBz%+3oh5 z2ytBX18TFE*pBW6&8M>DP93O*eeH2CIEvL(8-9&7YZS>B-rS_4@3%3TBh9TH+m+cG zFwhwsRW#jxZ6$jV)3+b9H+!S2(K2c z*|TsCC65j2$Yz2dU#dCjc(<2-C%sUsHeW9qRj==*Odu-qCNH}6u81IDwx)}L z@*|q4N&}*_%Q((PiZPT)zj|si6I<_Oytb`3Kc$E}-R=K~6-Ys)lXUU1uyMC@&??LJ zem|N84A(`vH?sUucj zzdrg(esBAcq5k^P8sD8Wy8gn|9<8fL-wg%F^WtBqiR!9%&96Lrw{N?eaOKZvzIF2rusyWI0gT}X?A*0$DDEsT0WV) ziOvg7UT*VhXX=DJ;irtZ2Z(0~{U6>2Um)@{inExL8pTVF0G@8w@HA#`d(X&w9C8Z2 z8$XseRgv24acpP&2<&AJj=Gan69k8xbec$xSc)}NGigTN15c0EwaRCo=$gGPoO16D z8!)f#Ea>~*y8Z?_#1Ji1_H~e~C$#1RxUhyAc}m!=Sl>4^5sMl zL>^Gn^w*&0vjg0_4AJ#rHJH|%Fs7|=+`aq0)TlBs|63bbif16pLd(UyJD+`s+zW*; z{pW=xO)0lytkI1=x-~cEwubg5cex;6DG#_~W>8^XejmlQu2jUp+nU4hR`5(m5eK?hYkyP-9Y=S6{Cll5Vxz)9wMFntNs?l;rXS zYSAiZic(j%^>)(3{Y202*ZV%Z7*se$qti~`)-4?3-cTU(@H%L}tEX#=650;G2wP@q ze;gP5&TvwXS-iHTHb3F2I?c6ka3wp->J~F!)4x<;=xi6RGU{)9XAh_J4Ik>hyWN2- zz-EcPZudraTwoYhx+sCDGA`h|sTUiPJDh|if)KR-BcYceSthfIsKt`BtLWxPklh&K zXw-WaW|%tE#);PRT%df+-&22Co%8M}w=Ayi`K)OiCtKght%{X&)hxCnK136hPNlgY zV=JAS*3=u~6T`^cHRxf0O5>6ndAGf%HR_wIZ8GW|h-cr=j(CXViLbRMsYWlz2mSK) z`#ef?pK&9j-_p}_0S?hpGua_8S=#;d+o#s6a7OlqEFp~g!V5%=PVIU#8O0^JB6&ih zQ{H{zl+%Nuqs$7Z%Cl1FqP-y{c}Lz?|KhjDQ~St;W1|kUw;3^3>Dz3&FLB0lMUh(_ z{pB@YBZzj)X}3Jy~XyN?2nLl+3PNK|528ZcEYR3pg+ZE778AlXr}eS2`KhY`gLZ`~ z(C8HlZ>k3>l6UKCEB0F~z(VoG7Y-Jsq`TSbw~R~f%CZ{l$hcbubRcIWhg>4@^t)E4ZVQ!3`MN!NT!QPLx}Ck5zB}Ro4QkBwc?1 zCHtvEhz|hoM!T!waLn>Lg>FA;yr;f$MVkJr)lUmCBg*N3)YjBUx2ytAvQz>4Gz-_i zP3NjxTOW_J^mJL~;d^zv&g6;YPx6kwibVH7;~P8RG~>$h-I<7%C;9*?Et%Hnp1dO$ z^k(kSUmqLwBQ`U8yM`SIH>jK*+W0WOeJcyo8cq{M!o3@XTFT_9&4#4{tlkhEw5P0F z$8smBXr8X9(c|^eJ67~Z2{UPILj3IQDNPOfCC+o`_ci@eChdApv%HvA^dH@4-g}XE z#y3N4OdU&@T|)oxG9(Mz+fO>4H<^y^$(@q$idl{|L=%y|OuUVSLRbKx=rRJpir%c_ z=}n`Zd4!ZVL?vvm`|OhZ8~zj#eAi_(K!~SAZ;ip{|K#3P-FFb{JFVqi3J;%f=iY@~ z*~>^J>SdmxRpAFbXf;A01#xfi?EpaihuSq5PP_l?I^+>jvKIqAGs(_@S(4%Ds$Oqz|2 zv=$1vsY+0X_88#GO%HBRe7vn2YsT82li6WL-t`M~{MVfkVVOP9RUIRogWCxYF1gvZ z7T#NN!;sp+3{-fQ> zX;j>5a799B)_Aw^RbaXB7e(;Ky3ZnHyv}d|mA!x~m(jY|?zmf;e#%|_2JwNzC?eYN}B%N`nsis6L2 z#AAxuo&qm)%Nq9UASt@9F21H$shmzDdnBz_&64ki&GbU*pgOd8>0uz2A^QIB$Fh85 z-?NbKSRqn=>ylI6Q`LURJ!We~2^-y-cjRtLqQuMdejYwYYc^oU;!gJDj;p3N+srPB zuFpNTgwE3&i+`x&6r9Exqls!Ct}N}Q5K@x+_O;ueB21%0kbCQ^#MJH*WijHf(0@c; zH%6;=<2N`xcmz%PdcgG~?-?7Yt!y;0fUK!8TbBqlkazf3%0`VP*$pp$IG_zIm96&H z0T#e)J_6V}MqHdnGqYa`ou5}DWs;vbNug<9DNsTa^Es7JPFtJJy6Q&N-VmFiO&8b; zr<{mVDnGNkst3H;(6vvPbs6yo6VjBhlW5-qk`+@@DUq#0H9;v>Lrrj$k-i1LNh)R# z%3*baD_t@+!F4u}Wjh*`JmBd5_$biKkSqnGTQ1E)O@&N98g%cI zg(rR`j-ZIHQme$jdaQmCw0R*s57^!S9|R1vU-dwY%M`938z(YM4RE(B$eMEAdxEuZ zbyISfmmjU3N02M%w^cfQTb|sJq$}lii%AUP)^aDqH7qnyWt0&!mY058-z$WqYGTa> z+k${y7GZ$ZqSE67sfBlLVP(hI$_%4(Swtomk0CVt4C7oFTV0;a*tuu4mh3u_QnJ4qXrd24V*Xg^Y+~(f7|uw zc-}r&P6L!MY%d5Sz*}^ayobY4q^|8HLQ92uxvm{(DP0LO4H`#pMvnOU2y6lpau%hbBzFB&I9h;>ONOx zoITQpJ!p)?)_PiXV(WDpBf<3=t=hWr*%^u_R9^g#?p;|(=g&vbITm)JZe@D8x|?j~ z0rvEALW*q0ff`4i5yLIgZ^bpgf-5a?D2$thrtu&M-If;taJT70prZXZuF;Jp# zsFSw(;06WQ1t{gdyIAQ0nzUntBqzN(B3!fMVCwfPIZ9S{oV2rG|Ak{klUGmmbQ?$b zW6j@cEAo2WZIm2yL+pw$z(Z?0IpS8momWbp%(z#1yftz^Jc{ExoOvzL7BOb$jtg3_ z@%ywB1G}=^A|#=19>7Xp1WQGAxP z0NcQnHIEZ1ULJZ?F7wLH-9IqXc$}MH%N_0Z3Mc?x8DiKr-q~c$$fC7Gx^B}5eWrlP z+-TJr8b*~KFyo(|cHSLnIn=6SVnB1fJU;9XoL1V>)x`v9vwI&Nfg+ioyFd0YQ=;aq z+o-t8&-r;EDSAlXl;ph$$ZM@&iH3Bitg5Z2jzoc zHPLctPC$XGrXy_@IN!q~GxE^>LCFjeKpBBNzi`x`yaI5vInk;B1Pl>TMKfuYx=^iw z!&Ub77i;T{I*5kg@7W}Z6drD+fzF?hJDHz&6Li?)L5Dhg3ro zPn+StrA@|A9_l3sGn~RsSsr|3)=iO$<7&CYWd4xCg~pA>y_OSk z;7L&vO@)CD`;?#@a#~(aHNWXqI@N>Qvv2}9WH}EbZ&tUjGJbz(R&7zLl9{2iDbX`~ zL)%~{5YBN)yOR5ywT#{Zb{5F?d;tC!JG^k8l$(ViJcC})&1SdVNv4TA7J52HbQ>cW z1}bT+bP~$VX45r#C-U>`hNt z7SMr8f6s}w!GafL5(dQnfL*252&K%ynO~6>up(OG=@2GbK4xvziFb8|3#kpDXn+!8 zp*u@JzrN9D1*9?3?GiWjh69GOUNvo7=L2iEr^Cy9lXNR_63)EJ>(Yj$O86?Nq^l_9 zTl&f&INfe2s5yOZ*{^tKfU`bz!xVxMFkn}a#&WK)!>H;wZ3#FZY<# z)KC40;R6bnu~#F!l#!hFGnhfv=tm%2>GKnVVp&eu8tFe#dl!_$w} zeM_5D$X1|*p{M63fEogMU0jC<_xI3vr}5c?H@ecAcXZL4y+<|PmU@F$0?9o!C+b1M zpy7=w;v3$6^GMk7cIH6p^D&PDdZT`zgm~zXx>IV)?RdK5s&j$^-F{@Yx|_1K;qHJb zxjr-oz>*?wwK-9g#Cb~-C85Vs08P5SK3l`a2SEqT+zK(`kGOYVQg<_G9iyEv8rWll zG=4su0g;9occn`u3}!wgkYX~O!n~(iuhFnlts^#FhU^m`-6i;rVAh>4-0JCDDm2RW zwTHG3^>>=kI*Z-)WaO;s+HBQ%=Q1a=jqfl6I4CyKj@i)~wuX-lWQ>KG^n!j1eZOd} z*PYD@g*T0^G>@S$j)ftP5$?h5cpbc27;mOeO^+F9Sa^pq3f;R8jLiqS1Spncw1}%G zo#uEzPTG{DU5+4l!VjK4f$iTUq;1kp2U=RsXXc}gVYf|@53Z_z1r-zjETXQkmq!2o zJ{!CO(l!Ba&ai3#kI7|R(7)>!5YXd|{BW&tJXJP7TAn(@*xY9|IJ~h^C7|=gO;%v0 z|2qdyU-A$pr`>J5NY9E%*SVFRseJbIbdTG3K{H=3MAP_#rk{cVU7yjrBEdhgppiVd znh*WIjyi-XXpMber$F%UpcYKDUCIxowE7stP^&qSuIN|0$Rq{l-AMxy&1X)ilr;%mrgeNnxv}vj{tG)_tFlFzmBA0lt#Rcd?r^)T#UW?o>69%V~lgLR_`jX6l! zBFVDF8Zpt)gajeI6fr36S7s&Go-k~-$p%oO*_{(l=*Sa8DyTB5Ylq2u)xXm1x4>Xm zM+VM!Ou}G07}~c6ZYw@E5ZJ74dC><15rNj?Lg8Jtgo7JGT;6mWk0Dl0JE2%1l~7kW zwqi0g!^!BR1^T>!09rYCNT}0pJBkKICHV(3gM7{#NS5;mvZtS*Jb5z|<6C%PxQ1;h z=zElBzmrtUlzD%a#>nL6u3ETfqpIj5Z~DB!Vq7wM{@JP0LvfszAi-5Z>^6J^zly41#|PFss<)aHRGDkkwL2` zemCBMH@RTUFBfiSv-gag{5hx7$3f?w>`4^Kd)U`Z#d#Kv!RY}SI)@OCy-VLM9N;A-xo6{FqT+e0~^$YOIlgNuJ)QuSfnI5QQBtiHIpa*TPfe zZGK3!nnFy)-F~p$19@n}bQoX#w3~Jd{~)iZ^n7 z7SRpxgx|lQ047sUyS$OKk+LfScd3(}li33q5g0?v2VvdyfK3^!Dd9nsh6P3~3Kyig zUinx(8XWfy_tW<=EiWjlGT;K}t1fouy!eGq*RXAUY~apm9urMJ{wiY%gb&(FnW2ML z0~(44qjEAdZQPk1?l%PW5*J**np0YL+`asr5lyPimVIj4mptf_Gk}0H%9k(A9bHHs zPP#GB%~3jBHcV~zSv{f>Ft$5ciiY?`Mku7y_acIRyr9WHk-ir4ndSlWAcB9IMpzr@ zF1t!i5n7E7HMH%6@6)rGaHZDy`QiF)mzJq1JQ-!TJ=Nqy4NQ0Y$?9^F21b(Gp!tK} z)Qze%<2wLs$!@K{2qs=JC($!$v2k&Ps~T^cA%Z!rlK@c+a6-ct1E(#wtKq*2MGSJ{ zZDw!3a3#bvCw`?MW?-`rT|ILFbTz$)Hc1BEBaGzyY|}LqSic<9lBk3RHc<{5R4jxs z`IS?!D{ODZ^#g%S3Fxd~DFQSNIU`Og4%(J=j9>hSuXRON=#OaC2LP|&HG$i&K?m9j zE9KzsgjrkWq}ryHFNv2Bo3yS5{G%<}@GKuN3n)Fbn#HbTVN5BFvBb$3dZ}=Hudfo; z=w6-7R$l^~5a$UiWMw7~<;@Ne z@HXO(&~gV?q$;(6!??P$p2w62`AyfbSOAvgw2#Xun4E&31>jbW;IXFQ+`}tP{rwlq z+ZAfgfXK2B9;WhqgmjfD_ugfa6;y!@BtM-IQJOuCNF9Y&*9B>wEoB{-Wa~0UFfUU< zK*{gf)&ph~Cp~V);qtgfsv>v18wJmUWB#6_&p=>@gP^dN_TrXhJAU;Ct3EDJOmNIK zQSbKmoF5o8tR$lIJw%N#>e7v?y~YYs$xa>V%wvzYpe)iai^biKr_d)p;nDL{w^ zE^~F?HnUkNurI0%@EbiLW_=6^UE7ojc>LIS)#jtCn*sU()da+(!IyxJXRt34p;%` z2T)tz;PVl8`%w&-idJC*C#%7h4D_cAn9U;Hy0ZWZH06&(llcs-I*do~8|O0Wjh{1DggjqXXHj48KH70l%Rp#88WvSbe={ zjApq6cmn0&oFFo&A~aSezQh|Hq)N3A6}dMtpvhaN+{^pb18Twf0q1;NvizO;R}fhX z%K0EdxL}@x_>p9TKi=)t7IxkMPv$X%Iccw71@kb)ul=r`>Tm`94T!WYt9gLyg~VL( zS%kZdIJZ{G2D-Hj7J^A1C~eew2-y#!yi{IS(3Bh_1ij1Nm-p`k{f-K;GSkVhRe1KJ zLTUgG{Gcg;jWpy$Jdo}#4@(^85_uE^O$)HHo%Jl{gN@9`kSeW6xn(s3)~a2RrW!;( zc=A`T>>P3fBmLhM22z#{VW2Mda#L43c*#>`kpkDdB3d!FgJkI5;IHW*xvSW6IJtS6 zyKTVKw*3}>u4@-L9uuba)WLIs-?KVHgi5mfm0v;TvmS+$=s|3CNZ*Gc-wgZ!6eA_w z>Q9)v0*dy(2^gJ_f7V?NPPtp`hxCm-V59|uZG?+F8i?xO;Zr48^(MiOvH7O+H2e}3MP1EgK# zb@?B80T5OQ_@MFu|1@dFPWlp+W+AUk<1~PqKB~r|I}iq~IX!?;4#YNEv?&Rw!4NBI z_mgCFAu{9zvM?Hz35aVBZY9W<&aeSTM8goAbiw~o$aJDHagZ40&H?o}{Gfm?O#?^0 zx*IG~W#Xll18CNOFTse8a-Xf@)aaTggB(8vKAlA zC@p9W^GXwHZaYW?t{iuQ?^{|ybq9>i^r2wXA{)C~eguO=GDyL)yQ(gWjT=E@&BjFI zg;yIn?7W`Zv7y_VJzp8$VrXae+m=3-gP1(6wle|}@%ON&avlOm3m?Z^!^hhigFBeS z5Wo^KuqnbFLc7r=8n%jscajoVxFCJ3*_$4=pQ!b*CxBC`DLDdoET_p~e?f+mG^9W0 zx8dxuvx9w0?_*Dn#eOu3xQne6jlbw;e;^o{H=>QUncB}RlKD4$wdvtjCa z$OfOx;M+_Gtg`R=cf7oM5Rez5zpP%J26$1=nFM2WSwkzd@bK{4WM17q@|I~3awZ;9|+0^+T+y{l)X8qd(6uOl%I2q}1)6z8GT zP(LK5V@Sq0;69Vc5n=n;U10Zrd;n~9BKSaH0d<3+nsL3krXQh~(1+=S6tKv{7>SKf z_d2%+#wIpquz`t&r#vx&mfcB#aHm-Wb)WKq&4ouwyYtoe^^z>~(4uD)W7(g@({%RTm3-H@e8L0b`O@-;Wf=WD54(>R{RY$&Gu;SA*11 zmpxASO2^H18hZJjukM~VXk_0I?gL(@_$+z2@TxOAG{d%$%)=0apy-v`5ae>QZYw-C zaPRf&EW%V@X&&yCczhUe<_soyCHC#8%&8tpw$7$e#cp=%V>ukq19~B&u7)Jc!luyJ?>b|++- z`k?#+5u-FD%VpZx?)l+>7j_Og4Q(ys?wm4G5PoCDz%&@1S|E4MWKP=J6+;fR4SU00 zC*|-o4s>)K^0-Lf_|gEUgGyH_Gm|&9X`@^N*%G3Ubz=s&cGvPxv*Z!~hk$kCHMzDI z`^LW0NmU$x4*mcFR#+mVjj2KY8((}ENW1Z%4oRVrIftpOCy_{-UI1ag#~pvsZ>Q3x)09d=SV1WK0;3>1yesS;gLG8i)4 zA??YBk(z3=lp{0x^mJ(873;wPa>~2SSTD@np;o7!D_U;X4t{+kgp*;ZfM}qMfv;eL zObj)j`bAB2Hy*rl7X3AnEgAJ~WDm$3nK9^9hjw0n!xtZ|ZD|x2;B*YhiD1wNvc)v^ z38$mgy*v0JhE2T)v+d=(G>;Z2Pyn%ZKRkGqTjG9%`Lm_#5mK+8~kIn)t zpCK$vgfs_w_$t(^|ROyg>k7JDBn#A()TYTN#N|B&pDHOdX))*3Xj17 z_3Mn##mMs+-}I}?o*3IO7kByqU4?~Umy`D5q9fv_3SgXR1K3uQ?69o+o-n5I0GxaI zLU3F4QI-0}Yik~W^@$;hyV=U81~}V+05P~cQA?G1#Sir{!ZSdYbUZyFVvG;;o9HV+ zpJoyva@2@k)i%+uR{`G9#!7fa;ia))k6Zp}WBgbCtKG}Y2!3)cg+|n&{^&LE3flTK zt>I;En2>mVU3OWJycyp!J#(2ylHRMZrtsXrOl*UXwiwH^t!;c@O-BV zb=x};CfjnY@|*VpUleMnHRsc+-wTayf%5J(>w2kv5bK-{b9?+T`b{y$3eVb%b7ov4 zh)`Xc1Iw4M%#x*iC@rvu)Dcl_#QKYGgYe&g?r9e8GdeXhao*s4xoL}BzS|CPi*z!l z(bzeVK_D*M84;Rc;o~y(QIYfjAAJW3xe*oOn4AqLL-qhNNU|cfGt$4azP&9{nJI_7 z0`WO{%;HkAc|0Z)LS@*LQHg-sWnRi{5uq4BB|RL^1iP{;A=aN$JjS>BZ^*+Fz5;B*L9R#uTNB8D--z$CB%@UG z5tUJJB3+7Cw+#-gc>q$HC-S9!)kzP<6f2TtSJGkZ2)8>DvEob8Sl#{)a_66e!6a12 zTN90#PvRI0kIEF3T)j+KG_7|?S@n1Pd3o}HIu#;*g zrNVwGPP?vX`HmMV7xU?%6=N2R$n8k)g>V|Ft-eYO8$>>70Ccek0ci9~6eW|ls~Ln& zajuZp6**0N3460chTv_9rQSCvQ3T+)XefULsm+jt3a8ATkc1`(eb7}#rYsXhwP2A? zqoMX$f*BN6v$J>S84%&%*e_S;1&h4J6%9jZJKCLLyhL@t#ilzSJz@v2)%Er0$$k62 z=WyNH&>32dg}Pgn>ntI@J2Tp#3g34CjeA35sDM=j1QRw%>O|VhfP-@u<->DZz`RV- z@<@4nlmJoBhtfiryKE1BZB&J4d(gZoflV;a5yr6m0aT$ihj-*hs_NEf5imNTE=N~+ zF@X@et0!$oNm0|J3oujWV_XVzn%|fKjNEKl&#v@AcLxliJV6m5#u8!(^}xU!I6+>@ z%s>fbpkp<}nlM9zh2f30ZBSOvtfa|&C%XbDATs)}Y{*9mk|6F4oy;BqrxGTbU_amk zeAQWW{2)a5$=PaQnV_hIccFX(;h3}Tb@0Yl8`+^*w2z!Od{o z?j&x&nB6P?5Gns`vwqby7LMl+lE+VuB;joKz7^jeHbY&~ud^Nst)JXm-L@*ok-%@t z4^4`pLIRJ>b@*P+8rz-HHa=%6^|)#+I||NEyWUWji34Fqfj%D@7~(-?^ME1UibPF~ z>#q<0nr>8akO<|@msrZ|wV5WETts{!=(b7_UONQJ5s$S85cmBO zn*hjRcF21m1D|wz3^Ln$Y({P!??_6cM*t{i&{AO9x5Hxx&$;L2LuCf{9Ms4#%vMf0 z!E`a?@i&C#t3++!6_KQ(h$kW zyFi?ne`h!E;;yxXxXyu-?1ENW6;wjRXd0wh-8Xs};2KV=v0b?#{^3@rp71`He62lZ zU51sAL4q%800}%)@+T=^h=QkS57v_JYjEI4pCG&@C7EBD3!~6uVOC+lEahnGL{B$i zC!My*c!DvOKh@F_C_&{h0F}2055l;}FlL;HMT!~)#SO+~Km!-1b74LWejpG**b5*l zvcSMVFrJaHZxJ*qR(Ps#3Mb_u>FK`tx}(!+PF_sG)d;2{CUg|YX^aFyBuju=cfrQHE9 zRT2(uCgAb}NEb7^O6aow0CpIIr_y%DmJ}XGriDX{3SmeD@JaE5q6wvzNjpd$R41lb zWp#3rmzXG$r8}DkT&C*^$MX};r%g-RRVIR=)UB^%L|u{rF1-{)mzHPyLzAmKk{=BW z7o3`GI~7{4CKw0d%`Uo;e)vJ>LQ;P=AbE<`xVd-#CWi0lGDVdhLz^p zL^*#?@5Vh42AyAb4g|ZGe`dYe*apSa?^oPVI_Y@)pk~uS5&IaMRXDc6M$u*JD=eS+ zAX)`ZZRKcx!tNdearm3BoZDOq@Kr9rB^ncJw19l7$~EZTkr73lC-jH><|HZ zIYdS}X+G$UH7Wtzu-41t`Kd|m>BCQly3G2_6mURH!8aPGK|ng{Y&OlE#y@pyoqC`f zvEE4$rc2|YFY+|59|%rHKxwGtFIl1zL@{U+XQ}TNTKNG(<0_M4 zN(!0=t#4^eAw>p)bxO1pDL#`3xhKpXv!vu#gP&qIWqja@fPB%FG}6jrv}zhCr8>1KIH?z z;$C%)QN|Q2wS^Om0ZCC-y#uS2TN8*{wF72KZ9@?8pxRuiFfHtUy6mD`xHJEIpVde= z#!yoo7E-0Tx@WRV7lNs|nr_BBpVf+wk+qj_?$$hOBtVEqH-Hxo#%4$zq$wZ}$j5)U0Uxdb&_HGcNEk&t>*+UGX#K_sx=0k)e6@q9-f@?D5RuX|^{Rsdv?jkAH3kbwg~ zDM0KY`1H@?cHpW;_nLTM*F(}%i5o3ahB_M$!$rbL_>2Y+PnlH#u6j!Qy5; zmix-fpL@;!Rrxy?xv&figU1WQyp-{y(k@dLsh;4Nvyo9^uU52I*}41mEOP(O`rUDw zWk3)MVc6rb!hSl?&GKD&y@oJ(E)TzI7Vbg}C>Sdy5BVgs-V|Qg1VAbWJLlE|=YBI* zAVqB>lPK+Y(E(9e;aWFq@7F_Cw7(YuCM4}F2QNPqtf}sLBZLO8OQyq!8U<@=4()#%(MBcltZybyeJ3pv{3={ z^y4sPgn0mzZNJ)1H4I!+Ebm>NJh9M=RIp*h~MCV6_R3d z(XZ;Ya1yvRNLr3%B~8I6(Ey_P@YPF^TE801(6SFMP;yy&fYEJ15CkSRWOJN2}Cb;N1b=TWpgaa97$XZA0N{Py14fZQW#4Jp42aq=KopSb|?p58+fMR*_s9=@;j zfbX>vKsx6q9^1)(fez6ojLok|&bZzR-M z*@9&xk4zIe&`U=*TGuDKr#ZmEJlqT%5F9CFVjc2#ErQdm?VP;|W0`TXfKQ$p47~w# z!TQR&=n5-C0nDwmZ|zEHE!LOt+3gf1G9{H% zS~`4oCrghItpgoCX(H?NDd|9`-}CzT{~wS0;bFTg?cwTrU)Sq&=_GbnnHFYCP4Y8P zkw1L8#R2w+7ay$N#BMc0DAxZPo&H9oSakZ3tcwJM>66Vk zf8Sgi>J$$n#V^iEvB7h%@>B^GD$ynr>H*q%Kd~LZI#stxq<(wdkml0jwI5 zab05BI7w5yoe%XRg*4GiSj{CzyYf2DPPxC&8HGnhrDqQ_Lbq?DcNqUxmo}cSU6%hM z;E!Jh3af^Mh6=V;jBkn?<+jfcTE1b5cHnoHJ{@n@(oIW#`C_3)7S+e9RIca>(S1}p z`D=#P&_}10-(9kIjoaPqTQN&%ps1{i(=OTPzH+f+@ZWZkek(tz4#rwhsx&}f3<Yk{NJ>Sgt zj%cM^Yrw|KXU+k6qR_j8GBjON8~!IcBn~6bMvcMZ_Hx%g^Y9#b=Rel4k2a-mt?fjh z^mKC$cFL50!E4_2vbl>*s8jUC4{)f(AL_jHFJ@D=`-CBg@ZR@|Y)vZOiVLYKYWwV$ z=`Is}b>Fk5RQVfYwZ0hya*lRGwi_)~wD8@kUrw?VyJVW1)Kr=5X!;|~*TH4dN2wQZ z^8y$7sph*R&Rx2X!geqE{K~3`ruYf-*I5|=zV)BNp!*dq17NB} z7T?2mlrp$0?yI|s3a7rW6N=0ho;!7LO4+qs^zJsU=@#w{#YcyA(=Cv2&Su2{g739$ z^LZH&kamQ+8;@AYEp?o4_lkyQ{1*^bXz6;IeY?DqVCQXx{xO*`=#Fu6!Q+~jtI^iE zwZ*1w>Ipz3ce&LL@hSfhVm!qY9bVU+cZ+Q|vNacO6u*SJ7!F!s8pxd6hucQZ-v0dP z3ZGE>OAj2koJ}@YZdnv|E9@ekofhl$17FPeS*>xQO??_u=9$T3UQ_a3PO6V_xsOyP zMH}-{F*Rup3wI&9VR-TZcodJDJb`+kpSXK&1NUdf*zEJm>fATb~?@ zY7QIP`zVVOQ~TOf898$_Q>nN*okG7xQ8(l&1~yiIK6Bg0@p zs&>(%p{rOiDMeXeQsKSujCCA}w`ZaH`S>dav~DQSvITu0|D%V7z+=7_CW4N0C3A!P z=h`&9@@hD@_~Wx}=4H06GONvH?T4!A%+JG^=7}4f=X0(ZI8xL&trnw_5A?I5`~fL- zXt_hSG6yWt%m+=!@3M6};8NQqjSk@jRCSidY`n0A5o4!nOzxvovB^UBAanWT3RN8A&HnQdgpCDyC#~vER+^(t zJ$dF7mzhVRMSD7yoGp^r)y z0tu}MC87Y!TN4(yM(+YkS(7mE?ou???*ma{_s`GAuMy$To?nH6qi7eU*O!%WH}fQ7 z5E!WwJ)^+=nF1De-9YbYe5UI87z`k5vQ1sGXTAOuYjY873Z?gLbnH2WI zwO2dMHOITV&ACCm=WZ?es^pSLKQ&NOUYv-RYYY^&-5sfRU61eM1+^VVu^E-+cTBD#~w7Tf0;Zt#%W}%Nhc1= z_4h0wZhFzYqdjWQ8sXFSXa20-^>s+hXatn2XU>nki=hkX5pS5|=0h`7E61i`o>T|` zq@l<~00%&cc`OFsCG-kBH}7`lar+^=%os&b(wtjC2ZQAq?#C={(y1J}gjc=aDFf{? zOy)a3YZh{bg0S1i{$mQETH|zOti?dljp=Ym=rK)C#DIQQ#30ki5X3ZzrNz&%&v=Vv z7${I(w)wht85%wD5ec{61c3Q6VfG4iE54@Kg8CR9PcR8|IPa>014`AQpjYd?Z|<_X zCtWR=(b%iX7~gGci*W!a9@uf#I{l4(={ue$^am-H+~%pg80R+|pS=gBePP1(&vvB?D;YG`x<20XBlY$#|8YOtkTs&lvgB8Rj!d9D z1=g&14K@g_eVy;s;riNpR1#FTFz!o^njY}^i|-+A_Zw+&p=>=W3-933#2aMqYbO6A zG1AltuZI@GIQSiR|7ihcf3fmZ<12@tuUNdc%g_$vZ3mMoqX7JQzg9aR`qZW8jccc@ z%TSL3!W)$)rT%;W#olR5fzAz&j&?ROsA6IZ?#`BfU zDF58sNQ2R}$%nyszKbyK6^#X1KBD*2-!#=*76CDrV|QHdMpJ^WlfHUg@ig*k*MC*B zMfA&J3(M%;0MBAHQ8W5;`uX1c@SBXI`eQ1b+2sutep z*BUl-USL7s3;SLY*a585(1|I-`)Jgn_RSEKfubB{lnqci&O7vW$@DKY<}-nQaG+6y z6fkoH0wiOslc?A}Yv?_hwD<5zq?$n5TfNOMo*ep1Wbb1!4uz9}fK2&lAVN8Hr7ZL8 zLGfXP6dWH65+iRC3ps+0(znoX5Wry;?`IfX?bm0#m0nr)7Bcpd223)jAgyL4T{*mmcKb3}H?{GV&n5%t}`cipdHL zL`>ck1O|L=9D|6X^wvTYr^%^vtlL>M15 zmQI>K`>ZfR0=B=IzCa7_MGyLq!R!M({-u+%O;na82b@vH>GI?n2o+AN&4Fv$Ux;6$ z7TKNt{e2VOe@hFh9EDR?O3i4N5fjn{XjrA;qwJQE;1T63?2YNC;~nyL<;rhoAS7-N z3E#m#qw!eS$yD$-$|z(Ks-@Sk+40jAPW*v$Xxl89fTA%TZ@Gt72F>C75+%L}=$hha zsN*EHBf{k2+GznNo?~R!MneQSFyxwU?bq_ApL!Kb4Fb~*FW<&i)SqbqwWJ-8n7wM5 zt!PM0k4I)ajr7}qjD#hhsR1O`w-GQ^@iZb0VcJGj789B+drHzAuq0VrAQvS?qsO=k z=a>NEJx3KHa@XsdcVgAblO6wUKhljSkxHS2jyDscAuG{y_b0$fkl*Y#2#%pAmr4`X zOPUw6TukFQECOv4YI=EP%9#4x9;qC$GYCSu|8>Cl z!&yf>lR-dl96gE~WM%u7Um@mUh2F>Vb6VXSQTCZ?o!#8ZhLIJ%2%iN#V&|DBz0bux z>-C5-&%BX2w?Z&iU^_zta!Z<|ApmB2O>ptp)+wcDs^4%W?njYt#od zd^V(eLOkgC28X0H6NDsrZBFCY;aD7>#d?G{eVG*!5cr^qS?Qze`@0dtClwzhVqwWq zWOCVjs4Vfvzr%$tsyn=tsO1*YGM5}%!-z4OwI7;3T-z?bJgs48c7O?MjfD4CAd0+qM2#^>l5 z5hsaKoIP9PK>I>^FHf-^DM24=A3ZHGKkV*>k8^?#h4B9|BGOXj18nrfHLI61bN)$1 z&;$$Iy1c++uP#{0Dprxdyqs0MArk_Ir=RtPDKeqD?N+$Vp96N$m5BF3PwOc?Ay4Pw z2G_2;oL{!hwG*xA)m-~@Ltk^%P)x;1dRM{@!b~cMV&nmrfeB?sNob62;0qI_++X zrlSg~zD;2}<6a8xvP3|5K}%Su@uS5Z0UEC^#nyX(JtrjC&}Rt!oVYOw#-eh8K_Shx z+Q*}K0_vF@(RA-pEUuwu;c^6Tzkkp#xEmN#^GZvAM%UxK9skY~R#Q>!^nCFewaAL? z^-Fqnpya_5E4{IcE3k*fX1A<5AN2 zYM(}boZ2+MI6%Nm{-xbMca)sf%_e_U4Fv%OC?4uFcz|HR*B2kzVV?>7@mfPcp`?{a>rwup@GQnHxHgIK@#Q)td?NP^Z zWBBFk^p4>lQNkNn=S181YFAYjX59;kS-uujvw!V_2>Rj2`0u1W9$#x(#_L~;ofo#} zl9N>Z<%k~Fo+vw&%a^ra@$%q%SmShOHL3_g?%`6SXKLh})n#CKU5Snhng-1-@mkT{03H-vayw)ow($tx34N6R=Iy-I^zw{2c8SK%Y- zm+^H&Rd%Fv(WBG*laF>8G!2F1wMzBT4G>Qrw zH^~GN{Y#$vaP37IGs>36k-&A)xBr^gqW88g7N4(^MjVp&YJjD(|B>&NiYj8Y4^l_M z36e+q8Y|v8$?8nqQI}<3%HL}vRt~2mfcS%f_ADgt?+W4zY+D~qPEExD`fQIeWxl!d z3lZ3%%eykr>)rc$12H1q;X`r7M`mUoUK)_oxRvjiU^sq;=-!EQHuvmQ)*!W4dJ?w) zWqR{{)S0M<*O52V`t|I{b7g*HeAqronB{7cGg=(GW@Kkc{|rM9Pt45v!ls0tt2-id z9b6o3O8x?&ugi$VRh0OCN3bAAKOY0{TrU3gEJK}qOR`GBNqZ|f^VvxYX`4{h>ivEB zNRQGdcJoYO6&rq0i^!;^`)T!Tbd%>!S1iT}vF?hV@H7I<+Z);)sB(}jq=mfgS?z%@t<2iv;u0QA#ut z2&xACZXe~=*{gQ+3$w;3l(%^8h~Bl6FN}>!z&?BYLK`6(1vLLQAux0PDoL_SvkC*@ zd|dO8&=6H%)w>D36R`#TaOhe!fk$ZKqU_KYeODbehWDJvg-5mdK{qSw4!G|Su#_R# zf!I1T<0++Bw?%2O>CT_q@sRyGEZZ|H3F=Aw4>9;2h;d2Qh=k<-y{!hD28%S!C@h66 zbflo2_w1iG7*%oHJ>eetTTHJZaNWqwb{YDl!T0HzmE>tQB*TqENLLv?SyNcCt=W#V zSbB*XU}6(pp!F1Sut2>psm= z8tTEx;>Ywu=eESmvUTm&prls|llO&S)!n3j#*}s9=&W-CF?W0Y+IuN@i0B#Q@+hPbn)704Vu5pb~fBZ0=62i`%kO(r)AP_AH#@uivG8czi&Y}U*`B$K2aHY zK3`^)ZqRtG8^N(ikO-hLQIRJSf|xSC#DK_-)IqIKatE0!gAjHC7Lmn)=Cc%cd4HC2 zRcgQU$|bpB$;`4Qfd47u8a)@1y5!WO5e^uY>Ml99YRNIM&Ey;#xB8ZDe}kDedk#N3 z)L>cLhis@?spo2P%B;Fa}9s#||k-1jbn&C_qBg`*8$DL@TQ zaTbysu{wl9XOrb}<0yltL=aq*X7W@rFo>KI48;#IhG*2;EtZnBwq5{7G0nQe@CDQV z;1}7Ay~=x1|MZ;4j*gc%{OrczrO4p%TI8)ny9>Mzvy-EY);>vu0hD-72BB9u8-(#D zxQ)u4kCFTxNoczaB3g&-Z7dRFFKZRlp`ql!kufy6YJqKfA@3{T&K&i@ayyYIdp3!ezt-=Ik zCbnF4sqVYyJ*KUksPSfb>l`9Qwh5cEx?(ox3C#=`RqYqe5uG+{U1VZ2NTU4t^>mHslpM zC<+oxYXQl*O5JQCzb1Cb7Y4}eR2dvjR&=B~T+1tYaYrppRR+Xw2}rUhF(+*|bE+G0{GpX|tP9O{FD9$%gR`*HTb$+P1pweO%MHe5|K-?oTaQqWhb+K{vwg{G$ z=e87!dLpnVCLL4NKwanJAs*2VKqnaleWZ|{@`W&%XE7N}RBjQyB#E4dLt?%l zJEK&aPWmK473ee+Q#V3UbgU!XrN?-p^3M$N!C*n3jIb^pPq-I+h^B`4NLw*)`^77S z$(+ddx-|=bZlRu(vyQkjWKP%+teQyktT}}KXr8a%pE%jqKDWJk3k{r~p+A<&VNnrJ zuwj9}{AyG8eQWLW=1bv1r}HCnHz&i!>o(T$p%g3@MW0_C{twTiY~S9s@Y?s+ngrK> znz!!9&)70l8eK2U%y{Zl@$Pxwc2CmW?uoG|-w?vu-Vk4I1!qz)&pOnMKKRN}R4_I%Ly)Q&21+Y+@8U?!9 zU3VJ(>I>TiX4R0$^c#Sa$IQ1=zv23^Rg5Fr_2*VNAVYPRbq{AdyOpDdb#65{T5bj9 z`BT3RsY=9sHMZx`y-~TZ70r?(D;45QLo)(7EkXj4kL=l{sBDWH-$A4z)UNuC=k`N; z0Qxzlo=}c2b0B-lyenedX+|pxX)p^kxZ`b2!0_2SVvN}8Xe zHbSD+$bCjUucjDVUc@z<_lt}Vyv&os`7wznD|n8Yz25954=75^6>k5Xi6ltRboNg! zwppt~jx{=qg^twd_NH5NVQrJeaNe{2Jc5t*D$>g2kL*rtTp&O1|*Ack1% zDaz3dBoW>bURCay*PY`?60w$NI29pMyP@npR93tzuRfZ0@+f#rh zC2z|XT65uZi3>iR;^D8eZ+>ZFobK~Ci7_O9ZoB=uy6nx5q6Zg z7g9iDIu89jLoI0?*p565=#D7!CxI%utI$!wqg!HFqW3O25*)FxGc%64fCO*Lxx2C@ z^y_G6Yf0;+1C9z!X`(T;PJbOS6=_PR^T)Rjek;tVWNSj)lXEu+OtWsoS?==JN%s!Hg~v9qQ9qb?syXAzoprqEC?@t;-!6dE0~Vv3bw!n?ci|xy3G_ zy+}h3fx+)j{;-V*>BDWx3q%zF8a@!J@qdL+>^wPw!B7(w2>b*^&8h=e zAopwsu$ih+cmU#4{VXUzHDP*Y3tXS83Ev3zxBu2@3wB?0OW>Lh(2Ni|44gIM$B=<3 zmyfy-T5Pl~5tVuuA$ufRs$VQIB{O>#z<|J|u2sco*QuDsE{yZX%&{X`C?nU~K z_tzd-B@6Jn>>UJUwGT?{I=$xJd35Luq#@;TpXYeotSZ880o4eaFU;nd22<+F2n>p` zvqGO9`#5Tx`;9{yjtRK**^0@8!Gkxc_EKwvYw|z?I|)uu!OZ7XHH|Oe?eR_1%LuWt zGY(c20l1DKQ0dWbns5>nRRNNZ?9NPLIxD>cBLl>x4iM0>a*09>$Z77eGr!`|sgs}R zt&wKC{Nb#8*Z(g9JICXj^TK_RKD?qKaV-NWcsvRzY$3g9q)oJ427|~s3eNHHY8oI% zp-MrXq5-}1e!z?#=an+4NI<(L7^GWKS&vFD7~&oZ-L6GP{ajEV9J8av{9PzWIhtPv zLusnOMj8r6UUHEmS+m<<66?ltgVvlyRjgc|cxnN;-;um%qOG!y*iU|kbYhVjVL)6> zgjWq;>XjHtMn|%Kqa^(bFdS(RYch@oh6*~Pcqt&)Z4(N0rhgn>gZxM$EFo)X&4QU0 z>Y0fqebC5xSnrXl`GQvEao5NQ{1Prsp{~V5b-A^&JL8jJDh3J1tGn?6Px0DbA;$9; zfSa?sd}w=>)@z$?C@;Gq!i{y&TE%0pF2d}ir9v(TbR^<9@lmq*euKnTqj3<;o3%KWn4t^(nCa4**LD=+PxB8PY}SmO8*ms$f^1VOtO zh#yVx&JA|U&q!#bK63L~l8iQY$69bZc=%a=~^xV|*| z07=!S_cvJSwtM5Lw8B(W8%z?2w*=9U*6~xC$4+XNv@I0P1SwFk^h5GN^y0ocA8=iv zCL*DfLR!4)9tp&+IVAeE>+_Q&mgBjpXTD3lo)bWU3D!=SLtr(mlbGs3oCFq#_8Hvl zJMo>kQ4WdD4iPDT%}p&DGyV3==S(r9DeO2_wWc`9O|W1xY5Ii-*?1_=Y(i?NLqFA& z(yZ!3%3~YqH2c)eZ`x}Ju*t;IE<;6i7z0bm^TigDM(T-?YVH`Y``KhVkBz=RIXp}y zPq$PNXg2|=GH=q&Sh~fNa~H*#w6dC&#x))8%@JxEXw!!)(Y%!yN15Xz|I)XgqC%e| z@-vxFQ6{m8O9Cv)4N<_&TCak;F3$I`R;?ovnAUomr#*g`BXQ@&AHie>E3}QBoj&N2 zIs`KMGn}+T5!JQWKi*4VdV--e=M6HE{$1v`ML=}G(QRvcW5LgLkL4sYh}8YtKEV_H zMfe39?|w239_Pp)`GakCX3y2FK1o*FgKEPge2%aE&_N1sa@{YnFK?M&Dtu`@Yic2q zq~M(?88(ChCg58@1KV10(uOf_k+M8+X#63ksh$}G@4xmUdJ!vrEE8G|vn#ozQ7YMMsM@26uq>l2O# z!*2PtQ#jv;FTd{1s+Ziqgl)UBVaHIX@-*)@7iYB5z zn_cvp9pZLRyH1_`*KfsMTWyV5mjQ6M#jEHclfplr3fblC$+}M<2O}hwwlqsldmu@{H?Qc3w`(!vp37j>=SQkJ63}e9$Z!+q z2a0C|-646{;zdb6;Yo)Kh~gwI(Gafk)^Xr@KQ(YEZ5b1>>>%2p*>#>4e}0XVM(H{4 zutu*7O1SAzh&jsjkEcd+^y1`jPa3%uv)4x;aG)&ST905&ICJb>l4LGMbO=9R2u3LEQ1Uf+MS^8S~T$z-k`DV zVq+^u&W`E>FZ*beAY|QaPGEEeQR>9TD9d~eaW}c>M{Qc&z)&M@yJ{YS4i{ONc5UIC z_Pe8Jyfvl60awt`otORG~vhwsoBkr)C%ot|?^gMGy1j~5a<-0l1B zop-Mvy@u_#je-{bT+{A=IZaf^Gj(`CIbbBD_qfIq1FPI6|D0=++gK;s4V@b6pU%um zA5Zu&{vYw~bfC1;c-yR>E&JYW-(L>5XJyqXY|E`f{FSz(5AV@7Nq(@hRHReo&$Z8x$L`LFcPk77u-RrppV{#ko8{|)I(7yR_mbv(X zxR&BnGom@?L+twbV_bW{f`P^t?NGmffS z@(zk)yl#n>$n%wq$WxQfT51uH^HjF?WFbyMjw#u*R-%jpYZ5GKNW>p7ik?D|BKeeP zw>DKm9e=X2MuUKIzF-mU7p7`sk1-huXv~jK4tk31A@j%E;SonZ-*kdnI)+V+7EC1y zc<)!E^Rpsc7lh{3Yw1cJ?~2eBfN z1M2+te+qRDR;T=3__*IyZeWPY*oiFIwI2$A%YXd^Ja7!OHde%LxX|W$q`eU@Yk~2$dEGVsgoQV<(I6mBc z$M?@Ui^c+&8>SOc+@H<6CsXCp9eH2_{V-I1H5y{GNMC0kLMPRZfo4iC6lt-gZ=)w@ zWp})0DUltX@EF3|1>a(9jpBs%V~%3Wra?=F~YGVgSKXVZai6K3a;t=aFcni4`8PAOS5 zI=kg@o?ub<)dAcwua5yt$8W?|k2R=6jrG?tw<~B7MyGAwrSpXpC=hkh4l7B1cdid$W1YNam(k(F=(a#@FwfLmkf>0s~;iL!KsGg2rAJL*ipkn zf~Vh>dsdi!M$igL_Q6~0(I-RY0~Lh2b@*u9yl_-}gCgZPF85i84;E6q*QtFzMH!~o z#t2*W8>t(7^(tEjucV7*$E?QGC0*C-zQ&d| z$@kq$P(Gqe8@#q}lF7wxb@0t)$20jjB97mBwqjx)S2B=oMiW#> z>~(+8Pc7rXV7l_!AANf1GdZ{MYH+o!{z~?$#Df7IVC~+C3~`8x&-?R^Yx^IV#nH8i z=;4P)P?$`impqsY4agE4Y(J8C5|{n9QBQ*`L<*dho$Yf z9!2cYw(nqZRA));l1wjF&OzVOZ59X9=(=H9&cwjkD~q zZ_e4=yQSRo_RtrIhZBgQ)Lrigu03;ZTfzB`aAe0*C2otbR%~ZALh;BdUto<}XD~?Q z@u$FjuwNGEuaSiI@K;-w#)?U)LV_>t{rW)$SBcyQB{Ji7j5&=|>aZe%_n(24E-TWH zkg5evoA*|ukGdz})k$-}6KHCp7S;qR1PyyAzLe;8F8`RM1Rxr+@wmm(_4q{|Tl8|e zBB=-h|LEkGTwMT4xE0#B3Fzi7;Fe2!GBKj37i%_PTT{bVe)MvEOFZ7;gXa zdCE`(2VIWWb5X^GXoK&_b(I4{l0Yan1_m?I*-7b|lZSSh+2X#+fA|w!MnSn{K~xK@ zCL18BhScqa}=T8H|p9VnNsA8H_;uqkfBykT9kwXdCe6AVkj z=xMPj#KLlAU>9TIBHhD}9_W*5SeiazE1nE4swA!sjxe6~!H!hB);n^wg98_yHft3V z#{oVNqd<0Xs>4|WKGN9e<_?e{Hgl*~HmA#f)kg-5o0t`2CD4#S?QGEl;4`=;grgL( znpOY*4*hG_xR5 zq<-G~2C1(HHGK~iQ~7#d`nIeLOQ4_eOR;F%ljaXuEou*cNy04YvDhy}8YdA4g_wfn zhRag*bEhp`lIU9KK|EKD@4Q1f+d%WHezR}RYWe&q?5IuJx(vzb_!j`W3TyhkO@zB9 z&F=wM)#FSbUGc8QPMN;CXP6{SB;P%T-7J)^(>>%!P)D;l5~`1 zE?WfH+|r{g92ltTjVN*LtB-dXG*{;H!4D#Q-f#6ZbqVf8l!>8d{|jHWm>vUeu#V$< zoK`)%U$>3)VR!Y{9rplga-hl)o29Y=6;+pvvh<%e3+FaN){W*0%iR;Pw{q9Ptrt5( zE*IEnnr7Vnqn8?hw#@ycTrWtY_%;0$J{?7d4ay8ASoZlK|A?lyo^h4p%m-cuhaxxv zgzv0CPwoz3#+>xBeZZ1oCu;u+941Hdvaq5w0oems@ zPF>R5IiiOCqy%(R4?dF#p>5XX;gZOw&{*%1+hJ*pugCeJiGRG=H^~b1e^u`p6Y#rZ z@QZIAQj`mM$bFA2@SAjz6wS}i&M@aE#x<~GapVbxjLN$Cj(&Tr6czd_t&WiUA!ef7 z?iCK}kwkd26u+Kd;)?TUYlLL|l8AAf3SwY;o6uhN-HHgi3mU+N?V3SQ3}N=)J^{Y8 zVaw^^kvH_FH-dWGHr-Z_g!KA?2DQr>9Ww!%c%vsOSM#hUUEn%Y9`Ck{pbVyCQFltt zt4xjvIXso^oK*{TJ60ivvJk>B(ax1F<*OoRBbg;fMhK81^)3X!+x~SNgbMw6bC$Zs zHtT<#wp{G1Iz}*J5vpL8C|i5q!uB^x{64c&@BYS>05fDpWIIZ-$_Zb z*-kPm+cz%DtKITg7t=fgjy0|u224t6{`Mck@J#ESBKp4UGtNdVoNw8>u?%aFvVKCi zO7E>wB8LNRaqz8cC(}4fkwh0|Mg&)93tmPPfsRUqX5wqJ4+*5y z-P<^k7DUuFW?F=dyu>2gfbl%A>5nvHIn+Y5t6=kzQH<=buYeT(7e$v3;OUL2b8@PfVPWIIpJa zetUitI5{v@W>!88t%fs)RP=J9HB@6pe_u+pO^K@-1LGjy1f))QL|G@|U$n|ARd^lK z*uh`H>2UK(Fvj)aJkL2Bv>KWzD|~8ww8frGMP0_Ve-2ADLWWjD$B!&Vr@)JRmaqK; zAd`@?(Qpa|~AmL^)KlkSQXFn*pzq9_ zAL-xO3jC^XFw?+t`qw}M4TZg(9m~;C4%@v*X^6TW$SFX)6LS}3lcdPI{eoLUfsY$v z?OIb*1$M01VzO``6XAskcPMrF#tMLl+#L=8rHZnXf6yW?k`-v+MpHjlB)$UCt6z{t&E7%B{Qm>ILL_$oSOq2@5Y5pVOzY9&sHuwCWp>iJxngmcbt8%X|LJ1CC9+3AI|Li?m|7#V#z}5?5-PfjfXY| zNY$QFrUWfJA1)saSt&ulGnAFUv-XwoQ$ zYlIyiWpKRv&On3ibGj&D!<<@0-NrOmN#)6X%chs#bw744*JFe^(aNBk5d zX*`wOWP;$iyCRSc8_%TiG82*~qf>lvxm$?@73gvuHv6@|-MX5htrgWP-c36e zoEFf0#M+O8yWoxPI~&-f^EhUDJvVdL;YYWk4L4j%F`hPaA+g-$Em~4 zgLx0RwQzR1P}J&z7_oau1&Zb83iqY(EM_X&9)$b(F1i)|f)D}_C6TWyal3ITC9d;I z8ROoSQtg40v|+`E@-@Af6*&>b%x7UFvjN#3rNHmpWpN*Jt^M%Hu#JSf3kF4#47{>@ zEDVtO#hBZ!=DCcVz(C3^dL%BK?|_$~iLt`OW+TN=r4MyD72+;G5z*%d#kg)*Cz@aM z76C8{?MP{vNY2qIsPd~|l@6hW!74pCaIXEFh-LkrPSvWF&_?X;euJ~bh(3FT%fK_y z@K%A(Ox%&pb*X!gmFeu>_fMyhf4#sRQ4d>gdk;vNa z>eN{L#6YmYZeI}Eax7ed)ux}Kb>N;*`b5JOlf*|(+R#Cim<#vu2)hixw@3J*ULx-! zX!`ou7e=)Y%8FG4-}j{9(E}uzft4vQUj!ru&6)5q&Rhg;jh>_Gaw|j9Q8~HmU#liD zu%DAuhc6;rGU4Jub!q+{#l&tl=lhW}-Xyr-SeW^n+NV`#%3sS@kdffNqdJ7QTt5v! zNG4M>pluLAFJ1{iG&b55jfQF4P%LVhbB$T}=ZgmROI zF%cm~jnv5Nq^;tISe{y9Jb9`ndFXuHgDd?6qm>HuK5r-a7;!Mym~y#(2B6JYw@#!M zHC(lj>|&WMxkxrl3C~y!H#u}1AD7o{tX@ro@9#%Hw5X<(9}>}nP>01BdX$prB7#i5 zRg#PFBB4V5N6f9MT=tpD#2e_Uu_@vprwGeJSv;J@`MzaQmb~|+8hBI zm2^Ump}`_?V#<%D<*N0pubOjqIA9#lkEa3Vr%`;K=4>#R3I|@a8Z^4t1*-z+n^7O7 z47ZpR4b*@Qu9*C6h1F7JfuM>9s_YHydJP@8z*i;1S4e?1j`D3pv^K>r0vv}(Ui-%3 zhih71yAP4Fq;_&-HhM7oZ&UsyGut(Hc1U{=A4l5?jU zCTtQ>VtL*h_2a%6^7mQ{q z-EAR$GsI_?`}mHaghpRG{kL1ZH#!K~^ntDQfr^Tyd7t!}YIULM&KWRkf5qnEd@B$z*lB^Q!@1@&TFBOCA{&p9vU z&J@TZ8#h^3aY8DFle_U`7$-KxwjPG2GYQ0TzmmfwT!WGeQ7unQpUPbUe{zT#DsRI@ zG6Rg>c>G2jxqw4QgLfH3vc;qXm}ZC>gCZIbMv%g>RxEh!aE~}^u;N z3IwMeb8Z>Wvyn!f>mEv8x;FNT{lBvwuu=>;ZmQm+tqFQvX+^6{rC=&hUKT^U82`*vcCDh zNE?N#KB1bg<^LqHt8R$ee!$Gpw#@Q5%D5Dhi%9DABaQNyoJIfnU3Yj5Q(@S7Hd++l zy^>-{u+L;^k}^he0R?_JMsixY_9%#=Sa8@N!U+Ch`;dxN!r2IxUg)9lUi1_N@Pm6Z zwvJ8ZurdLyPT^yjH3yB$H*D=vJ14}9KnCIZ?(cr*XZI0IUWnK%L|}e$=nG&ZG!+b~ zL`>WG$~|c;4oE7=?-$+(%h>rC^T|_5$fhy&7)P;{3qa1*le`hp>il5a%mF@hOOzGG zv{40ElSd{2(;+YQ_Oe~8b&@fH5koYRqdin=F$ztSRz;xezwv@g#NZYU<_#`R2gP3g z3voojlDW~b9@80I;cc#>$?yJ!X?HzJHlTJ6_f4|d{u!ip*ZX77hKf$|essaQ9|N(A zdDJ6c)4|c*i`Lrghr4_q)SG7G5vCwT^4 zj~is|*hkI*1|QHzcyN2FC&d3?K-m0%G%KayR^Y)-C;ccMM`Z-0hZqpi?FjC3@4T_m zlcMqO#6{Jg(N`VxA7*;X;<@Iug)rHQr@P}5i6#!ow45$$4^<_Z2hL!eWK~Vm4;2&c zc4R_;ghUaV?Ve~x3})0fkCj|Iwe;{uiu)5^kBL}Ig;-5bu{f&08tJhl&W_HVsH4hL zkACW$b7!SVOhgr!{<7HRZh<>eIaWIV_XMxJXu>r4MP$IX{7#gbS+GYGbl2V7Np~dV zY;0x>Pc$O(f#t9!IKvqM2`qS3XO1CUjgrLl=o&6e`55myJcj>`NyMIK*Fu zcJXyDBmG#E>1{L`t#|*(-bO;D=Uj6+DFrymu7qSv#qJYyb9`^(H#@4GS1z*D&Oc1% zxrPRFyjJ? zkKv2h9BssS96c0d`tGEDp;eK)x6%Ax@BPkXynrs3+#sgnk2WQ#vS1OZz!X>iYvqp zE>dxnvJ(;R)r*=VD#%0fej%NIw#zZ3j!zOkv|r#VIR?r)af4;Z9q|gpn^D05#0kZz z{Z@08k6yZxCmMebcTj+J8ny0s77SB{)bx5;YbwYrKtfctVcqc4&BBmhwIQ2--+ajh z){rWx7xu7MvxZFO8lUC;AJ?K{-Gg!=XifoYTS}yh7z^b9)V>(V6;OoASl5s4^nbeDh>ik zRt=MR%)A`HI~Uh?NSS79q>`a9wM8`UUH3hgGJO6W0E(p1tMN0F zDr6EeO`N%|kufD4gHRzv-}qn-7a+x9cJY`Tmh$ZIG4d;XI>#_XV}>Y+Y2&{rsv#+K zSyWZ0R2eE>d8qr*_sA=~I=J@Zs^`rqn1r^uD(Q>C0z2v)BvV1t7lpQwvzUBLK{Wo0 zbs07rFHntCrlhgChw3-Q?UCzuM5}+-%P7b5407n#K6-ZlvxeG3yCc#k%Q~TfyTh)n z4$gUhY??=X?xD%QEr~`n!`dMs);MZnIOiPC-_*hu9i^kFVdWx4%F}W*FJV|y&|?eeX$G(T%-c-zC`a3T{RoI2NZ-2?QA2LzPj8kx1$vXhP+jBuR2zy%Ja?KfvQ7W*M8unzJ=VVk4j5vng|By>8 z2OKe{OH3C8WuNH@S&4>FMPi+huc%qc%)@hRMjFFU6}KC?KyM3MQ|#Age#;r7SuTj|sx<%XgtUQo2@VN%8ufd;+wK;2SJ>ppDjsK0pq%!fD0OI^qilyFOsuA?V8(tfb)|Km#>fK z%?vk$csZ#Xw+b}|$%7`v5QRw1MK!KvPrX?2Y#Q!TRLq<+-i63tBTaxt74>#KH}~O8 z{S>3HfKiq^pLH}AUro-9=Pobq_aRnVbJx_kwr7`4=Kd4wc;ibo^Yr zh=*x`W=8(=H~c5{wLD@6#&w^HJK;uTKM~QAY0bYcvdW#%^L+Jvz4oJ}S65qZ-BS|7vJ%K=4I$(JI33M`G+= z;{G^i{!w}y1{{94 z=8$SV>mT3FTJq)69({Xm`tU(}XRmM{d24-mFnGA;yt9Dk_;Y3&h2H5=svsJbDz zS@HQb$8E%`mxt!n-qk_w)&I)CLx92H7=N@!j0^btHiA@3v~#9e9kK5HJYTzDRQ$D+aTA*k*#5?a z@>aVvk@7-Ncae(lP2#HhrMcBNeGfJ_Sk|XLRwdi*BWc|5#H%Z;ojyn{Ykz;9WB52-uaC_CzHFXYe%oGmV`j!zf0edr%f*K%^Y-wEN7ozj z9OLgs2>zLBh7{Q1eEExwQFf_)l&4(a2D1n?daQ*Pb}cOoEQ zELgrnhDymblf9lz!t+f4rm4s`F#0gI;&o)U{S#O3KvD5Gf0gyGAC8*my#7Du2j@KQ znJWwYQ_XtcH()z-Ufr9q)sqUo*-i34R3t%3zJ3gTnk(Rai^}Bp5xxstmC`)7iNX!> zn)R=@KAF0;?I!VYAKPdGT#n?le!UYO5v@;#R_#ZZoUZ-1)3tvR<8lZ)dTbL$cYsNy zq+Tg`taoY9q>tsDmkzpdAUw?NQ`T(pTLs>gxZmrx>65uq+g@S&?5pAHU&FJu;VIkY*_UuxVUtTb%5v$415Idv}&wZ=qj=ZU&GCVuDdwkD@+7$ zph-Y(-J=W05=bQaf0YO4qrQmEYv-i+XJbqX`$&UM&B|MJWsilTvR#$t^ORF7t18S* zu!y_MR;)3sk+vqdyfjP+c6n}<`%u4#<9`Ot6}#d-!$|A580{p;{2Q#s20=TgBTHvP z;oC&*?RaAJXxy`X>t_%8eU1>FY;-V4!NxHoN`}!w>%+-ND;7r{-;pZWZHaRa*#6Xt zrO}ORXptujt*`G6%8vAFfMgUqIMEo$)fUe^PB2o+xaw1JhRl5g^9{v}a8Vq(rE)2k zPe@@K$vk}eQpLT{rG5@iGd6{cyz+zNiVZyx-6_(>)wfTXg9K$*XhQygvXOfuk${G5 zJ}btVy)~agy~w=B*9XYq7T(sJ%`x-r-ps!(o+@-3bg)M9qh_PJ%|BC<%7#O@>ju5%zV z;XOqVd)0{!e6j;j*m7uMlU47ULlZD_d2LgEH>%*1$}J$0Af$yK_XxgwIf$? zF~@Ls+?hl6(AH-N2D-m5#3XTzTHkTaK|jgGVE8NuAZ6$-IVmy0x(eI7D&61Qatyg1 zR+}Hn!-mw~OXvPhmUZ=knZn=nB5RmldbyRG-keK(Eo$5&vaNR3yVZ9-R;4c4v!iiK zcJP1+`8_rCw)TM8{Q*SsdFPWW30@;R^97Vcf`)TWN-PnU^?nRZJ7BA}0xL}rH&rLJY8Jj<|2^m_%+p`;9Jvz-+`d#Eo1qf5lw~*r1aWvN^v?I4|g$nNUDuH1|0{qgOSQ!}hKmeysuKe<&*lU=QYL=AneM6&s4ph$9rWYv!5 zMwFg$cFJSm^<9I-Bl!%ls6qDsOoGi8-+8_;pxf{7e?i&Ej_Xdsr0_2tzb2Q(5Ay!@ zMa~|40~vN^h)H1;%rOaQ;E>({WUnzUB63hn%#1DIE*%u3rWdsfk1ZjSn)q@w-yrP5 zNw#DjaI1N7XBm>NUd%9itZ!D#)Q|F?@_)x!kfgoQbNaQ^ZnFrBM&wuwafneD!9|f7 ztGEhvuU0$f!~@t|_Lz$_lUPC&L=Heuehz?Aoa#Z@QAXxCA*~p5OHkZ;R%xpyd%s_&RJUgW2308-+rpCMlv3wWoUa7$yaIy1jk{2xn|{Hc;z0Z~tKn`nlrVXxJs z6Butm?ejCIceH8%A7xDB>K@^OAD>$~sLy|&1h@#Ao+W5H(hD)kYSyA2V{y|CM^)uY zpgK-pqG8lbk>Vt`gwDjJ{)2>HzHg45SF#83n?BWY5F-uhYxt5!ryyc1>gzw%mh4E< zLMQCFpbZaABmlGwCN5m3XnS%OM`ey#*qe92WT(TfQ(k|pc~tu2hUxA*>-Vr+hc3A# zBoLCVj+ULwV9Ohy*v?Jx0z3I1qV=Deioivmz;|?re=w{b|DS0hzv`@dzS2R7c(JI(4|Vl9fQt*hrsYZ z0+t>RFuE4?RyFz};7A+yO|a_+n|hiT;+6fLimlPjZ9GtehNnbZ*6P|*O{Q{`bPrQ( zh)HtJN9-_uaNrxB6HPQR_t4#r<()41!Ed9K)Bu$oO@W#_dRn%v%eCXDA^q%qXq8*= z$=e=y8_o|E?@xQ)R*-;zcJ&4cVpsVfPlVxt+v zji{4Hl3GYtOu8`CXWRXXJt#E^*O5?lg<`{I$d`_AU6X=>>;@078 z&NUOX;QYTLEx#c1jd%M8|gd`q1^rg-8TQ zq~*w#{GNgM3$EvIA?`WH3wvSjCOi7^suq^Nj@jUy0l|4FN@GS$o%?qa?%f5G(eBQ2 zIsGVob545f(!bqJJ07C^d6T3xk^)zKuRCm=Ez(H0&dmAPt_lw)WX46gTnD4cP1kk} zYT9c~0N>o#?2uDXq(O)n(bR173q>A;>E+lStDjmrXlc+lyxhFlQ((#SY^zt;=yz8i^b6zuXugE|VRT4Qk*oeD|G))3+h-fV5~ zcTc~Oz)`aLo9j*l)7iq<{+JD8Cs`q%$jRp($wHTUkhy|e6l*FXfv98%>xZnPyI z4{+(I)gCY-utQ&&?H$Dzy4Mt^PqJl$h##v5gs>?-NrU3(_pdNGA_XFDJY2>=!Gc(G zVF;lPPvhcdc8cV0RFa*w5h_6JU6tQe2*vjcG0x0?&VS1(2c;GlWeF^mR5GNp+g0gx zxL91jH{$dstlf!MA&|b>yppBed6#3Kq{^wiK(6<60rC){G4E_{6>_t^3j6at`p}!P zPq-D)H{kwQ@~{~!*tpK4JK_(2PO3TWj(h{o=~+wE^q(^D5qWytRW9G9eA`GGRjD_B z6rzkiX>R63TXA&MTk@nm5>)HlvvV}(%7Tln>P~Qihb-3gEk5|TF&hy%B$)l#p42L* zjLo3ygR`bASX&%Xx?rs`w~OosUL5*VE@bk3N3@VFW)0d)Ttg%xZ#OD4RlyfI?KPIQ z{qFMGy%T$FjarNip_SZAJoGU8yN0Z>?S&ogrsF)V_?*&U1DUHZpm$Us-eQll>3 zdAHS#P3XIF{>mSM59Kna!9tsXdAE7rIyjoEwM=vt&dZ`d`hNWK@mbVxD_84}1xLuU zkN83|*Pcp#7GCUOI6eK)#wV!PpmsWSly0-K1{D)DVZPi_i8QreOH_H=B3ls+jWJ2S z6~`Ku-*BqqdS3lLxiH?N<*>uZWa4Jt{KF*3)YT+bo&iT1b=6Qmt>x2t@b58ZkGHY@hM+wG-`e3 zx1S^k$Q~}^qTpIthVnpv%-tOlx43_b98@^_NDvwEY^26)mF@`kT#L zl5d>+Poekh=EpCRJgowAC-%1N%pyV*Jx!;Rcvx#QZCD9b()z4R;sK)DU*`CB)#urY z(;9ZX*(xdd$c7hnUfr0u4tz>!K3uRiIYkmB7B~i{ee>wp8YGW4+2mJ}+*+5uLpOcL zXvKIPtmT7@na_$Iof;_4Q2$V$nmOIBUFp6zHm{?FQ>Q+qVkVywlj2ihzDLdHvfRgJ^{UUS*m;h(0p zb@}n47wz$JwE=vie-GC=`rxw$DobyoTLy7Zt(lF;IQmTX*N^S{5YMjsTRwGL&K3H~ zOBK9Iv}-i;6X_XTN+>WLAa6r4EVAOk!&AJ zNRc&UW;}zbSHn5MTSd#`ZL!TLd2yWP;x2<8IQ`XLdW5~SQzv*zh->*nh=u$KR3~D& z$Y`kEnCakNx$c71!j}KpZR7d5!S0T@he@pExw4m( zj?$aX@Vw2WiJ%I_Vf58&+^5@{m+D*%RSRDbzf@dy7iD^)f=^AS4A>Ccb6MC@xzTky ze+@!OSARzv3hoFrFGtZ}A^La^$rsZJ-rBnAUY^tBTKJbsmWt4{I3n9TGm}a$teUzw z{r%t9tzD84K_I8CGUkWYlk_%mBpFI%rp$gpI7qoivci$BuO)ut(IE}2W{WWogm zZ0(AUe1v!6$_4a%nQjKY<#7E14yJbsT{sT}b}Dh%C03lQ3<@k-*8BzdpWQ*JaGt$9 zXUtt{Lc?`$xq9eY=x_8N!3y64ZlLqBq->}0s5K8t)ki1STn2W3f`MM3S{Ygy=A`6H z?fNZmM!0c;=x?3u+L3g)dGTa^bol+AYO|)V4c0F-wrYLdE%xRy0^o`VW(|^DgUo8h z9-v4gOm9!>+04;KK}xIPCul9Q=WcW_d2_|*5`L(}OcwJ2bSb=)dxMv%$L?CrWy1yj zSaIz1w=+Qd{b#;&?eTOt`N1;wbeO5vj)Qi@{7Zdbefi)J-QhRBo4v6G2W1{3iL8R2 zv1YEPR|!wff0;tCh~XDwb;&iudv z4pykLzXz`++#>mJ4WZWF9#3XXZ}7os33%oFO6sx7w!Ekb6qdl3B{ggx-$Pw*=)$n( z#^0+J?_~QKhwmEQTW<)}XA_ve4YBl&qD2d6{_ufA2sW7&G(kDU1nJh4O_qvJ>P20F z`8A5!Y+B|$f%N4cy!4#2S7r5;fn{=8ipSe+D}Si#<1J{1QRm>Co5}M~%0<%QE6Y*5 z&i44n!`2KJP4)?V&WReG3Wlc?iO5fBLBEPm=X zew%4M_9;elok@TE=8|+=#0ZS#Ju6n51*r@fxvwX>8#co<%?TB+D(PNT23oc8WUdBwPg%K>owB1 zbynW1&JFW{nL0MpwWU&Fv^%!e!{~L_A`Rv2dA?e~KB{c*lbs~tHu{EWAfD@3^G{jX zTJzv!*uZ;+S?>`z_+)$fHcV)XC|sny&db0*jTEd9eX#-c{A*(i$5T3w)wbL%^@$FQ zqnAF9!H>(b4VMv#95sUX)wZyOLUL)W*tTtwGgC1OmXz*4mqzCz;0Qiir&;TlJ1h-hR~_{N&Cxmri#&MQZ-uE=Sp&NT3;fVH=Ye4QAQnvNyl%uAhv9u%9uL4Fwa@#n z*&Ie`D4)$s!H-#f-np`}PNFp7nn$Kx>ei5(I0^D8J%d#x9S@w3 zjl0Nh5ydhI3G%>f?Uhp+uUH=-w#uU9-|Q{>)3F2*BjiI%uJ}*APhU)ONhg46T$=m#dk38hB0fu zk_hqUEO@E9O9s%Yfq95~74JqhpX5hvE9CN1r?fC-cAH1fWx(OYSX1KE&~MOVe|rIa zCfML8^As){ah)Oo7htYEi-67-7L_s`WNx6eOPn>O>#XJS5bdSCf@Zq|7~1^oWve6WM`PM` z&=30IQ!x?YhMV5dF)6}#20~E4T8^x~txJXtObhUS2S~>FHxyr=ZF0mDHhvDobOD8JP3Lm4EFFPQrN zUOGl(u9ZGoRd@UT9Pvz&4V;l5&Kg)AaFb|vFGCe~eae81x0i_E1FOSY-*ApKQ6tw( zv285sWxb=oZKGqYT4~X%_CJOjUpJvPLd&-yRdd8l0!&kSr{e29 zi_^!3J>$~u4^1ErV=9hy!A04ub=x__x+r`5q50G`!-jS^np8s>UQn`u&O5pu zwo~3R|14#(X4hdQLe-RvaMP6M|IRKiKl&i}kV|$|Y-?N{8^p?XSoeN81km_U0@?tf4vOPtty2azchO+JJBbm9Ri5u z{@yo1QHCmG-gN{59nNhO`mfcF|8kTPda!?^A`ePYGUugbDH4x(+nVZ!0vL4dGTYV` zXAK%kJci>-xC}Sxgb^0taj|w|ZM!e7{CizY|=uGcIkd zDe%UROCo0DFhWt99et-XLk1lQ%pch?ucbO2H*vCmItdB}b`8VIV!)a7GunGwC-Bt6 zy1U-d~K7PTq2g44kqQ`#~N@#dEurTPOMloktRm2M?%*#DsV&U96P{Uz>%Z=M-uK_b<7bJ(9~$jp>n*q`{-f*$U>KXmsCsIo!>QG~65da9Z(#P+)B571)Gysx2J9@6zY{J-OFZI( zg%+^!3oUt&R&Mv!ux*r&c-v&`BjFbHQ zDH*j4!zZY^ldt{oug(PrCj4|}W5L*=@L9JH7!@Acl$7J6`JD@0>*cdfFX@n@wD+e-w@#`Z%W@>$(_N<~rquEbkXnG~_u@%@S0`XDKw7b1ErsT?eAIN3e&&wjy;gL1xo{be7npU6AhlNc(d(t6_N z0rDze3DQ!S<4^fnDBtk~+>MR}w1J+pNo1fA_b`46C;(#SVeoppK2gde6Styl%cm9N zo4J^SXd^*Zza9YOhbYc{f{s+;v}V4FPqcCE8#BEWh&jE0VTQ&CD?MhUPw;g18~w^z z=cmQf^?yWFTEAErmTs&V`}uje6W3z>Ex6vQtUjDL^m_)u#$k2n|D2bcB%7b|pfq}! zTSo^T=$wv*zuX84fD8JFV1prA7pJ6p)J3*dG14P2EikBp-#* zb-Q<%9e$Gi3At8v1BT|SPVRrQe9vQSU(&zMt`H)^nvDAi5JGszO|A#Lx4J-i`!`ME`;Cc^*E4M#-O6Jdek8M|1-;L-JSm_OZ+*@ zug#+9kZ)HW-d;*;$;SY{ecA&BxnfdF^18SMp*}gJs%f_A8#XKlAh_vzi_>!-6 z2FUzV^w74_CEpOMagk*mvC`t)<;BGR`TiDKVhD!Af|ckFnZsPO=s2aLVd7LrZbyEr{vy$#MsE`juEWDts&2_!)W{97?2p1?29wPWcCgJ;z;)%rY){=eI00>#n1SX!ZQsTPi8hqu;B~=P)n8-=@EkwQh(G!jzqH{?cjAsT*zw_Q+1DL>_FSK#vXeMYqt~JJybt9Io)L%d0^gCefRhM2 zR~6KAM33|W{xp_2P}2N(8HO)B;9*s*>}Uvg5A3+7h+!D7`lRVW~F&z6)7(BN(yK_UbiQI@B;~K3YF)mrLHOKVL4yQQsXYNb%62%K7GM z$%_&BsFvIFKw$?5oLd%<$~~=|jJ%?UUaYPw(rvBdg1A1Z1_!Oiy82I|gG$Z}#ODL^ zrP8}i>_uRDbt=+m`@}-@BK&#FD9DY~p>qE0-;qKF#-S=2CRir*^QnEZ9zX8jhwuOE zz4o9q{us-8@Ty=U33|)$CBI^Xw zwa(S@h@2W6^IozH@Z^Yc=vRq43xn8~N$X`4|D@KMl+Qxp>0r1`IiVQG*hqx?j|MLsvKR*qi52n!ef%5afwp;ZCpi|%}~-oSM6ovXoeDAO=>~>82mqf z$4_+K5tP9GGa?HP02Loo?^ODdiBy7)9{IU$*w_9DKGNs02t)3iuZvktjs}&K<*TVb zxsE&MzrtG00dX-sFdVZFAOjFD_r==7FJ<3Npqh@`?jt>panr^)K$D~3zN9jL1%3Sst)^{ob*XY?dpM=`Y64Ar3k_}n9EqajPOSsXGyVr1R-u%o{qLm^5Cc`wPmcqaVmUtfPXLOtz7c>DgX9KTcv`%ZMLa z^rYR?GRJy7?@QjDS7u%N2ygd&>kp{|S53)yIeR|*^X;1L%hCa~fSh!oRu9P?yd$S; z8IDEj;PW(Yb=UE2zHY4oY+rbZUd0i=te+F+UAzC@6KC>|1uQZ3DHoG|hUdgD1V}N; z1Np75D1uVq)Wx0NQCMDz0JY&>VKU{7^%?0Mdfz&i&=KYMn2{=9cMD(aO~EH3S-bNF{k`g?pSXahhX%l@t`bDPrqjk$FjelP`H4%cQNoLmBAsG$jM^&|Ky-ip`hXbLPnrHOI3f|++5X9o9cJfBDy_01%< zS=fxhb4xXRUo+(gtYe->MpSO!u9)+hleYfJL+g*=ceH_ghX11b)^{13A?O^5u2Y`> zRhgV!@Dj^;DK70DU-0e4nbAycmO5piDxa#GzXU#ougvdlHL+9(X`-p~dkIf>-52~f z52|)T`H%61ZSAbv0q#$f15Uq^1WcbEF2A7#|&m>gcPU{ox*s|%nu;-_y9`y1U8>o^8Q(HgmZP?N7k$uuJ< z#Wxsx1gXZ7+~QgQ-3#{How~ll7{1m`FQJaUdRh+%FL2idUJF2htU23isVSXxooYf_ z*lx!Tp%v;<4LU z>#@uD46#23cz@+I*m3Q`_LX5aW4(5r78~fbL6T}gVTvT*abLT>K%w<%;H}z$nM2F> z!ECS0f+MQp){`9$nwWh(tdFSf>$1DIpepZ4NxeSYs-66Vq*~-B2{j7RgldtK<37@~ z>9v1s%Q?jY(Tz~y$5HpwNA75TC}uV_XjiVmjIZmV@^)ybZ%q)W_TqD^7EhXkdj#e2 z*x$gceNSH}I{b9<4)lxM;rwz{jvlCLl0TOZzSmt*nmCVU>JnT*?(QZaR$kEoTVk4bH?x= z<@2t-Q;!3vuJ|5A#*5Eewvmz$vxF}^0&e# zz+%a~d$cL1*kqfg)3oXLK6qH2a%`IFo_Fj-?Pd5id@h%dOZL~R4WCtO{FYe=zr_Q~ znxz?6Zm+Vwx@ztsPF`pMo}v5lr9ECSXz7@KYH)Uh+v6DbHz{v$%SAu;HuHB|$MuG} z&C2jN{S4D}o6;jkz=jlu8#^CifI^uf zLxEz;r<i29;sW#{3O-ArZbCbM0pOTQ9=44-GR+vWVr?GK;B=85J(vIq*`MFqSPO9*+4`h73G|^t3lnPZv|=V3I0dx9HnRtCvUd z$wS~i+?WuIx8@!-H_7@;TW~M(_?^g75~gLxdCZJU)b8nI#nm)3%@ya}fvB8|+H02G zbMnx}oxNWAH`A=(LfhbC4^ry+BpSa3vx0WIpf@+&INF-EnVZflA8#Be^ZVMlw}9}@ zLSSXQzR=m2l0tJ^B6<;nzz2XdU4Jn9+ILW{;^MgmC3&y zw`I`3-I`&-lksGgq-P)s_0TE)&(L*{EMcoK4>4S6aSx7smy73!tz~fBogF?gwi6+8 zu#aRZ#DpXN{gl?gS_B}t71b!5<(uU3DF5qWXL%{Y(!ywdX9vszk-*jCw-e<(Ig_B3 zpO?oY+ZfzvjY#O6Mmj_2Z{mDTBGGN=?fl;vm(r=fDO!~fISp`SW%T;sy&`}PoDSy9o(m4=3??HN3T;0L{ zl4;mHCb29dE_LB!A@q^GS#5a_RJc~F99wotMx1i`J5jBbjkzY^uXd@ieVy6|FJKAn zZh;*Mlrw zzXO3KO^ikgeK1#jt1WYue!yA9>s~OdF<0C1%z{OhtMsbv-U>+n;;S$EIFRIZmNpXq z&WB;HzDjTN9#lJnB%{sg>C5vvP#?@%GUDAeA;9j_5J?L90o%ik<~_!<3m1g_4ug{o zsPNNS>F8q|ipHDZtK%h5a$Aw$kx zx9ZJD6RX#x`rU!)$EP~ez84{BQ&5!#=stFX??A91tH>7@SFbsJA$-HZmU0wX4)MiC zA<7qqxu*@z9z)}U`D`M&LA|}8Jrk4-<>`PG829hsS{{n*X{v(?Cw8(S-#R0gTAfKy zH1erfmMUiXixqwNaG@K<9PKMJOjb~VdzN!v0X@dyxCB}_^j<6;*laLCo_ z+rE+~>c#Q9jhc2t#lr0o8s;|MA zS^Gm5W5d}?Es+|voVu_BdFk6~H=_DjA29B-8O@yNF~!I~+a87*v)kBP6G34s9+rjc z9MQ7j3HiEa*ZTJk&AW8PFR%9n&r)UW(bIS_Ygl2LP|kR5&tH#1bpf>Db)mDFaXbvT zC0(A51;rnB9X>Z&c|R@Xw%^AQ9~d70*BZqPs!706p68I>`7%7{7qmb12e}`~5EfwZ zaAH-5$)C?po4$MH=Np|tsF@Vuj+{QRKVtDtyqUof3j=oqpHT4;wmr?k9l7&XeA?h5 zK&E(u+q&#`a^ErY=5(;!@h~^AIJ*^{^l^+}e6b1J@3dP=+RQN&0i4fz`Be8Rh%WL= z-m_(PwoPRB4r&rUAdRGW-)dZM^MXW%C&ds$8%3o&A8B~-MCxuJO;b$F+e2+VFMuX_ zj&&id@(q7tH0CtJTTACia|^P=xgh9)xA6)G)&Da$-+GIhp~29eSDeTel658(Pd)hS zQPLTqSZK-|RX|eJP?`Ai!8r+2@G}0WfBWaPMN7sc59e&YhNmG);Lb4t%FbVCWC@{eSE<+oJD~hQ#<3v#)yKN#J&D(6FsK8LnHGa?GaP{Wa`2Mh)R#a*a2( z4;I?2$ZZZRVcpES5zqzr(!^fhnT2UqyjdN1ay;#!i2;Vjil3N@+up+HQ*~e0T1ZrZ zvJ&d3HNLs>hfP<^m}G7qG2?EN8GQ?j8h>{JuHH6KmJ7e zsn7OJ5A-O&(ePz)%T=*B5oZ|R8%{O>sD%hSjY7_)_42qY7A#hoZ~?vUo|6}X8srz>(!;P4Y4@I3 z+Yc%?Lo2#X9X-WokkPH?zd^q(qcj0;KJla0{X*eYvj)Ni0JyYtpN!|pBfW?3key)2 z>61tf8*}EQBdpJ37B+NR|` zxtWHKeC`4*))B?JU_W69xr@LXNBCcMEOgt3obKv3P?KQX&dRSs zB$cOT8?_*OO7TH5d5>td*S8d_AAwjNIXMS`4?OwI*5#72bRz8{g6pWlBMGePEQ{`B zKc!c!#L0Zw^Z3!{WV>DrL^G%rW1y1oW&lgcE}Tp1SqdJOFMmt?V{Ks4=YSG3r=^$J zw`3^)p;1JR_Cnvtb65lnIl0>%m_yWUN`LS0Sn{H%Z$^G*J2iBZTj##6*jz^|?W6|u z!Eqa6RhMIPHv2Fz9|t)`0k`k6syR0=s#c~=!|wfTuXTLDW7j8T1SAIwq*RF$@xakK zX!>Judd<6<#hJd1Js-d`h<9+RR~1*k0Ini&?2N$&4k6YN(~PjE;V_zNj+5hD z86`QD%*(f+_SWB;c&OkBUs>JVM$5mpb)zSs4k?y%t-x7y^|EFHpYN&=RQ~_d4%zkq3@d#Jlas9TrjdA;gy8Xjy9iSsYSK_JI~pXyT?A9mrUZXx*=7Q~k`t zJc4JVBp+G8rE)1@cIXuO=RZf-Vso{IFXGN(R`D`?bqTtYYdk10%8Wca@lN0fV_|ck zet9wN+rb+X$DbGqB&o=Z!;nlc?ewva4X-5LFleqP_4VR#FsUGGrttuTad~m-_O}5% z^2XB+-&x4JnxuHSE5Qv2>{-qdUEm{HdYxYf`JDHOx$S{F{`RN6;c7v%9=DN`Pmag^ zIl{&o-M)Ue5ICOOJW_IUfd~`U$ia1->|`^Tf!TxKaf8jJlzu&IeBR);lodAp|72}! zn)oyQI8-9Gztle&P1UOsXbO!B-8g}yM4o1O!~KbT-*4tD!9Tg~Jb*QS;;IPec-G)X z6J(sxuovW>Oz)H}CBt>5lg#t&jG(uS8II_==Q&cBTGCX) z48-(2PU+QD9ZZWTPx=c8&Z|9+rTWivBZlwB8jlk3G4wUmMyQu}lkB4tY-G>ehUsHNlGzFqNkLF=#5`bvjfpiJeWnj^}O z+{Povq1EG0?KLozexCA$<}r(Q>~49sbw)}oA9EN+;R{~H$YN>>rNJ+S_hwNByIo)fL5`a!I|A>thuT^yqYzRa!A&e0z`^nCx&h`B)u7tiLP zm^>tI%Xj-xM(_8;$a_=ed|MaQ0}ZSt6mmD)^~0nMu{nDz72Yc^4S$$&3g=J*WN``= z{;sWCug|il6v+o2Gd1#WoCP?aB4k~wA zJc4!)7H=Yi*{0##MOk5aN71?eQqCn<`9r+!t%?mx<9_S)3T(~VYoxepYW|f}G&LQm zn~N@LgH-|ns1JwRX3gxXlbGDR+QVmZBRA-D?DegDWH*kaQK zE?;4s<5l_auAY7Lz2h8RVWz&8h7}14zeLJP!C@j!Vuq7gBb%SL72bdg%*4YcFNuaq zPV%cqq?(k&BAg(P z`bRG=;lGfeBOb}s;44v}vU03@S2g$`wckC*y*;0O5E_vU_bijW#D{Vk1(>y+p{MuU z+0IW|bF6GyQf8!R{*7>T@brU*&Ie=8C|e;`(LckyJ%MWNpd2(JayVD*xBEgQ80pRG zZ;qd(F+B_4CEm4srXP)aU)8<>J->AG@cJ94$}IQ72eGNHTG_ro zkFR5%C_rn;q<@WvQrsHg3!*mbZaSsOP`*?LUB}#EPC%w?{vH9&4-m84@?`I-lks6L z#u<9M+{fQ+^zSsy%XGfy*|D=~%jC-1L$0^FYdQIsZN0xU?tP4d*V2}a&r z;h)ZIBhN?2>fiUJo=GX)_4(0{*Sk5G{UfpRCx7y{3>|+qsQpA3ByrwKJ{L#Eo%DaK zBTO+WXQ)*f86caMFF}}^P-H8OPF7NOGo)ufH7H^t?IwI)2W>c|bSk2O%9!n-F2O}s z4>Q5jE-ys_VdapuNG=w;h%t!Ojm@J2)%5Aeu*#F zl$zPZ6l^l@(85Rthb3WT8Iw(YRZcGXih6bZY^EsRL>hRWwp5=r=ReYesy@Z6&d*T5 zMxKrQx_6+hl4qnW*;$4h^5gz-j}E{A6Bk;iTV1_X(T1 z_OjA8vvXFkwYg3QjRwXx@!QGvP4?k3So@BLSk5!q zLHBBKnKr<+(3tyrADRB^MoR!LS01`~-rWbrP{Ng9eFw#6#7{cARV!`wH6?JLa?1pT z$!v`(6TZVnld5B{k`*bQc=w zH0bbE57#^pkP$v6F`#c*sQYUQuXAPlhgc}K&r9?AnsNK`!|FdR4_K6C@5-67&GSLO z#zDq*!S-Diqo-%^uc_L_BDXJG+E)aN}sp{Q?oeA*A@b6^u+uJ$vfq z3060AzBnBhgDk!V``OcDp&!S;LKLW7JgKayPnvKt(20VM9?$PEC%0`)RA=-B1N4x= zJFoHbLvp15AwZyiG|tgk!o#mMM@+=87T^7CsiB!q3^~RPBagQxzPsAwbM=1GBPik{ z2-4-?ihh?BH$BL_8u`ep+ZUJG?>H%8iON-K)C-Ob1V*D&C!tqx;nEz-g{yJ*xzN(o zqqX%fBLRa7FWg}y!|P9 z4{{M>ySjFVX3;;aw?HQdtB6;JK9Ey^ua|;}j_giy9-IUhaC*2=)5e|DA!*#p+Qf0? z3ZxMkplVs}iLtPSq{i!$wd>BWapAnyn;}J(p7CA1^G9l$=zXvE-D@48-3MPowmllM z4F6CNI|ubB8*8Jrur_>Vc4hX;xLZxJ-*VCwSbh4}C68EP1Y*%F8^)QgftYmnJ=NaF z$2L~uf_#au?f&t|^y}vAaQeD_b7$Uf%CX)^Kz-)5;;VZ&y(@JA?k-!!zFRImEJX_+ zD?7CmyP8ya4&O)$_PDN}YHFFv4M5<%I7?M|@Z`#(F&eubT)JZ9^&m}4v#LZ{@Stjw zwIpvEMdCc!{2GZ`pZzDZ%O^EHsw+Iqxy#&jsNiAk_?r*r8dsHPy9TeTcQ@{|8ET$T z(qvZ~u3H;`T~4B7cfVG)SK+dlnEKo?J%fw!lXuhqar()-E$^CgLC(;2{ChWiq4iFn zDQ^3bq9v32WiA_NAS%Ph`85)kDdKxR5@s6X_~=*j_;$br?Kmy_+c2DOuA0cn#7=uc zfgVY#!z*{D+95=A0yCVHNmNP39QmBQ_+uq#4w>%Dcc`~K^`4EC)eo*|zREJ1!5#Hy zq+bjmW+Tv7B~2dpDAFwr4Aog+e&>DU9)oxOG$%wLyEN2o@-3N>m&(?Wn-tXfFEzA| zEC$oTt5PMc$E=9huoItDzds@LV}4|8?onCHoGV zi{;Xj_1mOkN7?D@ETwYtP&{d}c{VADj-d(kGD$}#=xJy?d{|$iI!@TED7kT@vuziM zY2!ai_EGXm!4mmf*5^x}qO0rWTKMznR$qgBjWdyIp7!lqX@hNe%nQP>EB}3q-8G3B zW2S7-x51>n_DwBWBgO2?6ud3pXiXbO2uqcD15a`Ee(^d^&)#lRM;$}#M2$gGk^3rJ za31Gd6g?@i>2yuWEQEU1x`bXP?ph_np=XAvrE{Kd_ETq!ys4IXuGjVizwU<8cmy-# zfBEiP`BE6~l{{PTiz+&C0M#T0b`<{LjuMVHuA`9eac058>eP;h4-3WyzwTGFUwLG@ z%3;ER#dnvja?0+jn43CQ;i*z++uSO5T5-gbi*J42^gLfry2q~@;5EYy2<9R!x0g)pu=4-IS zxddAhN*YPBWXCwc{RAD2sfZVIF4K%OFNurShD9O(0&)Dvcl$~35vdL9;>Mk8FoM8Z zpExWE!+UvKGUf-^kewh*hRHG$f(PVZ={^y#uRRY`Hsx^?&#(_!GKR5)JCHk${%%7# zpqMp2`Rj{$XM))n#wzj7LRhQB9G>-aELHMtdEedqiO}sCC$3lFwLQaz_S~utGF4g6 zWXu7vOL=j?nIZng>%~knh&X1&!&N2DHW_aB(ApuI?V#geg4-?LMEN8ubZ|5S6 zb62$r@?8BG}5;|TY*#^?av?P5DxSwe@;q^IY`~) z*lRdqRoL{qAC+|vZ+G$6Qd`(MJw7R0 z&;n*C?qlpD;Q3j-~yZV4O&*QvIDRq+hXwLh4GA@ats})}+*CGwGICqNOY6W{VRbJ}C+k1XK|1k!(9)T8V4qwU|BqDK zIjCc{fi!2I5oGDU<&l50LM;-GG-aE?7fHm5+q>6yUxl_jE7i_kO`%O$6jAglbu<3T zgv&XKYrmrzR${;XCgtYL2WeI~)+{ePaUGb!XwH=K?;?QCNPh$oPQG2})1d3_*({;i z4TKddTh_YH&j*}Vgv0!)_S(ZtL$HzRL9bG%n7A0LW3y-GRUlN&F>%*+pWrjUda+r- z6E@-yFb4W&wp!>;&{NP~SIbMW+=-`Qfm72e?7f>bls>asroCA;#lo|x=CiNZhEADw zi9F*h4_%F2539ylexnq`ka1_D!q>`a<$h62f7|g;6GPrXYsz)vpSx|FIIk~#mP`F# z20==WgjpA-j`DI;i$b@#$~*)#^az%e9j)4sTRMXs_aWb{86`Wx84R^oueJmZ7{*b2uB*OR*~9(fy-l&Of1o) zEJ(46(KjNnF{px7`WJm)vP$9wixm!e1_&SK#_HaDp=xktv12U8HSwcz^XX1}ylUpg zoy-5TQi(23%4V30w>hzpbR%#rkq25%(++=$jg0u*7jWB2aEw9-LK$+KBC&?^L?8qa z@w!`hP|37>-Joi_OQW*MIj;163OIuXaKmC~Z%@@rj(IgK2w4Q)dA53a zi4LjmeJ_@Li{H`2AH0Ru#l@4_UTfX#^GJACQo%6r)?jL6H||T{>y(ou*-_j%b?1PS z4fMavdxsVO&|W{Pr6Re=5>kN)cQwkoV6wVP+Lz}n`9N#)%!_7!0JZ2W%!2wmlx*5L^}@se=tiy(Mba=YDh%N z_)+or{_zELpA&}ZWE=Y2?2AC;j`Yr>u7>Zb6LMl$!v%w94#7v}c6!>h6n6myPUL1( z=M!HFm~wz)B;1$4a2bkn(t{#s7P-%XMU%rQ&{M5NTYGR$ z5JWV48Fl|o`e*!&L2NO}P#2x`k1DC$VQ3O$%0wEC!Q- z17^OumI;mMu>apQBZ!cBR&94`^N~ug?NFnx z%re_8LH{#c8Ch+DtcIlmEY(7B)$Gi!o!62v`PL`hdj0RqZ)IuIkJwUg)>1#KrK`k0 z0bLW5@KInG<={-UT{^EN`{Y}OYvxWw@jm*ntU-tWP24>Pl=VBUCaHf(X1P=4jYJQl zc?h9l2#yc*+<8|*sSMV)Yu_JRhZDWK{Ypg5{zwr`b&e*^xOQ8$ZWsw_iKcuVxF7yl-xo5^BXcj18nIT zs)rjjSes?oGaUIP5;?u1c!WAag>f}{c7bGYBn`{xEhmET?K^T=o+>t&9{Pvb$X$;a z_laG||3G%}fi&l27L*RGL6-?qoL!VAi=y9}U`qEbPrCB+SiJ3DcBo@q*0+7Nj1r*z zavYapjM#yZ;yq*=#6#@C$cXaa8nGJZa-MX1GY#Z#G!LTnd3NWV$-r$vRr4EoN*42- zzMnTr=%RWB6kkaP+4t+Uqq>qI*2RE4lE^;+t)-6KjhHlwUDLbhTAS^tP|~4?QB2`NrQ!sZ!|e z+R1+u`i|9Hw)TC~%UWaRs9c=G$D~?0_1s9d;R_yn?#af*lRaB4_s8Apxo3kXh`z>V z9K>Dj9)92aDXSxEaMf8~`KesAnQ@N(_&XUSqSv@it1E$F0Lcti7ep|lo8EId*c0J9{ zwjK@N7n>Mg;I0U3d-s^f4{rZ>Xve5D5oyw?aZ;sS?x=ZGmov^rm{sDrU0nc)ml+)A zdDPk0*jHjDYduhCBG~-rj@tmjQSCI}m0!%JGoJ_;OB>;>4w*b(laAKObS1QXLKeOH z=0to#U~tgT8+u2&oq0Z5%KMW2Hc2!9GTkZC+NED)z4xNKg}w_V3VE-i;slLJ`J+Vp zpkj+4@?>Dqyxs-KM~I{wY3$nZc+wh-L&*TppOjs+RL|%#a8u*;y3-o=%E|s*ja78* zKzPx+<^99X0Y1n%pje(h%Fj$>GB*P<1Y{~hV;!VFIj7KjX zRljsNJnmDIc6^Vrb5W)q?zEcfb?%v!Vz#lbm4cU`#@7I?8$)~)vkG*A^+J5gzDo26 zo~^fI@1#nFals^tbH*D&BxbtlrUIgKXv<`IJdjwl8R~q_HCZw(`$7Zzp~?O_j$^8C zb+;>TM4$b2(SM@~tFP{H=pSQpX5yS$Y!s=ZpBAr4{GoBqHZKFx5Ux?xc1tsOy1A3G zHG7$p%KU<3N0x}c-!Pc2)5nBtLcxe0dhts=wCnrPi9Evk0wGqo#^WVoV8$xZwwiO+ zb)O6>M}(%u(FG_paQHJL1KdWYzq?6Dg9jQ$0rH3bFT?oijOd}wMa%3A9_GaIob7Yd z<=(Ck`+KKp`mBeWOSH~+>|SEkK@JgePmZ~4RVLL>lRRR?-BIzHIpSesIzf}cMWown z!08E&YQ-TE0b{ARu{3 zVn@GXmR;ezf2dQ-Y1t~*6xr&GRWC|7Gr}5gyV4t}WNk%?zmRmV7o|s|)s(Z-qu0FGYnLP=5a`s(9gN=B|iy|?uabcYo={r=K#(H?BX`v_%pNBsXv&gML*3$8k<>#Ro z;4-Q%!igGPbaYNt8zqgU1CGN$1~y{Q3D^iTg%yqx0VpJ8OPm1sN9!4h!oP?+S^tUS zs7ESi_dtXM!(qYz8tRtOo}UWvE$YQOZqA`Mh30DAx4SE3;w0$&$H}~M35sM`0BACp zgTzHgl!m&eb7?x8XJ9{H88dRSLGrmW*f5Z9cd33ws8Z{X&50O;F{_Itz@rnHb0Pn% ze%#fmA=r&x;Qc2?N-u{kfrsyq7Ge#0djAQs26-E4K)IRQX{OjE6ZtMY7;}jzt}XN*ULP@q zp}cMYME{)eH@j|Tc@0i>tI7NLNWSGk7KG)T;a%>W#&9lgJ)h*gt&^u^9YxoPLv zzLl^twoGsJuiIJ@_HqZ5{jDWhBUsBsr{0FAY>}vu%-G+5 zj94S!-tR8);+Mr9S4L>GdXEh=mC79EhKldkjP}qA(NxTbJxNM#`NV(Btw_-hxWI+{ zX&}~=%&}sVH1GQoYbGQrIvx=u+3>aCZyBls3?TsjKL4{-{4b*|qX$e1<3@dP zuVJ|yU;)IbVw24?7)EL_KQ(HQRyY$qdJ?4r!HBHj38bNdG$YowVDtb%YHoL7YSJaU zh`@Csa-@n~OhZE?A)4-FP`n>m-TRi1*pDxji3tMPU-INpobX-`RDLxdm)R#PUc?-@Q&C$%%S_dLB#q5Vsc~EKaQ|;_3X* zubg}7>VCG_O86C|ya+ce8V2~xk}rA4GXAs9sprZL@kn?F4%@UxxgXpeodtQ~LR`JI z-GtKn?{zkNb<`)=R^1LC1J!gzlx04@M<#2Y=Sso5VKwtus>x1>7G}1mVYl@M6VYJP|qHLpk zpEeip7s+Cvnpz?%q;Sv!OSmyz)Y7FT-B2lp0wMCse8G>xNX!kc!#_J1ush#F@rK`L zuc~+#nFfrNV0`6GSIrEe@RzpX^rM5A`yF< z?k|Lp9wRVasg(DS3kP$UNI1nP-`tGs zo$1bzO{eB+5N}Za39V&B%iYH(S%^RbY`Cpod5+4EJmc;l=12Fdm8WEdc;(szEaWMg zxq6q#H7b_7eES(GcPRyXgUJ}pd$Ui^o@tN1rR-?Rh7&p76|~VNBvI!UIa@kk_hE;a z5CI85xAbQoev#3 ze_b-+vQ&b0xwDM& z@5V97pLQ6N2Iina>As^iM7-e1;8Ct?7|g0QgD(Dj&cI`r!1n#a8vEmFjSbBU=a8Jy zN*k+bQ&5!B*>N>xNEVO*yc_Jkg`mE(psz7>C&9AT#h!S1``Qi6y)I^VCo=_2tc^L0 z27e?!&CJUyX{MWXcF%nj@Yb}DU_G7_eJf7M`Y7CeJe@hJi&NcS(;PI>+>&(VgR|jJ zuPnLiX_{UeaN=6Y$(R4$?6>D)hUUA!}e)?!j2i<>(q znp0TmAwOCt`009)_Q{NS_ZKJyh6e92^k}aBfly*9TDYXfN!_BJqerGo?PG6Bvus=_ zeg}s}vW9tlbv^EGH_m!Jug5{$XMzr&wDs>ds1Cc7x zeuuu=8q|-yohKsU@>N{p@m<8sIFDaqC1(CQu}ah-_M-BGg%s)lK$6af!Ez4S8`5dR zSGjBkAifX5t4z9Hc{}tkRY8N^Ffp9g&^MfGMjk{D9~X-|d=f#v&r2?jV_y=D|O1!RPsnk}i_h zQ{R``t~mkhkvoU__Ek78)h*&JNsv2C!hnY68qbQS@{y_N!lVhGv6 zj>2$v&$mqHCM2o&o{r0{<#G4G)XYaNuGEq@T71pyUU!|_@SX9Hf&oZ3cs7afF)jgQ zadTN*~0syP3o5j8?nUCw-_$~Pv z5P?#9l?$wbxirUTkex*uFEmNR;p2K@f8;0I)BfqzelC6BMvRf+agq(#(O#i11RTv5 zIJL4k6yJ=<-p|*-mcn)R)q>)OB)k~9`65dnUeVE(eBI)o9P(ia;Lee{&3{870xOhn zZx>g^OW;A|ml}FQK{nFoY zgw$=Qt}XR-1zURkLxrFLc%!KvzI19=hzwRPKgJ-&tbA4SfMbWzgq#@KqKG;5j5Qm? zrQrhWZ$W8~$5Qd5%d7UHJp(gBeXjvsk6VBXbDn81WsK2icntl**t5%id){bQ$mu6+ z3Gd_)Q#9rL7aCdKwT#L+>s}JZc0Eq>IiB!8;qlJ9=dj&rZMgBZ9QH531U@2%(9`wR zh7*#NrtDP;;nylVhEu6~FVkJ4LFXq3^Xn7lHRY%|01Y(^)bk2@+Duv9bRG0H^KAf5 zki3M&9UJBKDjJu?ZYyl%R|ZIgoMn5OUn`gR6%T}jse zs#iW>@{WeMIyjLuL*eDE3bD}hVbGYp{74-y%ZxbM-XWL!>->HDo|Nk*GL8^HJZ7b- zJ*(ZEH8)(|s*nkjEB@|%n5+(T=qIhanj)`E2z>aIBj(ysK*5=l4JM1K1ICZ=>|zAc ztsclc_mKZ6JiL7GV;5tjNLy6!!#LX51bKF@$R$1`BTtd;gvnDfqYAJ5A{&`B>pniz ziB$k6ttw9%l49TzV8^Q&*@xr6dFsXF4^D|5>{8o5iP9&`%dXe_(eR|<82)Zt>fMY0efr?~!S zeh@7C=C3qdUgLO)nJmdgN}9|!)e^skG+I@21w3!70L@+iBcGX?wpU~JGBZ*#-y)Oy zl)bbcmppr^n0s#GCD&%2I7vqhx?e!&%m?;tt!+1KcWEAfY?(`=hB6@Aep4Mw!S*FT zny>4;PUTI4cJgdXP`o?G^&D+FQduh|o|CxG#|#|^$V>go#Y1Y#pbcDQvAOcFoMODY zDr}c7&Q~KdyX&s~u+ub_q5j-Z;~10Kb48plQRt3az6XSrua^9M7-v50wCy<=jU}%3 zDB&R`%_>)nLfcvla~+4?w8hNh!|^#6?RfTAvzHNW>N1kE+lFy`EwDR92GJ4txKR3r zOh&y%t9d1kdYR3*|9<%ZE=l-S8`Fuus)1~56Q9hwZNj(w&fB?eFI9}t*^qP?g;Fc) zhd-~elt&vHyBC5aj>K>lf@C2uqoWJqcYvqLnKBNNdeEr$bYVxb<2gcP8sDA*7?5`ix^KY?(d>2cr^RM(j7_#2k@plbY;1SqKc0X_)0#d580L1~+# znQp(C|KF@6j1Xv`Y#yK$``3yI{uIz`Yyj}cgt2>GJtR?LQO@|ppo2j~g`1}0{W$e~ zw8@p!jLA2;jn&KAT)x#PMJlSa$MJuFLCL%k(Rj-fzFyH1t#5cvviqA+pS0oM#Qt9u zNoc??20Y!Z6- zy6D?IcCSyId+s4SlOybxEdt)Wo3I-i(N#s788V^hF-1B!TJ>I>~e+Po`fm8 zjmK`8ZSdayyrYRyG^T5@>%sbC1q}b;*2h9WI=V(P`1|G`GLX6PQ}87mwEMqm&yu@h z%!Lz#@Zm=+_WVe>XUUznksYB_Nu4JqiRd%dF_vyRZ*TjhTL#~Pe(u(kQZYD2Zu#AQ z#}{fRMyHh;fM&+b6A+y?^+Z~^-8aTOJ$V8SYXUg~n>)^t%g(jZkYW!Z!-)dsNXKyVh=n^o$J+GwuA*KIyMzuNjmtVaUiQQX_`;wdyQk*? zb%jD%9|DNK$7|c~HQDSl<6HAj_N}yd&Mq3yE**vF>1(EJ_}byvVJo3Y<;@SW;(F!x zV9NR93WVKy5{c>&oEuXtw$xe!N+AH@p{-KebfwN4yZ7x-UFU(ocsN2-(JBcnZXSyb zV}Bgmvx4#fkdrF_VRrfMWu>BN=4Wwr%91s|?R=i6a;-hI{^+&e4{ILL zt0mdM=yRjlIPa#^7{@PH9ZgbYc(}eeZIB;%d99RkKcIegAAH{jX=dPwC`Z(nge_B* z*K@rjtZ(;hIy)Sks_a^t+>G|N2Bz3sDFPFl_3fZsAWJc01!Ug)w6lt%d=D+C(t{42 zN)PQpeI=6KiSOOEv4DyBLcZAf2k7`buDkh{yP+NnY^^GfwjY}>s`tNF``Owx5&*vXF8aW~Uxnt<3OdYs^@K6Z)@1@F2*YNl{dPtW3;CQBc zj?QMU{;<)2{9cE%GbHQ!C9go)k1(G+qWg$>SUoDVZNyC3gw;`F*isIO_+$yn;z6T% zxt=fZIuv%Ed>6NBk+Sf}y(D|+QS)9sDnQOf<%H7^;nWBfvcJ8!<#Z$fA6qxno3M(Q z2*T(1iANwr+DS_;a*;GOQ88uA-TDVh8?YF{@~46p8*!=hN2$$gRdDx-YcL{_=$5Rl zc!k1Q!-F8~Tz>E51aAzpU{7Y%efnGSW2gGruY^cSnK-DQ@)=hbdy4-ML6P;JPQ=X9 znF56fOpe@Q~*~aRDKAr_WeJe1U8zLGt-o7}-SYJM5+{)<+>>Hp*DOW>iv-?*2QG#hRHMr% zYvn5BDy?jhW8HGI8s*HHF+}4i8Aoceg!lWi@B4l}`>DjtX#M8-J~9^hG^wk+&* zL_Qtl3Q!jiSvN)Xs!4uf>?lFjCvB^^s|hC!XO(QIg{%SAU~A*)h(w)knpefrMjf87 zy>>9gk09B}I7}EAT);P97lV}#A;UWPa9#WtWFGwId%m#m=|Mb^`m65%0BUuEL5JSxyk{z?c$z?9&H_O*0KW^UH|eT56Ds?E9u ziE&T=N4icAsBvK8gKHbgp8pXJh7bkH*{9aAJ(U=zn-isbZ+M}$I+POV=jlGK3*IPr zGq6Gy;F{{9rGYIEIt$nj?*frms};>3%=ln5<%?WT@rlEkZ+`oPdF3@|xn|cvL_=1? zU!C4$nS&X87-6o;4hOgu1{d5~wk4mT^`YUJZU5xz*2HR0YhJw9%P zJ|VlJmB5B)_~sHqW&aj4cGki|g#j&U3;V?$%`vaC=A1hgh%$p8P!O?=Cc)6IgZh6^S$TV&azL6A7~qW& z>Nt2m5O$hbs+Ih`cAWloA9NA)MU@Oe|BD zx%xv_(vjiri#iAJa2BzKEj`bM_LYWwRKvc7L}ojvK+cV$7<~h@nF`DXjQqK;hy`QP zI+)f-^M>{xoH7u5K=@|DK85HSR-klZw}R6SGgX{p_op8Dh=Cp%6<~QS4pbC(b{i zy-!*Gn&oc=b}yiBm}2E%xCZ<)gtGg83owy1@WTD)>l|)elX|Q1?dC7#S>yR{-jJul%&%?u0R@ndFGRL%ldmK%@gKz8@W!xBctwdT z8${hk&l5^rQKhnEA^Eys9L8aKs^Er+G z0x4)1fd_~7Nw-=lwQ$^=HK|zGcnwQ4wtNhcVr-dIcSsu!H^yj##xFoizs5BCLgdNNu z17PStFrzeSn-8+u2!)+lK~~-RWLkiA1&%M+4!~mOuF20J)d(*~_t_&rA{_ERe@gLhOSUiB$$BB8)&laB$L| z5|->i+|S(^28A7{rIYrUg7(D`-%(t-Oi}n%HZcx17s9&wdRHPI1Yapfz~d_};}~t? zM&Z-9a?;02iOUsSj7Z;rew29aLy`l%q8D)mgh2ry_9kM`*8n^ciW_+p=Yh-3Ah^lK zIAZ+-j~wY2s#_&qYE%FI;jwJE9G2O*VG-E@M^jy_XW)Tq%8?KN8}cXujR^0N(jR_7 z-=4elFLpWlF44B@22^119Mk0u!(7B`!+y3s1`C=CzG5St$BI5vKoW=a`nNI95;8u6 zP=QhiH$M;=>#kimh0=B5Xe#nNVFd8R6tSGXoj=^|fIygl?uO ziZB9>_nbf-lk_ODXoN_*ELu4Uf?08msJb{xDO{m6A@_O%>puHg95%4Q#?)K_fW@Fr z65A-ZLE}rjC9|onQvFN`mfDM%reQme$f`(uA@1#2M30b-V*$Z_?0EWFkkc5Zf`-cm zxvZq!JJ@To3*P0Qvo+n>x}%tv*7~^B_JF`kcxNRR9PR~B8<*c#HgN52^R2vd82Mo4 z;_B}9hcTb*vmvX8+!IbJsB^45GH{b)2FIy{r;nCD(^mYdU|>3@`y=WV)&ESZf#Da` zybk2!=oXde{!g-T8QtS{CTi(&x$Xh2nd$p)Hp0ywi@2e6fREn)*ASu(!uU+_p<>QL$2JD@w0%HzR0TQLozmd#zhkf8`U0n7Zv%cf6)Ts0_B77AK1}6 zirZHhvgtH}czz=98O zVtG6<4amY_I%NE-r0&c}CjfF_{ zam=x})AroYn&eDxD2VSN%NH!XXC9MqS&+sZFs*D@i4rlL0;-Kj5qDrf-#+Od#Lxsg zNEOplA(LO${JjB*43jH1;s`&&^_PK=ur2$0#88TQAcJ`hzGB(*4xZIguC~w!V73|4 zs1k)K-`|vmo(AXVXRxBCONq_i8lPSNL(8E%!SUC!d(elRhOV&FEZnGU_Qb@o*h!yqKuM#4LU+BlBqe``l@ z%-eud<=!qFpC2SGesPnHP<(`I8)-@CDp4#^P1RkF#K2PgNE5b)SoG-26(Dk?V=`y& zB+jopN6;b_kw`>{YAmysj*|?Vikv-uO4|V>en4Y6kcqx^%4lprqCXT)Qw8DLQJKwe zDg9_H;Q$FKz)MLu+T*fb4}#5Np&Kh)kuJHX;EH`Two|Y!yH^yCT#Fye6Rr3}KZ(^RLbf<_d}y!^K&aW6tf|UM!~X{Ee%4a0)<=-p zL?3-b_R-x@X|ryFDo+4%7KGH7Sd{X>ut4K2OU3i^G{!bp(#xFj;BGg2oG8U3t_K<=8*FC>28cbEBhOwQQSPVFC~dA zx4Vh7I(<19q2Qz`Ah+<6%kGK%+D6qY3jT1n!b%z(UIvK-zv7V60lU*icJ2Yl7b`v~9?X}p;zR36-YoVPu(TnmdZ^qWDuFP9 zN=aGn4{eW>=rDTe}&m`;eY#bt#vu@C(uEsh1eQRz#QTZFezIW=yK0kH0cic)P*OD`u?uUTs z5M(fwST-{voL5yumKckbI*e(AbmJC3M3->@L!x0?jz%qOcZU}rAD3LltQdfw9*~Mv z>zUixxQ!L__-s*xokigcONw4h3{dIo+d+j)B8@}~=)qM#p+HCQmd|({jfwlppD$sN zG8%?3um#$$_*46-g6O@43E{Hxx$>QMRV}PFf+&0fs>>Amlg;e==gN+(Bjk1Tt1;E23 z>q$_LhTk%E_ZrIp2nUV)9Lxw15@i{Ke*@RCGW&~c7#Yj;@C$TlcpnY-8Oj1ng7HOW zMbpNwn(}#A4fLma3#x#)Z6HAb^BXqKKVV#eD+MSxAl!zI!OC&hM_mjfL;cLvAkkKe z5-(?9KEs66AgKG>1rEjHPaJA^kYe~w0M1z0+12G$dK_yY?>AFZS8f^Js5(zfWLCHpTGpLjp?N2ri#+-|%t+Z}%Ex;NR*3UMeW(I@2 zLk=k1fV_uxH{ZWwj}0L>Aji|Xr1y&BJguH)DpJiCjnodu_Ocl z3PV*KO5*GbDuG`I6m641qhKU4y^DUp{a;IP+CCW^=AmK29l4ckW(-By#AX^qqZrTw<7C>kfA>%Oe z<{B2xaBuu)HJ#+pz(Yz)I|dfZ)EL2n2M8-BX@Wv4VKNHXxUHHk5iER>sV#~%T(CH7 z&5*p*SzP*?-TSz-$QR8IJ-B6`*6FLSBsH@pYQ@p0g zJJw!PXwm;7rWp>sqH72b?c?!wcM#3PrNGI}n4EfA@aXrcr;m=e^nB(5*hXJyKy@t0 zhkZ&C{2_bBX)I>54xRDZZm`|T_gU|2o0+Nn!oTv$#&^ko6?yyX<3&c;GAbgmt$6h` zd$il}DQuytzA+}6fr)p)zx?Gr*Exac!~;%K$QD^)RAg2W%iaehbOafSrE>q7^Q|O$ z-q8odGX+*;A-YF@$uC=Db(Mi==1fDiGu4?0mPc3bq6J!7gqAP?Kgq-!z}$Dgd}TX9 zqX11~g|izhbR4eak2}#q_TWyJbXa^@@Br+${}xVXh?q4|X;Rz zMxx>)o}B$5eHGsSQFzv_DLYa|(li?(OvNV9FZkx<&~tK7#W09K^bAGM&AjbmEu>q=PW_fzk`&{W7q0#sNcPcZdN;5~^uJ#1-Wpjrr+xEKG65%!i(r zt|dF_pzIN%osPPQGh{CI1G@=de?tjTNn+(JFZf6l3iJ=^U9eN~5{}JY?U44r2+?50 zikv$aFs~pEtoym1X-HcMtuJDAp{v==z!Cv(ErlJFvO-F7PKvqL2qO@_QqY=-t|@Hy zu^&{1_C^y{2I@SZ0F693j{CYBgcOZ$8SCnmp2rD9n7UcNCoDD znx3>floqB8e(mG~{X+FBO~UX2H_!Ure2}nwAnn)3xbjtxRW{5L}@^*LMD2HeX~OVB`jXgpDMCPR#KMX;+%J%z95^rZ~8CiHyud(ZIl<3?&vu`84LK z0d#3g#NW{~Q5O!;=`b1qk^>+L0<%W4EJtG54baKqq(Qxk3~waFLrVdx=p1|z_{0K$ z-ThZW9Z}|PlMft}@Yxj;%y`1VMg4_!2C?a=D#!EEF!|&G((VkXlD#4dRe9PF_=w|3=SBWL8H+9nF31qTcN$< zl2$LWJQ0rRjkR?p$*P+;^2V0#4tiKfHs9(kh+tB>w&q`uEp8~tN`d|ZK1T6$d3=xJ zBSe2-SRtH7w3tfBKElKc8*(BMy*Y{Y^AMe+8iVrR#GS{d8R6OZ79lCkk)NDbZTD!#hzU%h{v&jHn!8H^X zKJLw@!BI)D?y*VFZk?C;qoAr}X3w8`>>-(s*D9!e^~MZ72v+76XcCXPhn1FfxJN-N zYaPcS{37zU!_NPEi@l*+o343Y9+I&(MD6l@oVW#J3tCU5jQr&jjjrBX<7qbTt>f7E zthg!0byjNVEhrO*s3F|^_zu|3plc)c5YB2Q7#o&%FHc18@E^x!8^ST%&PedUEJl8soT+g#a>l+9X!b{Q^%YB=)hLCynI$hYmaO+q zE7+i?SF+wqxUV{SK)nTDu1(*fWTnIbKF%kSF=Wo~uCEdKR=w^T-Co!PW45O00)}Yp z@X#oJz$o)*9*v>Xl~*L#=Elb3=^guhXlE%ZyMTNzKf=~7KR8NXzL&Y6pme7i$Lh)| zZtqa&i2)w&ptNqL25mv_;Crlf{8<1oF;vf&9ej`M5F&aJu*UYo*k=X;(vC>k6SjT> zq>@=R;5_0K`s)x`jpkc)as>>;jw~X-8}$pABk4m4A>1D}eCRdfx?Uc{a;W0JbByPR zKuIHK8mH+OfQ}F|c7RP@5Dyv7+a;$hvv6s_*~Q=aOuQ#w$-LCkgZc{xg8y$K-Q@kd z!ONiN<^owkh9AqoI6uw08}8_hVMsJ@aR|J1M1`|9p%%sfaB1B7Od?I*n&5gj0 z0+C$=&*}0DUO|3lhR+|uF_bScfIz$SWd!Ds*yo0beoX4h!4tL2^Wo$v}KFK&Dg?r_nzuh zNp%cHIQ;l0Pz%?ZL@`aC2>2UV%nT?EX3vK!-I?({8te1>)RP&1gU1Ppv<~AN*F1d^ zlqQv<_p~=3(o+#L$!njFpxW~q9Ao}!_UYcI-NVz1{!bqsy!NIQ=bEX{vdOuZD^e%QwhV}b_{fEcz6p=PH2=uw}h>+ z66mmgkk#j{0!#a1Dg@7GG))na0WB3;MRTMZij~sewfm`~ijjlZ|Hj`6e#hSc(BTB4 zDHBJBDT=iPRShj%$XT?kJX|L(l1U!|?u zU0dAf@BzS25=ru<1yN8gXu{3xhBtBMBj=z7b??Dvat0T`(^#&>3~eI$GFb!mdZ4Ls zFr?%2piJVLeJPuSFY+}fzUR2Rk@?sk*Cz{8JwbXu_=yZk^O*9Rla%oItMIx`+>hNAy3opY7lcO5U>>ik#nmB$=2kx6 z*i$O2_8kn#e#+5+gus@lUc`bBKb-qf7g@r<`Yh^hU<9_~sfA+=+4jy72XDk1fgz#z zk2*HX9PnNSoUwv|8N32M2@{CXyEmtHwGFnt#XypT&0SsDEvy2O4opXRSyd_>npgqv zQ9}7b!WXQUv5*EvNPL04aC>Y4Thm!=Gk^2^3XX^|x0*laUSm^yQ zUvF_ZozmboAq80GvQ&+;_?k%JH*ny&8XK%w_~cL<=5J-_xn2y>aVpC_k~43%Pbpcm z=!%2N;#+JrB2W^CMkb!uHkM2Zj;S4qaHdkbTwJIQiupg)SCo4si5_%P^lS0pS~z=z zQTV_VA7Gx+N%3uQHQJX{A2{02jA)&HCySaN`T+zc~^(pr*hM zcj2W9vdb6}_)CF{*4^(9qa9#)s3}+FWiBY+?+w_I|4++zaSUAHbcXTXz^D3aWRH1~ zle=m}b<^FNcS}OT(&Z-vaehZ#H{G?ZOHcaa`n~e+eoT^7x|6LNq`MWZDK7^1FS~F+ zQDR%dRL_g{dR4y4oG7Q+=q!JDxo;OBO-OkhVZ%@QPvVk-8*(p75}MYR_prcR&@eE; zpFA<-fPR9;lGL^4G)P0&(6zS9Bcg56#4ue|aoQ}qJOHPBz^15NG5^~)i>uLeAe zmJ891*igouz#+jbS0VtQ-;o0g1Qjv(464jOg&G_Uvw?Y6at_cXGNz%}`wI{^1PCul zNaS?%-jD|{ZFNvZA;my+2@OOhj`@Qccx@oabcNV-pQPgUt_(|daLuj5PPqpv6j(on z(6Q13i)>c*jyvEVaTBPW1c#OP_grKF;;Ar?EWtLf?g$L>kmm__&^8ooFEA1-sU?Ez zw?J#%1M)65(;4kxCy-=y{&wmH(W1;S1Pp3I3Bj-NZPyWs4EM5~jwk872Nh1A6rXeMLIMLDmK@@D^pi*gF{g9onE?3g|V z50J;s?VhP<1jS}r+$XPYkMmD531w2^Vk1$Q;=Q2I#&vs}pY*0NNG8zC&c<$Aa=u!T z`$r$X++6cFjn5R)K5;E-th>20BPu&g2N-)Yb;~)OO(FMA7}w*AiD8K!x(lD zE-v(5=KRfA8bEo`PA~lA|0{iDNI_WwlL(h6E_Cu|J83n2gh=2CSGryin)sy!tsSz1 z^@;nH@*gcT_3vaXrF7fN;Ynh)#26Vud!dTX6!^}w^H|w5d?9N4`HB(>^Qj7BOOGn41Qr^zyMEbi-OItNtO;ILQi$p4bx6Vy4Y;6cZ>EUjC6+RGDv@=5+L352X+}CZ{C(e+AKQ-*9|JQ zgY5*C$-P-o*iIEJ!;H)fX~D)iK^wF4+ICYxQSGi87jYl;<_U2r%M{N*ldQBs68*vU zj5}Pi#U@wp>NeJx;*^}OON)lCcWYmL^kMmKlegL;zsH2hl+ITtjW#`RvMwF*SmUGK zWR}>S-&nM_VPAghksS=b+P^JNYDu2|F<#NhIu=c*NsG@ZIUMf1$=!kH%}_P@xPpVl z5eI7IxwzjWb{?5n4DCIazJA*-!yT#T)TIAOf5oZ!Y?iq5?(6ouz2{oiD-9K-H!JM! z!i`VH@r>gSWg@SgwNQ=gWLn)&iYT1vqIKBqxOx8uYYiOf4wM7-Hyf>9fOxTL_ibSO}TZ#`D7e?PctypGtPC`SurGrF&;A~snrs#B6b*(>Xb3KW z8KzN1CCOo$08apbR~X$w^cJD;R0rhna(@^sz9e3fD<93EJj|XM=(zc|biS$hNH4?5`rjpszVq8JwJP}rBrj-ub!c&9p7K{} zoj!Fg?!BMM+cEVqJC9cuS4IYO;#|#)Q$k+El!dMi)(nDq75a(v5c)LJX8p!^xzL)l z^yY25yzbY$vl0B|z^3ONy^sGY-a5A^ho$QDSsGW~WG_rAE#xRZ*6 z#iAB9e*9UdvCOZA@oZtWohYf}PX4EKV$^i^DWe2`*(8cS7455?@5#G8u8^Pg^ulWh z_xXYb;u;Awp9o+|)f2b>yggj{bxVmI7Rn!VkA%o>wXt!5X8jI5t78TZ;hb&pF0X=V zJO4GYUba=~8FO>b=f2%8BK_)8Lgqra%mcps`BK@ze;C9!RmJ*T*RinO{|bw%Z`2nd zkc7uCUCEfgF_kZeEOTz$fW`2hM!j)7l@K`d%XZE`XP>@yR&D2f@k?_YB~C+C5O+xk zZ-)E5@2sw2V6*;uJBORcdJQC>_8;#wTIav!^cf0knipu@5a&VT^@Q#zol1X_cRdVV zJSbG?vZA#`ee5)J6~AnQRd|&+CTKv`_UomM?~9dgIi_YCTI}#y22Sx{d4HBcE1Glh zIey0tUDCOOhXo_~Ax1HeNAPNBuZ~*)_&(f2N~R#rSt+Cgv{ZXhb?|f1oQi`C4*ZFz zq6s{JO%EhpipoR_79r^Z{My1+d+H)3YyC`rwFSkn8*9LvKt$23ZKvC_JyR(_%~Lgk z?L2V3PjB~(NnX1xAZuGPDQL)yrSJ><@%*KdI6z6u*fnt|t+NyFs@qxr*2quJxR9dh zQy_Yzx5YojV#zF()3oXQwu-P* z3vPA`G_jWzi;N?-){4^=|7$?Go2^|Jyq~7qtQC5 z;ClM6c$tGlM{KJy6PIp>?T0f5%Bicc;!#aK4UaW3YEJ(AVe|ISzV1I`usaMOSAGbP zAz#Dga@yG_a)i*@g47ZHGfa;J?qO$|28Q0Ga^6{;xX(mlIX-cpv<(prm5udZ_8Suu zn)Xu>Rt@#h5q;zCN*@YPK~;FTm*3~J_(-7@*cy+T&NZc3n|Iwaq8Spo$cp@^!yhdK z70}XR_T1QdV4C7lInlOsIs^SDkso$PmK5`7lv#LVo_@^9*`;S86WLW8tn^sAl{h~_ zIlT@zC-&lqUu|Czm3pGPbnj{Ld|oO|li_ziiW#TzW>TR?@}M5VJJzo?;URepio#_P zdkSe^fkxtnR-{vAOK8b2vM@Jkg95HTU_UwAdQtMKj3QLk!(IxEKn(6c#KBc#(0M${ z)`|(BBQ@>Z_Hbx-xm)<)g@M(aI^<`AtU(>z?)hBLoKJzB!aRlXh%4Yy!+JH-v?Wki zjZ>oNeiPw8+quzp^K4aPe0Fm^c&Yo_t^47vOzQHHUv4!ze-P(wGl30Na+ z+qT1*HB8krddH(yx3r$AjYlt#-V*`$?@KrJE2MH9rNW2+`0z>gSb(hqP6SLjTOE6^cPI*?Ay zF_P{|Bwq+a0uKm2_RtU@F2Q0X(XbyO*?=+4ckn1kS0ix_EZ#zMGsY$s|78G6$l0oK z7Nx>3kM}bF46OLFFa?bjBNR@e0o))-U_+zu-R~iB#bAXGDhD7}iK;yX$-@vmm%d*# zsV|P!SKnX5YO!#sk?*hNz&{OZZg3*kp5LxjXi~EOrGhzkrqzY_{RK6y1tV8aE6}9$ zTEc+*3%Axr^@1@~8}+mlBVE2vO=E|j33u-;&N!(dX~NWdaHO}!H}HRiIHu+7DYx&C z;TD%;$-mF2+VSP^f-M*-csS6h$Znm4)eK9Zd)OR-;zTG~| zJTfukZ^J3g=gti-jJwOa^1rRVgsc*BeNx6RUP(u^6VC16jKA|Q=_~E)cMBe;ejy_k z4k_>4ywc?NCmd(?7Ll|0t074$v-8!5=_M?Hd-*C~5$mG-kT3k0vr^dq5K9h+Wmx*t zklAw;yiXj~y#@6KIUnBN?cl2le42a@b>CX&tn^CL=uYZ8`U+*ph)!RlcfPhM1(OL| zfnMek`=1!M$6wS%muA2)?KHOe>ydqnXs;#B`W#-wuYI|zDL;gZrV{$!G}r?e-vFs7 zvj1?JQX3@H13CMym&0^CLcNyPbmpJvRTU+JI{+$$f+^GosHmz~NWn@SR<~f?l3ymo zflr!twIHSjgj++fc72fl(Yb>V%Z3nFoLNc;>g|9@8S&1U*rcKn=yGV?Pp$MQZ};&M zF4?|+<41~8lNr`LZZguk;e+}vyj(%yP21v`R$BMEc+&^9I3ZE(EF9ei@cB4Ub)3#J~&Pv zGVj)yrwdWv{XX(PrnqOUn7XiryMoq(qLhF=HqLj`U!_hPJ6q1&@Wp=fzC^&D{ZD-F z=|7qI`O(wE15(q*b`g(QI4-wt-&3u8ReDc^#(KT?uSeE8^v_*yS(Y@LC`=x6J9CW| z3%Hx^cQEJ15xs+x`m~_O?QzV`ocxA-)=EI$<3u$BpqjXtdzQ48hhzZ7!-mL+=7n)v zS2bbLoBEBSO464 zw|DIzZ`@3?hqADt=Z#B%1xB3|1c*=;q>r10K44}|h%0*LC{9Tpe%wu0%>R)BFH>yC zV>-<$EQp2*LG!^$kMi?o)fMG#9Cp&+5XH6ZjpD7d z5&m}S6B}zAwWwwfU$l?DXgB+Ld+gpj%d1=a9vtShK5Qyh-L>~`OB=r$4+k|)c-j|T zo2>26{52~s^G(@qw?C;->t^$tqVq_~f@THP7MrG$?#nP8PZf8%ztiqR-jX+pq% zO^h^W2kPo-Bgdz^S+!WvOT5E2bW$#QPxjK_wl6%}b}>);KIWIik?1s(!B*5aEx}2i z!6dwp3>>SU@zcKOi;c{q1qJYuZ}^gVJT{ibT#DZoqk&>cIe?Mc%Z$zQeMV_5|AyMZ!!-6u|Hcbh`Q&l zgU%U3rj2vsg#L#i9n&AxhqTdv`4e}7SYT5M=eWEDy>Vp}ajq-=*;t-w@Xmb;V;A6W z09pKs&1S+fWg#4|u-s*^7yz*nIk@yCO(0VKIx}yCcPhg>3{a`nM(ca@&o5*%{-j^1}bzp6sMDNhX*E*Dfb>XGZ@QKOrl>^Xuq+sQ}-ST*X&qD2nC0FVGI0sx*T ztQ-O2ex8C$1O`DgJIAV~^%hq4)6Q~LCDm0W?F$MrzhCq>Fa+I9BCTOUz~J6_$Hlw7 zh9w$$9tP(c#2n?}i77Ov$YMkZ1XWx=qMZPX)1j{$?zYWb{8RLVvgHZ64?u+O z@(rJG%&<1&T5Y&gWBT;ZV9w#|+?*ZMRMIwc%*6cdO}*j)6JK;*)zq0g&0&GDk# z*L(Bp*{yjWDTGFnSMKrVXiW3F+8U2n9tnDS@x@8~jpYl9gGG_r18VZmTSi#i4Wh+7 zD$v5!el!hMsCIKQUQ;dru^o)q;RxbY$Oym=4X(tz?nCIAkO9=bs_a(IW2tMCyzh@s zn}x459ZcutQHM|FOEK9dC3Pr!ieOLJk51%V=25) zvz*~PwNfJpju4o}d9r(uHCKGS6i+Iy5h>OG7Hp3d%7#OQQ6VVefo~-YQPk({rv{1a z>BP>&U%_8B^7;K4!_SyoZ?a`d7#otnvW4&QQ(u`%vBonQy^ zceH{PC*f@E4-r!#8(aw^)D* z26ERa;voiL#ZDuNT}G3v1wHX`8}hAsj-NkA_btlY(^%6huC!wwyUfORwBVMNRiPfMKFmJOhw@^jd-Iry!*`U zhwrS8VnFEAu%SR2-$9Nvo>>c7iO0kzNfu6;*W?uFY1E^S-u{YvM!wUKELfYVj=8eW z{xDfw08oqhZg96h>eYlmR2Qu-YHuK_J8802Tv540x7u8ZW1xcpKG&Rtb^li^-5xEi zm+v)Jfi231-n_@r;oHOxUP%hrGq<7};9%1Lv=&sCC8%Ao1;Ne%wD4qr$k5F!sm}9;(7$eq%Dnk@dC=O1f*OYu6l&0c60*}bAR?;goNyr<@`t-oGSylX3KYG1<* zIsd$^O+WN?d#=&U#ng9gZI@oR`&EbIB#WI_=C4DwesgKF^DiyUQe7EUL3#^Uvzi~| zO?m{n0@;c)>CbHJGu~5>beWIcTOSg5-h{qsKr9b z53a};UM!jYDt5}r*oU7&-XC4y^xy#BjE5=#-VU(qF-GY0_AvnHxuF{`sL2!Vm(O~E z2_(2lK)n-%=fSD8+x77{B?&2B?{u|vz%j?>TnXv{i;pco<*4&?gDVHRdM=VWOpgie zxdFfX=u48$7@3R}zraHUUKxZ%H|CZJ)+FW?9d%)ULojo6fr_a8(-j-}EF-Tj%I4;_ zgx^PY@%Iij;8->v<%n7>_B~vReJkTSKt^6L8AZBayCT^5~9x2f`$cJ zO@OoG?w@f^3s5WA1;BQjkH!LdMMfcWxdu!#bkz|B1EbygSPQ3D0n!zw6%h8oF*Na@ zD9~Vn25QaA|4BCarX?o8^xhd%iiEOl%HX6yZ$mg~9Y$9T{4y?=ROkQtZb8E==zUds zHd$30`x~T10s3GbPjA;zrfsIoIoaF_n{!v1)I@!q8w88!hHqBN8rk0;UR;n2DhXJHW#5_A33R$ ze>iMS(8fZuY{P~T%8|oi+PS{@-|6QX2^HBc-hJH=YMaqZ+uD}3AoQo?d1XJQBp&zO zf=wvr=9UA!e{#>FmWG_wkSj9E@Z!(?cLvhEr!1*7qA@Q_kjK3NbP&z#6vhJTEPmOx)d;2T_Ls6DhGWZonYY;^C|H$ zdr^(k$!HjUc-*oJn<`kG8`57>%k8@8q8()qj(qbLsMPi{ICb6KI~{-lKXzWbfs6Y zfYSkC7Q@N{`+CL)gL7U;mcc63P~_#0P%5;~u|at7-lNsL!$1mei?fv7)0OE|Y~D(V5HLR^QO)E7N98Qo z2xv($9u5`8560@h2d=mSi?h+&(r80Lhlm3$!um1yg3{zJf<7Ofia;^WU(lP#tbDkQ zYijZ&o9uP?-)`3VrdoA#+cyz(y)&Q9;@!9L593^Rw9V{Ane8$Q%D^fppK;=>P1qbc zuxGEtjy4G--!pR*$~BIVS9X`;+FeXFycJ^f-S5xD+~qfkhpma|J93PZS7@~E-;IT* z`i|6nx|fL#^q|u{=dvqFsg5(xC&X4wh~a~X-bdM|3*<%wO#kBCe4&|Z_?(ll>-`Vx zYs^hTed~qZ_zLwJte5(%dBSnGKmYBhuJeu==Z*3{f^y28sdlIj$f1HJn5*Zb_I=v( zfyUCdK$BC9t*66#_PD)tgeG$O`12>f#!A^ zD(61x3C~(DAtuho>;%kH#iMpVM+Il3$BSy`7G^MgYtMMZG_z@AaejUiJ?(WxGbPj z05QEd%&)8Iakq~mXu-3=ihzTxRzoYEw+c2ZNfJ$HQjbD^jx}fSgPT2m3XoyeeOBzD zLa^{;=7w9C3JL4N2X``TE{2V3qFn`ZvDesHPzZg%(jA>|n>HG#&>5h{VskRb1|4CF zw2t*$Lvm!yw=W{q~k|jC>#ie+HlyJU|67QzXAyV)*DOn(An6)xbcW}yx9VkaC00E&~7+PX1uX8~i={pw3~M?V&H z-Hx2+;Wmqy$@#re_UlvLRAjr`^7Vq{^kTtIzcVZ}K@%cDLtHyh z_0mI(#MCz|e1F2$&=OPz4?1}Mx))ujR0|i&z*p0`O{1Km}3i zkRN*2a#}Lk1WsaB0#Us>b;XAY$H-1$tw7`HWaQCgEDC^sF{tt)PUCbbs23=?k_y<` zY|v(&T&0)QM%HpkBLm(8c3R~geW?B+EkbFtip4;g?aTVYx4YxjbsJlpT-5(Y=ku=F zMLjKPG@9~&{D07V{O@N4MgM}*r|{ALh?OI!E&|ABPkkyDm+d~%da2Tk`;uD0N}P;E zN(2HTCSgWR(n0tt|J0RM0I6_pd^o851Xh1_Q8)Z_zNw2&qvKnQwp^?#K4Ej@pL7X1 zc1G2oQT~Sx00+FYd+$x;evy($np^+x^w^LZV49f$rzDihzAJ;0vBQhd zWe8`6U9KMy+>#Q;&Xqleo#O4JHDC>qcT79E;q9*M&&1PU1Gq1YfO2|sAU6>6-ea%# zpexC&%GXWWB-#n0<~fk#K69}dN9!{5XpST6xhdCHsHjcWEKxbMO{iFTXF-j~8(TZe zwo7O`PyeuRF`p|g9A(*YtxwLcPi`34)EhZrg@j!nOtVi1tl2%B6Z!t^vGoy6m~@4+is$L^PvMB#tm_6P+!3m%++490J~+0l6Zc* zf1tO+>ed~E4fA*0Sn|7Ow70lSBMvlP*A!LdnEUX9&Al4j#V4nnz`I`Ef_?J*Nz?3+ z+9gwnOR+>Qd~y<)vc2$6rz;8t8mpmoofIr7#*Pqam@LFzx>n^8GKIno(+yP`G;q^< zDGRRPSk8huQM|$zql3Amnt2W`Kk`y({8|LEGQ(XoSH`{JeHX~BetIK_2E`&T`H7a1l;LWycyLexGuat;B_1!P zC{4`lNHqs_Es`EKzeZj}AV%$b>@i3)%A6aFy$lNYabJlY$@kvYMPY1D+&Nl?o%Lt* zpO8bIrD&;m+AEW%+2oGC(iPOvH#GY5UNU_0X2w`Ad4O)qz(-H6mupes65~@gL5uQOK!R)fYq0^RD9D`@>X{@8w_8*XlA2 zZM_T~J48)IoJ${8-&fu=YzmO$_nY6pHvZWZ-D~Jg--j0$ApLOMwU}!dq42k>TELop z7O7{swoml$<)Xb6dQ~&D;Fw9;T_XTs_%9{IXgy!!`tKI3FInFT<>a5d7xdjFTKqIt zzoYWAZQlm>=(hMLt@)PwtY%$P6*gkv5^e&gkOjD4hysd%GS<7JKg*Qt;}~%Ti%A2) zrr)7J_?7D8oyI*Hr+qXgHXE|TB&lJs4I9CxXbe_h2Qo_$913j#yY(VvX+udKLJ}Bx zDq~wTO7^d`1pmZcH^9!3#Cn)^UCX*!iuVIsxBuN>+yCnc0CinU^NQwNjfUu&;YnVi zFBCoYz04G5i9A^A+T5WUD|Jrwg$7zO^V{I0N;xgnYt$$k%A236pKmaK)8g^o99DiG zkAss`wvVzjUp^bbLS_n1b3i>?_1CE%91m z`wdiVLC*~{)Ji+-MfhyC_g8ps7*e$Ekp&LkA=w}ksVU>dRd|$eaxuQVkoELi8UF#w z;*-*Wv<^exlUQ?zPTK*0^|(UHIZE!joI5jnG>-cUQRAh#D=Ve@HE9Rxs3~`TX$knv z6K(4%PQuP2OLwWR+z$q&Xc+)Zg#r;UT1?paohteOxlO_fw>DkPGEz+09Q(28+_x;0 z%-*xywoFMg_f30@8@^Kw2<7DcHIWnfZ$6LF&L*CKJ)8V)#~cow$P~T&@?jl0v;pcr zWgG2oDEJ;|*{+XAs(J2}yN9G2X%?aDT~}<8U&rmex!bYrQrqhV!JH`E0KJ2o9XlS| zdJTj8N=wkaRuMRMS5!6EoLOD_p;gH<>G}(ApSdj{bN?Oa`C?{FP2-P?JU$L-Fp{G4 zP`n1gE(%tYhskY#k3GoYK6ZTan<3R+6U;X`xINc3q)>p9d1n$_$tn%lQ6VTBX7=tw z^my&XwP0RgVHvg-j;Oed(Q?FQmKC<+giW%EJpz`Iq69YW0%}(31|=>aSpW=}^x?RQ zcsf@Hi)|0FJv1ZZl)2c@3)NH{zw-d*M7fCAg#-<~c3IPAY|Y16!o%Ko}TeRDSENs zZZsk92AHL2v6VyWgMwM%O3u7Ku59m$MZL z5EF=P`p!4M`hZ~rBc{4eFa_l_FZK4H$0lB5k?`<7@6PY`o;)I0x=o*6w_g>YNnd+4kFVTSm$mM10`!vi z#nVvJO+RI~k!9NOd0VtC{hrNh6xIdI21eLvu;NBvxQ*+!o+}MoNGynHEQq<&S6V^( ziI$*ETUL09H82720<@rB!+L*#ZxTfFI}}({NYq$PDL{PK%y>U0N4OCoH>tuI%$iQqar_4(5G(LrCVr=eNZVD9mY-u@AA~0^7hu zo-1TWSgCP`uI%9*+p-<+Gi)tXusgX(pbt>!O=q04!FDoM;`LGdI<1Em1f5av>K2Q! zUT3>)tXG0X?vpZcZujX2$vy*WPSpQZ=BryajB(5_+rR5^2y;v8e-T-HXLtE%bM3$8 ziZ3>d73Ij|(wg4BvNnbW5w;t;Kh|Pkf&l^xG6XPjh>B8K_ea1}=hD|b=Jz6u2Mlea z?eSQs8-i)3)eLbOHp>JEz|ML8CU~0n|0C6{qI&Jj?*NB5T1Vt<^+pgiT@4|8(@@Uk z+XPnbujlL21tJuhH)Zbq^D!t#24?>}-13jcNuAQbOjl37hH+?+umby8gLm^9zLsXZ z6KqyPHFuxDbQx!_tX_;4o&JE9qIefS%J)pyE6eO9F{MEQ(pvxd&!ch+%V+v``$U|` zaXREndfHa>6VS)-F>H0UuL8LBB;8aqi$i%?C4Y@w1}mN<;Hgqe{&OGqiH z$TD`3bu5u3CE1rFS{zI2q-_7|HoyPt^}L>$X;CwM&;9+}*XO$47bf1hM`2lM;o1e( zS}qyJ`;LCw+HdW#)zRnlN|+j7s`SM6ggZ7}J4jgSlbWIZ>32e{SD4}9jDm)Yqr+mG z`c7q-scUn-IZrjm5;%cvT5!J$-_{)K{2Q{H{`t@s%vbSrc}jPot!F27^^CC{$8teU z#pnG9;S}MKesz^LJ*8mB5{l4`WwV=GS{1ib`%YSl#f&g#Wj7~y81Vk$v|fKMK}?ea z3bnxmSRqJkAn)Q~CX8UJ8V~OTxorY5z znPq(Vo|aQEw+v{qw~Yob(bv5d#}CebMt-8x5a;v=2p-BXIeggz?SDm?J!>;hxaY% zul^IkacLkndh6v!V@rF)^S@{+ZrSc4UK)Bll~r-b0t;5e+8bRJvU+mm}>0X{~o+=*eypWL?k zzMbhhe)+(@e(u>R4yyael-QUm&$qfWZGLIODiGbSaw2k55Uy5NPxC2PBHRqiy53Dc zOvNdkh0q|!!v&mDW9G(9J$PFEXroH?jSwL(ebDo~G0y% zTltSl3M5%q$18G>{XK{fhZTEuOCtsfENjXB0J~dKr#8MMiQ5{nloQvaU!**|1utQt zAy+?SFrZfyNQGRtdijE{FlUX#kyUq>DGqN}HrW-TzZoKKX76#Q#XU$q{qiW>JUAML zKKW5>Qw?fhCE&^OHVNW{>>&lsO!=m$zzMe_0SQN~iAK$2zcKJzR{IWbqrJJ~r*!oU z6OKCbK~nj(@S&Frp8s8U3P$6CC=zRddy1lrrS3jonjj2#9HrJ z&fQcYaNj`Pcy5FBfiSV%8w=h)kXX|65Wn%zCj4lVc)pB0rr-Zs8upeU2)NhJuF{3>~Nxk)$tLW=jeUXRKOfIk%Gu3sNya zHMvjD$$8AEIBq$kk!+Sb4I3i&B!B6NV{33)JC*TpU%wqS^RH(Ax2_UPDX}J3(G_}X zQk2v+_QBwkdf}B(0~ZTFL^Aeg!?gPlzRhb0I5_TxA8n=4+Zmo+r~U7WmRMoZy4`;S z0bH;_Xsb|wQQV90rC%g$3QB|Q2oUXSe~j$W?%BdxB%0QByX;ge+xzAFf9^EQ%o@O_ zfkf)=4#MO0eaGdV5mA978jUH}DcCoR<~77@Ec_ccy$M}-|B&6=M7*eV;}>WVJQc#t zLzpYz0P?iO8U?ODlvs;d+*vx~Tw73Q(IK*ZkBO_z-$mP!Kdpu{R&E!m3m$b|xjAqj zC-r0TCyXnLU#x2bTXzq+efYPHXS4c%_D%b(TXv9f!RNjCZkw0K4t-47@2gXHLdzJw zua~i`y8{PyH+D_)9xN{qbz2NjpxX*+cRo%FCq%_q3FZ0^Q!VFj* zj`oe7^Vw?iI`q;2M}YLk$X@51SbMVNV2iN3?(0y+oe1}ihq0aCm(U~3LOU=w z5S1;1#j^^AVy_GlJR8_qwNFLw@xrR@)~LnX`t{AjrXMl^Hq7-0hopk?4c9Qje8mkg zrZNc;^t~qARgMvvI;>d|@|eeMOCK!} zQefqLi{tWGwFV$9hq1C{wsa&q54aAzoA>k;AaNKeXGJWsVT)nM;gNbdf0VB#7%%d@ z;;uKeHf0^2K&}IT9=;I$4{Xz)=e?FWw=3?hDTFC3eBif^=M)kE>{_(HG2meMlP;sU z<0su|?q5q^|D=d5p9fVIm+@q5m}O4#pmFP%xUpYE(_GrfzDvPjbl%}z;6OB+Py?&WFHjqDjWTcv zJiGgi^hVfl1WFvU{!aEPV)J^Vx%tcW_TP3gG5z5c0CubJB6=|{dP^y(zj{B_~- zaNFa-@!?_inS~?fCvFX^7C)))f4{G!n+7sRZN)Gla6r%4i;tv8B((D#Q9d>|< zp;0mz77iH#>Oq`h=rx}oqgXNlbHpoOmNunE`KR1+d+k~5Iz~0(P_j0A!FL)Xgl0F0 zu=!|^^f(;c)dkB=7wS}NEf^;6&H^wyX1T~CfsCC}aT*3*q>s2vBXcmjy7tftyxt7T zFImcD@a`i~zZ#w1Iv4*bI4JUO4yv~2biVzTnS}6_#jNH#9oF;m?T-Z-`X9gMFHj7A zO6cC$vs@2;FXb~MQW+<_$#g&^txisuX=zu`D~g{+`iersLOU=mX>P(DVB`6XTp~S< zxxPh?)8>uIV9&?W%e9Y9aC8BV2T9;P!{0mJNEybheM-hh6;mGOoiERB^Sp2SHA4O! z8W8fxiVY;Eb6En0%88EBskT?p^_$qvG&1*Gu7bx35nD`-JXK`P4jZYM9KU zZ|6U29Q#c@WAFT>VfNR&^#67Ec51GqpDnp+y8V9VF0Z1bNjN2Jhu?CvCu`iUa<6RW z2nn5rqsy~(A=TVu>!4<46?f!h{D9H7y54tYc(7sRfwW32IRtB1Mp=STz_KqEn>jI3 z&nD&|62XHKOb*CsELcEK!*?dvL~jOB!inyod4A_;Y4v3ZD!80L(E@xzproOB%YH;O ze)|T0x9RY8n05}ubq(R`QZTOYSN;?(a)is=C>_08hCyKPkm!`z=zfi0;OUv*TZ#Jl zOhM@7;X0%9OxA)BoM;@0&?kUD>7(sS@`Zz-43N9!shv5`RgCg9&9Kn}?qUc@(q{Qq{PyKItFIYhrj8jED_7b@ZOSrgB7tDB2W!eA+w@ zCh{Q>i87A9lZe>m$WXS!zh${B2wVc#wg?FgR%>msRDcoJv9(ebE=oo~>}*l!Jm%rM zz&hGFM9&qjf-#SxQwPOaY~DJ5ktiz!L^Lam@p=PjrZWS=Jml z(s#PGAOM?(@Bi$zvu5Mv`c_z){Hbftx1xqmmrog3+~^uj{`6+c{UA&s{oh02_H{|v ze=&G|@9%djLHVmQ{}j&7HlUN+t2p7Y%}3K9#e@CXLH`I0(hu~py=XMI_0LdzV~{SW zSZX}aJGaA-ll|E}mL->aUT>t?1}t`pkHbbbB=->0s z%jc6AzPZaFq1fhiczAn4jU}s3;C-c#!|kQU3Ub8Z;*=>y5k2Rl9 zpe=x;uMs43Nq&Uc zw+?WmDza4^hjuv@V9@kA$<%^wNdJAP2FUAWRRpFYC46cd`M;SD!MUO){ zM}R;#k%hP3v(Kyhz-uNyzarLr3j@tU*lIUJ1b5md-@=E8jAghPHj7 zq+f5{F53M~NQ6ofvDOMMMgMAb3Iqo)23&h)pr%uIMoa8OV^QtRU-G@4GvGH5Kk8h2 zMG!8Z(^-7{i<(D!#y@gg62f+^FL))~9vhHAt z;ilrm{)^F@a#J+VNH-_8)-gBrnA@8;=Pp65v-b&X?ZM(%TdVHGzg#)gqqoby*c-JZ zWE)B2-e|q9Su3)=bx{-IV-sq<4H=|J9gSkY8HKKdH@DK~Rs9AZ2?rfafk6xsj^YhLGs08u{X z29BW=msMFLBWpur zDl3B%A(kyuH!u-h|LoZ7>?M&_W7Q^qPtGu(%f}P zjCcMFAV`p>)BYT=zCajRJ9Ys+HGt5Z}>9p2Ym0t0YUZabUs zXWZM2Rz_@~Xf)7dY(vf=l*BgqukWeyzDBpW;jT(!=>$_k62V;iy3)b-)3 zh5CKt`imb6wi@xyDe&F9AEfi>AZ)?e#hPr4bn()5HKENL0zwRo5^8?yw_mYtBX_o! zu`a~ncH+CBxw8UBi$1HPb>@vLBJ$IDFZ%%T{Iyi3O{U3r3ZjB_x(EE|UZGX%*u-cV z>%{Y_vl^h+sXg$S(%~;Ci_$1}Gi6b8goE}b-shH62tVM)))I}? z5JQm1bY^D0KrN8+0eb~;8SmcGmIj z_{>@PX|Vws@9Ro;%r2l}g$}h-3Tc1q_k=HMp+Y=CII z(Y<~N@f>%f+s!E}hz}FeUGxP|Mww3mODs+y<}m1ct5HC?8<#`O>SbD!LhOrtQ_!1;5SP_ytC+ctn(nW0X&8H z+wWJT8e)|-8sCjyXc^`Fp0ZsLbMA}1TCbC5L72jt?v&lMR%CAwFJxr{?CWezm<|^; zn5zgK){+d;?gF0;$_U}?LUzIhi)j<))*@IlI1@!UCF-d1quIY_$<-A6t6p+4q{?8r z`{j$0u-3)L+EPc-zaP^-*1NboIXh(}i zaGdA=E~uLm*s6#rW+})Pi6nFBt=B;Oe65n!tzUVb9Zw|1w=+$kV>A)|GpPOm+-XFs z;4IOLe2C}pZS&3kP{x#k%Ymm==5I8j&a%IqN*}}y7!CpEp{iL{m@G}w)qKQI^b%7U z)0K!9Gk;}!_Gs@P6_T}?%dkOIQ2nq;&W}K^HLY1An1L-oFN{5#K-UeF1uNC2H?}!R zX+xs`e>FO-;n1>da~W!^KGX6XYp)CMmPaI%&?hHKRJ z3q46!qh-pd)H>`}gOw*~{7IzogTHZzod4f?}>hY8vy$FlGGuZ61Y90_Logv?bnHn z$fTw`0>2awr^4^3Za1X;2yJ1y7)~^(5T_{93|AXSZSqCeFmj~80nv?Is3x(PFOh%v z9w~Jl>9lUxFq9On8j$qFF%Q2_fbi#G7$WR=gu*r+o!B!`h?h7nRu=+)<9ZqE?{&%o znY8g!c8mvwIh<^b87FftrbX~1=#KJXYHq-u#F}6*8-&^gj}EKxBZ#&SPtm0}0V!~( zl_}SY-P1dHC!jDZaWE<&EHXEp3b~BY(l`KHdSLD9;h+0Xaq3o`?;+yXiJQDH1)aC@ z_1#KGiYMGy0i!JmQ}Q8s;UBRP)(9{9D?a}h%EdjqiLAikh-jOP$Y$NE@Ck)5O1GA> zlL`Km4HhrDITOcLoHQ$iEHCakewv)Hz}a@pyLt@1>DTv@@62#p=;*O=v7jM$*-UNW zGUZkAp_>CrihZhUXfxjJGou=n7zulCA^tEwDA{>Q6YALW;EzX;y_`nt7U5TE4!RXb z38UAI-7{>im;h9Z75C$?i;-};LM8T>%XzAs4nfz|0E&{T5%wq9!a2Tesv65cH5^$S z*J8bV9Kp?EG;xEi5;^Dt1BM4qzlSEsIf5KSaR;|e6Q2M&Iy=!6l17^4jIm45yB@w3 zAGA?Z{l{^>f=2YGd79m^<6lMe!P=M9o5Z181L8mGp=8I=hK64qsU`Xe5+*{52^T!s zfhf!O=y;mLN8^W%SL)rGG$O+pUSNOCFNRGZ>D$ir7Qa<{%)+;$Zd5#oHzDcs*@xX= z(cP>^*A`82dbK@X)$p(n!ofuIB79E}Mm0>|Up4);xc9>}V6`76R|&BeP*8@f3J#gLzs*LdhMVJ3c7VUmL6ey&)UM$?txqD_Gz`$Zb#XhCo)xeW61*d)LLR zw0Ji^fPXP7ACNE1yh9j5NO{{qEeJ~jD^R^6VXMI3iq-d6Pq`jkxqTys_LpIT!TYPQ z_7X+mO2owwffTGemJ}ykEA7I>9Ik3PYry(wR_Vf*%IeG)OyN=g@!@%DM$hFI9;l7_v~J`VQQZ~<}0{9N|E)S^wWiyGhfI+t9&y9Jzp{ z`#sh9ue>vS%6FWZQ?YZZkd>)3KIlMk8wE~F*22vFsX%9tgKR=JqizsuUQ>d*{u(GR zX;Nr^)%5vCF%2R)j#8Od z)}~Q;m%e)&kmBy60IiWseGbSFn^;`wq7kywI@NVr@$0N--qZ!demDmHo2rioHX$T>O`=ogcr1 z*d8sjyz|2q>C+1K6Z@S73v4sau#kP5@d|id5(oj~j7<0|ant;S#$jUo4gNU?k6hn_ zpV?3EIF2(GXL|A0aP}d$(GdO*$(LWoB%Z3regW6Aezs9V(Fog1eTRaVaI||lW_(sG z?#aeuPriQLlEXU($Azw|$OaenS=&rKKD*C_ge}#oiZMyQGOF~RuoUOO|E7B^j z+xF7r1bQPXd`1gsTY(23yELd8*V9Q1F<5U29XD|s5xOP^Dt>78EF>yaK`Bc@1}GmIi- z#LwXI0}{Urm1BbloX>$ljqXnJ^Udh`(ls1d;aTk~Sq}jFb|J0-Lt4@%UjCD;-7(cC zdRA`x`(cbmTn)Z8HhqnbKjN8BbcQ)FkP@ET7PQ);$_%M`VLu+A<#LYn_=?~Hm?VnCZnLVhkY`I+X_J<>&kpO%oKdsWVR|z&B8cRL6@JgG=fbNUAIa(CJJwS7H8Hn@l z9}8MSuzYD7o;N(1R_{>v+H(t#Wz;4Vfhmc`8J9%%k-0*2a2xf3shjlI4tgVb&R-iu zgID!c5KJ9#`K-_a$21qbAa6O>!{I71SAp)h-6GUdXED9ArnpV#0j) z#(qIf-5dvdd%l9MY%#Nk-f0n>S8YS!=wVsn&0Vt2xdB(rpWeaW3<063K8WuqjXF`< zwUWa2ZHP?gQSmDCD-AonADP=%pMAV9;k_4+A4FS@65bMU)8u48 zHGlH-8lYE=d0#l=Eg5<76)fm82EYOJWnW2c2?#;^sn5X1>Hsw}>;q)j3%!^cW`v#a z#>W6l1y*Gsw6W5{l&TP$KeOz|Wz~mot2W`KNCaLJ1FCujMc~jcJT*#QBh0fzudD&X zffGtyI4g?cMJgQ8DImlzHq`W#av~HDoDXWH!Cg3Oa5#Q8YNnUQgD*{S!XeHHD`s!A zlv4-VAe|Os1OR_WytID?vcmCD)D9dsDP-qx6E)x0jM}%6ox-S)$ zhu>mjXWxTP4iFE7glR@V3;-rI<$1_iVn}c(2Fqj+XCd!zF6$f-yMjV~?( z!?w4NLeWRTJnep9WE@1OVoo^lv_D1WxV@Je9glDFVQ z$A(u0O9QJuN*TPgHKMp)llCw2r;8zVA4D-K2M8Oe=lnw88n1SVQjo)~!9#gNDaZzy zGrVz2Mo_C__EW^={ zLDaRL5!*}*0d^ETg8sgFlP`@A7vWqUv-^s|1~99>r|SJ^bWs&CGpm=R2w;s&8}F}L z4IC`j+9CrMWF=@j59bk=d({sQV{~!r-&u!2N)-tw+{}E)863v#>Zg$JeYl)oNQ8n# zdtzZ%G<{EUm}nMnaDe^&RO~MrpYUM5?6W|6;`1H}rinEi2QQXj^6h9Kl#`;y;GI8< z+Zu0rgIt;JyTDdw1-?7t&U1XlnwSK#OS=@DAB!W0Nn*m$Lak*MTyrbwA}oxn1^bHa z{Rb{4f5Dsojr4?e@Jg?Bj<9a=7TID>TXF{s5!&>P|NB<_PiRw*0aUcQZ)fZqUyHy` zY{JVm&t6n9@xO}ZnzYH+mTx2JNL6YeYFtTMXk}TE$(Ci##jMM_6ZWXBkREggKLdN%%JO4X;@ZvN~w9Qmb1Q(hj_az8{^| z9-4ok3{$AHrufeQc(b%c*81P_PVBdw%+Ir3}^Zh_GtGPnUkk%-ox z<|riaM-6O{1+I)aAgftEGw^A)jQQE8qP6bO-8K*83*eZ-@$r1|DSo zVe-mhFIdFGusI^D7T(n@ZhK-$x}fj0)|H4Q#c&7v>XEv^Ey06GKtvq3#>LEX! zjg@X`_;haYN-1LM_w>v+0R8cI>3E4T+h%U_&*IK-fGGt?BYk;XCkGe1zp+MeaL!$D zN#TwwL$0F4xLwf7c!dbM2xjzs(|rf%;lEjfe+DGzzS|mZoZX=FFd*fCW`yR#c@oa* zblDk;_6F=UK`RhtdZrxN=`yU=Rbu{WRT|wH1@i7$|^7`wrEAJ9CmmbXrhL-Qhhq3bFS8YpqrwiW&qyN260var1}C{SH!iI@N(! zLp{jaf2dnjIsNEh%SdJ4Nsc{9e46PjtTif%Yq{;?HD@)3;{@OxCjw#wg`O?GR;SXoD$idqr z3#(Q;*$@bnSp0Q2@3$9s8Z(g4d9ixu@O78X``!DEx|<)Fvn*M^FuH@t=6Z_91{pcg zKLdd2M7ZO07D!NC0yJhUp!y27MU$J9r&ZlThp!H*E$V!$7e1*2$!q8#%`IpzoDDtzj9`0w zs~?`5uGky`$A(WAh%xif?jvw#fjv0X4{vT;qy>H_qCyOu`BZ#w6ic3}$6;QE7s(cl z%Dd>CC!Pje7iock!(t3HA#kC%Elx>jRAZoq1Jrpoe0rQ}MDaybr_iVQ^>^1rKfL#A z9$bvomqBOtUr{K%9aC7Z_YAOP8a)U6g8`v5rLY??UI6q~Ben~o1B~!aAyLe zgHQllmr)STWrxzsdMe6s_{pcMweVX19x`$&Hpu<{+9SL9iQ6WAU_MjUURHMqgj~hx zY4=_JAvYkyAh5H{!V>05QASGyR9s|zTNa;m@(9nF1Q}ql`}%x#4ZvGorzES+{E}@4 z%76a}e@oY2Fgs+O#v_||io_#?4NBl|H2ZyG(i_lLle5J29 z&0kh8F&>iG3zSlLU-%hkh22{>Hi%yLm3||>d*hX9EhNvWvMKh((l4Ze`tX6{YqO!q zW^>JR?@#ROdhqefuD8w`Iuok4-x%Mq#Ur3e46A-9o?QU?7{n~c$b3_B2zjdB;1Ae6a>`fTkPHPgyHbh zu(TjeEV!9fu=MwTV>A<&0Y9O4VCx6qW;uxuVa~110Mui&%vILAMrT?hP7}}>G+@wc z;gwaX12zQT%y4(r^!Nd_Zd35DkKk$#K%JE1+sS+ve~&rUvXq6&-v4G6EEw|kL5g~) zC$(Ko)-hcR+7IK3#d7TloWI$F1G9n(> zCv;2-e-*JB^dV?T$&v5zyX~vnSdp=OKW3N3jY}U2F#3@fPWd|@xu6u1c-PiT6R{GH z1r}#e{I@%dbrr!0VR&!2ZYvT1T^Mj4;vYM6=C z2ctP4j^;-l;dTmM#x38GAIXClvB|?xdW&chtbA$#vntM3t|_iLqKoGAQPmvD#{=lS zaIppp&Jyn2dIq3P={c5*Gh;OGoCs*T7$+Z={qYnBD;4pwGTvW#+@*p^nugv%vsrJG zre1Iq1fq$(WYilk0Y^9?p5l=+YOLad5fdTdW&tzuh8dj+kC61rqOQ7gytIxKGj$_Eb4Wr5BmREzd18S4qQXBsKDHGWjz;nvv8 zGy-qN_CSPdq9zQ0mzKz$;32mXA^g|O&#pNsrpSEdlnHmRD@UXJ0ulgBz*TClAMS3nlmM_Fq8BA1(_FuXQ8{x!o%9P7 z&Iip30j-b9fRg!dSo8wz_=QEj=q}(6Gd5DEoZy{(aQCI{>AQbt!L}HFbaA#Xjpb{z z1J2pQ{ij?6k}bJ0!ta=@Nzj4^*c{CTn%Z*_?x|b!PF3~#dQi8JRN+^w zjJ_l~g*jkMMY8k4|JeY22$=?1DG;@M8Au+Y5Jg3@Nf|1Y)vbs6NN9&s`*Rsh@ozM) z;sRgmm8)ApO86A2Eb*Q{i;gpk3Cx>S6LN9jW21g057a^$9;m58rz&i&_E`?$rtf~i zN3c2K+1x}5)b?Lo^Ux$6O?~#E7%71-=Ot_J-=aUW@eaAh#0Zr)r9?)6vm-nI)1D#}1DJUlbK&A{hCf-U(j{6}SFZyG)q4Y@qrjQZ)i zUcgG_6mJd9ktzC%)3zNhI!xDw1fyjW$g|C=L#(V$B z~i3+rlu;c|V55qdFC1C_0SAXEadO!Cg(y*Rmz*1mkd=19i7ht!q^&e^b7hODS z6gsKB`U(RtMWG+(<@dkgyImKAs_#e%Y&;5I)b$7Q3f^F?fkHgr6Z^7`cH5 z#zAAy60rXtRud?TN+@l;@1n-fU~l`bg0HP*cM%k2Ge5Ssi1&o(dv1*Iv?2WXI`|?; zR+N-|6sKFZdUZR=}b1ckzr(x=3@!%}T0r-U+nro}m%mBRGcf zQ7Q|h>;xv>82Mj_X+3Q+b0H7)Q093fLHt@mqvUr zfSDoI!}cBm1)Q~bR#}el^6Zez*daE3n}R0UL-`jLVK&HpH$`ixh>(PeN{UDOJ4X|P zOoBj7E*`1F{{O<=9C=bQ-(x8Jx!*k1WiJq2Mt!@AdlE32UTm$XVO(gD8rVG>gnFKu zuMztTr2gJ~ln;%QaL598Zg##enpB5YreN{EO4p~?IIq^m{aUip#F45Apc9k;bY(1U zOL_%pgC5$d3QrkaOC#k?%KLb}Qstk)D7FT_DGxpl=+2AZ#?NZti z>ipOM*M4jdfTl^^jeIg+#*)J{Uo|ATH^LAtI8KHX!?>{8Ab<%W52(dRI*v~``N3c& z?Tn=FVeY57WBvWw?beAx?w2mHuGBMdD$O^k@CMFbgnNyS{7F+!6YTg{$BQ>hfH*+I z5))wbJO~8WD}%d2(eb#;4Nas>%eR$S3OG=FDm|805cI2GMe`J3w3>(ov}n`H&Y`R7 zRxNHXvQG3EFPIP=K5L*xW9Wlm)16)suyEtpa(Q@vgg~3GQ6qZQy+ytDbsk_jzi1_u zMLfl?AG%U*`Iyv>cZ_-Ev*KQb4-cqd=)%-KsWjzIPTaAe{%}~oG9B0~^Cp5}l_BX~ zo9_bXGT=j20-dcqJ#CT3c6ZKh5i&w!NbiTN$5+YhnUjhs6a=}I zq7&!Z-0!c$>b|4%j1|S<{}q&C5}3CwpGW5z5TGJhI2mrHC~=|yZS7rL&~Ke}@+pZP=pD{_Iwm1T*ktDtF9>9&_uwH|`NU*IELem@s{A7^808$R%U^ z%@5-sony~`O1H6SgSfO0nBcCV&M(m4E}l@ZjoOg&mICdHXHzb0E1)r&w7~CzPfXB; z0N5I{HheQs6B=ES<_UulY_&B{bPBO+I#fr%4T>uxpj^p!_H_hy$Y@R}mqppK7wXYC z5EnQ41{NYBGR**gHuctB5@vEYO^LocE8j66NV|eZERh5RDuMN)WVj*X3MSW3_A2Zx z;00%&oQ#I=*d2PJJ+1oxiJs zY+&=?+WH}ziJ^p7HhXoLV;X=Df2PiAgNfgc^3n{2ko;Q@FQdz#_pIAGkqkZ8=hT3~ z9o?avhu@V0i<&oH7`aIDf_)=5LpbKZ=wgcu=!kE}q5Qqf_(Udi6Qk3OIegB;*&I=;-3_<#A9MNk(|A{G~z| zxN^|5Z-SLCICAP3HdI*bqU3j8Y4xxCSD1a#5p@T(yAXEQ>h=C>o33tslz3L+m5Bqg z=;Z2e$H@-2_0qYI$cVi!*g;dSzFToig_OMYS(d9;7>FFT=0@)z%;cvIKFC5T)dn%coo{+nbJ*~WUVAB7>iU11{kgcc@I z(Jj<7(v4@ZfqGEH6t~vrNtaQSCR6Bh%5hucpZ2@7|Ko+-+QU3sZM|DcCzGYiNSs)Y zMn%XF{bN@sZZ#Us9JuX!0ls|w$#WOuj-KcFaGj!a+)5fLmq9>m89I=pbh=F=Cqa9? zoKelOaek7NqAo#{XQ|7eg0eWsuWxoh%?Ck43Kw9=uYs7u0ms621k|A||8sjH9FdD) z7hrKF_(RuO;bxI_r$1NJz^R0p&tFY4eB1ZWa;oRO#fD&)?pmPLcia0`(h&>5+8+C@ zWg6Pm9-bXmeXV`A!5@zfTrKEX7a>9IVDx4)XFFZ|g|ulNN@hPb-GDV#Vv=6_e=9Oi zC}Oo3l3`>){Ba#{6ANpsS_|x9GnR{jBNPiCCO&mwI@hRTY4@J(K)nzVtfmlEqb#{+ z$^_34=i)d#-6Pb2#dlzcXOGuwdW`CPVrSF)(-*Y}A6#s+y4x6d(=P3vCM!}IaA-kXov5Yl+m-QgB&Yf= zoa&-~8Qv~Tg`pf(H0zzS*64oFyINtGz8(B7Jf%Q%HTCK-aw3jt{&Uq-s;JcVwb?w0 z$ku`IX^G?ZZT*zo6fAKzIc45rZAQZ`CRp6(1JFW~Bl3EtPf0CJ*8glzVBQLrLgzjS0iviWK~8}#)GDyxMf zwA4Jsv}xw^?fKSBRTKr%-z43Ox=`Y!r+{fEKJpRfl74lco+(vAeDu~un6Rd?W_lzd=pdf>D zaFT*6cM1_IG>X^2^IEYJV0t0=sZg&*yrk_0I{;YXc?=a&(MSo#EErKdt;STopq-&} z6g^c^gQz@r*!dYHW*B-4^Ukk4Ua$R)XUMN)b`0$@5HCgHsV6K0L5q4?-RRssZEad~ zZ9oI$1Uue?xI<|G{#9H6V!W*h$X_7p8yc-NM-Wyxj{I0s7gHM-!U(vPbr?Y!__6GG z@`2X_5J9(bC1HS&7hx*VKTamhnheVj!`{to^KV-MVYwPx;;o%9mqxOiQ=+HFC3(XV zPl~xF+ccFZQa6B9R+T1x0_gg?%l0_f6f~AbC9I?zb?Lq#Do(2BiqRe9soe-;%=YwQ z)dgJR8;4zVJpN0>VL?v8#io5H@*-f$m23A#U6#Vq``8%#9snAqjjqa~oLZzLhF@uX z=0Lrf&KM+nVh0Ja@R@;=L=MZrUdsC;3vJQDG1Unu3t1!sp%Tq0y9)y#KYV|>CjT`p zpg^4*lR6}LRYmfH%~H!#-V)D5)tqvYphH1BtuKc>?~Cs{e!||K6c~km8+2sS!)a6m z$YenvqIx33)f{2rSR6d-iW2ufJs7-tA3LViyV0rDGe|;f2~=%7ns-l^^si4*07fggQ zHFw+S?SYtaQDpTvdRKu~`ypol5mc>C2pq}!i!NyO0kgsYK4PYjuKJIHvgnkb1Q z@vUyh8Nb_x505S~vkp=ais%9%IR$-|VImT9FMu;Gg9$Yq(e5iubc)m&eK{{QDhYOn znYxbcJ#Fd$_*$)BEs3$}@bulX>8z-OSzY3YU;)7R978c8GlI{jv)SLDf0iaV(q{<( z4*FxoEL8EI=~|1V-anrW-r0b*ewKZL{+GO{9~b64fUg(?0Rb}GKx1JQg;{Nj9%%Y? zkcCs089K}!2#pl%%Y)NG$|s`5NFT?j@m0hBl04>{4qvhSFmvcJw0rDDFQ?bDGGUWOmG%NMRxOs1@Xc=YFu-+3BYxpl zjZvnL?D#WzRx=Bbz@Juffp3R)gvGN6peSuR9xk_Rb|}7&st`YF`Zem>ZN3X%XcAs| z%O11gssHd=ejqe@qF&vC7pDs4ekCZy%YLhhg-V}|~>N!fF(B|R6cnI%vHmRmkF2bLTa^d2q z;}EkVAn|uVDIn;>Y`ny4&}RP_x2ZkAXxUYS#&3%cdLeb{x5ikaVNJKMd7NK{`3jBq ztM}pA#z_3Cx?>_%TQ8bfWJi%_1fUP3UvIs4`orwX{WW4{Z4Hxu1Soh-Me&^vvuGNG zg%DwIBn#gL9gmfI$sWhcjZURo$->QG>`vl#AJ(1X$k2oy@FL*ApYFpj7M!}6g#8wW z_hf5EPj)fWWUodeM0w?{;RE&o>0rqKQUkBQZf)beLz)Hl-EgPE&W%v_)e>VK&K;M} zy*Hpr%sKECK0=wia~@%ggH8rZ*MHp(&qwo4={!n95v`LZd#9sB7Mx?ABGpG4frtN=mZvwih!1Z>V`MY3J&1fi=d9= z&a6O4@lElA^PnqtBk!`fvMY8NjPM|rEgG6;K8gU+5pSV)(q|8eIyIs61{|QQ;&AOZ z@FrAo#}ynqcu$)UI#Bh2?l742I$Ea{*TM5Fe;M*@S9UfV%r)Plgu@ZN zu(8{$8$^ID=msx$pT_^Wnetvnx(?5BM1*9m1EsRcGfm7c6&gUf44T$iP<}fN4;0wK zT;`$u^_qU}qVk2E$3jGBbr9uY*Dq{5kGmAh z>nckC?Bs;cY9F`$_!jdgD`!lNnn+a(2%m4AOcIEVFiJ;Qh;C9Q@-!B9tfw*1Bq%Uu zX^F;i5q z47Jnt6u$H+Tw--WeK>h#*T7hp)a-x=UP>y&^A!cMW`A?ej>BY*bTnev($L=zV_$Dg z|0M=c7vxxU+NYd&)I~wup(gr5#{?h);!d*4iB_m)eq3{{_q)tj#k0%4HIIT8F;Vsh zCp{)_eRFNLpbvQG6SFIxOk`pacUjFw+`F&;dolrl5*yYuD#2a@2ZJiTgC=Oa6!pV% z>g6d}MIFvfg=!cgtwfI*Dzl(hg& zs*)6Slr+V+Hzld6j}Obdp6|5%{Dj{P%wQ3Iz_^zjxBO2;Uq=*-D+d_x>Hian0I<+P zjux?wCWHW$bVWr@xNuhbz-t;dR}#2LO>r%N>n6d1n|HS+v`VA|8MFdiq+v#tsUdOFiNH6B;ADO58odH&3O4;VPsFKqcc7P zC-n*Y!#L*^Vk%)d!5bHHJ$}&ggkx2t@og`f)6|S+M^C%P(;X@{z*9gb!lnUh2>|1s ztLQlep%7>BQlu;HZgn=*8t{=IkD&V$UreM5!amO{>0&m^dui!+pFtUA(e@Sh-(QePODEoBKSA`?Dbkz9X+!z8_RmT~u#b|X^V)AM{lgxf`I(DsKJnh)yIp^q3< z3l`6PTXmbW5r9)Dcb`o;}(tGxVzbLoWftb zx~)>$iLc&Mh(Ka zY^68tMO4310?uL z>_gEEjCegPB;zRIfTJXMc2Bg>HAlgbD8~1yp*+EU^rLs-rOuX%*b=Hees^6KngtXE za9K4faBUEbfU-bYNJ9j4fiH0V!_$ueB^smZ%%Q3oc3B^>XCnEMINKoBr&uSK=O7Ye^{>CxwdfNr7talO};Gv}{5# z`m;O!hx)KGUv;O5Q1u_M#*2G_SXTHWm3Ean3Rc-T6-}8l)(09tCu4yA6N@G zOZ<1K+hnHzaPqIANpm${pgbY7eP=<{WiR@`s*o?ifJA%LLA;%Mq>tv*=ZCH_k;;#jb)VoF%8ztDk%HMa3ayY9t0pm(lIVOIvh zJpXGh4czn6D}7%JK9&}6+f@jih;CFEMkLw&Py=BQjK z8UjQ&*0c6orT0cCRCS-_Zp;@IvivuR@>$jdXztMF^g$mPbWitSjKJcl8NHrBow@k8 z(wn_A6mWv};PIzPxH;9ZWMr(w(oIRLHI1u>&@f?Dp%t=wUPJC0ZYSnpxJ+dM*{1A5 zoUU7Fj7AeNa1~x@j&xnt!^7XcJ%iWJv8V!xr+kg4{!6ZZz}T}r%hQII&pyb$ z373M%W&jm--4or<8b9U)dKEdn;KxVHSBq5dXwtegO41(==u$+}Tl0HhEwkF?0gQ;s zM)1j*uqdR**uUIC{p+grzmDN0_P3O^po}uTLHX9@3w zSRgF|JAwA`8HNds3+vFvuxm_YLfPMr+@eHpg{tpFHz!B)0vyoZy|M1}_7Rb1AAX+J zjkBjo0z6CO@!Z8?OF$YCfDT8o9awh4_Wy~#+2Y&D_#`~nWq@jJBt4FjCo(d6!@ft z3b;1~97{k*@AphZmzvq*b`{4a{k8LrP|yo>%C429M9S3sKbFn~tOv9I|0~RBl`-*4 zg-K>gSgBMp=Frq^EUl>I*nvvun^HL?)|6^UQOn9G$~vfY_#&jyK_s1}oYD~;rqlm* z_x!Kxcm1B{!P2ho?|pv`@AvENfBJ)!xKs;$JM@HVda%WhmP&`ozIMwtBJUHhRYkW; zMK@;hrefdTq#<0;t>PY$UYn0$g?!rXK(InWUPX$RE@8Hng{MY{oG*)cMdQAqdjm9d z`LQsmbh$xlow;9zC3z^(iL?Hw_B^BdeBj@BpS7@q&NB zB*4c0MKy^?|KIxL?fLF5u>{BIbcR`Hi0i5J(~wxL=R^$|GE<_E)NbJycU8y?xskl5 zf{0i80=`cc5-1w~5dhfm{fp2brG}O8{hqb%)&e$}a#}_XfwRoqtoO5!%5yvIk9B@= z!|hLDpTc`we?2XP6)H&{t?Os7RP`K}vE(@5K)wIJb2Jjiibd#6d;C?Z&M08~o3oB- zGwl+S05{bumCbp(bB^F?NzykFocS`kboT~}M3Oim&cCS5wINMb=GUX6mqdp&2$l3> zqXRN+6A(0o)*BFse6_F9v$ej+?YK6bn~QAM7-_4KGtw%)lCRtG>9L)om*tWxFL_>4 zR>N?XH7Lr}^jFdwxX9;ks^(!N2Lk{nWaf3;lSFlOODr)_arPnOfI{oy3W< z^^uYr=4wAR*N++|k0J*e^P8+@`bQdKDKWm;)~XXhHhF)NZ>cFotHoA$YV${Q?Pe$1 z(1Q7Cdur~5z~&YdRn4i%+njaP)DL}#jc~gB_#wj4vuv3}h7&34d)&VxK;*fq-B&$L z*paV!)=0WO(R)ljU7X)1`xXjhL=2XwnJIVrSPo?VFroKz7QVPtKYpt59cm}>e`6yStc?nw12bz8*{0i&tf(PgMJ*6gR`7rP^_KY} z>Al@i;qu09F5INBfRg*VGD@A~!c7KOJBzO{3FCsreEpk5gLRxz9v` zn{%+zi7B&!)lex-dX_A!R_0fUPFYnh*cjd3$Wd7qRm_v9XWM7u$J4iT&aUPuTq$tX z##!ykNJ5=hKb=w2k|gQ7Bvd)%5N1A!a#n~yn4rCXim>Aj zLsoww{Rk^#*eYgK^RjnFnxf9jIdWL54nW#WH3P}>Qv2GP!7wep8R# zDCE1B#CZ{SzxEUR51a1qvY$6FY@F7o(>JNa?D$LV%FW6p&*Fir4cz!oBgzO}eLef4 z!eL4gxl6Bpm9X`b6EM)&ST~i->HmI-14NF7J)S6qK!9qRU(Se7CD!T z@eFxf_jgmR7U}I)GBwqpNI=`+tamG`tvRZM0a)mTz@>71idiBPq1I7;O zb7C^Cr?B>~omv||vnC5O;lpgQ1*TOUx2-`nLdPP3ohF{k#wawRt!+WOUhj7lxt@)x z@SVi3M+fWe8;SnC8Q&=bAj6!+oVhkA6$}JwlA8TR^5XlI=UxS_*Y6Txcit?KRy-b5eg3GFkk{lq1nwh&U3bFvi4_O6nu*0guE-DC+4Va;5jrEgdCvMZ7sIuWW> zAY|KT<*a9{S>8~%>rqNiml@6w^!2EkL7?c{{T$gFp_$vEC$7aZk*?v_YtD0y-=s00 zZvOjx&Rtqtd*n8`>h?&d*t&|GffsFqdi@16@*@kMck_q4?D`|86%O)+)qB64Ok0-Z z`ydQ8llvwr)}3)crn;eETAaQ~?zhiUk00!@u;RfUFh*UqCAP}Y>f5xgRa(9+w7TQKpu&4yFc4EclU*VW4eeTjQ`p0 z>tAJ!mQXfsRi#@}`Qo|iUomFQ8o$cUc_WtV9A?Ns7X2#6P95A_RF$}9Yv^yac=v?P zzF4VJWQP$F42n`7;-RyDdWu&S3Nq%ped~CR)-{;fkH`?9oB@eF$`5%dO zyT6_uAc&$PkPgMy9m=R4+xIN6GScQa>5Mo0v7n-9$?-YTBQO6xMr=g=TZdh7np~i! z%|K0M1i%$v^!`^Ls>*p8RNZ|~k0fP|kg8Wa^?G(;%K07U+@yXju=m1S9i(D8$;nDK zj;>%H=_g9YFE`kg#P{l(n*1$1&v^FGHG>C!vP@$zt?hsGNeWNRvf4qp>c^3$|4CE4 zfdHxD7cr{`mEv3Kbe~rlETw6`lHV=*|G~8A_Q*$;n+;_*-lwJ7(!SCpHPq+%12>=0 zv&W`=lhi8MCnnkEzG9tq%`K9()Jc!+uS361gjKN}NL4&HS;HYQa~c}pi^$Jy`1zh+ z`mXW^#ZpwAVi~_RY{7Wqo@WASEyi6>AlA#ggC_Q6hw6urluzBhJGy6IU{kHeZk=l- zgwI}Yd;Mlfs^bP;?Cm!57G%kfj`^_h%~IDY^S{3~W7hQg&AQ0XnG<)^3S}xXlpDRh zg2)YUfUuAw$hTRI&O3j}Y~t8M@u#h(KYt+H_P_qRXfcY8i^N>;0qmlu2|yRa0cY>yX!>8wd;U+s`vLj8_*m6?5h70 zRstF2KvPM5Th65>;AAnzS&$dnP&Y$2pRhOk<=s)O?r(jUok;gGvlmfYL+U36OY(c4 zr7QoF(eb;0v>Q+f2XwXFo#z$E1}bP5x8x0pB# zE&vMaMT=|L$ewK+-o?#50V(wC^3iSkV?Tpkme~1fM&47G#KxW>{pS_2sSjlRHGFRN zdaG@hrVNajvP5VDUZvaDU;~IsFg-fD?$$fq(PO6mzP}AB#{PjCR3!;;|5hlxcm1MB zdBU@gD_4}=XLWh6`*O?NkEg8a@p=rp7dO|jD#{Ph)ZrWYai&FCQWD&|tse>iweQwboJI^Kg`M2dqRzKW^ur7WO zYGrE3sZ(|ju|yA^@BXM!LF(~yw*Rd=P}_fK&%J+#7AfCy=G8m>g%_-bwyBAO?V`tb z^dWC{I3EP9yCeGNhfRCU(@G$-k8nS=ORpkkI`flv!)wBlfTroYbA|{R|MssC_z;Nh ztF|3Gx#7Qa;k%0z$%~WzwdcX>aT;#EYhO;hZn|HFD9@`^agbZf;$i+>7{-WGsF+1s z29e1o_LZ9o$o9_neQ>dKAR=Li6Ay)=XVwrOU?_;jZ^O!-9W#&c*smF}mJDNJ{`^nF z-zyfGsuT2=><5&CLOJ0OV$kv%iNi9dSptR@reaV};2iFaa<)^-7^BH%2$J~oavT^_ zosU}{0l}AKAUh(X>}8Acy)PP%FBU8t6#%}zyRyc7sW(Jmcz^cz)D87R@Ai5m$z$uz zT3t!{-KE?Gual8v>P|3gQ#o3%S9JV-+`6VIRhLDlH_z@|3>iWsb?dDSN8Y9xy(q{k zW6BA=yU9jHi<_}E`9H0mT~m7^-B;Z7@TF#_ipji{nr_CX#Gm z^_S6dtWB5k;7g#I29HI*YB}PdRdaZdWTPyA0I2~uzB&XXvvMa~KeRY&xnU|x&(=0O zT%pqfC>z2W1op275RZ4TDw|@)^pi=h;F-=Tc9gbw3rd*)^H!(y&flK0rN1C>fp~yV zw}f&3#ScW@E^i^mLa(FE*EpIIbevyhx40!4R@te!4u(UZZ1L`Ri3_?t#Wb~&i}_Y} zkCpl@SFT(+?bnffWkKc8{%8~j~3_;RX!sv zg(ue`sei-?bNi@_^>fFcX0QUIChmG!HSD7Y_!Mx)G>c^1HY4wn9+Krh`4;%!EldbR zrdP{W!p^RqbeD`;a&~x040pE{| zSDJrqKuJ`m{}r^S9$%ZqFk7*x&1P1vP9nr+D3C8FH55MG!+3mBLKbQdF;p*n8juWQ ziQZbN#m_z$H$21mc5NmI9b5GP??7O9D|w~wK)QuB#I z*ejFx7#V=jg99-pThCHG?+O->tF43DU^}B!u5A5N~`>1dtOQI{t=ac zQPowYKHHE+?kUGs2|i2j4NEGHjv}U3URO3&?}}b>MUoWOn!wRrWLx34G`cJNRi<9Q zA>ZV`S<`i_E~S?5Twgx7S(*wYg26gYd{$3wzdR(J1$#^c6M1nvj^aS~8w4)c<;P`7 zRa)L-9?NXhcJRkdo!Y*}r!hZ|n|#p9$5h%f|K4;ef#lNrtH=UKF2;7h^}-_y9jj#H zNW&i#&u`m$y5bfZD|+^x?#H)ywb`=kymV9RX~1a`X2|HZ%Oey%)pCJ?%HWlaV`Q;+gnn)&w4#YO4+L8xIiwxh8XD<9w$I-IUsd0XJL2!5sB-MD&VW^lB|8-l zUSjbMI5;}J?9hujA~>|6UNAF_iFD*5M>l$CW$%u8pOvnQvJBMC*xM(DM&6zihIDro zSe4($I5Uz#IsDp``U*X~*980W6O-?;GH=R`mMb`_C}GO83r{?E5I&xO*|&|u>cv`z zb|zn9e~X({P1LHjr;|mtyby4TUP`1_p(v*R%IJ8x{DAf0)G0G&_w7BA6$&%d*4+q^ z2_EAqh7~GupS_RS39JW}E@md+5lP6A5WKteS=Sf2t0-}3WmQ2>>iJ&*U)8?uDkgeo zzASJmrU4Z&s$ZR!^LNWSeZV-)j-)ozc7~QAJksuqAyBq9+|`q*t!5e@JkLl>^Egisdur}FACjZ+r> z5v&3g<1}+g5RcIn$sfbEBel2iS-N(+bfz>|v_@&C%dGmJ7k|{u9p!a@Wsk}B0pS1{ zFsd@7J7SNXYs^2sB`)H(3*YEOZgbWS7UNOGBa!r7SfS2$w`lv$CCoUwtimru2u6gz znbm5K)w~DMixqkM?&K=PzJn(*6L%~^@cQDdD4sH>HAy15_ z=OTV^7^e~ZFl^ndyZG*#wry)ZpHsf$&y4~Y@#h(Z%aeUP*>qC`zxn?>jfr38UR7dnU#H$#XA7wW%rnd1z1U+`$O z)qJAx@}P!a>HCDgpq9lyrI)9Vx3D+ zz@su=63Xo6B8G@%j5HyQy`Qq66c%1St0tHwM(+>LPD?zItiy~{d3jXr2=-04)YfL% zodb~5lRA0jxo5Wb6T8at1^@g20=lUla|9O}3QoxLm13wR^rir)@!Jivon0NoDHrKK z9iEH(#N(V$CB~SIdUqQ8u*|31*WOcX79@ukl>q)U$&Z-ezU+i0jzIK+{#3Hu`b}R( z2io*B3RQ}dxg1<7!aGgx16>WE-{bmUKY`UCpu_Z$QO$Xw4oZPk6Ep*;oz3yY#?YRqQCvV$R*l*K@ekn_MNyqs; z)B|Nt}ZaYT;V9%qe~c$8W>!mywiib zerw=gmQzlD-GL3c5bji=c~YxR=(nYzej#Gaq{9gT+Vkh_qKJeh9hhi5utdQ2T<>YR z@&IAnT;f&;qt*FOxSHC1>wXpkd65~r#?U1LtUtFP7p2P|e=W7_dh>(Pf)R%nJ-FJq z$axz98zcp}6CmEM|!|yxR(@t>j3A=^>CCo;Z zxuU+Nazs{rbF_jfm03{Z-Xd-=uMg@ypN7QsTAIj@X<>t~@M zVSjY)v*qXHi1sbJ=fEG@GOd`X;UU`)V=d%N=r%cQso}vm_95-;ZK)h6NbIUh0#)Yn z;raw$Z@PF^LdBbJk`J!y;nQoA zTzahGNIN$lM^!JGk<{pPmlqwqo~=a1sOGP8wYfa#=E$A8YW2=WsET=6c4Mbfi)5Fd zC8t8l#K@ltQJ_a)I)!)HJ;b!k%Df9KbiP=wPoKlc+$27yN4>6A6C+-)fJ4=4uXc#& z+vxhN_wgZ)B~feqKYSqvZ3jnP+ijkbhOXHsw(h3J0Mt_a&>s#}P#Ij>{BM}wEvKSm zId?q#9_scAp%l8%RH;ynQc~_3VaZ07G}gQ75!>Z-m4`yvav?+-(LqN&&;085QNl$( zk;C~jD@RLbQhn)EJT_Q+e@$?U+r*BboDd{p>l+t!i4$0-nuH_VK zTJpGxmWJe2bni#xu~1-_ll7IB<=!i=LWBPPY!p4Sw?K)j4mH4`9De~O$2K%vdm2T8 z7FNn!1G*vC@(Pm?N7~bF`1;o-*aX-%FZ_dI)}1Hjk3#A=~z*fX4*rafIK z_g3MHwq6zF?(oWW$?1(M89P_Fo|EHj-Zogs+*ZV{EDCU|(~0eIul0{D`BLw|j)uK_ z58=U^JH2_U;(13u)JqJU=9Azi;O7?9o4Ny(k|Ke%K`-vtl!Pk2W~ zhPPl-3n&GfelF$ouLg?8MtsU-Kx~Z`-N{IrV8%9eKGlP)NT#*)lLy^*2JHf&L!bX( zfBog|vhS*`JBs|{3a8)tk7o9#oRB!E4fA6#U}WuQkL^;p{m83Oj z#B%FJKC`4O`d*t-cNWpcge0EKC%cgXfV*f$L#7EsYDcC-L@d{H{U838+!nfHBGH}H`-s+skC-}dgN`((*rKI4UhC_^5NK7)JD)Y zxhKgRRSS;dg=;leFl|qb%B{L>Ajv)&U&p;WnAUn}8Y&C$JCV^TqDVM#ToQRs}rg*5C&bHpSG^0<9>{ z=E7L8eEhe1?@sMqtKp)f4sF@OX7iTtb|4Q)-sTweGEn<>amTi&>)b@FF9anC;mL`v z&2kJmTivza{4TCfTg?iKp-4;=1O0JP&$`jIT#SDpd7;kwT!zh#Sx{onvs0UbiKJ*| zJpUDPr9PQ1C(&td-m~`Q=(stJ5T@YnT^pVBdU)=YUi$m{OWi)|{6HeS!uMgHFnNFK z;QP}@gT-q$3?nICG3LOx0Y4yW7F^SgnK8eRr(!nz{;FkfIp{-0@6=jG5X0J<`!4MM zCfD%xh0#gRZb**=vZ~#(`nZA8OYZEAZ@}KTt+SbdP{KK`nJjdyAa8V$j#$u1Kn$~P zN_&o1gPwwymC4aYqv+jeD5=Lvxd$y`QMFmBm%ONrv56^Qeg;nch)kwxsInTRu(8&I2_2M{Zq7W3-|Rebm{P z1Eb~+jN9RsQ~cwmegoupc-J-M0FNW2zsa*p&B=H@6SjWi@2R;aUlB(c5drG4m?0Gr z*zpCY#q5*!y|QrGh|uGj6#~1@7K+pO#=Kt~)P86uR`WWzO4TD7J9W?H;JfzPQg#C8 zGt{t37HJgDU8npi2lG<~CID|Vyn_H)%e{TF~&)V=Ik-h5kHRwQDEAbn@6v@*r{Qp>PJWlv;E7jBS7kHHO+*3Ghr|_}BTIMuzl!G{sjj~;y5#{G?W4l< zN%a$rKK!x@1++Zj%lgSU~J^V?dQ{0M;Zww{_BY(2v!T-v@j_Fm>%{*h6FPsxW3tPXUD8^h28OL zu>$`0e|U-IhQOdN=!ZPnmz>@>BJBOU38v^W(EEzVo9)W}RvYG^>$1vPq%^$mqxV>I zi@M=)FR57@HfDT|@@ip#pL#t@NY!fc_9?a5O1!SXgBr=9H*LzPO*D-WKi(c{)!DkV zV^eeS)w|Sllnq?jhUc0F5D4LtmxYcmt=8p31PPPGK!UxST!mMUJFRW=ND0f$+QhaA z&Qo`8X1$4e{=IyM_tjSRNeyfH$k4VqFpn*Kikx)Vif1#0X1+06#)eFs7}Gyz2_dy} zu1eMzdF02w2{lKpTjZAPabFdz-ZPrnSr4-bj$ey{>G5}M!CD`$xH1aO4{K9fb@55t z{>0AFx68c!6l|KhR*BJlR(ZuVLu$goGFC!D$ZV)xuNU=5boYgR=OKZJ2RM0P>@qjx zB1lVmSN0wfSLL}21Br!;d^#tmOm4yCMiD@>bI_c<=~>NzQR+1ea6?C!CRRTG|(;mJK+b_`R|lMddxZ={(UTRuqe6tr?e`TR2(7Bm+uH0~m@UWOUV0W~VZC4P_sJl+=E?hFv$;C`kVtJ5V`&PG$Aa>;HV#>&DJp zSyM;n%+1&nD2^V^#KL|p0C@iB3vLhX{|cFhIImeyBJ%NlvSB~{fzUJo(JkISwf)vZ z5+j~&tXg#E>NK2oS5jf{#y^6JgLwIMBOOw@&ga0TCND8PJ3o~I^b?)=_Y4#OhJ^-51Y(D*F(VkhC+lQPnMWZ=A63nQB?$d9!YT0dBpx**@lJ_3+R! z@4Cp=nceC$>VDdtEISlW6oK*`&NdqJc>2%D5d@r=y8jddth%7}o}u+ScUY2>qUU^N zAr-Qvx?oD?@e#sNGCqoP6LDA!QFP9sW0R-J$q1dEb+pKED#oC`DFT9`hBk9X8G-rW9K5wgg(As zdhOV`la-<$?;y?O-js!Fww{_a>uSj;_@v56Lo{GMPX{1!OTPh2nGiQCs#kIMPE5?jR zDb(}Y=BNY(5+y}s({lH>MCvuxh%o?YHmzxjmO zciPxgQ!@8t-hATh_6nPH`&1X5sLG74oiDDC4%mtzuUTcbB*^##`8VG3B=q^5n6i$6 zR_D8hJB^-cm2Vd-NoFL3I{RY{w0I}bldD`+h>f7qf%trV6;kdgGu(AfiILXX#*+6l z@-ke`*Ywmp4R+C$?92<*eKq4*vWf%;FQ(3^Wh8}S{XKK5xEIsMmQD|^O%H-oLl&(Z zti+do(}p!?&<$*JT%GIo_iCrodvCrs9sWZ&jyDl-3W^BEEXAOc^ zUM%3{OfR><+ch$~X!K{p1NM*#-|M$2eR5oL{J|yI?GVO;3rR4yP8hL$6vj>NLx+jD zu=>X5y>^^O5<{U@;WY{cV?;~8Tqv$EAN^vx%)InNmtgl%6#|GdibYOT_d_Ai4}LJ~4u z5@3V4fC&qnvY;HioJd%#d0R9|Q~)B%VFXMB2X}Z34zF!u92^j)YX-@Z^@R3gw){?d z7Ta<>?%BuJXOwxfjVveW$-o4%uCr7njDDT==q2NO1*3a%6>4cQ$tsnv;NJwD zb;H4%!&`C2TfSbI*_>fzouLVyM_+!*^q7Pz@?{Q-_B+b_hnsce%O@SLX4&qjx_iX~ z?NrzMNVfo0ge?jPWG9{8RrOQodNP1s98dTiS>FB@y2Q33e?lPhKB$XHu)1fe-cZ~G zS9=-@^^Xa4+2;Kgr@YNUHU@)M_Mx~k#|^dM^}1VP*^}N`v{J(YO)uJ~Gq_5g*r8y$5I>9l9G1yIhhDp2 zm-)m+EVUFe{H;Y#mc0H$wRir#JDuZ^TI&AH`l)V9T<1uZ0l@Ay|C^v;tC96vQnDgB zI>P(A@#Fs9CL{A-9JgHP&_zaC$Ss+xe>>#Ilbtf%Bt_DYuHWc?;I#D%= z)l+7;xm{O6Ji;noY$Z8=G{wgB!wc1lujhm*7BO4uqcT%>O2wGunRYk9Isomc#4875 zuN*fn3L%fFHDYRH-LS$+M@w>J&1<4!*j#1-vPHVAC621Ud>OnCMw8gklMI=Awu|P! zqfzhpOqrXBo!*j!4A-dYk=Dy)mVEEHWQjkUDbe<@+V`oyKU7?@OBMT46d)}Fdh&Lp zGSZE)jocaMq3SqStpMJg_^z@ZuOkSo?B%lT#=ZZ^{Uc1u9o5HK@c&SkA4)P`VykXx zmO`u8I9%E2rj?_phj5?I$@tm?)Aq*j08xfoN*o03q2z^>4ZVA9fO?;j4}H>-|NDB; zwGW20^X3Yxa{M)@RwbOLs&Cq?#F?urGxwc4G|UY926V{j_Hbfw$_fV^&jJ&-7!*q$ zsejnC3Lm38X=bP-c1N+TVGcPIir{Tdca9M0Hnyq-;BK= zuNiP_fCH=pQbPPjvK>fak??^!RN!{!XzDx#_2)KDFKDLQm}`l< zvUi>PU*kSQ;*5gA0EHQoBc(+Fl6`ZtmZ$IAJsXS?f)U$-HV>^p>z#9z_{q0f{QX$Vwc&>*x5kgtVq6=}>g^Z5p^zpO!&BBXB`+!`WYrfe zR7JdOW@4aQTM)oWw4q~)Sz*&G){o*Z2pSRgOu5!SF)t@e0h&ooz$=fer;Fcct>5H% zZS@2U(`OV6+}@=%oT=41cdNECL+fQ`_3+r^+V%+;K_=nH=aKK}>bSXMJwB>gY5gZK zOaI8S2u*-p#hh@kqa+~L-sXYcKnfp2jAY|Uw=)z}8IghwTd6>5FVt;2MP z4WYhT3=ssLxvMr{_T4}YDjnmj#pSXHn$89(g$FTum*qa(-m>|=taHX(pVNWOsgb7V zo!d=kbb+o94OZHoZ3i#m+^mL#FK+HLhXaJP#w%j zQJPM+pSRh~2ao5?_4kGrtzzc2Hh~PDmGnbKfNfj$!Lmzkl>qK& zLHOihCWQd8JM+vXmhNpgVzRYGW1xb*PO5|_S1d5EOfg|uGc6$50oayURVNu3uT5tF z4nzi@ZmGTm6K@??nInfk;Y6)c$VJ`SqU?h)SXL^6Vhsxym(p`dzU)g!4+oOzs};4o6sT_KuG5v zO}?Zn+-`GCQ|p*T9t&zfNvtkR9h@p@Dw8A_cNjSi=QDP~Z@I=UA%!HSOPkRpDKqUX zM+zcxN(Yy=RkG=nrh*)qK8L}P$w73Zc#U%t>EiJ$qfh~`cwY>!1}OrDRsv796aSQS zv6ROC+tjkN7(vK8XU?fOZW}(&DW?~Bgg3c)8R#vfcAcyoX{(HxHAvQPL@v!J{OqMTjr1R-wfUyH+-%EYhCRYmc$NHTjk)nxh5ZMy2`9eoBGLGJnz z`TF~QGV3~Ro0qda%z9=e^Yq?h+&t@%$U~FSnjyq)E8Z6vuNTZk+k%*yr$L8&{GS+LxeFnb zGpJ+`XKI3a7nO?|4|#`Mw%-0k-O-aUB5CtrBxGtg6yCkQ+TmUEk_X}YV@HmrbYKLE zX-}DtOI^~b845OUo6(qbj;5Z-vBAkyo4D#C{&*}Wn@ip=?0U~cc%LC+d?_I2(UbBr zr3b~+n-GCKuJ?auhT|t$;>*USeb@l4_HEj_;6;LdQMbtDyQ#~ERq6^`Qdt$8v@9amgBSK&ZxXHr5FJ?~Y zn+O;CT2!QH@3_iP!OcJ2J`ufhC%j$a%s9E*G7_E07%LMib5)C|(QVC?la~3Gj%1H5 zxTGPkRd^B{SwH$CBeU1M^OCONXG#(WCfemW_p*dq+2hW~V&LBk9uv_sr_U#J?{vNe zI+BmSU71^H7BqLC$MB-jw73Ggc)T(RTG$3Wmy2;1XFwU5-MR`rTPi=75;49$>h3cJ z-r!;(k8s!DdqTD5=}woPR~i8#z@P`4OLv8s10Q_O?pTaFWd#Zbl2@m_l02q-jdZOR2byu6+Ir_kp$l%^x7YyVyr=Y9 zLM+gFoObV@x}I%xYK)d!(Z0@(Fo<$BZ;?ROT7S_QCf(JKYd?&TS7=>qbmX`@_%Z+5 z0_b{{#FMtjh`~LwlScAQ%4+bw>p!6Y>HaD9wl=NYK7$!~p$_lNRT`O5^zhl_=S-)9 z%me?_#7N*D9<cfsN8i<~c*BX+5KLLbzp54}?Y<4>pqfHkNMxKjGwsx~Zup@C zkL+3qQZlJmC*30%9N0KNOHB23AMnsgsZy1;Gg`8V?jqIUe%m-Z#GrA}AI$wy(cP!1 z74uo3=zQSIor#LM4b>I6XWSz}rKW#VbqaetUinHoeC9o$gc;7tz3_-R&>H7mpPu;Wc^we$LOjD8 z)@_Ji1Cs%7yP`-Bi}+zf=|CkJ2`&zVd~U=7&)vHi5fo{VkVASQfp1(RbId#(@x3TI zfr{{32M~Q;Oaz|)-3MEJt!L};kh@6@E!A#nJ`p}+Ci41-iLkGgRUc4bFg@v+PE?Fd z08N4VXK0S$5Mq`DSpcj3G&Y_9^%AWc4AUhZ^xP8U$xN=1q$}9`^~0)Q$Z`CDW4H~& zo~`pzu8Da`A2kF;6z&T4O0huUEMl?^b|#$0Z0B`FgJ@>VX&Fo%otuN`!caBa^f2(T zX(DOk-k7fCiu11%w)B8hP~Y8CbB)u=s=?ar>w2H>R?slsnd24 z58YrrAW-cTA3S&#+X8+lH0ODbNV$&xlPy0k`%3(JQ6O@HX^u`sB+Oq%rgN{BrXZ0a zrP4mgZ}hVq<{NIDKmc>_yj?T z-{;!(Y5mu77e4yN0pZgCZ4vNUekFbWLy%84^C@nH0&iR3&UGsZ676-#G}m3Tz)8$^ z!I?!`_1i=e7wu1q5#%ip93;9s7x~ELpT3qLpzZW9te)$u8A--C|HGB{WrWd@n7y59 zrtR5!EYwBADs=Fn>?_j}zlfU_j3m;v{A?67*}W>-^5rpN7wEX|wt>b}=UlNlFCBvF zm%dMNO^Ov$(iGm#U0KWZU1ENXxH2QY)GKLW(|i7N9~7k1`wX+V+4cyfCN$ZD1x-1} z@`20(^^#xzwd;YQY^UPu{xg`*UP1HWuvAFk4XQfd`Ovx9y89aNg?t@t-d@3_(dkZ| zl5N0-)WO}%8Ii~||Hcv=AO#&Sa%9-5f1K)_JKVJ6a(IyX-EMEhL}=eG42mE8Ab>8; zqfo(dzQoeJJJ2{k@bUgrR;jS+O+>Azof^^qOW8?D<|Trc{T$JGCVj9Qc;x+Ck}rj$ z>6ezg{^G|aR~PJ6#Fh!$oAf+sHSa44uHPQ)*HB2&Df;~PA_8p4gjDR9%{>0xprC=~ z;wL_KR&DBsZ*s+3J$Xr2;mI|A*plEhtSEZo z_H8ekrT)c$W>Rh#gp#zXN4raRhE!~;~+5xEJ%R?I^GhR{jvT1xr5 zZ!D_???d-&oc*6LUX*zf68|Jdj;NrY&fQZG1DvCPj(Mp=@e&Zm#G5SQ-6kNEcgIA&><|2vPK`QCs{Z+WbB{!0zZg{t zu)Mo2VT4FI;UUpWKw%ns0HJwHORKiGcee`rn{5#f~$ok?6(skNTeZuZGpCYKO2 z**)T}tQ*+z-OB-9WybB;;l((rU}32+W}e@K)L*1HFi4D@m$Ea zVE8`>sFn#4!8Lw|(TwzsHDzC_Hc+V^?I{dOo{>Gbv1|HO7MuVUihN3Xi5R@Tv3&V- zo#x!wd@-id@CZ*i&tK!4D5h4U610e7LTcI+Y5pd7+YzNr3CWKv{p6FlFF%(vQWg%> zEwN?hms2ZJ@|-oS&3 za#w^-5NgCA@BOr!8{YbkNvWW-c|6mEHKVAc#xN~EF-3V&URJ7>$5cm1+&?)>jidMR zO0!{B4p8p|AE?gjtgysWY@IPVHdGkf6dbj#om@4};_sTZ(LcSYQ+V}IZoOOM@%2nq zm^gKA!iUScsPj|dR=eTsNBcyVo6`2lqt{}dlzvo9pM1S%(3g9S^~$bk!a)QqRGtUY zpy0na4b{CS44txrbrL)GhSihxwn9|9^iK_zkvV&d6SAxF{AWBzV=0Uld(#76%}6-y zbwwWV!-LpzILdTuO>Q}lpUv`;y?*qaxy-AFuo6c%38CJSC7H047b=A<$?Qawl={&> zHt&t;TjrVk`>wLo>Kh?>)!6AQMqhja#@F#`pfs@Qh+Eh`9w*V@s9+ioXZ3I^pY?Sg z%zR6`buFb2<+{SQr!rw5!XeGK;3*uUerV!Zdt`T2W1vI5XCW7#lMbr6kJ%O}KTY-y z@7mOgb2f*$569%u-UOjb=GDX_j8DG*mvRcqcSIi%y3F>x5`F`JHJv|JxlK_Z>=?D% zZ7u$Y{1`bqLr9VtKWct>9IA*8S^(@SNxPpx^(ne^(YyPE91EOsig?>C>+?bA{nq@U zOSnJ;U7P|050r?!8N?E0^{p5hd>t3{@*J9_i;0Ei7qSjj5XNY}a{e!D@9EQm{rj&< zk1#Len{bk~nt6U8sytuqW3bW>Iw@CPG#~o{29XJugic{OZ~SU z+YYU8K#qB3nq@e*&)cGUH%A$7H_TvK8miUdSk(41z|{Aar-Tc3DM<}4OT-b8WPs>+ ztsYZqCU$D~xEdFO2gx-`|LcD4gcH+ZB>Bk>-UvKPa&lB!`V6BzMI2$DBRp-9$MHcN z+q?(SDvh^Au&}Iw5RWGyGF!!LJ1hOqb-w4TI+f}!rnF|a@>JKqT$Zqch2STpUZA!` zeM_PtkOW%{$yuC6mBzhLxv*t$k0aM0z$h>CgT790e5w7DFlILa>6_L;I>O;(dpLZ* zbIw{J>r)DAxSuPV9@8QX^5{rdSCV$@){_C*^rKH!9e3eqx;6eW)!9#>u}8^_zPu!s z$3ZEq<-QmH#C<>4c}N59X8oh@UaR`DF5y%^)2}pXfYx)Uwd1807Z{;e!gAlC@n~|k z?W;5~AY#KUBIJ<-)4rg}@WnS|m28y%5gjMo52>1~I8efu9>3x*(|GoMCaxDto%?LI z_1Sof8bF9UOW8d>wm@n0g9A{n(*(`1&av7zb_GxREd(Be=W&37N*pRUdD0!F2l+(Y z*YyCj90{6>{;}nia!^$TOaAaQ<#HtA`N3Dm;@_V?&k) z!U82KOIb6W@a6Ks^Mz)be+XgSoA`*7)Vhk~&0~vqEu|J77-xa?V>aiUaNC7S1T&`i z!)ZoffyEh5}%UM!ce8CK6HOM+SBINh7hKI&(Ss0LFF)mf;Wjsy~DOQvWWsYe3W zYh)D!v6)5i5klaf>EN63FM2%N|9Rn-CrZMhAfmC5F|ZKsnv`##<7gAJS7$F99b{nj z&BDDs9q&^tbrEgOF8T7Xqs?Ch-L~qT@7nwu-MU0@)o3P|7u_f2g${dv z!uV;T=A;Q3}4^}a%7SJ)WMaPjyf2GxHx&7V@2E=Q=F z5Y^AfJI&2`RN^uDY=qjj$B=G@pj+tCBmm^=@8_y*?zC<;toX3pz}R+2-_UO9iU&1_ z_l&%(e^lzPzmN8mY}{G$kNzvyhI83qk4LyJTJ10zZE;6qRPMSS+uQZ`y_CZEHAUCO zT~lgY&TrKGvG1R8PwFbW29&Pz0vu^Axr>(H{!Tjl?q?~j=L=8=Jb%)^mw1G^#iOLb z-klm+5{=Sty`v^bHwdlU2isTYo$;STla;GWNQPUCu#(p>joCSIalbW7{ec(vKc|rq zub3mKZ)Qos#Ckr-uw~M&ISP{ez&SD#IYZ)nCvW?nr+QvozY%Hmq2Dz#PN(ZPZp-K3 z>xA3BjIC=A^&6$}k_o;o%A+?`+vB&GE5Wd(t=6aOuB)d~y)dP( zIW*&q;S#MrkgVsP9-rl#{p(pR*F`$v`%!ex$SV{bg@jrAPgC(aE{t*ZlUvvGYR1K@ zH8xBQmBEA7Zk{cVM-AOPPjRNk6lDs?k)^DPjMsuI)-fvhbEffPOz}Dk$|*Kg9gS@_ zcaB~Z5E-PCSkkD+_HgtnTaQ76_mF9vvA;p!e06GujOlWPUn4R(e;@vPdhUwrqO~)e zt9nP*Mx8vWtMp;-M)`NO0h-@`7QO7P1ob_A&HIIaoei(`fBKN8BU*9(fC`QdFBSZJ z4x`yl_C6_|WBS{&)6$`?BU3Mmo|zKtRa$hd#$YBK#M}rwEXy6J@>^6w3 ztX>2@UCXFKw{*PB`i*X;PVxMGdhlMiG^jtL!xrIxlJf@(pixx?cbpJ(5~NluM3)E z?@A31Ty44_WqN^qZ(fKN#cVkkveQ7cRm^hlEo8=uNS?4{BF1npTU8dDdF#$09#O+8 zSAV*Q2eb71^mKmZwr$6zeAG-Gg5cGwKXTmicWT+G?G>wg4b4*mFMp`jxbA7?vSZud zX;ENl@%{?)F;1rEIN$KpEeteLw%X9)XCBu#-r65*v2fSkiBTK2*vP$o##L^uAsr36 zcJ>(YY0)9w8<;IIzpMJufD@p;50V^ z?UIZBWBgOf)V*2dF|I?o3FR@Y(Q_6&BIdIAMyG~54KJF8eKwIC6WLYG0 zA8FD$cB`C+T7lwVMOjV$!Mr`*(~cxN;J8SQN>~+ByX~Q{%6SB6y>_p=v35Y^`q>d0 z{;z5~(~l1c+|#mM{`kXVe4r$5qsI$rx_a;E7PWPBYJ3(f&+svLtZXjBcTLqR9WnIp z*V^|=WB=ceN4PG2=kSgSuWxL(pv;jFD|!T8zzWBGl4BtqYwzQ8?nzVH9sPM-)F$WKTDu zWOxkXefOhnxr4C?*QJ_>rw7l#jp#IsA9#-rrcLdH(3$6pS26Sy#wEP(DLvi5y(t|* zC^Zk3GDGdC#Et=`K1D2x`t~L)kPIHKVuf#-)Xt%=tEWgHDI~gX+mEzD73_b;hVS@# zLDqZ^rkuuiPgnR>TtvZn84jbFX8Op`uZ>RZ@vwG^4R=UUU8(U4Y#yRR2bA%?gFA#s zA~sAj&yHs^2^P;uN95`PDwC7Srom_hEAYdlga+XDTKl=D0qI`7;#FMyMBE@VyDewu@kK7{m?UphI?^=$ zsRUpLodlK#5q2$^(ZHQ2W}V(JUVODZRG`vfn(XuzeNfWo5_$Q@%G|wq*#$?v7ry;p zEKyYAtJ;ahf9)+kk6VL*q5HmFoDee;eWx}iN`Pl%t&y0tTbbaIcNDI5tU>hqUnCi( zGVm_lH_Wt2Gg=m3r6eya$A`g@(C3Xdmn%4KyGp8FlHGgj$yYj;zc<)3X8f_LQv=YG z(sFdKyvD6YdmT*@ZC72s!3V?tHFIo6hZ~VP6D?bC6v42^fJ|(OX0*!7_Yd_tCDMn? zaJGvKSZNx7VL{G#p=`2c{wLo~evNlh9M1Fnu&azPwapnk6ZgI2qwMGU0j}9z;03UT=3f{$8GJ|}bNyoGnWsFFG1t0I$OLIS;ql0dc{j)j zYe-006M|L`A#wwaSyC6{(6Tu&ai+DnD2(EM$Ib!x<}ewEe&6#w2gUW1wc(jkt+qmc zdQ|wrjYW^vey8zxHL11;|J=L>ho@9qvj2S3vh4`f<<<-1*2`$-R~F0Dx9466WT;N! zYgrvpUTx!S?v4OeiZH)LP*APS_ax^1_nFQ8d{&M8xQPBC6xvB%96ZiI8oHXME*~x} zylJQwt3VL`R}vDx@@k8HuDA2c)kf%cU>@_L*G?q>pz*eGIRlcCEwyHfhCXDx0_L@{4|$@e%Zt8xWbW*YSY?YF!Af5kDiSSrkx{GSR9R^x4& z_gCDPzBKPjlSDk=qt^ifv%#l|;BC-i9@iIFk5nq#eJZA=nrs$TXX3r(vW^_}=B5_A zQV{}6SwUl!UBDDSXjhvI`^0EPv1wQSGD3WsbPQY<>E?B&jadV8~ ze9Zu@kN&QYl_>y3dEt&^sZ-)g=MQs67)x&(hLy+c(YN)f-`go8RxrreFAT(YH;F6h zrpOc!<-E%`_K&9Q|FoOEPvzjp)#mwu8g3C(l;a=nolC!^Txw?HJNBqa^h&%LMDbbjT)B&#=uh6s3BAx?46FcTSZ#pv#)t^93>0 zy0X>IEq45TJ}y#iv_$nh=iGi9KjZ;|K%TVrFX~8$UD`cuqxZYwZ34koN0`A z?u4*1L~~UoX%r`GC^nhipLmE3@4W;yNlsS1di1E-Jvb^`vKOoz7wq!4oNZd=#t@rR zuH*KCEMVWFA$6n=l3H$wnsDjM$ic5*cbd+DkmLsmi8ej=@2{X-axHyKFrh_`I~9?o ziyod}1M@+wAFaC!Q60rVW?CYA7giC&2#oIDCHt%WiqJn27n(3$n(~c6FAZ9^* z-nb&|#kRTG1kok)&9;1xBrTT@{^{-6;r!v&=^ZclMxDA=;SN_?#o?uT z$jMryTd7uX^pzyv0Csnhfr;wVg9bGnj6XqfJw0nweErS3o+myHKm1@gdX;p>!$i~L zpN4(W%-=1>S@?==#00_Ps|89k6h&!zd)M`|S_|<#EvAsDOQ;$bF#B)W;_GSY?OIRq zu`?{~c6id}&x)pCsfV4TcT`}tFgzeB>tA2%DQ20*^gadVcpiMBz7K19IdB83xpr#K zwh-ZxB;H6Q!!7j?b3Y|JkqVRXP2|sUQ4P0+OlX`+SEOm$(9UpBjO;N6ODhXd%ZuaL zIc-Qv_ncTQc9YLeA=(6@6!%u&meqNS=3r?=%K1&a(E>y_=s(yZ-fK_ZdB4>lIxi+} zc3au|TU$^E0o9SalK>wEg8*aF&X#~rSXcNPijxc7I#w8mCX>4P^0LVB_S#h8H|pB* z$SsjtH=6?<&gCAQBTOKDMWY)doRTEURx>jbt>>Kk-{->f!ziW@AdH)9C zN8kLE$=`=z!sTLi#uELK zDfoVdBC|lOZSo_7)m(b4ea5u5t<~G-?ZG%xGf2!Hql5J}s@440mtSph#lX2r9sHMV)4*2{Rpv4>?+lp1?Y*f=R9DP2uBYsmxVi%jxuY2R1v zMuPKL^(0B+A5l3p3St*IB+SsQDd>*!UG%xz371R?l^ACh~Gvswl0uRzIpH9vA_iB!{t_#O59$hJCkblqV8;cu5rjk9Whr#=H09( z;FJL0oZm<9qX8-~-dn&LI^QsrZsI`@0vkbL$@ABkGSfs^Y_pSt&H zqi#zzL}&RFow0!io-ieIwLDQ@o`yEtB+usDFVGYy(I+(4aO0$EE_uC($9t^n= zRJXH)tftdNx$kLg4n`;K66Uz z_sEW0+blVbEn~cLmRU>~+xYkqWRia|n)R=<@>MDYlPk#lR(&Y2_xKY$*^gvR8Gr)A z?DcZDHmjmtn^eKQ8Mj?$oVb>P>l&k#(H0Q)ji;5c@$^FX ziC3CQ4i`m13k?QgUm69DQfGa&mp_Da?A5Qt^8=g@g#(w#j&pgTJL&P@nJNxrT`H%T zsbOGzM!kk;dlAeL$~XMO0u>cX5M*<_)$BtMm+}nCxN}?8Rq=03i#{nW9)O*J4dBo_ z&g+d&Dn|jg7oc^W>ySHCD?JEwX`&4QJzD-qt5e1HZz3{t1VGF8QKWJ+0fqAvdcBLs zKMScI$}Y0^(ECH*;D6|)27a--TC!z`oa!A`Ut6bPbJ9O- zJao&(99kV7_ym zs0{*@6?5Lxx}IaXHbg5!ou`38 zY@U!z?&xWt+3NS6KAwF?F4CB2UZ&nK_m85AK5(nohztvI=_02oQY$)!%hE{PnZ4&>7&i4o%Y)`7UFC}C}H zA;MF9inH?Uy}xjHabd37B2a<1nr@9EbV(4DZjO>Jz8WT3ThbC4CyH9I2@4z*{(Q|k z;=5hChUu4OcekK23XkDP3w=s(M6bcmRR!Kl1XT(N#UO*GuFD`*#k+0!K1JI0DUyNl zQtb36oQPb$Y?=G*%JPqsr(6ncxpDL{c8cDE$9wl0ls(>gInm~_6*+o?mSMsIZ9D(= zfNNgKR+e8{u2><^#GcV=CZJL+hiC)w(QI90Y&_qDH=1CrXURNrLR=}-ZH7M6wCfNJ zS*4$ZE>B;@PO_f->PY_5MY^hXu>Q$e#ztFqPb#Z#%K7@|zGsenh=>-_Kji~kvP{EX zNHf}=o@nf{@ho#<@p$zJ_3gyN3D0$6{rsr`IK&b%ZZDhEfA_xJ$6^euD3u0jY=}(a z8$hll?LYv87O3{(c~A1$7iV;WLt!v4+1321j{lZy9j?6emdr@>oQUheD-SI$l-co@8n0Kg-yn2drMywraYHOB`jhYMS}Lci>>M0J+RRxYl`0e^67nVlON``77p0l z_SIkLkpBx5730YEs82tNs&Od%I()-y6iWwv+afWTw9z5fD?A)%J}@35{WL|o`KJ8O z;Q&f~(^qzTWahb@pME#t(-w?9W^nt6|g9q1F;{`O3}n zA(IeYe3wX*!IXqtGQNC$bhPb{MqQnz4P*0W7(odEEYLNPm?l(*K%DqYW00t`opnjZ zOn7w2y5yi`(FL6_>(cgd`grVQ z*wrs&8bwz}3tz_Q23%&YcsKw*HENf*Q+NqzIqzc^*0%bZzHCGTa8A1?$z8VPu=%91 z=9ox4>oK4`j5M$A--@cQ4_UAmqd?Gq zvE@V&6B`hQnjPK|cCq)m5gM_jVV@;A@urK{9c{*@)8S`>Dy_?u5BU6%{WJs8u#s@uYg!h za3~K3Tmi^u-Q^YE6T+pI^$@jCU`bK?#HrV#Y%)ZR49_q*AIL#^;KaoZ2&nncsgy13 zW&6ZEsY2)M>=aTW+x}k`qHBBU6>1PQuCZl;x|vk?oe<53ed(`F=!-ek^HIFFY@V@wC3+$%-`C%T`;4k_KlF=_^VY(UUOFCsaipVge@!P`eHO3j&u4;qz(B5106$F93{u&gNTA0 zBBsTL=&IrT0Jf9!o!PNkKhWM`O7=We ze_a|@=CqLQuQiq!v5{jcR@g4C#7_6-(XwAR=2&nK77)^+hTX+1Seflf0E{Dl_Y2*( za|yBs-H->9>3Zl=*nFhsbyapw>kfUzmM$a}FOy3JKFO=rEus`e$Y#~nej|s?SR~yL zbC!aZb0m?5WH2!nEk!etoXFm7%fg~1-{ILJ=pw=K1R-To51SG}k&2tyMlO2d{dLGtg~fsG?on#>}=W7Jxojy)ODRhEK+#(xc=8O{0Rb(*86K@=u5-ej{^hN7i}~8 zCHLgE-3H=sUjzlZb$i?*AQMDAxHj)i%``UZ4zWLzX*n9d*F7m+!1{6v`LH-YmG<X(Z~UvFDOXyyyTnwVBV-13Krt+sALM z(MK4jpRf#*QWsHm)c^GJ*TFT?a=%@tf|Ftta}1MCDYbm}OP_w(->#{mbcU*}@%YL_ z!vUfaLA@iDvzAuSYB6SPh5K9^H7r>rzx@*Rm{gd^nH*%THEu$zDS6h96<|ekBUe<``p{F`<2iG z_bRRY6-|j<`dT;Q=h3tBmtw%B9bM*g!Dy@Xi()U~D8-94_+Zx8BVVlz3v}9Flk@mK7o0DUStA~{q)XFFOA{rXiE{%EG1b>u_YOXK_N5Jd8&nlc z7D`^V&iGo1i5Ev>goa1+?dyFX;C0yaL(-$R2cPR`w%fEaN|YB+mkDs-2x9M9U!aK& zSa;ilU_9*Y9vgd{VYY$w?>a)b)_bHHjdAf<7X!GXI84v)t@)#w6ytNlJ3WL`$KB@5 zqn7EF|E9?DRqaJ#FeSG2ftyv&lXn}m`W<%>WF&vsNq6&Y0s4va?R1=jv$@JR*}>-w974?J{RB`QshxJ=Fg>q zfLV0gA+#b`4u`7l?Zjm!rp|LlfrX-75GIF-vBSCppjYw8@ehW3O$x3Eio!_B>?9);YrsUbvm?l}Ex zNSTbgx<E1Vy?g?1L@A4m15HvZK5GhF12*V#oQDcK}w=~N;VtxG$p09+>WENcfu=l88KgRXwy5Z=Wd#4wq!h0(Z z)q4anR|c#1Abk^5NL7DnjH&mZr;&f&Bh}xBJR{#N`(-~~T|Y>?tUrG|GCW@*@4))l z#Gr|uigSq-lH}QQz0=QOR)Qa}e$qM8_xi&KE>xkn60@XM1|e^axmH>kFJ&HSN(q|; zKg5Z!Hg{vEouG=c!nksMB3ell>ipyHrIUak0dClwtC;Y%VxLeLbgYAncI(e=DD3wS z5epHAHb}#Oo&o;Sy2U?pe?i!c60tDi0v#-c3ujENm#F^p)hQI;*3GG(+3{W@X%c=i zb$pC~HcL5$`rm=_*S(hYbojT;D_Sb_NZ(+{$h!1KVL(c9CDjCSU6JvfTK76-=Ql;I zb%W8W{kWCZW1MqecJjkWQ+dkpqLFL<`R(1)j5*Z{GIya*<`B6yt0%UhoX@_5@ST{4KGtxy9nUjQvDT8Z9|iR!>S^G zxK^f%N0t_&qFnRNw;s8nyDUOBYk$)?$FS;op4++Db4tRZAAD}ghk_|#8vY#-Pe~!% zs1w0|GiYjC*NhlLe1@5$m!zQ>Og;^f(%oQ-m`_yvNzV+_E85eGfOsP1Yvd`6EmVO>JY)I{1V z)}*qHL1WS3Vf$V1`UQgEesjFJ0(gAll(IeMoWj{VsEX%X&YNpaFBJ;}M6rUL%W@#U zR5a|D!ka(I4?W0^z0jQ(m4aV>IDwM~gm6$R{tKCBx7>je7RYuGMvhjurT!51FL7fz zK;{gok#zUWp?}H;RKbPI*W;_G$o-GgLBCC9GSOKC)052N?-^*RU@;mcM_q}C-P7vw zLI*}&{JTQ+zQQ;nnHk}7rEd37Flf6Yx3IS^p^21gs)Spj$1W&1GRnrd?95oJm?ll< zy#}3CBp?-_wpmL$H<)JE<3D4-9*+XO=ZQt&zkW8B|whwrl4zjg~kv{nD;sYvs zbVLc1U<6u7;Yt2rfgtJabz`vNo+C|E>ANH#+enH@P5a#eT(SdxCa*$VJ1w%r>%?iH z=!_lPTLI`tpoq*Op+e!7L+80wZWE$4N8N>SUQnn4@ zB$^HzRhYY}NG0az>3QjjI?5##4T^!ax#}LwmdhML>}qW1WNw8cMi=7s!e6|n-1k|5 z-5Z4(tfoJ6r8$-iQ2Fe=pM*hz_n`*HD*2{qp>CJ{@fI(n?ST7(g@B)fFT_`L0onPX zOD%Sn4LJB*z}%_L7rIT)W+!{q9B$M$RN?`_IL<9!ZrYueE2Kt5t%^p>F+`l>(ka{E z8M4iNp0vbw`br?DJhV(BPd8h?X|8shEbVx@OC22xyCk$3J<7TU##SE$l$acv><=dl zNTux@cI0Wj!B@(@GZbexmFk1vW`W!^oa?(*u_hP@T-eri(tn#BG&9Do z2)PGh0~cu=Z96V5_xWDvN7AZnXlBEqR>(xrR3Uf3wt>~*OG1v&Wt2s^##MRtdTV|K zM-AFp^zFJRGGa%ts7(Ki9#$+z+>@`V5I}8#2z~ETqo6*(#~u~-AW~o*kRgj~1$cM9 z6DqU2?2??a_Z%wdnVo#k{c1zy)k_f#b;8h-yv;u`=D3xWrX*5GOUXn=3X1S{EZx0g zO{J=*hQ->YHkYwbY2DvwRD8z;0k4ul?RurI6&aBMEYzy6WuwSppK?jAhI|^RijsEB zS}+pmyY9rkerNkt?hC%u;x(KeE&IQ1Ii#a^Gcn@$eoM_NFWya2qb^nm@ATIgBhmvk zX2L)UN13$a-(1V6=kV$jZQHFR(`t9ev}G12mlBP@w@3#?gIM8&1vkO>dU)8MEAJ-L z`jd*RKJJ6R7ab7pjHADTyI;&-F#Ohd-MR>FN8w0Y}VX*B0uWx9*6G{b0SSEyZ%=2;Jemc>kc%80p)rplvZ50 zx5j5i>h3F+Rq3$T8ikmiCYKfKqCayRmsj;SFtYTOA7M0qw9WRfXgH1Z0I*1-=2 z$s%Y%(uk_uSTljd(e`GlWcg8qR|hR^Cy5=VFv($WK$u2doA7gsdqkc0LduW|#5ywm zNL>|k=)#oksvRYp11h>R20dF9L){rl@>{!wepne`kj4IA%2zTKxt$~uN@qDC7**iZ zm@b)9J6Y`sbl*e7@bK<`h#&ZNlVL_dN6OKD)Ff|@1ELBE4sSXadeEQ~%+SMhZNy*o zL3S=G7*((Q(@jV#m+A#tv5XDApfP(5d?Tde6X6OOnAcSK*z}_5#-E&$FLlj5;~p=X z{60%r<9_X@ri-a5tDo-;$4)-Rs)o=GPjK1+$rQEbzxrkaHWy7ZWtaleL8HrhZxZnw8>wh@v&qb!lq*qt?AFtcM z1!9#=EapCJetaEhQafqETkbt~zI(==S!B13s6y-0*PS36>-_;RNk!saZe22xSPZ_0 z?uB=b1Z&65(c^lkbyoM$^wrpW*tvZJZpE%r!3HrszI-w{yW*gRdjC}-p25zAJV$^% zspJL8{UVa@BG7FoiXhxgcW+`ensW7JnU#nZeK4`x#K)})AROE4@)FL%VB+4ZGjgpa z>O2+T5Ytt*mN3;CbT)OACKpDbW~B7@4>6K*>7J`PDF#c_l%sB6L^Uptm&CR^%wi&h zJ~Fg;at#LQr?1+*2hJ=t@~&bojMMdq;avyf3_^|j;Zki8GF-~1aUotvh~p7?wA{$L zmcM9a53WR1LQ&f{l|vT_riS5ToBy>a{uu1)frT#{$SvUf^_e1O1H{bb>p{Cd>xx;| zj1%>yf1bS&5r0aBSCLJ$}^zxu`0?$dmb#Z-F)5zH7|Y(7g4NSKKsavm?Mb^AUNhrzTp@07Pa zpc7?u``x&Eq)>TqS8l$K6b?BiPc?)(8NLKo@I!eUKkY}3w9SL(dmF2jCa?mQ)uX(}6XrV;c0i`@>H2v@ug%+|n_MGzt6L`6q zRSmc3HR00fk!;Z`n1D|7qgb8hG7(|J)OL<_pxerVC$ISeZ4!Z(V4n*~Zm}B>RL4Sh zv#=cgii?&i_Zm6O78^hf4_-doFi1%Sn{A8Tz*>dp#Hny3tTBal6WN^ykFAZe2K*@# z&h3A;<{DK*Q{tAeB}SA^3%xm33ip686{g#MJ#Tn&-;9v$5gq=VP71KJtdhKSab1ck zAdq(Yu%7AL#^+&@1&Ob54Ch3&};`A|6W3n!mvF{U5pS-!u&Z zq6VvtjF+F_vs|;ZU7-)^?@c=^(<)e{6WQ?!cI^}sj%Jyx&(v)P<-%-G-`d<>1~zFq zH!ES2B2ubXWw-1Fu}CwkNm(u|#6hwr?NV-z8n3{@Z;yX0X6i z^>I^(d`IN!vO~zSJtwp&;^!dQ&7G4&8q3GJ-ojhMa!SW-h2Zh#%ok-k^HmLQn=`#3 ziENjd>uUI32l-*I3g}zVVkk#Ij`*VHaMTYybo~+MZ=$L{bXmS`e)nlwoacMN1NJm~ zme)eMJbq-myW~&?5EB|s&f{=YnvudQ8<=RHDKtau*Q<7|@AO}QQFEmJVV+y~8>AoO zQ_;OWn?)GNZ?hImsYbZ_Y-7+nywnSRo7KHed4b=|sP4Hd(M}E)vz4^8dq38Q=;p7g^@C09)l0=>DG(ozR8eG(Ndq7 z8EZy;65%@Zfm?_KXg#}Yslid*uITelJGx>kuNG!p^r&kdUDT9YRbcP_Nfb%*=y~HW z@C~?rT_O6)=~N5fkH+|e%AI(aauj9^Y6hy-naMiNi@p(qBCreY(F%_aB$S}w!+rOU zH@O~@_koj1wbbR)x)a;D$Bt7Ry2!`uphfI~X3uBZbyrRBKfG}tuEWkg4|5h*q%b(V zYQwxeVxD+9$pVl}TbOKuecOu@%R-^C{24g{zAWYyl{y+@CJ50bFnHO8`_N15x^2f!9qBzf=eOF~R}bIVnAZBuu*3^m zxZpJ>KVmtJpBppe&c#TcfKrTad$OA>=ln;ohFm*hYfS@pIq#jVWyz_a-+3rlxzWxW zUASjZUtQbiuu-qvioADpo9^f+MF^x^p*E8T_stbDwq0)6Z7`-v!YdMdWHy5T@rI4O z5^oAsPTa6+$6%aMZg9Z|YY&T0$O#2&vVOskDlXvcZnNWMQFhFgeb(`*Wd}${6N~oi zlwN6TsyZG^ZRiltP?bjvO!!tocJBM^UqT__bLOjZU>@>?|IGM_L}Q8RT974MM82BN zTPs6?&qP?WfrV_l+^C57+jefsfA&c~{Wz+oYR^F67E94TMW7EniqUA?#Ds=P4 zkMT`P4@e8^AkP4e#I0eje(*Yz>Fg7P4KAAnSZ&-H6A7vOt%ChVcp2Ejbp)$NzIClD zt~I%1RD5>D8i7lTAYc1!U0VU4`ZY&Y=d?Pu#!eZq7`3Xnw9OLwpNp zlb~;Qe#;om7LfV7$-A8GG&Y>GxCKs576yAy2gJ1I1KZ@81 z+hfD}TkmBEIMOoKuY_-|081Y5W2byq3lP#1LB_odWAERO@sG7-h=6p`FP=l)5rmD* z-Hhjxwr5Tpx0A3Qiocdi?SJTbAxP8Wyu?&wybLaI&&(ANTxWYwaLZTq&h-Idqf#R_ z41Z^G?|E)4eq}t%2(+;R^CtaK5>+`tCC9qf|b=RAcQV_pAgClv|#28kH+M-{x z_uBG9;W-#aq366#{2V%h7@;c=`MwgpZ}*``v#36Nn;zPCGZ6wUJMMDyy&n<{Oz0U= zip&DkjN6EbK5qZJH1>c*4MhrcP@E}F8Rbf-aUgj!7C;L-qr%QYwABGsvIPZYrdc7% z4G~Q3dhbB9XilR_^65U|3TwwY){MZyF9^PF+1N&pHb%^E32Hq<7%K){P5ZmMtRL3+ zJ!#+6c2JY9C+ezrk44f3H>9zJ)EZ95J{W?CzUY4}r;)?sBla7%XgbfqlVhK)2 z%sNKEjz2;gs#h51Mamlxo_K$}M11Bg`#U5|arN9~8GFqlx-I^O&tt!u1x^kNkOSbxw7R}$^d>5b6wLzBMv*6En+Oy<&rc|MR}wOpj^1h`0e5$ zvgNv4!Wat;1exjMAI~5OD5#QgoH>Y3Y%>M^^fIcC%}aEs*CSM){-yq%T{8Nrvh%}t zEG!k|PCto2fe#f;S~moD`ot${^?!w#w~(iq7Q*R@A+No$mCDUTVtaZoJrn8eVl{En zBpb6yl_|kprfll)>icGk7!X)jW`b=Ot_KpK(mXTCTA(U_x%42>qSxe05}~~&G-LqO zJTESOg_zdtkr${Vc~K+NUT+N1u1!2smjnZ%J+(kSMZDA}H($p*h95z?xH`-H9&tkW zu4=2;kjCJzCA4LKYNTbTJQ*6B93j_b!}SW zi>t|@#s{X(Z2LgS)#^R-dknAPwoow_!l0Kq4X40r1qQNdv$UnaHVaJBkq%+PaISmm za1eV!8>-vK!Wn^$oy{0xuwu3FBr1R_HN%#f&r5W)iapF)_2#<$Rc8fII2i*` z0h+fgN*FO0n2YJMb@o*}W6(Ysp4yX+0aNO3IA{6v9Gi|rvrQ~JFg+;S`~$+c69us5 zQBx`NbWhwPB;61F){1pU=*KfOBF|<(rlBhc_p^I(M6p!?$K2!Ed_^Pth0@Qp$+Duy z$;6@CfNNIE@N$PEhd}rvlbqYkB07XM=Ym+|k1&@GiM=|?Ozsd+zT7Pyc!*YA6hE9n z^~JpWLPjc;e<*l^mluYMS$59WY`AhpQN-sG#P5F<#!(UYf-}oyi+GZKs$lrL5}<3%4T_K1obh=E3NTrRHsltCdZD7(8s!3Y~78LIp|t{i#DrB~C%uei>X zaD(`Eeff@pZ3V+~3$g+CFy%;>L#Rqa*QUVf60lATcVCN=0&oHlP3FO6^i< zN2Rul1`|%x#0+}9B_eD(K;zBG7 zA)j+9Ek`%pB`M8p^*+3_VCWUmkm_@A+q%3qh(QiZNCu(^4d0{&u!8OaaozygHi6Vs!{ z?|w4V!{wW|)qS*^Vh+FcUdQjz89ea=-@CwB@(q~Z9ZYD@oB-bp=0cAe75AJ_N_?>X zcOM%l?F$9-K(fVMm_6zE%9>xYUtHj6_HyV-)Jj;!{q|~|K6jpo`O7>CCEhLybi1v{ zWA%h27tAznGYBC_Yr%xK;mjF&du=Hn)0J3pV;RykrtP7o!AmV)@$N#W;J+2Ca?4WR z40@~1&7mpV&rL`*ymWv3Zj4H{W@Y z&*#Q6m}wItea;4C-a9D4-&HP3q2R&=)d;s^f*PnotMZDCEog>@2YO;TujQwx|xZ)gEKE+=P=Xhl;3irk?IBW&;`iUMDZN{O6YpD0ef@3AuYxprts|OT`v;ypBey zCvH_jXF*@e(TDE_zrShLFw5G+MueQ+CbHMT zI0G^<_&#k)mRo(VCR_UYNGnYSNOxlB^HbIb(f6&GdajQt&llpvFYPHy%}5cD>Vnn_ zQQ?00Y$7i7_1d1Q2}Ky6B+Nc-fx&ENUCr3DNyxC6EFT#l*?u&3B&0FI?iqw*dJCYCW2rN&!#l0L8yL|&W&HzJ*VG2=6ocFk-lS29vGVkYigCcLt_AmDX_06W{S1eC8- zE7@u~+r6rgMRb&+Gy^qaAQW(6)+MEFWzZ5(nnBC^`ag!K)N4!>N;MIF$%_tJ4HS=f z)~!aUcty04w_q;$BE*ZY*jh-7WUqe7USLyny}8Mp!5u{nb=yANI&k@-K+q}mVX&}d zd#ceb5WKX_$2h<=_r#n2*5PMqJ@ietkge5KawE(8!&(cI;{ZbCWFx(Z=y5B?*eEtJ z^?8ps8+zzeBXs4xclvt9aNXM1HD-_Y*WqaF zAb;bj?Y_=v!5nFdK*A}t=UWdy&wFzsCefzl#gABm2#w1yHu8OrMV83cAXsYAY1@lP z;+-dhBgKoZQ7wKx<3X@KLB#Y~JQ=LOpi_6(IC2V%V_!A7T{*3@CyX;StS&qjd}E2> z7N3qSd9FF-1rsz#1x!~pV%s6DZCSWMaJzH8B&JksGE3$xepKzi8uFsAMy@e%KJZ%C z^e^^)SMLzWzl*Et*7szO?sL7B-Cd*qw}S_Yp?Hn6?Ovs_{NrMj<9PX{vR$L2n5UrZ(l{Ck2CrQ>PW)SYS^g)+&}E8rI2IwEk2&;k_WktiU>04@fJV;6~F zc#BFgzR^7N>y zhdtt-g0O$8GjdCw^Zn4Y@_&dpd4*shU2}d|{OE7soAcr< zoiqBw$T=h+R6N&lppgO_GSTy{k>#^KkaW^|O=bgnsQ~X0H>%dB{DQ7&pT63}8eUgP z=rU*LdpP)Xs1HrE`AFCNjk841{er$`e#D9`M|3$eQ%_gK7vww7<5GO{Os>r70Gdm zhA$*P32w*RU1oLp;{WW{KHe$pXg7Yw4&gl&C%2lyVt*eIBO9e_2`k6-8294o0m3gt zGeWNxvHr=-0^$<>*R_VF+;hN*69}~Tr>yu@^oBoDj zargRsXjmNgdEiK4U?oo@7`4XTqk5S}7|O6j-jl+rV^qs!&ql^rHx?(_w3)uA40lV< zSiW>gB%x^WfzbqAzfL7Ve=J|D_sjAdOFGq}bqwGDHiASHf=9%-Ehup5iYU73)yBk0 zP+{ZGAGjWxoFIcRM2}H$)r^uAo7ap@om;Jt>^3Y0-UvFqakR;}XGAOF|Y(`2zh1cFht$5>hFNf}VtvvTz3tzxI z>jeoRF-XmKO+y)yfqcLn^}2*3QpH{~Buq9$4S#;Emo&mOL9iUD{?cdnEaIl)FLd{X zyU$JOxqtR4ddOgSD)rip;tic<*2DYZn}hoFgSHPnj=XQn!~8$!}(?UTX$@h}I#`^S>^Mvc$wq zb8xCGAFurS!o9`E$8?;FpjXsDBYNMW`V8D06Zw=me$Le)j{c*?}66>CiTSk>izi zt_06f^#dEtPh+Z#-N} znvX%rUei!X&5-0Q@ML?X%m%23`0*shvL8d#=ptFG6Ws*NB1aGIRREX%6ET8fHz5Lu zml&kGmt!u-bt@317a3+zUwm|;upbcWtWc)e1ziz1(GiiFRRZ(`)c9B3D#^kSL2R=@ z5xY@!LXm8FpGUWaA!Kxv`q^t({n7d>-&_&=YCH4e^9A=4 zAE3@f==BcL?K($0mB*XbveM+KOW)*1)s(X77|czs+>|?J;<~w6UuI0Vuv@E}{}mdi zZ5J|r`Uy=OVVbj2t4_|CgTt!^fd!bLyRHS^efgAo2VN2-uxO>IY+$bRYMn0*<1t_K zVIn%f`4C|lx;5qm_+=Q6)YAYBAKM@eep}rImUQObzn}{z6PspEmdc|2B6Mi~7}9{V z3>RQ?y;d>o{+*85ZeL{X-}uPWbNHVX+>|5Pz_sz$G@&g&NG$&@ft!0R8;3~U{*QeX zBCv(B#_`IWifEb7=bJTr5n(1wTYQF4po1*)CW^%6&JtPH?{U=x=tu0> zUo{OK5eKq<$Hn2@mIm?+4S{lZ_gJGSl|t^e*H-wnSCB0Qhln)6-=%D?j)0l$vAO%jXywMg%&sD+b)-X?X5 zB*HP5%c{04sJJ%E1P{ZvD^2EREr=#E$oKu^)i%fa?3BAi^yaQe+ENI`B7rT9*eqY7 zGc-OmrYfCwK@70NYC!o!?VN`o`uykC6BW&qY3a;=(|y03gl zEA(mLa9oYcH0~YTI&H=or6GqlYk1f=9@a)Axg}n8kmb7hi3YKvf21yY6p21ZeWw}i zyC+MlsJc_Q|*+7EMD9>g8@=Z7YcM4{?an1ZtA2pNEZA+ zle7N#5jx!fz@?8+@Sb-!Hd^qCysZt#CJ=VIb^Ymkh4PyT0~s?FzsR&#DU1{QyjsS% z=1hK(x$l=BpRPBE{Co9N*6v#XVAJuMJz@3vvHD@87BqkN>U|e9g9pcphqF83yL#^d zrJvJ|d1lZy@j|+G#0WV}sXsgp7KLsTBX38+=nNLMY?wRAZotOwNd8xEwT6x?D5}<9 zS2-?Cwg2c^ecNaAw!`>5B(xVzS|$A;ecwNHm^F_PU;v7dPv)*rPmlfT!I8^KBgWf* zMsfiuS?$hT#nH+=T$KMvBl;D)k=vXKAVQechiJ+|_WR_)k|mK4I1G40ePme>>Jo<@ z;#bEVe@a_3os#DT*)NU!zEWwN{?R%HV9d1Je@!!XIiNpCS+y!Gu4W5J1<`fTgWj?n~O05z2u#7LH}p;SN%cSl}F%=r7+6Y=&DuZiHA<4 z{5ySt5R+V2V4;BrBSQX#V)sGV87(?(!Fu4514oWQx=p9>M>H;%%|11y=6zMGMaDua zLZd`JKM5ur7mYMt%BM%8L@J7}#;rSVY9Az0&Xx2(1dw6nIBXUlkWBm9!BW-!=t%6j z`b1?fBK33H0eoNT|%d_^a(CO7#R{tan;i@6A2LLBA$5I5Xo^Si{ zYWf;ipMk~sEiYs`jT~1Y5lW>hEWDH4j>0N-p-HI41K;-_?UYpsRcNj_?UT2YS^Z!T^MBkvvJt`b+9`j7*p zBS1%z)?s5dB*L)RxnHpB40U|;lU*8}CudQuale-0xn<`O_)oV9&whA-kDH@#{0K_1 zLl;R<@+G3xG1esC&ANDhDCAHyVQXs^uWYT~KE&@fHDumU(?afD*7u;kCqa^-!XZ`A zz}deARR6HTR-#V;b>scm%CT`d2rVlkt`>$r>zG6=i?GGMer!^jyks%bhcX&xf8-&R8 z*@)G?TtY|Awc^9!XTLr9yl`I)MM+L`pA#b9^1@1O`Jx8|3fF?HB)_kcE0B+Izdip5(pr7^@7-bULpdb z4T#n&_t%z^A|SKAYVCrHq@j#J0b;Tcfn(evnD}J8TE4REC)XyyItRWXOQp7$AM zvn1h-UAK3b?{f~Adi$L>pRb?yQ_9!xSvkSp!PAjt5-Urb~ z3U{2S(3xBDNdRO*Bc9C#SP>SV5AcL}1V_0{#DZfb{%g0Ik?6G@mNzwlqRPHEfRSfXw;!>9n3W+3uDzNK- z&GG3E1LMk}BduP2W|#6d%}hUc;7o*T{1wTaI7Jhm8bjN^OZM6towADPbNctF?HMB0 z_;RVseIF8znkx8Q5ex}2F&{3~HQc26=27r7`?)LWC@HSf3eEaC1}-tJ?v%@`Ml%Mv z(Iku#x#$&Ee)2(9RgXc8aJICsChpAl`ASFadz&<^m6-US2A|I&FD-cs0c=k_Pqp=S z5bS$$o$JWdY1S(bN8{U`OgbCUyqe3RN6|{RpQOMV>@}zAhkZ9=WLx(0Y)jSTq-4wY z?o>qQii|%WR(}_^o(7u&`EZdYjt2vLoQz3Wa%5x_jgk)FBGSxiX+fb$oFt*YMI08t zI?q#gc|&y7u(+J>X0k`OD09k*cfdsc3SV=uemh6A{~9S%~7voT8x zw|D@O-{BqwT~T+Cu)7mb87vp+#$6 z7K4UMBJa4R27^xeA!N*~#I68XS$L`CYmT9Sa?;w%i9yew*5Qw%_664{K>#l1nW;?} z0~adN`e*OSZX_x~e)!k1AKXibT(GA!RNw7!$oilWNE66W8On?5jfXlHvc>H&#Vt7n zJzg^z3`hz}Mp$q#CM@Tk=93j?i0HpX$Q2VuLZC(|l(oUz7ZXRyN+<*ST$Mt1BOv{J1VdW#)J zL+n$?%eZa_+6iE(=*-Rfpk#THmfQMkJ%Y2Wu-9m)pP}P_+(=6`LVljQoVw~I1z&wW z<>Jb=Np8DJwv)6SV5Hp43w|n*{a{Xp4GcE8e+?0ymUPujUA<{HQ#-~B>Rejdf9 zMn|ahV|Yh2=_D9T4k2RF`s*{r#pizb%aHqc;YdNW%g`weNAp%mH5#7{Ys5>JqkkS! zPm^`Saf(rsbM@xqaohGco*EYS0d!>r)<%(*FZEN`j_dAJ5ZmjOgLoIAS|d5acy+YG zo>`R%pW=ZDFJ#&dyS(f)D6B18B$=R1-+7CO;pg~%IwkYz_nT1mc8TV@h~h*6U>bb$ zB>lWtnwA)CnZ816UOUg@Lq9_O3N&ic^_=4+1M}B@pAGk6Y2=K3P}AmpGD}E;Zn`Ek zXt)ZK90ENVFH0j(W2~^>SQEp9=tuHTwZW)mC;W$h_Ri;58vjV?>N{0ppK0^)I+N{h zos#=6=VGiaUGJ0iC*KD@KR$k=4CIrycPre?71Q57MP@N1ped^x)S1{_?f~}WD0TDI z=?a9@pmXO$!$UyZRO9R(cjz3ar}D}t zJKtFjc#wybox8FbM5&+-loH4^HaFsG9Ht`omu%Z-A|WI9+7*2IQP$;&6JAGAdw=&s z&z2@`TYC+|n>0JM{Nz>*>3zsn-vYE~*1sOh|b1U=vMK*@f2qn|pF$|`hf<*>J0Qes?;)<~<(bE}qrei}q( zpY5WXbt8W`N@DKKIsw9%J(w%>5$-6*ud-__NK_pnApc)^9nlXifF+VE(DmMt5yI(E zej|9uw_&o}Ds-Z6ARUfs`2}X2CXtebj^oACuk5dPNZ*`Pgs-Zbj2aG@;GhW00CcJV zE+J6De(~2c?W}P5u>_g`8Qz*w5WxV~_x88fJZz2iWys^)@#rILm z7|E9D(Z>)8?St15I!xJYzhYHq4(#D8m-(CIqr<+@`V`;bqf*)BPf=zpvPu0 zaM*O@Ik#;e%I2Bh;M!D(a-wAOJk)77gLhlKa=BbNBC7CLyg5UktakhNirBt=jGrzujy~pmRg;ilze##6ZOvi8L?ze z3G8th)1-kgIzGAM%G(okQ>oeTj@d$+y4=qwTx3Hwa8QdS>u+(&1FXRNe*xo61dmXa}O->jra z%a^9V#b;AFtQwsMVHdxbz$hkJa7#Zgc{gFdbaL?Dr!lH!_{OEG?GGcq(-SJ;r^E#J zV_`!;7kfYx+{hLuB*9sl;${E2@1B&vQ*r|^hfOM5d={0O;C1pK$H&pd)aj1Vp^HUI za_f3^U&*cal8A<3aIUAn$_J)9vj`hFU^%zxibIRfuG(F(CY_{dB}cGW2HW@z0uN1O z85no4L5Ta*z{#X_39r6ajTcG83dS2ODhWX0HMP9m+aFKygu!P5&lkguD=^|^Y zO(Xo=?5)|2af&?(p6^^R^UT{&JSZa5dSJ);YD6<34GS13VrwQxHgse7uqr~Zo+8@q9pw>Jn< z{IVM6j6y3p1e?=kXYqtUj8LxQUQT0?t-tI(y%71o=u0C-#>Fa$A%eBP3dQ%r4kU1c z+?Y@HN0mAh?Y(g{yXgOr?uFtDS6|J$P^%$SLf;v(E$`DXi%lbx6Y@CXrrOr{Ua0{VQWoP;*-(gX;#q_HHlctAsLb;PK3n#IS% z`0dR#zIRDfQRggVl*eZ_IGH@n(*R}4bE%2_pSrGud>&<&Y7yTJA`nK`aArfH-1P`* z_Z&m|8<1=Sz_)AL2UElww#eVg5%F$au5}J^EE=>ou?oG;JZg2z0!NKAycElv_6vDh z0umr(XGf#_%G(BBeL5v+i~gh^6~7!GQ*!3W$O97^d;k04>N?Gt8XM9*HlQ)LR#632 ztgOquJ@a7W#q>Gk3|TnW)mdn^6==2#@bkQ`Jv!W(KXTFvJTPge_pI;M^UjvU6hlno zxlU7Vw2tF;i;J!DT&Q>fDkH&dSf#}a`6kRPKM~{Usd4;d9K3-E9<?foOMBhpBmcftp`;I$~&3+65s9cEdVe@uMV{TjU* zWfc%Mx4+U~xDE+338>NL$1Tn*HE#X6sw0HDb_A*4jF=;a{G>km~&2RFuANTO*$r{f?L- z&vTeaGr51BpHNE1iw`~IrL}dsV><=9So~Dr@ybTh-e&p+N?fe{U0*SLSJXNXAdl28)1z< z;pFt0#kQ&)JKTW?u91?@%aha`Ra4qx*R_#zhBpUZiu`&{N{tMK`q1_m>@-v@0gmVS z-6$)QXfZUM;!(YmL}kKCLyK+T!>X^^9frFi@YZX0;KsB7 zix;k2(K3pdL@NWL(LIEQdiSI<6z>d;0|jN@7YYsUKP7r!91)Imas&CWh1pxXgrm2U zQ=4?4pCwyJGS15tHL}+M-N2h=T@&43V8D)*Z>vwl+L|R#8wyWZR)1-5^s(u0s>P7yRpR19ZM#BbL^e}vbF-fy zAR$Hv)p>FCo3?`#IPfb%r$%QFjKai2px<~UJPyt>WEu}lhuBJ@pCXSn$MOJF`LMA< zrLAS%;FxTwxomjeGtt|C5sZoT=&w5OQpqR-F>gKTf?xtL{HVkS0>+INGXg6|;B~Cj zvA8qg(Xz45uP#lqIAi%<=iT@t5r8soz2;Mr* z-F@?w&Fi!(-J+}hv8$jE;RihtO={Bd`D3<&$ z*?~OsagXwsqT)V_6jMT=-}YZaz;uF@8|=_eyi6|g7}E7zNNJ{=%?MmJ%52^SdWu(uTWChk((xx6bN!rkEbI1MQG!kn3hZ3-;e4g z8W6ZBIj;IMr+;5+iIuI6A}G4FCV8jIHr}-0i=Z83qZ<}#N}_Dnk|IRKQ@))!p7E{q z5ahB#&E2~ql>}14_fP?~p4a`Q5V-<5= zcDTYr8m0!H9G%;!7q3BtE~@TqShCfg8!k%%%A>1zjz3c8srlaf*ceDYj={3tzuVF4 z5FzE_|6*Vt5J=ZiJCb+#3UAP8#mRja=8NE7?V=0s7G?U+%s8a9j7Y^?MAB+HaBCOB&KoBZtKRlIWXYe@e3uf^{9kQJ-r5$Zfqqy!bRN) z-s0MvWm9P|JolDBy)B7!R?}p zFwL|5+$l_CzM_&=NWW1PQ7Q2i?Omj=Y0F>@Pv13p%JVLTs39f@xi0o`bBc0ls(8Ke zrn0$qeL6iP1iMLQiV8+)#W|t3X!abR8grgN6}xvz=?N2Ak&F{zUnfIp2P60)V*k*h z^_`;pfu@HZubgs^v@=2tG#0Ip@F{9RAPSJOpN~Za9G%Gul&+doW+#cS3!iy#W1nkI z`^Jef;nCUP8E&Y!ZCIr;tUJ3}cVqEKvHLb8>+YevUNuQjm2dU2p1HCr$sM%%TtzA> zEet5oj9!w}4Td>boZxGOO-KFrX}V)DP7xHmJ8rhi{PmTxf^URgR#(d?J8j3LQ~NUl zg-c?8)N-p9TRl7$TNS7u1RakvoYLA@XabEVoCWFB+9DjgH3-Jd9TwTxu3IF z>Obh&V-Hda?=Gz&wR}@GMfaq;(3`ZE@*b+-<5NYVbT?adBHnK?LPRi-qWvg^5}gO; zg9TDVtcYq95nNQV58!@pw7FbBOAE>A5aYlQ9eI1yVVmlITa(;pCXEvJr9mO6n1BF` z{sL%6+)?AW?Q(@!g1#^_r$*lCctiiX4`?qn;fD59|l|W)3c7S zEUYys5d$S7P?#Uve0DvE)Ir=0?&urA(E;%mkR!~|bLhLhAj5p~BB-P} z;^KuzifG%5Bekm^f~Dl_c~8T*%ksZmJU<97+(2@*X+7oGhRbrfbz#1CfOtDNB~63x+~$izpmd7 zHW00M#H(TaoP()#HXUT?;4y~#^gFEonw+BCt`H)RgP3Rt7Kv|;?C3Oj{wWPi#gS#* z_wDfx@Uws&#;*s@H^SHM?8!j3ELk9{2kBBzs49%Ju+P<*)~c`=Q+yXx3@b%|^!%r< zN9NnaEED!w9D4%{t*@`m|C0Q>Nq4TCiAn5!%NT@~r5YNK!^_y zVkYD!I?)GYtMu21efv9vh<*od>JM6PLr16((|6_kvCQ)oQR0K?Z*C7n?&E6p#o` zVD<)NFY8GISDVhye|jzJni_v-B~2s)3pVI0A*jw^QuxEI*JaYu2&%;&V0E) z)g!*Uo9e9XB2?bI0&fCfl=mrgse_TR3$d9^js)uq1Y^K3fUMdOUx&9f5X067T(rAx ze1^RRaIAoC`76W#4deyW9td&MR(KTb8VkX{X1NO3>Gr1!z1{))oj_dj{ui~MPXzf7 zzI+e?+Zf>72h&^Ki#@tPo-S78c?pPLAO;d*v2+F|aD>n05IEupBhF|Q+dC#!BC01O zz&8xu5Qp}B+L}-M5CbN_8ElKstzw)54x>RZd0TMH1hPTIrtU4!uzYz~hHSuUmw&vt z2E4YfbX)ip1IJ2`utQD@fO_o$YuW|uO%bgFKvys_05)&Oz&sfoZD;co-#(kV)}rV^ z*dt3Y1lvl`dIMf*k=3-&)&lL3+C6kvS&vjMBp&$Y)qOtciocH>T?&%-i(qou&PdEV zn=pPC2`-}oV`S@{%_f0ap160g^xLssX)7$kj!Bk1PXLSan2hTT{O00PYcIpjFtmk!}Bv{|-e0T(8IWSEdbOIY1 zSRrMcy%v9v1NIy6XfS+4?2Ut zB!MPD?GU(Kf}JGRO%&ME_Wla2Y5;zqT!SGt6_~37cYymYqTKYH*acvWa(nRsAvRpr zbsr4QXU?jfLzcbw4})<1J}i(C=f*cmp>-xIUuPrn--f`9(i_H72tbBJV2)W10T(|kLA2noJ=%7E=p4im zQOqvZg%t-9{wWZc1lyDHH2m&@0FrG3tI642h$F=X)g3-w?B}I>wC{i)&n7Q6aBH00 ztwvs6hL};ZlFx$R2&6|{opBWvAn*k7W2tBSTx)>`;sIW(Z#~Sg9tBf$$6CXuo+l5=+A+_A^W%!u)-VP`DDlq?E$ga30Q)3_4F+p)a1=`bW{LKz zhzT#U{Ca&o=1d?6z=1?F_v4`Lu7^!v`wQP4ls~c(dT)T<^b1Vv4JvBh3l0xTI#0mN z=X%4}V=K!Vy?YO5=ztz6wv0IW;L@(N-zC@*cVyRi^B|T|4OQkS(uTr(DI&Z8d0pp4hF0o^l@p#l4#5yYP`ISAoDotm7T+K;(4 z00R(&vxS-cxp5aL<<|s019&2$AJ2J&R0G)l!PbLN99nO70*OY#LOdxm5L2feZ?zo< zMcj0OL>l(qKpCVI`g_Q8h_tix-NE095X2V=tOGtA5YzE#&LgX>+JuK_AQ^POu(r|t zb2M9wn0>v?wShl8l1+$elkf|1n1o0qK7p`ed>U3kY9`&=2T1G?r=un%W{mlZ84i!oZo|2|0i$<9?qGa0WuKn+hyjkF$gh>vJDIn+}koA67M#BsV`yi+D4dcK=gs2F` zFJ;;<@B(~+8BouHknrtb6c~3Dze7elO<3E3KryJy^UK}2@lB8ID-cT}m{nn2fUvCq z&(*T7b0!wQ;s~M2K(%(nQ>Ov;-iSAuxcnE`KY`fOVtjsq(H!K-Z5umII~{{?6oqIo zD%s+GEPEU5K87Lc)Nl|gfOZLNbKSpzZVJ?$h_D^R2H=i46(hbCw2fV$vouCRl>%*h z!kyITS3op5hUol3{Uh@XA(J*gv-XnHoR}5(iu(6I)FPsk=s9wy8cm^3!FA zk8_`EZfQ=vFHM;BjBNAmgHzS?kyIp5MA6avZ{E)>MQqm%X$WlqkU_2kw?H3Vm>prC zbLcZ{WxV%5ctvoK0o^!=Z)AT1)eFQ2V<7&t+HVWM5@Uff<1#oFLUfLctJqF%UN5iI zZ}SAFG9S+sFM#gs<<|vzND!y^cKW#LTuC3;;^hH6Zb>yZtD2cw=w)j@*dE;lzP_zh zEOb?>l8LZ8@N$pTtTMIdkid1m}5aArVQGzYLEk~Q!>Wa7CC%rRd+NNB#x z20>(5#RU~R*u8KZzKQ?7qr~tLXv)DQLJtf3pqs$-dwPxwR6<}6?CSIJ^=k1l5e@%M zWIkkVkQo8G$6Q#L-aLzh_i0%07>Cfd~(wIrdP(}i8;6T3f!S3NB zw?%(Zzc%57Z<4ij_Fn>8$y^{uu=cDccgZxA;`n7 z=}_nOw=1LvQ&#~~;8E|+Ee(hd?gFhK2o}!z?I`e=De!0k;-b2k9gK@2E( zqR+NuIevK7>ASBdL+cuN<-i&eNdFM|A!2tSD}e|eA^6FRD4ancM})-yc1OpymK_&B z{LsL}9afm_uO45UwO2K$?g{Mz54QzQ;AwDLoHpL-xc-zZ1SW$B72uQ$l$Q(6JPFfwn_xkHb&mkyDkO0DGAPQ!ZCqWk0(6Z-VJMd`1 z6|i>KeAvIP8r;rspKg8LA}xw6C96S-uF`w2(iNOAjC3Ww{r)TAZZLSv}tV8uz9VVE=r}HBYfv~>J{yX0!xQ2r~(q}y~1ZqKm z2_Ye2aC;oADVE=}9R!$uKr~b2kqcXS;4JSwWai}FDV@AO9dwC60C=lGto*m3K*E=g zr6=e|k@Y1+4!yV(d~e0_GhStbjYe17ma=7b(`SGx18gpXR>K@$z;_<8*;t^+jPOQW zeLyvS2(~}3_kF61IRlH+^H1zmj{{jVEbu^0gYZhhA}o+aOu%-1Ie&bIvdNm?5DVQ3 z5E^!V+5uF4pos(>3uq#L%>^;z_@+GXYJ_(@8wvCIc|marVnaktqXSa!H^|Blp%etW z_vXe!pGle^GzSA@;35JKN~f}kFBR1iAn^e|Tkrq}HKQ5?*aPD?gukV^>+t&%ApF?~ z)|$x9{{64(jO?4i?*fT7{vKiTeE_ROWRH&M(UAaCpyhPm4Sc@fuJb+KF4$=RQ^Cwx zy+MeaGqw_Mf&4j89pfw5mz0<14UZ1|l;|H~j~Yd{Do z{15_!BP&ose{3=r*j^5R`z|O25y|~U7?KYzy9|=hKya_#Of2uoHlx*IT{2W~&j81cL71vDMVerU#L{kpwCM{^D0Ig};@ zDCx>JmM#Owoz6ThztRri+|s`X5gR84K@AUthQ15to;!< zI`ITtD1HN4K+s_JHh*|ontbAIlcQM~q_ibYF5J{!dZL<9ez?KbHM#6Un&D zjb^r|g@7Fm_c zUYks_HODCUdeY*GlXc#2h6%{1!EAMVqF`Cm8 zg*j2eLXirSk*R_A_P!e)ipM`$>y*%k{iD5n4<}_DRAAw9j%|Qf#>zGEes5TQ88;e1 z^pE;16hk}n$0sz84gY8sb4QtAT+84QF+qg|+G6vouq*k&IzL_9I(wA4u4%t0Y05AQ$S_`iX6<+wa?JcQ8bm-uppBH&Qg5oWB zbvW6}G3DOwp-wv#ys4vU;r=*itUq)9_+(AKVrOMPHb2qQO`!0gf)8`10KR86d4Kf! z4!5}4kSS8+JtO)je6YlyNCC*D6O=5B#IeE1;oEAE%{ZV$!h4I|B+zb2H?U#h*nh+B zkLqJ-@r>Y|siu9sl;sD{(R}tRD8XAo6&F4!@_msX|3CPwb>4sUOchaEXWCM3e05-w zBH5!`k3%_dr^P=sB-50SS3UP`oAls-$7*aCLw>nLb5-gY+Ze|G&@8H#Nq|wLr+WPB zY;m8R!&GpGq;C`aSX50o&Qs{KZ{c&={Hv4wt9}3HlRjOo551MiXSs9SNSG}neYfQI zF}h-IaRm%TOcD!iANQ)C_}FZyf1O^^aaGHQR&n+tzocwE2DVH|_;ZXxT!G29J)C0(YYPu-x+5!AlGuh9T!sh*E=CTE~e z=gWNIx?aQXQXx}3lVbyLpYY)@R04o!;}1gDcH9y{v~AfEp&;X#AS~LyLVhkm%`SD} zgLI(l0q?v2=wpPSP~<}2Qt7?HXxuI#uoLRKKG)1d1Ib12Ij8R5_$xca#m^1qc7 z6dk3l?xpBE+3cAKDm4cMNEU!`0S>S`u7Ez3C8-B8Ae!|lrMJc@VA2; zQ7O?ULZt!me!Igu1%$$b4kuk%Q=k&vMqfz#ep6psSnWLnPr1WMSw_EhFQk3HYh4gBDm#Y^=K!ca%3TDV)1Idwo>r35b_#4*bjgd4H6H z{I%M|%~jAagEcuddOZluw3h1FwTI=xA&nNap(x>BAXM}?bRQ0q9Uf=ZKUS>|k{33npjmx+l}AS88ZGOC z)?BEFl0PiidG%wf5tqUz?MW^JSyH2MY~`NIb9+qFK8%Rx*NjLy;bz(F^p}#6W@|#M zg2#=FbOR5J$l7i@k^a&-Oj_eyW!nS?|7^z=ma!spW=eneve2mLCA{f=c4ca~?uJM| z4-ShInY(xNf>3yckxQ=b>SX@o46>HqVojk?(f7!U|em8yKK!dqz@gog5``W;DMZs%EIaVx&KfdoZdeJ@T0b ze}}4t!0H3ut2nJaton#E+{(YR#|bT%z<@PdnGE;zXj#|!=t<(|$x+5BTt1(@&4c`p~*?ll$7t%Hu=GI+}h7Q zt;Rk>`fxiJE{2rEr~jDaUG$`@hoDqUs`i$vk?FQc>;whNG$V-PMgn-FPDA>JPHGBO`2Z;q^MvtRde$Kf*)iAo#u?Vf_1b41i=rMG zY@9jvG%#9RRM=a*BC`9bri{9V2aPB_DRqmFOYqLV*P^=7&nk5NBNOe?G)8;f+2h8y z$L>D1#t4LLxRP)0Pbze>;eBjuyII80ym7CVY4ov~{>Lbhh73c;HuGm3{Eh&{$9-MeZ#sO!L~l z7uuxcHL*)aA8~)UFS+|o7`I+}OC0xLG-lU9YTjtMHmTsW9-og9L6FiY>E~&Udz-e- z-6;*t2s|K|GHxK~7>^I05aK9Yr(!fl$4BD>6hCmJ3s{n>S-l1ur!UOeFl zwpjl#7v&cQiI$i>I~x0LQZPp|y&*T6=2EzaC59R^e>#__DaSD5C?yZ2U+%W9QQJVl zt>dV_ltY`+P1iquiYlV($Zu@Ad4X_#>|(>yq5jxe6(98mK~iwXIXt(jrgXZNvDEua zQ4U_^)QCpK&<6pA-SABn;t@?wHj=?hn365aYt*i@_`N5KibK#Wo3xtBN!8I1RcmO;cr-;gyJcDN9+se7 zQ_B198alx^EhdgNWVGU(kB!laIZ~sQuc-Yk4r%z-dgp0Y!WI@clYbA3RB2;Mq79i) zBeNR{@~*R-Uxd#%Rh>iSw;Ju!x=boKMKDf}>{fr=SJaj5uq=&kpiMXHo|rUU&Eeaa zmM)`WKhN!;@@vz&by>k%b@U)pjob#k3%U*ps`03@aMs6lLP^nTdM~c_mE>@dh6pN^ zU!?UYSHf6jYqoNC%&r$O4q*iizebVm{dGvf(d&4K*%NwR9yd7N@QM5!>|bwT)%8qq zUSz?(XCFg9$4?@=(-6gP9P6maa^+Z*tsR-iXD&er6dH*bn({Qh+ISo9o*p?!3s7~) z;q|laZ(`A{hO7lSxY1>Ro!oFF^_1o5Z_|f&dSFe z0hh2jx{^ifSJubh9ds-u$P9iX6MtuvtVTHc3XA{Oj@KOT6#MnFss{uh^T!JWei>E! z`rmr^sS1%-ISQ&_ibmYr-7h$N^0d7UmP@)cGyF_1$2)A;v1Cf0JB`k?w@X|9w6-h# zBGfxOcP?>R8qe$?Wq26>TUsSa)`>-W=5<-mNzg6>Z`LpMo7nN_3_4+3PbvK4tsqNiua}Hki7I5FJAbhRy9hR7FR#nRKeTh<^ym6c+IX~NvoA09{ zL!x5fr5%UT^RtB9#X<#HPK2Q|A}k{!}jyj zeSY>4-Tr8~fg}3UY5b|qfpjIY`nMB$-hlxso=?qZ*Vkd3hdOh@e2k8Sqh{snT&rEX zQ6fPB*o+VS9N~Ua_YNHOf>ZjXnSg#)kh5t#nselHE5|zuC!=cNeI=Ct{nuOmv)Gg) z`&op@l9U}X+TWFK%uUv&wm+|djMxv@gT0VMU zvnD!`#U#Glz|m_;b>?o<^=wRU5Rs8Ha;vx;Jg`9)J#H+M&!roEjhVbzws*%(2E)W* zl{Vv#zOP#JEWeeYOqXAN_+#hB;InBnp&30a7rEMfQ>OV(h4GHujDsYG+50M{O>(em z%zKi&E(iVPdYF%~1hHrz!!+$-h#%p|mJn)gRO}0STGg7U+kX1~(vZ8_`9-ugsZois zi<+E8&Fi!g9E@J^zI!8!)NVgBwX@XG`93+85*8Cl7 zR_C`G%e>(WGFm#)I&;`%CReg!%~}_ZaoTW0`BjeVt+)iu^yaq8Mvix-Y`#%LgzF@0 zG(=1y!~uItmXc>2yHnlWSc*+)&tKB5L1>(ktnjcfqXU*-CAiH&d-AqRYq$ZR1@nP zO-Cu}&+5hruZZl^lKL0~cP=pBtBC95X&I>IzAN$o zwWzdaO?k9?uH@|c(wx{D)lHYbEMwJa)Quba2sSG5SxW`231>;}aqf&)#@|Y#rfh57 z$-(d0px#OdnU1;=ixEliO#k8plfv~K?97JD7c~K!cKS+_lD9n>cZn70Y7iPNkc&*@ z5UB^mYc@oGe(7g=zCmpambnK-xm87;;qbPPwvklh^+*Ahhq+Qr(0*py`g$Eytm_N+ zNm?W<2?gf_Y=jRTqro1m9a6SlH(Wg(Bj$ z*fat*`juja05+y6H1-aNz(7ui64gh8SV#X3a&`w2b+&;t4pI?O&r%v(r&**$zk-|f z(b&xd6c5OXMsD8NE4r2dG9x7;kPxg%HJ(|JAH^Y8EI_tkaRs^m4&--w2j#*6$r+6z z2#JDZlmNMSVQibay*# z{fFomScV1saC)P_qB$rj%+mC)z`?=WNE92q);O2o|AB5#TUJYd0cX*Uh}2OcTz)gH zh9@3_rLau5!@;RgO%N2=kq?J;n`0Vyl5DY5meEQ$7(k; zche0CB)4c1G$08YoPga*F#ZrNPY|N%2V=S5prA%OV@u-^*pWj(rGZE~eZ*8v6l7hO zYonJE>fY~l!iKF;ln7sQ5t5^8A=x;EX0V*ri-ly8C?vDb!4K6Dgpw z74D9gg1h%R!W9}l4emB(!QCMR3Tg!T0i>|gNMW}{cec?up-5rXkWBeNH-Q8EL_bmT zk9qnbS{gYlC4BUTRK_vIxF@RDATxa*WHyo}kXUelvbNFaPvnbe{GvO(pdvfHpdwzo zj8w7jk&^2Kl>BLuqHw_tx%V-0??J2vHrNdkxsc~H3&mMk?7ig4`VpSJb+ZyT2fnGT=Wuueav55;(x35PqZP;SOAfP{`j~I73^RScR{lw;<6tc zc`5q0S4`44ql}6?>603^m3#Iy7uB1kH_!UAU1&@$yzX5lK0r0Ezg|i(UVX)@F%Mi5 zhaBX%t<9}~5*d~46`5?DJvGd%QK0gW0_>=yDF>(4$gPqp&g*XVwG-36XpS*FtwYMy z`N;V%a4cWRsSd5|on07ie49IlvqNy!<9c(-5EY$xQj-d@h`_>qeJ_2Os27hUnRqj9 zJ-gduN441~cRNA0jAC%|-6p>WGQ$+jyJ23}hz=rmF(op^sHKkS$?Hr`+#I_lK`fL< z8^6B);aCJo_kruc=?^F+zj*%$T<(PyszYQug;&j@@yhKjFQ;BzE_fS_O7A;3vYE+{ zJA^x}?TuPlW~^(_Q-5|@%hVQCLsT@W7~?-Nx0WzcG>y=n+i;kPiv}mmkx)h?~F)uD~HdDA?DnhSrXS`O>rO>k1{NxB`^81tqsfxN? zj(yw=CfjV-{BT6q`EiG{PiKC%m&!)jhJ!Qq#b!K{9HPc;3EfGU45ivyvK3&p-BEvdoIv*LR8G zp0Vr04j$etHktg3gJ#oBZ&@y`W-kUKHTNp#Ww8hveY~i{VZV*ZXs`VR3gw}_M{Z{J zZ9kH#L8bnoTrC?*OZ4b{jC19Vx{n6B%3f#8`B~3gLQr2N;sht|)P2;KGscApazAsl z)O?>I5r+y;VPe!paA(XLFWqqbaaL0RUNbQw%*Yu~d9)^j)i-7fki`HD52*v5%d7#T zVQ3jSYbpX@D*)vh3ZVOz@DDTY5bR3?gtj{aU?0~2ezQoOclo_2k}WmsgkvgS+(977 zL=Z^@fZ{U{ykY>p8tQ=Nzt6gw=pbYPFcVAxxF$3J2AkJO5c8iR7^E`(&xv^eN#%@J zcYdP+BzrKE!=2Sx0Lg8YSQ%BXsQ+`~Ilx_<5Hq>Q7I4>NOJ`6%8hB+)wn!3vCR+f^ z+s)gL&5^?Z%;a!@uO)yv(FNd}==!6K0K&&ax%PS)e*hsn=SWy`G!yWPpY-~QtG5L> zub~G0CQTjzI7b#-TODYC0XX-6tbbN7Lj-h(;bxzCwIb-oGmjpd6a;j$^XPJ#(&W)b z(@>34P;w757#U6gMT3o%`c6(#*;)U`BuaqFFcrg}P}YLLl2NG}@5@9`+AleL;Btqv zobe7KANrFTnF<&l%oj;d!Xc1mF#RpxkK6LI8ZlLrGnYGv0Qj>x+#Gi*g8#vSWbtif zEz7)zwMS(!#rx45RNJRB7RLu!OGv!zMSPPUsGYKLC>x-^RuBdN>!CAW!+1?JZ_ z=G|4%qYr9Y7G{yz-KT2%#e&ytq4twf4&=zxtQTpGYES31J1@@4TkM-SB_fDV&GC8_ z9N=82CRVZY-33dlNW8jQ-r|CsWD|mH<+vt9`#Yq91c?)j(DH)oPm_o82w}tJ>Z?A! z_vziC-gl{>-jH|fTzjeMEPt5He(P<$mF4+%^zg2fFEv@p^)eWVmU12SxqMyTFAA-U zt#gLaUXiZuX_Y{Iz}GmN1udM-FEFlXh4y5<#vAnOr8>TzMvf zY`I}+KeH0!%ElcisgX!)6RVK%>|kRmm#%+TuK)ARaCa#eV>q7=Q}oPo@Jk)XFW$E+ zho5)OhPkPEcXVZAFL#S%cM+QD9cL?w`B8J`EN-HyMdj2FTWF45QEY2yuHH9=Yq*h) z@?%{fG-QPo-n^#%51L?3*)Z@Pc3RS}h)`j;-DtgDZhl?;$;MfH2kS_iqc z(s=l+ndl!OYVmvcr-{k6+PbnIX_F``w0oJGns#L0ZNl4^U^?^%YL+VY{I@S~U$_T}()Wv>TInz9 zO#kuq7k7|~F=rGTmv(QtIz1u7%<2;Ps4G#%_H*RBP-2;yxPbgBU9YHkwE{lT4@>j+ z{)1+4RBFB%P9+l`X@{+d94)nC=xLRPN!G})1>B;KSg9MS3FKyRqrPSvqOyn@nTzqc zxQ2_naO>iNbWfzESJo?4`tPK8qr675;|*Ola1_=~hG3?})x^1eG!`uWh+SJ)7Tv_y zZe97x?Wk>2mf6=)&ZZhW1@VI=Y^&yYDd$&_x!ko(8SS0ee^A?&zZPRTPn6%+toQrD ziZu}(ug0?W-Np;@c?`7?5FaednzjQvqp zte^DN)z2{0Dv5M3@<;5PhwqV@+h<5*MXwTycD!8;FHg_0G=(_fwvC3{~e| z6rhbB?rp?qfy-NmB6750WQEYu4d&9k~M8GJ;xNYtFHo zrYuosOsA=0?l(^Nr5e*2WV4}EPsy9CVAFpxsW}&o&c&f*50tZc-t@>YGN07g-?1L# zP9WyU=)JID%W0?RD(L^hsGQD|9e$<8{s+T4QBlY{-L6R3B{H8hzulP14DEPn<(nYW zGLwjLXLIvOVD7LCon^>b-EK98{c_-9{~8>T%~LwwzbhvRxzQA9M{gsS=H;?djjT~?mBu{axZA7iO+F$RpvHXap%z)Pc*4g2!{oTZD zFUrs3Hy_hK%I9c}TBq3>IcVem%vr61Wl!9)_hbM$jNl$lTq^L(mz@6EiT5b z+i2fZjhJrvgZw$Cq8H|#GPndzRBSOtUS`SS4H1Af}rjjY( z&F--((Ulq7FJQV%nG3e2%^r;x0xWkOIQNu7SJfrk-GA3*wLG@_UdoR$`up}u-jd2m zk5?B^KapWMG5k`~Q0t(vinFM5tLdF#cFGZ|$Gv#lN^Dhb;sJKO{&P&nVU+?3A;bZn zQ6Cw64aazTkcf)mgN_^}!@ZeEj=jf3uNNZq(WZs#9J9uKpAosY%#!y0H-9Fo-KCOi z7>#5BfOm z2N^Tn@J13XJV_2}c0z;YMD8^#{qlV52;}r6f5k`&(|E^%73sz;HD~h@Dj$=g)p7)O zKn*q34g$j*3;Vu|1?Pat#NmAW6JgQGr{IC2{ zE!@qSYLjzrcNYIhCostjMYER5X+Ab8PlaKsdG{4Q@DYET7KZl>jM#}D;Z0-tx>ZG$ z8yi$(VB=$&d^h-;5EJcqkaWY{E|oNUQY7C)ed$O;8k^62`KH#WfE}JzT~XPtwW?#vIWNEQsY~VA-25LuqT2syy-mpUHWr z{k1tu_MWoKL4e)gkt{s5OZ3L7A7(5B0A8m89>Wj-2L2a+J}9p#ut@{(3i6$p>SeGH zEXQ=P)zu~Q`cwOj2eifg%zUVol}9RaFW*(mAF$%+bZT;=ugx)3f1DKnnO~DD!^%S7 zIhKxhvULG?TB)}Ta!s)k)pFGPFOael0IUJWOzABcK)IF4mJ&+&13PiRha-sD-$ioBpZR_aY{@>x+P#WN&WwvhzL_cbffzbv!z*lf9OzUZ%BQH}J67$LpF`WCKzxwy%Z zZ@17H-zKIi2@jcq^i4s>DdA!Iuu&UQZ9es$EfsvD%UG`V;$F-0ZgH!~qCO3(cLJY) zg4y2}qNnTl+IjO_mz=G@)}j~E_QX?~*Ez(AD*}7Na^nq9fwL0P@gpxSZf+^QjeDxE z$R7xXT&nh#Gm~fcQ<|pz1DvtHv*nW2j;pT@@{G#ixo%JV`th?Nx7p|6F-pt{>T1S8 zLG<*f<1V{~oqH(`deT(agwol*qISM>QyJzc?%~L+xAV z-o{i*#nrJ4CcjILvy@qE)}#G9oTcXkrKt5eC$T?WOCGib-L`UI3zhrWNSt}YWrZQ9 zJR;o7ji^E^vM+6Sw?V%riu@$xYj0)iNZ8T@?E~067sd1|XRTWLQSv1+UR1d_gi>j6e zq(3Gy6;vKDezsAcH?8EIE6>7AI!Q+1W=uXP#H91im1!9TI@qXtV~D5^1tn8$`?{JE zm>5#@+P=J>ZGd~El#15d9Fc~sPr?R*N1ThqTj-c>sc2rOZ>yQ!IXsu|`kSxn%bPdk zpIF=x7eRf|81Ns3=weGn8RJ1}o@tn>#ssE;9vwev$Z2y=kILU&`g}X3`W4}#{PO*BQ3Em*eCf6PrtN80+`GdybX-XkR z7TVo?8OAN|%}MnA*4x!+H$ka%p}Y`einO41=PR{>y@tV3y#C>qzi-CHO;cZJIOo?@ z%f~Iqcj}0GU|DCro@6gYIdjR>(U|@dMRJ(WA-HzjC91jfPuEk+uX4sc6_u5;j+1J3 zSEP`uM;i$dlE zxtub9re|AxjcZoWvPLP|35`4|vyoeezL?3U-bVlFmk&Uyd*peW0h} zh^hPfj%wAAvJHoyDl($D8|N5vH47+C_a%BR!p+}9p>}a8wUs;S+bTtw$-MeSZZ9ev zV}#gV7lz3K$HP38gUWxl0h|-~6Q(g-woToc5`tG-`$chDuU+N}gG`j`8XxQ8)NrR0 z>NlVr6Ra+Gw`dP9hWOuCwQ8MMfT3K!&uDdy{Y(g3CcnqQJTm-?RUW%DMiMXg7Z5sW}>`@WfXrFqmHEU zD)Yoyz29>mNxHBF`G-Z1GhCvTGu>Tgf`d`rge*x-KD2^eCPCqG%}-9tILh4GeKz0) zVI?@A7p*>186J{ljQW6a*~6T((xdS5D_`X$77=3uoHBp9$jM+ae#?0DWA*B&h?%Uq z%AHN(E=`f4>Y6%&r?RWoODb~__Q*S9i?}ZR>>QdXKa@$yEJ}QQ8r$UQpKsguiSq?IOv#*h3!kUS9s7W zu1g8OO&c$zF)7Qa#uND~Eo+j0x3!GljIwuis-vXdmY!o(rxm1du|?-pc*WIwzQv0x zM4%)jsocr8WL9l;&I*%_U=mS1z4gCDBq-m!aLX&9a{CnS74gW@OqbsFBkIC|RFdtR zb6FTatsi7cQV{So;+BkFa_6fLWj64?@{5R#MeAyk(>t$P3gcc~7^Bk6c_yB>(ESdZ zZ>u+yYtbO+i?Ov1IdJ0i*)o_Q+b0SrGit{%pW9a4RFcc=|CT))R4(Nf1zcViruK#l zKeR1085@baC`Q#|SsIbE>KN{Mu{ruTT;^!026wGDHR<@LyYjF_M&m?fju&`b?fN2U(Ny#>NTg|M(?hAIa>R$v}RCm;QWH;p{aF10qiJ%f)+0U%|%J7pE zz5jQ~PBz>ny#0abfN82rhi0c{HuxuuRiMgend*aAhd|jkSmoD6aSCK(d`!lvece9J zWuBF46<$>B+h>{NQ`-5Ch20WeMNF9{9X7s5rcKT6%d(+%qA(|En4&$jsh@eKr zBc1v37`-mX!M@VFRCL!FPut~!azlAOWJhbJ0$`Y&575K2n3SdJ^kHYE76hjK0O<|Y z0MiURfHd*0%2CuU0f2Pk$?dc0kq-d1)E{PL0yx=tm6KI|OxXww6W!SE4j@*ut$B3| zQ@MSb+FNj+w;$uTnTX-n^GXD;mk~t_sQ~st%~a+yi5!>SS5#-|Stf$-F{;jL+}Eq`igd+hS1Hvu?l6DfN6o2$&yO4BVgJJ#dPB$mwSAXu?gR0*Q}4bic0jnUdnIv zql^Xs<891-<1)<_1jbpC*c1UK0^6i~uSlwnIl$Hw$6yVajD-Mf`@#qtxV$0&JfZf&TvhS zx?CVN5@qa#2gDBmL|=sgVyQpOS_ufXLIYr%JpjKoD1fsi4>$j`RS6?+qabRi^r1N* z^0PGnG)Eoq+N=-oeP{=0&i`>%@7!B?E#qnZSz-=~4mQet_*qXsQ^w6LEOPUrqys`> z%7-%1Vh-CfaSoW}Om&~>zO2H-mB(*xeOXmhTUw{Dk}0C~+oV-`ll&R#M~6L5cZUeA zmg^a&j9jbN7WfkgU z(N?-Rm8D}NKl$#~dYhGtZInc(QkL?gItw<(Ha>QlYa_;sd!y!Mr@oLVVKUsYgAoTn z8jX6>;6G~{v@tpX)!7&D!{kCm8o8(_IWbP-z;&yzgJK90F@hmqQ_E`TjYY% z&%QlT&Iwb)Q&ITo&ake}{9R=p+n)3Y9O$j}-rLy5-%%3ebG6{q*~b=K>hRCb>>n%R z;QK;b39VL78IcusoiVwY`$&mo`@bex#&N0q#$qO)5O~w>vjqUZaqDmhzmVz{KMN z%l{thi@QNb^-1cHO%211R<+JoHs%>B%QZSGzyJE4i5}XhH+%A1Tz_BUY76G_`k(($ zR=31Odh*1*&I}V#<8jGz`9i8;GR}cB$?-T%xaIxsWz04(s06C#hSc0vP@uM znWBUFHNZfz&HmQ@v(V`Ua$|C{7bQ_PGce@f>5)L&+F}>n&|R%j`qa!Pzsm7!il^<0 z{M@L#yx3ska^b;{*1reQVtf%Q(kfbeG+X$~?796aPo!0J*)4za(r`b)`(br2Ul6{Mx>`>=w)?Atq{t%2IMB2Teaz z70zNV8rT+(9*dF=On$@&^$VKj^_96qI=2(YHgR5*hfgY$IlHXm!c@vMIW-<~5QA>U zk`WZa-S}&#S^U0>`_rtk-*0)Tfdo%mj8SEnrYz}w8`Hsdz9qI`UU~$hE*ClD-1y41 zBrkUQD%tU8@l>C&qx^z=E-Y1*l;MvV-TbCBw9Zr;N6DxP{&EeYX5_%&|QdixLbK+wQCuL7b z*!I82&?0!VrxX$QA9N>F?1J5Zb%0)K@znZ4mPBEm*hOs2X88I z5f&Gfvlyny^|DOIto7U#s^pR0d+NMAjeZ6SO-g54@}DbHlyUnXw@dEMeIy_nMqTuc zfAIOuSBmLy1nDN}J%?&GXNjHihPoOW5ymc9^28DI(RF;_2dt}FI2=UrUtEg#(#Yugy zOWQGla{X~rQ_eDazo(EedRt6(EUnNj4M2q)PY%ASTuhAT7A}=b`1J?xyEutErD`(E zrQ2$9jNQv4Wyy`RiEGx?+S$%TZ7ZEW&N!@Qz-uz*)&E5^2a=f`TtLa9Ld%%niDE4m;e%3PO2LDhs|`C%LWOhS<9o z^8*YmO1gQq4z;(yp}BEXeRq=flzvci+g#>8R6M56@;<+P7)V*gi37{bokbk91xFWs z;~(^dOp&P)xn_YB(HcxvymNnajmxF@EY$8+Q)NLLLmu4q9K!ozn{^V&>Mlz369|7r zTvO<^lo!VO)fSd9Hir)JiH7V>%8U;V&Aox8Ry&gTTxQZ!TsBICZ_DjP{q?`vM_cJR ztKi1}=}&!p#n5y&7Vn`lFCZA2A~u5^J3E0gy}a5uOqjsaF$+thl27c9HrD!yDjhqU z>iljd^yLWgi=XX3n2R5I(Tfcwk6gxRS}>#Wz2w32y^eZsdAwhzeZeN+SU4+EMMYj} zN9cewxQHOUREW#PU;pWBnW&SIT<|};vOy>UPmyUeU5z-6#qu!|^@Rr%Kkhnk7g&B` zteSj|h|kiTu3`zn1sUetB?4Xi2fhGP2jl3A8NGYPU$NopTQ~Qid|b4<`vOsw8RjZ8 z=;SvFleFClQme@*?fk?qWIdGgf$Z$U-reO z642lD8hJ3MsGSGuqN`|Yx=i%UX@Wn+wtZzEIyhfsHQJ-cdO+C6nP;UGYB-qgEw#~-Y6t0@ua8o{aN|AN-oy~8cdC?Sg?YPRpJ0&%q{ijho9dusL=-TB=wxFs` z$&`%yZn{)$oa#?093f;aFwXGH1c-f*#9Kf;c7sRMM1qW*(=R2-ihBuvB)idU_b?U8 zMQWhgLQ;+22lAxBi#v%8Us8ZP6S`*AmbBH_a^W2F%>=cOObsDXC-%D%uFoInHK*(N zER0h-@D+J78?)HyWD8pp7nSwu@nRT4KX#1f_XI%`_+&vb9#zp#5l^1_fx!BKBYMPd zdPIRgQjuHX7J?#>Vku@Y{P!ypxWm^PiATWmlO8;Ly;Mll;*QIC!DJ{7yttkye39%5 zy@OOSN0EQ`m23ZQPQk5{_|W&K)Hk>bQC!WxBP-cwa1MBkW**K5)h0wc$1e#A4clcd zFemC)HiJ_9B|@QwAD;bJMmeNfNWHtDodnvp!}-5>e*Q>8Zty!Xd#WJCV%fV2^%)>VD;5kK}Y$UTs9t`#FYtIoay58&;u0a{R?*A!7fAbq~{_ZNk}0# z3lYyY=n^W&W{F6<{K>!vC!-zh{2UAL3DtVi0^XQ=342eT{+P{J zFLYAd`E0+7FV=Sk(`Iw(KmjyCuP;#wv62hsD<(sZ?jK{ zTEbG;5-^gGEOC)Gb_fkTg;7dF7}i7l6Uv_XUBu!_?>>nf|y zZ~H9V<2+R%lqp(G6mY?XCfzeThyV(zj=Ysx*np&98qoKZTJz4?wea7loQ@O++?B z38@hJf9`vn+HId_pXb?qe&7FfeXnb-G3K88^tnHu_wn_9y}=GVQ1&QAK*oX{x~9Xi z417c=%VsVQIUx9)*yW3rdj*td7>pD8Vtn=n4^I$Opf;4-J-wZPz3{gjvrt zvYfUE(wrMWnXlFocKc%KdV{DdV;D5Y)5I@Kk;WE_S>YhkCQc`64@hErQ_Jp8q9PnK zcZ^{S%ZNC_tWwDMaBt7zwCz_`<>m~+lb@J6HBv3-ScY)kxQ)L-w_Guz-_c<(+4Hsk&q0sD$XRgPLfv13oCop(1W8zk9P|^%; zb=18zSHww}pH-dF4v*LzqnU-8*A@Xk3>?+Yhsi;tf9kKPtdLam%YFom#uPO6`h>tR z8$jii!9V;` znwOz&sO<2o2^*u4Q*l`QVXZ;*ixc>Zsh{#dxh2W%^BVj9i`=wwk%IWmqSG7_L}?^}qR zfhM7L8JFUaOLTXXiCJmF9)}8wbnas?G{vt*7`VzVnsb9PRGBHVM=W0oV9hWN$Sh0H zHrcQDP7{=HWUVnu|Jxymv(zLNzdUhhQC~>AxsNYn5=~NF7uWHNiZ6UYqL2{wzxS7?yUx*)!Q&sY{b2O^BJi8r;c^U(AJ_mYf`v@^#FNgo_*q(Cq)LwuMcB$pB$C z#l%=brvz-H0+xtjE3^wd_Az5XXt60wHLWMG3@d}JT7%&s*sQhtVn`5ic!c_-cu$m$ zX0tyBR3az09ctlS5t&p}Tr6T!%_wQOGMZ^hySo>zB<}&{)Ei^9f_G{K$B?P_q4|~A zDzMZBB)gTTiIUae`8w^~*)NWb(b>)|k9K+rGrNL=j^SSdOAlOPyL?oZ-Ouxa2&>HG zY&vA7xY#(FZ#3fvI2FGQUlZO5TUIYw3Bo%&K4MjIKV9v8eMil31p8`%{|(V{nSGZc zO#B792DbApOb>h8m;n}v^rM>pXvt)#QU0N>`C#+)>+o6ue$89h9br?a$M?jzIO$?z zsGjbb$YSwbMojwgzIb$u=KC-;;uTWU;TRM_0gKOe zlJS{6Fg4((<77LD&ZrgX`B1$t+C)UD51M_P24GhV5h5aABtLtw%L*KoXjI~eEDAfZ zUm~$KPwJQ7ii-(+A28e-b!b#fNS<{>67&>smb*@9#yV3*ALrA$c8zs&fJgFwYsMEI zcVzhg*Q}X5xsUkt^o#jBJ^hoC2dMcxe7D=cV3Zk5ZJe;Ci>(=9=p)1v{t{&axN1aJ znwveKUP;*Xp`iuLH0TS>2XpGgY|ZcNG^hpeuMlV=%P;UZ`~Pn>)RJy{ci_f-REKHW z)5pDUd-Xisg83Q`EUEEY{Uo+{$yPXP=Na+GSz-#egV~lwb3D_$mb)PCJoqX zQ?Vk627IkqL;41gVCRIxz$29*#;CiRfb)m8JaE=Fq1a!FUc5FOp{gAqrteE76qK8DXfpS~V7>s%b|EQW2gkr}^+c6`jvR};#3qLtgp zN7LO~JPd=V`El+c3E^gA^oZkL%elkq(}#wH7)9tao9cpx$}97sSu>7p%Uy*(s^<+@ zly3hu%L$M*iEOv)Nr07E{pN?}7l?s z?oA~tnVpV*<`#Y6NnOXVzKyb^C}0MBoyA}sWtS}fK}y2xZ5!!=MELS;Sp*gmbxUkL zR0J%{t4#3pml8*w&s*uLCTKwe%qGrXqz!C2$7{c|WBi96i@v3BuXDky=uW>bfqHm* zeLs`MKW~PX#6YxQ-3Y<9;ONeFVD<67xiZEqq#5U-BD>6k2ZweoIhJZWjtY31xP4}^ zOlaL*OTWmbUX*)yfl#|*S2v9g!hnNJ;0nQ%>`lu7)s0!%nju8B0}?LzAx$J0mJtiP z>ZxTTqN%F_8w2mvB%FaY5S=02q3}UiB1Guv2I69DQ9uH$C^#aqV3mOQ89v$tum$Z# z!eK_hczdUa7)ZYfURYSPcE`8?>Lvm??+bAL*TC0x-p@{^;`=m8dz4kV zlUpfEtgql=5$);eA6?h9C%Gm{2Q^sr5KiFVEbC1VSG3oqMBnmL8$QOC;cLWt6Gx(Y zs4Clm>(-`9`U?y?=tH&ip-pzixD+yB56s1k)0ft?>@1JCwO157z6=M<{=xP?h%J|8 zxjcZqS76Nn=N0%wDDNyvcqi=d5>Km-L$Db29?W!cA*NDW`Heulf?z154ubrjH(RM} zZJCX7Hd{eCBNTgEU}&5>xs2ft!YXip%)ND@28hTxws`PCSX?CA0*;CgNJKPGVqAWA z8E3ak%4%L1wi_SEQfNDtGpm*oTWvGe)ZE@06*+iD3G2Ca2t7>x`UHKGvlJYmV2Apf zqJT%{1dR5`%5$DsDJahSPx($MQFR(N;|2fAv^d^et}vl6LuM z{>E*|e6T>G1x^Wyi?twYG7T@&8)$yjf9TjBP^8PUP``KWM-y z_P!K0G$<>qN5J$WvMU7Six(+69}TdvQHV@S{P!0KTj_RDYMx1|c^-(9VX}uzXyyjto!v?d^4D!@kikbZ4F@b~VCw>9fHB$v5;HMjK9@gX zj5b?Z0mecT3iUz7Vax{x5$FsNQ@Ts~(ytasOnEMT1ri*vHx8CM5|)~`ivS;e>5b{o zT6mM_M{qLnu?=lD}UakLijO@{hEF9-cPmJqpb6x0M}8QG(Muogy}K*agO z^rWo!p{drGiGYt~ShSKep6DEaWffQwKvaPaFDz~|vGgUJIb+);Fj*8AK*{&kSx1LJ zz4SLFSR`z;Xvg`+Q5ILX`TIO$C;8C4`X8U0OR^}S`0g7d)W3ex_FQGsI#6G{jP2gf zkxN30T1}ii#RtKNZQYDxgU2Xz^t_Sae=~=HBkS(~d9y%gG*+i5Bw%@eLCHL zwNaGWqwPM%{qlvO;9EX#$Ai`aOF&~2cHSmDC`q;*l`JiTWrap z1W54xf;ynq)dRB%%xnn@5C~EG0Htu8TQn`K?0O1J&Bo{K$=caOmSaVSM>xGZ@awjR za7y+|Uf3YW_OXE-sRtZ}UcWJs5(N??N*zg6{b6EO7#gAkLdG_>seCa>_()nkS4l2# z@&mp@t**t>FaQm?*0^>VMl#u`%oP<4Mt4>1+8&vM3jXJr5%`L z-11PUti*6tNBa_(Wu{f3JLYt#goSA?zi^oFg?AJ;?DDkP+t$$A3YIGWCpi93a3H43 z|6aktigF(d|FQD+kq4((o@>WhZVVwKHcx+p;Cblf$0b+lj8ad>MVSD5Bc*R+k=U0p z1{g?nHDLDD*=q0?*x>5Sj|dJX>36UvkzLUV{ei*JDf97!gH`$ebLaHLU|LnMv-Amm z*joP!Q&y}+dwUQ1k6~wx@0x;D(|Rg;s9M@un$Rbge|zgte|q7^jPIrxebziwN4lLp zcwSq)UW1Ewl!VA|Vw-d;Z|(4402^ezEPzf4zh#ih zxUj!#CIfa^Z_J8tssPz`y?H|fNu%#***rD*9w>zch>@wi+T}I<-HE@vhA-%5N0!d{|>Z|kvOzwqRE&)zxW7P zTLsohY~xc^n+^SxPsHv!x+7fm#y^2lh4Cz}v`^8GZp*_kC$nbqN*~6T{?{SpWA7ogER%umBUoF_{o(xU7Ey=iZpI;M!I|g)WLWc~o zGL{A!ZpIv4`do_!^ehs~`K_fP%&*q&tJPQthzVTityrxlaK5?^k}aJ36k+jA$+bAp zhE8NP9MWpt9Q@=1_~eWiPb~B6!cW&4+?$IHKNp!MgrgsG*3Y?y9}_{q01O7;^nlUv zhrYUgYEDE3$Xl9Fm=O6QfYoG$kuF@CMdD?Jp`4zI8W>tE1sQZ(b5@@iC5}%y&1ccX8mH^LzFOpVp z+$>Kh0HL`Q+XO|sV_l21rDsIWMrRpx2f&)lLU7!{P?wg2h6@N-KO^6F7Q+WI=w`Y`{y4x?apZz7iy(LDIlJ(bs=F^J!ZO3yGOsj#$3MXclzOUdA3$UV zsw8YHh;D<$_?zs`-?sQVL5Aruz$zSc-b|QJj4WDxOXQ zhcTL`I>gZ8bkA*BRiqqStbo^=_lmCSPpPtr7Q4P>V5VG0VQ>I5L#RF87L=1hA>UVw^LohJN%^>ei{FUc>++UnJ-F{b$zVU!c z!3|O^yy2WH08AopsrH(qn}SEnkgsQUT!5ZTtSiXe2IGt8UJHQ608JHUG{2)(vK9K% zwo0%rlaJk)-{HgmG+Sb5y;D98FivFdwE(-X-aAF=cnY?Z9MS{n-)^KoXm*AO@3Zlm zC|tmL)*?a~X(wy}nw|sAUcxFa3vzJy@t5odE#@jMVi%1u;xqfG>m*=x=644V-X8 zE*UmjLchrYAT7`&g&5)90(|HJq_MB&>J&xi+DQ=ehH=GSD9#v+_8BIX2XChIM$Sjl z0unDfYGKgPfgRXcwBOsXmmt&jzCQTy^NATb$li=wDRw$?&Kg?qG(Qk~$VGjyQ8<_Z zpqJ!s&}Y?H3Kd)sJ@fS5KMa$;hG5qKHE#tD?PQgHKOq!P#TW}pqX zQUy(MwunRUt`t<6Ozgx~3tcFnKT(D72!FM)X#sT^zFV_@-*6Hp| z$q2A-;|v}%1~d%ce$i<)lLK&6s+vvep)@gL5a7+hsY~Ta_7#x-7q=ePjgc4?s`$d4 ze9`*I`T+L}>_&UIA=FHV_~-1kIJ1s_tBp7e37SKRfl(D<4*!h?#0c)&LO~z>WP|1; z+;9r1b%47jYk~gnYO3Qtd2F~@{AZws14x9&5pZa-)%i*xEtx|Og;p* zp9TU4DU?7CqXp*FSfZdK%Z2#BR?{cY47p5j{P`C^CHlDoREVcVJDm7?0OJWW+U_YV zMce)5g&a0k+G#PA@1Ki9Idz!WBQ&`2qt+zC%pkv>`X=RB09%s-eM)drs z*_{r+=WyZ0@2&2{=F;*Hfq~_!9|NKP=Q*;(xH~(TWZ^(>EBP`+Ff`Rn_?cEb=cV_j zWp2RV3fRI#1#jtpBiq&$nAn>cZ2J#tFVZl3qE?0Zj#gZY9|VC;@eG#XUASpj9t0RS zvoJg@r1I;u-rC->%7Rssz@o6<4X;s+bbQ(DGfs`&jZeNxWW&wd-9V1#Iwb?JB4DFd67y?cXs)!H0bcjGWL%iSH=kX*NJRLZ5?ECi>8~_;>9t(b8|2Ks}s{4 zdY1c!aQD_fQqFc8!X1Cw0QNRWr-D)=vlJL2)hbd2MAKG?CU-_yZVlYCxk=MZf*m}h zs0uqk2&e$S(e7LN5twFt*FMR)A^DVN^*Mn8cR1IDM@BR%MG4^!3VCcsP2tc0k#p$9 zBxyp!d;<10MVC*c0xNfc<>0isI%0td5ED}Vfm6zaoT}kVM_xAmC+T5Vd!6{F8Hb27 zrbiwL0+07X%5ER3NGLwIoO(&zBAvfK!0; z&jD!QYe8Jp|4J@}NMjpP6z5Bd<`O2z@cqU=K`!(|bq?o#{CJfVN4da5f{sUHnuFTza#ny4wYY(2P1I zXiE}iC)bQJo6xFX496NkHO|PwDM$c#qlH#=GpQkG1l||)MAX_P+6CZuK%wBFas;ga zvLl<2N(3Sda}u%)7a5{20(VGJ7F1y*o&qIl--hqvDrYg^iY1Cxssy3(>=1B{bV5?e z5q;5t#^ST%W#_A;3l=HtiHpP+TruUiUicUYkR6&W7)2n%c%XG>%uzYclwlAuL%|KK z?<@T5B`5)aYvpDRHIlb~@tmKK@GwgN^!38K0!Z9?v_e#@3tVL~^YT)NoDzS{uPsU8>_vtUraS-0Kq zDsmn3?f_c}>saXSt3(obC-@E^u?44({P=InE4~DkMt`&v=2tIr(Qv471^_-ce*Zn` z@;+to#lzWfFGZ0UOV|vTDvIRF?9)ZAt3;XWyLRSr&t2%uhrewch5MC(>91p#SQpLo zPX_g$c6w;w6M&kyOGS_Df$4f$D~lOHc80HOVF<9<(mfj_*MT%~N-_CIGdyu--NuAG z%askSuss*kUS$gWaLt}`c@`qoI_nOsuoJIO8z)Akx`T@IQp2DDP^mB&;jC zQftBaW@_?A$=4piXI&s5W=BpV!S|YryZm4`MVOxmC)S-{8}sBcf~e#aO#SyWMJ(Oc z_q8^;XeC=ZUId*b34L-FhG?a68t5gO;H=axKRRrl8;pAIfaW;fd`eW=6lkdPEyJJx zEZ7GGdDk^Vtdi@}@^zIUwkt|Qe-I+>`Kpypz2gfP4#flmCt6h6A^MBG6i5`2^{55yrTIT-(d1U_0QIXRRZ7SPUVpr{~G{_xtV;H!FD6a3R_6EuqiL* z={s{cFht<4*oI%KJp)tlfU&Iavemw^+{l{(H|1PCL8Vj=U~EXW!d zG6Gw;7cP82INz=rc0=?JYz6>{r+G+ynzIs)6acK%x$o@7k9{xdWQ*K3j2binzRUdG zA#%*=(|T5sBisWPblQavYnS>fDQ2Qp_jpZ-`v3ydIt}C~xG>EpDWM$SRJ-beix=|P zBC}}@unWrnL>K_%FccWvN_=}*J1J&eGtT{y%!0FuE*VyTJKCiQPEHIsE01W3DUY%v zE7gAohDDsWSIc=lTD_j+6-w@=sol3COQ2#E{?O|FnjbDE(;ZV!x4pZgGajhOty!sd z)MARHy2?tkIeCp>@`4~h*i=^YmsFFRA&|etzM#FX<`Cr7g!`5Nb1dLtxKjxvHGwkB zg1HrICJ#HXONt-2rQRH*zzN(HdsKj2i*xbRWjD_KW03;umf!XaDGH!if#?4^=^ zK-zn<{`cEcM!2)3Oy{n|A2pGpLc1g+G!pcM`Ny|Q=y*?t{n1w zl<=Ng1pY9!;U`JsZ@l?~QmAL{@|tV-13eeSUjM~Wz?8XD02A2BH71Y!?iKBL129%J zBV!+T1e!^kGoTy*S{&hX0F%-3j~#C(+W`_Nj?}B{GM8XFh)>L# z3G?5Giiv7)2o%%CbE%1@C;<5pRj#$97R2?_Q20qM1yo3D;|FjPA)K~i*86OfW6q8d zg3NhP*ILdir2VO2;_Uj+pIa&VBE2M9UlwY+#`a9g$Ru?cr}W@7FB1d;6GWuUr2P?j zIjei-b>RFrT9?N<6EC2TK9?yt-9&p(e>FB@{Xm#wEbeWIX>XjsXJuwte(L8+=&#zx zSx@u}5EaiiZLG6Qd!<4?3AC>041E(VpbI_F07wt^Z=?xpaVyA)%|Und(X}8O1ot)n zFnS1f1BDMDjLd0khSYD069=<^5)>+e)zn|2uPD541DqrRJ~xSkmr9kTbKic z)a+%!>@DEGP<;>a@*wIs5={nji4~BMbkqn|`21kLWPofuv!ESLQjXT7^^4dq9=zGH z7wG+v_I0Ox+}ll(7$r0_YMyP>1Z_@sNvQb3Wz3@c0;TleJV!viSd4|>gyxDZ^i8g& zn3x3@GILQD7VV5E+Z6d6UKuEXUxru=l~H2RIG6t-j9))V1mkaJAEB{{oyy%Pt4ul0 zw}OVkEzC4GzSyLd%=vVCVHXYD0~%KLL1miJIQ2~9A+&r1@4(aY5=iUG7z0#`I$_WS zMT(21tRO!)Ct;V!4ERnA#4`^o1d{~oM!dZs`JqWt^da4xhzR#b_>U(9M+*KdFM$2_ zk8&*~h=N`J0ii}xHi6cw$M7awRMzmn%JP(tO{WCRW&_zWhn~yeGiq`>YjP(7w)e+( zOYDhN%O3qmMa(7en319t);=AOS`bC!OU`K3Os9jwah*_rzWG`>gTCo2bj%-sI?c|$ z=KjxapZ57w7_8JpP8u?4V1ItbJM$(@*UJvPGk7LicprLle`6wPy5j9VnEnUJpAbjM z`hdAdG`Ckc9fmnk(ut!UMN-GU194jfD~c>Yz@oEtCGahPc}=a*drhj2;D?Nt5}0FCcFpHgZiwwlGyG;Azp)zTINVle?+xqO zip|%7*=0ba7VysaQ<&s~`|*+({JSE23Qz%E(jP_adJD`%h}}O^_F{kT?+NL%D}ERb z=aHa&8w;CgjdauDl{H<}<-A6iI>R7JfzOl0>Jk}DMF-;l}iw+2MHQ@_B-Yc^78Y#}EFP}8CrX_qJf z^jIKmh~&9e5KGt2>Ne46*v%x!DXmz?r4 z44PG8If&6@Z3CQ4bVpG40eIzrs{}lPXT%cq^(I(xRP@nDSSpkQDE#_3q9c4P@0E1p z5A$BXtqha?o3dW)N)+huQ`5DhB8So zQ*x#C(94g3Q$e%>sSI;K6>MIHwuRGPppYr%57J(#aaT?T4djWSBgQ)a0(4}>E^+U3 zXWJ=+4qg1{V~{-UZ)j9(_|9?q4-+m&TumewWP*@LglG1FPI*|6%Gc^xWrJseVv5qXK4zecpfK#0WJoGl;bnP!q;+)u5>QBe5qeoZEe zWtFco+IIx}E5ej$l%!!Gc18~FPYe~Pm=)#1diLSIs4oGKY{kPV_Az?u<|xN)tC_cU zM2~-3ANT$J0q;x~5ANf>GLELl`4dBC`&86rNs=sGe9uUxnZJF^KN`fuQ)!wx`V+M) z+`a#2$7&*%^;~>|!(}OanEn#Uw)I(2)k6ZUCl5)H+-Pb=pr#}YJ4u6}+YnLml;eOY(Q z**vNRDhR)k157oTA8+R6v^q@eWG=8e)3Tqd`rfV9-S9C?Z1oYpL6It>Xt}S`&?kU zS$SYSApV;oa}m}qV$t^aKat%acCrwzy3ju@YRy&GKm_PKz; zJRS-8L_h`)4mBe5VTsS;^8C(`3eJV}BalGgtYGjyb8mp{0sQ{ou*w4I6s3!)cg0VY zIc6#dA5EhW7e z#AdyZf8l$XU5?={?p>RyXG~}!D59@IXJ=MPNON6R7{+tmUXNmlz)y(`}8DSL5s z)~wL9{YkRI!Za`O6z}HEYU3>V(ri#{_OavA-YlZ7!g*ix&0Qib){ti*oD#P_A@k^l zVte@YR4<)#MomUsvh4lOXE1@gjSez{uHUeqys=I%nPBsU$JcfK+;7A*6UDeKYd=2` z9qH$)IyxPhSta4W1AoBk0X09VQL#_4LtUbO^3q&xSVo#7{(6OQnu&k^6uiw)${ zyzCIITuUHgj`ZXz0f~cb;{5?y@^8!3O%?|G&n9fyc4aV7;ll{*tWXh&#@YYoA2{;O z-$pA!C3gS`BP@4XtuzckgvrE6z8;)VoIw);88n+mL~>%U5v~X=k+q%iyC~s*vQB{c z3Ycu!wzt1-JATJI3&a*hjIzUxuBsvymBcs#LjM6cI~HUG9Z)RF7Ll--WCw2rgrR3| zN*c$IX>K#nVcw4HzL_+_nd>vS;Rq%V7B$1y#o~chQi?cUU54MdZ&Q^$i65_05O@&6 z$&x^uh~shFd$P?gQ>(&lOZuPHfo#`|b@ov~lVFhQk(oCvggH z1j?-CHMixrmZr#{8`=w*%90-NCfNy)>A zpH2Vm@0%v_!BtY`xJfV-*E6)Er3A*;b;uxVk0oe;7x!IG9ub&?rj#f4057> z8#PdI@!?q%*MAMH{HH~@2(1iqo+7xij*BQG0X$xpNB)4SNyi1ikb6d;F?dHU}zGM?6s`_lmVYOwsZ_e=Nv0N>Do#8?n}^MKYVRi#W9vN864{WAWj~yuhY`*Z4TIHBvg{6I zp-@LXmT4u&n1l4+e3AF;;)3blQbQ3tjW7#2n$6+6*#|1sA3DaqkMkcqgRIAylA_t2 z7c9|*%N71C9bx%KVu$9j{tN0`fCND@5WXq$NKOLYO~jrudmsz7ov@^jZ~+e`!o|rK zAPdk3cYla1Kv0hhywHCHESN`7!0?H%*Ry~IB0x|BEWxo%cM3>vAd!BM%YdJ2tJ7Qp z1Y92A0RcDh+gt+@{&E809ZQQ5z|cy4rD6-qYJkWvz~8(-K;&&+cS=*mH@OndEg*;u zRu9;|Viw7T0N`N|$*@*&f$c@g_3!Mfy8x{6w_^u1e*-Ak3jHPza7w{Y==Tncucuc% zJ@=gq!vBgCsZ8$#y!iV;8oo_LuLD?iIQK;i0gxqhO)zU!0qW$Uk5h?JaY%XvHkL%F zrUg8(zhmcH@Z-PBvU4^6TZ`8@DKX39scGA_p#ypZj`5$d4yO%Va>QT}7Xw|;&`@E<|t zkTG?4ya8Uwbp9xCw44F(MxyEdcVR~-XSr^v5}@^TSJ_0ic8a2vTU3f{8>(?l)do1N zw;m@R@r#apGal4=0;waqAhxH*xDQu6L|AUW6AO5%K~fgixdwjHfafVAKMTdMy-kdb zwA&8?WFQ%0C0f)lP%09bpxjSJjUFgc^wdAWH*O)u_$Q(8gE#EEj@G?=sYp@(w5cMS z?PNd|?v0(LjRIM30Gm<WsY&?-^rd)zspS3@f&M&Nq|tib8q*2*!U`naEiQ`loc=|qvU5s6fib`W z3tuJzO#J8*ARId~_b2i)rqh(I!!>*frzbeXog>*fMnZ;HHH!4Oc> z3@pMLIl@gv>_NiOb<+emzgvQK$^mt>Kp>A6ro5)@Gu^5apvPjTu~SAGVB%9Jr|Pi_ z;>6PD+DY(#w&SES_`X5U15JkQEQm4SJ3K<2DC#4i05S+Lo#QQV_)+&qOX?~?DxFO^ z03_{?1G6ntW=Oz+V4v7kuTIP+Ub=k~ZkLkSI$WY%1}N4gVI#y20385*5g51`=rDr9 z0VsiP3_`~$sv2Pmkz#Ed54g${aR2x2u?K}$@X6R<&}V4$V0az*&;$7H*YqY3wh>$& z??5z(aIAAN?PBWGx1dZ5JeB*aFD(|b_ZZZ`01%Kk30~50t9JyeA(3b0wNKO zEgVv~bo&O{evkdGdNV-wPqDC4?v7o|e$UMUz;SVkh5XY2Y%L&f>W@KAI%DdTs2jro zPf^w`wLzpt*TIHXR(02PS71|tY}M`?6wUnETbp^7aLGc;;~gjnYW~4j_W(uzN`_%vUMx_C&#xU;`tW}`j<{Wtz#qSbzU{{3rT z&(7919fC;Wl>WyeXTkCUru3*&VxBS(KeNR`GZar_tVWotU&Kb|Mf!th1_()FMi^1P zz<&hN4qh-bu%AvjC8T;4X#hceCh7nI!(ZMnlwSZU^k=5b2jXPmT1|@im)B}e4|8iI z+w09@7;b*?U%vWgpFn2~Ex0!Nqq5~+d$xbcui*&-I=sNm%o1VYeSCD7s90e;`bJ@K zIIOH^B;?AOc~2iQ#KB#eY!lMK2vC52<<|yMP!)#8cF~Kx`D9=G_xEK3lA+yaCRbNE z^NmTxSFztn-TX0CiG2AibVl=>F;^{B@$0de&4kd3W zd=wm0)KIpr@7sAl=0kEB-;s~MxYnh zbKME=;C+i7F=|gV+r7Pxzxnts$;6&9oo@-OE1F{rT$zLRX?&!k2^9OT$g!Li9qjs| zmB@J{3df7c2Bp%qo1t<-X`_Zx*mHwI>Jkf#@6P%m9sn=OpvUycso zGaGxG#_40|C}tM@o-5_#)9k8;Kk0TFwO)xY*&2&xb6$(_4fmXk? z$?K_+wyDskb%x6qX+HZjzH6Tbwj-2_sgpe;(U>-X(r_QOSyh8k$FC*bSZYx4ww0Wq zo2?ohq8g##^mQ;q)`)j7F}_rEAuq+~Y;ICl9wQv;*n8ra?)O=}@|RF3+SXR1cgaBm zIV`^8neq7JuBDm$^~Q&OAkyR&g1U4*>urmc=NA-d8{Y){l1fD{>Vlnc%XaqHI66aQ z!3LC^`DlTPT;oZ@@@+wPQA*0!rZg4r)cIN0PLfBZI~@$Wr0yB9YVPh|QzU$#lq{CF zy~lI3ds}I|PQ}5sYokNdMhiw1uXuA>RT_9Zy5B987nU4&M{vJhHL)EPX2aVZ)BHvB z*V$J2Mts$v(_FeT=J7S*l>_)o53Hplz8Al>UuG>7XsR#J*Yz>V3nKFQH-E)XUVXe4 z6VNp-FkK@1d~H?W!7b39&svXY#NxFW(GH45gVf9rG>T;nQZ8cDb~%aasii-w7%$f} zb-=S2Jd$dLg`nQXM?;Tw25sq4b9WIX;>~J|k7kN)+E$Ih)zF1s)m6(Qj;?#aoHnHK z8{VDZuWK3M=&WOM#3ZrS9IjmNN~yZ8o$leJ4PNwc^19Y8;JT`~VgYnrzCWnW0{ zp>>3r8rHBnf~ex2WSUH$&f_|1e<@Uj3Z|xUYv>uHm*Q?;@a8JGk_S&-M)mL)DcfUR zmzU)aSbkotH`W#%lHAnK*9}~9-8{;3S6f7a*rUtF<8%iD~YcI=3}CV~&c0X^jPMJ)B0XbO9B@w;j7Ju!?1>*U?tZpRvaZQ zdO!FmMY$#~yw}jT4^myRwJx~2FG`Lk{XaWfgAdiqM9UQJ+>J78z!R<0jE|x$qS_XP* zT8z?vFg_9@C%9))x0A^CG_LCoTvbDE7!XHUubB$sMDl`%=u_6K$}f?2qZGEIGUb;< zlNa~DQ58!IVS8IUa%)@a^QeMjFT1AQJv;XM`8@Sg8uw9&HhR${V&yOK5*_gd;p1U}Xi zS9>^qxbN}iK(*k=t_DTfi|F2cYOQ<;?V!nEG$(kX%K!V`wL2kq=LTQdPU9pXNso=a zd~U~1)jxJS1ar0KSGBwS#Wyn}*m2)iy)i%5)lJ$*U<7pFuUxJ=5dLYbC-)H;dH`(T#*Lw|EA=9ZWql8t5RGcMx zYbKao_Y5mK{0@g-_o{n%Ml4k)IrK6Wj4vHkEY|ZZN%1yO9G{Nz-r(!oqvar$n(3$%=~M1m_3E-yTmws1-e^BI zh<`8g-P5u)YUjC{Cnwo=eJf0`5e4o6nMY0xC*iDA43!$swp!m+GgGF;A5qyTODc$` z>0cLb9DXm3>x3k(j^ubH6;0qDR6{)-QWPCt2q%(kV`6Mw|Gq8%b^O#uBcq48x9r4) zkzE~XLC2k-n9!FwEb}XwNx~K1p=olU;$F;{y#F3nS8^Hc*e&|~%W9aolercf>ioA_ zF~YE$Ewq|RQqr2T{D6jh*XeViJ}4{lzRlRf70L?R(r?yZckNxVyFlrUl5^^rZ|-17 z+4%67BdtXfy)tg%K?$-Mt>=Bn5PtFp)Mlyp+YDxxUg#^z8hMIis=&-|B=o=}`YUUY z3^zPGl0@O2%`?K%bL_-TUA(sHN0-(AN+OHV5~Nyfz9|hxkEKZALas9kHh-cs?C&{R zaS_FStG1knDM;sP`gcq#W{S6}RqjPy&{%D(UfO*AJryz|35>$;KP%3VlfjTBcf3hV z+3YKUe_^^wu4zk9mkhM=sR6ITN}2W6^~S5#qTy(ASYByiYRHSoZLG1I(yuM3$s9Qu z)9ezTt%=?D6fr_W>bReZ*E4NsN~{PSHIjslB^_9)B~18iv~NiIRjAC%w50A&vx#Zy z`v}ie3r3V!3c)@XUe)+t6Ti1iJbL1W@XFp&g){i`KU~QDABL~tH?8E_APH2T({W}o zv!F}&^NH}yV}*xt2i~5uh>cdrdaoblWU*T@E@N4Rg60|<`Kvz9k}Fen9^1Culj~=u zt<#o%cOe(`eH{nGz?|Dw>hj17l_6(rrd%GM`A@!e`H9OplzHjQs zKXQdSQ}rV}E)ZbQqoGCi`kD?^h#VYVp{9N8p+aq_7%E(q136Tsshbv`@p-ArK}}nk zx|^Py3|UnhG%8!T57*DRn|Gzh0)Y6B3J8F1>yk8*Z_A5d-s+ zMRb$~yT;(zRgz_zv}WI-+0Sft_|%#o8!OpCNFn;$-GI&hkAzw zs}wZh%l*rZ-m4TmbM)_c9rw$nV>tvi^imjQ!jVYba%o7siJh<^Jl44Rk_IOV)e_J< zX}Viax%b{T1gB|JG{>L2p*O!`ipOHoGLq8z)}H&G+3-DqAES?TAa)KDg%$ocJh+V@ zEX;DBhAy3YsPf1#a5+_wakazDTywoaML@T7ny+G{`x)qvyZ`Mxp;uy${3zdV&v}q0 zOZ^$L_Oq6Ua$K#uX&EW8DgEI;(l#&ZuV#4rHD3BoTU+H;pwR}Oq^@i8HfdTWrD^x+6)3 zL~qo|sg3enH`0GsrEd9!UZ!iMG*2&hwbJp?`*uFx7L4{O#$Bv@v|g*1whGU06$4#c zuWrNLc*%-hEGA1AyO{Dt0i%L;?HAX?Y@WZRZC8G2N40_BjjC(xZJ# zXyaBUcjzp&ENr-0X;mXjTcW?*6CH83&N443rs;@1i{4+;ac^+wu|bEH+RD5kp`Pv{ z#c{i9S3P=Od`r;xz~A$%!)-R_fExJLUwK->-X8N@NH&@(o1ZYB-s z>=Tyx=N-dDA3l2?M}8`sK@LPc(`Yezt`an)+TZRnY+ysYhUQ_d3&IFf)bKv# zew;c{BAtslCCpDNBVS%*1RY(43)i!VGPOxq@V#s%&$WIG-5^cfy~%gBj(ze zfX_8ENjU?uO54Ahg1YxnLdvSKv0auHTE!^l`M602sb@zRd zY-#c+v++-i&)I^W;EILhO-CHnSKK><8H`;72}7l2m@>O!^*KQrim;HXsY=A>ty zQ_447B0gHgV`_kMt^~Qz?`Hxp0amN)9YBr}ta;xluPp8?lIPU&wqkYjH zK@x@!am9<4^;M{A2?_>OZg!ZDjW)^4P%YhSsy78R? z8n8OI&G7l>bg@hIe8+Sro&fdA#wiU;|F#U0F&GY!<>}`IswFWmua)q)63KI3NoO(Q z;;I7KKReX{rM@vN;5!v;z?Q0M zqj7wFUX3!H|H&S!BY}Q&+LQYz=-13!W8vRNW>hu5Cgo<9T86xNAIdym7sbr%^YlM6 z9&4lKwhA)pu;Upn-xBrZxg*viXw!S%eBbj;wq-h&X}yMxO-d;O(r23!{AyU&HiwbL z>?*$D)+u$FpsKOj0V;>mMhCe0-z~?M?YjAnKo(Pluwfo8bpEojDyJ;(YlCSiM#F>s z=yCe+NeuV&p*Xd;ZBf^EPA@N9f(y>&Xf|#3%jIZHcUH=hLe5_50$}?+KfR>NW~g?o zTmpU8s&RX(zF5-+34<|JEI-TztNUy~sdCCK&##ZAE;9i6tV|K>T4Np2=oVep-q#oK z97lhtpXN3dX#q^#>OQQ!bL?(ma>%H1uSY?=b>ZU;DDI+Z$#bJe$zDpbS3KTsa5@?B zXnpE%b&B4i>BnBIiX~H9cUwvH8)gouQM_04y>EZ!riY1^ZPimu<(QS1@>kHOHq@>8 zWr|l}Sh1^6eQlLV1w4=;uiMB^Y+y6Jv`N3F#The_wxy+BW%9d< z2CZaHi&j$VFw$!-lHlK-*0_Dt@cAw^gC_Md3(vYhM*U_&pFspKU%#_v$?=-&+Xf3r z9zKe@ZAzSl4_vnOZ2I(8U0}FPvSI8BkJ0{Zxm817wNp>82q+p@6M09PdxZ+O}P8uD`lM8=ibM6=#aKv@oOXPms2XE@z=Fho?Ma` zhSBE|-}h`fltx!|>wWn6@^mNPL|I1Mgh!L;T`7(tN#!Y#oLqT|v;n-JdAxga`46aA z13lD04!w)4$K>8I$cT2G{F0EpPv-^aYywi$pe0f?K zS)nTR(-WC*N2KqgHVfm0QO>DHzT7ssUP)-Twz5}Y^Lw9_K_cHi*3xy-E=^F>&X33GFU}&ytxoIAwsP zs;EdL^Mki|2OkVZDT;+dDoxgp6edipgft0>UD*Z`>2JU8M)CKfsFp23cki*DaI%GZ zP@}v@5r!qZL28iOSlwmOmUnw}aHDsETCTy1-pA&&q%KRnila_0y?(Zc#<}l1b`uLt zI1r|H)VPh;K~~oK(C;;OwA-=5Yke|TCMw347YmX@HMBH?vrC2$Dq6N8%w81LRn!#u+Y9v){6H$V~`HxA9gC^S!(D++s79Sc7SxnM!e8WpHfr z*2%$>j2Lb$N_9|)zy9p4D7Bt(Mut&*{+XoO&{bV}u2ij}hiV7c_X(_HjgLK4_UUc1 z?rg{*zt7iJS8mXAcg+tXsfkdha&nE}9Z;{e+{_Pz@{SQVJ zv1Jc*)CeBk__M&0^ngkq;-l3!ZOaLdjoGvfuX#VaMs~9oe#Dlxx+y#z)j9n=z4Ef$V%f zR^T$orSXUK8^-EpeqZq9q9YHaLa-Thv|VZJkp%C@)N`Dg*tLiiR9thAkS$Jei)pL>Y5k2GhXl3u{YDy-7vyg=jFzo^%tW< zWR7tqA5mGWNRy(v^CDxf>68IaC@)<2cpFJhS*0~stuqstm!9{BlzYD& zqH1W=W7M7Mc3<12%Gwq?rp!}(qHsOCQ&*vn#m}ir^cJVpc-~8sR{gqw0{Y6@Vg~(@jvTCJj_A0TaapllPB~7?r76U zNA-g7s2_!K*GBdiRTiCc%PPtDr${&A|8gdKxp zp3@g)p3Lr2=#0iyEMfF^JyUpYVB7aouWyNP<3)y#(DZ2q%`KtALAML{*g)(qiowfK z`RsI}X1$~`+A=GzVu=n*?qR>1MZ>o4U-=zxQlTOR7ALyX)A*e3EzjsBn#!42VbQgN zTEGDP61T|?GJG}_X_OroEu8o|378}d9wd?7!>_8@YO2)oa}#fP;OeCao1^CJ-B#^` zzdN~y9+ILoq-+f!PWd|{maT)xdq zj@19F^}Es>+jnO)UA3wZU}E*nI5Oc9ig)iax!^hFKfVuZ2FUupxmF&EZA*) zsPp9WLve2w(cj&fipDueMgJIH`D(J}yxBeIei7l;<`-kIiwLpw`;rO+ztZ=rKOc47 z#gH%0n&kEFTRz|`_0rSZ`q3i3e_Cxt^u(?l5F*>0LhcfqEc6>GBfoxkB2RY&t(E^? zKSD4a6(H0bWl5~D4}X1F*p}`iP9S13J8-F0Z5{o%6Oh?t+3>EUe7-o{KQBz2V?O57 zr||#Pb~XM?uYLHpjV&1yby&!plDx!5r!umMqnAl~IZU5n(n+16}wJ#Uv)J8S?UZjxn^;hBTvNUgBAu=X0Ka;CcRq`}4i;>%Ok*zOM^>9|DLo zfCL|0Q&Y+|4xbcR9PKi9s%A6d^`3+Vx}Tz?8=_5@&T$z^e3m1_YPC> zp6q5#pa1wYdh%dWIDOyihBD3AP4e05yR6yRi|vnDqY_v4iJa3}lMh((T4_W`uX5h! z8Er#s5yvCgp~6yu+Bq(&sVV>_4;LDV{^b$pQs)tpd$ZYRsA;MGaXtcUb-bXey51L{ zKdVtjmMl&!R3cLDf2G@ffsKMc&^ZrG)cTFj2T;Y8itVIpxr7uwRN;M;C8up=QVJ4P zI7cT&>;7%1N*~V@q*808Zac}_I2G2}QHpsz0^fQnivM#g=zXhI9n2?%1l1f8 zgzO$Lm}VeSYSAfk(w1F&TA|B`7OesM7f)EC#M?grAWwB3)o#@@oxUSdyM5j_@Iv6> zzp<&LQ+Zmuc4PkpxBr=5JudXqzCXCM#_Cj;BPdw_6Lx;T)d**#VFwUfOb{^S<}jH@ zR-Pxr+dklv(`|={e`pOTcV28x{|eiKynRYmin~R|CKkiCi^vDkZ;PzYQZ2b*CTmV| zN^yGijH*wJ;296U7qKg{W@&GAV<=ASbWNhJxNN;SvK?b^^8HM(?}&%1^fIIKebx<1Bw#-9aM=!uXh zYL(@eO@7>F9Z`VzI+KVIbcbdzXz$EmO^a4c+!i{8oTu-B)W?vNt(dH4#|SXxFZa=p z-1`YV*KU9k3SX0LL!HgKG}|s|bj12cGoT=+&hzTiu6{+!&s{VkmwD$?-2Mryu6_hH z_Dmo|^i7Fy0o;Y(wrq%DcP)8$y@OHwDZKsShS;r4;>l6k4`#<6$!@E|nMcUOz-$n& z7c1eE4gEf3W;D}WCfc0PjkFxp2L*7j_^#13yeS_NF7QuhV{VATBc8zFkp6l08Dp%~ zJkC*iJmP)eOqlbjiXc_3+8s84N7#iKa9b z{kQJ~6eJt%-c$O^(+n53C+2;7P=8V4BPFhYn-q0tPkT~7i^docxR_b5U-#5vm<@!P zGz0gzK*;OWX2&YtTq4qrJI%WsD3|`R>sdKk`kJ>N=$~V4;G2htG8xn!LC z^;ck}8F52pdhE4!cnp@)W}et~y8EE`T;J{Q+i{FYB508RYYXA?`Nk1{RH>0J*AQ{_ z>Au&V3+Q^m3w+?@e_72=pGl~{je^?<-)NREjPo-j{o3`u8rtZg-=UjG_(CNmY}=hy zu=~qE!urej^|Y50=G-tsXJS1K*&l6nrKScA#W^%V%!e61kZvLC=bPks7`&K|)m21` zO4!G z&o>T}p^HQ;$YMHnr9LX@8n)V|AU``=}XJLs1JnGz+Q{wam_U?wp7=VA@NygEo{Vyt)i+I zBkw*BT2XH=78RF^$b*}^lIo+a>l!H)xf_n|#?&2DMzTNj@OFYZsiH0_0>Y<-1Ql+0 zDJEl*{<0TAW@oC&cz8kthgxy{h^4-|*?hPJk+5LS3cX^IvupYK(#tW#ljx7C%b20f zgsr0ZS9KryWO9Crz3_&k>dp!DB9vXG=p_qY-6E&GRWPG$*~nx|Q7=`nzt{}{i*m0D zH+b07^D3dov`;Ln3!f{jk!k-jgsWW_I1M$y06Q+2Fx{4{R(%`)Ez@In_sCz!7NGxu zMc43`W755`&*2sTXmSyxwe%^%dGI#h!qBqb#&5$qmfFD8^i}^l^lK#}VDH`%Q-w3I zORwfIffKfaExaBnSU*OpTb~Yj-?VQT#x0$tw11TIik{~=ly_TiHzeVQypmd@K30dV zz>hshprK^vY+UM6_M%~Q2~cwMt~v5wa4j)oRYJc3)bR$7S)-yca*8oF1n=K$y4G?B zo@^C0SE41c{2_;uRC}LDe%m@b*f*XK*&I~m=-qv)m}DD2-Q8>r;K}Z-tF4>PjX#v4 z2M#0al3f?E7PU!&A-(~ap$bol2evrmE=))sy*D>xa{LTz>N7N# zo9`Ue1u!pT7aMu%U_Cl1*i^Y%Myr*I$kxj$Ucg?K(I^h3y3pWOU{Od%jq6OsxlG$W zIN+&m@UC4G?W2gd?*6|Mo2F}bo4$>!eC?!xjQJAmYy3~)c(P>@d|@I z*lho}H~jz`umWw1h`Y_Ac)>)HSMr#YRuFmFe(Y^SfiEHZjb5QaCn()9)@Cz_=Er(O zUIbmJBDqATZQQECd5pbYFkRVoLl@$VBox=?^6@|#hfane;7@nomlmt;2N>2hkT&NI z)aV}+8)AjV>K3?_K#3W>>Yh9EDDskTI>5YAaswpg=xm3bC(My&_$bkjF-~{VB{%i7 z3!=7~2O(F;mKyNdda$HA>*(`NeD2SjoCqYfmj0ZmOlw?sd)qphQTNE?0lU_Y!CFOe zp`E7nrjyYK3mzpo6m==A7mKiyw#vR+^fgPSq@MYPK6n7^^S4h2TlCORe4zN$230l2Z%z zkS*5y?)V@4HYI;wXyfgbL`M#F9cUM(D0$e@$K-cVKwzx`kB{Tg1lo;=$p%EqBG%hB zUwc4}i25+aT6XYBvtG=@@Tf}FlY6SX^%+94pNdtKohV#`-W5O@EKGm=$$vE_lkVe6 zw0)NN#CWArpa)8A7y^kCl(!w+rlxed7O-1)hQi#$#x#X=#hyenB|%{#QRS?Xw(Xlr zj@gvo9bP3SQ1LLMhVnB5I>S50sK-=p%|0bG3c`4Vx)6R8(pQbX+uCxe{dR76v(K-3 ze2EckEF3T)ovcTc$^x&-tw!Fb-$94}kadzh=kpKG`65a7di#1A0tX?FPB2bsMap%$ zWwroA3&mN6v27~WVCvKOL`%_-6Ks4i>}sT(dGAM*RXyza5!F;!){_r!WvaSJLBCV- zVLi$ED&&+Zy9Rjoh3G6@@1U$1wRQCfbR*0(*Ttldmc6qmt;@e59opia3I<}evsrS? z8X#Z=Q0}R(D)E0-AyR*Zn-@{jrK4(0U(bY>`P4zT*h7CK&hDpv8wbi@vhOa+F39;z zm#=_xPSg6R|Erod8*}cbmnaxt-&wYOb59-=FX;wtH(9Z!m0$c>qW_M}ns9{dNPD=Q o@)#G2w>}TK3a{%zzH}X_^@~ literal 251664 zcmeFad0dlszCA7?S^;rEKrN!UK&gaC6%hfUU{w^PrA782xMD2PAOr{|Zb2;ylxTv0 zpaNFeS7Qhv2r4oW5R^rhM218VNdjRBO9;RBgPl%$Z|}_9*W6Zr-`D&xnE=U?=lMM6 zbKd8i_d9j3%U547oiSs^68N8z>Zl6*-;5dY$ukzrn6W@<`iK8K{AUIJvjYEbu7KAg z8=qBQwM@KDdMXJBaC_vq`}3bRF62IYxM#!C7K=yTS9USfzTGdb-moq1L5PT_Y>vIP zedi{WE5_){=<@nca(nNs9GI`Kq`zw<`E<$RLw2kKy~!lPsu@<55zeR@=833?ovYhV zk+o)K?F~`C8XudtcUGXvTMMVDd2RhO)?L>7D(NpqQHs>F8}^>FF-%(c#?UF?ZIFhJ z{T+h+j7Wp=FH`C1j&AkeT%0qwTlssfOS=rP!Piz*Fx!Y1_GcZR^;ItI>*kr3nollzU6ugk7-k{^$xO%ZKZpfv5T?Rm}7cyKdkBwcIg zd5PUSYp1;-I&=F{#^=xfHbL#2S8vb7*hmIWYqwzMw#d|P?!G)~w(QFG|2+B6BK!vl z|Hdw`Iuqqzb^pqIw|#bR$>P|?hrTBN#?k(dwxkO~`*FSecisR(_ZE5-k$lkG5Yh+ zxv0rIr`FMb*r#95425`w6GhCnQ-{a1z`m)TkV~3XThn{kCl&fgH0*rMJ> zd)+M?Fyg92->AnARS#`dxXB1Z4YS)FO%0i z`B1m*=!%uK0V9nIqQ z=9!fF+Ab%)<1TE7_cab&7tO@Q*G?pr?Nr&_o)G;`Gg-&4)WgGuL~po7d>@*6M?nK>zX?7Tk8Fq8Bv2%bY+=EKNl!lTz6t1wVP=&rhyDUVSM}d61#tE`MmVJxg0FNn95VQDU^COReVp&F zdAG#kz^oYx%&l~awBhFF-NN*J*tgzA$!}9I?$K8(#=?{WuW_IEz72X$cX3KCGISge z0X*1Np%m%0UkdLUrt^)>T*!9+TO$5HtYJ@=+&8uh*4eRAQFc}+jh{Won|;H`1V8rm zA-L` zhub&;buVrGEm5hlWZy6GV~)zoIi8NQ7ZK>yyOYjw_ocJM_@>^?x#;HYr?z5V&%2X! zU)3wG*4J@ny4ZKk^usLV*{n0s?pDaNwGAhl(G02M2fIT%Voi^^pNGN}w#w7tJx~9N zqVFh$&7sYo7iq=lM_1_FtTYT(uwXsv{7txs!v8um3O#irOwngY8xGHxWrxVS_ z`^OAEkdC0_`bDhc(z6z|L`?D@XO(M{2t4-oDXjEV@AhKVS}JoN*{LSRnZiF@m)0P`to^Pw>y3p=sDNdTg>||<#|Gkt=_o% zN^JUny{wikhsLFqC0QXK28D?Be`NU0$)M^*4SO(_>b~75dF2dqD6PtR)4~V6zHt(Bz`Vea4EnLy*v^MO-(msu&#rL9joVd^%h_O^!$)WW!RTTJXe3$L={+VUp!yQ?36y{?)^PsfxM0)hl z^Z&l+b0RDCyv8E;NBin4&$Z+pG2F5P?eoPx{0HNeU)9ndzN=czY&hk_eQb4jp0r`# zdTQzPa!-?`vEHZZVYoL-qb(w0Lw1ue4x8hovYuH8Ej{@Ka3AQ&u6O}qi}O8Z=uekB z%YLPsrV)Ow(k}*x-?R!Hr%{dLRvRwDcsdUk{xi1v^*;JTF3aVP#qwGzAl#^HGtit8 z#1K-K*ZaA@J!xY-jg~s@QED_FWjOxogU7-M6?Queo1+&GB$;y^PFL)aPK$(TulK70 zw1=i{b^oM-DomU5`W3={#Z7<6n*P4f`0DfhKeoT!dPn%zzzR5O*neQB_8xobj(E!(hA-PozkPC?k1{~$LXciw^`5++tmNq8`R}0E z7l$8O5*GfJsvO(sFgf@C2M8&%o4E9mG2fNnLS(ugzL$td4)b28NPV49V_|Flx|_?t zxj;G_74?TR#P6f|@8vx;YSW{;ONZG%%opcQoBvABPE+CE z{nFfqhZktIDGd=tDen&biKO={nEY~ITQ}?9dii?3FzZbQX72B%8E&zigDs0vKt*>hdiHkw4TZ{rHl@^IVHPQ z8km7`RAmOLZH2Qib4k{a)tL{Ng5K@CHA{WQp@rP48B5RO%PZBZK>CrPbd?Gv(xin@hbpGGu`)%r&@~zFRv~nRz>x_4)TWpCNsv)IE zMR@K9zB8>tHiK-e_NpOl-)rlJFu&_JwYYu^!Z*ezzW5+8+kE6pW#ncIl+X6lExXpx z{uA_XY+~pAePM5#7{3Z`eCYSYKW`oVW&Xu^+*9jG3HWi^6*J+G=1N~wgS*K!t`bu% z9p7Q@s3FX=yu2w~&-MdkP{*I2osHa&uG8uj7W=+F-<}tfTe5{lXje z$-}m3PX3*Jf=YM%(>8s`^Rr7L@7(yAt!_S};(Pz6J&M5OM}E=54Mu2VjeT!ZP(uS3 z=K`i6y_&uyX$UXBHCk_p@5mog{Ho}$N_R@qoVD5D6NJwV{!jrax;4vmo|7d#+O&Kh zzWg6v4gk)`CU(mr%aL=JXP32?rC+uUbe~uKgybdeduvseUYI5wY8+@B^GkmCHqcAN z{7KsKS5vgi``eX$?@sH`Dwix*;9K@9Lmp{ze(j-;=&IoUZS(dhc$ay$^77+-Zs>da z7kv6&1N>4n&z+Vz2+I;Ps=V_aM?P#uq1U%;5#~LaLr%&I2`<;Qc{N*8-&rd0>g z@04C;2qTB84a4?v9ODQyx@k=${$bnlt{hLNia)RsYQG`3DkATZ*+wyDvtWU>Fmj(R zxwPb8bE>yh@Sq}POO`hY&-TNz-(ONL8GOGxD)(tVwaQbAZaHi`v+Mp+u2Q~J0~04Z zAOGLh;_o;4-}{q#EoZs3a>2_NOurv6$~^Z&!G~r4;_bLAT_C=Dt}tf?#!G!4VT|i{ zS!2rL{cTWkX+-18(MHgjRuQf@1RBvs9uSe){Q8nJ)ttpBK`{1v+FH{7X;C_N6+!`O6pIg$Iq*oW{x)w^H4 z?N2zf>5sU*tf9e z^9$C41%2fj)m|A@~h%{F80_&E2=O>p}V#j|Q}to`_afrm4(6kVyY{V0TnMUNzYJ zXIEIIbmo7I=|0rWUGVJP0RLz6t*kv$c;?IN2Eq?@GQV@PFCGdWmC)X&Yr1FWl;$BS_Ej@igA?^KmMDw-{TjT_;y8XAHO0AFue5M>D{+Kp!^f)sN2e{5nPf)DrPE0nUizOdxM+>_Dnn~{_E`&#v_ZeE*s{ZGa-(`!#l$Em6QDX6J=VbYE@ zx>XSj?A`BwZ!qjnzk;utPgeU^+|;>gRq8r4K%iCJT-#vb$7uK4<34vr&X3&30xEoG zy1zLEy?kq8&c~9!UmR86T&p%PWjv?kYhz*8%|$)(>9s~L9jdP%3+2WB$kj|rtE82m z79`RTaQ&mA@~4$v7f9b{s+D+M9Se->?VHaHKDF^A={>+{qqUV0>3mYqY3Lf@)5`r2Dau1|myiPFF^sUYCY1KlIDlKDI3l z6248Gxq|+3%TChAk_vuh2;-hczE`6&Y0B#X3=LiCetW!9XPi%@tsT0P^z$V6pSG9& z5!{StD96ZtIZK#Q$MhKQ=V}(QDnA}BK+gZGX47E*@qoa}h@uCTrc=i2VI9l9?m7HX z6o&VnY4z*%C3_RL#GsuPb*14e_gp`Vf7wC$@QUGYY1T9QTDrd+Cez+ zh03{j7FVnHyMMIXfA`J*;JE+ppKcF%+bu0WnES6zU;asJ8hv}Y$;Y%zf7_w|?sEU< zI3I;}{eKo()<#q0O5a_FZJ9nN*_m}{Ru+$vW}bU$XKr@L5y1g8&wP_ofq-Wl(c(FKA49; z2~aq@kyXnDqn>uUEc>`4p8O|QQ^uypxi{yL3W^ECNmVYcomNxs_EtD&(BbkrNnWf`oTZeTcWpPF${KLJZxju6y`3Dl1Lgsx@K-FlGu&LQ zy}zJlH@c_b)8cnNI!qBUxtZx_T{l*y^_(bze_WuHtNRt4lI-|`tPO?X#5s?|b4p!hhax#7Wy zYBQd5tGBpmU9rffBK9fy!nTvi_neV~LgF}}% zMTOs-Gwlcnuf4=>3~|gT7|-m>KyKW=SEr==huvNU93BoLx9(>aQ!PEnYBrsw@VD0e zliI$n<|DMD8w(UozO%}H+Jl?$J-p4FKs~H*O76|v2*;Z>4M!(ZP91_nS+9hAp5LEXH#cSk z`3yZ=SIu^jc>&Z1HZaDAtpq5OCG08CNCNB(}@Y z1{D@@Yeh%#(GPF>1s5L9H@leSAAxp~Dp0P44s+shV#y zamN(btI?X7BJ=n)a)bz5XEH_>%P*KbXSXgF_28Xj0xg7w882i?UZV|ENmQ9t%8!DS z@Qwjtt8V@Ri9aD5u-aeTLP>irb-rR`1JvbJrUM8$m8-sl-KqnW7oleJ2{AZWm7mez z+VZUwP#vbL0+c+U9@ z^(sOeZ16BWW4~Z=f^N!#`8MiO$pzXF%3$>_i5p6;Ldc9ef)}az^q0nHQ#-4zG0smL z82v?)!23GXMl8poqkr+0u&2#Q$+x^Ja}8EhZ?$4I?~=r<8EqoOU= zS-~x?pbmshl&3Z0ZFg6X7Prd9@-RXdyXDKB9>SJA_8VzGcG0m+bssE8m+`LF*)7hj zd-d08p+bI?L$6fg7B+E#NLF)_6ZycDQRq%UB|q;_7QjHwY*XR4STiktM+9e5XNrAN9ZaOCRRWu#l>QOKTtW2)pN~kOHj=hQ~Jm?b_@944b)uiiGPr-pjM{701 zI?X4uIJawP^XMZ00M4v<`J%cB4|y0zba3*HVy@YECc1}>Ef#wkSR7&31#r$fb)V-E zsX*BiPLsQB#EwC&-{%N>+6@#n;{CjCm>n99)?se76Bg5}5VJ0eK&bGT_Vrs3RfVRKxNpvy?*X6OfuX?WGwI;lC_A{JRz z-!$5Y4T)LvT#K#Y^+d(LBNw-WHiR}X<$?g{FXmhb+o*!Grws)$E+fT!6lmA|oNmco zjMK8chH5PgKf&|GDH;wp*M%<^KLJWCW-qILCrD9id#-hfPj^*otIy`E0WBKnbIBTB zk5GnBt|sVGMb%K~p*pMbF084qb=+aOP{|9(cezN8Hq2;tiw;rD{4p~w!h-PTYDzTF zyn3UEKRklwwbbYqr9I&_(wf{~|nl zwHwN=Tipjh$;i>-C%9pm1`pgc^ZKyP0*=AL0sAT75er zA`2S0L1dGfNwJZ*pYgXp$8#)Ty{trY|AihI=>Zz$q$#5)Syz z;uP^4pOG45)>&ma+zBUgF@4D6E)>{1HUZ|zqN$!T?rwCac|X+q!im{+qfX+?_<{!9 zYdR+){!0D95t?tn;mJET6}SoNip<1umVSw`A_GpO>|y+sS-@|6q%QM&5`hSz9&3ih z0AQzzswSMK)S6hB?jn9w;y9gCaV$_MCc`sk3^7?G-d}S?@7Pf~voO3dv3*J{z8`*_ zKxZ1kq3TmB-qgJFM&tE}bV<-8hyq~|FBBsji#`e=O|piU zdfrn@?lU2?$Ky_A;~dv5ICPDzE1Jv>-j32I9~Ok+I*ALFoI5B6r_)|EIc;>fEG6x* zEK)%*$!43QCdUlnzXGZgm(!lVKj%OhS<^_LuI?*3#hmco2G7t2w~k*h+9uVi(M z3i;7KqwLHiL1;1ZteAhc<3ji0lAP*m#@E{;#hs^|vY`4tcv!gHhu-Q@Se-DLp18%h zZ0_L^D!F3+u<>=k2k5w-4sG86^T}Lt(PxdvnPOfyGyG-fH!RGQ8vh<5->M3pg@LX- zD8;=--Zz;WjA_sS3)%QE#0OkXIoZGTZvCJa&r$v0= z)aLB(*igDFo?^|Jg~WInRPBUVK%LxR^^QbERC}XcJ{h1Tvwl^Ym&l!4dcEN2Gu|#c zffYiBhjh>tR}Sge@QT~n`DAOy5jO-I2W`Z0=X@d~yMrrf;6y3pY!we}EAd zi`_B#6|%MZcs-fOV6fglq?nVJlVO#=FdYX51{h9<1sV_x2{(LZ+^sXt)wu>6yvX5g z6P}Mcd5>%n6iKQ#&S7Xr5k)fUE-D?s}4A`(Hv`hgFYGWJwM+DR~x<3-28MZt&f zh=R}Uswz+(@=HRkt}4*!o_Emuagy=%*6M3}y)y1(tnr8*iwGvjl#E{n9QX?}Bf3zEC)L>FXiDNd1oSs$fAP7)B|+}+}9H}X-=e!I^a^5@2`dU zx|xqqR}=wB@)3-4B{bi9({bwl9f>t*d_L?Ja~YSPnK(K~){{-xbyFlGZ2uZb73I^S zmS%2!iGj3LW`!nG#G!U?GIZAO^zC7PdY=E1tq{Ts>+r)lI?VZiuO=3Qxgi|b?+;^)1gL%F!{^=56a-37lEU z-RIY71vObZ_~GLY;rqSd&B%{iUjg9oqemX~&KefA`C ztq-ehf{?%2^U?OJDOjJIRtY+c-g!1BL~KxZLjKH-TiLBD`LlsCdA!rv@-W=?YZoa1 zU~tOgZ@ntBq0+CK$>^2%>vKaN|0GZ$RK*=>a@-Hc&z{V+S?v{WQCFeo^?U>>cDN38 z2hBKzDqB{aTD{SNQ0@}W^goW`xE1J(IJ<>ed$Sq^>unkS*3{;t6s4Unjh2=Em`V4a z3B1|5TrljpBj&(S3E{4b6{gR!dKsHKa0Tczz+!b(n2i$1N9QV&TqUnz{G$az&ISFX zpnT;)YV!?VrZdmNK(pF9tR)%Plg*Eo0a_PHvAH3CZPrj*X>z6Y-Oh%vmHL5|rLn9w zj`oj#ZLkVcpI<9+(@(bS08LvNr=wkmlv(QM9;eb1QN~vVufBL#*x`1{b|)5PtjMVw z*UwmgOt!*UcH+uZnG>l2t8jcwqj_b0x^~G1Vupld)l&aPVJ&$H&c_##e^1J$4HUR) z(3^^8POGffgZvege{eEom`N#O&-cBG9y0|TwHrKvw`lt!u8169T7$6lsdJ{|EOeR^ z$jvg$y~~HDC_Npyq%m`aV;jl<LYudl5PiOh`Mzg17?vZRP8uVIf$rzPQg{0wm*DJPNS6yT%R*4RYmGZ- zigw0`#3rOjet{US8+R)iG-SS|=i}I-YbS(_uh$i!4Xa{fv}0Ga?0>+BumBiB(e5{z zsEP~ECS=l&sEPpi){I-CM!RNL4H>*b6gI(N9O=f{?nSliU1d@C6fg`@()j{$A-Hxa zFl_i{s)(2$hD=6=zWNBQaXJBMB^fDSnC@{MwREXaWYVGD^6fjW^U zNO;{GUP=YeZF2l^6KfzqPi1v^j+JNEV-TH79&C(J${7Yn)0X$n3#v01oo<7Y1`v&Z zZT7P;d~>Z;ymM}VhQ-lE&4HGcy4~t01gB}N6FmFq{tG1h%6>&V3<$Mv zOEY$m<-JVenxo?>s-hzw8(`K{*xp+0r0v*wxWvlrMs7h)^^L6S6^dS#4Fo<8;BdcH z)9)`hd<4K+*1+w}B^OH`8a(MKP>3Y2*vrNa0*8sz66gSvt&Tk0+x(1N5SP7@?cjyM zVwFwP`%5>4i1Ox z`kXyFLUujee~J#7kPkQ^$e)V9k(f_7k>*Yt4la=PV3@e3IDiqwb(Po=yK)e}fL1`DJaW4x!buHzj}1Yq$=@9?^(s=b#nK$era{;R#Tr*%M|(bfuTpH&LU2VPF{ znouQ4b~*ZkEDa_~MQU|V;jpWEQ+GWA##}DW*qA+@i+gD_0a<|{+KM$DSeZe_q^+=G zEldXkU1rAWj7p)D z`=M5v5SBTwF_8dt)dqh|6HuCd?6!Q*n0OH(%zE#SU2!_9UA1`S!AKJ!?M;(C07uPW zN5Z{g2#Jh}X+3M{4~@%m_R9^7J2%zpWObS;G<_jR$_4Sc+3t-MZ$A$)@~X{P{ypMk zt|#I@_J^>a5&1wVSa<;NRp87Frl8UmjNjt`B%gEYk)*T!fH_FKM39D!HB)Lx1{1}H z58u{2>hXm&y{Z79TW_kkbpIsc<}(WwP2_1Oqw3{3=RK z{9aC?VgXZ(d1D0>Y#|0j@rZWaMW5AolB~c1JtH<{fT4cpjRZVLt)aqSX&t^RV~WC? zvF%scbs@tUvDpe813xeMx?{ZiHDX6zvCD9b1TQyntSD|ztPA0G@!nWV`jLS0B?Zeo z=^3-h9NXT{=E|6)?{kqC`sN2#R=Y(AUZ_5DA}(Ck_GA_BjJDyjwo$3$K4J#=8aZ|Q z{egs*8`IFTLruPQxTAG3g*G%+*TIA+XA~o$bc=_wCn+{7*J(R@EmZ5k$dOV`$iCD@ z|L(9Q+m6+U^FrI|3y8*5PZD)P(wJ?S z85hnp(0{rQ5sSXRap%EC$R-uUYy_-eTKxB^&u0UvOx`cOAsICT26iBGps)M>Ctv8R0Wh!(~ zZ3y6y9V15vRp6}e4C)OXrKcW;Z3Fbi1t$)vfEYM29sD{M$hHoDNGnIMPFLT(Q;oVl ziyY4HJS88_&tsAxK6)<@AR1L`X8?Est&_VU!iPXqjFkAJ&R%kvsc15Htq;Y&Bip~y zs-#o}STQ37WME1xgp`aC@Ey+W*x;}AoZU<^ARW(zzvo9gcQ6gxXhRiLyB9JfUBdOP z3x^&N1Vi}VTVZ2>&C0gtdcCPp3qc+xrKs)v#A8gYI+Yt*Ma*m+8HjfHcH|lu8W$bL zKsrvs)npj&X=aSDIUM6{SexTud|EEz0erW(p|v4HD4Uf=TeTUtgr$IA-IU_l5KboO z)cA$vZ z1V*45p^FQd==phsZcDZy9g08XO=Hyq^{hrAg4i%n1f(F4e^UYT4yGr++r23SS})YDLf1<69~wCdkV%`){T3QWh4~jAYot#n>z@J`WHDkh>g;~_neZ- z-fD)GVTxygTjJ#5NIBfTPr=0k21TX{I8@?zrhzM_;2~62h!hcMnonxmyFS|v2HYoQ z$ccO#*P9#U3V59=LVOeuD#Yn!R*gTtv1u<*T)Nm8v;qQ7%@sw3kRN3|BNy>oAuJGw z0|0fbZ{aJr)^`+X=zg|BQ@1LyE+9X(=1K)bRaYuxR{EYXYRQnKv#}I9z#ZG3hXD0z zB9p>i&d5|CNJv8V75*6YFxxrNNJ68jXm`#m4yf&` zC`6=1DQe!wiy`;Fj3+IT7*^6&sl?@M*|bWV(JSP*b|$MCR#|MdsD{_UIWOK&i$`E5 zh!4J%kbB~;%Vx~>5|{8XkeE7{-g$zX$86tRbj1X(LnL%P^?&DcUf2eT)?3_6JdrliNr;erm~`f9pas%_>-rb!JGV<3ok z$K1DCx1Yx-ez*KitB5!p1bw2EH-m?8*16lyf=)0wI&FxYzt9`be>14(?3z~U%*v2_jU^`&Z(v)Rjtxbl$FFkbaQp=@{ zC*X*ytV&Wh=UXlW|9*)d_uZ9sniTO}kO#Vu2W^#8?Wxcw+5y(Rw_j_zBkv%~W-EC; zvIq{A_Fk0sL03t|@UBZlm|+!F27Q2PYahX*AZlY@^6idM6fei#$`g1INbO(}b;^4mnyaU;5+}#b|?+EavSD zx&aycT*2uQ^J#}fvaIeEB$t51FwAH;LZCMCU?qpOaebenrN^$f*4)r`1eFKr;XxoH z;INX;q@1bpZ%g^JHK?(4R4IYyrQD1NJWRj8P`Lf6WVQIgFo;NZ`gU$=+})H_Q9LO=#uFg2@=Xn0 zhK5+(i_U~2iGV}}>5{6*Lg*M_gwvc_p_RElo8aeu&zg(Z$^jvKFoD(HpC8x^7z4W^ z6QlrLK87v~KyI3_x^_KUDr7@LhRrEMb(t|_S@QMPrTe17XE{H`JHh~IUe-1_w8=MG z_^;-MZ-yh~TOxp5xNNU67$vim2U0#Cu*B!xU!?<0JCbdiCbVw44NL_o8eY$fWB-ucoNk zn}tCM_ZzEJW>xnB^gv36lwIRTwKZe5Wip5jO*LDNBVQ8v-5xBlLTwDY9>A%n$~=Zl^gS z>13vToas(pF^olAX@y)~PPFMH_X1545i*o@)gW>*e$t2Dk4$c~)+yr+is2+Q)ODndgP>oVTp{bVlM|7S=^f}X5*eIBvZ=%gbLKtspML?dI(X`PNFN6R zRV)miOw2~)CHyOkyl%=npIi7t!#SGT4=`5_4QHBz64md{jzN<6KLmlDkchBg5AE zOAHBPc`3x`syO4?yD z!7$#|4)Ope0s#8l3Y*{<3Yr-|fmY~qvSSR?k~*umB0YM3>kBF9+5rRTnS(%RVC~or z4qqOI>*8vWCV zBq~*g^nsSXxq8Jg%tjY{^u{FkJvrL>p%r6PDyhmVr^IR!0uLHI*q9RS)r{xqSd3b> z6+cGuA6{ECF+^wcVd(YDGpw>?Lj^|~ti8qT;GZP$L6?(r4`pmby3oj+1F0r)Gh%{8 zP&SXQON0^&kbEu zXCcRfV9|-pL;{(uj-(8Kt^-H>ij2oWb|f-g_T$0fy~lbAmRZ01+95xqk8|F9)T5xm zA8Ae=hGtF?zZFx6Jix@zNa8^U&b@1r?teOYY#D@sk437Mi; zkR1Ze#HbKq>3(YeN>^{AI+yJz-DmC;d@tM+nyk$+b{w$qz+7TeqcquUzFE# z3GOv?9&>X2An0*Y@|uv6L_EkEA#*&Z9hcJt%=ws#-^Bv{ya8F#5OkD)Bz^h?r<17t zUPv<80IhQ#rSHpR_Zv)qbAXh=uQu~ZdPd6cHDjYy~5n`*E zj9b{u7MCO7u6R6{euA_W=82pyP^A!kdh*NN+$cYZwW(l0V)Trz`LwsmCMy-BgP9mxg9D(d;0N#P>v`(S-biB1@4c>S{&nr*vI6oq) z3zQRAKS8F9b{eU%Ds?>h>9tOTygHRwR*U~Td!26e!PF4_zGRqU@^rK{Ya!4{R*|72 zOJAD-9g=VR*It57;y2RoX*9>o!UK!y2-vk+H6GxIToXUPV+{P}Drv=BsRvFZ<;Z&P zOx@PHJLn5TKSDZWKGTytpe$9*zk*N&gg~nfGU)?daRs~>n&?OyCK8WRJ%(3soBvn=<;YLqL$*Biwv6 zIzub^qW1;%QLA-CXZN#q#o(5n?#)1QrFJx#Wu9oBy@SF<8bQ^&+pi`I(vUcm8QvTs zvwrFuqm~eh{26IZdMb#t1;`9sGYi>SkB}ZH>;!bo+MNxM<@ElP&EWtWx?f!C9}<vLnJX^zOKDH%E*=y7j(Uiq~d)kpB++4R%$-Te| z{7XrxRsI1B|KrFz7OFwCL_km_3P$q5;G9wDl4HY_vbI^laGSq6IHl^(9oO9=H9Z15 z1S6c%$5bgG@bQCgDB{pA56|}h1lmmv3`pF&5XG=+W=X0xwJRw_w_9LMwQGPEtX!7~ zrf4R00gP)vdy^MUaJx|0PXZnblw%2%US)drX0ri#oLYiE#7y%Dm2v*igMvmk*cLVh zJW+yNJgjXS4ewYZCmMFOakhK`T^|;m6vUbUIQyQWDSOqPYbKq4u70b44+ZaOc-&yt-C)2}UA^e66Ms^pA_rEeiMmG+gpPsEi zi^5^1s2yBT)yWmap@jW1u1y*SFb{pkhPqM5AUD&xfS3`==o zhahs=Ya^I9l|Z|ZNJk{a0!Yr6<>-tew*Rc%qz{BkSV)*C%dFPe17-k^_Cu7322IQ1F zW+u@`?TXte+`%T}I=mi&<`H(aH@XDcLRMT^76Ip_H=MJ8X{5R_j02HwR-W5|JJ63o zG#x<@UuS}J(6cY`3S7aHm{xB@8Mf>lQdzqbG2EH0GFR)sTxg+75%CB7iHC8bdKldW zCWR5qZ5B9Nmm>`@h0%N2lZTA2;p}0G*LV*wAJ1;)j~NY!C(%!aSo|ljIoq#+lpK{h zX~1!yAHT{9YCgZk&8=AQyts5fO)-?+H4~}*Fv}EX5M$Vx0P{$V@Bw%yjlup4Ylg#c z3yK?Icq9N!e+q=0T1d8Td|J^lR?pIa3LOWZRvut|GHn#^{56)8i;@SGlt4>f60-UR z|8xV%+^~|HC*C=j6r)!S;__kOa8Jkiq68QWmi8H%RDhRI7s*+Oe8(I$`>-=kNg2$GoS5Z5$OAF!7B~DGyK5bcu7^vYsoe)YXVl}A11IKie+0k991KubjXW$9P3P#1f=zUrJK+f3Aeb?s z0Iv>C<3(K24O_$ap_EI&wvSvrqR2ban+v|EX1ZBEAG%e{PDqhb35GCf87qVN$}29= zdCZ2%4~Uj1)jPeb;=3sjdUnHHn+_BHmG&2qf5C6ypVFp?!}UGInEMUD@j>m-p>l)~ z(&wqiVU)w4kPfkAnVca@H-rhFrW6(traMkC5mcgszb;LIL3Js=RqD!PfK&O-0=ERF zZ5>i~!N}xyXe4(cdDROqUO5Ji2I0>>50HX_N!~T^Qloen3l7(1b=_zQ7RaR}4Z&nZ zGYqF!$il~9;`<1JaYx93v15+O-8$oKawPiiAL+e?1?jpC?SH%|J~&&hjHI9aY&Ohz zEKY#5RgjPtTtM`nC8l(vC_2=E?!E zyo_KU^yz6g=D-jcnDtCc7y+ujaYwey9YV@^F6l?&@V8`#T#tZFwZarWy097y7ScQSt{MlI!xb4k zfw6Pwbkc_$ziS=7k-I&UUAK+j=m`1KYh(a!ga)0>BjBmSo7MP`unSrmjX6kH2{4Ha z(#<=V){K~V0Cyp%W*&s#KwsSUmlO!b`zf-)_WKFZV;c&b$OkT!jwFJ8dBv`iWsy}| zW0^*3G!ZhVULix}1|5P%5MVTp4zzj+@ZJJHt<$IdYA|KDK8V6yYNzv7y?tqtsO&v*61U zrIU~=J#t8mBKyMtT<|x@K;xc*a%WRLQjW+SyXe%H0?Xd#7ee`{_?X!x4fWvRYe`ik@;1y zG*Gv_F;h5!T#N5OUz|qo5*hD-Zz|9sIeX#iU#nr`vr2EjN*6f|)lJYqSK(oXtN8k|3z%xCoy@>qTbupBTkOs1h) z;GZvpyz=Lq6$-Qg4x%BCXFqzK_FK40Dk5Xcy+qGcfbQ(Y+bYo{Hhz zPP~g&Zl@>o&Gmz(2Sip^2${r0bLb4|cLwR{n8FJn9)*q=IQUNgO5N!QThH+@ZDrk> zCus1$$W-p)l8ANPCgxf5cqy(=2Bn;qPka$^L4g7h&70G2uD44s8z$P zhHDypzk^{Y2x6qBA_F6oEcbn3TXk3qU_=k`J$laVXdE&$C%Itq=;VP>Pv_Hv{WS-k zL$eC$oa?YUv21S`9-f6FRJP?w4okGD12EEVKg)_bU)ZX*)4r|DqIy&?nMp@ROV};P zv3c)&dgrZng=#D!P^GV%{n{f3+D-)OF<>oC-=czV@y7z2_IpAD`*9MI zI}X`<)E{`dme%Ev@x!f*b)2&-vlYfKk->BLDh?TonBRN34-xy^ih(H|ABcv)2#G@h zH1z&>nAv@qI6C44enHz;Pp6M}#m)57;*=2%d@(2@K@J(vG@AGjkT$38D1d47=?+l| zP~THrUzt@)2Nzm^1Cs6ckaR}``H)Qox9b&oE{r1&K*g3#Aj4^)9;bYuy&oyE{@x)! zmG@?@ISsl$1*0;i;uzLEn@og!yaMK#gY*DB$b<3qdUKd|(}O7u{N%gkx$q1P-NyF& z6!^vuC!8;Fhj|XrC-+$xfi)zZ_pPR<;M(Aot?(XqF^>VW?VZpmhry6-CP(2=I-@`~ z{)ESkONC&0AZlNQ#EWq`V=YN){>LFRq^&H^+J=U~N%9dG!AMXB0|ZSWFG`>Lp{w!) z>8Xn)ccqUXAOcY_%othKD?`31cCm>Bs!+xMsT5j4J>Nhasrtx1j)dCq^yFXq*RFXk zgzqwh7MZHSXgTy>9>IJvcY*&1;_X+WXR&^>y61}UZZ%Y8O`C@!JvsXiut-Cxy5Rz@vD~T8d-an+-hd@vN>*RnrFi| zE!KB>$vt~>r$>vmSv~^FSSzL0b`RwD&X2Rl2Vo!{2?3hm{~hh=;pZI21o5ZVg$9ep z-y#v@0Q%EC(4w>vnSCRzd#kyk%xUtR>A~;X&@{)Qgu)kPmgD}l zQBbvQ>S6YhQ?G`EpW<)>#ayIW9RSmn$9mY~Ur8F!q=)f^@GYQ1sQw3C>0=wn0p_eC zXed1qf!{~^i;f=P{EZ`f61s15!PI8}2VV&YH^J#4{N*&e) zeuRBNoP=(q&IE)^JRD2_fli((u7_4*s9krl`5b#^nYs}rGJ32xmUrjJY< z>%8=Itn^{V7I!SsT*)APYJ z|9?Ea4O|ZP{{R1Fb4IzzOifEP)NiBGA=Z>OOm0t`tx~BbL_$t&rK0Q{mz&cFZ89du zWQS5o(o&bpNu*zryKZ!IU7}>Vxl+2*-S7FneEF-T5Q10Eo`FSgbun&#W{_+lWs@{2ifgnz=cwX6t1SHok5hlq< zENnXy{Oz$v_UxfgYC$L80Z-HkKBDvyNwVJ~$D}ESW}d>eMj^4gJBv0{J>x{le00U0 zdG=SXBs-c32d>u9W@sbRfWjnUF)Y zWFLzf{o*QX>}~2RD)eR?=NC$=WcM!#UMp4RK5 z>CKDxcwjx_b$@!W*zQ)_X(20nn~fsO$2Z33)Wq9aB*k_f=;)uBz(aFD1kNd*U3#KB zt5OIg2}%PA-YH$PMJKbs`FPpI{jZ1o{_lda&{*4bCClCYkzO{ce$P(k4HYdpYYXUm zeNR=sBH)b~f$|hil7^{^L<;t+AI9g)vXex!?ABf+Ft|`bRD@?B%9|cIf5&UI*leQBt5V|9g4qIfc z)>9i~ZSgY6TpeWEo*0)La>df=if~UxfcwX%XEl8nWIFa=GMg40{YsU2x?pbJ%DoGE ze;CslUVdWl;e-I+;ZO2}Jmfoulfr#u$28##b=wWAj!HGT=RTz4tAG%kV;*@;wMTC> z{n_Aa4xLk&2wa3gDB$~rLn&S*`i#;g2XlTlQ@?1zBxHdVxJ&QpmnrsPpJZONeO}pB zdgIU;$4P}zrZ{uIU+BNsZHp(fYq{HoAnCpVBA=gA*)z)5%&?y)yD-Xl#Rk2Fr#zB- z5|P1!lL9bB&{%;N?~YX+2yXrKui?>-8!sJI{HHef(Di~Ix47-p&Jpt@1XP;bQuCz6 zm?VCnfHd*9y!NZUOlfa*_6}WLijOkmzxXjcd+P&7wmR>D!;H^q>PPY(q&e#rX&IVO zi-9fWy*(z`K1-Ha1qCRD22Hi<4HNp@HCz5+?e%2y@&0q|u7C0zr%oVSu0s1z+0}_E zN1#a_&x;Nx#kEtgJoQ}0@sArHx~%Jbm9PCXro_GPpF5li2mIICdTIX)(z&K@Oc?MY zn34MkH`}6w@@m!^^y6@uE7r7|P$(Te|t6H}-wDZd}_c%xCf=k(Arav7w{lynsiI2c4?UHn?%T&7-7#{wk72zVR~JvEuZ& zUqsYyu41`H09axP~LuAzSGn!^WtBhr}&Q>28Kj5k13sVA-OsC^6jZn z@s|^(Zk(6a+i6{lq!=x_?Fi=KLC>xR;K zw%PBC++yLy4Wu2QlJnhK7fo@|za+Py1Z*4|TG8gdms7mc&dI)-s*D)<#43f_?=1#|7Q4R9OB zmKBbH9Cd?p+Lxp(8JV#URXZ3`nC+|N{xFNw!w5Id;-U;06Bp@_@v>G?-P{}G^uwZu zQ%Oe1vzz47jA0J6pxbd$fpM0gm{M1crbQV@9}Kwo z%?@y^86iA&;cN5rw5-x)HQ_VEaymqgac`EbSM$cy;BVEvVS7u^7>!LS0~U=RGdi*H z;@igy{)x83XN3*`5_4OIJmE&TYH6ybNO(MIX2(C6K-V3nIyY-}2#RC77@J~RFe9dQ z%!q!YfsB(37y2U8qgZ`ym&!uUP@sKuv1yp`bwemmW%y_uWP+Hp zTFBUGpwtyE|G!UTjKtammtreAB+`9~eF@a9Bkr zn<>x{$b6K*n!P&%MvG@RdU%JXvM`)VvI{IJ98F3`(2YaMIeZN_n$O;-P0C>F@w{mn z_}SN;#;z|-nx5Bx|0RMv|8AY0Zsg*IJ9#7Pa#(r5ui)WBMbI<}Kr$8}QeQ$kNbDHo zg;Hhw2c#;v?ZNPEQR}Z$Cf!f7_0BVR?_{)RZ;;yLqq*aeZfd=0#xhTu65?Tz*czUS z8-&dYulQG6%7|k?aH;#SP?R9{^#Z9wVye7Kws?& ziZtj@Pc&xB9T>)9%NW?iG90z*20bdbkmk2Q0PP2xlCFMwF6Pb5DNdfI^@uY7Acbrv z^Z+D$6YnU7S2Q7&Z0NkeWgzf0$_3@6=yi|xk6H8G@}PSH6X!y#m`YEgIe9h}hmI)&S*uJyFVi5R_qgh0f=E%z*9XNB5pC1m-3Vi(0$4^hF zzS{g6_NI<)rss{f5?bCFuX~gHv&$%pW~PFww6)e4-x7BM)5|Va6A-2ET#bGtV%yI1 zpX(P_q?+?}<+g68$reZpFI0Y>0uKLWLa$!lNUh`0dUMGDVSQ(rvN+)NWwRI3jRSz6 z%N!Rj-x{DY+-=n=RFUC}y@2}DVur*TbVM4oE}K&r#gfm|P&j&&WiS6-)F?xt*b+_` z4Gi@;hje!u-(`k3Ar}Lz|KYt~Y&lYo-WTt0KEb=+-~8a?$q&39?o;&#qG%V;r~iQo zM)U+(iK453lYWz$hq4p}FeOA2ezoPn8keFzygbK?hvEa?Ut#26fC9N+)*MMZD4Z2* zqLEbyEL1n9?n{LeJ)`Y7y5Dr8ZNiN&wpQN=0Rd$c{q9|4oDcC~#A4t0eM}Td8F#au zA1@rbNngjBK+Mv*{GnLRkwk550nRnh;T6n0^#>uFqV zzGe}IjrKpAn?hXQ$R3Swcg$5VB%KJOz9zc5Ly&fha29jkelW|(#s$4%_sP?GQdk`s zI^Sf;(}KCVfa1r%xAh265k4C@=sjNEyvC2ZZIN`cXGfbAj@g-9Q%WPw`F6#Idf0gl zkG~>hqNfU-(WvjYwW2FR>sb?Fh$Ta}#2dU9V<>?&B8^XE7aNSP_eCcrWLIE;wOG~t zXF6p580NUOZr{zzecO>7i}Wtc;(8@cOjP$QP63Nsro|_Dc@K_lJAs388(h(UnqbYx zDx)m>!$Kbm`|~m&GNr9W@t-D)Zff|VRO4!LWVBY-vqGPAhG&ILI2~Bx-%~VI>3S$> zrC)M&_Z{c_$&i!KpoUucJ2igLP|M!8yk2ymIq4k9e0ML~8?^-dwVw_^$wj$8%nF=*LoaLZ;3K;;#6EaNyy@49?g4ytgfT#Q1y2=EI4L+McMuRmy+4hh1Tr|8sssp zK;sqNl+H``9P+V{dxpH+SxR!pDe@6$DtVCRgS<`^borJ75N*vlW-E@`oMv?4Zs6_N zqwla=V1C!V(ii&1&4pA)*#WEB8s6YIR1d)%&-`h3eilxt1y4*4ED4Ch#9^3u`a}hb zzNPQq>-JsynrZe_Vd8Xjdy>A;^0;*3o(Kb{BQ5=v?X*3u1!Cf?z)@!cN4^)IwDMS+ z2&NgHzf8E^4Wd+1Lo`Up&XluzB9yD(u6k}H*92$3EX=6dy{%OXm|4Xy+UQqzT{_ka z0i{W`>v220{VfI$nl9-K{KqI@T0o}Bp7>O>MbLe#030Jx1;6p{47^F)Kqi!4fi6Rn zAd^5Me~ICB=k*7=q_6g^vVN%SZ2GkCOy2pq36 zUHoDiRt?WRRw*e=sCl2+?&A{-j(s>a5p7&YUP;7gHfvFC0FOQh%4_of*lCX8ywZuh z>x3M1IRCKuc^D4mmTPc_nzJiVy4NqvqnKe?Te0N|EQBwzb31H$p~^nCZAsG&vKl7s zu^Q~*6z`Rip$2a1Xtdt!`jC# z{u;`A`M~={PPMn6FS^)M*Dz7UA>#L?QG!eTX_V}Ol=pe{?*k&d%=osb_P+1zFIb&} zE2v9k6?|V;nYZ~B+5*JeFh2gVyjC1+*lp>wZsE3P*okoUIGn$V9pi|Pgn#%%El2c@ zt`yZ}dRI%ytlei*06O`Kf$gbobRO;Rq6{$VAtDEHw8{m_^wHbOqNSzzDClzXv0dDI z71r!294pqyU7Zsbt-?+In-Ru0oF%z+U8^1`1G-lI6o0wsUZ;P<#(J`jGE5_m1d~sb z@wSphZHaf<3h++ko_yBRxtUoGA1JgffY&pJ;+d4TdH;&?r6U4PBq^9KK{KJYUe8KJSkWruMyEN&#@A=Y=bCsd zJh;NhLt8WzO`Ir-Z?zcXRPPOXnt#zgA~e-bk{FZ%mNEn{ZUIwGxSq96wC5r+s=!T2 zhkRqNKp=OO9ezyIw?%#bT-P2fBB5veTZ~#w2s1xW9NFf+{*rnlTwq~v?1%}mk`Q#o zOlC!v8@O)dW^0PDH!Ncon=QSu^XcuVtPwH=u%@tL=d&HVW+RjcpS{5qo)Hr*=#SYS z-hH?u=(P)DB$x(cZ9+bX0o3QkfL)?95?lGC&}nU^x3=7+Gs9u!8cl=7CXk^`ScBk- zv6ub8#@l(IZTpQLzRj1?FdDiNG6xQ6npO1pQ=Y(}q;iZ+tMQ~+&ZeQJ<)XyQ+5+eE zye`XO1z9^muW~-@&UHYNn(x+zwymQJoT4A8~r# zINkSBh{1Lux;(qKy)N4<@)-I5eoW?_l7Y8 zjDeNXd+KuPS4)fhxa|SJ{s;&1>_Apu?3Iwh_Ara2LZw&pbp51qnNEr27o#QMh7x_-j@N|44ghnE%e3FUavbofK-x7i2VOfC^b z)WFyChC#>H!+Nvk($sI`l9QM;*HT7_D1n~BCxY_GUc$z$s0Y{S!NiMyqGY}jo#)*V7S|v35IZx(Tu5|H zZU@-T(-WHiA@D7@fY4Qq{r+KJn4ZE>AdgKk}6f;8$){80+R=ExfV9z;K3 zp-)O*>N`sw4WAewbKLdAwn3noJ#Jx+Bp}gLCo>?X{1l&5a4KTkjpjtO{b60}`A8;O z3~(tI!xfY=>0LDiJs69g-|`B$@GBvj*nL9}7P)4>Y^rEn+wRdgN2yEZ>`S~K-UcBw z<4$l#l5@o?5wCSEi?k<|fK8^xX8o{e?B;St>-pc8{2>NM6KBZ+Haw~kZgq6|SVc`QrS8W`*!fn;s9bkc{%i}fAF z3WQj)P`~OG@4Zpakxk-FinQ0TEB*_2e2obuBnO zs6Ia;6-KkxC%a=8Q)Q&22EZt4%5C@3(j>iw!L3J+Ej)2Xw86L0Lu;O;F1#XFVihRZP15rF>o-X#$Ye?IqqQRhJbPxG>Yjxcox# zw7<2VJcJsADN`$~rA3lblCXf$U0>OK|K$kZtu#bP8t0vitRS!3hlETj+;**#BpTDj zE#d+hv-3YqlH%gbA|DK#4^QND`Q@m!ObTG3xar8~?6<4z_14}A2D55^<6U!BB=;lE zr!nfiAb!z*aZAogMe3tC3b?Z{bxV7Y^MRmnWo!-Eqa@sJx08TBLI&Oc&oCPxNmAS-Vz7lQ zwj<3CCd5bpF?OC|!YB%reN~4K?TcXuy)Wcs4H8Nukssh0e`dEC$}x)6EVLGAGiXKy zM}1bDpxx(5*zZ!5m<3BuA0ZfPUY+7z;RY0JLA_I5=;N|leS}}K>S27; z&<|L*aaqPCf6g0DDyGU!|IJ(r>Rv{P;uLBTW&2Nx%|~4)2_$s0+C=5Ruc+(;L&EbH zbW)7ph!cZ(1eqL`4LrbAKPj+MW&kJ|iJ#4AA_EDL#0-Tcz=M$Dqrd+$12@ma{Amj; z9YeH^SRb6;-SOwjec7_-C>4&wnLoP&mq#R_Kv%BqY1Oa}k&Zy5TR}I(HmK56QV%Rl zJ#Si*v@pf1?Qnu+pi^w?TLlcB83=W#(VTCgH7(RX@2kYNfd`0akMF;JqTboLJxo%# zMB_oD?hykVu^t6&fKymFL{J>|{g=_D|0?AbNe#+brvHk`V{%m z3K`F~A$eDDGW&Aax1qU_VzA=8p@)9QC%(=LAH`oC;yTgr0vh(rhH7m5K={NlKF{9( zL;^oSQOl}>E_``yf=0w0DlEjQ!7J7XP%1kV)z5+gRKu2$r5|6X%V{e}iJry=?nS%- z$i1Z~OG?zxmCaBAReZ^F?X`MKts|_iMbMZ3iPRBETJ$p$mWtmso+ZBh5MZo zmkN?ek0$Gy;SrQ5aD!{U&hqodNWoIgrj20J6eLLul$``==Id9f!pkd5C*{IUMjSkk zZrFb6W~v(fMsoUW5ef{S5Qr~9hsm$Q-oUZ z59u>7o8!bJi3VvRvLZ$R$=+NYU49YFlZ2!Wi^#<*SgpXDJn!!7CMJofSiZS03QXyfv|-cXizl{tQwB^gOiJp;*yYd<|xU?hW9syh)Nz;y9m z!W1K5A^!$U5FG2Y@P#znk4QWwbVd>QbcwUuw7>DigCHEH=O3h(j;tk?T_zPkdyuZ}mXo}L!gEmRktHt_y1&Cb zWq+-pK15opc~T{JfUFFnEG6enUiL>q!N^N4awNEsHR`%uq@O+m5ob{qD_0X-V-%4s zfZGxA(N!H6Klsgew#2yzG1Py?2SRLK@^Lj)rZ^BI%6c zrGSpw@YNsl_WLpFf^QyeTjQiG_z+7bnCZ58b-(fIN9~&GliM3n)oJFDu79uvzeJ(f zhcOi=DFeU24^+=oOqY!~*m6G9LLT6|5aXFyf}4-hyRpcX*1L#i$;&<;;YP#gnw6lc zn0;1zBA4T1BAV|ep99RCI$F%WXpXBC1a#~n8?j-m8C~A;mQUz4%dFKAzXsI+MIiTIEd13)!Ie{-hIocan=t9s^C5tfZSiml%vK z54EDe1Z$U2`1fI*CX*9_I7tT!G^u_}elnQAg>F(iGjbOGT)s0Q?2O~kQq46f>>7WE zRT3jNZ}%i7lfx+_zfO((cWK`$SAjcLPt7edlfhkOB3#4?B7Evs`}sFLw+U>+!&Ne1R5$qRZwoAfKvqYXvF({-sw0q zq6mq}_bB)VQLYCbNoEI7ax!42OkhVhIVRIakSQ<51ANtQZg- zaFpTjf#B!&J8gp}@Qj~JOEwGY({@@UN9mOuW!z+tys*f%BmVO3ml+oOW9$Q4lGF8W zET$xbaxs=`+!gIdeVi0)x-bO?293SE{=B^9@}?)nXRL^btN(GKWX@Qo5{2}<<+MvN z<7tlBj^56y`s8$e#Lh>_Qj{ykNY!MhY#1Lb=pkeGvI7kQI~O-PVoCbatCYKzY($33 zrW#7?q#ZUr$F|$_^i8}w6CVrx_g^YYu%MI1rA5#rn7dA-j5x%s(2$HTylDtY&Wk?j z#^D4z1onqd!DC`MGZl`9$Dk$@u1 zeE&Um{oXkRrvk2;h+l*tE(vZO{!*>s^(k<4BBq@{Wb`v z0KS&4QNHhZYrR9=zD$q+!`P0bf)=g$q!U6RAS(z^dQ-)!oeAx&U`0qs6yQuE=TzV- zvJEo}l?>yW!pIa*qoaE!U(X5zvj< zY}yzL;6pbH(4fN*hMKg4ctU@V2mB@>2@cv$zk#gTeU;M&*7sH3$@!5W?GTqv#4%PLK2;Q9Eld?jmS!D)J`%Q5^mCB&^jG~O z(f9t~lZt^@a<2)HgX%2H;wyr7m%mGr{I&u8*jlS_i>%GkA)96)ZPUHxzd-!7=UA{< zYioAM##5Vs3&XRDUuK%*AEFf0YxBIGE-?6qVUi`cBK*cL4I7 zQ1P7dR#h85M96fnU~$8m+{{azmj7XHShLG&KAsA4+Qy_A!stLq8?dt{_q8$Hmn?^T z@$zz$NpVeVX8=i-H+I`i@#-cU3nk@E6u)|CJCUq`mjl~NGL1C7R=SZzq~}d}^+%g{ z-u*BS#MG8z+sA-9ryPPE@Q4&xCOsrh-An=B2t5S1ghF(=DmH#jVx-8%6Khw^9|3`C4z6p&jTY}5HodM7)1qvRiGJ54m1HqZr%65*h{F~Q;d6FU9~Y>%+Q*v?8sMmyy7iID3Qg4$4>4IjUCA$4X-yhSTGUG z4pIY}P5xH)za$G2HtJ%s8}KI+R9z9MPmaQ-ZLZYYiF<{e zPGW^OvMl_qaz^RHc$?g@%2PW`A&1bmTUM4j%8UPzEKENs0+>95fIF%9lhXKvMTGD{ zToe^hexkv*;7?JNInBA+p7~>a;QO_`F}%u+?(l(wS*`cRkTnCaV#6692Gp>b)*+01 zWWHDmZHX>^up}EWB<5Z@_s^9l6bRK4?JB!M1#Vh+8HM~DZw==zjIJmVY3PhdV^yfy zXsF3FUvlA!C*PBU0Z&oo29>$gA}+23IfXx$b_dK^+sCDW!91W>0l^`?&3?6;v?p%E z8uLAw+ri^`n6sS@<_!rktKIKi{bGc8cho5D5SDheI>j$)nVM#@xcf{se%t^sLBWjwzp5Tx#)1sjGD zfdQClL?I;I)Vt41OFmZjY=n~Tq9tm2BO{Wabzo1w6tYs;-rGYZCnE&<9fniV{wXac z*xwL;fJ8M3MM`B4JFupx@A$p!bpGTXXF)(8?ZAF1qyUEAgon5*VX{e#p}r+6w&kMn z?b*6m1J^#U?q~{L7fthv~gZN${=NQ zXdRRf?d=}f0?xPUL7d?ZyXpyN9c_Yx);Y#1UZ-DeKXUYOo0 zmx6Q_aD2FFV@4xdLSsStb%!YfLiqOPM5?@-?#Kh%$;?NH!WYQi{|Pv6XHlut5Kbc! z46a!8T7p(aez)n3eFJgE5pW;yQ3S-6=w=Lk z;YC-9>evtfe!uHMGu;Rn5t={e(sx^cjVRiBjA}f#+#jlmxN34JV}(gAX|+3E`%>6cngU`1ME3MLI97+F2nGvq!Mw>MCu zA}5B#d_w2p-VPZWe-%0V2>3`=YSbO1{dI8_$T}T1h017AO3Eo?UKLTB!&HRyTcdI~ z+OZ}CNyg~xSRb@QklsWM!+c9IN z&5NW!<5-#KmGJ5_s9Ydd^T3tq4g}Nu6rY(L&U8A~B5O--U3Y^C+dGz>8`)n(hkSS= zdz9GHd})GEKINiJi*p&wL5WDM`_R@#0zCFhy}aMbz!^2l>h7gob{xF8N7KR+ycU9T z5GSl`q5H|Tm)$@60nfHKwBsC@}qxPIBB^>*dHAAio1pq2( zMz$1vjtml6QqH%wh(HAnCEd{SIUEvu)%RcBAp{PK*_WI`<5E=$uD2hy+&i;%XG$V^ zI`_FVPyH&9?%ORxCRIjZXRNn)JhSiY#YkI1+l1&;SUkZJCm~D%ITGU@X&G43R1TR_ zKiuHG{jS*$-7!zR#6fX#mxDMea++#NaiLRqd&49)=4!#7dZ@_h0%Z<=XzUbYl}GfK zRr`J33}ez|1C(FHK6JM+Y5e8wC|D+251}9p3tCKm;p7~MK?E-8{4d}C7@5<*m zMCYcfx67*wROb*6rzI}W$Sr(9Vtd|}x;V0-AsyFHN91)qT2EU;G4y7Y&&OFr>=5$! zDsUfFlTBA=;${(A{_mEhvtqJGEml3h`hT-$ZN*g~2Tt%nAcp5_$iMjdNR%m`klC_F zC;b55nRbD2S=KU4xEbb-->PY9mjh7?_eh|E0;Z{aPJyvig)s@ps9BZqmq3sqh(EJe8#H10_msckiCO>UVB z+tg0z{lyF$(qdJ>;>nZlghD291R!FPBnMM@crsR3%ZU0V=h=prFmQrq9vk0$J(*BK z-$4m^b`qli98}OXKW=q3V8n2cAvqX>53W5d#KiN0*6bgKlHaOBg?LAeRNyl_q2kj? zWwoGpa*r=~!W*xddZp~$IBP4`bPU)0m!8_3nDvR!T6d`7sX}G37xj$UpB97Q=MulEvy%_5oSwX2xoLBBpf{pSG4wcE_BCL7{9Bi-<7k85 zmrE6Uxk$!gu?m2iFsSm^h|So5Rvzn~XknEH9EgB{V|XkHiH6u)3Aw&nl}%S9bDgHC z1nI$8aink6?sq)qv0v!KzwqfOGTsqo25b`s39Gv~KbS5mDZDg<^a6vNlUwkeh32+y z0ILLIoU#f~l)_uNH#BzP#WgZCMh$9Q@OR&#IL>4#cba2>%Fd;>D@aRe8{x;bF_kkL za>a#{E^`gJi$I(`-fn$3B?ZFrv9Xq!MNjKvWlvH5 zhw#H6Tb)MEv-NO_Ui5H*qL-hT7}G@tT8519oZTDoupP$9yGL?A#7yMI*~$i@SC+FB zKaR_qit}e$i}E%5Hin1^IM9u4+%{qTE%nJQNT~(BL|O^FhzYzX zl5}+$vVKtxXd{b2gZdJzOLECmZIL%R*XYH(zT+jc&2JJyJw`Wz(l{l>IE-!nflQ8Z zVkl2#C*lE*!%!CJpVNYNE^C80dD(03o(>IUga9e>YW^0CR1ZqBMfB%f6IkSW{)1^H z-mmX>TAo^oDp;;XlBLjG#Nu>r7VUNfT7=R^z?Gnn2#BYt(|Rk%g736vSR}`Um$QB2 zvfQQ)=CLl92&2FDPMx5>e7ilTIeG&66a9wiSBZWv6|r!Z!=|u?sQApD)7tv0{hgZJ zo}Mwv&3${*<~&)Ft#c)|3mgeDsUk*0m>EF5Dhy|w+^LC(TD|zxhV=&kay06TBu1C` z8>em@^Qenu$S|9{4OxIxKNz{W)YnSnu*3;Mo3jNkB8os_+N1R0*{3W{1yt1NSMM#w zu)`Ho%(QReKr0v72GX8;=a1f~y{qMg{YGRNH@%1Ak)!gYamE*nhyn|*9an4^8{ z=vqZp#(gBex}tI&Ab6&JA{x&<*=3%}`L{~KOwolLek=RBeNf~}fBeWyrq>dfKVk6) z(~{@TlwaAIf{4lm3@NbZvd`ND6u9F`!v~`~3|a6iH+Cf2m3kCnhZ?Pxb>t2Hf&oW^ zgA7Zy=q6Lh^Rs)dycH%b%!tk;A%NH;Hz)FZcJh4o7YjNMp0mF?olnGePW&YYtUgd2 ztVRLEKkla-353L40ULNMFqkScLr)yD=nGDN?X*3G!eZzFKQMKm5Z zTA>9e(Oqvz6&EaqMSuBPNFOt=7f?CIIw==g$xWEBFU8biXK0<=? zV}n_9X9AuGQ4SF(OqyXW+~VO4t>bR~bii=;)>ifSfT%(9-%?E4GkIeMog3@g_yT=& zlm(8q*)O-PA4G@7JMj)uQSf+YpUE5Fi!sS=D{%NeyR5*G6&sVq;ulJl594*?y!%q) zlzhR?F1INbQ>h1PL8{ z^HhI4j~9GkRz=*^W_8+%@QPT(?I&wi_P1x4?Jymy%FXz3^t@;CBUUNpk{a1wb?*A?Ynkxph#-l(OT#Ek%f*ZShL=NRRt1?{^x z)>YUaRGdNs239?USpU96phY?7_etiz9rg-(EO{K5*;s&%jhFap>}{BDKk6YYgR2y+ zkrMQRW`Zld%!7P1-bEYJMGG_G{>UqW_H$_h;siq+d@}oqnl6g2vZ)tCnI+R)covn1 zvJD>6G!nFF1{>0$#7<+F70S^SKgA22?9e?bcquFqKsIbVz9b$n6C$Vh<7I(aJPEjqQjK#ZpB=TZ8OSbj?9hv+q+CQ82B; zfgkM(UfxmfAw7dfI10Y~TJlq*z`VVa12}!gJe99HO`jN65(A3|19{sbTuSH-y>g{HH1)9W_+~a|gW8>1D{MPA9%Gq! zX#82|#q9{`loeXG@<}eJD;We@(13dF@z(lac|!oATtzNtgC(>{c{Q9(-~a+JP#d-x zS#Ri;x63F?*ltck$U2PDyYR&`=x^afO0%U#9v_LSzz;#k8j;H_paE{;rT5J8AsEel zJJ7q|oiRR1>A;#!z?z)@L5PVkT=>bJ#W@-RT;g=I8mwAZ> zn3>V+qu8{$0kQj0pD2elzfN5f=y``XJI!ybs`{I*li6T{1uG&KyKTtqyaB5C@>s#? zeRE0uGhJ?6Aj6mLlHPJ-;{1QM033%%PP}&CUN4fXWVFBt->t+0MkJ;DoHPGOzvwJ@ z2k+(_o5_QI%=X~;LgjWW{(|qE;aKTR6pM{Wh3DtY5FuvMNS&%7VJp|mD{qoRbN=WL zo1Y9y=t8~rpXOf47&JykO#F0}CGiAqF3l-Ph%ykLb(l8s6@8fZ8M39Rmn=mGF~srj z=lfFM4d0u&$NL5_{*1!NBs@mMByP})G`JMc?eHMyYXSg0B?&v*=hqqeVWu1t__}2$ zh7kPa%#tM$DpOK{HK3xwq|$J)_ZpDoyeCz5oUUlK5Bq!4!J_XN5+lo&NbA>{!ya-f zdvg0|^9k;kzftteD9z3U<$-!hs9ePcOkBUC+Z#0{pihS6S_rmC?gqH|ah_Gc7Z{rN zKpfeof9D#SJn$U+;SSKUCcirmCZHM4O63{nw94(^Md{=M4qPk_T63_CB=wZ0BN5a) zhPDBJVFcxz$?a`lozImGoIe#g$A&3rGoyA1+ahUcfKO8BsE1T8Tt@S8TYHC(>U1#R zpyQh+YHx*%7dHj~70pysbwTZCTX?%!UVfp2{dQxqNP^^YDJr$gh$|~y$vVJL&V=YA zDMXtI$4nOiP?sxPH9lT}{(oU2rY7sUapgiwaWCLZLzFVGC2M_nerIxhL|k*s>D8Wo z;_B9E#k5OE?Z;W8#Gd=kNsMMrM?QSpv#ZqkLdzYl<$|r~>^b}L2 zdqBlvu+?GdUCS17AkC0N6rY-LFYWfWRj7@k5yJ_7Sza}*-=X2F^r&90iqhpwNg~iR zvzP}u{0?Vxw9V(7z(^d`p`7?_Y@8T zaN_6iA0lO!0~LaKgNutJceOrxwk^)O%neA>NI4sDE<9iUj&o@>`Y+;GZz?%So#2t=Ka&%9j!FofB)s3FWgL1{)@QIv|^j?@Gs|}hTmfg|jd&0U$c18wc zcDPDVC8#yU#qFPMij*E$yojsz*+AZd3BMMD59lMp!~&{k)Rud9v^SgE>qDRB^pXCo zKk2J2?cB4^Axj7YA{QP6_c_MB-Z|wzaIQY$(p#KE=bQ^Criguky@AONiX3^#1_X3e z$eziv_H>4)id>F60)T{nhG4Z3X(Nppm9zsK2-0jgtYs zMu#v;DhS^61#$=gSa`Z*83q06Y+pNd?>0_{%;t#}5xGCC3FtQ?;IJ4WLipYTdUtci zh7+Sbi&I}MCuUtfF5={~0m*~ek)SD`fu%>7Y^mXYaP0|8cW=bB{CMJ@!CauQNmHFI z(_VXGY?vG)iyRg{Thd-Q3K}q*^Jz!hCN!%driqDbT6a?GSuJYGqA#6x1; z`V6J|3g;so<{iSB69y$kxclEA8nqz@5I{2RZmU%wyT~yM-S%mf)+A_j>S3eS<)M@L z>ERe8*r-4D2%ldS>RToL`pFaL7@=Sw4_dN&t)B;uuIsiwwu zppiL{?>p{nplT|F>rR)BulK*~0rCgA7zJ1^j;}d@k0NJeXcX3)FhXAX5$isLbOz7t zVe8qPBKPRw{hEt->|6sq&T&WzP?2y;m)!c_)*LC*O$q>!gaYe>p|>oxu9;O9(w-7s zb(wQhqL@9Sd%e|s8mUA1?HAV*21C~+w*vwm;2p{+f(sO!gX+;By)a5n=QNKdJz}6Z z*e?tR_*O+>h@@AMGMJ@*v{MDRl#Uzha^OncrSc}5z#tM=p{AEC=Uj@TvfvjgnM31I z@xVGJX5_(WqzsXlw6WGy#L*;GYG}p@2-Jlk&rjRJHAjDPfpOW&1s&}PNkJU~%UuG_ z?2C$3i*mu*oF!IDgIAYq_IExen*1AhNY$ZLqH2CWV=HCe?w$ZN=IWkA{21^ z2V(%ybxLf*E6V7QiSE;PSMT9gm}RckdZvP1yYVwy90a;#Rm`qI=*K5Q_%NJ?1&+Q4 z9fDL+V91US4bu#A#Ce8|rsLHRbCz&7wi`J3l7*Syd`tEpr`6bcFq$Jl=U6Wb^PHT6etq%yJ97tGM#I4e{bcYq@~C6JT-_vCt;&0)zQ&6XAY)w^0t^27AAtE>Pf z4`$z5A75OhADZ;YI2spjd#Uq{=Jtq5`LgZgN2GDO$DaEy;}WS&b9};|>@rX{vUUEG=+o1jhdFC>kxOM;o}JTJK%(%$HIIb6)+uI=xZTaRWCS42Bi^!%kguCSDO@<9|v z+OHWw3zl+4oM{#shFha@!Yp2T-@(aPhAyJQAo)%7YQtjW0)`5iCgn_oOV|uKiy}v- z%s=+#p~hjhLf+cV4n+x8E4>US73<6pSu=K=VE%=pKieIy9z&I(;+2P5g}%p{S9*!F zr(Zbs8zlsgejI(VSO+_%k*NS!DO*lA!(?#?AJYl6)H~I1{rONRJ}Ohv*aC{Lo5X6P z!&xxS_--|2l;e4pKz*-&f1xpjEF5{^@`vH96FRs%unej8n0?)j*Lc)PL2F;g-HHa_m z$+CqPZDmh7->9r949S( zH2bd-iEen%WU7y8mDQz~!2}Ab>nJph7tsARkaBuNM6%F1V5xS8J2b4A+D1r`s5>Y8H5{=`sV@SBr#q0Z2FsG=SY$a zsz}aF$Y<28WM??8r|PwCJKC2pH5__d*qUZ_U3c_XY|-+DCrBQ8PK9g%(fia!D6fP6Nn3J;x!%rTyT2HvQHnh zHZLM+ipx4UU+S*^xY@iT&4AleN-j;1qyacTsX+hLTCCUv#gN1LpjFfuiOAI;3Xz&8 z$YZ_uH1)!>IZ1b#nLHJp@)s(|7|NULIopSD=FIxeV+*VC>Q$d~l!V4bw-GL2^L=gD znNSGqj)ifVrt9C@l88vs1`Q@6$3@~r46>JlCssEbKe4?Q8lf6r6CWJgHdSR>O+>U@ znBdpT_r&>{%6~z$m+q&n%i{%8Drs$cPBDItxy3y`Uw_d%{p#GZ7XKYz1b@8Y>Tg*o z%|?&jK8E6!Oc%KpszPxKjZE16K--!qPTR0iu;~DeBh)bmmu@0BlEG1O`X#{k!Dgq6 zMN6wP@xc<-V#lyLEbR)3r{a7>7pd%-j!}`#2}u$AlIYkuy+A zJ*~@7k>C7@T>Rd@quDjU7Dk3Zq2XsMT&^E^#aoWLktsm}dPm(srG2c&G3<^8E3AaE zIfmdp;|faSf;k1QDXWGwsdffj&|3ETFDhHoM7+9(b7n;NVB}t$JQV}a;um98J5%yl zz0d#6D7(#5e3oKDH@L(AIX})cA|$&~Wp`^-)04tQ!y5NnT-af@d3(g9#f3YM5#6!e zq^X}S&7o4K_*-SCL$A%8;d1I9CWp?tnR4UQ-?kemuMpIhh$C(F#+}U!?;ifLwvW@0 zRit3s{7>0xE}k_is!&X-c+^Gnk%!eG#n!OEsc_2JM|}yu|6gs*Z$%47^xYiMZtQ;U zx7#5{HqLe5@lUzD5)^|nP-h>;BFld%=ABeQJ< zuHLBaN1Ly@59klv^DA81HB+^F&eh*_3p}e5vJ1}qT_U`2Qxg^Z$du&&;0l4UihvI( zA3B)2zFYpjCAnUov~-%Mkto~{ul@9>WPW4+FB6E5ThA^;jF6kd#uVWZR|rAqH#U0q z7tynwB*w)EJ9>3IVSzl^l6u7_f`k+_$vjZDap|B@Tvbk-QAkO?3Ip9i%)Rnk*AG{F z-gLk|u;h={B_vVcpGEA2T~Lte0MSo^=CE^UxxphgEF}uAI?Vy#zc&HXXtBRT7lA0E z&z0~sar4lK;CoIe|K~oMgq95TZ`bXSGmZ%4`k32gye?%Y;8qgh|GY_qwk^%v)8V}P zVz@H9qzOOw=_T(IGz|ABTd~ftc0vJ(l&GksVFCd_oX2f{YvqaLz^A|VVi7+O+&OX) zcY8qQ$wyaAim`edS$Y8*%1h2dEPkP#_?cUHw_^ZbGxhHD1KH@BBpo*XCc_BU(Kg75 zPoW)NqRVdk%b~Mh7Ht;@$YJ+Z?WFu|ekmO-&A7_MBleth5Rt3>g|*7r<$!34m_ zp@dcNnMeQ}##x>HE6AWm1SvjQC~V5qeAAw&B|)EK<|*94j9=h>EN-q*vPRoykGwR4ypuH(Ke=$n4s35Y zxA8{u{>`}AY#0!ldU1P1$oOQ9oWw(6EB=GZ3k^ujkeo@v0I|Q~G$+NfmoJHBj0o%` z^-sO5J*Y6)%dqzL2woX0sTf2fEq9IeIZ-i$zGkcl*>iXUIcdy;sE;DsxZLd3a3(aV zz*OHN>2TznY7Psypf?M>jxzVUy|=T}omWHcPU3x`N}KsvacM5|SRNT7MsJ7gmX&^~ zYq!BP&bQa&TImloPl+F#cYlNTix;%hg%Z5RjlBp`{fxWWv?ny#uKyzTQ}a%jBKHb{ z`8F2Ty?hv9&WaI$gyxUfpe)o)a}BC`C0gJa;3#H|t|t-?-?0nOeFM_QBlv?jmPbwp`A zzAxElrr66xjvhSWg5M+m^}qz|-h{aq^({3!Uqs_XE=Q3V&GH+7qSO|7R3g0s9@-ap4=ZC=J<{roUjkw z-M6$y7ssD3LdD#oFG7|z*{mnO>d}nf0trL?wkY&F!GKstPNB)MWic;j<@6&;eTL{S zUT3K|RYn6-;#-9G`;D=0;8OX$XO8}}kN<@il@*k_R<=sY$df4j@u7^4*3F( zYET?0QQp>#w{_h0gcvU4W+y&tahdh|T|Ul6j-+z9lnmn7sJ8{EYB|0Rk%rQ^h`;cs zwjgCBd6Qa~HJyvgtTaSc`SJL!JSRrmbEE?jAMH7B;EVX?2cORL`EP=z1eq`Vw~oVk zcAJeS&9D7m2Zd|YE^MYDQt|;A|NrJgLo6)Kjzs_uvoIs#=#+-97zy6MNIo3n!7<&{ znukLg16aXayW(7vSg*PggAC-b+$rUt7z+>fFpz0xM0|)*qy-gT8cP0YXTYudVQ+WZ z-8{c;uKgdg-nFeCUWQ(mnEvAGRHjNK=czP9aR^LWvJkhF)*{tTtXG^TiAWp&!Bt9L z5Bk|5e74J|X`hdDR$H5A6Z*{V(S_tubmSTVTLS0j9Q*XI8!#SNG~05sF=t*|CnLdo zGj7y&@#c2)@wlpGy}lGPJjyro{e^~V?@O!l6tmq{6dF$eNsaP-kjqg{p zrJEd7%}LYu%DOYJ81g#w8uvvnhUdh}X+E>)@-;z{0Vl| zDXk<4@$+{r!Rpe^D}Q|}*(_?yTR9xEKu>P&;Zwc+*g#MrD@>4_1(6sEN80i zz}Pekn1#{Nn)V>kQ`D7ZA?ieVLs@b?iAyztWZckpFOl4|PDkC609DOaAOJkR!}?v7 z^9CMWHK2dA1(rQ|iFbW>!y3Z-^pBL0VI`}J z!)wl!hC?5*J4aXjti~x$v_-F#y9mO`6dH=_do%4?X!0%UjOuuygA~5hKLYre7RBvt zKK%IX{fg!egf5~le333JLG9-4-v|0n)J#x$m!0dR3@Qg7m)6NhNGnc zGlB-J<2%K65#>;Xsb4M8&qVVyjIS(hQQUeL-yb|OD#i{effhNhtg@F8P|IbC&VtL| z`Aoq60AIdws&Xx~%luGdpRdl47~Cv}&dD!WNm>?z#egIkY!A!f%<>mvbQM*SxNM3^ zPXQxG+JgZ>jFbcd1Q}VDuevOM6eDK{&5h=W=e4I)rG(=CcsXQDL}qeScvA-w*aVL;B9`=CXUa&yituH~3=D(WdW z>a{~r;BZVVLw&_95>t#k`>5MQ{U}t>U@if%-Y7r+PcyznRGUa~JbCJU3a0nU85Yh( zVb&&y*UjqstF?G50mZWmU~rNMg5LC+Ld^yR=M1Y$?5(xx;BeWWLnbW_*co3n(qRn}x0~()$1eF{?y~y@LqpVpw+dt>O@+u=&s3>OZ z1tcViyfoYS{dD`yi@y3p#OPfF|H9Y#;Hl~G0g*|Kw3lBKdmw!+eO-K`dXpSdIu>j4 z%Db*R=OLPIQ9?LCk|2+rq|R{B1sJhCUA#X4VR>)u?4etV5C5mCS_a{k;PZ_JkXN%r^^Rij?`F~)+~a!bH}QLOn(?J zp$gvh3XN&y-3*ly#X%(ZK@78N800qNUU=E0F{vGDxNKf4s-KbwGV{*C)#&9l+8^D& z1sEBPc$nivW5S&J6LZ|po0wm0j`TTpBsRY=ZPXTgH^+p#Q4KkCz3`Gl_WW{I0@VN4 zbNCZr{kTeRisljh!m@c~k({c{GM{kbW=hK)lRq9BKXplYOR@1vY2T`o|HRGTX-X)7 z#9BnAuH|?xxiB>WhL1m*UcYx39Hr@y;V%oOH*$8|;tYlQ$kCKP*Xe)CeC;%x z59fvUkNy-fE~l8;z1d|9MfF1_e$pH{-ORV+ZWb<@^H)=JuXz=IT8=`9dG$=Qk7SD$ zhLBMj6`+X$HaxQNS$|4#k9!|kq{`Pxtkg_=CF=BD)`Eu1^Qt?JR|C(y3ZX11(73d? zPUmq>e;~J3{NQBxl=*{J_MK^P30dyq`BwRg)t3#%ty?_n7x(5wAr)~i4paU=n%+Gi z2fP3O|6n%cwA&O(^s(jMt-~5g)bh#sbho)jD;ARCM}2UYFnRpM7?-TKjlk@AvEQd_JBvdKa}@9?(GLnLFtE z8P}jO3-}sDmqopEy^W7IhfdmMIc3@bxH`1BtGZ`4Y0IL$E#!XOFq}6IbET{Hn=r?wJhPe& zjPxZSBnAZjhaZ|pxEr?)zsv?3wIbxRY*M=I5Q2*^7l^?ij6gK*_{u7$H{Kg(=bL&g zK+(J8=vy4F9oxfJGC(XtE@4T)38M4Py{5?2QJr^C-r{-X>2CYX;~hBY$S8RKG2aBH zopa%(ei$0>l_po}7zfEC+L52QLM?v zri!Zxq4%?viu)F%;I?1;?=&7g8`-?j_Apx_KrgEN2M<5IwNY>zx zgu0or_Q3R@(gE$NQqJ%d1Q`{DST^>fS0G8*KJNW9t`#WS{&y` z0vVlK&f|g>@i~U=7_k~UJ$Enuf;bbwTna49b_+?O#axWc43mN?v9hcL!?{Q9e3rvZI8}xSi$lg0` zfS;8*8Ks71OHJsOd@PBKBbWUM*$?e(+2F9m-lusCY;;^d3#)p`*hj;Jk(m1NtH1-G zkVI&RG}iU77Ig~qhqJdQ?=M^PT>YO|>3IYe*7=Bq2K1WW+ASq}J$avjmw!ZzJSeD` zpg&hOR9#`t!*-^7kbO-_unln4+bfn&!7|vDRepk@J-Iwdi&PtRN}UUi+>H!p zzKzBB&Mm_({n>#~65qkA`vlb@^ahCXE;8P$18z0#X_bcHP3<4oe&bxbpqoYMCnA)L zpr?BKRJOv-t4Xzw>sD|pZUH(!{7=n5hWm*_!=MlveH-u9Ic3JlT5;&?eq1syG{ZGK zAtQaf_1N|~8)`I;e&ws0?jF6zMm%HvaG)&dI@t#mMI=RuK{t7e?$5U>KI+%F4qP9d zum0iff&iKtkKe=Qv!D6T*Nhf_!YxR0Elv=Bl&7Yiyr=@#n zN55L7KCjjOo1@K@(GHVEN&;?N@Afs-LsqeKLn^(Q<{*qj+hNr`4%{@nEE8kv^E~U+ zv=IB9#UX>(b{vCmHPa(E#5fQlH9?pyG%}Dm|JA^y|2o$E<$tFCk=i)loqgk^kjkAW z2q&*)tysx15z7K6QRa&0$J~jfVniiABuYoR@%7xFXn<{huiDmQi$)EfO_dkfIzhF1 znIG}nf=PcxsyJ2#?aW*of(!dfGp4ru5}LUGV4Ahcvh~^F?j%(~3XAd;RF{U*C{ZzB z*L-@VQVcCJ)`PK zr~TfLEjo%?7Iwac>B8DJ=;NSEV}Vm}XL=6P@j=YXO`HnVG}v_34R411T@oPC3&e#~ z``VFNGZ#%Yv=*t4iV>teFL>wFhWud`S?&+*ALqHYL`=(Yy;Rw@(|%X^s+Q0@87@vb z*^$?nJw>Y14Q&qwrp|RVI-VW%K)76@&*~5w9>{MT6Z&3jEig1PAPmu^Ar~UI9(qP$YmoUK z3Q^gETat4tWh(Eg59b3!Fu@`!1}rJc4Xfug7-EO7$FUZGAe#Yd55xK)IbSk;n- zzKZ_w>Lp_qhPFu|uhd#9U~X)mRc5dca_|tEZdzvqw-XTPGVY`#4DPYyE@Lrh_JsrE zOUv2F$m2BJ$W3s43P{!?ga_A{PF=mN*dI4D2!bX^G+t_G!BVqLQiBFM?4xmdh^=v2 zCbNVuG(nYFWtWUAwMpZ&^%^vF`M+LWXyjMba+2p;Ojue9$T zEXUh;eMDY;;C9ZjgpJ;7JYs;%f;|j;$6HmYdjJR33DL3z?-%!v>FW-khD~WXKgXN0 z;cjnY9QC>jTz=c9-Gc;IEZO^w$II@vo15co4vs3x zD9s<1gAY+(l{LN%U~=CEOq~L(P^xl6K?vU;X5Fr!xgm( z&BOiPDz`k>Cat8-e|iflH71ePm5J36)|Cgw`RXl)++x!_wnIKL|X-|^H9fsBi!Q|LG(c@z3%!4nWPt%SEwW|{=KemEA zu7H2F@bY64o6}zvLK>4+lqT4}!!GD|8G9BtRP0q8!OZnPc&e?A^U|^%hu61pTUYh5 zaP8DjuGvl7c4ixQ_VY|Oo+ZV$FxH5fV9wW=zgEN!J-Iu$Ghwa>$h|Gj6jHBVPA+t* zB|)H4DAbi~{1{2{RBsa$#dOL-S_z#7*Lya>HKazk>tM(1 z%F(k0&ExvH0=Z+qxt%`{(@zTlkpw_|I3}*(-rM6AyjYTF7+KdCQ-2Zz0f-&p#*V}Y!Ccvd~ z;3uKt1X)dpEnjAUt)f7+@t|+&5rQewYX4PY^L9qp$w&5R&^}sp)FyzLB#kqGf`pp( z#t6fjKW#EF#|CD&pS=59Ui&7se)WR8;~S>KGNr7?2kbctiP7w4XiCo% z(i#u3TcNKfF6tFsNQJyX1m46-Wq@A4m1Ar0&&rZ1~KeR$= zE)=bhN~~t%?!%@69%&`H=I%M%ody*uulT>-uXk=0TLKW@16Wx%^_#iFrGNv7w!I8h zhW2TFnK(%?LGDd%$#R4~*oaV`Lmsk6Eva~6pp^8=o5P6tbPiKDkYCP*YgtxXq^9OaActWBC1p$tnN8Xg16p8q3 z1LoVLgY!J!irL{-j}Xpzh4xIzD4WI4IxbpqTDhUywMHq6X11Xq#GvKx!&!+#H)v0L z80>o!aiqD}`ZH&OA9!znKcQv#ge;wj58t66RAM)qZ1j`R`K}COmKC9!QQDLk9T3cN z6SCP#CX8jgv&V#sHT9ON?)zKwGV@q_y8Q$&pxsF)#Vc!?<3g(=AI_X@bo}owo_iu6 zCF{8@{`<<3X0L_;_uD&Uq4# z0%OQe_BI?b)u5hw{fk|Vq6H#jQN`{%NTz(qBI9#y;A8k;R1{|gs30^!fTyem9=e|& zV<|uYE*>U4$7C`+S{YXs;)&k){spLxz%c9tc0Kq8d(F)x6w1su;bL3C2}T+G8mm9Q z$Gn2QQ>yrAHg5lQ7xpf6W(d*x(kT>)b3{^J3nGBwJ~Tegn~YAgBC(7S1=Zj40iC!` z^qxOtgpO>8VxR|UZ;xqJHN#EpIk9;=xn_xp`Zd%$D~JzT1S9`TzHm-gXVAseKKp6R z>MZQiCywQs^?_e;L--mjM6|l`-2;l6&)Bt)=j{vz_1y_(x0U`FyfHMJ&Q4ks!kF9> zHM&M;RY%dYGw31w_Kt9Ubw6ujcHC))O7a{?VCIq)I@&Xgei#)}6=NIn?XVH3Aga9n z(-r9rwwo8*HHv&%W2WZj{@2Qhx&iaU*K(3obtkySnSB~sQVUWi;(-Vb2nKJZs%%~L zyr>qHkR^LW&hN8snvQ-3SxmRy_sZtI?d@*MP4>>T3!JRJLwkKL0IdZPB$r=1ZqA`w z8;&gK(>rC6kJ7!fvlJ(9m9-iuN4XZT;95?3Amgq zJ(ESi`(|miNv4D5j3~l`KDOK%@VHYClMWz1Z~_&TeWu12MOUsqFXD6IRFRoj5!*L+ zMg$^_eX*bwQw;W)w1s4b?7TRrb##qJU-9n6TOqHq zhpdiAZS|E=KUD$nNa*{5^a+i50oMS{lYSxJD180o1n^WeG}V^@{t7IW)~HRqWSf`E zaEOVhR(eEI6s?eXaJ(5Lp;#`)(*?R34GWV=1QD~W2Kuw~xE{Y6NZSEn3Or=ZXD1qO zWy5tOo)%369q_+|EHM$IgG~Hn<5;6jSq{ON{T^GrGgT@DQ@gc`XnFY#gEr~UIG$2& zZfIm(W0X(&?6byj7rZQx9Y5hQC4GjglHko7?oRT}y%*{7e``8KvI*EWF?eO#A~9 z|9SkmHdvk^0mP}{h;<9NNjsRCi^st_uWP~bDAhSP1d}V`Y7Pa^jE8@dXfvih;OKCX znCk@`3^WNH$m%*XtJve6r?(b7Mf&EDt4ynPO}dYEC?rf4V!rPI%Nq(El59>b5OUC# z!^9Q2g5Eo1J>u?t@wtEMx_|jcu+77oi`tF0di_?;V^;|46UaN}l6S|2*t4yYkS>GsEM`6Rg1zk#%IvJwT2vnNQuP)HxTDfXw@m08iWhv&04A0pQko$+vGI! z)K$OhT-Y}UpbYvtewK+S$GbO^E_y+};uIVE$xL&$2^I)dx?zu<;4s{;SqDq6HNl2w zpgoix4#i~rOVz(AA}J$8&~zza+g&*7eD;Ku+2cc}C4}rf_kA=_mQDU%0|DyUX~iej z*mS;Cira6}X0mA@VU` z_-%G8lu=G#S{?qHaS&GmwN}Lkb1t{NPg~5-0-q0l%*u(4-$4XY_|B+ux5Z_?JiB#7 z7g=IzL#@v{V3+CG5*hO7yG|vNq{vUNdH3Uchj#BW@SD&OV`%N$I&Rjg7K?!NVai!I zciA|XetSA@QC>%_eSduzWpKWJ*zBBg^?ebAR~G)_&s8KiN2cE7+sVe!9asg|lISr! zIdB#0efpwiJQev*D+>;8&hYgGHYP)Kq>PAI3H3D%AqCdUoUqNxQ}~ZIwX7z4E^2fJ z3dGIb6#Xnq;%r?bYjmB&t{CEI$!7t4&oQJu()d6=zspqIU*?S5QJB$W(NyNN%LxLJ zZ4$pGNhSprZ6N|emq&SBn&R4~t zC>HyZZT2ulC)zjjyaXsSq}Qni7UT!F9PA76pr6Nml{uz-)W)o+vJ3XjsdEDDUzY@y z?{FWKJM&9qNb;;hQ>P3;6x7V{(yb{J&ScnF^gE>9VK?;`rt?G8iNq|kEWw?Z-*??_ z13X=Fb8s21>TYE4L+C;;{@Nl$8hE+~Ts2@K@BUI3mIp@{$a8kTv`j)@Lt+C$R8l;z z-x`sPwMQ(7G6wo+g|(qA^OLnJ7F~YskR#wpZWqY^l7I+ zUiog()C4FiKQ~+3ArVpr`XU`)e$hkG5=X>{(qFw`%kz~behsT?>u)3)IM)X#Wx1`X z`)OBs_mqkA_QyFNFnOfT7_~F^NY5}^rsMOjeN=3H%Mwg#m3kPKT1HZVo%{tLB{PCh zG-RmBfJ*$BbQ7JJC3mC%S7h}l7bq_@jj4!!5PRXvL0kLU+=*ziq>w(LL#Hw#4AC;2 z!|YOz4|EdvCES){{eSThpeflU_#kZYR}`MS$O)I&PYI@_vXtsi(1CWSb=Pt1jNuP` z6&F@Vh8|yo!XxuM#|wm7OJPVRpi_0dRZl_Lg>_V=7WMF8?my|QezRf3fac4!Ob71V zio-I<%Kvq&Bs=0edja`cM8*e5j-X``kQ#18aVn~`bt9Xb3n2M1g}?COrPkx<-DjQD zs&s%LEQ(24g}$(VQb=`7!K=MPy+ra3bDv zFscG`%`O;7?3m~(s2OYLp6EC74o*PeJNw4GV@Cqs2zC<@@S;2ewf{(;C3P=SZfLl( zav3H^O(+tP&!StF&Ehc3`A-imxO3aak8VO|(-yJ2cfQUfqt=f7P4`r0>Oj;lefzEM zoiv3cK!wjyx!^I6Ds9SMl5aPq=9y{T5i}iKiZ25Ip|lkR1YKg`R(lMyHL^YsMMoJ>h0QMJ)Wt_e8eN z$-4WEKh@D=O38Tz2#|7k_oM{EYGA@pC0)Z(amy7BvGCcFWLj z()l7ALz(eMuq}BdAvz}HhG>A1!a_q=mMNLHj;M%$_%c&x#>r-KD|w3Agk(<%)}a(g zly&=W0tpiFIIdolK3vH=FJvYvwS!Bk3tDjpRkt7KUZxVo3ZaDp;+B|}_WZLa)Cw<+ z_H294D<%_zWPI&b;`Q+P^18AJ+7avHd1TYND>=QmblH0gVk!_unxr`7=oxR%+|Er2 zc~ZjBgk#Qpo)e}cSN}k(@-jR>m)) z*}eyhNSVN$x&d`#r7VeTr5trQ6cfx9w&*&hLu5i8lmh$+VXOYMAr6^7=2qxfu0Ld$ zue5ni-~|vdis-Hur{d-^%v~yAs&5M=*X@?2g7MAfTGwZj@5U^z4-UVvM&yrr2LmT3 zU9Yxz`#@moOyhKYs>#k4yYyh409+60GZ$E*GzN`It!jvvqdvfF_}gflbh2s{MWwrU zl{+tws?brP+zbXhDFDpJ+8>QiNLTD@z$@Fa&nBdNbvCAwm)W*PS9#5(;=bkU^ARuT zaqKh}9+2`e&dROIHHey=#(D6b_SPg4@ule8sIKUd{g)unt8=JR9W+8xe)alz7I z7nt;za8>rM3;tOiYk^+Lq)94K3Ih(Pa8)SRxR`L7$-!XKiN*FZ-6;5-4Q5H zDBM#*5fJ0pmkqeNJ{w2qm8gt@C0BZFuNFBjqx%qJ$T`1oRt!GonFc&s?j!M^PLy=-{_6BF+aD55FEnh{ zQ61z<;&}vOuzW8p$2->1lvBS%ui0q#t`Vw~zBMhWDK&2;|HIo(h(N!}BU@3Kf5JQ^ zEq0+fQQ!nC{EzYAXv@APqQJW#SvhigcvLaa;;SWiHq5oart}ZI*DSnWJh4Mj4#-q6 zs0pzJo)I@Cruk7cH|4--wWo*W4;IB3aI_VHY}ugH8;rvC5`ZFxumf12I)6z2YtstcGOp)X4fCkcsfP^YJ|pBCpiPn0brb%BJ} zMVJ9-%su)pi*$zYSsj>gg>RdX|A`^@(-gh*EjS~_v@9%sV*IP zP79s(ro29%_5#76?qK5=S;>Y`XAL9&BX2>J3)B<779Wl?2Gb-AeuV zG?qe*AyGLv%kt4zB!H2-bO_Au8xPKF#_v5WS`N%{P1%2FmXN!2HkS^W%lV!-nIo@fBf^B z^=A5b32XeL$EMz|NUYqv`Y52dXL;5c&b#x4?)78lDW1Dl@F8f*l&HsU$@!sbO*LDs zX&6T0$kF&53d^vuWA0@6-L@}7UOu*j&^jQ}*<0kkdNhYf`9*#Xhf+Gh?*^nF#z&C8 z0adxcNClKj_rrp+WJj~z?xJ9}K?s1!%z@+_vjKEkH!{Y+)LD104jPh#M8H>{Jh;GZ z+YTiM>)5f{+Z&IkVW$2%9c*1>&)40>dlP?4bglbwZ5R#(|EnZ;giB!B-Rwp#%Ye%_j#ZVv%^Jo=F{>CCL(Maj z2*YZAmQ_2x3@|dZVfqs>y|rB7|Ce&_KUa1rRSI!7o=eBJ^Xe=LP;WLxNA-BGV|22= zSN?|a@xfnL>@PRe+1wNq=ODwBtCc zN}@Z{&zumsI1hT&1#VfX4=1izUORVn!=1!is`TD8^=F%p|G+cI9K2U6nE-57!rRPB z8Ixqb-N-AJ(`Mxw#eqgCP$9Gk+v3}~)=mUOfHT-D?$~yE<;2wMQPYBSPh}|te?=Z? z2{q>U#{I3Xy%0=$SbE1#&Uu_e&JqU)>$bwkKY8AFiA;SO9@@8gnD>1e9mxRXHI${U`T8!6p0=zo9}lvOocpP# zepgoehg{O*I~{1pQ$wqdr5q?dVe-JR_gT__YwX`z(!X(<`&)kW*z#{(N>Bc-uJq!N zYUbzlT-dC9lg~(p&T$-YsjFNUTr$}F_kY+YJo^NO3$41Hq0cj?bED@TG7^x+Tq^{R zL^ZIS;dGm8ET;9Dr);zQ6@pN3;)`7x?z=r)oc~eK)A(;a9xZdyAGKK$g6nUw61Q25 z48TK}gLbd;jrC5GFL^7pfc8Z4@w_Bjc?nkR=kA4RHB^u!!_yc4%63VM3oiScJ#5tw z)lmJO{#p<~^F?}&j4keU{2VU_OtnXvgvNr~@g>R2b7fDIE2{Weh}~XBG+%16;XvC# zoMb)83SJpihObjTSz^f5bNk>QUJ z=9;*??0h@hh@5eAVENMB=9p}$+pzItOEPJyLdLfjX&as(_)v)8!xeeN7dLpA-CZ0U zUi%xvZLaY_!{X|1JiOmTZOgjR4-I(#7zxKw&MMy7KT>u;<9oK~N$#vCg2&p^E73{p zqhm(K!QzsYP)$yYN8sJ54RkWqo+Dh$@5_y;8_D)?;m0=3-j5s&t!EYaC%o9{__QXm zZKmBKwQXb;&-c&qsr%zrj@BeZ7>(aUbxEQa5oIB}^mL``hmTQzJd+$peH!PowGkK? zPnFP*Xzxa2e}H|ZF$KoXBrFuLMD%~*g+c;gD*ZQ!Nm~4PnLAgeQ@`S5(YjOg9tY~` zO#aDoa8<&>58k4_))E~89Pi2fPgaGD*Lw$CwPUCWV>DUQ!{THKIis^qEhy z;$by9`+>-Y{#L)I1|1UrOyL^N>J`Ju4ACVSS@Prs3RG9W3Fm_k5P~GxHDUwbKBf*a zkc5pKQWfuTXD`pjT(vbz2)!w`y*(?8n%SUZ;2?l(zUM+!>1)V2PCcc+5xo(jj+_#hdkK-nx(5Ss11=eneUSV( z_LEBE=@$pEy|M-BW|9;XN(&Mf>`+`>*+-0mYF`#DSi-79Z(|)Yo^gg{42_K1TK`XY z&(}G_sB?|fb7>iyV=^-ZB=6D z;x)YWxnV0yz~@stAM^EAFSH8E&K|W1nQ-%R`++H2FfC$7J7^Xkp)ca0LH=^<*Sr$t z*pe|*upRQL7575dGw!xLvVc3-Iq{Kt-j8KPYjAMr#vd`x?uiwG94IE7ZOF7nu^$Y7b5n z@jCIL+CjNFb{ah%@xBVpdfb|6Kd7P68jXtgx%)EzGEaik(|LheCY15fZX z2)wXSH)e{-EnPH5HnVB&ML<-Ku7ie(;#b*|j~wG;`Jc2;lD^`@kHmi#4yA61y$nWz*(Zna4 z>?ibL_6t;R??`y9YAOcFYEz%`6a5BG zpNxzuKVvsaYe>@x;2&_`bqh+rw+e?N2mC(D1_#IFpfEzeKAGOyukcbcE!2cyJ>X9~ zc%&~buz88M2oLeIah?JJL-(NBxY-F6ufDzXJgX+@m%0eCV~07^jtpq1uwWU^TxeB$ zTL4OqOJfPXaa-BZctkgHddvP}AcI1yId=~h%nN;$|4hZ=RL=ELo42!d&Unf5EeZ4% zcz|*6G)x_D8S^wOaANXvn~X0u?a!<{(7htU!~A~aq^kX~D3o+w?6P?(!^)G>RGXNS zgCKxtrX3A39oi7}x0a#Q@;;}J6Z3!B1A<~;65j1BS!xe9mbXwpR#!5*k^DvRSl89> zJNY}Z3*#uoJkrDJB)DM@xW7nx-nbUdq}OPjmjO(9NS*c9_A1GeF=iDzf87e?6G;z} z`_|m&_=qBmh0Pc18f|I=C6xKzDv2`Y^@&l0f*Z8&nFHb22DNld!y z=jPuAx;;CydUY0Y4+TMn#W~jbKlzd1J*bTto{ADk`L3bs=cYt~@xDv=BCaiGUenp$ zf<6`FZ4i7w1@VkMMeAs8CQEG1n7SPN`L_u)v_Be;8vC0{#g}PS8#x$#0ZGdj2Q$-Wj~_K2DFzqUEJuay#`MGN8oeV7^GfseFYV4LyKWmfqr%Si zpt+{9ztyIBR`ITv&W{#syl$J;;q5;BpjS5iidoYQ=k@cVBePUFgOy2|#K`pHZbfF} zbe_IH_GK*6B3J1AyW>0Si~LXPKr*y>n#W{;Owbp6fGoG`*wIbM0P%%;jpx3|HFjis zC#9sFq6>HY>RKY8fnU-7%6jKni#oOLrtw{(J!Psm@B_?qep&mhGtudh8Ot(+6@Q?o zi7ob*UCBU952T8qQdAAG-lV?ksSUm38f%r2>grg13P)Xc_J>cpYJlsTDWl3NL_9&a zRL&w@W=s}CE!X3jN~Yz!$3MD$OA&1pbbUq2HufsUo1I%Fi4WLYmx0zsRsjbXgAk8* zj}IUtOJ+l$`=R(k!f?%V$&K@fe|fH}>|aqbaD>Fd<;X}}I~NBx1de4hht$|7n9!Yx znb+NL;Zk*o|62-GdABzak|&bPLC!Zw7mq&#hTe|XqjXBzk5w^_>CrEgJ`ePtiE^m( z_7r%yM^Aspa2T2?={6vLUccHhb1AuA*a?XWCWQvR9xBU%>v$uZ{rATcKo57^Tea_s zW%CCs$K1B>Y7aeq!W?wUf-%Am2XQc&v5W{baQX`eeNWbsf>f(n8&03Fje6w7rJ5%P zmA6#}+SW+Cu@L^SvWp`Zm{q}?yL}vXTH7!3J6gh*{qU+~#>VtGWk62(-VsX{=n^*@ zY(2Jw$nAJ@q!J*sfMod_q0Y#$bY6ZvuOmyPK%riqYwC)JCtoKuqkZRvwq2Iaiv!Yw zF8NNJ$H382F&3%DH@oz_vDHS*yX2_wel$;%zD+r8I~|*S8>Z!+`u<7xqlM)ypCMI5##jFM&4%|1HsSef;NprEM@QpWjKi#4qKyae!{n*&)BnGG;Cy$fD*jT zB2rsKw&sNA=rIb|;ljZ`uR}KsRr)t+LulyPvw3$D64T-deb*JX0!`&;#D?{}+b5Vh-F**q2=}qU{@^q?Hn-KY+@IcOZ z&a&=EXHX`Ob1?B=wNs3|Y0AmvR@{OG#K})%2X&agL+tj^!mG#u*qPGF-jWUa|985w-*`8tTqw$t2@H2OrM3?cVeKQ)Jrn^5n(b%Gdwf z(z9X7=OD%RY|tmr3;!+eZ5*--$+{y4*=d~CpPQ*1D6pK2nL?b7%UT1SwrfM^|6o;4 zw_*qq1EvNmo1FJ{^qldH)sF|9F_db?M$r{7cL>gM*uYyih{!VaSn?}85LAj7!giWm zzln3Py7Uj}^68<>zF?M}C(SzJeC_3oLPJ}P9_vzwepl^?SWSU+=QP=k(Jgaa3!qct z>19c{Q#u=sGM0cTlJ2xEw>GOp_CJF=feNE*w-PGL0QVua0A*vA99=L(t1yT&ET^Br zKknK3g#+|dnAZ|7!FCBWKgp(24HHjw_Q%{sx{Ejdw{=yY690|*5TY?88FDNcLK?KJ zV{q>05Wcg)CW?`z4QaA={8Q;hhn+RD%*OkGCw!D!tr2<+*+EC9a+#9jusHei2oFWk zT0**~Pg8wS?R9qru?b_QHYZyu{CV)919_)@v%PiUTwLJ&ihy%WGK(vPD*nL8UHRNj)4(+*9GeBz%t!B^ed-#xy0(f*UIdSe=H?$T52K3lXr z>LD#rV5fbXSwEbEwN8dRPl%Kj)lVkr$d4|(K5l;gxBQb6%bcBB=Owdxsl;sU^TLVa zBLQ}z;yK>Wn%bU|fksU4j1%S^Sdk54)ftioI%f+IXLx+8u4Ga6A!_KGtB~a7V2ZO8 zM8txdpuq{gfI>K#W2_o#J%X|^=jA$tn+Sc*e6u!$jeAq;*V+}g1a-O~Y8Y@#b)CJMcxpMPzr&nTW$@Vr-fjit4&^!d~BRB0jQp*DWRX7(GBd9WUN z5{7yf&A&23@8Ya^AE^3_z9Quw_<=D9?6M*+R*Eo`wZnrU&OO zUT0Nzi_?Efn)>oZ=&1`jYb|OS>D+_5JDKB3>`0P#74$uw{C~{}8crP3AlX^Yw@W#% zWYsc?>_7DWT~7iQgJ`~a%quK}uOZu>#aCH|KhS48y})nEtdq5gJ&?mYvcfkVP_!Je zMv^2mP+QCvbqyi}dQ~JF#w%&%C*qQ3w+;KZMp1)ccmgkRrX7Ien(iPyIbZKd%Q(olP8xRR$4wJ^#L*L3xS&Af(?M_dwF0QQQoea9~%l( zvo9CAL{3aM)bV~?c3sD4_s+dftIfvwPpT5<&3lYEUjasC=00k4LHNu>2$yUjqpBRI z0K~qrcGvLrntgLZ%hOzI?c3frFIw!p zo>QmY@;ph@GyNSG<=Sa1qv_34aEynD0L1<2F{VmNq!|@o^_i%HDkCNEi#-wa0fy=^ z(8@7&Z`!73Qjc|;t)tBM{VI2+8L{7ig+W!x(p)goY}jq2J*WQMO#N#~_KF~bs5b}R z*ezUt?_ycrp4qI^(frd2=)~&vXhmuDm#|7wMz=^m1Rm8?o9&s9Lp%)$h(e|!o>O3Z zKga zbrZHXe&f*_5IIB4uz@DveiDw__%Wi~YdVX+e6#&ge`C2=Cf-p{TN)~7B95@ha@mBY z`0$vvqJYgd2j4QS`K~HWeM~MjNirB_q$(QSaJso8MAc8pSkY-*?({Cj{cg4JGDGuspUz%q0m#r9J=Ic zOpt?v-**J~1ElXY?=rbcAxm>vacg%!I2yPxzZR*lxVC@qaSU^A3>L=RS;SeX!k_XV>Hf%vmLW_Hd4WHJBIG2`&&Rl#P6p8LC z62`QOA9=UavsjO#vEasCPs06^!l!k$GGWjuTV$VpU=H4ii#g1pln^|6`t14gwK-|f zsAnVJsHM=9)>)TH`E4|7^Zrd?=)oXe!e;~TG@jdjH0Y3Q3?FVB*a%_G7ICwg}VLnMg58QDX?6ob}_xCHcK8l6L^SZ((iNs|aYAYPay?VA7BP zO0N3Jd3n<2?_iIDEz5FkJhi`UNSCJB!7W_9A->33CE&}C-uUg~S{Eq9z&@$|gp*L}h?|zgXYrj!K1~fz=juw55b%ZYA_!hjH6oYbxJpVU#T}o)o1MW9L z7&PYgrDw92VHr*7RyU*^s^t)37o%yR531966wy2vHy~xtoj;aA`*r?ZoG==hCue2a zR3<8;QSMJece=JZbE5LRq7-w5PDQrd%8glW11?NBWqpodNp!Z{ev?(w__9N%FZRqv zSK-GJyeZ3yitxjrhlJVzLPxk!pkw~MppYtnsh2HEM|Kfq#kxlfjXlQOtOvK0!#>g( zs>KoD2kA}l z9x-{5am%F9wb$fS#IAlue1YyA7>vuXICdLlWug zZs8?c5?=GHb9sUbklrJ!GF#@Zx&(*j)(a@146 zV56XAVyatf-If30Dk>^kmeSDMXT~(~eaeTi06@`!Olvz&;Sgy4E?) z6-QtMJ$Oi}d3Wrzw6+S71=YL}V4(8wq+>zO*wK>mM(E2mdx=ysUH5Ipd?%&E@Q~F5 zgb#6}X%fpAce(MHLH<#T4R+z7ir(&x3s_Jl3a2ypYE>4gt=^{uTw-u&%nXMH-9S8y(}ghYhPV%%Sg$udAU5!Gif+%O$G!ZRQ+P->ZFeIV)jQ5B0QkKJ+rJ;2Y754miK@CI zLSD(acN-l!Qbw1+>?79sJ#2bp%5>urj-67?jewc;HV4ewaFBzOW?dM%`_cLlm&SIT z+5KqVtUIl@6|)L=I=YqLX|)-%A}p_~AoRq6w>r!3T-xj0waR-#S(TOmFmU(vk<500eu2>KW4PTc`J+5^hV4q6r@pzD+xJMFguTO9lxx`XGfPPHu`)O+S2Sxds+?R(qj zgMiH8ZY2B-^l{YchH7>ohm_Q8dg0ay`QONZ+J21>e=V6NkX#n z!=%I9XGn*wWDT);WKxg}&fId<;hOwxfP-u1e@>%C=xNLo>$xb0w}x-5%MS$jW2L7|0G60MUD6z!#wAvdYlFIgLtI68Jh z%Z$4p<6iwXQ4gSQqKz(PWH9oag3#9=TfUvuQ4pMvFSsFx%1lvfj&MGt+p@46k?*tY z{ofy06t+8|;uAn@(>3)qXmh=oYliu&tqo0Q70v-?dKPd-xlUI`hxd&*Cf))Rka{lIO+cjc!7T9${GUr)|b)Pll!) z`TGCkvM4*vy^0Z3y}YCUm(_RN=)y-||0-%q+nS5N<`j_0$+Ikdj#PReAR~IVX=59b=XHN!42bBZ$GZ{L-Y!m-1DN`(pF3zx? z?=`_=Vb-&ch_IMnR4z6y`r*wG|2VeQp<59~%&%f%BV(J*A`fPaIFY|&EB-m#AS%*L z>*WXStF8$3DkNjs8i`22B|p_r8@M&X1NazVx?mCtsRdaRxc*|MuFGUKL~Xf_M}LUV ziXaL`xs=u-Ra0JNz^@u-H^fDLWUHV3OTVrz z857KkMX7t}seLp=*3oF666y-QIu_W8@FD?zW1Q_MS}TkSJMKwh=R7|#tRfIj{*HKW zI&|#Zxr?q_=e-N;JP(s~*zShx(CP!`nuh@jyJ3mt7`9@NayL}qcz9KWu?PM6o%nLU zb$1ZrW|TG_fA0Dz5m3&x(>)DGxE@G7{sNK&Ewra>!iXQ;@L*56T#ape87Ecz?{F1 zVI0B+He%O$PtC?QJDI(pVnw?ysd7OMV?K3d+%VT+zfj5-p~F z8cJ)l{>8qeN2o9v?BGUYf!^!HH<6GgW9F4QeP`Ff|QjaK&BQa2iqbdyMf5N%)v3TnEWoeq|NVZh2-Dv?RL1E9BhI7YY8SFlW;eecbdt8 zAMR{l?@(*~tz$DeBO_E%rH#bq1*QAXsxY*b_9)IZ>1^Pmd5;Hk^f;a9dMbN68*X%8 zO9JROyqQv!N-)C`jGtcfJG&c=a+CF%$Bxop9+Ny=xBSK>N57VtT+oZ{Arg0`)9u*B2*4nS`ql|G;f|Z=f!E@I`#D^X9xzrkkkq1Q!vt)z^KJ9dI>Mm{5ip~wGh9VjqbVjc#64VoP@vepNPFCC z3dPydx#3PcL!jJb=08vd;__d$MBu;zF10CqS;mB-`fuakN~?S>TOBi5l+1!gB}~Txr9pO2TD>F=QIG8%JQbhR{VUXe4bi<9i+0fi8xqO%@ zN1XO#<)+YDH*>5v+B2(kU-+>ehaVLr%JO#ocOT!Qv39Lp@qP7MCZRQr%!f`+HQe)a z(&ZbkZdrEQKd#udBl$DexMt(t{@A{7^K&<^pK0oN;dCx>s6F|sPM>Ejzj}&nH^-}p zzw~f*8A3eu6NRIsBTrJKd_|OZjSN&Ch}{ZY1QWU*yNZymt;-98^C%L88@&Z1L$=MLf&?^~Mj6RPhfa-wL4r{UriA$bD_UV_2?qnH+C!J_ zP!h(3P=&&W`QvKw@W2z6kw7d&x8?Vxf$vp8PNTWSy1kt03iSARn3YkT20V;?xzWZ6gnisDRUqdfx^4xw{`|!3 zWQgy0itI5PlsE*IgH(~C-DBHmVt9AJ!DBJ*=FmnSvmS5 zVDVB-ZGsDFVU96|(vhRVC=nlPzk+72IRFqz;vVTBXf_yZf?Lkl{xcLGWMLj@ptFYqVcQ>l^Dl{ zS!7UCbU}5AFu=XzOOaq|6#P?YO?{lrsUI$hSV(KBH2}AE;l!_3H#m*IQ25Knub-+j zN}%k2T_1w9>?U)ZtNsK%$TX7d*<;}hYXDzhtCfmh7JFVW!y{ymt%$%MJ}7=M{rI{e z$%P;yk1nMS!_AKoh%$avgEaUNVh|6zuztxtLMF-n8)@b~m)gL!Ql>H{Vnh6>5zHyq5M?&B!~KmG>8qiNeX&DGFZ2L!;K9yS`H-nt#h9C~xT@Mh>+B%hifs?x zN-h>PdD>h24rO7leZQiuXLB%Rqj|`I+O3?bS})XdGMpqVH}*9LTlfX%tuVkHUr8a33-n$CaQIo9XcM-pOjm_ivjULxi-h>ELu>Zs08S!E|=6yOsZH!pzr~MwL<| z;NQJ6eiM9xjz-86qcsipFS`stzvoCjdoO%17Zy}gPjYYg9bfbxM1 z*A}FeWvBY4__)=r zIZ9um#sUtQnZ$li0^?dE4^QRph61F*Od*eSVlN}RB2^MYQ6#bYseCM$^Rg`WlXVg1 zt)Flm4n8S=P&xSgZEs>o5|Y1ijR9r945r%l(d5vk{O0q`UqmX7SckBL!W1o5lKTV4 z4Y#4py6X@&wm?fmf^c5)=WU}Fti!YbHbBQbLPnURMUaE@|H&|z?X?BRn+4kA)A3p- zgPD91b@m1lnT;+I(QFSkEOg>Z*`eTza8$Ohipb^T5oT(R@3x_KfRa>ZjOPV)r6p2K z7*p!Loj71P=@@p$nh!&qmNsdGH) zjpj%rBTp9i9Cz*HDX5%paGIZ&J2X*d=GtANmP3zc}pt zti9>Sgy;eLsD{dXS`=fMm*92v!AM$f>opYVJ`=*2(OpR4q=F=;fRNZY76bFP1rx~`c zNAu#cTO|gGr}^lD&bnOORx4P^vAN3+h&W2W&A$tPc)qQhLuFTbM@!sqd1%4)`9^CO zCvWD^HA};OBs@1RZ^HeI(VCpcw`}}y&J0u1vzVA1Z!@bN(c5Y?(p^D`z(+^Sl>( zc***RRPV*~HCYq87w`5-ezk33R>K8GFbyQptg$W6Kc_LSaJ2Y}r3|SL@>EOo153Sj zMm>7`(Tv9KdRJm;)a2xdsSD;`Dh5OI)L6KwoaeJ((gyw;Fa;&!vy1=4$IYR#?3=&j zb1orR8|<_R@|3Ew*M49Pi<^P`#MNznlE{qd#o`IQN}p5m1tOKB%SsQyz zX5r!*CoW#rm)qD+E^l>kZk72Xg&^o(oHbZmxqMM~4{+9*ZM&mR+n9y8ktFD9nVqxi zrX)OWkIoDY`iGorlI&5?b;mu4|7)r7-8a%8k+)xFI)wbEw@Wej5}O(4@eicL+?wGs z9ZL7%KLQE|E+GFwiDz|CefSBg9m%x0mj)XJ5Z^?VdjG|BF6r�+O!2AV4mjyiJ{3 z?;=r4KOBHgeDy(VAC1CxZ`AUuFU+?XDgO3oPQs0UblPM+vgzMX-eykgs*bbpczPFA z*bxiTZ2X79>0XN2nK=HwBfV<(d3(6jkwl5R8KF2dmF__SLQX2^DTx3Hxt zQH%{}_PSOcH&W4{I)~(Z9CORi9O?snkm846K$-IxStMmHE{8RI6l65+*Y`IRJ{9Li z1Lgf-{`LP$u#0CimXEVxLj}8PE&2j*vV}+1+ExgICoWy;Ui&}XsbkF~$R ziryE>u|t-)i2aMiz+tC0gD9jDus|eO&UE^;oGap`hc6 zX^7dJLrPeSeJ4jG*9h~>OJ4x702tGOFBD7RsP5@JK%$b5lxU{7RyB| zkxCTfO<-xm8J0)AGH=HRG2JPG-S25(Ok(UGyM1)R0xUN9=ekL65X&uUAy$7wPmrHS z*oxpn^IXuWN3h?-o6}WTNg>ycf?`ON-$M13NE0u1KSo*6OIY;5E@Ln7CuK8P;?sVTL#RJ0h)ThJHDI6A$OXo1RWco0OIiQMqk)} zaj8%T0MXwHMHCst5VEO~ArUNlq7H9-3!oP{j#t{8#wEz*%Xw>JvGxAo1RrXH4 z8%1oH&<2R3BS2nGF(TUx9p;bOqrKe?T^8JJSjBp%GO1|dUpj|thx5%`kaOKYSkW4> zF?{aE$+XUACPqR;5;;1-BfTFpuijG7bn2$jMFQ+}$e%kOdOSAD{k$bRLLSQK5K(-+ zdyNwR&dEs-`=IpY40Wp^tJqRue&!lwY90Xx4ZhX$h3o*eKsL6CSNO89I*kSVssvi- zO&Ahsg^mxnww10+k)o}5G+S>#e}e#~SqRdebL;x`wD9`YD$_Yr&4|zRGJ^|f*GGfX z!x4+lXVO+Dx|E$Fc2k^3i<_-Q?_v_vO2K8ubB4*IF#3t!wwH4#uld%Tw93inr1uvT zQ3U<_J*JBTNtB#z8)Ne1E&;T9B##06gKhJ5ywC1$7;~A! zMyw;XK@z9GdsPEx_q(0_N+}9KEsv>dh`b~A7dm!%rt`*|L@fMRJgo@NJOa}m7w@Dr zw}u{`=Jb==;`083m5HX615?>AH^h8r>IJ|#uKFFNHW*pvF*c{NaV%^;o=FBgmE>s` zukPguD_Myqc0x(*U<6NfiuVD;q?WYOo2Jfv->kblH{H;NdJ>f+dC0S4c8&CEs0yEr zjeBDA@<+xW58paUr$XOhS3geM7{igCCdijEx*qzxSn~P(?bj0Z3)V2^{_87V!l6{l zlfPd?|G*fKm?Q=twm1%oHO3b;7BY6!64pd4?)kqzRHUSJ-0W6H08K^e$lc0&jKI-p z8#aY9cTr;0K5rBN+JD?(Oy!5oe3f8ol(BWHWX+bj--kjqbl_nfch}bF|0sq#kWL#1 zfihV?{x;hiG~o6Y#<d(qbzr1Fnq7jknWw*huL#$M)nfc18a zw~AR%_(n2xP=_QXFK~tleeP^GD#stMI?IdQyUwXH|K}%v+evf$?wLX-!#uA{rruP7 zmL_VMkic1!L-sXE5OS;r3ZBhTU%SBg&=gDI?~L4ZG=2$Qxs>u5A^935EB;lr26SIV3%_H+mRl zb0ovlR$gF*ch)k1gMzJiybk zFrT9*9%>7Dg>#&7DB~iMnuuDm=WcanX+s=@u>8BKFC!yn!s8{M3PN&1n5kpephd#b zjn_5?thNlXSJmP)U;-U|Q;&$}y9ozDFy>z!RlCwvnb z^n`DYQ~KfndoJ*w{#HGR7$pY$N)@~fkd+4d{97j!El;G2z(&1q%@9Kz*eSBL1Kfv? z2FJ~>_qXMBuihLIu*wbh_|tC%69hLPP?AUWW6*~jSI%8jS%o(^*%VJ9DAJ~pOd8Hhfh{d5-VE57G>TNwk z$QAWztW@250Ra{tEyWFY|Vy9&VS+1n&EMMT#vsvraU0#nC7Yzm+%AG-#(M~&+ zt(w-g70I?Sx!kQ~S?PQe7zRw!llU;$K6Hng`lPE`lowPM;D>bx0IlxXbxYE-)%*Y5 zs+-G7_*Yb~x?o2(TvL79vm zZ!f7z$Xyh|0d~WD_&MJptrSr?x(hZythLep^b&Tg42&R0&O!bMvzfzScO6e<;O5Ei z+kg6arbKA}i6h)coHZ-UPfQ0tDs9pZ@k+4aIkIwsgv!2q*1w@D6d89K&5q4hEG=PK zmAy?5i86x+G|z$-3gdLi0>7y^Udmvsku;aP2q?jWziy9P^^E%QfY*Bw1`?N?9ckdy z_y36c5^yT;HSU{A$xu@_W~`Y?x3aWYvo%^MR8t{ar>3mOa!?K-MVJ{`N>SFSw2@^T z$I`*+Ft&s!WT#_k#IaPzetf^b`M&3Sp8IrfQ>nSV=l#F$@BJ;Di@sw}|6?hK=dQ7o z;XF?*3C0y=SkA#tv&aZJAT&fz1HegKfS{HDDZQG~CZ`+nk9V=1v(yaH-WJCcA|_Nt z*IF76b!h4$Sc)!gy9JVM=yL!MHR{m=uhehwFFeb*fqM%Z$T;KFK~joN9-z%2v8!#~ z-yk{&v0#rE>Ykjo6eHSy$g#-A0BYD~AGA@j^neY+CR{OtvW7X*I5Y6qiH8uZGnk%} zlQv#UqQW8ey7BCjz`NP)k_L6)B;ry>HeL_WPPXVb1kP(Bdbv@f8loLgba5DjN{n?D zQ({o4REs2OoiMi`Y!7Gz4+~tLw4%!4H6^(4O%~vVbj4fVi<(q+n1n8SY^?<8(2g@{@xb2e$JPt`i%odfSV?m+p z0%ZXNFn;>*g7#BW1v-wpyNT3m(ztNY9w5R*VBZ9!zJmPtqp)FK%1cIku#v=9c&x$0 z3RDVY;#>(O&J=QIf+b@|w(q`f)A$%aC}=6T>F03(fI8%<@a;pW(|GaxwWo+KJgbgM z#5L$3$mQGh)ngR=i7T5jELt)$;zhq;<$&a?x!dSE%=Pgmvfxh!N8DEk-fS_t51So` z64)}Z5D+bikw3csG7k+6EAXWF1}|McN~%=?nwNQ?NQSyz;)N$=yu`V2FOL~F`^l}u z;3xG3(?GAHW`c=zR`InyTNU6)=*!i1H+R#Var>E|qF%@Ks;=9r)*JGSJ&FD>z@PTA zNm3ZUCC)US7qMAO5)25xso1L3Hp5#0h}RvCe{W7aB~dIC!2sWf&C2W83_^|pNM<$c zK9HqV`|JU{kh_Ic9T+-9FeBha7>ov*dYA5FkyCeC)sk^34$B*Y%1E{YJk2pX5-|?+ z2>nZvRj`8w-*lKO9A?0tj6B0rgn}bUjCa8A1{lbm?*QxO{FRFP#rI2o1(J9iq(y^n z_zwU8!U{wXoJBBqz>K5TNgquF^}S)eTGPKUH}UM+5=)ZAolqxFwMFM9{Iim ztVbw(bUW;_y__}be~(^-M~?1=UlscADp0>i>`W7m*$Hq;sRc7<;_nokX9j)?&1!5U zY)GmHAW6_ANnmBT#WFid4*_XFD% zUATRWOC2t?U3C_)WH=1aY<>S5c?l_?o@b zE5m^W*bn^v240a<`uCvWf?P(8+~#W(t!xSJ@}t};6}9Akh-ktKWWdX?B)qfQ(C!}l z$%bi)AYvri0fAsf5Nv6HnJa2AO5AR7wU#)#_TrOwMA*`yN)~RE8A{GMJwX*5UgB2; z15@@5b%cO6I(}1{+DJJ?Rjw3^f1gObq5ks-drtLJ*g{&>GzDBCZjZc3@^x&aSQrF& zoq?n;4TR+G$5_)0sD-pR7c+Q9AepPP#HEfHLy~tA$4J0RCod#wP)MG`7btArxzQcI zoUC2M2#5!Cm$7XDd|MELhtYr#))($)5Te{7kowjlp4s3V60RfX7CorU(5UjMcH&z- zN5@3ow+30m2_`v(+cZmap^c3o-PN}L5+;a7_P}}X1)LYX99*4XOTLD@^W@0=9Cn3B zxR@B!2JU!j{JQHwSn!>Nb_;$!kB*XJT6y`G{#5iX0OU*@si$Q6-;TjGvP7z87|y4> zblqEJlk1p0?nnM4g$Dy^zsrZwRf|bYiypa20yl8*o{|CtLP+CSS&;Zi5O656KXv_P z4aOtfQyaFF&me0A$^v*yo*g>@L|C5QZ5@s}U}fTpZRz)26E5Y@*^=0I>xn7_;6HYwmGN3e!QCpANJ}2y zj=}>HF4w7o^AWsZNEB%HCjC1EEs87EB{1O%#`MFU023k?5RkJ6iRe)3F_CI* z$6LFE91ay}#(Z%Lf|hHkau$7D-ACi6NJ1jFjw$yIjgDuCn0b;Kfma*9)g!)v1tB5fp~0ZE1j~wlY|u%MMRe;&r->?T2?NE= z@(u8L-03e6B?Cm;MI>h&i#`mfkt7e6WG(lNcV_|SAmqR`AymuB>u*w0&NJd?l9BKZ z?I6nWx5%9cj+y@NLRFlg^{?*-nvK>wO%6YRYZ{o4m@40vw4<9M1qqhoYC1Kz9+qrZ zD`Sz!5d#;P;e$J_0wY}ss0@e@)oXwFZB#O`yadcNYp&%Mm9f=dl82&Ipa!%<53BwHVgI>4e_CO#kb853o1wpFTIE>7 zMb!~HqKgvl(HIGjP01|>v0}f8v8_#LN6dyc(JxF9R+TW3enpK}KyyQl zUWVB2b!@o!`eYQBR&R}Or#K$e#9|DFnPi(K)|Q1%r780|vSnNC4PA_Og!40OAnV}t zGmKo>_;L2U>Y~r=HORj9=gyE^%wd80SGw6%z0~&%0t=D5N}lR?38=VO zfyn&^)epYV20tD-ZjUZWt6})JfZRoUxak8)9Q+~&^L>WHudQGFNGwAS4_XIyG^pjc zC_{9+bSWH&A1Aa8wAqNpmw?tkbk+QoewL8J;kXC+7Bc7WgIJ4~wdTlQFUoKT2brhH zKBd3I!o#}@OmU*RCXA3l5t89^@>>*A@CXRM9a9PTvVli^38HIP)R24?;kg;gjT#D78Hk4nZmJl z@G?E}pc_B&Z(<36d-SwFGQfL2PF>Xlo0XUVc^Ayo|1GX`&$HlHIoLJ(D2yb?9f3Bs z0j8$kLFKP?5&`ofwahZYvXLnKa` z{|ym-DAd<_eKGI*Od3q`xN&Q0Xysil9Q0L87?d55im)8*H?l4U#vUwSzAC z?{046eJZVQU1WaS*v13320WL|; zy93_k1=MUJ0G>LSv=CEE5ZBW*)oDG1MDfTRM|V)d2Sv!gg9AuzFc2ndIlh4|jgUm@ zm?x>Y=WG{EV0Ch^>(naaG|(;?!?g*L>2GW#%x}XMxTbu9D}}Z`w1oZlu6n_8TRiU` ziQKgN(+VV7yuoT&zbv5iQFrGeqDu1f=~6V!<&t8pA{n*FmpQVs78{+XY}f zP_M`o!Ul5or1}s(59Vld9q`hl78i;uS7y5fNc8H|Mq1#4^CK*GDzbFF`mm1Zg5v|{ zTsb(Kih;$rYR&%3(8d@=S!XfJc$4@!71=U$rsn{cRgx~~R8dlBfYIJM7L@*Ow*H&8 zlMbc)YP_w=a$-U9#PuKqjuXqf&8hFR)r z6xqiUUn!2F+)r4$al!Hb6D&#CMkCb*qoxo3Y7dX9PxFJ?-%w4In!C|t=iujujtD1$ z8@OwKA!H3=vW9J?cxh3w%AEzZF%-%Lm_&XFf@i@XG68Fril|G2zDq_oAnG_{ zLg@we&@{0rK!G~IaXMv#Oxry$DR9;FL%%-EAk;OO{`eD&QIr7SfM*~nt3{}2qlTKV zEo_Jm;z)QHz>NrWIWWK|1C;~e4Vp_30glsPfWTTJ1@|VRU0a$cqV2z_dOPo)6Q0un zRk<^VB`)SNHuo2%d@9rkzadL=(rJyML@YtL|IJ`sSw9NN0EDQ}?;!w;T0~x20>6Af zU?)gmcHw8iLqvrEtU(SpYx{VH^IjNpc7tjMqNfy5vD9 zqx*>iTQitLWx_-hovr>RxV89-vDLVZxJ2y@mnS7b?8 z{~&qT46NR~O`E7y67j3uvf_C%{9YCMGJp7$(%3rYUmtf$G&h_Fds6ffZ3B*+-P-lz zTfrTFzX=}*TW1|O^eWJ(gol;m7u@$=SrC|I3<9z{N1gn>xIc%!Q5M zJg7^VSrLE8tB)7DUc9#q2$UEUQ#686xkQlMoQ_T6&eBK14VUe{Nm052*ytv($CrGO zp1>P*cpXPMNnLyc9NOP1&^*3J>AvOKV6*Lvth4j$!SV&8;x%iL$hJx7$dk%w|J$q{ za=-H?iJtdxadA1jVA~BgSP@iPhvEK+X*FR{BntodNWOVnpdE1@5+$J}h?U5dzR`-w z;$iJ5L8GP=NhT7+XQa4zXLI4(V}|6!#zA&hBHUA>|2;UVD?&ffmMa*k(r_&W6*y6< zX$qMq2wB2u9tf*Cx+eG+f4jG$7?Bah$IaXW-h6B@e_>a-q*cQ`pdW`fTtJCxt&tT| zuUAZSg^G`ui<5j-;KoRjgPE;O&c~WzlAZb2GLp0oVU-u?u*28Bl$ z!~)9s6g}d{Lnu7^uTk?5TSy8TFQQ*p_@`>|$sb9f-ohdR#UHo{kVE0P3{$?dUGU$D znz~AYLUGp?f^oAqkq%}YAVyH}S9QVC!CZ-1ci$c?ID~o#kfkr^qB9OOXiSi5!8-`3 zph)#To-MS~bcuBvAd!9`r&G2(6PZzR+MXFDRZ+%v)DtOZS1<=}PhHn`>9u$Xy`Zn* zXTX+2QHVq)7AwqWcG95>h2u7sD+^ceycQqZ)C6bK6GiPaxC+_&DnC1}B5B=6quOoD z&suIM1JUaPIq#SaCC`po-{ALg+-yH}u0Tyv93gOZz`Gr~(3Slhk2e&53w7DNX#0t= zXS%N=6f5UWU0eRgY4_114vR=iJ)i~b|gm?2?UaY}TqkaR(k z*!jr3Jcya76Bl$+8eFkCgXiQT8JapCwkYzf#kCU4^9Tt&7*r-JGwv;@2a@0c&e^b8 z#;rNDKNRhRWQH1K|e9%kLU|Kti){C%HxM8qsyNq+_X#~OT$AW=B_ z4L_)Mz+pQt1@-A=YWRi!03s|{pe;#6VYmasDKDfNgZa~nlsfzv#!#opQBhL z00D<*jO1;QXD9a)`}*b}#22Sy+Zl3M-+Eot1yS!1xQ_X*%g@q{0el2k7hpQK)qrDm zl&H|c<&0O`_!@FLPxf8TQcGgeY_6rWzYtU5)}BcDxlCf5yywIgANWu5D_fqBHTMV= zE73&v?7ah4NL`Td{{xXVxMR;{$L>%o)nC_Dx4|5}&pdzz!HQ}$bE2JcasA>~iv3TZ zl?fiBFaBb;P#Hg7xmU}}waU^#e_e~YRUjer=87O_(KG{+0fVn21x8`dL-}-9K{}cB z;HHQ>5I2v_z-A2(F}(bsmg^F_c3KZ{R!arf>x;ag+9h6)_Mrz0IDpTE7YvAR0GksZ z)eR(ryMy#oAm+$wa!9MfIf+;iA?|oL*bi7;{&qnoBGSt)(3TusO2E)uf={9Ahv=+x z{N7NJ<2Qm4@j#HM)rB$dzj-;JbWnRTaxbnYFcc3CS6G`Mzh?L^bYL4_NP~y3;PI!P zH^eOizbDBc6;*y9wl-9XV(izkmqZl95=nW*T_KqeTNykiuVzg1xi9e}XS+N&?o z|3-9*Q?Elj(~gq}PBu2>**>!5G6-2BoO+KQ4~19r7;&ZoksQp5X+A-R{5GGZQ;U4$ zkN(Ilj^Q-|9LcTnk2D0rb8U>| zD@Xz_@=Ie@Mg8C7^UaIS>V=dx@iA2yiDrlXm7`@qvzg^d#FA&+=0p)*=83Km*0t6I zlb=`Q;lHoz6^jgTlg4C_-g#SyZz$*l`1rGR*2Y)#Em*j|B<;0~d!Qb}KFqDiW?+fN z4X>?Tz%{1sQw3d|*W$VqY{OAVciUUU{I&}n&tNoY7FWAOtplga>XNf_o2Eykxq12L z*qN!ar!&Xp-GkK<7|g{y2B?q(urvS{BLbIe2o{z^FECbd_D29G5s+$cS9=ovjpTkv zn4%s>*ib7FSq+Xj2fO`EgNig4yCaE)U=Elg=FmVw2uENJ89oDTHOZZ_XQ__$#>VfF zmPV#gcv}+CkpTcd8oog!pK);z{TD7Rs9pTC()!==GZ&sHjgtP`_5V$zm8$MVb|Fq4 z{2vm=hr|+rE?#p2`GXn~Py~kUjJeOs8%q5@ds|@cA>rKg{gq4y=B_# z$87CoGu6$te~H63WS34YQi`A~!Rmp({(t|k2g2dY{1D1RG|gH1l_KI$PqKZ>LpL`l z$mxJ(2xg;!3=2y&lq{Gxx1gm-5VC^Tej1K}bZ+t9DwTO;b`WXT^yJttj=kjFUe;L% zcP0>Wbh@VVh&l^wL$BqTL{2rfndtM2iT1kZt<5C+U;^JB6VH&!sKf@^QI^s2hc_^-0+f7!6LML6EdXbP=at6B~ z0)vW8MM=EpC^uSFLOA3_rCsGf=cn32zBsqTQl{9GYAMHQk-&GVR)ULmqNq$r82Gr| zHsydd-*a#4dZGA{B|kwu5qe+tal*CuDZI^-f;D5$nx@C%-#dfuGaDU0C1v%Txllo` zvUFrU6nr+ODk}kQ{N-_?vg)%Lhd;Nx4}83l-A36a+Ymism#}xZ(bc?c2mKFt9l%h*%dEQ#QP?+P?*?Qw@G*eaAgbOQr8Y9q28jS(nunT} zOv%6ro-BsOYJnMyrceAjNa`6brsM<)W5N~+$yz33gVJIswvu^2kQ+hAhAY^ZN_jEz zh;TJ7n*xIs)WC>MTA+XZ04>u>Xz_GW4e@d?hp3U$y9HN9u&C++1>a;|<6!)WXOp zcj@8^F}UVR+4lD7A~J>sXJt_uqefhh=~;Lnh0`KUE6jgsCmp#hKco1@3jTf*>%z%q zj)%|?NQf!QF09&D3EkSGAG>P{u@gmRuxu*Ai@iIlN}sIjB6DRzf-27~&`iR`iE+X&X=BIE{`QS&O<5*sM^irtF55o&XTwbE zvWt%n#|04?gY@%|a;6suMfXiWD@1i!RA{d zQ?vv|=r=W7jnqkp9|kyu#~`&TY<_*i+yS~8J|P$(@aRv&CD?IcU9+0iUMB3^7DHn? z6_q~SLu4tu5Mq%)Pifpe&3A<*K{n$d`B(sO!iUP9aNv>D*aLHP?0D7g?}8fb6Ij4w zBqe@CNC(J>^jI*oM2+7|9nP`~w?1BfGX=@jlRpj}hJzw3>OK?Bbd`UJMVQMNJsXS) zABF03SLvVe$GWCW^u94&}3_5bh?&! z5);lc+JJ(vci;@7U5;1}AkKgrlQAr+-D}UP$|imetIcy??OVVhU!33k#|dQ8#e^v`FVm3?90n9`}GoZj7D$RAhKj1paC^GJo! zQSnkUYRp3ho$!oKO1Dzwm(-m7-L)_Hc8;X%toqsdkslj83#+Vd zvO+wB_)AT+TZ=#OCez||bNx-(1`ioOm$CZ3dU_P;xK(o2AX76o2d!KO{-~PcgqXQ_uwv;{L?X7y%AbYP$kntS5(Y|mNF*(m%}jt=0)n3w zQw$9)#2Wnt`L5)YHMr{_aV#EM%m_n0v6!)&%dJQUbj=InLA`?##yha|)2K)z!$bia zfAY;z1GR0AIg&jN2O0lDGrD=(0#W9IYJ%189R+O~iI0SySBCIip#8Hfl<5M{2m-aE zzizm23HNKF11L@f1!8O|-1s~0(gH03i$^L8{t+Z~3n4LLK5(eFh9L>`{m|wYAsLBG z07IK$=Im_u=XO22p-~Kr|Gm}+2H7$wmH`D$qR|2w9CBe*>&K{FE5d949V!v}`~Rk1 zKd}5CyXpSD#2LJt{5(AN7#VdT%f2niKY(HHdZwYjLRC)qN~Y({@Rfx$sr|>#!yvE8 zdfm&G2g}K<2;_z(9opRK<{6uCdhTaY6>haoQlGdU z?Ci};imhI}eB&X(pQxwVF60%>X*aZ8E~-~j+ED6~;qR;`L7&p*oay$K5KTnY#Sbc{ zx1H6h^yK82Tov)~kf8c&IEr?PtUVTO+F#xM~Cm8G{kBNQDp5VntNnz>(@NqWqhB!^VuV7@3j4NYE|vDzG>9V|Mq1}@4V0X z>6b_830{<=7BjECwe%^nwwl5*%^Q2VR*-IcKF}=t`9o3>IS`Zu-nDECD6NlJ>o!-^5g_raV>oTo|P@@y<*u=7g>mA`}IYyUWL zGa_a$R`V~U=l(KTcgVuE)M~-*n>-LFQg?Y^WiXh0ANE4_B2`_Zv>wJq7%uicY`C<3 zZl6*cZd5HUYNTktouUMzf>S;gW#~{)Wf{41CgjAlfr4z57T3Pr7?WW&ENajvMrxm! zvx7kYqRkRhvq3PNRhR5DFs1Cx1D4OYu|&a}5eiY^hyMKB$VLHjN@^s(5>{h98hxMTpAys45HwETzrrZLY$9b4LJY; zjmqTOG^I_dZk7@d`-3%MOD-|8JYBD`6It_KV;DKttRrEDeY9-QzyQr?!APMb4iq`YZm7%@Hg{ z!L^yATvoMC^d_FD3U3mhjaXK-imU4~?LGH)+~JtBf}baCMDG;TDf$GUKhjs#B+0Ax z&IIAVHy(AXVLy5*#xbAh!9NNJlzi_Ta2d82*n*zT>_IclW5_=ZJY@Oa5^(1nrdKJ9 znYax-XYwzR_9+isUaI~#7p(n_Vqkn=jcOv}TzdmK5q(>RB^*NoX4v|OxlE-t$h=5x zE@^hkNV8n}-)~!h^-vY@1u-DUx$G$2cZh$5*7ZI@;}XU3&|=-S>tCMvQ?IsFjrfN!Z|d#ee8V7CHHyZSYr5j1ThH2HFu1-QEW!cEG!{W zwdX^HS0cm3{@EU7_vO;xH9eDTkrZ2*J-wvaefDGoRV=)Q8|> z0*Ho^3{*!1xFPmz1jtpzJ@CG%s5%-uDVLGaczS9cdnpSEEiv>xKTxNxGt& zvv-$md#w^*#DS5-Pj2Dcowx72up*}*O1D^KM3&4_ZvG6KVe0xKF_P3 zrpQyd=`bKTwIYEmQSBE4CCAV8I8x`*2Ua-;(M3l_gXmP;f8-CLN*$@nUF(`j-4bh+ z2n`=}wkh-S)9rKn6dvUzJkM)B9BXmODgXu-(5DfOFm(})5B|HUm@3mW$Ku->v0VW+ z?ZI#?#`#Gg1$*k*NW~Wb$Xi@?GTQ9!&Ejg`hJqx!*vKdbhsB42;S9azQ?jkKb1X_1 zX{7iKuyipKwX7IL_5&+(Ur+RP4*vP z1EyB(n0QI~1F^y$=Yg4nuvG$xqaI{gy(jTa*;|CeLF$*Sf{nc4qKd|T!!j9%K96#! zpnxKhl^bqPzC`7)!^d_+*p-&=M^!ZnA#AE$#unWPP8H#sf|2V0nR9$)a`)VFUA`Z$HK{ExMLV@T zq=n(Uu46L1%Ok33dQ>&4X*O9q>(dr>U`|eJzppNiMYX=gQmD)h{Y#ncO@11c!*CY^A8gC5pG@qD=oS50`ib#{K z3l)}A)(5VNIDSJz{XMz|4bJ8D^YrMr3zH67UgryUFixx&@P5zO2Llz9=A!6g`}8!d zh3(_w-!}%)- zR~3&|>N%qSx{q(UmSIA7+n}Sy4#q);>_)<3EXI)}`K`Om0}sbnnFsiYEmVH@WDWLq z{H6UeDfK#o>^OOhE~M5T`u2k+{(il2Syx0;9hnKjW)%?j{Gk*^%|@IrFXW-~e%ttl z@o;*0W*6$K7Y7FetdBFD<14^GNk`lsb3w@i| zFOR?duy+S8r$?gsj4o$L*ok6@B&qBrV}pEbV0`WHr7DT{ zJ2@7O`O|b?D>V~oFhYJlFDIdtHt9HfF7D-l^AVw|DMyV`uqllJyad4l@tmn}JbS#^ z9H1vOuf7A>Nu!s&4wo8>_ea`7R=7;tWk}~$98A!DSeJ{XT%2#aEnd#vg*_(wg}l(V zJjo%Pq$6#ZcKzgr=v~}AFqBe8TpzJ40RktM<5XOBD9KgPDndg(>(n-2B4s`^`MKQY?cYMUy(yyWiMqLKAIAw_q&_kLcX;mM`hwzr#z1=BA$ zEAhQk2a@I)Hy!CK?JBs_5lfos+S?(e&9v+AE78Tp{g3xO$SiTjl9 zpA<;r#n<$loW*nh5GN(NQ2`B)Jc_-*D99@M9RsEL!`{syW4-C89KW#`v(uwWjxurwKc0S=?+XZo1M0FoL7y?n*C!ew@Jn)R;SR4>@T#QJRIR&N5xJZO8I;w zyGP*#+|(Z@?o(tpdU*;|UhjlGQ`RZR+TG2j&vaYq)ZrcX?d=xRbEO~Fq1PXI@jf6? z&;kntlxZHLv%k)2RonJ=xsC^0XH^*w1)sJqf}9e8n#M+imHq*{Z1H{RYnTz|x};C( zkxdKs1Na=>Tcm23w;|eMN+I1T476vM%E2|ECP`6g$%l2xvN-QU7w)DP7S>;3)l6@M z=c5qvu!$PwdoZqVUx9Oza{I@c&m-4me-tf7jyj%DE>NON7hwtt2grJabO97iCmtm* zKZ`JKCOR$^B^FB~qZrA;y0A7oDP(PQ?QI1o3)G6jf~ehv;vm%8LcAReB2VZ{=Zea; z2!#DiF3t_^y8fGVVj8r|a7knp!*xGf8EzdKrY z5ktf zI8*QY-}J6U;{`HBo=?g5Wp!rR(GO9#oJm3FeN!^Nnl9t>27kwj<(huVK@3EsF5^3G zla6kZsLh8NbD65SO|$nXFctiY8)x8MAJYsp!r`^pv)~&8^L;_<;=@G{J{4fF4rks` zF-N$jQ#u>B7m5U}Jf*XP9enWhA5V;yhQ|IL^moh^PVAz*KZnPjKWqRx8od;Qw$NJb z{@G;M%VS}3ZU>rWgZIJaB-LC_>Fek043I(=GwwTzj*yGyV(4P9Rqo8i`ganvTuz8s zXF%yAW0yz;RyOe5-B1lfR;&ofYgCaXS#n{l`{5~@BBFZC7R zB&$h+jFA!FQ66CvU;ZVP3Afyv*VwB)Z|<#%7u{V*_lMfL^#~v#I1Z343GD4hbTGW_ zc;Dzm-{Oty3^(NBDt}MV%)c<#BDJePbWS12UADd2yKR|n%*$4M!}_3Qa#o9(kp#h@ z0%)~Gw3k!M%5IU!2BU~FA?#lS1^_Gtcz?Xk;?^s~#Ufxc<&s;#kY5^qd|S-1OZF`i zlzRnHz*V;?oai0W81CAUmK_nTI^a4zn`im^MaNc)!86XyY2p`1D`w+9!Q$}2Z- ze7!wSYg9?i%fY9=BhetUPDHJ~OWW-3f!?ex&gAqQrPFzjj_}3HC+2qC|7G%*LnlK@ z@k5>Rhgc{Vu?;)i0`Ge7*uiE!bo55qjPW4J<&-ukV)Ga`KbN`S?s^NyP{97D4xv&{ zIcI%_|0%^W7UwB)mo(8JWHw48pqzO)Wk}CsjGP*NQ96TlJ8V>awutx&w3r4Tpl`H# zw)TFfakz}UdlX!+sf%qcR=7W~)s9pD2oe+~3lXeb!h}$!-JQIQQSBl{+a5!59o|4#gz|75C z-`%Y;wmEu>3)pDLnCVrxh?R#0iynwzqP3B1_{_w*sJ_+M=0pOgOafXNT$C_4C`AU| z$}ad-=GHTdjAABs`jwv9I=F=5qY_Ggbs}0XWajS2-losR#om|@Mh*Q`3i4xd1=3i@ zl{WAGxz%r#t<9?@^M{cTK zw}~E~enpAVdK+NWa!q9{P8F)!f{C6sx?K0l(KKM9-tmK-Pu4u4IlK2}VfutKZu<`O z&$SPJlE3&{px9P5@;z)O0Y33l+Iw~W$n46ad{{3a#JE%Ft7~4goxH#b<=t0PShQJ>1vEF$cwiE;5~Iv9ZR}%V3N|* z8H~|jAZwWSV9BTBqG`{^RToWsq!0hvU;_GxP0VOkk$=KPnVT5khKefy#ol}|J#kJL z+z?W@WAnZq)mv(JjPbT$f&rGX71O%&9{qQlKb7vw7zRV8(Lra{ z@jn6evO3=1c^5!=#KW8q!i_LUEV)fEXauN0uBw=DLiPt1F$REs1&L0(Q_2xX7)Xw~ zVvdL6hT}}118siRB&8!<6BlQiS6VBK1wdUMXm7*t$dpemKwKWhK24J*Pllc7px*eY zOGw!i>#_{G91?W-G2a@L3Bkt!DRX2-FKWgcP!rl5&EA<&7HQ>uM56b|8yvrdFpU9 z-zihjF14j8Kl<~5!QFRDFO8j zF7Uyh`fU`2{D2@EwV*R?3v;#2HE=-1d^g04 z7J<8mOB*h1LQD~-{kHup2Ffur^&`Az70w<O9S~jW@U!03;0-lDS9_n zD5rzrQpx2Mh?W$JgU(>Qb}rfgP&GKNvlgY^VN|Hx2|rNxRxk9$xkx0q4sQmov0EAU zqVpw$p%WIYbu(DDTJ#wGgVxxi zNOQ)$j&F>=^`)&eNceW58aw1jz7fGe^l<{{;Uloa;5lHsX(6jz4(uQVgTEK6S@q@V zhn{5apQe(rJn*hX5K(RIWhU-Zc#(%+3pF8wxd4l1OEDPn;5yeBm<*_55v#6U*oR7# z@!U(*=gdVOG>8Tn_c6?1uJI{-(sWPlzU+cKaL1KC(w9cmcCd4cl5cO_6@;=5@_anO z$B_t`1xWAU-hk}ww!TImv=X<4?QuK z6ejz0`-j10T7tLFn-Apmcc`s;byLnP#ONDiaC^Iym#ftB(c8Q0J1v&&8g5eH$Sddf zcSLSHP`brN%{bgC-Qt+~&rBF^WUZ4W;9L{|IO*Q2gY7(;DR^KaK$AM<98@2rv? zwUwBtilNivvOeOLimrbmv{0mX@O7Fkot8x!?~r_A*@3YEQ()yyTZUgG^WzWj+007&xi>Q@OQ~XRS%R^wJF(#41B@ zS88+SM=fyy@lvP9$ks9uUSPdHJnm(2Awi|9C%U1}3$X6hsR5q?ztrMZ8jNq01HkA{ zu8cptj%#D5a9+-v`6U@PVc`BEx79XAfm*6fu8pstWcsDa{Ye^W%b^SK9$?z?q1{Fs^ zx5^)t{ZYo7=x{BF8VrILE2#*W%@3Q{NVv0lMxDKD0EcI2f4+ ziJR81K~EH{c|zY<9@Qj}xu2YX>`Sl}(dTKnxAqVyZd#3DZ`+*wf?Wg(_ffSwPJ#rl zlT2Tw=t#6vz^Wb~GQ^Z8Xn1V# zP^^}XzL!UDIu;7v=pOxuxk%Md#`yu2n&a(`;>m#Xsw~~3(go6{pPU`Ewk}-%qIGFt zS9`g5GAp>)xPn9^nrs3@p)zNnaK0zi$^&*^eaUcN1WkL7xy2VOi&P5CKC3B@ATotV3Ginu zs9vz6rNY5j2h}{$-F*3RtDon`)~hQaD!IZ!s%sV4u^Y?AwyffF8%P3{-H41T`FxmT zYc>MXa={Z$juJR7){$g{)MRP4T$zltZ*MM7FQjN>7dWsI`(c-M)(Bq*oVT>{%uOm@ zy6#3HfH%i1VYx$$0brO0OTYeAVE#HG%?lB8plQIZ02We5exoBs4iPqRk(NYAQ;8q+ zhLzb{eEEoOJ>6foaJqW_p8Mz7>3=|SG0aV`6*o)yPn^rnJFny&!xaTGiRwS>!d*kw z?jDfjnZUzh-_#EHSc-jE-{1{KV_+OGSvXSoXR7k@3XJ;O_RN50-GQ4JZWpSHUeuS5 zQ$bQ}g=XeSi)%EBc!{nEvV-9F3>|VRi&SNVE;Pg8tnQGv1&y%LbjToG-{Q{#!izB? z8LXfOg=&Oe%qjZnYr%ZF(C; zvF)j%(>vMnV3cjrJ=(#D!<~utE}8fAw0xpJdmAZsT#T^y_;lHqho9GRU?4Xy!r|I< zAoir14LUpTV|!nFJ8=g)#Dwm80aJ67cQDQ72ySTp&RUgrRrwkIzC5LuZ7>IW2@cET zgkyddp-xqlpgNa%7mH3sZC{PZKGE-1+mxuDUk1u*k^)^tat(C!aDQOu3L%KqUH5`Y zZ^89T7ZJ{JwoDdK2;b;FdC8SM!PNl(^JtR}oFVp`dB|1}UJju)%Arh1B^@WobcFSE z9!_^4q51G2*y9!x>L6Mqjww*1P~_SRF?`T)@w2s|tb}_6Y#~ItA=-xm`(-N@+mCPQ z+MUk21m_5DKZXNf(zOy61vYuNvJb=L7SjE-_2iBJ5^tADLK`{(;H2@P?~=0Z|7Jb1 zUkzS6uxg3iE{CL!?!(2rzqJ*wO`b1{ZLTdbyp=wQNg+;UK;LhnCE4GlG?|bRx5q-Zu4jmu<6``f0By_dPP)|)FUWn@M{pL5JX)B z?STxC`tML!dqd;lMQWF*1=JX}Ds6HuglGtgSH?b2Ys60Y@8;u%0+z$eeHn9qjNEA? zoQRD*rw%0~Vgyj1eIE5$xX!3{WYisS%tzMnPT2Gbpj-aFGvQ7!dl1-)J1h>?*cV=%`#N3Vo+Nw9bxAyFN7MQB& zW9jZ>?ke&w&#C`|kilaO<8Vxx`d)5g+8TB1m87;DZT9-na+}Pk*m~tP9R8dCCUDN^ zw>_FYWuz$kFvC6|(XimF{!RM1#sw$x>y~4nZTZi&Ifv+f%!>Bz+h{tH)n@&CTy8kC zF2Uv=&`xvwbszIbQAI8Pxf9F+)MH5K2&)i1DE^EU-4o4rqALG^|7y>ES)^Kh0m%hjNdBJ4)f6BLFJESoj`Y@fiSiuz4C5%mfiFi{UbU#MgFP!FO#+ZNSFp= zwZamV!ZqQhQ8;#>hvAky-na(~)((R8eJ4GwPbtT3r3W&?CB=+SA`Ae2&~R}B+`u;v zS_OQ#4NM(VrK+;odscl9mpoJ)>LpzJ9E)UcKd!Dy(b+)baX{XF*) z+A*YpVFv^W2h{Wcg2dqSu&Pua&A4F{d*|%6_%>&Uhp>{q|4JUe*?7C)Kfr0wO{*H+ z`)cmU$D%I14**BUod?r^yhB_=vbI?&2GzY`zvFJs+U4M5?v|s^IjfV?SQFm%I4smc zYU3H99XZZ5Ip-!_r3^B~N^zn$5hduU!>(a8LK z?(_53-~dkabW|Up~E5$xu16j(*`z}9#wjTJ3L?PJe zE71%gD8P&2yY;r#UZE9(?fE8LkOo#+Jy^p zIG%|UxlGZW*BJODRbyuTQn=bxq0(Kp0vjWHB~1NZ8FnkrS?-Cq0$m3~^}51*2oxl9 zFj%auAFHR)_Yl4@q-wP#SN34*n#L4OVv}ucpfE)2M-!B-Ky>k)eb19`gHD5S70g9@ zyO&z}m;+|DHOJ4D(>M0W6W-Ro3?wS?&`u-fqT}0^ipH3oi^Hu|ZkFJ)$p}cZl5J&# z3K@VCay$ow8qm(>(nsDCPiF)>upUnL#%ienN`8U{s>bMCL3oyKfrn`5qK=0aD#a#x z6dq-;gEQuUN8{KCiO>B`9K;_y$}2TcoE|2_vzTfx=RSyVs8FaOff4Ox420FJPux*( zN&mnn=j}OLp1k>yRH{Dk@lM&F99Kk$$%J)U#2&z&u4e9`AN=6b;Wr0uRTuSc6nJ(Ohm6Ku&+*ir7x3$$Hb(wjjn? z2y#!V53e!ZN3SvuGEx*=3tXBTPz%HQgbWr5s282D%5n)haHt&sIBY~XY40r%koR3}+=?hR-a(Xm=vD6%+UljaRld()fCSe!r_)`?yM<1tc}{`lgu+iLR&5rQMR@^ME5iArVr>C zKK;f(F&|9eJeuWL?9Ms8HvhCBKLDH9mX@f*EY$Oz%!!4arv;>>&7*u?|J4<2Xm*Zs z*<$TIo-BUNqgi?TlL=%~OFUpocXw@)$Cb*mCSKTI>pQ;ZP>!L%ZfHnbAewk)TWT#Tt? zf%Ofb*0w9aX557I)eX`oN|++GuaZKtCXpH=TEeuWns+iGasWjb!XNDZ>)1LJ(z-?G zXp;FEUx*j|!VibzP9Pt9LoIWLq{x0C3)i()x#h;(wqRtqG~YUEl`nGDSFK_>$( zWAl*_WH*V5`qjN)-T%2$+BYZv_8WH(YwP1u99?OxabKO3+8avTH@zw9L_3y@Q)waP zgF`H>L9cM!25NJW%#276T|Q0&F8zDY`VfJ`dLW<$=H*6>j)mlYi~uHNJCLr&O}``i zcp(*}iR}+;wKn&w(Q9YdD{b8J4kbr;weRRdxV_-msTC32G}Do__%H;CN%Ad&@cndrNaoboxfoeT z^t*J#MAY-I1u_m5RwqF+F9T+}#lqeFe8mmSQ4Y=hcB&}#|lM^&2478G;5Do{J3It(kpTag$ zqD#NUXn9JR#B10B*-EU#S=*o1n+uZxRUCjuuhQsJ-Kven-a9SziajHH?S4>kb=1b4 zd=2==s*Oy$#Lz_=%Lee>>NEQdJ69;bvO~1kjTK64{Huym)0DX(_T8hNjSdqIV=^Rx z_C!(b3uSJhI*?d~FPP-dvZlx4E@Uud*5e_M zx)rn{;o?=(>f!8#$1kyoIgyGj1?KQg%@nX-;?{pwwoTZUqT8i*GcBT z#Ju1~TZfA?0<8}Om&y41O6F(z`xfNK7;@$%nrTk^kE;mz!_e_WN_*iXd@C?f+SQVz zY)r8#lJpy@jW>MZ86H!ZLo88|Uz1;|4ZfP4N+c*kFh0jO;Icazl4*GzD;}2wf7q#V^w>6zR6( zoa5=i`M@ao2ge9oWY$%XER)erXZ08s&;b0j>j(~`<0QYKHryw7{!1}j5kN65ja3C@!oV0^4z zzu*anZi4JU=CCi=-J>+_td8oI)p3(aL>CM`sJS#ObP`Zh-myCHE&(4j!1n@Z0Huv5 ze16|)sok+?YO_@2Si@OR6O7461M};_JQA!KWF-(FAjD)&A9yO>(~I=4^=lt*4@tkn zv3=5T``%7=ZpPBQBB+rBlC`SFELFMdF3@0nIHGHC)Clm28*GT7KMHdd3_ zhGSk7{4B6YLwd_maqu#4ooCF-8!2MY#9<*gFQM&WhU2Ti5Ytn4-U$~u+cWoOR#X!gIEcXv(; z5_a@!gzlfAY*oCjjTtv1rf&UuXNsBP_4T`NzKeaAZ(QXQmAL%%jBc3ayMB!u;pR@} zQKJc4T3)BNgdT%xqF*EY?*zbQKXSx{?=Y z>wuy`xC7M$MdAkWa51*sE~o0*Yf-9A98iyMQLX=eNC&iH-62mfiow))kdO%rBUo3- z-UN2_C29B7$n=lZq8&LUOk20IMVS7P8K8!^=kvKoSm9D-GW_={H2TW;!OHP%IkW_h zQssn4*-}jNyu|(k?m!MIvSpwxDiGZrBdNViuh<5N#I5Z72coN+{5&6nq1+nb1_wi_ zBHs;d__&_2!2?pL1muG!sP&ds89Z^B5l?ev-K;H|i&VL(fX!8xNt5b@O@aZY6iW&0 zX}GMZg`(3BX}C+i?(^9d4pWc|DnlUQhdpb;>ZY!S8vsn+rZh^mw!(TEtK3646j|YB zi%8}_9`7>$pUwcQFda$E@HC9IAPrkTua}iQbA47(wDI*o=Mxp%!VPcXP}M zbdeVZP5Xb)UiV@!$++M4_}Whg>l<$W(WLwe1LCI&?PQD~c{YFaY+bfqq20@^bED0p z90w!(^g~6#&wu`~YZ_1irVVecooK-I-$~Q$PbTj27~!zPk2#(TWL?uIfL+!pXzm(G z`HO5&mfyOOE4|WL?a7CyOXakDG{N8nUU-M-&kmxqZ4(00C)Y;*V{Uz3B2z4LYi?sQnKKRERzS-yVkbdvwfd8;JJ$uhxE<2;v>+aO%8ds1YG zkyMc+EYSokP44G1uko$fYAI)(y$fxn#*C$qDYE&KBR zq>M`iDjNG)|1QFa!{QH|_hXa#8jQmPKmeZ<_Xas_bj9nMG*&!u`hdZ7KX6_^u&l0d z5avNnf}-1${F5Tn$6UvcWCt%Fivo+BrHpN>5fmJ~3i9^Db{HJ@*7s$E-TT9yd%N5^{|`-P z0#0?_zyF6w2u)3tC27%=tpyR$P*Kr-$gZbk-{UZrqlBlCEk)T%mWnK62^}2r%NnBW z#}=ZptCQXT{+R23UC%YoR2(Ls^ZCA)`+nWRW?i;qh!)-p2hV$q!Z3f>Eo>0l+~|5@ zsjBX1w-CyN>%jwgrAM&4TAjm|K8t3de2#{nqhrT1_l5=e2Nfp*15sprae8aXmlbv= zwJb{DuAqS5+_969M}&?1vE0xuaM#Z6xU4iU>7>6GF6MT{5y;iOvp=Mj8x5v5j`;k; zOntw_=bwAzN=M`=8b1FCS8Jj|(Jy+RX1L zUtev0Gvu%JqiHcxcca6lTd0Vi?-A?TZ`R6F#FzN&#O=IbPRH+&q1~5XPA%;>Yp1J0 zd0;P&OST9rvx6zdf!?@yZ+(^jAYN@*Mw57g+giWIN6NzZ@iWb|n48@$dUK(!C(ag0 zQEJ_5i}-G5`y}cez)0iDs)!-u)<#?OdrIq7$A4Mvd9yuXjN{kL?J%X8nXvtFYZv=o zS(G&J#&)Na4~}QA{+)AdP!v_Fbl}mn}t!iZ{DKrgGQQ= zl>l)+pW*FdQWaGy=b6%!Z;Xe&24oFxPw~xrr1Twzb`)df?Q)Ky*QD1gPF41Yy2cI9 z`Cfy16&;{S-Mcx2w|uU56vPznu;?fMjE275ne2egVbq;(hUvBnr8VM(!rRY1O082@ zvEU&Uh;V1og8r5sC00u#RB6|rOV0a6>OmIJM*NMKzqbDdS&K0gk`VHK36{GJLJjI> z!s((D4>@jQ%QtgA4}uq9B5A22eI4-B2d$aYqq;kSFLeScFkHeo>>lofKe z<2D=7!|umQ;bITu$qEHuEq@X3kbMs>f6MrwRYUG`+G)E;GfYSVKdMNf9vMgv49jZ} z(Fx`LLur>ti^JCgp zK6tS7+}=*~enx$2IQQOzj8vZI3;QlFKTN}?t9NN+>b$&^_OR3?Ze94dlw-dr@`H@$ z4QG}fqE5k0&QYl}jK{%{H9ws^74C~S=Nmt_`}q5)`08e4b8_o{!oKr8G(?rXKgseH zb$3F3)bF0~>m)22WZtccz2A5!p=9y@tbVCe?e{$HQIhF1#ZRf(dFb=Fu@a*2Wb}u* zz+`3So2djW6`OTne=vDPEj(u)SJMQ%aBt4RoXf=Y&!C3b0vuRyI4r0LVfaJCWM3$FH?=9>6TCLhiyx+9d0fNwGv zq($Ig11C&A1{P04qoirOU&5#DiQ5zQx;HXSotT(eI-5+DOC*&VyeMZt%+E8byw~=R zj2)H^I%?fYJ`ai4bO1&ajOwzxBE5YzA@`bEi~~EKO2785av%7t zYyL6vYT^?Ay5$ES1RkbUxfD=Bhn=3}HA81UclL?) z9EEwOP?{cQ(TW+>AUzloJjaL&?!x_=MbW&RY{R+Z64i%2$40c_zYY^Q#_IY9#=EDQk$IeOc z^SW<}w#8+f`F7Y{sNgE^I&Ryt1Vf~qbJ9P7j%_U0&~^p}C2ZHQE#_SS%NWhvjr+}i zo&9A?XL>fYo$5h-VJz5ERe&~*kt2_}-%#>^NYxgm^6as5+n1HM@7YD*oFSbP*Jb&f z@DRyx5>ggEYYfuj9uJLfk)W*vltaIAq^ynYXf)Lpq(+7)mVfY6Wl!w#9Hj#??=UKH zU6y5XBRim->A^DbbuWciVQ8sdaGX#2aT99YUpFImL+xGfFQ=VFv4&-WOkt+6Ab5CKIw|ho(>|r)j zjTtD0dl>7CCV#jJE}45PeH&Heg18~O!{0muwR*a<(b~a*1m(u@OFnxq9V6<+4^7h@ zhUq8o1iNz8xoXaLduzYe-dJ?PJC@UCb!j(s7As{A>zaq@6nQ*99;pVFPwgnbor$he zBQM50`C1(JN3537FG9g{HZJ4&*$){@QdY|k^W5tGbM{h@cjdvnd)Hk5k`_APD7Z+E z-&*B<=uL&CsF!m6DETeW5IP(U>t?)Ub6tbIJT}$U6XTo5=jQJiOtIQd4G}H;u*U|4 zzB8uE4W9@K4wXRTwm%oWJX6LX#BX!iBA(=o8xpalg1_}$R9Xuy0dY$qx@AzdvfsG? z7|tnMq?)!^qY)d<_WNEvbGo038OC}P&1*ElP#ivqkSaE8GLk$8qS6Bp4IHH0Bi-6e z$ROp?OoDz@AbHHfJNq(P$BAqPb1t% z!7V~6`p}Q<#RO37p6GU4eZl-M_37n~g4fVHBHs{i6`_-uV^n!FprG&6z1#_TJM3+L zG}}BY3jLNY(-RM>C*xUt#1}eQvMGpL{|!qM_9L10QR@*5%%JcQp*w>f5ZD-H#sOCl z$>#tOY(7NNiH0>@;F7<$o4Z|JY0??gAi9E@=`o?@fqip6XXBp5t6-t0CN${{s>Ct| z5%;J*sVYGqmLa5tijB$KtE0Ql+|hO7E5TcB|9K*K0)mY`V8g-e<2?73Ghn%g>%u?B;5qvM}6y zt;n$8XCO0Hlk2$^gctH(Yui<0E#F-Xiwo>{zPBvw(eS>n)A6}yb#t|TtoyhHYRWDt z?`)328qt6snWqhJjlNtS7*#o|b0j%t%CU!|6`HaJ&xXaN_@4aRSL{<7_o8F}qB!Mf z(KEzZ|48LYF&Pp=IN|q*=~_DzYox!0sS<+z=1XK3Wv;w!r1LA}U)U><=R9fh@c8Fl z02T+ffPuQOZN?rGP5?{=uW#!r<-{nB4VXprYfOlEAsh;}g#zu`p1#+mH?M9}K|eM{ z#U>j(agfmvBT6iRz%wuMXx#%F=;Zwm^>|&pm8Lh)MS_IES)?R%&a!kdc4J|jt7_Qy zFFlt9aRmm0!w_+-Uw1{L!rmAo@DBL(eodZ%h@*pw`xV5*0^T2p5k&45f?=`oOP;_3 zBJ{xRD;xP=3-K07Vm-(!QGPWzW4qkdP+kIXR$hk%N@sUw<(PYR<2Ga4hBniChqQ%T zs-iM^QO?v+Pechs=@4*8$Hn=3ThpaQc0=83vbfn`34|rU!)V>5YMV^TN5Qi}3)oFu z$`KQ}0gy<*D+-qf;t_I?5Cca1rfXEWusaRhn?ULzNB5vwTNMYgWl}#E{mIHMpSHl( zZVx6wI zhQEqP2Z2=mDwGbFYtb}anxD^$v2?f;#Nk$Bq(imRcB`3M&c2&^VABgH9V&D?j2vuS ze2(AMf&Agg$76r#{?TNT%ee%}S;g($8Hw;Axp?kZ-4;nWe$PrV2LAE!IrbO-jn64| zjj@Y7_jinuly{K#snomN@=dp~c&@hFoRX1yJm$mdy83c@Bn0WNNf+1daQS5*Y6~m( z&@?eql_0VdL{lh6Nt|li?f8Z3iTGPL^QJbLhskGN$y5Xzeg(VcP?)-EwP*Q>+n%Gt z>OCsCvbhJpAB{6=$L^VUIx$kkWLRieX`D~){goq)j_jT`8$UF%7m~ne;5>H%CnZaD zka5$%oH$3-P-C$_7?8XSZ-~Wrc?|WkcTY882Ejl&7D`nQnEYVWGV1^_0{*^cC7&})*)i3;(`zs$Y`fYTk@8@_M1gHE-lqw? zwkc!1w+suh$d3MGUVF7B*TSE#yU8aGK{6}pAUgp?H_O7V4e*(M%fja6fwi!l0&x-r z@eH!J#-(z)^{>~`N8t&51t7@}nAWcmAY)(6c z>zh5z8IWC}s!rJWx=u_@LcfC!veCj%~KYf<**&M))y9rH?iIPHAa;xvaO%M*IMsroPJ){FRez;TDb>Y-sW0M zGdG1as6qgYjUCaXRbtA@8Qd5}f(Zl+)hR1;n{o5J6{Me1c5YS{d=J~WDj z#!~Nqwd@fXsKZ?yz~dV{<~6}aQnbUX{np&}kG@OCZyB<1%V z-5ti)X39*P&7cff%OEu=|1FH#P!)SNoQzyuydbqsQxv^iSHYI<*;b9^>PaIS8Ieq) z44&@Wokd7Ibx_ubAukEWbOlA^8XX?!2)VH`3AU3YY0YrJ0BFu7MZgGxl;lQYEt0#A zDhH#>BR(CH9Adk|d@N=%)qeOB?Ch`YUi!pIy3;Ue6INSAMs2guf!l6@t}_lAZ}2y( z$KsG{K?q4ylrJ}_{Ef9T263}ifT~=l{#<&0sZ`~w*@fk<*s$;4uw_Z7YMfXiVl$d+ z_AxFZH^Ndd&p3h!occeDM@lvMUs7^(tL-)t zhXgi#y&uvp7^b8C74TcIton(%z@J0h{NwLKj{QW>`CXTrNM>9C?)O}wlYpx3pF zj6u-L>CMqj1}{hzDAG)&-%kY}tUC}tx8O0*zQ_A%l%UB~N9ACT3A8I)c0X!RZNR1~ z)WH-wNNJgYFj-N-V`mKuWs<+RC#ptM8(L_N>=2pPu*s|=?9ee3#2W!_bS6UB7V3Q= zDyZEhdg#!I{$&hu!>k8>0TEvw5ZMlZ%*Dn4C>wjQenU71@$j#oLKICh$KWHX>`x*% z=Q7mjYa=(VHE)pwO-7$e^z7rmLUCBJBnATz!RuU}PGW;dZa^!@xm`&=rpSXH9lXHh z(OvN_lSu?YKVAB%_pvC??h4|BIucRYHW1QN;f95{teD;w=XX0$7AnZ*zlz|qMfoC! z^3|cD2uHKTr|^>zFw!>p02Z2zm7N2HXwQr6vZ78Te}Xg!4ZZ9=!0_QO84!Usr<-C4 zq$B0{ZG=CPrfm_NZx(TPT4q%<`c>%LDEz$om-XighZ4PQ2|a2l)+ zo%`#E?m_jvu;HZ!{YdSEoscOujXQmk5C(#qqr+I=S?CGG zJ-3Spb$MiesIb}6asg)^uz*SHtBE^Ae*>*8MfjS?!Y<8pY-0u+>SgLh;P5FolkDz_ zB(9v#FJb)YyjJwkV_Xk+^OJ5iY#XvWT8!+Lvzw~z-+4fz^A$v+?hoG*TasIO<`h4d z>iTm<+RX|CS+O17Bih{QrgJ##b+_X0*?JKIiPKnE{x*YxVTZWJ3pdBFC&RuksAr9) zRcNGJSZ@eATKre#%%cwKJ@Y6?7#x+s5*dWulyeM>5#}(LbI<=L(l?40&Zt2D@I~eY zhNfOz&JgPq&)_F)>`Ar?ZSj3rIP=U@$pL2HcTvb?%f@EHfu!bR%Yi)g-@&f{&>U$9 z#UxI~WPEnmNsNv(_1U4UTX0UCgF@0}^vJZ*^nlqeu4%1XaL#Tc?}I83>hqvUgMy9p zN`cnUNVI0cpq3Zni3J><)L4ih@S4C_w?eM4DB)c2m(F!gsM9p$6A-3=Cqkd5gJ6SM zf_u6z2m-=0^nL;@N1pe<>TRC)B-E&Fc+clH{VLfXcpvcXLEs`MX&D*YB^-Xlj|=e- zgAx&(`Kktbj`iNd@_GZ^06C8>BsW=sbrSq+K8R`Hu16k*>SM+#km1IH3PIz77ADEK z*ywgDSS8Bq5%8lhKKzSQ3?_vwu_G_FxKb1W9gmce+_x{*(mL~76s?IEC`--Y*1zf# zpTSgQyh(vY8SZ5O(S$WGQ!E362l{Dl_=VYpWQB)LEy8eTL#IAV(0*i@O;7;?L!hhl zKl@Prl^K0`WO7U#@*$nDnp?uCaMNs|t%NXgxj>O(UhbW@4>BBB!(Mo^v9_q;NY0LK zjRO-C;>edq!;<2fLq$nAMN5PTb0ccJT{F*mACZ=%aK?1ol5NdZ@fR}5>P%z^3TJY)(dsnU4_J{CA+LhsCOQ^2sPgt zFWl|^IpzEwUDU~!RdD+r|DV$_AJh`BYXr;UVrTKKMjX2R!p-~fFsNX+>t0oIe+xgu zOAw(&Ju(eOu_C7&E#`hWh|P7rl1V34dbBcZyb_fYqP8~Zf{yxUG_9J+jJZ5R)=39y$RhQLRWc(3L@Z6!4z1{P`?mmZ%)6Ooq&oUoY zv1zv@!REFNS;OJw{7{UA7#Ft1?N^7E7@%s8-xJbL&4QW_`43^M(8D+(R)^I&%&&^MsA>xMeE{>0 zHSpHM)PeANQ{>$jYa$T z_-L?|p-ebRoX_x0fSv4P43H!3IQ;QGDNp7OiI)=K;w+jofJs1&g7~*{g;ju{riFs# z%=(8=PvXv1hXxp!zz%qxsV6X9d;Iq23F%K@PKNpDK(7wlGwU)`Z$HH)oy^~lW_Eud znw~2CgGp;IVDD#M3yfgy5;h=Ux5by80@sCnOa%11n3)YQQsWXd?PkAalxZ0USw&uv z(zj1++pc@-*WNe5nYH)DPm7rzc%m#VaJ2?r$Q5&~nXjjB&0DCgnL68XUQKWLor=Z3 zYqWyOsK9k<9nW;xrQUVjh*w#ASFm3BV8{{ok?m?_zb#!&dN8C|*$WAc_xaqQ^MvBXT3E7INc_%@$)aIuZ2@~8TtLF(U2 zyo#4eN=d&@RCqUFkZ%!A{7W8Xv7!@nk2jLmzISt_G2vGS002-3e1h$0sSZrRx#pRdvB3Q-V?0qkw{-hydAJpalxwq9YIaq5qF2}$zp1HGFH*^@y zccA6Bu6eBor#eo2mD8AbYdyR^e?uAZ{YKoQ-!AH^sll2~;cwa@x+%Qk_Abpdw@YWw zBsKp150i+1tpsk#yVyTu;4qJFX22L1^r4xlmj=ZoUcZa$XHjBGI^!fS?7@u|w}KM> z@s0_h<+ibV#s+K{dqU@6i|kI=6D~MZ1jFNlc4!hSE5j`0Gaww1sCp43 z1)zvbuV=Zi#2cPte@(i2;{-h3l0wG2)3hu;eZ2*Fh-k(k9zLN zRAQ{c$E{EWyuNY>h3~fs1AWx3ie^CML@#IJydFG?XMVT7!YWQ0z1-${DhL&6q&C&( zL(8?fx5CO+h1}fuu)!|>Qlm6AV5bpSM!ZMXup@zP_DA_+j4yOk)2!gRjQKkY%H!G> zHenzHpLW=#15>bywoR;=xXXDTvanOp0pINh7=aDnwVhjP&2a^%_u-lB;y5aR#V}4R zPqV}i7khz6m0enr6`Xn^Yx;leYL0b@f3t2Gb|50B+2OCt23n-+lE^g2l#iQdL*BW6p?K?c13nhIW6m1PB^6qKZQnd||Nh-7&e?HP#t z1@rDSAVGM-0*@6p{u7aSqX9iNnLunA%eJ13+`8>1BxLBMIlToh4V_vtwrYh6S)tlU?YrmDHoSdzVgjO^>+*X{GJk)< zTg{)Bkac|>PoL6jFFJy>MzbBkM~gLE{?I!{8>ly6KFTdRa0zTX96-5b3=>9QD$GY2 z0eY6dg3M281|1F`GxH9g6l5vQN7?L!4jq`(O9Wg-@|jDKEQ+^|Z>e0KIJ?Xz!J_dDF!V}H!D>WUyscbWab!n2zqT5hvhrsyPx727Y?{7wOzo0pTK0!Xqu857ZSY>` z$C3Ptf6u$b0=wX{#fLww+`ro4+}`ZF&t6?L+?;*a@Tmd51U3?w80QrHyj}3KDCs$W z#^r`G*o76Q<_;M@XvjGw+_d$gel8HN_N6c2O-ucSbt{xGbg}A9S;44tpQ{U1x}ml7%-9L!CL8gyXo-LW%Xtf<%OFERKvLk2WVG$Nz#dIJ|a>6XSlVZ3*s^altp%x zcy@np&`PL*^$nh3l$$ado*0w{EJZ+0V}e-~(?fBfa$FSys~q;V$f!l4J-y@$JoO|U zr%%F>xY=JP%0O2^nd{+TZNMQMLAyxSba@ig*Xi(UW|xhhnw?nxTf_gM=pdVAjB!=H zu%{C)j!0u=5=d9s8Dn^t!mcBpAOTU5s7nAVsfrf%*W^$|mVqsS%z>@5LZ=N>AZvjD znpcrb;PFHrk?iQSU6flg?vjzic?PoV6(fKQRXOmmCmABhR#<821%U>e1>S{N18>jF z@sE01xwA87{g%J#B;6k~LG(w{bpveD7BePEi$vs4#Kbr|+Wt3co1{sE#X<&5b3{Se z33zW<-YPeZ#&sd6d&7nW6KjMo1>&1#=PC4T?eHJG6GgugpOO-y|JvI5b!aAbG z>{8?(DoeQ9m>tG2Q2YQwK_AW_oTRHcSXpd>V=i~dZ;zz7g&t4)eoPTYpy`Q#WeDwm z9vs3C(_W(@euYbxl6yROZCF%o(fW0>%TI)NXWY)q&$Du?!xT))n+8v2ncuRedHR-$ zyi*x@YdMQ@;F%EQncF|V1^-jzY0()?W0o(sTU9Cwi%To&^RJuZ$gN>+EvjO~eQ7o6 z4jCv!suxU&r@CMD9WrR}1@Vq!9FEK+4GX?up0h z4zR8DA1VMJhT#1I<;!?u@lu;>!Jp&g! ze7{w})%-h-Id5DuN6mcL%Zqu07QeQ}w5s7mBjHZatJQ;z5!R*>Rf>XPFGwQkm|sBU zrizOEz;tcm9=L1!u_;>dO!@zFeDrG)!T-i*0zK}jdH8Bh4owDZ4RZm7ovNdrrv ziN_L22+`jd|=kl1|_6IPGyecr6tpQW}dBoigk&Q??B+-c<^=@ijCd1ZG zoeL^ao?$dM%1SA~3XFcspExln4@wa*PSSJYg?^zF*rWsyfBNjc2VxYK69W`e^Lntz zTy3eC7W7}Qp0TmNktzh;uWst)Z5217ywWDnvN;p?nv*ps?hd1%E8LBL2jUlW5wHur zm;>INMe#WvGy4^K1x8^6(S=#TBwYP1Rg2=#*IZ$K#{6ttdSvSP9oasC+=3!57D&;+ zhPN;6!gI+EqqJM{>Roo?(rE96!5K@zHEQAb)#$8Fmd19WD}`1 z8y{iF*4%X?a#**`5;EJ|D|?PcyLJG6UxArj%w7IG_I6<^x%Cj1CZ-p*u%wZhyf*MXch?dS{6HGuTtfAh*Oh3JbEF4hg!U-Qx ziMUkk-dct_F;2y}4Bv^U;27@wZCF=@vSli{XbH%;jW9ttl(W~kMnny)7MxDs9aKM>TM@T`;OH(goy}Q;caJSY6fdGQyeCU};ex}g7oPh-B`KVdMn3o5P^9qnAF$*O z`+=L3MR^aY)|kYr^cXmH+z|4Oq1W!s7++zUMFSe_Mg!_wOY9mzAq`$3J6oFd>zkTX z_rN6+)@7()fY9>?pBg;6m6w)NkcuH67bJ6LX~RbU+qgX~=jC8V2K~vN#x@ZKI4UpT zOUuEdc@N4jSI<^9@(E!%-~^Cs>$Noa9C&^nJ?^7Tdw(z-~+1d$ZA_eYiBm?FB{b1zxxEOx-(@uh%UfbAhx%Em!O!_Gxp~ zh{jQ++Qs*ArMyBB&C<;?ac+oov!dMBeiQ=&mV2GoSBv1Z72Bq!_p(F zvssbs5WeVF+heXEuBq))w12_HPSHC^>~g9A?(hQK-R%2<+QqLX37IGOI+Hk%)o>An zIdqDfegug4=eH29a!~<`%s%T279}b}Yt(R~L0c+7+8}9lyR237r-u4W>*!(V zvx1AbsD>LhK-wag+-jyR+z->4A-Zl3mhl#&5M%$$K?!GQ!boZr{0K8aO zuc{8OcTHMvEUfVv!_b}O*Wry&(#KUj6Q7w0xfcXgWQK*Ve*mh4VeAmnZ&y2qR4~Sj zJ#9911++%=oo^)XmjXcysoce2p`gCdE0w|8Le+39ZrcOow*hQdUPlC31VQpHF#(xx z_Z3`b^dTVg5H&*d)^{+t`<4*~2%jbsZZ?S=Ap&zU+fvP69O4}=;i)DzKFj0V2K#+C zxF86W$=CzdPQS?%QR>XPoJ==Zv1WuFxbDg5S3HdH{@H5E)Y2sybJjta|w0F)bh(o2R=P_~gQBK#c+X<~+Ra1b{cy4o2654&&O8-HO(S zfL$Q_vP%~3JnaV`$)f;X=E=xAGW41mDDDtnR3K6C=Yg|g5FyT{VTN@fX-!48iM!?X znDS@3QdV%*+#KEPk8xDH`&~i4EeG?0e!P@evU}Oo-{}$$aR7oZbG0Z?>gKV746;je z3_M4F5JCRz)alE_gTdXr*2=p8yye^>cu@pLdX(}Yk)11vHW=$WN8)RShq~MA=*7jj zN)wEg8;%|O(D-izbIFTy*p?F=Nwa@uN!c0j5T|@YKF?|6s4c?*HU)%Xer6;jT!A+5 zm$$L;;%vcOjw{X>^U3f+dB4T}ZEFl?NhLs#9uQ5TF<~catANhVJ2F*aySS*}Vf&(G z!8`zwg2)SG2Stp8P1~>#bYD0<2`hr9L{)edTZV?M6WxG!0Zuhv)k2dYIMn)W!?tyQ zlj+Fq~3Ce^DQ4wg!aOP*?+rb<|4!Wms0Bmn;G9F?XS;2;xMDR5`-QtWC7RcC? zDyPa}mn$BgRe9q76*BVCO&F;SKKW0Zw<=v=sB>|=qG-EHNl&85WPY#c_^jbEx5VJ0 zo%$ZO`@S%6fIfPTDb!QKTU@VEbaUqZYPcJBAY|#`Y4hdB7j|?#51kkl0JYo;0Xys< zCDBO7ztZ{MA^7O0V2Mtg;*v&NfTy#5==hf7{>50pl6PfWef%b4ak4EEH;9?u4mq+^S$J4Ss4nCLcE?@Gd!s3axYH#jRb~)vBh+yaDS}U+c&S*l}+7vpwt@~@~`#pS=jv3oqJYO3U=Obt)DrWx@gjXpWx?)`hbxkqW)?>MW8^^^7>ufC#~ZG zUv)MDdDaa$ecoyFX7L-5jKh&}j7%czmQZ?9{a8b z7^KhN4Feibx!N{p3_$lyZ?XC>bTGqIl3y+f)H=d`k(%nzCWw#mC`N)?BA8q_?LA~XqC%lLNAB?#wW>~aX8uz z3ma6!W3k5Y8&<(4v%eprByKxe*w)2RN1wM1(D@Gyf|31W?S6P`)O;HZ(IaMrF}`j{ z0!&wq_kJo_Zew)T96N(nNNLw6Z!DdV7qIlC?UTO3C3gZ-Dm8eS*G6@*{VBOpggA0& zwh%CJ2QAslI|}jW>={2L7&lg`fMh({orO^8A7;!>`}hq_<YiPaZ z>~rV4IQ6>r+bN<~l6;s(J3Vic*eOpaAyyImm_mJgFvdqzSn?T0^Lle|CESEyM#{Pd zi!w8a3hHmo;QIcM#%veIZcRtns8G#_4zvlx3fLl(;3IEjd?k-hn>bo9Z9T?YC*^=I z7wb)u&F*kxcp!i5=pAcbj1Yr-siCg<%_Hcd%1rT49B8bb3hBLtQ9eejCijR1(e_*NOUBr?{LS&yt}T#qa*_*j_q4bvXgyOPqXoSXt~ z8`xq7j9>t;5=-)@#`=7n{*RYhQHROxq&)^+-=e!ujc)~0mb z&hi{{vOXZTb^pZmSzzxjDtN7C$2n@Lly1{8*!JIsArd~?O5@0#r>}r|p1RD9LH}w^ z`lMVkjmV_ByR09w!C6qFn~FrTdAcH{9vNnTN_Oabq0-GqYqjLhcVWkQG~@t%Le`bT z-1Z)1=OzUV_wf{m*k#F*wI0zw|;_<-?)GE{=TLSJEV*(G~}_%&}b6)_RS??JEXA zYVrQ!Es)(*N316c?;b~d(GT_Aut`K;1cLk)UniOw_gb*CkTj(F5FeyzppVY8Wpp9I&a#8G8axtyfE}{Uy$(K)sWIs zZh#P?zT>Fp0t0I8qnjeX-|mxk&g`$1XCh0R)HxWeC>x|xQkHJ9JV5y*a50rZg_Dsx z`ypY0h-(X&v;g0|ETYY#SWr;RC8Ai1Uv-VJEmmcU~4iQ+?(m%|NqJ5wyB z2%fQ8d@T#b!Cvt#y%%?X5t>}3Pio%;0;oE!R9w( zC`mC^eO-3fmOo1r0Nhvd`(AhKz%mR+R?P6YTBzgUQo)O0VqrP!Nv*;rXaEXAql0c9@F$|vIDT66q~j0 z5s7n60<;T;K@J=-!%Ueh3`-3`)p+}v>5(T6UC08YDZaGZYef()kp}JG0xVfEhyq%> zIt_AAh5R4a-WG|v5>rjYTtg0(ZfrYLSv)v9>@MDM^knshX${ecbR-SdO#U9?iA>dF z2F9|ACeAtIzEjZh15x|%g|5B#HRp8bU?iybA*N-Av&>o;N3r^3dgojNwn*s<9zxkP z!F+;lT5mEM^SSd*C4Z@VVkJV}O+1nDvJTl@bg-4tJ^4MtBY~(EhuRSq3^0Lc~AV>{_-bdg?A`0Fv)GPa%7>mL7FWL1VSBy*s0dJoyr_v zm8N5SA4U9maPeskQ-(o+-VyS~MUcX|E&@x6|TVHrDOkI!-JYk`pWp+?l zTDc4R(Q)Ad#SZm00@Q&SgZU;NM{{bD*k^erLes7zQV%mKwEi&flAzzgHpD((T&cnp zKJSm{T_74U(XGmvWzj${O*QZix?oZW%P!Vp*5sm8(;U0!h_IJJY-K^}|3ZbYvD4DR zeFP{b>%D%vsxe!@ctG$=(9gtYx+o+8V+`a0zg}+~f&wt+1}jF;q^n(#vNi`}aorp{ zyPA=dcJ>E>Aian`vc$k%b^+zw&2a<<1@o-mv7BxF0?Ya>X+;>=GcS?94Ey?rS0Dy+ z2LzgO@LADAHc9Gcph~+tj8pk`GreR<{6h~>P)~>oq7Fdt;*Epf59AxE=pO{`3J~so zZ=6yt0RMh`_Q(=EdJ2m>R zV!CDt@-7p5CJ@%{f(Zir22)7Ajv@p+12)VcaC9IfI0-s_UdW%BYly{$aWsF@fUQTn z#mZ9nBH{+2#A3s^2_o^;#V(sGf!+tBxd;EzSXe7m6O#s*bc?8c`rc6F!lugv*Lkt8 zA0`_^{@^M9J5C75EsC#Cr3#ygio^bWpwp~;X|?*R7^}ALE;_vO3_@&VmP6BW zDh%}}7FLK&S+IAIq8us;z*e8;Ua#9V+D}`2oc1@0*p@itT-AMpOhwTh&H_nR{mV_ z61)n4gX%3nlRd99 zWt7G%xv%ClZjCmueRnHM)RPmuE#%azM)Ste6Mz*8l zfOl+X~b9QL+qW0yeViN(5sk-Ob z+hx2*p#1vx8Z2Ua7cOC~ri#pkEjYgH5y*TITD1#Uw1FBa+vc@rpak33pKI~3FBPO~ zKzr5uw#{2^eT!F#27SYz-?+*5G31FLrPoK$3%N|z*Pp#CX{(b<%k9<<42?7^6US9F z&NG1#)qfU7(}6ff`@QskXl>g7P|`uGZi{`uoi_MsNl;@B(W_kWM|-2NKNk8FMKmRL zO_%@8%WbKr-Rb=VaiKaW2+4=3$KN4m4@nG&T=>^oZegqtzX4HdtVk6w=xGS!MPdu2 z2K{^}M@AlB@W0WpiF8xeaR_7^d_Rs+Y;y&u@ej?)lT$&}M>M4w;e{WeQ(+y4JAnPP z01_}Ci}MbQ9lBi}-VaQ)6C#8z%-&CI zWSin!{MyHIlt#Lz8n6K4hg*PY13W=jo+@2SS&cn%!yo~Od+szvx(E@6WJo_C3OsT- zzGBoM<5AJjjH!(gJLJ!A5CTJ{?PLR=2B)EJx8N3RoJjWX1Uz}i8pn`#O!C2nS34cw2o3@8YRy7?;YyolIV^d@(AM_^@sPll8B=*2bBOFXv2Yg#?)zStXnwQTI^K56xbgqv zBnB^hVa3v;;bJuh(C$p1Yj9uELuO7eUop3}6KLQpf(npELPEbMrl_Cxs)-^!K^V;ey5Jc3kBf>Wq4cx5c^W) znn|!}25ps#r;Yf@Ad98~hL?Hdn@1{PNkw>G>5?~1QLO^G0SFTEuoA`zWPIhgg6<|k zEvN_>xrdiJV2(wBz(VG@4tk?h#>EAd>=rh-4eR4DH6Wt`E5}L1nX9KWSkWs1kt#;} zv@z_5aAmyNKOJfmXb8*wNvc%u*iwVeVW*A4O1m0(zPOu%{tN(Ed2)jY`lbT-xe)HU zQ37Fusdsf_061UV+(qAqH9X`i)f0pk)3F0sTb4Hw3D#yjoVEv5DFlS?q%$|rKou#% z*3Hv$MPB=H(>;s*-a+Nb1VcmFn^QzMWKd1pHOA&o!{i`y2vPV_IpjY}R5_3|jh zGkd#A^)YIWg3A{AeNkwgpdKJO!K82{tZ;23{ey^&s8X)xjXR`mR3d>d?OY~LS{$gS zBYy)y<#4lc3dXd)TY zTnI7?9vGv!J_mztYTk8cDItk=O1gU&?6*cP6A>4V$&Cym=fl4KzRZV{>#;8d@LS6J zREl|AEWj9?)(SAZAT8+-+y)QZt+2HRDr{qnFd~zdYbW|^pj$wmgwpOuvu5JfsRvGF zJY;ma+G9lq8RDdb#amCVW+XYUMG{wf*i|;yJIW0$Rnak~b$3|&pIb@ta~IOD_+fGC z0T?YMrJ;}HgF6iX{Yn_GBTT@FbR2~QwfvfeJUxb$jx?~+XK)20ZJiwfxE-+M1F?d7 zGye|QoP_b_E-HMk$`i|X_yCKljsMU@@U%*2=1`ea<{IQ}U9))u7dJY8GB<~RiVuA{ zE{fk}8!?{(ye2dkR8-%=;5Er`Ht6jQ3j< z&RMY5cOgPNAa-ZHZ!?xVBsM7)^CEbr?+SHT?}b8+C##R-G*&@F8b!ki&7$S?c0#Sv z+dz|Eu&L2}JL`wR_(;j@4DI3yM@h6)cC9xW$Cyfx^(D`IObHI74dWq)7hwVR&s z#@%ew3nWxb8pd0?w>FhDKFvee+B zRZgMpK=iG{vO+oI-~Vhy8zfHv7<)Tfbs{ z%TYc6F!?a{LT;D=;3@6*b*k5cJ>@SDS;$Dzq-Q`s+8e?@m;wy5Fp!)cRY!sXNyk2K zrG+l;Ksb=f0M9Bz{E81+9JDD8(R-5bX*)cw+R##8S0Z`%DgYG_R3UePx67|2VxaiY zDO+0Db-7u~5Oh-{d_fgL68WNvH7Gr5FpZj=SpP{XZ;eS(T*9-Osj*%*)EeuItmn{) z<#)1WrU||&R(2eyk>@1R6ADfU66p{{K82uq$G%8GGr1R;#En0FgTYZ+ix8PC*hOFBr{#*ViJ_fOXT$m+20O4P&Sd10xEMzPR;)PduM-k)ON+X|yo73|6VOL~NpIInT zS<%Pvem+Jz2qHfHU&@C+0pLYH(9$brjGR`W>|=EZ9K)y(p(Gfj>-3dp>os?GB$H%? z&e;W{q!GqXSEZZ%tSXg-HA9Ld7Ty)z6pSjh6JyUV!M6<`?3@5F;g)s(IflVJ1=(HV zT3Gape}H|P4+~-e$Ve(iyb<~FfPF|S~ z3nvH&&9LEpK$}j^Y5$d{6*jQFt(p%-%bA49Qj+y z`hKqv4IsFVnqY&!=k3Q|yqc<>)G|z~(3ho2K!JC7X%l>UzT66+r~EKDNOC#`l8LCf zZY_2wpS%OZ;AkEqh!o2AeW{=H|5}x!uAGQ&=~*)FEeBo5c9mW6DQ97A-2@5ptfjAX z*2JfRVlfM&0K!dKQJOamXjYC@jHNF8a_QCb(I=g{OU8(8BubTBi&N<`a#;PN)1Q}M zG(oWa3rVQ~(UXjy(klTh_tK{`O7;hn&Wx6#|Hg6c*tW25qW@X_pZ#fSMtJl-X(&2W zI7i|g_uF^J;7Wb^ZFKYWjho ze*RQGh?kJ3{P9ZsP|k6HG2VO-|0831RkupOMm6#c*i7-EmD-yW>3|sd4-uI76WdD) z{!%Ke9KN55=Xu_6RwcV#9FzoDx#l+mPBkg(e*Z1ps6@)-kF<)NsH^@`%mhF^&Mz+f z&4-ZPDNIjUdb`TKtNai!T%TN&n^T9BEp?pXJ-0ii62oH1b? z2ce~^5Qjw(9RB*peDr{pmGoiWh7`1y%1zC(C!)f_SfuR9Mv^F^-Tr?2ao(R9eZ!VRZ(;& zdt|?@94>Tbe=+Ln&y8+#*+-t4&I}A}MX>gJ#eZ{2a67tcofS)!?RvUu zXf_8r7M8oTOZ>Wvs4LShX-PbQ5_OatFu=V*l9&GDlf82uT!5>I)1n*1|5%r1X`#<52+z(JH*=sFn$nq(`aL+pZ}Mr@Pu z!1ifRj_B}uW2pc#BMlM^r-z4__HaHNxJ{a@-5DA#Z4F@eItaNSk_+zqzYeqY7-r^I z1!E?j_PNJ%EDPA-{4deUP6>vnfj4bA0!x6)0Lls6gV7j?u0HHBtG`{oxHg|3rf6!g zjK`*u&l58G7%9XBybA<4o~(v?F}vDQp$ec7a1wWHCLn?KXp3~lR8zR-+m2Dq`&ORl z`-ME$yY6MPkU(@^u+8T-WScG8!f*2C4D?xFBBODx3!pvZGO-rU*m*wjR$HJa;kevl z!Xb^V?Kc)FRy_$j$P;~>(@-aSctGZd{O>#88@z3V4eBD!7sMSawjez{#Q!bqcLWH{ z&EMy2Jb*wKlI7hXmJfWHrvR~DyCSU#3(=K)c#{|b(LXT6jBcs-ojXiq(<@_GwU6ha z&ym9g8flguvy}1#Iw!oQ`Z%m8S&&t?n!QC#G%f#06&x$-V_1J;#$|b8WduVd1vb>8 z^-+9Ft&S+Eu7_#k{#ozJ5a&1W zlI4OGCQ)|FsB6GZ#ti>+zTOuS0R|K-2|&7W|B;$e>^@Ln0&8C>R#7LpI>zM@d2&Ik z&XrT2W$j~%`4mz}V8)Woo`x{5;58;q#A{bfz2>y39ikAwTN%jglDKZY29&=kDj=wu zFu*YoqK@B$Zx5CYNZ-Q|hse7QzK|Z!CtDES#yX~R9pM3UOlw}?^T1H29w8U9K^;O3 zQU5*ao_kmYP8y4dGN${K&btB6h9!A;y&;6mSxEEngesscs+fCFq7q~Ht?2uKoI-1b z8dHruqAxq3tB^k*F->og;tW9+L1PIP^0$t;UyU)XAoiv>alk6zA=$c3*%|UZ88U}* znJ~kcbHeY{aZU;7Vu<(8X4^5pU%?scrfQtxBECFq_jOVAbQ)GV867Qr_7?z#X1`YD zD0n4?(n&Bh19qA@EUu+b5!Keu)o)1|!E;q?#_L?RrWfD(Pn)mnBUFi(PDFR=<{U+z zWT1~NIiu5d@)Tq2MjfQRiZ%%Q(zby&85d*#LHST10a>8y8oYH}$fYqK5lyNW>jnei zT?RK)dnZ9yL+ieP9TLa20o7&VWgHA*IjYH_EY)+Lcp_f0}@7l{W8?0y5r7d zSYtMiZNY_UV6d?IL^cx(%WfQ597y-a7LZ2)-x3oR-Zbyj{Z7xu3d+$25rVOZih{fE zNTC%%MCPEG_jWr!FO1+rkp-9dpKRpvFB2E=hwE9nU7oAfZjR>g|5!Q~a4gLJkFQp( z6193$lay6@Tcj2uq_GYbudOCS(pgf7A`uWin za{Pa8`(M|4?Y-8P>~cT%{ri27=la-jvU8SG>v?&|L=)yqp9eZm7F4#o2umP5f8L}H z9|>l{qraT|pBZ6({O?N8xm03Nwyx24BgEzGt7$~epNqinv}LdBOB6GfCZftSbB?HhJG_lhpX zgR(8{Hdyt1CXsXKP{XWNt6b+<=kv*mq7xy%T6~l@TK>l3J z@7DA!n$#%sODY(p9o_9&DvY7Go+nn;>zGOXsD!bL&Q0tN_3D4PeP)R)R4nztPA+w& z1EYdlGP*kKRh;?~dNKBEcg>1^A%d%#nE(bV#Hz$Hr06HYs{*KxPg5;^V(kMrzo=W2 zMM+9Z+mq!uN}7ISw&;Vl8gT1xB%n>`pd3XF*ugI6x^4`m?GsVH^dy|w$v-;Y6aL-K zkMiGpg|wMn9h)+-HHxB5=cZ6HE4NQ~d`D{?(Xe;l(o zr9JJ!my~GT#(P@$BbvXakN-^w-AN;NVIR}x!VBc8bg#idg$!@(*=LPcJn9kQi;N*? z3~*0B`JP~w0i`ITiXFxqHt0_UyT*xC391o2(~b0n3Jw(s5Tx%o`5D}# z==X&NiC@S2ez4P5zcK)+zO&FjA-=EtD6KwUq1iJinhw^ha&%9B?-Zc&aJTdx=0JoX z$d^?aVhie4wXi*LR|;SK{Z1iS3AjC5&h{_E(AuUzG))cFhp|f6Vm?6yMPCeI?#gOk z_dcKWH6)@P5iI$?%D6G#CW0JQ5~^zS zmJ2kvgG+N~t@rr}yMB!9StO~<7!E z-7IY_H;(ICLd@ii%E=GNl=>ISDuZ^dtN?@KpRt!M8X~JbdZi+=%ji0JZVF~g#=hI? zoHp!cXV75JtU7IE(r6&nVcxEHz+dOz>#d)c{D8PrD}UE?rV9f_GkqaUE|yBL>uZeJ zEv*U#TRKX{)#SW)((1!G!{lZJxstrv)v+R~HX+1F&$xtabYFp+j|TZJ0wt?oXytW#k2xjpjk3PW z5eGx3Rtnit3n%L~nx#dhf_Wbpx#Pr??uqseBV9Vxg+UL@T~e!EX|?~+x78gP!1EaP zaXf8}NUN^(jtJfCx2VH~kb)Vder|bDY~->sb8Ad~mr0z0i0UFa1dY0UI7$ zJ8tb&&m85@ak4toI%sU-nouH!*^WvJ9Xj(8kVzHl6ik3rO^knXZd@_3KSfW7shY@5 z#`eS;`-2^pe%)F0BQ}e$xBu#!e$(x)54=?W7(|pqHt5VNZ56GDK6@X!u4r3)(`Rw| zWvf6h(S z_oM=dVT^dko|?u^=Q+}s)UD$B6I&gEf|qRjNf z0#CRr8s||%AInNGP^??KNM(Vr?ZFzIyw}g=Z6P?I_ZUO()71U`f%7CM57l}CATj|p ziJoLt;xreH@YkdFn;76^IyIsWo+r2mm~>u4SuNQ6p&{ZTNA%}Crno*@0sFs9wA0rL z#D1y&qT|Qa+jdU77c&wb_LMbY&*Y#q2Q->}>$DT1r=mUfSh{WhfeAF`jy&VXxzC>fMA3PWl0`di5|27nLVcZJu# z*dBGXhks&GK6L5P>Nd3h<(k4Gg0i%d7LESblSBzJj8+56%e16?eR2LKR*L~)Fuc8I z`WZe5ce6w|B?Q8tho89><6p-xiU0Gj#v+EHED@idf?0vQM&&8BJ#ITEw(h#Up?v4Z zuYr_q#S%%eW~)`3+ZX5PgCE;bnKL=ZwL$m5Cq43aJv#~y*u)8ONC@Qn-ob#AZQ;!{ z!c4uQ53{7~+4d-q-a3hhiodSoBjN$(O8kF`()s^ypeTHo&jF~>9hA5&NFQmv7Z+#` zWo{STkLt>+dTJQI*>Okv?_R0T=o)=ua0K>wXx)yCTtYz8DS~+KbZ98M&4VyunW!rr zs(7au*0FQ{hm+H71MQj%uOCub`C=|hj3^Z1iun_~o3&hk^+k#b<5Kp2KrBRxwZ_N$ z5oKM(I@kY;nG)kKD9nNrP(#Hxs^aMLMy>*7{<-v3z)8TNdC656rmASQx?hf@Zpg19TCI2N{JBZ)X(s8>W9PLq zF(m4Gd*+lb(W`7}6^eZ;Jg+ro+xkZdK&U0-sa!=zBwGuDqc|M(AeXnc!NPvt|gSk(`4bN(#h;O2&X3arEV#hFs*j$`_}^>gI^@_HB?+6ljIhpnFkhb z?bY-KBO=-L#+M*1I8F9>wWcGB6@F%B$DBEbs8gmI81l$bQc~=Dr^f zEc?D#CsTi=(_-~b(QC`cqUMY}#W8~NxdON$4@u!TWqtu$kqNOU$H% zq;>Znv+AgS{MPjH5Iy-+I>)Ck=}u|yixyEi!$e0eB2j2f^XR66inHHTQ@urEdm23F zlgsn1#$FIPC}l)S2mkZFcyYr`BeR4WvQ@G&^+#X^3>qvY0PNtC5-m@HY zC*3Oj@orU>E&(RDlza&QIWAQ22a9|^we9tG zspXaDo{W|Q)%;WG`+L33?L}#I-^l`q*A1Rpd!G4`Yw1EnI@g@cDr`S`Vec7MiP|=@ zEa#GrFOZ#Z;kgVIjXR2)U8h9_8i&L)`T2il!ywUa)3icQ#5Lv_`h>pE&#-F-m(SG? zT;}g2E&H4KQKVD!z1qDoBI6E`mWvk!8;xw4Yl-Hg{@8s6XQy;*)JjW{WAXKt`ihN8 z_(8)6P-{s)B$uP@X12J5F%x_9xi3`Q(~4{??#1U|#hd;v0p6+0#v;hm$I-MAf0h64 zf-iE!^vSVRb-MY^qGGtm)CQb(f9cJReW{VF*R{B0|3{-89Nn42r2;B)4Dx0#XVWo@ zOI))oBGTN`@`*bMsOGnhRu@0^JDS@Cmfvm;bHrun6({ngld2(vN+cqwXAyxs$kw)AC*#2(@$SW%cu z7amUQ*#*{)9=<=wtOQNx(j_^dl(^sp0pwt^il`E@{-p~FD!2cm_;LTQHw~x!8whgCZPU)xZRvSqAH#+xYSO4&n1OidQTuiykfuEMFL5doe zxkRyfihTu&5pkOfBeUf8^XY-JQXBT&vJLRdR#t48opJ~b$zT9KKXsi<@SWwdf)mlC zGh8h?|9um$u0kdy%k`2=g#rS@0s0gwrB5?L?%m|%L5zMl zcMlxMX2l^^x4It$ZGJzVkO`J2FIUxu2XQ94HpL$EpAH|4_aU_*csNP@LNXPm;^lhB ziX`d@6b_Wdv%K5=K1W$ogr%eEn`f}ub*dl>_7UOkrIb2-snzjg(6&Q*LrqQ%bF^zr zU&s#RrN-Vq+QKrX-Nqt!rq^Y(FV$DItKyiuGxaLpUshEx{`4QAXsJSwq{)kI-505O z4MV0zu@$6ZeqSV;5Kxl!0n6xW5mr(Yc0Gw@gy$O!vktvSZVz=T zdmxOrS9#iF&Ukv*{QoflWKy92p!6Sg?1}GzeiEDiu~5+!@GppO)NEhrhYNMlo%p;J z`9>U3)8&C071)}xr){;uuOC6D7EMG~W1sG|M9=bHt}5BpQGR=4AU&@F)~>sPh&5zk zikg6lR-P^Wvhvlmub1eby$9A#nl4*C5$gF}T7>dlIU2FO|NgARbiWNZ+Sr*0P1h+K zKTFAN7mb;XS)Ik1zZGCC8B25z?b(r=Cm%?azdJH}mePDfs<<~CsdVE|?g2ynN^E9% zim!#qk8Fw_s=_hX+4Y^KTp74&VaosTC;t6pL$fm_OrN>h-jBR9ime!Ly!qakUPX%l zf)5D9kqpJ$bJRVp*6Gi&1RntJP|KS!B@=SpDM=5hI+2f-F*{nnNYLGeg5t*DUQ+Ts znIt(9UE_BY0n9Kxaqv)#m$c?5n>!V%l}^bYE5PWFf76zVx9_fO*E*7(i7^!$)8;Wu zbx4@3RpcSq!SUyH2&4+Ly!PMHhjr(&iO_2bo`hDF$9aDSfqp_Tzn&;3V5O-|2m7;e z_6OO;Yp_3Q+wf%xS`*P|BS%_Ocrq>OJPM`c>LA1>46V zJ{#S%RQpvhxm9M1i?(~s&MDQ>@L;_kyPzr73@eQskog+qk`8T2y${*@fhsPbPO+W6k(^*2*I^Msv5)tzwY|Y1b7{O%YNhQk z(rL~FKcC2_a&>i6)V#)27gzD-leAMJDFpij&WGxB#S<#>o3tVUw754Lug@R*%LETOBs7(mw>3&)jGUyLUs3UrIVqq%g06iMR2lR zA`zvL3_e<{R`tZf&Ldt8KH(CCteD&oBoA6V&QDgA7AS?pi>lAs~P?jQrU-p4=y$J70`DLb?QAMiypmD zO9@&)J`Nb+hjLVExG%{~S5Vl>B=?l$|u&@Iyfe^hbB=vK7m~>t5e3Lw-l-c*R zP_6|Cjptu_Gmb%+&yLG88qN`#Jhh>UfX7y@KrTl@`P11gCgf>2bj$+|=OnvdNHE3dYSh zDNa2E_W5Q^Av(9{Z6zmpNX(9;V8hUnO0rd#c1RMny^UOxCF?z{fCN6Z`&dYcTXj$? z!8#Z}71Q1~1#J+AzSb#I5q+vQ_-*}pNl4t3KNVIY*z>Azm3aht?(dnMlc)9R%DQs4 z`0c0yPVN5?`ocE33U<62hNnc5J&8+m9j8>1d}ed0-!j=C?^Cwp%JXSZ_t$^R&cj<2 z+gTIp2Z*@}5~$t7-X~+qMW?o3Bu8Y+W6U9y2AL&{A)~x8GP8b{qz+Dn|-3+@*FhU^*?IR`YJ`o2P?_gBYh03 z8_Av4U$yJ>tDW!8OrA+)ONx$I;GK7J+4kW9nKtZ~kYb3?imcY0PY$H{FUT}fTeD3* z2DfKK{y*OPggEHPQA*RDOE#-|d~MLNJoDiT+YGPDc=^FhkCOF)uLPu1`A%AE&>}hFDvrcEw1W;2SO53_NQ|$4T)mzuoyH? zikMGWZDe!!Gl>IRzhZEkM!f{E(^{R7=qop-*6CoMC<0W-cy(Zo;kvZ3mpuaKs2HTx zl^O|an~Hn#NNXC{uCCS|y*z<7v*;5W&u>LhN;0mmLE3J>F`~z0hn&0kWX*I<5_!{P zQ|@}@k6>i>y|w*{q3@-Vf)nS{>vtqYE8|hF3gDCF`uEAFix(*!vHRK0cU%MCpk33U zv8v}Ck&9-?ng0G?hoR*U-1#0B;GyrRvy6Y%knW(z9Scd{x+18+|$uiV* z7dz{!dc7pqD4Dvw$ILf=0Extp_rvleN#Thh+CN+lU99PM(WQrkl2FD%6e5b&Z^Hw# zJG<5o$bmEUO_H$qi}O}y{wArqTGKaPEccGu+>g*zVw*<{b@|=&(4B;q7PYU)ua?Sp z&FU-mu%#Nsa@(V25uC;NuI^c%5z|9;RYY@)^};+vs06AC@w6kIgZ=MDupiaLKOvR( zmCj~Sv9f2c=Zj(Jo6-(1OS=YX(bg;KsTTzNkGAa5v%*w%TtHEpN-z?FtH#6+!!npiwvpfz^ z(ju31krd46NRqr=l}X{r%H|8AR6^!H9N|*F1eDWe@>CEkQ243~1m+kirZgr?j{PB1 zF{QcU;C2Tj%T0mb#I(CvovVs7eOItNVas0zp`RCq*49TTht@h89!UAwO%^<_ z>!pm5^gq2pp1#_5DEA(oHcsZDipJ1m>WRMWA_H%PSmJhV3Q`U=F7h!eckU{I>FXCiXV#HkPva~m4S|`Rn z6-ey>p(U#f3q`K!50>GwjwvkbqYz(-UX?8MT$QdaN~SJmniY(F*YznyZhq*l8*fxh z{BC33*{MJ3_D1fUX#Z@~0o(5WinC{at!;xlZAHxN{0YskH=hk`Y}*`lrQ#1~s(vmU zSs3uYX~y9AzdfVK^~ZuwKAMepa$lh;Fs4xx^xZaAk5_H`RMs@GZI2jGuArUGlF%w3 z_1n5SP*11%>ASAYU+}`a+G3@nfb4P;=FB)!6t&TgSXNbV(H*jBO#WL&XbyZNX1}vln5Bhc`NJKu#!GBgE2xD>~!OM0jj5 zQ%LIVx-{OLaDnTw3iFlon1S>IUTZh)OsSPe%UV`ulUh*6<(l9;X^P;|rle7L z5|P){Av@@3XqEE5z|5rl<~!SVo8=erD*q{G`;6DZxz}w))N9bD{t3HWGoHF_?#n}e z=Qq+xeTq?BB4>{WyJ**GcfV|>v?NS(*OPd_o}4$2h+uzuS`#`gDIzhJ=x8CR1Fhsn zI~6D>DXDtq$3+~sf1dPlI8lwrQ1yKzuT(Y7T0XmTfo$*+hFBt=FJH|%QIG;o9cTQ? z26C}^65pubfC9N0x&2FWropWM7f@S8>f7VFJB|GW^?y)o|KH2{3d}LEAyt;nn!ob5 z(mwd1@As~)k)1k{L_E(LgrJWuaHmlQ2)52Lb6KcC``L4FY+f?Hb}s3=xf{x3KYsmd zw`Xxo31*PBAzv5%SP&F-<;g6qT^mLg6<%m9-yl+Qk1X}Mq8zzv>_1UTKh4BPGWKTH zmlbgE2Sv(*s2}9=2DU0X7H^Vx}=e$Q|UZtoXQA9k4cAZ)peyn6F%`+ed`dO|e8BUx0~nf9eiQd)Y{otCX#K z_$IuVd^c7$_p;~DYad<54zDP_H_9wimI7m z+N8^X;lD5G*vE%OUVQ6IdB`0>I0^N?K$#h?r0@XM!^-HDv=G(5Y}4?}#>!bMw0C0w zxxR_vqcpj)Mc$L|E1g`Q;>k%7VzLd~6aSYXcBY%}urXPzcLUq~a87b)o4C9}{R-vI zm)!V9ZHA|&ui=^fYI@feoo6fn!<%nME_O&}>%zUX;R#uzrOyKrD|Z?l(dV4l@BCopI&1h8`)D|ymXZj;r_&?o+BtrOyQKl{Qw5OnQ{kH%iCn97zft(c~+HS@VHwI?BdTYka) zhpU~McE~2O_3E#b&C>B67W$RAgz&siGYFEvo3y6s@kw(tjQ zoXvanzK&d6e=&J=7!69w5-ig#E-YD)goXX z5NWRJc?49>sUl znvEbV6FmD-!J!iw25usS71@zGm&B^Q_aIB03+Y^S~g;KJKNf zgssSmS)k{dxGK+Gp?zd2_FH80gqYeFl38wa*!NwV_|u-lgmpf4e5&JH8<&2j|paP&#@5 zFsGrQj()pAoa~jyuaTdCqIn6y&7_ZIt%;TVKEA(f*8H-{AJ+X|)3e9pOtX@@mKKgW zEmD>W=iqX?9gt<|FRX6tJzpnGr3i(H$lOA_$y+=qfiGzjF}hE8s^W;gtHeOrbVgbLE=zn*}eEK8zMeYg3O-B{++v=dWB(zTyvuFE@{3=X_v83 zb#&E-?~U(u`yxRz&(i{Uy2H$uFbRNj5tL_5@RZ!!x_n zXE>mzkESOe)kUdNWx(j=@dSuS3_@!RxZbyWy9Oju@H3StXZ&~%;_N;aSXiAbP-b#S z8gAr?GAgF9et`l3j@jh-POSdq*^_0Y==R)ImEhmJy5nHzPSV0W{K}NT%86Mho00}! zo=L;BN9M)U_{P*Y&3_W!2Sys|&(d3H_i{|h-qy{X`PzeSjDOo7*L6 z5e*g|!%*G1BsXH+qg!lLARbTU5qLdchdx|PXiP`({Ts$!W2gnGK$GM{!$G;kfOI4Y z%g-CnoN|zP*QB6HbS7r3W4*3EWcLm)B($cz7HT|ZNgosz25EwM;>u(n*(bw`ez3o+ zF*#SxME4CDVnaS=)9I0`vDfXx_wm}EaEgSJkE&{!6|WVQRzxrLb(Wt|C#GhR#($^C z2J?~b%i4m#2e_2IUEepUKDe2?H@@xeBBvhLo3GTShXuK(Ti4&MsClP-$Gro8>NvvB zcdhf*ZGQPa_onCMviJ@K($X=uSR;JdA%KZ-8u;S(f870dtAUMl?*%!7P-2_1?~H1Q z{YV;$9gY_yO}8(|?VFG<0xk?sPRLVQ#g&ZOV7n)~6+>^YbJL0xrSvIOj%z$SKrF6v zQsS2JPxrPy#!F{~w_|4s83PgL32gX9u8%JkSdMRc@(E+ zW44?nN`R&9Yd(*CJ-`bu;7=>z20d)zmsHZN{+pF{g-CMjnko2zJ>z%afDY753_(xd zNtaon{M5@4kq}4@jY0&4N`uhSlf@!2a&Huhe23JFtkfQsUtemVFzQE@?{~j;wOkmW zrtF#j$#T@lsx4*Hc8TD+Qp-CxEDzrvbH)Eu#CTS8D$V*w*S2Y$T^s8_ky$ye~V9`MV0M)mwb{pw!)TxfFdlJ)u|4X^-=>r1{1r+Z9&~!J76e;MAlMcZ$7~HJ#YN)-R7o15kCU$ms?rJ(_G? zP<8>e6M08Rmd;4+9x}mpd+m#M5NWg+v~|46VW^Q*{Hy}!2DF{RTF3B&92Q4 zgd0V1DKURu$hjD&H=^GX_p*TvTG>fVCvY2r`>~W&tM$j`8(!(ZETh<&sWZ>~dZt0S z1~}zo>+HN`?)HL(#6xdXxUJy0=3)H8yUtBmOA@~5;05AL65>13o{1PI<=N?O{HEV$ zg?`0Cg{{O4WuB8J`}}juiI0&*x32}>M`EYJ^7VK}+yH%Lgh{BjeW%bLx%Epy_`JiMU!soMat}lP{J2_+R(I z9x5#FP4f|Nwt9-*!Wj^f&-Jw=sTbD_JMIaB6uwZOmeMSy%QeQS>_|J~r{Vc`^c(K3 zOJ4cqySlUdgYa=&@hGdzig_pn?4ted0MVfnpG-9RqhsF9n1s-v*BwCPe#Y8Abrq`uyfcS}FtUyYmFRLaBe(&XXMWOf zG8wnKRc9CZ=((7j@|82%(b{<7#Odj_`&Dea-lzr4Zq5!h3G*@FJncH|d0m`27$V8a z3}H6P6H9wOk@!XVjjspD0=u3WJAjr1$S5zQDKma^=R>E(YCrm%t#sT*gnlgzchK3t zvAV1Ek2>(}&maJrNhFm^q=QZn*$WaIZ11XlwQ#`?rni6OhOPi7Sk}B>4W}py>7yk* zVWry~+?|^6Nj3E9+ybTV32U3b4Og)c*(DG+S_X8#?c$&aGr4{KZ&SbQKBwRFD@7&N z3K*luN6y7(Nxk#pKv+?<%~+~h92egH#SGK&sExNw&qdh7bv|XYC-Bq%iMo#CoWo*) zXN)ADOxk)j7hB@2RMS<8wd3GA_Iu{N0um2klKJ60N|jT zSm-(YDU)@kV2X{sGb%FoKX*pjTIp5cpPS8dMqf>`knq5h6W}d3-6TJAa^WN{Nz1jpSLQeyuZA6pPTRJ zg}^ai+|%YC1lWjtBe5QDcazGAEoCf_xZ1R+2-y}?8f+WuW#7lZX$tWMf53{Nc`fn) z2OFy@X&eilm-7LAp6YHPyt17`h~9+s0OdQLHt!$H6bouycCAzVu&#ON>g8cK@8bkP z)5Ir^AV^wo;+@y&oi6Ktxcfxl?6AQFO|vN+%NxcM?R#b}TDR})j=U+tqb;d*Q2abb zq~jBndW^8USH7jLQ^;$Qpw|KkuzIixnL_H zNKA%_TaRd0uFTAD=&(V5q}?@hQICnQpvHBuBZpv2dS6_6AZ8J~x+Sts9m;SmIl50y zuQj{5&4?7{>%W!dEf2Mv$a@UzWPj7eH`b-5r#j9bRG-_Gxj}KKD0*}e=Fh~Q`rLmM z?S~QV@OiAY&-nbtCLpe^&eAfaM|WJX**O^rPgCO(B1#d+o7MD#YUMXxq3s;j8wP3E zZ#jP;1oeOQhp2w4&Y?AdAQCLt=nwzj}inj|78xfW6n{FNijQZKQ-o2q*=|!IloUEoA@oe{rq7m9wNeV z>+eg}?DX{87M7*AsKW<}336#{qWRalOS&+e#Is)ITKZtyvYcy~M-L_YkjjE|_l`^h zdKo;2Cy$b5%Tz_oJZet#mDBahd6++xvVgN#VW%*S(@4hiXPxDZYs+uL8RV%?L@SoOJFRW6?l~BBI&z+wrq!JD(z})LZtp#UI?1xAGMcox+UcA2aLgsp3AhtCERB=D$z8tT@!;G9Dz*6E}JOoCTj0?GF^hIhEgT zH7vy(kn%sr&TLn#&N;Q6Vp`VTl$MDS%jUm;9`iGYpPYIEMu^axVAY6Yv$2GrcB>C& zJAv|Hh=^bZqdDfglE=*@PP60kV*}zF*8st&U87gX<>-#C`~E`2joI0qLnvD~ z)vsUSbXhHU-e3B8KNGNwwy*I51aI>D8&&Dj?vI;X8>%u9naIBXqgh$lL*z(i?hTx? zK)JcM!(8D*r!yZKqM!XX@)4{$cp=IlvTLT$!lzzEAD1jECSX}Jj(O33P{h=lj|1s) zhov=R|2t70zV))$WPV}F{JLm!nh(t^%U3#UoyDQQJvTs`-2n5O!ulZKwJFLj)AIEyLwH0pktgzL`Zuh^H zL?Rw-ktB<+$ct}&xnmc*+jXgrNXEq+B2;;T<`m_Rr;Z4%GqU<=gB4|te#2m$?0>l2 zJ|A^xUnP6m>)4_8Q`aqd`cFu)HGJfwE3Vvj9>quJ&JY>0_Rh5WFBO$Byn8PpD?Ci)${ZseKAB%jdDesl6wgTZ}z2GAJE*W zVvr8`$VUF4G$_!GiN;90Om@#PSbf90yg$}&v+H=*t`%qMFp;hhBpb^B9PtD zX2#g<7`uJ+)PiRg7FYxYRv#?de?!D}l@YGoA3p_s$6K72w>@wbO*?Ge_vMrGQAkDr zciy7@<%fB|GE}!YzwrWTiy|KMRHU_YFfZ!>l}#m`I+T7?mgL20ur)1e_ZSQdt7b-h z?pL^tT2T}rjtLM@AF{A~$WE_=*b!`_9ZA=*Xcn_ovQS?@7YjJ*(|*=0hv6Kv;!w zNCQryPlnn`7oQAZRg5%ai>u6u8oM;gxP+&)uH0_Dv4LC3 zQx^lTF=Go)&Um$f3*D3K`xSxs*s6m`abT_M?WnCrwU=^8j=;VlzO^Kv8>EYDT4E=H zhYJwl1bIw5YHr6Fa5Pbp6nX8AX|2uL;wWG-E?n6BnAW8h^LpJ72pnu)DIlciWJL?B z+waHDmJJ2b*SxlfSG>$+Ao3~qR^pUYQMrUNQ%K_4-MxaLaP)An+nwjpezkB~tQZqP z9!E*8E%>2z*XcEiHr9Qukelc0`h=oby5&(S|EPb`b)j)89VQZ(fZWY}iMHh`WS!|j z9-6V0^ah8PRTXXKz2hgLkUAzC*g8-xvT9*9iC$i|cHf?+7lkB-#u@nM_k@bA3>Y9% zpRAp24_jVZmO6iRYwMT7=mD0Bm5%~vc7G@Z!@kN3k_!JsLnx@LhJ17u9_!d+-RmWh zYCC*e&`j@{pQl_;xOMHt{z1LRaL<Nil6)5{K;4!%dT-L+Yaun%gWr$o49P@TlwN_1M%Zt=4TdTl})m zE3ffC!IMI=TbRLoG+dUSPB%Hl@2@M*I3TtML(06^WN1Bzn<92+0ReTXAH+e#p6%)D zo`NCsH~_kt?(Mz+{$@fJESnDtibn{8n&QAO#mRo9e?1zr{ zR{sCq>ir*iRnhkaP<6o4#aBNc_bSRg^aY`0C+}w?qsHIyA*%1{YI2>h1$(I-1-4~< zli1Ie?ulpCtvkgRdVRX;uCQrXF{gZybL!J$NRS?2a!=GF=XNw<~YerY+b+MaEgkVW>@u}f;Vrd_C_T!5e zH)z>YZBL0HjC#G&JJ5=1Hrw|LF1^vd0!p@JrS>@GdA+y&p{DeQ z+GEdrZ8oise!JIcpXA%Ac5pJRoWRV$|5pg{XcWGA+HK(PgW;tTFNcANO(N6zT)vJq z?G2^bO8KV2ZDv1`P2$vZsk)LcKCZCMn${BY3HEV`-|ust68b}NX;8e<;<#B8tEb7; z#YsqMhL1ng*-~FkU&ELwhA+c9=_*HpfLzewuEDXFFoFWeaa6j2FdkXwC=mzDy%;ca zq7^``%S*fvpvmmWGOKt(IvK-885;sP&pJ|6nTOL@`ammiEoUih@Dg&Um5c`}0_lu9nFYw1 z6g}3VUejaxf45~!kxbz(yIHrT%W0Eq$Nf8RHqBsum?tjsdg#gZZrj~_jav_-l|O4J zu65e?WNwh+puUrlSa7QkHz}vp*=Fj78h7&FQDglPM&3Kg%caitb7hN%>&@kasIxSZ zp7<4sRBqXGbOv56^efwSnw5oCD5S#9v~}sLy3J z8YbXU!pOpKm1gnf^F7`28%2^HlZWH+#UjU4U|tAM2K)5N_19lZs;cSOw{hFzG>!YH zN5p-Zbt@}Id$~M##E)h9yCV&BNPfEiKl4*j;nbU6JJy$EM&{I=5FgL{#;i@5VI2A)ie!QhQ8Z!H<_#Uf6rW~X zvI%w1Dde{wN~y-)?j}2S;b%9C?}dtu*SUTnz6Ljbve;V@P8_>Y+xI7VM8$)NZmquK zl5>IG^OLyVmdn;I+Jua)RrbB3u&a$o>B8C@-;M}a-e}|q&cVK8F3H`R`bV*yF)L$0Z$N+D#{V9!jYssy8hoU3axF;!36irq+GF zZu?V7@_ITXzW0$iqoUZ>667k^4^8=fZfx+(XDYs*H%PvZkEebqX}&&2GJ*x zZdyFFFua(0cE28P1@yvuVd(5?s8(9jIRySMxFwv$qa$(3 zG4f~FyQP}$mfn5iXw=Gw)xo)@nS>ZFn(+{Hb5j93yLQhA7um_`BTZaR)Qr2Y zuRWwQHF%qmYUY*W)rZCYB1Q9Feb}5=vle|Z2c{SwoA!X(K((4A8{c~0^-TDAz>u* zzk%pRSzShT2p|(&Gpj zS&%xCtonKFZ}Wae&F-k8hahu_0eZOoD&?fgPEO8{`zcDprDpEFz%A%EzmHE)FkP)k z;Jn45E$rndM)Npaa9mQs`Q5La(n0vFcKYW02>}|lmD281mtrSBIomF`D%HICwP@ua zvOy)KY7eB`d(GY=B7u7+jnr74X%-7bdn}hvZY4*~c~=8 zS^jt6G+-&}n#qB?g={q8TGADOMoUV%8pnS9d&iEsJojsVjI6ZUl0V`Jl}Sm&i~|!m zAat5Uf=*bzYMIH8K7@ybcWc&O%=eVTritGqoA3rn^7+57#p#>(MXG(H-U(SX3RNlI zkGd(E(rs5>ZmxAmO@=&O$T{a`jg9194E>5rc#H6QZqe=RoThgDFqwSq6Y0U2*mOihuvk724cTvG zBwK#EY*Oe7_%}k;GYNt3SOHaDu$)`0zAv^_n-_UryPI^#O8z~A=;XgGL~PLtTt?s} zh(ab)VxTwONOuGN8_$!+Vn!-jaPz#GzCusMOBLi3l2d?Dh9S9n3x?+X%;PVh?;tl_ zcqL>NSjiMxzYu(jC)%L^Jd}ACs(exDeV}9;!v|w#T)JS8s(8h7GNO+HSXRN$pd*Pb z5y(`cj{#@+3t~3|&di=VWkQfgzg{`+$$M+thN~TnVJ!naYLFaj`k!*j1xGD@t)oqI z)0mfySHAp9mjAiouD%4^rm@Fvymgk2+0x~$rfln*pwSQWqmC-nSHqtbnq4H zh(wbdM~nQlxC|$<6s!}oBKwb5<6OVEi!;ReUZu8&r#kd2`wF~qrSdBI!s+WG)b$+v zDaV?3h$8S7|K?iqXk@vW1r4_!UHOso{CuL0|1CIm(fpmggYr-z4Yd~~H(~VJVg-fo zht>Z!;_+UOeOifR7uK!np+?cNx>DuIX?01@fXbktl-!U;Eq|(QZY32{X(M(VY@0fa zm)v=$HLpG{jxOz6rBQi3H(Tk^nVq%h1g>4&@q33~C5oq-c&Ec@8oBvhGwttQ`vVY|0A~0CL;<$);d99;BknAx!vAGnppB3oky+dRJ zJi_)|oA1YnKe1Z5zFpDcU<-@+`vytwJTfqVA@xLfH6tP!>nZPVWT=Q{LeWUnv~(?b zF#OaNOat7ibI$bZRsLL*^6vgGC?Y>K{dsiL;vygY!HwdSkH#!x|6?m4mazwx+&XtnLH z7lt>*ox!~D(~{`-=n{hWzUb$6m5L^B6Q}<87j6tkxa#*sPEAJ;#&_&N*i)d}geWmti9YE2{NZ+z*<>zoR z?j7-VFpz^azci~Oa&KLs(5kH{;tCvLVE}!IZ_AyR)8jGqdblr^BTpxBmY`;8w5S*O zkVi>-?RJMDV1qKC%>6oj%hEoSXY5}De2%0^tW!O~8ofyFlIE|_8>+Ihq*N(`o3IJP z_zh2No)=$5Y4A|bZ$?2HxPIL}^@Uc6x=w0AC!*!}mENgUzI>lp^4zKdG;kAdMgG0!Hx;!~56 zhGtIu_X*9>Xy2u4+cedJQAbv1Y5MY>US}!bC37MS6G0I+uKzS;#)@s@+uWY@z252^ zt8ZUbULUw9?2$Z~qmJwH<2c`#R+p4Xj~u^<)9p%s48C?8ZMoc`RCFROI*dDxHyR>x zFhwaCi(5ZBIo@~TW+XAfTXfBvB!;88P)bflQUZ=i!#rXtiA(IJTS2{3M+lNcdV`O* zQ83}Q)exEqP@R2xA;mZxBYwS}8J}->J<~8cH{up`bLK?VzlazZMMQ*1386cow6DXH zRfwkK=8bdwsY*aG0?JwGcp$7j;#ZRu2u`oR$j;xhZ^x0G6;@mC#7?2I_C?}W)1c<# zhLs6mNI_-=Pc#wL)2sQM($FiPKsGT~gTNw@YDsIEYqt*Aabw$sh_oEAmRJP8h}Yo> zivv9iA1rb@N`e4Je)i^(6&iXk}}OmX~NK9t|=n@coq0kW?36-eQ4uS|Qo={JV2wb_mrRxGz$~9@Jru z&hZ-*xlQ`%;Q_ZgGI4oIP${?i)}H8H7}cxVP#p~YH#?WIn3$Xo{_{j7!6ciSSweq~ zxVdzR;z?}l@nnN7PuQsRAq~J=1KTIL+AZpR5c6P<Cg;Bv|)r<=AOB`srC4?a# zdB!ZfRPdod9Zml?PFo3XQw&saUGnGOVBt+5%P$uxHS9m zUZUj|-fB4iwuOe;&LJNZJ*aBbxrmo;OM#;IrRuI(eAJ9+MsQ*qSN7JPA5k-k@|%6z zZ^2+{5lh0^q$&Y>I=;G_J0%yHX$Bls#DXJKWDkv-*XxQjfp)h#{N=J45RB`^T_936 zEUa#IFhydk%rjhH8P7pD5xBfEz-i2fa{I4CXnLV`prg9(%zHW0pS{#nr4j%i8-idI zxM4X$gm4>hGChgy*wN8sV!K~2uaS9?%WDDqx6Nc#@kh1rPx6$GV*xj`4INwHONG(Z z#7&b0h@PT0gK`7?46kw)BYL-Z#79IQHAovLP<1NdN$oI5E>aYggn`Kl1b=EBe79b+ zkXjJr%u2^S$vF@;u*=!H($k8o%-M|GqwkEC*)t`&7(Z{hCx*)*3?BQDI=fXZ@ZPT+ zeKHv^@}c*vm7afY(Q|n**Z23A?^$kapix0HH{rQY3aoHa_<(@tq z&92HKAYIgMC9(3Rg>94|2;nl~_O6LNJFGz;)y06*z&|;j_B0kdk@xB`*r7pg!U4O8 zUz<`^Wa0~EO^VZ5t)3an!c%I=YO?wKgtgy*Ha*^vDmiSnV&$#wWzp3TKhW>NZRXUx z_n}}5L;lfsWNW)?WwD1n$mw-}O>7zhbqXtfToZDDm8Os;TJGa3$8jiiaz4kZ6->uBhNv@hIGKK(TxAF>x%Z@lr;C*^uFC8$eS z-pcEw^5srlyBzLZe&50p6M|l;P#!4Nasi>@UF`4YUn_pM-5-10R=bFUVI1fK*ITT% zEqPWf*mbwLD)pA`j$LY>0P{5zo4W%j!QOoY+yt9f2^D8v8FvY${K) zl|!;yKTXTg_TIZ!JjnZxgD(Chw>truY^Zq5@*362TVeAJKmRZ;M`GNc`#egn56ti`s(p&>Cy4 z1z3i}5?+5kzH^h}opH%!OpzH6(rcsi#1UQpkfIBNlhds~!nu#8V?83n-|JlN`G;en zKI@ry?+e8`cHrT&uUatxyeDtV4l7UG!)<6s2A|_~gM%TcD|=bM?S92S^+#7%{T8iY z`Q>y`ifyg;gA!pjnuQ9Z360R!%b^C5 z)dKhKi4`xfRQ>EfPZC4CJM*h=Zku6Q>Oed^_iz5*%ShqH^31C(@{_ChzF65gaLDRH z_05rx@BQ)qGEaoM9pr|WUP}(ur2mNTLUPfiOL&oL&U`o2d_`IRquR6xwX{fU1;fU0 z^J_`>&++D;$*JaCZgfaJ7T#lDzN`fmNSV@==a$fy@o4#e%YJy^`U@+cy~KOVZ#9km z6+≺j7zaVf1I+8&7~u4+amBkHl?y@ml;l)7!29qhNASYH|6=RZx35Y57>W?C8f# zvvcgZ&vF}b6^B-1ySBCbm8%T_$jw(W1riT0=i&pi25g}^xR8kn6q~o1jVi@`Y zPw&H$OJfu|q@R>*_f|uHr;Ound3t@X*QSwgJRkff3?XkeAxUyVifP>wIOnUTIZJw@ z{q@x5E19iGcn&J{)5NRt)W zyI|L2do(${j}MHiJTyyZrTBBlYc^4NtSQZlxcYHx+H(OsSXK?lWz70RHnqO@&GdPJ z4^EXRVZLo$5!F1D0C!}F#Q7mVtaa=%$D_t>mUSWaQ#OOz|#Uj$nTzd+|?}O7B zLri~Hs#=i$=kYvJ5cr$9Ng9kZP)3)|Rdd6S)%aWKRYY2)oz>m+Jv+boCQT1$m{+&U>kFpGqJq__&~b9J710*MQhV_l9e z1#BWLi6cl%-F0l}!UwbqQPJS>W*p@=GOqc_X;l2HjdQ1}kd$t55-m?wUXft)HTS*T zK?~Pq^m3Ruba4!C)3$@4!DF$U&yvE(er`PeHP|2S=5@$Hh`3K;dlr=W2Sv-$tMNVh z_AEq|5`WYsj0g+b2oGmF5}YO8%uP#5UZ^}-zD+{^vH!K?lRam?o1>lMm^?os@yW?L zWSIT(s=Uzt$Q#G)cns+a#> zB*w!N3q>p;>M^R$6AFCaJN5(s8qSVOk47PsT&>WmOE9{KVNv)`I032tLTKAU^l7cje=pgjLYZ*HP&hm-?=fOdv}1a`ss%sPuQB`TYM)O5M!_L_ zJ<|vS5geee7)Q^?3nyd1%xALc%YU1%YlX3hn893uJ+)|5lQ}pdbewGO-l7!lvs@ng zr`al%>s4O;{KkcWmHdODK(NKe&pYC6b3V>m2L+k&^T8Xv?xA((2>FgxCK#b=f#b)q zyXp)=jXMNrG*J@ZeY4i|_c>a_H;ozn-JSJ~?+WgplyMwm7vz7g-1MzM=n8%G?QfP> z6IRkQyS#kA-qR}WwBi#H%7THnOt1zLnw0uBa_f)PS*m_XorV|O%OlC^quRWmy~H9nJgJze#>unU^kh7|C1iUGYjU3)L4q5uWnF#JQROM$K6X zy&GR$Z0Li^c=BW@&ZT?~~PY745&jIsE-jQdYC7Fe65p5A`PD;o!s|MVr?`z52z|@ zix<^Dt#vDH?I%~vdpVfnYK({6X^dT-9E**k!k�J!%J?GWDKT zAkeT4WUET9RHuSp>NeZ0zr~$>TqL z_q3}B5T(b?^)ERikEGs!Gi~lEKeGvWZDO;_JkiVNBPm*GZ5so%MuswSJwT-Sz0%%6 z?YpRem?K37Bee{ zGKp?irM($%dl%JgOr7lL0w?l+$y$DE4J-gi)z{(r>r7>JWwJ<-x+KC9c00EglQGLA zJ1;CIT1>K+$?}3$Z;jNnw_StYldzfCZ^5MC88^fb1xm@{fTsJ4ly7|vt4I+Q3!nyr zOlsJvrzw@?TWznl=~AT~TG0AtF^gKt2~SF4pLa|tHd^DE8x*x9F@;WosYWdU{*-7S zHvKEZ?|Ii2*oC(02-dr~e^qo!r!OO&z1cx?2`dDd7~i;_dB)}fSnZpp!svSAA9&A7 zL!tgiP0!&~^5?v=+=(NJJ#&v7=d5JgGBlV69PmE{i|?)AsuC4+6OI zsuSBW?+6xOH81Zi+V{X4<3PxLLp0M51|y_wTHKC@XWWE&_pkn|GP1UPml<6}pa=2G zS7PANu-bN$@p+BN#)&=_u(1LVb37aoE}wsb?8{=lZSQM-$D*ZL1v4ZiPhoHh2a@Zo zkTrc%r@rAfjzYX+^q_`?_={xfjIC!O;o#DDneE=T!ir_yV8Fr*@kOSwkh^=`9wE;0 zuGnvvwwA+cMnJhQef9Zbk`5xE7-fR+6TvY|oXT%v`rCWI)Khvh5a{D}`;I9!>ZRPo zl=8Six>-qOp%C6G;eSaTUso(}N!_n%3D^JL@e7c8ksnqh2_L= zD*sQbV^K){ys4>Xo%&@}AXfToQdzd_@}jog-V^{N^=bw z`EtD?5Ca9HXvE!p4YY~YYO94xG>1+6eVOpUS77wzPz)`sv`BB8fYJz)4o~)-T;hhN zOcLn1in$PM@d_+C*=$_CeT@Q^bS6tSV@%hgAcA8MK|b5&{neC~OC+{PD((%_2U28# zKDk+n72z$^QzNvw+F>49+yv16RuC~(9|YKHtg5sWbAtD(N|C}rVbw%M@sg8k_9P{m zKRff*D!A^fzhBX#P#fqTt7)^|j$xoAv#3V$6}psDyNq_MzTjV+FVm^Jw@HXh4n}q( zlDkRQ{H3-1J0i!i`INdLrEgXqJY~;#3!8LQ=@Qrtlb**Y(D%JZ5$HXiNrXw81Mqr7 z&Xlio^cF|0#^aGtSwbOqliKm3Dw$hNyjJ-yud20hD-#u)SeDhXabBIGDOcZb9T|q(l^$i2R$6Wq1b#*@kWUL`!-KM#p9%n-@ z@-%TO-EkqRh1}1z%jd_wyPS+wZG`Cd_$SM@K+aQo(ZZWBP|!J-w8gKPK|qYNlSQ!+ zYR-&AaRd4qMHqVpY_&cW&y@!wPky4O)xSEUMz?msOyMv)MjE%K%#OFbO=v5j>sPj{ zbnF8J9V7<jSpp0}upja<*$xC{GBFIuwp4oi&h#$kIcz9K(c;HD; zt-YUg&s-fwgwYT!+EJG!??E8SIh8L_vU&8e8j*XIM;II=37R;tBRLYFh#8$Os%f(o z&M4ZEH6kw~_qD6_STMI4R__k^heZd5yH78q&Q+i?8qn^jkoy8?xO@f7y>V~pe(yj? zfC$}ei@!5%gm<$(k&-P+jKArquWpb-w4&X z);DZs;^X_I(FE|xx?>r+2-FDoW;ru3A19$s7k15N27xS=@zR|1joCaMijcWE!=SpX zMP$=~Iqf9Q_lb0eP>TaQC(Lu6Wjq$douy89lmEDO?m?qwW6Ffpoq^!qBOny}omFc0(BD~8RbEju}5;%3%oa1_6_ zt4QTsc@wh{9~d?=lxAX>eckjkj4D7tH`8Y(n9-d?s3jTCc#vyV%;m6_7YIR3rZ`g> zuv#C}1!6m85s4xzub^tWwMNl9k6+p&PF7UZmdmn@)GG~WlYCzo{IyxIujRNJjU4B=%=Zxzp^lN|LCX7R-;~0wkU2 z*>@3MkVMZ@7O)ec&WMB)0xBJ?KgIWkhS+b2wYXrl4gQ4NM+7F2rjE_~>;P5D=2#bV}mfeMB`;wiYVnnjZ*FR$IZ)lhTW(~e(kIqJE zjJznrB_$!J3GI;J%^jHZkQZ@j-bCE1L@?Pv9wsklQr>CwLj3jjeKgR5#)uVIym^#l zxZB_pC+7&!TuzFIB!YDaGO63d;J`q>RT;a`500MVz8h>({;j%{G;2h6t%P~^wCX=q zmO_O=6*@|mZ&aSXRuNuAa^Ea%HW~yiQj&N?-Ijl#E`fF3+mxxx#32@gM_F{Av>K9# zwgi&o2LmQETwLIH@ghRec%VLJ-@}{b-_^z@RagAFsT20Km;~?|k3XV(LI>$O<~g_} zjW1}47+sm2yS*uW!hx0n{(zs)XNR{R9^Dd}XT2qTO=?wn-qN5A)WU*n2IpiCXzRt( z9tP~itV0LANO?LoKZ(V}zNJq{6%~ugjj}&|+CQMlGs0w~y|Psq1GA%AzN*Q1kfIXT0xsTs>q})iwVb zWJ1Bf`h*wVoJY%Fmhp~jYXz7ZGW7PP_4l679v{|{th=G;ny96|Ff(UiVuZ()gEQ_X z2f>3$cKo}pKgS%M=kwW$rDroVn--+(3cMjSA>MOa@f)c}kh;h1)fM?g@u~(3qi%oB zVxLi%kw&6@^n5p4{NRZG}oy}TJF32u8|v||Fa+cv&c zUY4@Jcy2w>8ahJSpBzY@K``95iT>bzQQ4*isU)UBY5%!U!W7uGK^fyp+sJ-Ns1~#6 z2}aMlN7|gn(Pz=aiK%m&qSsWWi@43IhKAwlW@#LkD5vs34PnMg(hOV%H@nuDKKgS@ zjq$hMVrRRRM_iE15&eTejPVAQ8XVr9hd%>!j0$> zPvYmv0Syv@fB^p<0>EA^0JSwSW6faz^CROPVlwrvhQ-I!7j_Q6^JQkTct#>}qEo?= z_#V8DEw*SJg^=vF!^TRGMrOLPj~tU5gX9FViMC17-w5(QKuWs{(uY;qI&$`CE<6Zp z2t+5Ju2M1#ERV~}hE(z^S2;v>>oEDBO>6X)p0AA!?EXi|;L!9os(P5v&=iG^Q&h(} zzf@H7OcHIy^{8u+QJYWLZ(_;qFwxDcBJTCU6~bW`VOhk-cC?xt4`O2%cwTV^w$_oi zX@^psB_n5HeR5O87joxjD02#g_KD=~9P4IeKe#Q^l(YnBKrgjLpvNd)lGht{t^ci6 z&;<1!6n#J8ajS2F!Mw1#dq(8 zt7{MH86?||1t7UgUMNBd5wW+saiJm?wqus;A>C3XP1Skh(s;fziOgUw%1msG&S#4q z>9L3dRqQs6Tusl)lU{(8;dj^Ai~R-jt-jLR1VaTf-(9H%YebQH2ZjoQHd%<4u{QM? zq%xbi43bkMf?Yv`{&ricFVJ4wqvg29G4qt|{m6WtNS=Ef|2^(tXwkn_B!W8!+6>?n z{)~BzumyymjW=^FHC<6J<>Nnk2Td)ganF22bJA*bM}NvNLgZVel8gW-^wQR`eCwGD zQ|B+=Tt4t{vc<>$`|=l`vMw16B%D`_m-W+vP=%zv>Uq_;0% z2)(@j>F%pJc7;1uSbSX8^rUb!QssiBK>~R15Z}>5S=zH;39)XjGd^&6y(6i|g;9|% zzWd2je*dM#a=*95@r-oeaJ|rg&_H1!oCuS%mtf!kHLyuG<({zP@<|%u+osfoJ8&o=L<$nG^2m1k#=Z9mB%G*+qm~F(UiQ5@H8J7bkrZI+f1&lq;=kz0+%|6h zyd1Q`-;mQqu(h}4+Vr+Am6{G+lE+%~ctSMvcdP%ztQed(vlt-a&y?!|pf~F-0}L3( zXAG(DFSEXyk18~BNz@zS8W?~9l9ZrF!RhBD^FM%d(gi6cib?X8Nt4>at$mcJpN>9u zq#xlP9|2TI0(g|7>57s@O8gk!c)t525lGGo!~#KtkQD!!fczfRFhp+1LRH%#+l8#1 z9Bbu%^t*RX$auP)a(Y~jKI&AeK!;!qFETH3wcHO6y?!UrykXv4H9ko1ck{inDi zIp$g>dK>JJiA>qI>2*z@UH3~zul?0e@8q)hi*gO28>WF^0j;cAV4Gsp6|xKj%%44R z%VkE0^^oF918sNW7JevEMtDBrcN0Q-hFxkkMpxQtFX)nHIQq>`t@QRd4@|A}5HdN}z;4XZ9b_3YlU;?uczE7=(Y;<&W3*5e*4e*#OhS1JGlXVuURXk>|Re$!>9aU!)5-HxUOD9v(EcOd~u< zKFLJ2p>yO!dA`y-*BQa?@jKfJzrYrgc3;#{ske{w#0^lL@|8Jg-Kf$sOLDc+@aH1; z_&0qmk&Dtp!m+MWweDJ>)FwI`WP6;D|AhQ^8MtI2{0#9dTsw(fx36ti#|Wb}Pm@er zkglzuj9qDtJ~;TwhCR)G7Mji5{YpJ+i5WC)B`^rfut#4olJe@`(j5*)B8zOh88fB% zMWg?cr~$6$Rx3T<@#!G&AT@B`3j$ugesr%HW5=&80PQa-Fp2SC3tFeG?yRH_Y%J5*S79!C|C`tFi{ zIkz0|oH%-6xwNjJhjfjQc7BV~OO&K?q+M?cnEZ{S-wz1hXmArT1rLMm%VwnkEb{B# zU;;YT&A|he9~^NbQ7s&izNXTkI)@>#=(f@2JY}Z?;C?UK_wL?X;yVhb$*Aj8d=Mo@ zYOH`eH7>le+@(>@k(|m6Pk4MvmAwaLtIxSZ4;(u|A7#^%#j>d3YK`e1a?4E9m)Cc5Z(dG2xvyXi>L*R2K+$pl4nTqj zi7=cZ>>-JJsAHg4@ioB%;nNE@#w^a=UN>!Kx<;=ErzT889r{Bk)e{=jS5zp6!HsiP z_6OcRSCXD&Ko};O({X6k)!C7guH+L|(4z?jNZLdq40j~jM*Ck|z$4e&3Tt_ESY0P> zE|Mznm-QL4nzrWLdOc>@%L!tRjHi^Bg3m2xN&bkn;8q3z0hXV=F5&Tww7z55K)5UpO%RwTg5hR?)E`Ib<$6V;f;pg&RU3B@@$4sFi-pK z>c8-pEf+EDb$uYNW63dIMgF`nO`w$D9Dpp2M>?)l*#`|xd_fysl}v>F0`^7;L_Yws zn3Td1H!_GA@JE%?F|}E2vUCEv4jl6TnoJa=cXT<+4(c4JBc9odLQM0Hy?hnP|1w$kx^IBL*N%i^_LUZi?_ly_S1 z>J{9udSVz3GDQRq8O=EibPBh0$<^~v-gIRv*|v8lpq#EowM z=SlgaFUCiBo{w^m*ll|?r#$aOgB$@URUN`euWaV^7{meVWZo2}5^Ji4P@Xl?f2zw^ zm`6IL(pqGtS}>^LFWlK>^8?dk)50?CHy%EQ&w`=`1>^%xiAM5a0uvweq%jg5^p8C+ zpi-V43wmSBfwUoONKlFgX()5##k;$Y$_lYUJgWXJ#SI0mK^zPu!9MF-AD#;j557{? z>u|i#^2C)q?G8fM_v#S)z6jTPFW?X#5hR=voV%)|_5Z5%ANmJj!jJ3lYEI7^QhMTU z1xyiwAE>2~_ZCTI+H1uniMa=d`m=-AAL){Bs87HG-zzqdnRhEf2ZY0I2AAx3vue0~UXrj!KNo|`bBT<;D-Y_uTY9ynyM90z0o zYVtc4&q_RjSk#IB;NyR;j(-?xVYVZ|tZ5P^Rj_WM&9LIVWPR8KNCe5E#VKkA@}@&b zK;mfGJIcHDw;bR_)>7iD5EYe^(_T~>$#5BpA+N}cf8i}{TgFiM#S@>4<@mb1Ds` zBK9C9(Z6XjiV@~gT|(!czE9M`+HEObL3vRK<3J5J$d4DbrB-IcK$h9LXNL9P4=#gI zt`3@2?H@W-2b;=U1m zB?pMFHqU*ky=WIIo9SS5zoWtge*1u^X)2xL`D|EFDs!mK7r`ze5(#&AtD4g4lu+OSu*8P}DpUbfEhl`}aJDITl!H7ZV6a z3H411DbIGn%|8k|KYG--3CE_?eIR&3q?%Jy)!2SIh~Pqr@c=XL zjK>O^`CvdT&K?lZq)%3VW7NP9K0Qqf%7&Pn_^X}1i)$W`jbU{Fm>S=(lSA-Kz}5jb zN&foBVC`si+Oc<7n10y&q0_^$I z^#%NjTmCOWyF z-(C512q9|)woH*E#M`S&RLSWgUale0PYBs-OnS}YBcQN3e@$hVY1fLB>GJ(-;m7K# zpB_lvU-7w1ish^6suYXzSlgCa*w>%xPR>k=8*R}2WsrM>=Pzwl4`FL?3i-^&;*rcU zXYZBqd&c(qOU{#(n(1#JSw}K2QUpfCZqm)LY?Nmfl4%RehNzQNj1RnDvWSepGTqGw z-ZyOyN)O#Mog|;3@((XeTXNEuU7{H=&7EP046Db^;B5YohkzohZs!By)-)6u&h$xf z#A+SVwXX%~%vKJK9FvCK_U=AsB4Nb-fjS66owH5NWB~u+kWPk`kRuU(&3(;kMLWcbMkwO99o{e|EDQi}65c$cY2gi+MZ!DDK738i}PO z?;Pblk>l$6xFXl9AOOYu+_}EG9H?MsO*jQFp@34yf@b>h1Y>S&%Q`mnER8!wEIrkRe(gnd*)B;$TUY@+xl4m(lzTw~r!#iokW&{s$_+X5 z?=-JgT{sNfVBzB6BNpmg9#&-1rgQ<+Gy zX9y6L=Az3&vNr2{fvuKu7jTWDD!&BTlfWvW0GM|T2r1@h+I2UT?T)3QeV0U0jJgeM zvMu{vTA-9hVQ-Tu`%J$oSyF?Fg9wD51-|a8TM!i~cC>`y5^5TB{s?`I0@nHMg_(bm zc~OANXvSn+)*QS)YzM0zt8Xn7$$t;)@{#Q2!`F4kE?_Q zK1i;VGvir~dGBhJJF8rdX4#~ZhgIAZfm^%F`YM~Wb+X?*b1beh4QIjQWz=|oWe)Uw zbT~6a?f*RGOO^BMskW!cz-0(Y$K)-VH@{ePL|gF++K7 zVZQs;BOyWew&&M6YWnb?`y<@lyS48Si$e-q!amU27WR(uQ^c?9x<_~86F2)>V2T>3FsSnp6Tq`7)=)C_IGJod zfSTNXgK|ii4&hE4c*wLSURsdM!JsWZk&+rQ2NHrMP9(ph9Yd@Vn}qVfli2w}dsGur z8j$OQ{D^;xObKxkU6f{VT4Yvq5(*oAX~gKqiEdvV@|$dH<88d!SvYBzzFG*ywA&Vg zTu$x7&;*l}dWjpQeR})>${_KJCt!Xk2@2a3TO#v}H*GnZEIU2hDt4-`VZph?tt2C% z=e-!t2hh>M6n!O&{GXaZsU9qFyU%FK90LQGK|&~=)bA;+w$dh5Tq+kVUv;yBOMAI`b;$(Qrmb#BMcPf8qm!>{zlf`8t=cio*(wf2?7QPiT`dDWYxQr)3B{D45yg-y_GgXCYVK}R=E~-g7yn#cT>b1Lv1lU- zBc`M9rL9aZte65Cl6fcXgb9xjWasV6p9qCS`4Ss@k^%>bY-{*jq!E@0WNDsQ@BPMl zex@Baobp>zRdjDJ;%5${n zi?yWNpI#r0WVmO8iu4d~uo zAf2|zM0Ka?Wyz|CbrK+Kzk9hcpxe+FgbgJXtTO84YM0=UeMA7A6hjnWzt)O5R%}# z!S;x60c~zZKRSA7?uJB=`Js6LH->K8+V25Rj-6QtWJ7>2eS@ob@pZ_66<7C|ZhQEp zx)@!=PUSkFJohHn3plbpw08L_u3cV$s87t9CH=XW`J!V9V0#(Qe?8?OW&qW(fHgvw z8C#H0-4<5pt3GkuPPHn|Lz{TR-w(@&V&-oet#9LbEyIf)x&nf$!_C%x0 z9=Tnvo`nLX7OGAslOGQYe0}`X7l1@o*Ec54Md$(7?GvzNpx~@pwb3F5j)CqbHn{s| zE|%%KJ!&cq9&yVtI_04lCN0c1t#yAP9{x)4{{fQos|W3fhbge-bf$WVO3Zot%cDus zLTBH??*$uWvgv|KG076M0q{w}&Mq+LorceX(}!%uz%u;rpndt6(W9K!x&J^U3>+)hW1=Bh^lq*XpoXMsj)!E%GX@FvcEO2^3z2urvZ7+JH^ ziyaDj@>GZd<$|bABT)+S&-taH>O984rUh%;22ed5!$nI3!Z#F6JIo*`2EB*D**%ZL ze$IG(O_f>RW0*rEuqA|KTrxzTKBTmS+EH9!0*b+~)xU{%D|0f1};&*sV#9AE_NbtPQU{^}e>L9}a&pm#(X>wsm8 zf0SdhX{k41SYll#3&zUMzo{V9;+|i4^&OGR-fhrfrw(8_&*5Aa?$R;b%lX)Om*O8B5abOyqZ#ar5UJG<#Zn`9? zPD=iw@FY>MB?l+6< zOt3oI?eg_6R<*LArzx+qQs1iu-$6TxS@9*o2pb;L?w6EE>H%jDV=X`s$-Fk;>d4ac z!^rO!HpU_9U^UWF-GVQucNYkt>Sqr2W7ZuCPCpW$nmhZ$AlLZQonmWmut5 zAWj1wx_znrjX$|*;58h>)DYF5PNZEGNu%51gP1N=Qf@FU6QclLJwPCXw%Gg;Svkll zI8%iIT80(er4J>^Z7Dt%TGlZ_&e>qwkd*7kUJXQ<#`z{O$dnlqsm=(nyFt}ayKYne z(1gy!<4U_Xe!!C?W{5KgCN9F;0^RYp_*O@ZG>J9nQWS1>$_Xn(hbtcF^WD#n^OkB~ zcu`fsnH7zIxMl~_qF&%26TMcnt7b#0JK71!xEjadodXn5OmMn=Fy?O;po8ztnEweeL zlvv4siFCdnj^pp`z*14PaS&?-g-T>usn+ZX2Pdlb}f>@iNiIr zdG`=tDJ5B5cN3=)@6O(DiZ^?nuR4UgrV)bpdJA3OinT}`Ekzo_D%5J|b#C?J@)fGJ zUFP(ph(Y!wlueM?#Mj{qU%a^FH68^7 zKYzAkN)J5CIHsQ8PD+3vkG)+;*|Bi`}Tt ze8QusYCZKa<6>3|AklvOHJ7mXd@oQc=C$Hm%39pVY8!YHwQ563W^s)=5IYFv$ zHHoc(+5VQfPHka5Z6HxSE_J;8DZKn(k0q`w^5_?lSZD?*dQcD%c?rjjlH#)IA5n1J zxWATyR(|moE_}-s5X7F=NJ$GXJ6Rnmma&l6;xiC>;Zzx$3K1ErolnN-XKeLcxGec; z3{`87W+Xk_wxYJ#b3xY$UNx_LX>MUXr{?S9(!BQ)bu20E4PcYTrpnSH9rydh=)KU!T&&SH(w zmHNMK!jpAxi9(f3P3@j04{s@(jt^A%oX%j}Jga_(i4;o4c2pDSAqzcx+82cpgI~*G zLbXN~8(BXl+`Rchw9(#bFYxWKq{0O$0%EN)ps#PwfK=uMq| zn$&gq@%yS}J%;721Xc$T>nA4DUYF`CSy*yHG}Tl~{!Pmp)ymJIZN zcvjT#Ac7Y$ew!k1pO65Jg)+GA&Xb8w1puRkF_=NT%q2j~vNUeL>w zCz=*s``#G4@iewrwI%gT_0Zhs8x%_+uqpApAx;CUH=0PGMnW}o$tkMkjG`hp3)Psm zFi$&^)3-T*Bl|c_^-F085pUMC0K{3yvE_WpwR~W>M1T6}xGcZ`k)Z}yTA^@pZYv>c zkny&yl|d43kbS~%E?sL8emxT1Fa;HGlq6PSQEV1n%$RcDhDREr!vP{Kq5;Dd;sfVp_SDgIUU6l=YM}Gg9U1fO}8zhUUaP8MsB(Zc1pXg|JTsAD~!Y%DmSvM z$G;5Xu(ccCnQwoEahvj-J>GGKT=jXk^B;^(m78^W8UUYbE{VWZyL_u>{EC-&a!D8x zX~I0_>MFr)<_D&O=6OBslWKE4kEcLq10_qQS&3fy zaCz=)1hrdt`9kTDnL;^@C^7N>u&MvI>jfCQk3NgoxVJ*>JP?|-*GT@QigjXd{w;+H zc@S?4(cmLe#7XzDfZUd7XU@DLQq<`3{5P_3C?w$Ty8>+lvP83Hz!|Rb4Xdj28BN|g z`KvVB#G~Obk%1;*e{78sbIQ691bT$C0+WsO50akgqn0HJgY^aL!&d8j8cu)_yXj zX+yg7LydKZ*57MZ-9N4%7V8tu^dl1gW~zeH+Z2Z)5M`>;FmL@THkm_C2jff=SVQu= zGefm{7x&x0DDff1zerAEnZAW7-*87iNeK=zGOoZ$wG z+4g#Y|n1 z@%g2LSm|9K@j0MTjbnZ}Xi6?S3w~KbPb3;7W6bFZpwm%neRJrMFqJ3-QCc_eNHBWz zVM5m;*AtEDo7rqnLDs=(pRQp+{~ZJdaPe-v{?z!O+m8!%t6myJ2U7t}*JAYrYMQpdc*L=r9|(ad8^T6B5j#adbz-T5^Xw1{PLndM`7f;-{~Q+F$nRO2gX`iY zS(GLS)QrRVZDfAk_Wvk#xDFJwJY(ej<7we~zM3`C57~iO#@BwL6}iY^V?Y0gh?5r! z7V^?r=U|)%@XcazmU3Nxa7ojBvspaXllRZrxwtW{#b z9&w}2S@mggB7td7YF5= ziDEy=4dKUP^Z(^k5_@0YW=IvdL!QULyQl$ah1hLjq(V z@(%)z?#lDj;@#Jq7tuqBVQq$_NRCcU=YS7_OD|g|Da#kO-mWImPko)LTE$ZCOz{Xx3>I z=-HXnRN-V~-NJC&;$FscpA(xO;QtbCiEjp^hFcO2GgXjDhZ!x!iDa)C6o@uTG2A~N zb4`Ncc#XIfZ1B{M8b17z-CG{ic)bZXy6$OEqtSm3-5qOpw^CQ+AN?F|kUiM7av*;& znoC$T_pWZ^HayX7Ku|`NF1ir=xhYcvw(QPJ+$X|57Q(5Etb;FMGK_ap@lhq} z5ai`Y;#nPMCel6H2l z06~Qh*}%#@u3jnf1fLO?3F4}YR6RuN#)lXDaZ>0&ncu6)|B$eKg)-f+|C(D>$Bl)E zB(MG}n}7AP3tieR5cywb^HX|Ukdf~))QB4|xe^PZoZ(Wxf3|b3diNH`B;9|#dbJ5s z3_MnH>&?jFIC}c?Z+=E*v(+*B@_9DfqvcyRcV`ZC8v##Nr-qmT^=uOPl>(~%yXy(0 z23tdavMiG}k|^n^_%$L-?TzCuDa*zGSVl0>m!Q`mO8G(lrk>LsV|&`-gZ)DvR+Hox zAaEk`)@(&8fdZ(p@(xj^x@5mFYYJCH+9ZXC1pDl)w5VF_js|7r@1l9$l_Eu)z z+?0}eOj|#3w!RA5TEL_Ngi5R%zPbV0H=202?$EY97h93{+?b ze2bt;_CyIHkGZlQ88?SGM9!Q|o)F+umTWkz6-$Tbt;Jb;k%8ID#iEsa;fz-z4_$F#eb(k8A?9Fxb$U;wu^$7j5%ZI0*$?I!Q1$ z-*Y}!UyjHpfVLAi)|U16c>d*xidnHjlVNSr<4;E;7{a{$XS)#hV9e#>8&`iA0LYgh z>DKEBY}(p(?mCgpQdx-IE+eZ^?Jtk~jR~pc8Pdc(SHG6**!e_Um($M_FQI!%DnsOJ zMCR2RH=rM}W5*W^ejpBHc7gTi7Wla!El_R%$S|?#3OYp$lSp;SV%-W_mg6n$Hmdf{ zi}gJ(uFn3J<+gRa{ns-G+}Vc_)JDpxqIvG&vN2x^E?Y=^8$cD41G2RYlS3_x%G7#s zjn_5SsUu5+khM)*(9)SS-W~Z*_cfV75`|ce)%!ex4Qg}w8t*gLs_l{Vp7mb@9|Q#w zh&_rAR6Glb&Y%kQ>I(pE5e5f5ncthrZT-@P3FR^lU;)35--0jaPkS?cD>ZG|;VP8l zQIkozy0<%djh*jp(pI8;HtyP;ufHZnSREoi6v;y(xVOlJ<_RJ(h&`kpC8h;aF-dF) z*zQM-nwN7DtKOpkGS#@!=_3Htn%+tkB#Y=jk z795VN@tD?uoevf**;Gk+WALtF`cw1o=n?@KoKUY6p2bKfM_hay?=QayQQ%!%}|l z9T}oUXU^Sl|1qOyQWpxGIZMZIR4w^{)@t77!0;D&43J{FPzZ;2@TJr)QeHK!&*zRa zI3@@~r2ryFVRg`nM0Md3T8cI8#<))qSUdoklFBxUj8w(!koo6Mdpmd47f)0inwL*i z#Q5u19Zl-4TxabT36?fd24PoOea5Ft<{M$|As}&$p+=t`4`*`gdL$FQm2D{npZG)D zsMQi5xT5J1N=OSKBJ*)+ND_=r|JkS4ze|jLcQSUylYQ;}gCFcZi}#c`%BGqzm-T=C z{S&nTHW?Q~xKXNSzFD_T^iex^Mu6Vx0rx(=fXct8#~$_I$YrHv(a=75Q`8}7gEX$< zd^mFeNisAZ%HC!@MSOh2y~=#4}%(?lR}N z&}^uee`8Fyu7=*O7A^Pf2pFB@HTkZ?4tzk$0Llm^(nUuSV7SjrvNFHBAi!pfGcWP! z77XF+_fIlhmp|Fr{@T;@&M?XIfA9GH+}={++aBEEXVSO;Oq7$(=qfVWXpSYZ+yzAb z!0`1p>|{5?Dn;S#!rWT$Bg!33+^5;3?}8LBB~zL3&b=-%+3CwNSRJrB@mhmJrk$G}p3t z;>U;fZgJGE=xuM-bv{xuaqma&3s{^!Z#@$pM2bJp`ypc$AZ_cQw7;SA+id5&LsezRd<3lHno=0xuh+VMV2jVGYmSP-4oN6l@+$9727}tAYko z|3M6@Txtvlh&mdkuZi`|6jLUTv`b^AG=^XAF7TfgAD(@KZhB1IabO5avB45C+NKpS zhvcJd+PB*#e^9q~Azh#s4+taJAYaW&*L{%lEr1}^VE5I5?!nl>rompLdI8n{obFVx5}vzL|9Ej4KJkA&dP%&gM^$fybk!@)-Sv zM-6`T_EDw}A$~GDtn~O&?L?G)kCk z$uymsBaI-6==41MB(3!w(JAxegvn>lwnClA(mWke))bmm2eEyhc=AzC9ks(|sssLs z^9$Q{=cnu%Op7+hR+Y=EdWcF9pQYjng?>jRK~*ib&@oyTsApQ%@u0UXDO}$|1pn64`t5ezhGnm| zJPfExpKo<_$baWwn?9l8h}M%-alU|N`lMEHF5@MsW@j4)i1QQmqg@JZ(lahTNEMhk zsz)J;Y=%ZOiU3%N;GrLvc{!w1!}K;bTT<8gw=HD;ohn~xUBe+2zamnHQd4i9_YOPY zMJwzFT4lOSx0ln%)-79;+q*L2d}Y~%xQUJ_$kr9_#1Q)~Qq~8R-fO0|bG(bxw2AIt zc4Z-BY{{BfuMQu-f{5Nv=PJGp=-#nRQ7I_Mwv^Qgh?#Vx#$74@{s^IH6E?Do@sA*G|mR z*t}?OI{G(Sz5nfvQevC|i3BDua-Tcu1ZLpg)?GaGMXp9g*!}&Irg^R&J4bIP$U>72 z#b#FjEFSa+k*8=KCs1n`sagsb%I{#wF;cJ1crC%7TYLKGZYp!;i55Pq?e(O)(Fj?4 z{E@{8YRHK9e@|Vhi{kj37pjJbfSce}vAde`>xs+W(^0Wuf9kVmo)F zs2-tvkW0<=bi}X|jjco7w~Z6;DP{7XcnX%Bc&Z^tlUK4yA8wE4uU#0kc zg#C8AkdvRNog6WlT1D%VkAFLjsdf~TDWPg*+6ua*hKej!91r|%d!AUls5MVb@k1`XWNbzu|Q&(8NMrHcO_1vDhtK+j-WGsx<<6F>NVw0*4fo@3bwoFF+Yng04 z;BR6SSQ%ZvU$uPIhN?JL93Z5xD-0&tJPaQCdA<3!{ofz%8+fqJzgq8VVob{5mNHqY zy9hkFve0#tlTrEd%@0g{wo;-e;ozM@SMl$UPygHl$aIl#NScKeM-5m;NMnw3 zryuXWCiD`LmX(41r?8wgsdkc=Sz)i=&OF?7=Yj}{89}(fSK*(|O`Qr(dFK(Wid+7S zoVRC&QJVq*F8=b?z$(yjWc1wSf`?gSxAn9^`h3T+=ksvWZZstr^*^rPjyTj~OYi-6 zBLrKX3R4;NjJTD~rAEzZuiNfi96zO~DSgcyqR&NT*{9kts6??GB#$LwPCeC(T9RP} z@^2=W_40NGP?8A6!e1xZ%}~n~O3Mt_b_+pHD|K_pNKw}#Hd?QGbhMnfl;-N6MLR>f z{b;6d6xGr9x5h9 zpOVFce>)yW$d$TPuLx*P7qRHA;G^m`il%A5*1xUldCZcBy!hqK#FV>)+ML|nZp-FAvK5_$(M*cf2XsTNEQ`UFV5I4Zb&ZN3Iu3?iiHBO$oW)qh8jj+J-X!8UX2!{@d z_rmpcEhuHM2KAZ&u;QD|9q!wrK{?kgPSZt9 z4{nihp@wlH;RBM{DFyA_7J32YA0Hc+Ig8C-G8W%!Z;Zi@n8)%>NmL!D=F$hlVyCMb zE<{nCA~YYQ?m>7Kv}}3EC&P3UH|;LSdC@p}U6DWHn0q!RV9d85K|<&D*0_>-3V9a{qr`c#b~epUd@ z=IOld-B*7Q$*X57*u0<8Mjoy&MCPBGf`RrwKyqYE7z@k(VZboV?nh@VeB-Bs>+6)8 zPR5uCds+n^2vHL*9#Ayi!5dX5b|y7mzyB=PX~WSF(<}`UHHLIjs3t?rv5SRDQ4k$n zdV&*4yvi9?9J2J2)#{#-*0t%{H)yL@ER~Njm{(Z!GGShhMA!1b&MLyCF)N<0=o6gy zp61-wSGhc$$>t^bA_u{y_YjIBk7mDRA`PpQKM|S!ZH_~~oEyPb-((z2mbDPa|4>*S zZuJ4II90P7Ng#0b>-;0MhBr0}?ayxxn@7GpmoIvm0#Hoo`Q9APoDxFt;DkOdP{p(R z&HdEo2rOMh7G}jz`BySf)mR4sK08qzVWgLzXzY8XBC;*#6i4ud%e}=VGskZETEi_E zYj}Q$&W(iu)fG_&FIE8vmVJl|FMyLF0L` zd@~T*HezJpe3x8<4kyKTJ#W#v^|^p2k)EhU!Oo>yXne zRPL2OsTwR_RIB=z-MDQOfGU`bHu0IE{zT8ZMRk<4eWY$0od7;q7)`hROk487Hx&kx z$w963#@QQM@CxXt`)X>)#rjtZ9Cv@?n#$|XrjuczdKu|6%j1to=c+u?c`pg>Tr*e% zEj;B6mdLmybg@#M&Et$^Nr$ao-Yuo1+eoJpX1j(lQdM~)0i@}YZCGs zj!2#r*tKDG#K!Pz`tmZXiQ-VwYJ#lIu>3Dle1`N>D!hn*aat4?iYm_f>N68PvugIf zy$iymjv1$td2QWr_y0*SuFkcx=Gi7oy>_xE(VGiZwi2t83hp zBYXJrr^9|vDwU3E)5c&nQZxPKXmQ6A6Eqrfn*f+!EaI*dR>I@NyKO^8+1wwdkC@11N!+tDa*!M=g0g7& z3#cwHd3}u6x&N*r%dKmm^JG%#jqxMzwJyJZz6(uK3F0sTPQ13b7Iys*JW0hO_ny2A^hR#Rh}YjDz2z98q2A3!YISkq(v~d+Y5gtkg^0zeUS46r58H#1YU5Eg=qNHN zKw+dP^cAv7-^v_?uaIc;J9F*9$V(Tqf4LWM-pPLBf+u@bmd#x(U@g~gzb^e=+CxM> z6%&qMSX4}loSG;CGDLFW{WH&eV!7)=m=23HI^lrSuA%B?ig6;aK#aKYG&%x_W{3K- z7X1CnHRb+0+B?r&dEhn)+*bT?bybmGPRdYC zIuCn<-Qb{*9uf=`MOADF>9WD z@0!S@;_humiqz4qA>vm$rPHVg55{b39ht8r#i)pHAli|k)JLz0jfdK(w)*OSl=QnS zJNQrH+d{HHZhA!nkI2H%5g8Sj%5;FxeQZ}S%wnGbZML>p9!6-^yt@>qW>zTQ$$#L%0|J%EvH<)CPU4fB{>^85z zXREr`?3);?P^LBgU--JyQn$N0vAH{)()B_UKC9FV)I}c@P$Z4gx@M#Bv6$mtkX9L+ zPiS9kA#yTz$QtUHV00?Wq8Trj2sQa-!B;0#bB5A?I&zDlyGbbw5=4yfao1T? zplq|q8B7^$=pf=CHXq4Fh)J~5Q)qGnBq40&8Zp8aNa&R(v{C&38DYRV-VI5P*oQs+ zPx=4~MRZ`HMkUD^H;IKAyopE%$p0ymBMAlo{yEW?g-qz@Y=*}>Y6AVwsWog+Xfxh% zY8`U7SEX1lg!5LW8duqET?v?KG(Z;w61KCdl!xX2LDsyLY6v?}CAEGnajR)=$CTfj zx=qOwazos<)dLl<99!g;?F~7)ThGvZ7W;3h-tYQ}TgAm^UZpM!3k}30OHgm9MP#Xf zu`L3g&WyTaC}vA@PFfABjdy|^KO`B2mv&ES2$d0&Wj}DKHZA(L9lxo!t~9tIz_)jl zM*Q|G!s5NxW1FFp*HtKbXWq?XAyHSA_H|ifV-PjVcNN$itCQ11dPyc2O6q9SF{F=&%-aOE*t7m#4NMH`3|no7(`D&LUeIo;IyfgeWG#})n*7k)4h|5IG)EzJ zQ_WkBLgUIa=}tQFh)NSLcz>8x@CAKi)Eeu~yb^0Uo^KjV)4K&dWMG^>&OMUctgep_ z-#z7!)}#!>+QkBndu40uprv{j%3D#{?TJCgs$g)$A;=k#xF$RQZcmis3wW4#8PB|R zqsRGE%D)lB{s6Lx$AwzXkG+=#p<(@IDthBr+Y{T4uEjYSa&7u=zG=-QDvih&&eN}Sy zxM&AO|AUUg=>1g3`Jy+PPgM@-F5xt-J738uF5k$UB`#)s6SyWmdPj=AQ_uJ zE7@orVTpq0X;@yg(?LZch6ud?J1u>GS#Ob2QP`FlA@pjY(BGJ|w-hw?mSl=+^T$}< zG>&zBFRyLhvSaH+n9%dc%Cfln{d3kMmVDzkUY6}1*QAmu^4o-Nu5ON_Dy=Fm&9n1T zm!pvWAYe1mlgXuL8{jdesWNq1-w0*%XXoWsZ!mge9|{m*=V_i=pE6(qwX&s)I8?v^ z5oArpDbt`8G3HFHEMAR0_}(B#Xx}%~j|8W4HNL#r51u|6i?_n*fTRcl zr#i7@khw0`lU61T;Vv-Jr?-|4W5=)XbIrn`@Ung75*#euZo_a9*a-701*8fG-dJM@ z!MeC#kfmXmIO=kD0eGf1G9iTvwad@K65!)&eDCPMa_drPhK((<3(*OwTH=nff zyBjuqcsb*__qS|$qZs0hki)z%~k=4)E4)lp82_sge>dPWBz#+s;xM;O4PrY$neL+|l zH?NhaE33lPf1g4H^AJfRx!c*}DEoc%JEl#|D=t%+;gKj*tsnTcVA0V0&ZJ8RIaZze`HOcc&7 zAsphZQDB;c$UL<-y%^qf$946ZXC;v`dnp4X#baWPQo9$6RV?5Ln!tSEkW$lLacPM} zs)6zD!T#0}rZC{buraj;H!b79AWETIHeujI>K|<(cc7{YkIvR8&%sPl6e+|SRw6s0 zMTAaPu>?&*sQ&5j=#&dD|Km93LhOPij^1AK^E5xTd3!t>FHLMH^EM^(w}yrgQlu#I zcB!1xK2cr)M9vBm&UH4F94T`Ils;8>63CueA znjd3Hx9!=nBv^>^HikDF0q+30{9X4C81Y8Sgz*+Ra-&t%%Ln&hB!$=l2|4zLfo%Le z_m6*a4}Z5t1t|rZk&EX46r?!Bj`SA6c?e7p<0h{+g7kY$vp!!ro2HU~y?vJAyYBEc z|EAgFJa18qD?}R1r985!cEn8GNp$<;>r&H59qQtJixO+NKcObkE{bZ18vgRPu2JNB z)8o!c0($9*4{NX~Ro7onAnwNMvF`8nI1UFc8^*1x+3<#3gOy@sDRyaiBG9F5E$&(N z+&Cef2r+9@Rxv4ZqzA$DWlfVVRqDqF)5uBxvg|xP;@cd?W<)OkEO9c4FXX8HDFMA= z`$pv>P8?yB1V(dV_By7F*tH`_CSoTcy4!?eO;}{F){J~~NYMJpV(vw{v9d;^OMUSR z?gz8xN=MzipA0D7`{mO}QVUuZ58{q6UcJI_^oKy3v(OY zg3^?Cf;X>6CqdT|*?T%Nz_a~XO~iF#}YuG z3sKyWzD2k7t?bPRC736TLpF&B;>J}~!^1htc|P$Z2BL1`-;KP#qVh-d7hIvY3R>11 z1vp4?*^Uj#@hvgPuFups-j?YnG;*@Ix`(q@x2{hG%i)>UYemcZ|FnGvR8v{Ic0wr9 zouE<#1W81YsvsH#gE&eE5Tpo#k?JVwfM9}%Mgk%ZN)6RQQA3k%1EVw*5Jw$IXrm%1 zs3a%|2GJn;zX#`=JIuP{b?&?LV1 zk^rN!UWhI^y7d;&l6$wCf{~G?@(fWbSk%D=4h%YXhWUf86DU~0-xuVu5bk*<_RbqP z0fz3*6G-Sgzk&tf%d+~p!L)-X4W5n^o4ahdvyTkX?BCw{Rc?t622-o4c@x1xGeeLM;DFGEgn`|6G6NQ^aRAHfZffbu_!4XK0 zf=BK8`as|b;z#fSkKEH!9pu%F$S}clC_=0%0MX|3^_;vSh0ypyK-{aH5QDAVQAd!UECd^Za-lpe?L7gSy7jYk<@_RAV`}@s$5P&aAS_$@N z2HIe11YZ3hcxq-QiG6yEd|o(MuCLGl9=>PY0J`v-sNk{{Xq za$O*7&RZTWWa5*7S#1P(Dj;Z1LLe})8oY^=uNW~29)X#Q{TO@&D zfae!5M25HbG^qj@hseg4<$G^IguG#b@m2``0OSe~qM{x)(-j9GES@yb2fE(6dl(!c zz}e^bN54w!12*f%qd=_+!hV-MQ$I)U*y5#sMuYtbc;60RzMZ=BGSKhGRdqgiowDQT zU<)0n;TP6g1D6`I-$o>XASuVZ14H1`3#;QH5Mrw-OiBwVp!x=uz)Ncn0>jVRA#etR zH|iZ&?E$kraMOeD{_9N}DX}AWVB+lA2`MCRbpQTQ6A8%(c4=S?R|{VMZ3bWnto#bx zFV+u#&IQk>b*g!dn?1PMNy_fU}RA@j!<8UvwFmseh9{b6wL>O5q@nSL+}oKVUrm)o5ZhkV+>lKw{sn1+Ro2;AVkPo#4(078JRPumuXKxCGmnfwL>X z{&H*z}90% zd-yXriM8JVghf0`Jy>i3F&aQ=u7uDEko%Gj zg>!47YJ zNj!jX54D;he&N3WcLsnECP~s;u#oepKH^cm$K#iSey#5~wO6YoA+G4IZI9N&MrFFS z9!!E`nvxk1EA&PdsGO@f5F96X00fv|-3waA;zOAruz|&5C@9roZaaj`a%a>mhuw@p zHTl&njts_=4}c;KVZ(1n>@JdI5y2x8>qHv)2J6w2;GBby|82i24pIQvW3e)?KMNWf zd~l>(S^F7~6!d47ffNT}$8Q13@iWG$s}uw7U9SgI5|9J^5vXy=IwWogghu?Z^%H0T zA;_dM*ds|_MK8H%5*!JN2FIGB2Czj59|CMgpg??kt<+fIFa%U zI5Ya+ZGL|mG5K9!^9-cu3us$?Qg+mQlwTw}^)p2O?!5wpF!CDXA4W4<+U1`>Xy&$d zp?Bl>p37tiW3O=(2rEIe4$MQB5uS5!#f1=zza~kfzWd!0IEN$=;!$8n+xccaY`$L; zxQK6!LDGtpm(CCk@5Vx)GVkz8T8>bwS^}NrXyeXN#D|CZdgmJk=wxz{piWOswwlSx zJsZpgvMF$rWdY5=jHaBL0M-`UypHueszH3tjouG5>;dICn5u&d8PG)E^#N~mh^#cY zyLmlGo-RO)C!qZ^e?M@){F8t94G$na-De0S!H5B-*BwJxbs`kfFa<)?CUePHsUV6w z_yr~FoCN`<<&Uu7K)f=5%Qs92QT8rRf&zyNy2J>v+!UZ6SUpvb18yNx;1)vGm#|q! zf``WSxV&uw8;#)CYCuCUeWQ2#6L8+FPXOl~kE3FU&Bpp}w;2k9H#4$!Fy;sq6pZ?{ z-hjpF`oVH#2rGgt@L)&tVS54?Qb0U!)BD)q4`7)wFKF)d5eG!AgKV@EI}0h2=Q$NHBAmkz4sz3Kd}FuTYpPg@Tx3~vl@iv zKLJA^SasY2Vd$rD?`N_g@d2T^l7ATD@6!?sWWhjh1ro^7OCN!n+}{m|HISYC$Cc)6 zqut;O+42T#G!8+y2nhWE3MjCx1U>pAcxC4b!N@204Jd?wGW+teGX&7d|C|C&9J!Nw zPdSTDI3)Cf={s;xi*Bq816w07*Vs%d8hB8AEN4Us7SiBZrnWUP1vKe7h$+#YSO6>H zCyr>xH@956y(>uljQQ%7;rdyxxxa=i-h1Tiov@7E5XznnOGons5YY?PgZ-d2sgZp* zDfct@PlE^%G%LO*Yk_|VjDx}I5*&4>fmiaaR}vU>WXjgYfJQ*l_S6AL*tXkS zrR6H_9Faiy{UHtz73k6-8k4E|$ftv_N3znSJb{gM7vh{aLpTKD%J;xPjkuISl%4vk zgKbwJR^${wwe^D^WJkIBhF_ukG##{xj-O`kcr_SEI(HCEgPQ{>tw7jO`0O+Y?!l*0 zseZ3xSCyn8?281T>*-tbgJ!SZm&n_;MtrgS@q=EkU)y1=19h1$1wP`L`K^|cB!NQP zvXmwpg)_}!>upn0P-un$PS-)2;KL%}gq8s;icJ>@2j6G@T0~)IQ$?+-zBuw&ky~-8 zZ4)e#rQ+8w?((P=+$uJ!LnE**dFK9#zoh&#i~shE{KT3=Ql+dR`VUL-jDYms71Pbz zFOko6Y{*NWV7W{5oHG)&F80o9?f87@kCNz~8@9tb$0Xk+$svc=EWGrpPYYTHBW$Ij z0&;R;XfTD~@G1{YNGLyz^{iVc>5gm+bm) z%)|F>g*%*Bq_w}~NJ+A618^M34XJm?=j_5D`hR6j!o?vE%Gtzj2+v{-#Tl{T7i5`Y zd_O>m&T?0nx_PvVg#FaK5i^WqMQC0k4;V~DwCWv5@^5wDir+^)fvw-FyNLg2p8;IA z&G_2-q?v3|xw(^{%%VqBZ9bQhz{(|r?Ip~=zyV!R$R{U(mxBInk0O)TK8+6 zaL~lixHCnZ`BJWi+L`Z9!WR*E46T_Y-v5>I&n*7?FAD`>?-jS=+XRc9>_n~0I6J4} zYXdTEisG!74dcpXtJYH|SR3k1Q;VSwzIGD8Ee)41t)0wLg+ppja>`PY&pt2R6uy?G z1S>+0g@f|{2XcS*tDVPd32AA9e~JJV>WN2oO1u@wsP#*x**RF%_$e*uTSaxCHqfpB5e|`JQT@ji$x3@H?shgpGvukFN zo#+K3>zRcAX|S)k{PU6G##`5=+VSSKW|dw$?fB!FZjCHmQT%vj0RQDA9p#bQ6aCsL zli{=M6DoVfJ5@sNpOb^oGH^W%F{HoYU>PTkjY-}{`d^G>sPoKh^`Cj?mf4#%j=U?c zCcTQp?&REouDAiXCfQ-3JCz#xxiEEPI?uG*wI86Jps~JVK>w!#;=MjA1d3+X;M@B?#_9d{bS$CvKzUwbmlwAu`7>)2t8n*6|-N>oW1IB-j zZOGw&oS?Nd;s?hqahQfn6l>Oo7#0bCB9)8xUKvi&(9 z&D`j?4(ZdcQ|2ht55JUz%h^D|93|nFW2s18prXhtsu~$_f7Weg=KKFQj>)S%)Q9L; z=LRi3qgGsOpR{}(BO@Xp_Rb}n;M^TKr?jhY+4y$RCvJ(=&f3iN#D&dUs7+4ybMuD*W?lK=cR`SDBp%RIP|wGcc0pRBk4 z=hWdRJ95r{y$jwjSR`SUaY#l)+)N3!!?}5tb7U|i98xsDt-9*1@^#pS*w$4qXG->g z)UwSYERO$sAT8ORn*XGrkiv+%u#GUaupQSR?P)OD8{I7#ri>2JUPbN;WN zkvpR3i~e%|g+KB^J~xw5%+h@V66vhv%CT@-N~iEPTG)f7Sgzgi!or0|t9NS~&0(Q7t;Fy-`xIY{6Nx_!S)Hb$8I-}OTP~_M)2>R@;lTESDB3HA{_tQhs(6)@ zi1FiN^i%SAfyaZvO5KfvY~~v7hkCwH3FU9WlCA0^3q_bVxx=BfyTQh+GF@+htw1qP zk-(T&`eK}_?O`Zv-2cgE5x)0W9Dy;nlTOl7my^o22#k^@1SRrwBPqrGmduY@Oi!1> zdny-s5&!u|A*P;^ zn#jNmM!(vQCxqYQS2^J9(xYD4ubOK|>s2-Ei=-q|$4IR$PYVe~IjHb2&enQua^Av* zpI5ij#?p5p{C86O z*72GiuFn(&6Erus4jHz%@Fc8`VI7?^df@5-x~1ic-;ISWjJ2VmHspCFECH=OAcd(i zSBf^aUwK-JC$-X+MDW&Zd74G=J$E)+OFDujX7ZfQ^UY!pS>+V__;*BXH8ky`%&YnJ z6;2ubJ1#N*0!rkYth~B)%h2QE#ajY%^az3M{e%4bE9bDJyWN-~Ki8>` zy`);Jl&)&LhhHi#UNXJmUE$pb4UsfCq>l~`MRAmLWF)s;L$VMDZvG_I+0EVD2^L?}k^EwwW_PvWBXt48>( zq;q_hNe{``D*E_X@&~khm_cXIt8NEs%|D?cTkyqsG&v&BtAk3%NmMOW(Xg}=~h*Z8px%jF{Wt}AtRFmIBB(M2_49Vk%KE@>y3*7Q4a!f(%O z>~@IpFQlb>p%FEBeMx}bdD&zVu7zQsrm@zqk$>bgm5_^d`20MxAmd5C9ZmSk=1#In z2xVUFO6Kc`pv#zY)|x|OWS&x~yZX&c$4qNn!iL6kygx>MB!O1iyr$UQTG)$c5;U{4 za;8K+wcQblMfrC)^oLoyGPgAwtd!+uuN0RJTvwnF2rYT1a-QOZW~CV~pSu*rhPQ0v zSN1I)>ba?w=aE{V>ea*vzk{pi(Q4+}(bawLD%{|a`hPh2X*=yc21{$0h-H=Mn9>(J z=B(p~=yecR3#$$kC_Fo(K6WU_nEQo->bS#yp5FPJy*cu5O`A5)9XuZ`Pl>FX4Zc?j z?d`bTkq(B~eZsy^0hs9xikg+{?B|+?q$=n3R9g$jj_6W)tul7w_ybl(!bO`=BkS=D z6BoXWmxXsS%y5l zsn#R7;EN^AG>K@vFO44^_4`y|dmwij8ZRb$gJZ8ry6_gmtJ%OzR=m)jEO$Wo(Kdr% zl(m!nu7eoqg%NUh+DkR^wT!UYCSg3r_S|LY{!!l093w1U)7m$0E01qMu5XASo`t7+ z4?U+fIC-HGPkY5)sqctD3DkD*d^K?V#%UBk>htMsB-5a*^b)BfIXX9r1xDAF(x2wK z+~7qGJf|&kh`x2Rq(Brtydcu525EqeCU^MEogQY^{X05)DHMl;>Y>8PiPaqh*}SL1 zYRV!0^H-EbYmeJEemK`=X+rN{RTmbVII3l7Xrt^j7#kFY54Oi-OQQWXqrL#fsJu)cUtR zicdRgBzn->p+m^6;^`FLBU-8UO2kKK9_8~B#0Y`32C@Blxi9tji8;%kXKv5c4L1}j zjYvBg3b~z26nRbh3{2Cj_muj=_|>+H3VMp=45t&F=J50Tw=F7=Dy7Q#Ni~jMC{R;R zo;K|*KPnaLyL6Z~#%QyQ2)A*qg1 z(UXbQ4$G_`ihP`Q6Z$QW32&6~cCpscdW}?6?r5qQziQ|4QH~W9)@}Q_hl=uj#A#!B z;pwz7dW?znYh#N(-k|cs;|1yU&06o(7r>h;zJ`V=Pz`ytO{%hdH9zspg1G=54{-_q zx&x5bAQcUF*ccW^XGKEJbKHyH9cqu^YD3d;W4UTu7rD@2!4(Cnp zPct`B@>K3Dr}gTp)P2qhR_zHcT#+OS&kv)qQ;tz-8t_$4&oP&n9^GfZvHSv$R%frr zlgrloLQ+`(iS1WpVZHfvl96QLM{+^D1&_aXj|}ajgrRdgu7xAc7X=2#KX*LsDzZ*3 zOeAJOtxb6{v|j7>z$+>G0UETPJ;{oc0zs=|Rt7(08UMwJjq~7r?V`ZKUqDF~Ivl$S zQ_TKF`JZ!EN6cA38{3CY5;1J@v#+GQ3zy_SPnM!mD3*=76#FcR0;|Z zolQYKIm%NiGdjv2OpkUvBOlmvgGZ+dr3xCD)qV} z{LI?hMFGnBk8Fpm-kS0RK}>1KtW{qKiiI67G4!W7TE=wEoD~FV1JY_+Rp&{2^yBk< z_J|(wi^F@d>;nZVDsMU>f;ru3aZ64QBwF(?p;4ne8<{xAEXEq;2!?Krz|zDs?5K=w z!?cq;&sQ`@Llj)o@bF}TtSGmDYT=Mrb)fK`D0P&CS!;LHrGUTh;gF(3tQA3+Qi8OE z5g~gyKkB$h6>F`)8{!{FuWBh!$@jpW!dzaP7Vm7b&f!iqT~F6gm>X%oBJ4I}ZMKFn zJ6??DtH+Z!KGzWu&Y7x}WUb4!R}}Wyt^{~sOYLxp8T31a6lJP+9@Wa}i$*}QTorkG z?cs^aLI+);cL+{xINC8wQh++dlj7Lq<4#D1rxs9e18R@D9b;$z*e#xIR_3ELhtKTS z;I?Wh1i%{SM*Qgm6lJs9CAhPG0+)jHqfxIYSyJ@nwtR&&DUqKe3-d77=H6Jet-`de z9gRDz+;EU5wNQRuDw{Ac%AdN6I>__W^{6A6-Ey=_%q32mjbusrTUlX=>JoV!{2{xn zO%9XdZxu-Mg?TLnVjGH?9G^*^kD9H3L!Bh}XmCIL%6s{yQXbb#<7Jsr9 zmbqHnSUywSzQU9Kg;f5)s7;46@h-YSw_r3r5g@p;mzI|7$jMpAf1a31e|p;cWhQo` zM!VH3hspdPBVhy0jzz~cJ@-eHgsz&8*RNRoz@gE%f<8qSesBnOB_eE3c*31hX;Nk@+&?3E5Rf2W0cj>>)VOVOYFhvcQh{s{2mf~1gPwM} z1JOvi;DMR&1SsqHl{AXd`Pt_X!6Q-*z4frkb^ZvOdmHVq`%*>Zng6NpE(u90XPlD%+sC-*`A&{C4kVPuSYjg_y!WvrrL}xmQ!yDTB*raUV_fAevK%fNIy)K~9D4DR-8LN4 z*>*1rP13@_L2qAbK}@m?iMQTX8pl6}H^PRTg)?V&;+QPQ6)fjxc*E9J4@u-uxSW3- zE_=ALG6pl|!)3AzT-McqGpUJjS~xi9?PCcB&(cVA#=^8htuU=ns}n5ZL0zPnj{1;QGIGND7V_K}xL2%I z>lscKdCmg3n8St>mbNT05*#w6jX5O2hRj~LN*+NT+a3pJXh@kkrbq*9g);^Qa5o$> zrM0wJw_4#KMuJ18^s1XAwD{TW$a9UM!n%2JaAs&RBo_VviJbwmaDbm|q#OcVT5@U! z^aLEB%n7&&tfLuZwTcVf1j1r=&Ly~Y0%;mDd~85|#RWh@zIcj3Dpwj3a;2fw7vhA` z(5Fy_eW-aE=K<6#5^X+=O4g7*e8so9!dG%$5sQS&wB8J7jH1u~!&w}QDzO3X zV>YQtMsSDKZg0cY2BqFbUr4}M2GSFJ%dy+5NrR~N=BS)2oaV}IX=5+;IBM4b@i$MZ z{{cx83s2L;<>L`Y^G%d>_xWS!7gPp}b&Cit=+OWDMemm@JdRX9i`$#5a5Vpt&8Ox) zid~;f4O!?m+BMtAtOvfLzF7PvB0(XeRq>r_={m2scdpq=S#y8a{_JmleE5h;Mk{KF z;DuXv|EJ37;M>^WwKSy20a3>G=vsf%SI$N1%?kNWnFXk)Rax(fT^0PLoQudjRItbW zgB=&8Opg}3;`vOA(x27}+%Q><9T%~}hJ{@#H0kUPybmB`Bx<2b| z%IATIQ}<~l>|PrUee$hMQwf5drrh#Wx*V<8SbEWjMe*4dJB~w#DVKc{7g_VPV84bw z-@>WI?wd(V@`ZPe$o)jmawG|i95eL~OJ%;`Sb~?A`VUYy?W%6yGtMLMsJK3M`?W6!w?Jb1gmpP+V zc52~FvbE-x0A!0%@hg(CDvrr>+!C+Zbua**Rs_CJ2mKm{B_Qa&SAP{7u z0g<)-l7WFaO&~EhJ5rv;Ea~kO%-*EUCscDqTlqK%dm1p~qx7G{(yntF)*( zJLd82#aTgeK09oiSKVXLrR;ogsQ_*Lji$}6sR*=jXO60|YXw5fD-X!)?Df6HeWycXNZzC33g`XEuFB z)^G&^XL|lKooQQubGJ8%6H6Edbc<3t9{QKp0lMj3nK4NdI)H8}V~IdzxB?K1OL?nh zTmiV`hyaSDMPg#24?GR>|L#($1pifnZ>4ARkt+bp-@3$v@0u$CrRzNH_I$$o{ibtR-m+VTf4w&8JL| z37H<63K`RWJ~Y*klDbr}VTnpbDQd+2@Y)30PM^%K%5v)>rTNESE^VZnN&FwU6{|Ju-RU_w*p{e1YBrs3*7ITT;>D^DP{b1>#?Q?pX{ zi1eWXwDU$T>iZiuJfBpx$wPC%Xt_|tJoQm$0sn}5mk7j;wmj79)Qd+~8&V^;6WTJd zrXk(vpPjzdM?MGimDWW)OLBHg)o(FZLH?qgKS4W_IcLyxo%9&r4eGNycIp`?>y`W|*B3VL%@D z+y>RKcLVeGz3}^PT#`pRjr)-m-5s7(>r^$b@HPE&0?`_<`-v={n@xGo!z4s|C)_ef0`7XQqw@0&~Xr2?oJIn z8HZYPZ>8IJ;&%-@*?#){N(rt+ngHvYG2nwxUL)n0)8$WNSlr zTY6AlGJ4v6>cqcj+lcV=N<0Y_smww@QABgg8Z0zjhn{6R2)QUCN&4rGm^V(@6GqNL z5xOw;BJp30;eGNg>4a4~cnmYX| z3ii9-Y94>fN#T4$c%xJLx})38f|m0y5+!yP=|90_@7?X+6gyRY=9rPlh?c8sU0eNoZqz9@*)mZ+=lZMt(k;a`l4fkD!}&cI4@-H66R#V?jv zXiA06cYE#=>^1Ehua_X_ad>xunq7l;S8-QZRo?fP_-439kDGg3RBiA?tVw~nF*7X7 z?c{5!oMlj&z;f-LBCAZTi#+w>c23`zp<&3s$oNVf`jPJz<0_iT1jnUFIF={B;)Pi} zL!#f^Bllj6zsDTY1GbTQpPlLKxSeZveSg=Lq6-ceq$K6tlo?j~=oG&vdtS9I?NOza zmr)-7aIn2ymUwc@IeJi?x0av(zgUk1(VTm=dAl1l_HvHqkLB&?8e*RgyyxfE#b=n) z<$_jtaJ&j8pSyM6+NAYwvi12}M!Te*3mpCFN~J&1kH$;HB?t~UH*peI4H}@kRC{6B z+x9QU+~2Zldh=R6*pp&6?Q>t3tS0&V9oyfVyePJ=HjSe8trh9tmT9xHS(ubeQ&Z5sxo3yvge7}-eU&pL)49Q8TXIB`9UCN>>O~r~GoRcF>uM){ zK<7#6OHr46nIAY>!Pr3Dg}xWnO{#D5JT%<5d9E5NH1AspX+1TVV)Yn~m6-;?M%tBM zwNJ`z8S73)?hd#8?_;Prcf~E!y+d+K$SRS9NVpr&Jl1WIpOTI8* z&10LSJDyQS(RGqDH#HwEwDr|z4P0!pIzJh)#h-X!Ug-bj&!g5xh6(heoFmnnc|M+b zZRC^wRG*RDvJP6$f+92Q^PX;xHHE`;jg=A?<;82RnRhAhMZKFGqIQ2Xp`A&aa+gAO z?>euNam_%n&9Th7O4OhjpPP31W~ywHYfh|CVuLMaS0+LrFz zJcROD_wY(GN{U`LG;c+b5M{FHm8UHV!|9{RsDheXMe$u34u$Rw=19m1EKzb&AG=s6 z)JS!&SS($WDT()S6NR z*u%WO?IJ%6QQ?~js{w#(5&(}}GypK?|M2IP8bKAM0KkhwjVv9E;38N))64fr#?)L$ z873!|%o7D4$oC^EJWt$IW<)4;;nzM*hc(lQ)tcW<3V^(1Q>wwch`@6qHhSAuZGdMd zA@Piu=(e?yLGrK^O^^*>W%%Z0F0ciZ(;Y7qG}KiB%5j9oUP2*Y-rHjrzKNybGm`C6 z#IH04qnWk^MF2;-W5wNr0~-L2yQ6qF3S9xKIcERsi{`On*XKJ1;r%uu$o=vEe{K zlf-jidIeZ>1?at?0228KPM@;@w)zN)DS2q-7tk@FR=bQu*$@~2(+|af+IzVGVjcqV zCK4dt6&V1zL=5_~KI2pIMPiDO5L7Alb4W#fy16aZ>bOG}%AwqRa=f5eY*QPb(;$7d zIX~ErA;ZbZByNbEFI>^N?>T>A-rPP)@zGTj*SetqxA?5PEF4W-F7_(rpEIfZ?Aobi zE7Gv=K(DNMs!r9Ri7n($nCz4m#2O9p(b1okSsAoE=e%EU)TEr)UMQJlZh8OD znk~J^reGMgq+1OoR&{IRviQ-F3-Krusf$vyo5eVvl~TNIyRuOYnjnUeHsb76&X!8x zIjndglN+hOI~m7NI8%x`vu)4l3kPTMq;otvQ)y4atUBb4WTt~PT7zg$f>NFerc+)( z*qJ~p+@oq*@m4Y{9Tk&ANHlMFkkIT;dNu6 z{k{9;-sszPZ+yJ4!}Pbj@V4vY`c>T|{{gkB=_VsH3{Fy}a8@P%`3bwXa8~v_JqI?6 z&BuOAab2R4DdI}e)psfFPdjmK^V(etPd-dZU>F=x>$Li7*UoOkS=n#6js4gk`AYZ?wP3AVC@4y+%fZG*D=l9~MBXt3-yzY2W^!+_8Eq1P{ zaqfDAu}%1nkXo@9W_2a=?Q##4EuDxOtF_jxd;Z-Ocf@aF4>zf2Zf+LJrg25=67`!& z9(yoPqXukNDXq7W-lZlQyC)b)N#OfQ-LtRZfb-0_`&nAvL4LtRUO@Zyyd1 zsd-86-R=D=x!`*<{aY^N3t)dc{DfRR)v;erJJC#D>FkBFwig;w38XGHLFDFH@cza$ z!dX*@`doYGMr7?KlUphS`_cX7SI)K&pCsS?!b!A9?^o^J^E~gs=19@p#^!Gf%UQLU zor!sOB`UZ3-f9&6jRv>vo|H@J1X4My%tz^Q0a^NlzcXkZ!?~Ydn5`&%1KT zNbhBKZHsNnQHwThKZTE~C|ed1kfLMHy0V=9y#@8o-nT;Z(Q``_R%0JZM7X^SGf-Z= zr>xr<-Ed39U>JzR>#pRaXMMC~=x!wU27l)~+IFwu!*JQ7VR{F1pGjS=*GOf{k6l9z z0jgSJ81%7;@vICh9yYdQnvDze)Pi7R5jIU+|-G5 z&d%;q!fQ-(+_VX;cmkEo>zdWS-+;bS*_yPhw%_==Ph87*R<*$mD_rdKxBM zqDvqOtk~>>UGH@fV^ofx`0jpUg7NfSIds9rm?0^GY?YLBbM3(( zW1nk0^@Z9`B`Wo8AG#BZyIgfr7;gJt*h?k&SUALYB&^me*v&ed_;U6l;TsJ+)=9V* z6KZ_1{BSXItfD}bA5<(v#qX}5UE!(Ch_qPap3=KHHYIeq?=GhBwxwaG74wG#w~>s~ z{^3d@X_q-Zp1X?;L!N!quCyrDCz(1KI#-XJ>-YwQX2JfZ^t5*z19y{MYI@>52t)=67{5#+DdqxF^WLtTkWQ>Dv~>NybyvX(bI@ z1$`-!J6;QS7W3V!oSHjgb*D=S^4-qjB^MIY@v~QulFDtF>3(^i4ztlC#?rf){V2UQ z#$f(^4>^50CC^b`=`_mG+{mxN*X1HZEX3(-n^;Kk{skDBY?mRW6EQEDN(tnwN)=Z@ zF7d3Zt{Lj=?rlxXTZOJ7@#p7O=ZOzEzci4XPbh5DoiF_WrMoZz%O7hYPFW)Y#xKnJvXP$R!v&-HeF5ms!HG|f$ zS$_!cc>Sj2@R&ZC;IlNHhArIo6hqJ7?bh)+SerC$RJ6cvKy28qqola!>H1U=)ybf# zS)wbw*xjY-<}qC%CvWS?c-gXL&gF&v2W2RHI`Oiyin8aHe5zyf_`F=MAnGS06Qe6- zcAV^lLA`bPonrU5`A~OP1!WGu(9tZ!`3anq=@*+g-W6%_5oc3Q789vmC7_b2b2b%( zZZyhAAMh;o$`^gKZ7FV5;iO6QeluzJ$x_)oPE$(|2q#)QP(e4TK2(V=qc!xP3k8mO z82a;Ju_2?XkjEu-jpcOI!U|;%Wo!D$#9pr=erge_H=NVJkuBX8Cg|N{pG}k;Zt9X~ zqxub0ZxIjz1Skt{vg8T(;jjkF=>$5}_^Czy(I1yh-0;!-+{`J@99_t5JfAM=tyGNk zr@E6TVKLTjHyzX?RbN$Jl0VfftlX7xD?ja%Py}!a?Lc^>Xfiax}=p)>D$;2jSn);Y_ zAxIqtRNJiwq_%hgs`r;V?n3KH1FAJ(Hk5u?1;AzFzm;?&;M4!0`jK=IS2NzWIjZ7y zFyOe})22O6rOkXgVK7AGK5QFds-q@ZUv(4kJ{_pI5$8|res7V|!uKxI9=a31OYL*> zI6!=YZK;w1c%;vrXUCB(>$YItyJ^RIcpd>Vo%8aosyhI=g9uBo8J6a=l9tB)cNWWvvFJ9;pQ6N;@M+ zwMCFAY6PU>NuKHS)jG-S&zZv#Sv3v+V{!mzXJ|^2OH~bk^Ip1NuTcpAIXj`LBhSbc zfK1=U_V0Kd1V9eW_oyacL_qH!LSHJIuHVF=y6dS-tXT-4-&VZEkSn+jDDQbfwG(^c z0Z5c~s(I7Ni2&p+F9jTn7a_p31l+1_F{(6*c12*FbBe%}D?wnaudKnTrXa9&Lk2;* zETFm&0lhwgV!LB7CU`tuCv-XufJk=)T(UIW$?sDT)OM}`5ZeN#A8kS)?)rv#=%aQg ztv*o0KuwS80w^6k4xnX!Gbs^3nvMd@&JP3#$Dshxu4o(OCvF9z#M3y`Z@qd>0LqXp zfYDva0NH#ZAh^jB0Db=3Nki*O%DN^ChV|uYEw;KZ6L5NiBZ4mF{mP@K&${GN5+(2` zDU#fN)K#j~L~OtV3yUuToqX5juzrgMK24p7Ng6e+5w%@>5uQ&z!L(IFb9(&Q1iI%w0$M-YBtw<( z@t<><{eVTD^S4#ZD-Lmz#tJCrnae0!sLf96GHDpC@wl1|5@Me&hhSwSyh}} zxLKE~DjuHFHe6&g>N?yv@TDtFaAXyK;J#CGgW`wWF8oC@AI;1Z$-5gk5~{ubxwB{E z08hwGB!s`4hcm%^)}5FL5qVCi?^EMqOr4RH>`UeA$lEU@Vm#MxTy6R}x9fvyzg&7J`DuKMy zdNN|{!O5on`idM9puXWWdYUvfrH;U?u*+|wvxl-eLr+W z+&1H@bdPUsV;nv?O(rzNOQJ*aRFL8T}qc2rG%%R`Grdj4;^_?9SMp!z=#p;@ELRSgxre_@|XZcz0Wlr-1of|Y>O z;q24Sx4P+_;jE$BogciJSCx(*=3Upqrpy|Ov+|ieN*&{;igh=Wj&5R$#*S>Y#YkJ! znw9axP{Uh|=M(Yj`GX_u=txgb=>hEO@2$NY?x~Plo!^5g3%Kcqsqs}}A20S)i@1GJ z%C0IiZOoOap_Eu()}C!^cyadR_RsTP-T}GAwB(6pHWUv!k?*c$A}O$`KFQhBUEotY zIe*=APfvDWqU%s^P@ZU8^z0Yg^=}j#&9rdVxJl)0uU#QAT2rJPYh3FhCYMxSp~^%( zD%@*#qTG6LZcByK(}lAe?Hlb$ylKi1WX%m=Oo!h`Np_;oy71f_PaQiDQfs5y7vfIl zIQbRlWLO?S5r3Zjx|p?Wn0@K*nP?H1fv&e~v;C?0Xl^0z1!s9)=aAXe=2)=ba{ER; zvoFocr9ioDFRI9q`72|CxYa3FL4-?%YePf*{AQujki^w*)OXe;*IOca=6vZk)!-uL zah`t6s0!_L;ls>feqDLmy-he-rB0KJUU-t0cxBt2#DDJX*)Kq)o4(xLxdiWu0ujeW zPY$(&k&b?^#xpylAtbA2x z>EclYY6TESL`Pb)b~CjN#H9J_9jJjmb17JC1j|EQNhHTgk4LxLwQR^hi+|dQi|gA| zB>k6v0^VoO`7M&1|L!9v?MwY=kr7|zaxqR_sX>9w5;HxNcU}FUuF6)NQX1`&ce6rG z1K#6>U_W{drtsto($)?Sf`Z;;*X3;ie8W}dzYMo5F*lZepyk~@Jh=86iqX)?Co$fd zS3aUXKh57C>8(>3mxcIRAj~Y_Ff!{e!lwE}kv={@27M))2fLDxv+H<`?wP&f!?zlaJ@y zVQKBgK$m5@SsRz1*s#x*q~~8Li^Y;Zzo}~l51!~(Jt&}0B8!EIu|DEB`li|K?O!bz7*SLl=!(N#oag7`>bNA4rcbCzA%7Chl+97$Qnu=rrhcVW$^pNh z%x;Plc0D-sY_}R1u^I@OTof{?hV%k1=Mr-3Oz&6*ut-`i(oI06X2w!$^cV-Ov*8&U z9{f^Wm3<-YSkhwTUT@d*$3UEfN1Agxc=r8QbJ_%7uC!kwCdP8=kg z^uCBs<%YLQ*1i^~g`Y`}8|lgd?@M#44#l?-JQrJyN;9(V|1kjU`twjb(K#?ae1^d5 zF>?#q{wJ&Qmc4Ui!tnc?P%D^s)nNerL#hnkUV>Aqt3=>64ZvvT^n0Yu3>5zuB(^{; z*Qkwy4^)*lu72e4Yv@Q@BL)+3;;hv5(K7}bITAXS4#(I-2CRsU zCMX!Ljb}h8tpadw9Mx=Lm49UeJaP#kpX%QV*Ha9T zt|AS&Aq@$C4(@i5eUlx^wD?dC%erwb3LJ`clsU2~Ev%4Za6`JN_3M8pmbC05RJ!VG z2D&M{JNJ>Vf6@;kx&85Hsr|Ug!xx;DF@q^<|Cr3NSmHe5_FN!4R9XuQ12JMi$qR}#CrO`1(A{eQH`%rqdh zWav1=%0L0MPrVPzeFmP&Ao~#GdIiR$DNEZsVXRV10#9$PSC{-r<56TxrXxwt_{NF4 z5q$+(>;g&V=j2-=r#Vf;$i=!$Glc(8m+g-dgRwl^d(K3iBsWfejcP^}`l!k?Yreh( zZWm6Voc2nzWS>5CMf?T&W;nW__jGumFWkRZqKVcak2y&Exn~NEULTYvBZkTgIvrI@ zPLmwlnA?FSx>P-8TzRW=MU45@A}y4;y7Q>_;wf~{FR8A7@Bn^P?op==vh1kIkLCX9 z^{}ela3ZWP0Pz&39=fKRFO6dj_uh0vW}eRXVaUsZLCq>kW(mCAeOBRcaf_&HrABde zoFn=ytjET);Gr4HNi=fbjBjiH;|1}zNgrM(3b+{X4ZX?uf9$;pSX0;5K7KNg7)U?^ zN{~@a1Oy={3WmX;R0&}c2dEkeU{w@RXh0m$L=cK1Vi;AxsEiI6lsW{#ARd%xS>@ArS6?|EVj8P2%(+H1Y*UGJ*?De4BiLOi!d#+}3J z|H|zA2t+O452!Rx(JRVH+UyB2gf3&MfFeq0d#3;Dqy3tgz@{G#+->}@n;X1cCv=c; zYh+eXlg!!Rk9J<~Of~R7tj0JzVTNCLxY)Xd15M2nE|Ko$Im8^v}mjzja3JG&#K{CqB0D#(BQ@me;rPMk!SJW_}4 z)`y{h!g(Ht2?Vx2eA~d30e3B>xJf0RK>LW?Xra@$-4MLQ3hYp<9YT(+78cAWQ2Rds zp@lJri@ti)>5)0Synppbg)v#7a@lA5@;q$Kv*XSltS(+)tGpsgZB{>*djH+2JyLmpO~$B3en_BEAvOf?)&ylq$V5w862Xe!9WLl+mw-OTmm921fp z9Xf#0`z{-TT~2ED!32mf&wVj$g+r+`Z+)`DZBo+g?)pk~Faeyz+6ECp&+9b7giyFz zxp5IO6=Lo2^Kj8-B=ZZgl{qiEs(6o4On>TR!!XHrGoOP-uS9snpmfbkv?8j z13gBS$;48p|0{_q%9>ALu z==UY4(1d+1ZK?wtib3#*HzSVDUquhfl6vp)s4#9 z?N1-8C5)9W8aDk;^-ko@{q^IYEj06&r7{k%!e`7|cF*_XZ{~$c{Eo!zss7*y5kW=d zn31Ce2MZo@^~cjHffMgyNR4lC+xnovx|cpW3~{fy{(6HO*&B>WoM$5qeGmUO&7LbZmR8w_Pg`#0#UPjQjV`rkH{Qh+X?Y zv6^&Dk6z;HcqLjEc`5n8rA|)s6rC&&*XWt*J#(+I^Qi)^y>|F_r-JA1%y_;fF~AYS4zTw1dE{d^ys-ECzxG8#ak4Q%nj+cr)UYbnmNiK9eNf#=FdL=au8qV z0;G|voMS+g0*5Ccls9()Ufcx`ty6_+N4aQVe9Q?=sz7K}E)`7yK}$TrvH;Rbq23F# zc;d}#R~o)Pizd^%WW-B0J_y_*g*y0-M2Edrig|QvI7As-aD=D@rsVvY-HO>E#+;P8 z-?S{%SW)K8JT3fHk&$)A@WVBL9u91$xU9Y2`(5uqWsP zvB~v*aORxt7lD&Z6%Lly!nWP=)cNs1c!=HEjR#8HQ@Zl`@7qCWUgbTHJ*J+&a20UU zz>-4+@w+0B0!us`N5K{uj?qEPRdGE@$UfGHtTaC%-kS1L+hkunE+iXxnCK_q+HCzBqWoA8N+-*#U+LEiIpe76pLu8SN+c$-!aq50 z7~x%We`ywVuvA}cWZHzc<1+u`^9Qnr8{@#p*)qD{wI@F|e-dpb1rFJO)w0Y_hhXH3(>5GMX^1s*-;$$a$?%kSM|ihZh++VCICl* zc@ULV0%n(=4}1e8>Gztz9hkhZ(GxXv%d+U`-kg}Uarsc6Ii* z(M+(l?T82AKbU-$CtZ8sn*+y@mekzVPjTciAmKe#6UZl<1gi`qRUwON7+@;FqVG{o zTU%b8}QmG%(l;ie$J)l)PyeAQ>=zwKrfSGGb#mGy*ldq_|0yO!nR# z8i&^(2RB66c8fLu!UkmFESaj(o^s{WGOsmz$PRlA^gN)E_{Wvm5cirn3qb_*0c2@@ z&e5jj&G~{yr?jES@gS2MwtfI(lDDpz0A9j5hfi-SzLlNS(|Vc?Lej>iQp_U=Qm!-cWCSOG|NBFP%@y^fpa&?;!Ke5iBwvi|WT05vbmL7XNXE<* z1X*61qF>%I?6@7A1N4%nVJbDei4I0sOqL6Mz_>x}OO6{HrXh=gAkzon6pAhZ|d9)XUDNxsQvfaM+8DK$20F1%tPy#{oyr#}WVl8O(6 zF6qC_pc^Xs<@o8WJ$0YOzOvoGRdUM=G{*o4vBK{J%ak*6Hpa(bK{)s^ivt|7rU{2) z%dF~FNAHeAH3*ptEP2{f4p7_FsA3V92kAFycsy9FaZ}^uiuLOFCGXUtJYAosb#4ZQ zh3Wc+xzP@0=q_qJ*ZbCr`>Y*LnRja9sVSoLzhg?|0^Ld25z})e&!0q7%!TGDIn<&@ zpJf{rL*88mM>3z~E!SWx2WAp9d5K?2v1D0?gRtfH5+nnuM<#=K27Nt7_z_8+v5YRi z0vQadP@2WhDQ8(^{zDlS%j%o!%SB_a?RV}9=dUa|Wys%UgmO9*r@*3_krP#7$6mvg zize-n&^1sk_IjFGY|vt4A{-_q%dGeS5I+fg?n8|%bM;TwZTv%jiwb*`%t@@}rrHU4 zcP4iDnD=C=U=m5zXz2A0pcU;S+H0E(XPvVqf4{II+=M1h!M5zqtu^bg5vX zinx3cI6%G5in9l!ihVp3+N4NuG*<${+`zL1t#D>pgyH=rcUKozfT8TCfCV<(2cGyb zkTDy*^avB4TFj#9)T|7Ne98+s_b)O_yXdvK_doapsVkLT8STS9-hao714z5sFl0eRp3>0Qz1TxCoXQN^z zCkVE}f~q5a2dTWaf}Sx(l{KGhGQtx`Tm%sIj{q))v z%HaVf@+I?t8$0I_+VKm^Zbe)!0tFfCd4yu+R3DNi`OU+eSzX@`=H8?-(JAc;`HVrYGkG>a)Mk6B#5M=?fd(1m6~5 z$}Ka-%%ne8ByRoXkdYdXD>J67Q0oNjv@#7lAt6F z!_ZJm{eiX@c(#PUx}CuZnxc_7XTHJlnP&?jSJthn>sPb^X6C;txdVNi-O5y}S?UZZ z5bVDrYp1pvmbV5GD-G@$Ce47C#I=oo;BdGN3Tm6i^^^U!jzFuo32~ik$Wx=XeVO>w z0BptoF7avdmb`#1_s|S6w>A0HzDrjimUTVF@z}7#;m5O<%v96lugkPT>gv>}EC;#gDf*BsSVS z8!hjK&GHN%6^P+R$h&^q76oFlLX&Y#s;-0Ei)p}@@Un4d?t(WZ_4cW6jyD-Q8_9g* zq|mXM1PJBkI0J>@nyCSt$g8qcU(}?EgUMB}kHTU?`Ea~ELBFX-v7I^?o_$nujk7xv zlN0Sbb|yl;QaUXwmypm+ekLQ}Qq!q?AQum0)>*LMe6$&43)O*jrdjkJPM?E0doUuf z38oP!+rfR`1+q|ezsdNq7KEiwguMk*Z(5iy_&Jsy9@C;&{uDVg@bLw80~)t zg?$2uUyoT)ymw1M*d3aa8Du={ZFB_Aw>6tMMt;Y4O8)O7bodxYPK(%bdL8%@H!<@Q zz)V&3w>{}4#0ls7ni+uQ(;+BOtVN~fV%yZ!8IxIvwl}*|SQ><2aqHaFZka}YLJmzf zzKS5kNSWTi4IN=&rGzDd==}Ykg)BLPDlPON&A6!$| zH^OM}EaoyePbp;WdJ+tvjrxV&|LZxH@?Y9=qi3v;C#%Y1ie|bq)XIz+>x@QFVTae- zk~HM{lLq{`M%IF&{d>zhGNZl(XJzq((osxFP9C{iQ>sq|w^mvtf{8F&n~VkezSd%p zKbVbV?_rDzC)E&-qt(yGs^g>_2gI}jrX8Loux>gO2LWEzcp4gT8vHyXs3ImZ{WXwH zeX<}R0mE;Cw5IwSL8fsxm>^{F-vRJ2%9g+qU4(hbtTU{^1eriuJ%FQmZIl^-*#i+7 zY_TWAOWJ_OZAO6U#Tp5GCLnPNL@U%l&RhwiJsQtzPxl6GBb1#$LC7M2DMz`FXL>&~ z3h%SHy&b07!9*=Ev(w5pohp7vCOaP(#k({$sr7F2UX+=8<5{B5g04?!!xzal=`V?$ zoK3&zG)SaAZxcPv!Bg?KINCo&5*Px2N~sbUKYH%Yq9OAEL*zd--B-R7Y`Vqfn?U!@ zpEfzBdeG8%a39f6o0z5V-RP^bOGcZ+|Cf-n##p?C5iwqprI~2oEgk zKN+~Z885rVX}}))UB>o{_#WJ3^~2J?0nh+^Km_CKzYLmdO#aprf>0bl2C9H#E>7gQ zhyJ|>AMCY$VU$@fg&?0P4VU$N3d4-tLGD99UPK4HAjV42J>=k=d_DvfeF@XZ&e2iw zfT#)v9sJ)PvKs2X7@RPX(Ios2D0DzLE8dHXu5Qvyg7Ol}%)~}n6Aq6+;3#O)09txM zTgLFRRS`s)cm$N0;Qx#{T2G&9R_7RP>;{q{-*n7i0+a`F&w9d%i*EKAZJOK-;8S4R z)!T~AtxI7#p&H8`o&6OJO$$?;i{jaHkRT}T{-(O4Ypp0l*Wkv=or%cIF?PqEVjG2$5@CImYlM&js#yp!;+&aiZ!F&p-u6^xR9Y@KO&venjT)Yxa5w5Q z3$SQDsZN%9dvkxO)}^gKgJ;K_3}=qFy?a=~+ojA^e1T10_sGXmdy+BG0%f+Q8M zdP)P-UIb1tr5t<xMQ!&@Cr#l14RB-|0cLo|A0VlDgx!vI0zmq6Xkon-vP~p<0pYz>Y z3wI>1{O)K1Bpco(_)Ph5(dx0AH_z1%oh1TQC1lt*p(S6NwMsjF2M;Q5?8r|QFT5oS z|AzV{&~d7~4`JQ{o+dTZ3nD&;%QD~=T(%-eM+#`^fCAvns)C@}FS^|wGyc%)c2Fz) zoET^!_=lFz&}6-$E81mI66R`5HxB#s9H!83gpA?99#1rS<|@}H(2zru_VD@E*8L)z zFQIz?)J+03@l}TeRx7<7`*=S->|8T3svY1KW091~!%oVHgYC@6Uo`=;KNvrFhFhp| z4V4mpvxd@M>Qq#%kN>RJzy~nT-;~!Id(c3`DO2(-8k|KZ|H37!9aA^{lVcjQ~t^fxpiph#V0 zD2PlXdB#{sXB#mIz`&?Jb|JNu53LQes0Nf&B>opjD%lr6cs4mAS!&wu?KRnFc;8?n zM{9m}MOK1-@BkWMls~r&7kZp6-PimZr-If7CKOzEqu7pdYMV3<&K@fs&R2pyb2`dJ z_)T#5fP6d&G?bs48g?;wro>mM+{MT*k$tTm-Yhk>0`3g&AEyWVqUz;O%Ho_)8B|a#hV0~% zYZ3499ifYyHCFRJjbQ}G0N^YXC1oH3gPaizh5wt2;9oD(0p#lYo8o zcd{%n-aq#d08-K*R*P1jsmVAquyMsh4?iB1NWlv(FkRH50wIe7*8rp)VuXUWcK#XO zG(dlusp?$r?7kNip$_^AuxJJmDO%tWv>bo-jT1kY>WxI^ZeXrXBEX%e+;|s z$b(lged+L|Ws7eEOF8@rs5#Kt^O-eM91OiRVJlqSHS!o`FsSs_xDBvLfDM@GJ zK+e+!DSfGzHV+d)&+d|JxZm~U`QZV{>!G}|)x%^^o9^=sJAZIk2>wI%fjIXH;sYL4 zz2USTUcX4ZSua8YAE@z{zWi@S0)Lr)1BU`zl+~!en+hYd7dhzPWHOLT_208DA7v$v zkB($&bI9HVQ|$2NRn$8T-#kB#y&j7&{1#S+Rs#UpCP^EjXr=2ffY!uP9{*8`Z@6wsy?X;C{VDY+>L zL?GPFD*!vl$Up^d0}D5eglpJFLl{DZWn}~&?1aL6sB*Z(6WJb8>;@MnAOixp0kFlp zWKl)f0>}Lzc=ViXEU18c+FIm*?*Kawa{?b_tyUfl{4>OkA?&27a3k14@D{vT_DdaX z^Xk;f@?VXRb2!LXMs9C@a9DK?&^Vg9hF!O@|tO~*qxS9v9(pBM|^LZLS?+Z1vprq~g=B~hJsRP@xg^Y#M zG(jU2{%dx0<&@&r-h+!`7&~3YJVhOoajT5CI$+Sn^DzN|ot`XmtryBZPK!=A2fWDt zyhad(JzR7!U)<^iE~@2OuPO+q=LwS(5OiyBfanGJUw;9dQn1vnrk0n@*McaabH7YU zAp9XCA*KBDVsYn~FH)IMimUh^)G}3hCxnJ}skY5B+bW5*;4?VhU*`#i6N}rDpZD|4 zJy5~s^l1Lv9LF*jdVKYQKV$Xfaov_^Fo;<*L51J3y48OavVgH2n+~%xoO_JI=Y@!IWUX!@u(o0$`+ zuZ&8yXit1qKSIWCe+DxK%yT|Q)h2H>5TaVXhO|^*98$LZ^mn}S2FEMC9Kxq9kFFU z54#2P)t(DPZ6~0(1t|R~h2h2vFrmw|Wplnz4 z{!J;PHSj(ARJC>X50#9#%eMm=hkG=n25jqCJgAIST=JxPP`EG;aFDhdB%^-L1hpSX zt^k?G0MVa<0@E1Gd0KDUwzAbJrPamlrxgCWACegWN>N}tNJ2okZM?H$o5@RIlWM)Y zz2r+ZVr-~*t1>|f8w(+e_4v57>D7$3ey}OTytsZ{0~sf^#^O}6{*HowKc}gu;Cg=s zHTp8GQDD_#WHLr57aL`&*y)Rn;X+Fu3m?Wliw*>Zfq)0Xb+QE^8Ajc{Z;`X(?HrQX?6KnC*>CGL!+nZq&BLYP^u#FOlv*6y}0Z;xV>h4ONDN zQAX|!&2RxY$8=y6@{_mg(&hcUJFm5^iVl5f{pAyh9Lx@@8=sz#J3We?f##Q~-2e0h zpE&UQzMMb)$2cbcq5@_cG5KbHh6b?}lu9X=Hh8eV)S+l7P&&(m^Y^*{{{~)PRx5CD zBwR&G*c516avcByk=uH>2;c}UK5W{S6?$ZKLJQuTg`$+ztxU8}PB2f-cw+G=w79sB^bOlsXUF>tK5(u1t0P$iX!SaQ$OPcXwtQMBVYZ~hTYWtcr4+6Rpkd;H#HfidS z{eJ%ajGC<6!k5Tqys$sadi|!J|KOy5DCgxnfScI4(^2r_fL}=7jU}g96jDRq{9!GO z{?k6={kcYT!cL7^_RG2!%KxcLvwuiSf0nBQjQx1>VVTbNF-g#nXeUQ z|DCQ9FD?%^U!nb8ffyg0_B+HF9wWQz+(-ukE#@v<;eZ{nh+zJe6s2>foEFk@c@nuk z7+{Hx!`oo)1np%WZUl!&&8{?Oj;++xxqFYyfg&*as3k)| zCr-5`=REN|b-&Xn=R$bYoY=wj#dox&>zC1*rt_9UDU#}Y%yqX@$$xecjSX{8Fz>b)wUTH!g-9n#pyI-KL|r8T`R zi`4*~b#S>g@dGFcr@ZRujJM$1p%VEg@fegjG->y=)2r$)HG`JNZ@teI|D%EM(aTBW=hwjcFM9Rug9n^Yq@oFng# ziaWrE5ych8`m_VycN@h-{I*KL>*gx^)pGN1yD*ev0=n(Eht-bC8xjT3%qJXs(l9}{ z?-yLB{bhk9F)N>O^laPAGMDN+|m1B|I6w%$VZ>3NXRSXV*gM0NPihU|B#y3Kdh$l zJG5c=W+Qi3ku({((VxBe#~_AWz8m24t(+x`f7w5aIF=|kn?`(b7r!40Z2M;AzLIX9 zGjPTeq0nDPVtb(?BcMpGD+xhB7>O_lA5St|I_4(j<52xNMu3YE)t;RWilf$g`pXvC zk5L`AG^tI5*|;u}1*~y)FHDibv&;}1gq5FjeNVLlhGu?{TWFm@xyvD`y1U>)7s==A zJ^J}FR9E}&O1JRXB@5=5rED{!Zm$3Mu9pmpV!HariPKSay@_~Mpm)aQmdVcfLl?p77 z_HqKI*5^LUFDI74IPS91G?9V1uR-!z$X>W;f$L@0yHiosBA>6k45BZxaNiVf$#1OF zzP*xIaS{{0^q;phsX@4c>8)=sF6tsaTY{nt7U)$uUir3T;<9tJ;&6jMF*J;b%+B{a zfVGMLgkQlroG`uy#yPwMDHw#n&`ccU&b-(NtW6Ly1OCs@{8hDq|34U-ejVe~oJ#;C z1cjt6I5?Xaqd*H?y+)FV2s2MnXrA1K$gX(8rMnyi%>!T|oX!5y3>HVOmoSzy_Rd&Z zvn-yj?tqp|^BIT; zw4i^(7BJ@ETmX4me;mL8{k&%8i{+q}RYl40F%y%6N%tpmVDa6PN_LNn_P!7BbT;@I z&QztGcHvc=l*SYov!|RDQGQ66&)uQD^*)9l`L^b#D4X$w$ntiddOax!qLjYcu(?rq zX6?>R$KaHvTGdChF6!9>o25~!g|5q})GOjy)f>R?fMQJDnx~Z7Yem!8Z}MgSK}i<9 zK1@OJ+Ml9|U+huZ7^)!h>eHyzslCsUAP012*_4L6)DxJ29q8B4$Av6P=$_VkY^rI0 z#`4u_SC$^AQ2yMr0QCqiCq_h(a2Xl=2lzW z$*8N`YxT>7;UB|W`MpOOb=g*;(o)IyTyZK;Y*nYu&uzjEsM{Pd37g81+Cq4O1 z_F=@h8~_f&@lVNz--v`N@EOZIj9t{u$nG1kr9qD7H+2#JCOq@km8L;ml#f!sBzf42 zfgP|F*?Op5hHz^yrsh+J~};9KoSuoVEq`m0xn$IZOr*9TmLH?N7X)N*dXJoXQm zl@Z0a(c5}o4^NVut9zrSPB?`Abv$p3?u4l7M}}iSUA6~O4IkNpHyHTDLtax+B{wzs2WoinvBXTDqOX>iW3A30|atI5PKNr+gyinFq_Dl?sWf%96n*8 z>-*KexkZ2UXVR0!7scCdS;Q?O?*>+l1FCbr>7q*Xom~lV$vpy`FaW0-ehD7^4ngyP zN2#MA7B~n&z5!F5nY}QFA2|WgwE^o(QTaGJ4+1p&L1mvjabW@K)=F@8i1ISBEhQTa z*)*Km|IkG(Qji(I?IC~~`1qF1L4ZF!OcqcO5JyE=LXf@yzy9B4HM10?W(RP~`|so) zeX#|Ieuuz{`Y;@KT2=0J#sU`L&2j-*CmNzDQcnmJ15pv?P^W7Bc4fKLpHwzT^jCwE z{KP`^_@u1=dm-3QU;f7ejQ;&|0o5X-uUuFUmuJFbT+R&h<*@9(%N8P}zK__F;<$R* z+o|^79o>8NnsW4*4FLU$BRuD9zLiSzj<}TLTkcQ1)Gl|t*yyR*JkGdVY;oe1uQpsX zHg3*d#-Y1p_;&!}8r*o7JX{b4WOsCB*6)_W@7O*$R|~jm`w@DZu^WKN0k_;iso8D+ z-4VnGNK?n`ALuj6hY7nt1?Z+UDg?;hIvz3x_}Pe(MKxdFO({6XEK>;1A#YW9Tu*%% z70m^rC}l1{U+zS1Aj#%WXXJ{B&eD4P{Uk+C{=EmTip*%w+c z9IatV{w&WfP=W#%ZOjHr9B_(7SuUaYtR9=>h=}e)d{nEM2le3IIq$X-eCZK#?HG>kpp^%we;LHO*a@5Cjj>;H zAcJZl{x7gOXRM>aCM9aVr%O1J+x@j52%W_;2AVR1U(5KRX4Vy^YgrJsLzu=(L+tGM z1gj-QtX)l^u;d(A?IWUBgZiFuXQ69n{BRXebL2QghZ`XcyR26j3#1UGJ(O?ePA~-{ zN!SQ71RE4c2%woM^;m&#+J8QWkLI!13^pvWMOD2)Iq5^a+HDK_Abp;bhwPlrfnQ62 zIwIJqlHnY3Weg(IhXAyFi%F3&YtFVZ!tAfY* zk*rXSgViScY^CG#0MZ100xl=@dqvC#q&5{&foB!Bl8ItabF*lOY^_QlajBWm@0Fe> zTzm3Q?GSPVJtXAja6^M6GfF_=O5sOw>o&MjtIzU$i7q%?xJd@g{)T-oa3i~<6Ya+-^U@%eA@li zuA2?U;xL09#+I|=&NK@2VXZ@jj%@7lKRA#7@G_+T+n3?p=$Z6C9N2~Jpz{V*xEwge z)3*(4*(s&_|CYC5vPc>)3A3bJdCfcGjh4}?yf4!}`XkcITeTlNBmuJy-*|ZZC>g)u zEel~HvVvqWso>Mi|Lm+mb>P1{ozcay(^79)4ygmCwnYvAS!(No!R{3W3kn{OgT{)p zXgkfVOibp(7=Pcl)N>BUm%?)FJs02c{FoobR9KB_)B0HW8ChnWj)|TD=SIjN@ zowDE@A>NLf>E3`C{;#d|=%0VQ*#>z{GKLEr(#k+aYZbE2!M$;YxxxSSw~;t6feR}( z!vOYs0m|w0OacMO#{e&tHMKxF>k<_Mz(oZGnpuEAY2x*3!1Az+yfVfl$0Skc5bryZ z&k~e#o~b_n)mvYJT>atc#l-oTTuHJjeaQZ6UeXMLFX{v;a63xke$UQVl6vXK2AjM~ z-D7A@i8E*7H|sZzxyI1C@_E4a;zHCVetNf#{(fGDgxjRKY{7@Kbs&u~0QHGn=NpmB*}ftM@BJKt+8(4LMbOgim`bhA+* z@Dt-L$rvcig%(+@O~#7RiI=EbFkA5{xWQ~xPv}tJGLTG837?yCCG)78NAW__ep|WQ zW_7tOmc5GEG1bAcp-Iw1<=4gwigym~j*e`PvRS5EH;HkBvC}fkDWM8f~ToFGJOtxjhyiUp`>3`mKBaSd}QyM%4TE(ubNE&2%Y!*^Gb}!Fu7r zy}dWv4%YJ_F?}#{sHS(P3M$DXsZ-;uQ2_t??DXPy(kPXLZEjj8-lMALON;p?=$R^S z-m;r&q_Z{Y6M;Vy{Wut{~ffmu=2*mIAn3>Pu+~-;d0l2$!_tsmVsOFwF~k+S_Zq z=$&Km;ub%b@T1QXW+w@+GQ>DuH-_Egw`M#BYQYAhLR~B61rv<*C+we9U(CdDolffq z9(I{1*+$VhXyzoh9ImYiT+l;W1 zOBg-TrYZMOp--G}vYdnW7z<49q{_P(-vpZ&_cJ$-m#E&8wR$j76(*>k&g`+;nHsNg zNiAcsp}AA5SNszfuA|`BU1vqw14ek`Lb-3JL_H~CUL~qsSI5pEq65l14lJRmU zku>Y{%A+oJgbv-0H4M&cXq6x=aUPav>Q{K#oJg@qBelMK$4d{I9y-Vjb`^$BKWx3V z&S54*JCEw`{ZSw7`kt0>Ns@M29c6UeHtVWnN1V=bCTgxBkY&uiHZ|kN zYU$W!PvVl`nYjL&<385E4JjJrxYvyh6-ZY)7xF_6#n2>7&6480BW+2(6z#qVP-mDc zQKy2RUIsak+AJ5pb)_)$zi#9hn{$Zqq0>V@SOlF?F`7Y_`VO*|V|SHlzoD@r@Q31= zkoix$60ca3x98mmumW-;TfJ23Lyp(@PGss^<{js%S4qcosh|XwT6B_`ICGW1gO{u_ zHW~__TL^{h4)-^~LG#ggw=uKCE%_S^Ee_nL$y1Ya8m~$mMp-@9oiP2yU zK+DIh8}o6o@Ih1OPtcZNgJhz*XfWQnSGHJ(W9Yt3YQwazx}hcKGY+`ox1inm9OHer z7MI>Y6*Y~U-pqHXPaMj~)#P6_bok12_llSvtB64_yXdzoaw~UST&a?Ow{DzCl5Rc5 z`P~|ET+@u8^7IZ>4kL~!<+&0fe`LM)bpbAl+W#7~R6TYQ zL-0+)$nH&-+RlJ(n^4+*ZrrK@3=nDG3j?W}y1INO5yiJlm2{oRec$McD&EoE-u7W> z&X8y(29@SZ7)m)7gOg81l?qyzJJeBp==@1(u=lH(P)HtE!p{npTNaRRo{@FW+V{Fa zOP3U&Z=7GV(mPBqk}fE7d)t(1)(J5%3F!7KJN)wu3-9DfH%>IIv!d&eERxbh@jlF$ zX5%^w=NWC!r;3W4$7;-RZ-m}VZ<8+L^4AtdkG++jdpPdKN^ea3W_KBRD7V>pX4bY9 ze1@-MX8I3nQ^P1x2Dfc(pz{_8gl!fA;!r!~8^}gH})N};} za>?Iuc}3+(2W9?ZUgzWpsdRRfe{pv1lf}JRZ!L%xdyIqDMYhk{X}t7}dz_AL(W~4LAB5gH*>9aNE@HOY0P40RHnIRu;8yI`?6$V{ zlj=VFVFKD-(w z>2>MsCh$v&qeQM5i{iLZR*63BV7cuJ(#>dw`Hn#C1}zNK>WP6E(iX4jxJtDG^gA43 zRYwLr_ZQUM#;7>|W=MlOYhx%o;rJq1H2VX^+~8CnI|2I&Uq!DAM}dxe&bNZ{WOq-z zeWh9T!Hy^`yRR9))^vG!GO91#=!uW;8Xu^ZKV$h1uF$96R*`Yc3U*7>w4;rg-p%#7 z+>LKd)TFO<_zaz5S;*OYByPuq%UGO_Oy9{YmWf`$f5=>x5x&E@^v33gySEqDbuM>9 zvzD)mkac7GA&;Y;l*={bx>?x7G)>T4^*r4>;3 znl>XMEr6+k@eM{>^S(ILKwHeho2}VJ-a$#Eeb3fX zZ4%}f%)`*>I;)AiBPDgn6mJtut9nsKfz%jhdmCf%blt)X3z7VKo7@Q3?v$l@yy|Hb zMCSX}S>;(bp4i8q`BC<3UJ6utT|~+Y3ZUdZT_0^q_G+uULWJ76m5Cao6eW@Ay;r<5J@@v<&&nN_)|g~ovn#wQ!%KI zbIe)~?y-u_k;F|?NgP~V8BEkA?+&$?Tb*Og*{)hH^$mEqvdSa_Ey(npK}B8SyIXUa zTbxQaoz&0&N%MMvOZQW%ZWMuNSAc3U$6 z)n;a)*qa}}cCC)$%+()=9W=<%aJ@T?U6fWWd|>fn?9iKf$K*SO-*=4JP){w1n8mXx zm88UChe(*8R`$v=)_P%V+v}S{zEfFGVTL4k?(|PLy62xCu)Ik9c8BH_Z=96Y09`8Hd?q+GpFo?0asnW_oEAI zFz5iUJZ>fGHfXD1^@#Z5QEu}^AC-!e#!*m*aotDB`4a?8$T68=?deLZ$O)A}QM7ud z^v0UGD)}2S)FpKFKFoXanb~PS^W_qmhsVr#L7h1i$A*rE#vWnaN1?NH_15b+%k*g$ z{3&|90}txHJv9LFK0+_tYkYh)oF14t?KJJPr&X^+`Ndr1Ko;s@&L0ZakS6Hw%zYiS zc@;#GtZ;{HJu74xq`39i>%?&t8z}sDtGPSEBYY#53t??N_q# zv2I*i;!0Qx72Gb>c%W9ML zSfOLKB{kmcx#XfB+s-L-Fc`Iuw&kN%&`A$^eGXkZR*hwgeLD3J!*&cxpDJuSGrLX$ ziX?%BNn_U_u2LRlE_W(6>1feE7A*_On4SLC-1IJ{^Q~tA-AHwC`Fb6z)Hu{utiEuF zxU*%)cAehJ;~iq6-7iN_-FC!w{m1Fy}HeDt#w7i z-%>=!Y=rE!C2>q)sHONRzt_jB>dkb>-^S@V9fL0r$Nhw+t;1e@Bf<0@YS|>R7~FpH z#tu+7C@K5uUKo_Bb`u>Ea!3#@=_RbgZmDNpAqS>{Hp)3!FH#R121i_D~o^bAH;R=iv(bKbgeC}EN`k&^%pmgd!uSVpg^#g zA)&8r1C0C$(f)fHP`g+>qU&X5O4YMBa*KKrI%A#9eKcbbTc2@554uJnO)@6uNcrRM zN@@2PIj1|&?3<^s?WXIJMHjl+Wz!+@H9mC)fnVf(NzF;5-c+mlbjmw_cRL;Z$O+gk z=xlC+R3khjX1033%fem#^*MutJyEV}YZl(!ca7P!Syo9|XlmsuFMb|!WI}b_wLv$t z2C1&0ykMP#?hq4ST+_+eq*aunhowKyYT$@}NEGmYwtK*@w6)#_F$W%AcY$6_pl!!- zA0I-`ZRx4uCQ6?$Id3P757#=S1FacLY3bQiKbuo@V6wEfPV{|4k4=WzlG2T`^lG6z zHeGJjTfhoUnsC`Q?Z7z~H4OKRgBO(=pe0cAd0lr;2qtOHMEceXG)=R+FFpd`gQR%|dRDL)LyJeKT!Om1c5Nsocn zpTsvO3NE^m9MG6;UZ{sG<}~+PPc4boI+w@U`P_oeUcwybPXCCxfx|rC=fSnvl=^C# zM>N4VE4JB8=a{V7vVTzJK)40PB6CKdnL7Hae0gEliTFk@(p8#aOMuylZei}F)t!TB zKhXJs0op2eKOBpo3+W=u7~e**MraO7emeD28={LQOT8D3V^l|^l-bybQL zhr4+TD}ze}F;62$-}1S{3tn)H4g1a*H={Br#B);5pK^&tHY_^nCk-^FWit^{$y$a9 zNH5O7gwIrIz;>-=Rr5ofb?yeXQOZRk3Z5KELDdmZx5J=2AKB$c7Z0LA%!4YqqfK7O z)PUw{?OuEu8!pK9s*D=DxTKPUA!@tGTx&&B>&?IIT>E-j2ehfM*gby|d!aYJGNht3 zG11r~r6~n0Iw+|}5{=v@p4B%fnv=Kyt3&phvu7LEE30j$`}`=CeYNLN@jplB`4?N} z(z|2rhzF#OQRYTt=uGPL4lCeJEV@@yEQBFCzI0IWsE|!6k;faNl zm&bn}wT(-Qn)z``j#|cU3I68An#Z`!QPwQKHmEX)CyX$Tnx8X?#!KW&GPi3>i2=F~ z?$NN_9=+X*N&HrJ#&k*WYHn=re3au+HtN~YPTSj*vpO5J8yN`7Y@WI+}lLwj1;@w9G9Px|5Tg-C69VHH+zQ zMuxU6&%K1lF?IG}^mZ_QHIgtHsN$WNCW4@%d8$93jt{%Y;qk6Ydp8I=S}y(m-16L$%h64SPlF;#wS%<@3m;?28HtW*j?8TyyM=EU9GSlP;3bIs zK70~i7@eoRm&`OsZ=T`~)hweYMT9@UU@5CjBhP(vswc6yUlnREsjsN8oKW@Ag?!N) z6GS&Vt4Rs8BdA>Y7G1m}?Rgr{>X-f7GB8!@=^pik%p*A$$%11C0@Jk_M{CARj}6}1 zz##FDhAi%F2yOBGwLxlOWZM%z$T3elmUYb+=etv1Gs>;XcojYCu8l~$@oj==28Wtp zf|A7AOh7vZU0b+}CBdcQo^(2K)%k5d0We~|nY5~&E(++5vM8{lTR2-=OEs#7PTq*+ zj%|A>m%I=<_ipu5PtlPtEws#8qNe%i%SJq&S$;)un8CW517Zck(rh`sj$4m5G zqau1d$LfW2`}GSDajem}>05nC`=ka#gp!Bl*~hN<1*9KTDdO@SEa-WTp>^Zy@PnN{ z7uMh4rm)|oX?3)=7-jL(8_-wSndMe58#taz??V;MmN#Rc2oF6MYfxgpBke=Q)pZD> zH!=C^bcoYF$N{ADatz7xSoD4VBcjUg2zB{-sa{^CWU~f4)PzE*rTJe8kcK2DzFlQ@ zxkeV%(6Vb0%kP&X?fANhl*=;T+f~ws%L46+TCN%3998VH9U5BI7FMX*WyE9gEU&|f&PGJWn z6?CVBfi|91zm^6%@R=T;(Rrk~+a}R%2c5!gGpJL&p?>1P;Gy?5E7z2|IZE*h$>N(I zGy`W&#dWBz2oeQgx%h=@BF?0{g8CAj%MOwQ-W_xs12WYyNvpF(PJhB=l*LB(KY-D6&15@PFUo{0~;Q5|N-u??QPde`J@(09dWvrS@1>HR^sX~rrfdD4`R z`$TgKg`y_l28E0$jCaQ<5`i|DCqqutFSuAQso|Yv5|f@?*tHUuZLGvmVNW!*Xup zWt1gEyLrA?bz|SR&}`if{L;lAhT=m~cQ1Ntdeqc#fh7SGdH$3fm2{^=V{+y0*KAbe z&`rHPP1wK$QG}`WJ?9iuBK8#oeaQJWL6CX(xJO_+y3IuM;L}c2Oa9|jQOhR1<}GJr z+qUD@uF5dH;Z@t=%T0~FXV<1Bc|%MSq4>Yp`M(dptR`3xs?e*4WlZPQ^fwxv^q$U`J&$Q&JE+U6k~r8e$W%JI;d9z^ExzKSC@ zj#ZWwmY&2py^z9>#X9P0M%uYdJJykzM0Y40-MyUGdA;sGaPR-{{eC{5_rvG?SuE%% zfk%bYnE{NKeb{ya=>Ofq;7jV=_!;z4i0OT;VSyuH+Zq%+z{RUAGtgP_{|E*nrDEFi z=!S_^{j&jGzPhRy&Nc`&4&5sBZ!&_3mm)y2ZsZ`?AorZ|r#GV3IJePlD?$r+4R?{zsVIxIxcG-|+Z1CVNX=JVdA z>N+$wk!uw{ z<`?0ri2OD#PQYcOG$7h=7+HH)$4mz50=O#M+IrfLLu9Inj`$Oj^on73BVBdW+UGn` zqK&mPSs7>5t%o5XC4%YPr!A`l;4j)VH>^;Hc_8O=b>$~xqXfX}4JuCij8rehltxQu z=k(ZV-C*<4=>IveiKtBY?G>fZ56E@UvE|^v4I74$UP{p=d>1P^oG0+V#;IQo&)DQ2 z9B|IY0!XQYgf!kSLu#Pv6%F%&pS?~0JI8cBl;F12oLyQqbf$fV6?kO-To5EQwd}5u zrnVv8Nr~T|l8x3Eta0CLiR^*0A;2&hjmN)XI*0wxJBLHm|8y|^y?yowPSPG+#81V4 zC_*u@QQP!@kWfPJJ3)9T=rU*Wh@#FS5iQ6J)G6}M^*um!R+pGPl=j zjY2QZSBH>K&k0n#Tb@%k_pIuaM}dl(iwx*Jip?D9yKN}hg#ox&IC<3*vyb$n2 zBc?Koo?};Gw5Mhf^Eu5Npa@iQ5kbA@=A^oL#c30-*W{g3nmXVAeo$Y0lqwzANAb^3 z>9_(uGyz)>8Ci@NHW)_Lh#EU&XG8wNG?Zc8MF%YB2en^W zxblld$!h7Lqy{u$=ykt5#@kS8pa)D=31_O1tyCLf+A&v)gv_824%1*PV-N$m1ash= zfsob0LN^ZPB;>sO_fpvuO5!+m`fN!Xii0U8cSR4kd|LpB$pHR`RJQkoR)5R+y{X@1e*r(BIE4Eek2C$wz%3>_HNr@wuEs)y6D1To*0GKo`3 z@Qm1+=@rzID;Vbfn`57-+=QHt8L+bswIB`pzLf1dyqxXevP1Mb&B(No@$Ak5`#Azo zS}s!MpP;>(GQit1?>mnvJT`-~FJiu?9*7QO0{u`TBsSjfWl`T`wS4IQMtR8m{43E_ zR7zdhAgA4!=rzO2DwM>5QW(!IQe-G{InU-;$Bf>G!X(?t%ehs_33ohu4)sFp@u{Oe zY9EC|)7G(Y1E$`YVUFBS=u@AOzdbH*prW>s?7Y`Je%4`OlkRhW*piV)Q?C{dKD#$8 z?+R{yE2DmFz}m{_EXJtOo;gQC38w{mGSDTIExI3x8d)EICSrCVGxst2vi&MLLP3%< zBH*BUqI@vl-~@&;`set_ira-L!d@n;)a{;ER9l;Ee_hj>x_zjk$+6$-78Av_xyoey zuK@45rgXLm7@KIrqLn(R%4lNNo!M%+6E%^zTZ+A1*GAkGsptBjcGgcqB6}3o$Y$DM$8Y!!JxrzLY8TgV5ocGAI>1u?+`4&jzkH z!4SpUl0pY?G?`i&lK+jPsdd`!lH7aR=Af$<(U`oGeDa3rkB?VeC!!kMtT$t1zz7nK zjp>wPm2JCABnOIJ4Oe?&h&T=G0n;9elDr6d-DQZ4?9H*Xbp>bbzc9@y{xMvW*{$vy zmIu1V=uF%0}t$nPa$s z(jlF?-V5d-`_AW{j^CyNIxY># zwI8$6%p#gNJ*SSWot&C+9J&z&5Y z)UP Date: Fri, 16 Feb 2024 17:25:42 +0000 Subject: [PATCH 5/9] Added usage comments on the example 'cuboid_inertial_parameters.m'. --- .../cuboid_inertial_parameters.m | 11 +++++++++++ ...ers.ttt => cuboid_inertial_parameters.ttt} | Bin 252171 -> 252170 bytes 2 files changed, 11 insertions(+) rename vrep/cuboid-inertial-parameters/{cuboid-inertial-parameters.ttt => cuboid_inertial_parameters.ttt} (61%) diff --git a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m index 83c6754..818af43 100644 --- a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m +++ b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m @@ -1,3 +1,14 @@ +%% Example of geting the inertial parameters of a cuboid on CoppeliaSim +% Frederico Fernandes Afonso Silva - Jan/2024 +% Last modification: Feb/2024 + +% Example of geting the inertial parameters of a cuboid on CoppeliaSim. +% +% Usage: +% 1) Open scene "cuboid_inertial_parameters.ttt" on V-REP. +% Available at: https://osf.io/jeut7 +% 2) Run this file. + close all clear class clear all %#ok diff --git a/vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.ttt similarity index 61% rename from vrep/cuboid-inertial-parameters/cuboid-inertial-parameters.ttt rename to vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.ttt index 135832a398fa5351f6be4c26ae501822f005ad16..4bf79c91b5870074628d8f0010ee3c5c52bd051b 100644 GIT binary patch delta 48364 zcmb@u3p`Zc`aeEv@0oEMl*7)oQ6hbs z8pX&b5~YZA5k;RuA7_nh-R=l}n`UfFy0Uh7%wdEU?adDgS{tm*i5 z@nhG;D;E=~BHI=}Fu6AniEt{I=4(uwH5+U* zP7frfu9;t9aAvBT<=Ky~}xTFg4-B3}VgGlUJ!U1=;Re z^HHgZFCIGl!8FtpHJc^Fq8b!)1W1oMn}bV!H(H_kw!JRH)4h)Kq4~YShv++5YlBn2 zH}`~?$lhK`kfKB#ZsNENjOJL>u|N24Yvw7j4Ai~kv3cQS4_@Ex4yzmirjqd=Bk8l` z+WOgIDzCl{)IE`qOz_m|wJaV;I!>{z_0$T#$CJ#zHxJS0 zYn>O@YBsQ!=2YshS-pV8h~h|<2PP&ayCTnwZFWheg^l|QY7Z25A;JeO(#*aN{Jzki z;Yu`AQqe3Tk|Q*;fKvob86MO%Oy+Ov5%6_`STHFbdnray^b`p9$jT9kiXF$x#v|8u z5)0JzYw6z2&s-|?F+_YRk$}e;V^yR>>oV8B>#h{*%7hx6;i+aY-lU#H&HUaRP*yh! zdv~m`VA$$L`KulMIAyJ>YJAX&_46Ri|0GPt(iZ0_G*F@r3c*RORn=M)vkrvO2kPv* zRt%&^RZ=l~2_;~N1xeH>m$235^9b)VM~1Nn2x^A46E2!z4+w=JY;kzN%q4FxBU$Ce z?Rg?XP=AyD%IYq6&*;5*{eNJ zT@&>|U4Qxo)HD&}DT|?!ga)iaQC`4PbMx6~gom{$p3?ZkCn<{gD}&x=c<2lGe_+q% z!4b*_S>DahFZB>Ak-(3SuzEOzu(CKHWAe%h!hh0@KQ7Yl?tC)c$^LmvNRW-_L_bWCs~;{(<)iXOz|XgQ)3>V?(K z351K91H~EVusbwuD(SYht$_PL$|jZ>b}WjRs-BqdzvJd9L+m6e0Xw9=Y%#N2`%p8} zkoU&Jx{o{_xI78Ft$xymOxS&4pg&9g<89U8r~Tm`=(kUsK#*$h46e;bCc@wr%`qdn2M&XHcw}| zM17%W=b>iT=L5tQYHXOQDwomsHIr^ezj59w4i6zaJ6GsYuprF@z`)*UYH626#U<#2 zDg9jW_u-zNPan=^2|ifX9Ni_ndED-B7k&qCY9}4kXZ53)fmWO^3+ih=K<4Uu`cSrn zYFu1f`i!r((;pueM{aL9uP-KMlRfF->3N@LOA{E_@?BH;Tl5=G&lepB_0QD1zVX!W zwhnCWsU*E|*4*_laOh1scAgZDg=vccAIw%q2HUGo)QjPe6P&XSxGJ8D zSS`yM9!`|_3{)Doh|095@YkXp*f$+9qL*RXIhYINmaZFFKe08ohv@O3t(oL+ZP*;$ zx(OV#wzU&)W}=+dbhdhZk`#|!M9iU z4!u_s4^zez^-dsVWUOz^66}$lu=dco{DR}G1ZVLF_rJJKWst`sM+jzYIkd-&J(zB( z80A1FBb!d1;qlnZE~}9U_Ug?|l}z1n2X)5hpQE!y_CO!~))QRo9C4`|d$=qN2w-OV zKIB)FDEsH`*h&3Tq;mykY0#s3lRA({SSxoYOO*g~i6CK-Ve@<4CbuX%?x7m2v~?Fu z4E|Ua-BCn(pjP!j)&Lhxr&RaSsQ~3nAB6NhPP{+shAfchMh$&g=U#}kd-bS?@Fl%-KDtoAhX68NEh4BNOu6hXx>-s&7|VMW;= zo*Oegj+tAEk%kh}-3B0$j$>!_#QwlLW3jbaNBjeZ$g2`f#r~|;fk`_o*!>tbYC~Q$ z>7>+50f(Xo`p-qloy+I@^bA&KP5MJJv)b2Y3HsCMIQx95GP>fy<|cyz6~!#x_7nrn zOTB|Xry^$hFwC)dsdi#P)rHc{7JK{MP>9a&i};fMdbf$YXQ=UV)btM$WKUeH7c^o*$b>sqRr7E zCWZ%92Vp{TMTSPv=J)4fK1QwU0}*VV>Um7X1DC_+I#h<))HLR)*IBRTQkXPB^?C0o z`<8jE&Et$Fpd7l!ZeU0!PN`v+Y@e$?u}enB9U{KT&1R|MQ|`@!BOi|4Ip>9Cd7h%} zmbFI|FAdav$z9ll+Y_#cH;dMFhmPB6En+0NPEl^vV8?_oXRloF9((I0v-oYs8vpnD ziaE-{Y3ELH@wgipF!}{Mu~r#~VprDYXz{dnoNj&}YcCn@Y)M{)ja!ln&UenUe`(yr>=to&%sB`y8?s9&NYEsnu6+d-o`N|C(UKZONgN zehU|xvs}u}-9H@Z{dRr+xT(J>c5rJJpi~QQ%K{)7JG*@oP{4j{*9GKiTIg2*sYl(p zAIM>uJC%V#b;V8^0!*=v-S)t=S~|=ESxjz=44eeC^c&UFHMSqwTJ;zsT#6WWitz|L z5N-}ftO{3z!#@tk5b&aUOJp?>h*rz&e~7@Qw+G||>hDh17*s}J;GiU&Qu-j52*R)@ zhcCm6xC9dfY{#y#a3EK`I&m0^R2v_$Cqe~dj$Q{z)mmvo(Aa9p<2U$C4^F^Sef8n2 zmnev>_CF;7q~wn4TzYZf`nICZ{OqybYMJN_5WY)#8Om1;7g|w?q|ceY>QcuXTD^G`s-i5D7A-an%_P z7I76pV6pZ|p*rT8v>;UCI42YVZ>qoE4u_qpx7;~{0ORVp+Czfybg;>s1aDq%B}40~ zZ$DN+AuunV&Ju~HL5xS$FS@n}z-FsABoeXy>9S%&ISa6h`5^Rl{5WH46KD z4vm;gt`_++02W6KRz{SzKXR7|xlz6LUCSqh>!ac%=>J8N6>y}wNq_(fR{z}!L{!gz zpAe8qHk*@ip|iurbP@v1b|mya>m9A0A^$1}%%G2OI|TR&lA~Ad^3jOy;p8De4FO@C zIwIJPsE2Xr*XO&|?5GYEG5BoyIIZqu?!s=3{nzIuRX##pTRv-iWxT=H2!K`K4W1;RRVFj)Y7OyT&;gFQsp z+NcaJg9y%E6>yjcj5%MH0u6q%v<4`He&F!5Kmh_CaTvPb1#~>eLLZzH0H&Ph%fUFm z{h>L?M1TTkqb0C{XmD^laEL#-qysp>mrGv-ZWF;)+-VK40oyshtN||2S$LZpxB|6~ zcL)6dN;5n`0mS{LH%Q`NCi{T12$18b_<!+3+3?Z3Jxg8cKEjZKWagkj zz(E*JwR$IC1yRoP-N283HV6lHB#?~n-3MgB3(nDf;3^~r$8)M78>JzqfK*x7~ifk9=rFYrxsA z>Xw_v56r6D9JHGf?o}}!<4bYCgc@AL!4(9Gd7S}1hynTai=xNk61h6H7hU_yYAwn0 zXUX0qzh^Ihd^RW@qiyp&yG-x9{Dv=98)mmmrz_wc=YX+z^47=4HGCh%0=?6Ip||RB z={&Fn;&>nr+yY=5Zdd?<;U!kUH=Tl)odvN5dbj!Xc0NjIU+8SD z{^i@=>+>?qdkgh?FuX%|9yi~>sOOAd0G=>m;VX+EjLG<=BA^ce=qv(T1jzGeE}!f+ z!)=N|7zC>vW^I1Yr6q871^jghu!bl3QlJWNT9yI@-DF`*WN6RfRk8C{*vtmzs{)|H_8;C6)pWIA3WgFc(VR+TyCQF=$&dK3EELr0VN# zwa+Z09Sdf<`;K+?DiuBWB!_EW24>(P9&{O)N+$1lK&@P_;cp_jZ26vLjpvSU7sN|1 z0~HANgUjGN40U{0Id}-fIm@qr0wA^hO8SPm8D^yKq_kU~A=BN5Kj6o!pb08aSpoH@ za-LRz`#_9x(g|Pmj5}39XbkX}DyXT#0RxT{hfi1|{K73bU@|Ux8)$;<`10G(EHdtU8~Di7Cp@ySn_2Db zmYp8b9OO)RrPH&&Rfbb{8+-z=>y;W{4)enM8V~@qaQi#J5<2bh9qMAUh?T$)>JiVy-w?5yq(`6 zi6e9m)bVX@ZUBW~5x(m;up3x%x_$%SfI8*D(C>SxH%5K6EXgWl%Hu}{eHEdkeM@hg zu1^jREA!qiI+tsPk2Qkj(2iGDwz{FIpU=OY(cPgDU?R|_q(R25nt-NA?Vj`Nt=CLZ zUoyt=@Fw64XXP}31As`mL{Y$vn_<>5!=svkrL^cRi_7Pf^-Ods*NJsQ;y9xd=m0Iw@lHrFqFlM20zTCR4v5#Ee(`QzNf)N2i}&Xs%&g~-n6db|=fGA- zyi|-_SSK}z68|(rlXSAAX6|&{N@YalvX+1rU!V5E;^j-=9^vT_;SY_ zV>jn)4-9u8if`|QvnAud^uk4;9K2NxZbX(RmDf9~RK#X{Uzj1k6h?gMdr);GKb zr+_%_{|>0ih}=KFu6+BsG8Bcu=j71aAzfm!* zFInP6M=Vr0BQyTCxdV5-)uO^ z+_ulsB=t#IM}6{+otgUB;Ug6;HUu^; z-X3cbLpFz4d zaZAUJG3`PX?enSrJ0zD`bJvS29^WqVO=;uhRfo0RZ_9|9ZL&#Gf=kDp&j6N^&^se= zwS>_y0%;$NFCK;Dq2tR&fi4L-kyN=B4;%#=MEW$IPz+|3hZm8$@WI;pU&(!FzBx<(5;)`^_i?EPv3@1%mA90Xv)K4ft|)lH9t&Fzewgd&VXVd zLxv9y&z>GWXE1xnG}?Xdfx2qfeps?B%mQl^kbkvCCV=+VW0W=G4{9IFgnizAscU1% zi_BloT4>aqF(|E=?|1F53!ATJ8~-}jD2i`H5MzqzE~}u|zVZ7p3#uu88bJ(+WN)%4 z{un`az;(gzJA%AB8PjCkj;`r z72N}HF%17D>}l$nH!9hcs#=_S5>gIe&fg<|tcO1SO#m?vrCbtUG_z&+2RbrXxjjb^ z(SaeSD~Nc&A}vl3kwL_aR+;h(l+TBq@NbM)c)l=_3tBm5A_#=L6@N)V{2*J6M3HTh z%VG8ws~-r^9f0{ot+Q@Vt}3TY6oK(d#y5*2Z{Zqbw+JzUw(MJk)bP`lfdmpD-Kzu> zzVyEhc1~bUQECj8hXE2pyg-DI(U8kOPW{BiO^yRzhHn8iwyv zL8^c%M_m=k2IPngLuO<$&Qn9AfhpdlhHQ}%oomFO`5HZz)Y-#~48(MaG1o%+_|YV%gDizgS?eIdu(d!3&IiL| ztsVr8j9=D6x_}XfwG3I{$3M#eF@z&tH$dJZvf=aMucpHkAf+4&4s7uSfm1U*yk-``99f zp<3;>NETS!x|*6>+TJ$wX}+TEv&IX?3w)nF;tMBewntV&lNPT;;KM4uW+ikpEHzdl zFtaJ(pBxZ=OfGeVI=$jNcSME(4C@9bWIqJOVl{FQ5vs47ySA|V6O5ocF32)OPOhT= zx26%9T~P+5WsmYMUHQCxUUq(L`3xCH+>jB7+PE9Ci%+3I4@4E(o4`Mj@d6Lz7PQmf z6VX&%Y}8bE-}Q8=ZI@}~frM9Qb#II^UM1hz&^N~1jyExSIR&1`8ic%kzpwH6WX{N1 zWFA1rfANMCd4wDLAZ5fblWsH4TOY(52$3J0A7 z?UG+%CF?EH|CtGEBZYvodyKD_&sYV$I;ovZ#-D6JX)^l_Z^5aYnryN3xM9fBsr=PUX zKQhRu=hPfRGNBa5^)S)^Ur=zwlaUX6(tSUIY=$y#3 zBmp-5auhKZB2VWADN4*!6gc%qkwze-V0+{G^zFLJ?ReHP!~kl*I|hl8jFXNdYv4Ry z#}RKnh(#x$e}NT8FALF!uO~PG+5C8Y!AZdp8~*d<{WFL#5fb%DK2pL*r2u)yH!k2j zj1W_teI70w;hfY9Fyn({&geyi0+r^>6(R8eP&sjzkfSL0!a>WBT?o-=6hyz%4#B8ofcKSiq8*vwKfot- zA{GcyF%BjY-g6|5VjA|=xZ1^C{KZXwQ;t(Nzf(QO@)hDlfwL!lKpfyp08Zl&G6NUh z*PX2i?JYwinKv+kt6H~N-Rs=yU-56%&h2e8ZW~_CD+G1GeEZ=OvI%PJ_!%yHW}K+c z$R32Eu&gO9-%{`f8Hi>*f>EYVPgbdX> zep%xiZaJ$U2^ zR7UVGI%nZurV$wpF;dKtIWLc)9$rlcA=dlKl#qbeIbng|z<^5ap6=HsE~3$PssXsp z3}j>)9x=mDzW9Y1WI0uimdJLNqkWU7ZIuWl$O?VDy;U*kxBN5s$P6MU%zAslW9TDm zkuM9Em__LSt6GkKRqIsRdr$1Lj?4Y1zd)%c;m=?TAl!QirJ6C}eSw24%gbHyN0LiD zNN8on)o!UTpTgy7DO}Y>%WyDmJ2UhE=rc;v)X2*>}yN4h0mFo)>K{uTKK$MhuUEZW4T>tgm>Jl*lWIYeG)?^Df~ zXgfh29*)in}>5ARjn4rW|Ps8kw76>#P}B$haSbskX^ z3^=wW$;~->1b;e@P{qKss&`G*tsQLnk1RV5UUwXo$J1j`ZKOm3w_1Q8C*u(dh~bK@ zY_f~$R_q1D*zT-s+FvoIrKHi=Yv#88{QJLj$l?AS>Ms@`>e3QhvyAY}1E_*nk0Vqu z|2PhQDx7VG8Uyj{-Ke}+q}$qM@9oNkI$d1t3S+Y|)D!Wt%pO43qFRcgxH&-8Q4-3< z82}BTAcA{L7rmCnb z3$zbi<82>TY4U7hs-@Ny;Ccuux5m9_U|hPgVO%cAaIU|<_=z0+o4USgO@jBh zvj3vp#ZMSyMWdv`?jM5|tyat1T{RnLr|lfY95b^7MbzU0?iv{OwPeKY$1@RhC3Ee` zb|(F|gv0v&2j$F`s<85Aqbr->@J@D%$A^p1FPZ(t8LdVldHU;wD1^nhNnuz^Yw$)zL6)*bgnQB7itQeP;}LQ!S@tGz-L)dpwqhbXGV z++AF@ks7nPf}wb@{k?|e!3PqA3J2ZUoevYTic<;~QG{~Y z{h5SKR%@M2e8$;;BBP1!(EjhPB{5eYtfvYkYn`lAjF097`H>#D`YTE~d9|%E^T^sc zyZZq_yya5k=5DXnK?|$Hnh%EFcvn7YX~VY@(dA6a#7)v~)pCw6Qc&CCu58ldEUA?n z(yvX_T1HpxwXVWQ0ldC6k z4r>k!Dps}2>6d+U(9)-{S_kPFY_f&RcG_*bZ75+CH=3PSJ~wgd?G)vTadAsU7CV@; zx}7NrR(U;~&ofrxdJbwAj1(X5vuQBUVi_(Sq(9LI8MwQ~gNKA$xV5TrM{ugkFOx@G z9*zv3n$wG=w@{)Jdsr5zzOiDlnXAIPQi(wey}jc`?=t&@xB+A5%?2rFO9m;ozLv8K zijU`78@C7JQ++LUZ`MV#KS&F0&iQ!nfDtq4i_SP!^h7Ds<#{xz(XXGWZQI z-A+tw_bY0skJO(?)?W{?%mFO1@-DH1tJ^6m9fj}u8gLiaA}qUo#Cb6**3WtIyjyge z?*WNT7YAePFKRFX+H;q;lgQ$$+oO55?$PWKxActima1!K+Zo|$v%SqMz2^qpBNmn?QB_9KzkS_V-Ig^RopBapTu80fV^lW+i z{SVWF6=lR%SKPUF@%S4uDz78u=lC6>^;aaHj?fW2*uAXsvP+dPo(-|f49uJaL*=quQ1bdAyP2(p8Pz~npqWWm%p!Vq2 z$m6y_lz>ZI&tZjk(X8DSVtu33hKR4l59egp#|7~6z7jOut%ttke0OW|$ZGx`ko<@k?U7)j|NU|yp-bf*eHuT zqOe_iC|QH4N_rwOvO`sBGNjyEf1|h@VX@t&k5h!;`6;HW0$q6{Fb*~hcX+cdq^9T| z%F$!l6*R4W&^!fHoCQIl8?b;y@Ii%AsW_XQ6J0rs#i`>XO0Uy>-rdz21ntdp5W?2s9Deu>&{f+H&TawolD`vnf9i=+qd)`(60;Xbu9sLdHN1TmG+-Z zj6q&|W5`>rLEDZCjO1>ah_>PuaU~V!t#!u}KWS+pA6%6x5u2CDv6oKf4dO=zGwKsm0FIkJ<^%=KEzuq)E zZGUGoBmC53)4`~doh?p&_R(r)gHc&h#c}?%>qYX^+~g~tyDGgPGo2~puf4Vf&sNCw zs4WQ|bS)ZdsXaZoU8f+BdknaUl^@ zb!lSn=lN*v^u_bhN20E8h(2l&otS+jfe})i+2>?rVUK+ntiatwP&wfYj1rYah%V4C z#Un&ejipHP6=5eoyCK3GOc)S*ix$FD<}K_#3UVWgevCEDMc?-G#BYh9isafXYJ%NX z{G|x0t|r>vtjEr3$;7|PDXD49ckeD*@c-W7pgY+?5O7sa4im>!DX5{Ufa}w2kH8e} zssUpQ`x7kcqL$7eljZGldhuL+d_CBVM^aF=C5i15gy`f=)tMRi>W5Xg9%{^4ZH>+i zmHzQ#knEm(tEHm=zd=D&K_T8rLG68+tUc%QwlDC;TgYzJs2E(9X1G!?{9Rc&`D&A;0Wdj-9P((u4<&my>p zO28`IMcWw`Q8YFg-ztWhnO#`3j#hUM7OshG*I611fuC5&8XtBxJbAkRYvFb=bm>aI zwmST3T#h#J^rxbH)qrLUR7&%bi)AUsO|v#~kt61xrX{_FMVpg7O;*UDk1cWp|J{X2 z#7A*6aWq_nN=t8donzb8(v#?RcyM-q0*z+iAnYx+zWNW@{@f zb1Q6Zy1pieR(BfSG58(I;$LaSXr=tyzuzPv4o*>rApJ`~E-~A-KV=%z) zJ`TG(6X6})ZZYbuWX@J+$3;Q~<07Gg4qNljxro9^Y0~hC(-E&+jCKo@3W^OjII{7+ z#jp}ClR$IG!YtO@CKudI5>>`GOQK{V$sOJsSJkK{r3(wI*|vx1ln7J z6B8X|vnf9=-+ynX;%b;eCQ&x~7{4o#%_bbyYotwW0`Z7Rg9!LQJo17e0(o1Y&Ho^X zx5}d1nC?f6?!ZUPF)o)G1dVaf<=Jt96v|5`C))nMG_elrjipnBsdu~hhH-f|IR_f~ zb`Hypc^~g#sJL2%ph${AOgcp2OQm=*GvAPp3b!%d=iPUIf%Y~kk9YofPYA^9&=qtr zG@TFOm#PA3^SfQb<71W+%GBsd|Ne_4ZvE!XnhD7bV)^BY(F~5iZp&{YPYwikbcST4 z%M8nz!|mCXzqMVvs%M+}#n^{aGTGm^_qSomM78DV!_kEySCkqwNY680Gm8iBF#aq{ zI(Q&&TAX4LcO~*^QV-*rfn=Ti+f+~A3=4X|wLgy(q@2t2*GGOx4EHE7^+Kk&M{29i zJ}ely=8`g2OP7BCF7~4peQ>C%$w?$8>CPRGIe`=<>-FXz>%%Mk@U-5-(FSHoS(6fV zSy!z!eZF!NX;l3=*L2>$p3U%o9x!Fgs><6WOnvSvVN-tWOXZTGZ-mB0XvUYa{{{&S z(utTl?1zY4C-3};7#}Tx;YJ>HOTVFaO@nMvH@-|B71jUG0k|p*rtux}sH*V*XpGAC zm!SSTxUT#e0=z~Z)z$gWmB$w;pn5w0&d-0I9N(^hsxhU4WH*~X!5a;qezlME`p-?f zCNr4t+clV{ADA9qxIg$8H?an>bF%Dipv2%CEkf9;8H9`AC&fRB*kRN&$D|Xv3wbphy3O z##g}muA$-m^IQidJztVeT_+1oZ)CC`*xlP~JGa&=wDQ$s!%@=X5XI`-4}I+Cbad03eKjQx8F}}lkm$$F$3pv$i zqsr4Jm{0qZpCvLpjO-~EUuyb&J988mkr@>vVxy9!J?+0xx9jhR@mUB_b?>x&xuFiX zQbwhj|4O@mqTHvgLfn!WSF-`b8m`T+ZWQ5(N&BN3-IuAGc5Ko4oj|x(RB})NB`k8G ztN+JtX4Z$_B$MLe3V)Lf^GVk?F_aF!7uL{8Aqb39CFA3Py2Emo-G-%j>_O{%{4feY~z;#j?;w-EI}Pe&03av8M+8;D6B$ zD#!fm(ioyC8dV%{OEfs6GJ0W!YkK36o+rKsauvGZFFQi}QL-%ca=Q~lDW)u@C+xpj zW921d?S0=dA_B&vgA3Bv*tv7Fx7?ji^xU`^KFm?4n7NZJ!W=&Xrp+BMSCZm?G4fSy zU^?V`?E5sydS_fipdLfy5<#%h7OlA4r5-g#{jHj!?4*)qd+Kh8PCy&=U-4b(pVS*5 zng^&&eKDODxYrVNiO#=T9RBCpfS+4}F4OtXxrTp*<1-76$86fiZU1`3`F7-2L)L#T zUKzwJy4ASrRQL2Sh217eoe$_Xe|&?>i>uGG$)SrfH3S+%x=bYk4{7E9oB9Rjjz8z+ zu0M~nwa?joxTr1=uT!w7AHPsp3mU`G{rFT*p3)i=a38;SC>$~VwUs<7g3-ez~ z#vk}7cTwR=aSmOGZdu~e{mo_H5447$%W*ah z4Pag`DsdeSQQG?jzna3?t9MzueY(48lV$O6@YUBMI%}e9ZyG)q8;tAT9g93<=NVj0 zk7?j;zA4|s`v<|&trpJ9x`_FK1_7d9YC}-9cKh&3+BlSqi1|vD6Jv|SBx>TWT@8n> zg} zaAg}n?jHEwNuKmtN@;5AGGZlezH?|OIj(eZO2~&{KAon&hc?t^9VsEj@gSWN?!Fiu zDN@s}-&_fKSa5BByyc+an!SEk_&gl$DG-}pDREBv-wOJ3AYaa=L;9rf`I7Me>=L)v zL_?V(F~t@^{=twzzVxmyByM}2!4>*&YIIpHRRXoIqO0-z5L1Af%Q~x$<=3n=C#Xd>}b|{UKK-SddB<=OMGo_(Urr2Io$7 zQVLal*IQ58)9$K5COs~N#44+TJR1a%hA|G1mA-tEItw-!el5e@b>TN~=a!*jDinMf za~CTu#qOe5@`!%t-go^9iRXG z)Oyd{Mh9EmV#;Z-JG3~na)Vn4Zl{ZC;z9Z-Wr=WnqfKpu{`8brGjLKdANN=7N8PxviJ`^xEoWA!>lIg0wvgt`;9SH{H!ZW(+f2Rx^=-OuOCjv@8_%n$ znk`cIQGNJ|jxUcBjZisJsmSwF zpwg_QOfG121FmC)n#pMOJB&+wEwd3mGBP;d8B^IJPDND*@K_^s`O=ux^1$5=rMY+J7tL)Zw7ghM&&XHJnP6M0|39GyPuXiCLZdJo^sm;0})?bYpAE z-tu}4xCPE-wJL*l3l+xWjZp*U&L=74(DND6{}96n{>|9ewr>neC+kiL?Mn1oq;w=< zYw@fT;B3&!>1wJk<#FgueZ}h6VjvoU$Dxkac2KQh;zsUl?Tj-Ty(Oo zL!6MerN4Fk&|T9hmTkZseN?DR-|BvNdB=a>9OQ@AfZ+sicqTo#$M}tLIs9&QvW`$Y z*GT_zdIY{<`ofFrWd$YlQ)At}r!O7qi)C0x@C@oA(=9I@YK+-yS*gtFlkL6LsMKNI zZ*fbhTO2ntMRzbMF_jPpi}psAFdZLb7 zE6%t9Axu|?zWA4-jS#4Q3%xL2T%+;{Y9qMzIursb?%(kAB9*s%CjDboH5jJGnS@Z6 zkn1AzAoA8B;!f!h`7g#78e0Xf1b=**&XAvLD& z$wx%m69VJ}0sCgi$IsUm!byebb~o|C_L)UyCW2F=+d`B!iG5Ngd5?;WJWYY{rT-II z{JS}Nie^%37)V{zNY|VhD&uV9?K*Gzg!kjOJNNB$N~O&9{qQaBP(6=dTY>7(hzo~( z*MGVt>Z9?JszMd3PcAGYh(Dk4kx!UPA9YDtljO>x<8v#})siOUNv^3tbQ#Bv27GM{ z^(d3$_+kr~KEy0x_$OGPB1_4vH&rI5+8zYYcZcLiM}b)7>CtFbiV}M2%L#7^GFg}nCxdGqs;`x@S zskGMQrYKqpdBv&|oN!J?Age0(8p6T{Em0?RDI(o?-6MUA`mjUPMOk}`IlZu+^) ze~)%mV()wzy-;7hDaR7kRz$kL8K#r8qlB$BS2Fgzx)v*R-7uG9&}8kmn1!FVLRYCS z*1hJWqtdil=iS$LjYy{Mmb|cU*~5c#^6MHGH681T$GvP(O)cMx(&GKsq$3ZGg@D!B zRUVb1`f!svceWtMP~YF}&~W3u@Tuu;)d<|(8a0th8XiyZ|Lu0L;mB3934D6?_qh7i zc(ygVa;dQOCNz$>yQr==U{UjvxUsdz52iDZB1()8MT2qERhfmx&+&zo&^w!KQ87Kc zQr7ic6b)}zFf4g!2*eOh}X4pzdP&UdPT z_mB5f(P4_mwV}Jg8I1Ul$z_8TwP{o8cNuG!B2=DIM^MwoKuPGFb|s3G;W@sAS}Jp{ zal5ZwNN|bpmvZK%7%NA&cQ*$5FLa%%T2LIPQt?kVsJXn!O+$RW?PReYv&kxPf*T>% zad;Cl%+&PY;WoCY6~(>ZBBGoX7%?!|jp8Y`sNbRwnIQ(gl5l5?#Z>eLD$@-AY>S#{ zw<$MnF4I8k^kc?9UZ<0ZZE+6j9oh%GDj(^vbPU%%crE8xaT7?Sr2ow-T`#Jn^&kaz zEB>&t!K6%b@48bB;!e&klc_$$?2t;pY($sq+30h=GFi9qLOWC!Na3w^sJyW6F(JkU zL+45Tjxz^oWADA4fZ|uDWc_AzD4M@q95wROBGrE zc-BfZ5H#aoR-#smTjmkpV_zzm=aXn-z3oiZb-1MiY9`L)t*Hv^Y@47v=37qN)!>N^ zsFa|L7egx0k}`n@Tf@0{wy3CFscc-0N~chvL<6-fhcTSh5PU4BjNtg(9e?A1$}+XG zI~>mxK6bUcu+9hb+qjV=k?feCpOffVafX(DZ*w#`cvih|t*&gEdBsP<-~SoB^_QQQ zPQ3QdP9-_-axeDLEcWXy2vLp{O3u-SsOijjnGpM2HQx>>ElT6vle#%z~g7>QijTTv_=Tf@NjiXpAkv%d)(jvrjmi z)*0je`d+b%9}PQZ<2mhvJ#2P9_3N{Rlr;5aF=YD-F0O%gl{?sxtKW{Vfjj1$ZR}{5 zX>9*PrDCVj)Y~WRbO*BG?mGjPpcot~+Ox?sx+wqp&n^*-sb<5oj>Yk4w!GWQVU7&nkXWxL#(D$$J@7k76 z*Ol0Q5-D%zEqf|tx9k~z~vi{RBh&>P?4>s{{)4KiqJroGN^M0sZ&l`mp8#^!aa{x`Wqnl;(-W1d{L=5jI z*v+kdHfs}5Dcwb=f1ptF{ebSVd#)Ga6GKN`%HWpKj%Wd;!;%AX7VDrQj@O-Ye&kx? z1x~1@#^^#Zy!FGz^PUe|o>nVXGHc>ukX&jcDiPHGwg$}`z#H~68}Uz0sFzZiMeLl8 z3+l4OS^R`L+=Y1K*JlEv66-Dp|3WFK$KBIV1*@O-P)w&Rj=bBer5Gy8+T!(x^9o|W z%)`Bt=QvXLiMd$}83OZ2%1SSxd5O5Yvne0ZcJAV$K$@k~Wt4ZYBrtub(JJwx%ZjaW&aus{rbk+~qO$35hF zSu_{PC=Xq_m`%YSbjuY~B+~5Y(vV{RLdq}vcWH)>OWDxb+rL2WXiCKwOkAeP5QxPU zd~`(BD+(X{aq>5DF~2xE1+ie$R8%E=*e-h3&ji*uva^R+e$6^?<3bQ&krEv0V?jp# zpo{fZ$V9fw#{!n+4}3NXZi@Q+TI4cxNs3u>SNs6J#$`>|{`civ4S_IA#>L^_1GEFP z)Na2GU)h1$G^ze>EPh3VUw^mu`&-}0No_2>`G^HabpmHC98FD{#>N-QiCEo5Ry>_Xn>lI#cwMDxQwW;FnWB$A^f04~1;{V=pUiu?E%M z_;YtNpQ;ciiJuDPpWqwE|JNA>|AU8kVyedw+_`Eb!SWo%I!6Y8h2Bnm>SEX-26EnbzfPo=3{@bu`(^?D5VerQUwyQD-~43aPZKoWZb%|jEY3^p-siQ6Bk&huFF zZeh}Uy#CoNu=`Tz`va-0rwK{?HDeY0NqTEwU`?*iWsUMONHA#mxwYfW_M-gtq7pgW zg3+h6;-9>Nd%m>3iWojy@z$(k8cYpfh!V0;fE5sen98Qj};$}6v_yg$u+Gc-;ag2%LT8`$?9Sh=3^TKu7uh7*@?4vlEP;wn6gie zL$VoKAr*4?UH8!G*>>xBe$V&+{r_M8*UR&4hPlms-Jk1oc)#DD&!t417>>+3azUNriQhbg8=-}gdK$=T?&M~&i?Xpj3;f)<3>xl+Ju0tQTOkeH@7w4}`OxMv zSuP(~EVXDD=M}R-?tO6m@ZC%vuOf_c!DZw2ErPqtf!{Da{{+N?wZ)1ch+6d^LDV{V zAIIf^vz{U_*KuHbU}wrCiv#OTQyqZvmeLs4oh5(+T#{qoje+uLt32dK+5|d?_W+h- zAwP^~VpDUGfA^OaY(uQcLe2B*6IR8+;I#-?$_bKWW>&C6zy*`*Cd`^LI6|5px`O_T znRf?{Fcm0dt(q#^g(hyFGUS$AeyYxMv7e|C(v5IgO=(>9f2$^k(pUH`dMFVz-# z`N$cGLGc>8((Ik?eM%KI{sp%r@bWBjpthLUXt`3`>+o-<{rL;jE}CVvR^ryV;6ptuB`E!-P%PTg>+Go<7t+G%1+k(uj) zOczQU$MFs4^DL)|*US|+4IM#PO=2Yr1#W*1sp?$Za<3A%`VltgVwwLX(QG>{C*Lm|)7*b`vDK<2Y(hSP5O6bj1?v zJ)FixHt3_M4l+DRu>`G!(P~IGXB+zj_$8V~JdY*Z!0|BHf~lmrfSh3*#S#LWww+?U zwgUkTxo0QaDRfsgtmy)rV*%(s0dG?`taKDv)CTNtEHRs&2IZ?K69Q)gM*7$zV^|^e zZCaP?s+?fCV>T~-iZ(V>N~d0)sG0`(-G6LwUyJPU|Gft1`=thV7xjrkf{|Og!^1!I z^q_qykMMZ=;83jT>B-yb$!^^o4K~GFNRazaJRs1K&IRS|c0hiay#1rNibQ49evJq3 ze4MH7pTaV$)xLx#N1qGyf$!hHPZZYw*Wz;OHLniw32)UAI%Ou_>zZfpla0_p0*IRv zxAjvwl2FFsNV98312d&KUR7F58dfs6MeF~fp0N2Z)Dy7XHXvD#fcI{LG&O2~^8#^m z!b%i3Ma2U%NmM=9IK@4a4&!)A{Wc4iZG$$c6bidQ7A>WoK(<^7-W1XLz*%`E%`Pu) zp%D<&s%?jqoXiWw#Q2nlPX^=@_}M`jtI=;Wv#73$2@q%Brhs((_y!*hR925xQP(XD z!?o3&vedrxq-%IGlQ_;`$9pPsN60gVaKd(oEGfD6Ke9L=2%d|%C8?k>j9m0#*c6ql zsE;ga>z|@7Iu~~5sPpIY%EE03!hpvz=GrMmV7*~O%@=uGw z#M-vW!x*N?Y>pgjCnz0&u)C}r1pAATj@*nz>Z8xzr$nkNF@i>RaKB+Fsp`l2GJlcOR7V8 zu9QjJ0ZeRDTb0lS$gkz7k^8}WUV?<$bRXxmJwe+CL}<@KP@jf56Qo#PS8m_al4nzU zP5q#^mB5>-uu)K9^p)ppkBduZ@MVURZ`q-(Za8hPO2+n=<(AWJ;hQ@kg9UA!X8(57 zM2Uaoy*>(jB^kz5sFj?-cQ8lBqWabyH`s^v%)uRnNTvE$Kll9;9`X(jsm^hEfMmoV zWP*ekrm2yPoKZaR?*p|cqzF%OGjT-LD5?ASVI$q=v~IT4{IXbsvbr-b|RF}Y_wIG*IiCJ>KB_k-$K zJFm7^U@|+B3CythHy}08 zrSNA=t>ds{(olxuAfqR9oaqCa72d|YP}Li~Zwlmjd{7X4@&|%)oHTZa=RS^ zOi+}x?hvgE_zy1DHszR=46qp5QtMIh7}Ys70xBbyrt``2l!FGp@VAD>@FSH@9`6c7DP|WdhR%xdCt@ zklHkW+!CU_3%?2(>#?)~T^=iG_77@8AtWSWKuo&f30b1eU^E>fegUra--J1spM^QR zrYY)Iwr~7XJ;@>Uq+@scs~^t4lfLW6NV%uZx6BHf-7%Wbv1F~U?)P&h-9p0j>*)HI zHo)zRN&1)U>kY)Bw$Rk`Y%7n4%5#?@PvIqOlM2Z*pZ3f$e86~2l$`B+K?_{vd$29* zw7BCh1L|Y9K~GFX=(8K3mzt!`eWjo#FwH9XE8`mL1^`IaM^LVeSI~4@!ekhNseK5k zZALIPta?uoKyqASrefwAtus&X zX)YT#KMpxEbcDvh*gwJ4b&Fz%|K)-ZajL!>KsW!pvg$;Kskk(>!>lfbWEnK)7&0W!{#B|WTa9>IkP_y@ex0GdI@zE+fxl|o5 z4@a&a1RZjhf+C^;?9!NdPXl$;hlaNO4nbe8Z#r7Sxf(pKOUpR}H2f!m`?kaMI%eZT z<%g!b8bI^EtR5fynJ<(b(nX#x?ZbDj*^+Vm_$mVvVX zrHtA~oJTyjd`4K?oeQ#n(r28h+i#Ia$C{3RxHB1#12?xnL}2QF@bZTM(8>WJUJE2l zeZJ#!ejDtmSh5IP{7bM}7?HgQkR&#?FdvIYuB6plz;khO6WvpUR<|^gJnaRAvw0Y1 z066_6Cr0OBLom`~D&(rWLTxR?)gJ3ej;uDh8R7QMZ{sY?i>iHJ$nE!HQ}oZyguia% zT~n@9`H%M&)AfIMZ&`Ey|FgH;|F8BIE7oG|M_XFAF)c5_lj|Wh@o1i9 z*8OQllokA~AEfjJ7{l_a~e<4$UqhYVk8IP?D;i0=!mJ%}oF8B_C2*fgdJz zR?Fowzr6==v&?%m;ls-kM&e{2PE7|AJ%Y5_;=+19V&&&62=(gi-4Zjm4eq|fFrLlD zD7mP2g~EKDuz8NgVjh{}M*)Ea*kcfV{<2QchcBW%0f4)b7Kx%V03ntWZFV^CE%BHW zje6b<*ZV`7(3L=ac-S9W$jlc2PWP*8#c1qF<06DT*O)A@QkUJ)r7MTXb&_KwzRRi&V44 zLIJ3l)3j}q7j8Jxy+B!Ve&d-;N#W8LKYvG;IlajP-SA+_(egmBXAaI8@Esbd?(umd zvT=+pi>tESU}tBrXR18ZoCcAN17`$6O1uB3h%q&Q{B_bIO?;njgR6LvpLos} z=u%dBY(|(hR~jg1QUFRiHf;3eg|wd5C#eh+Nbf*W_BZ+g5`kd6BwbpK?D*rr2{n1N zSC7@nZEv?rO8fM#aSZ=5M)>F_BOKd*N1EEq4(W(b5E-rD4~e)f{-W9Xu8s0-(%g)V zj21G$4oFxq*eryl@Un$L4N$fn0Q4j%)%NyQ>(QzRfI^fIXDm?t&KJX#gRdWiR$&15 zJ{b=wV$3nHECX^<&71aiSnw`c2LC{Yq0OhyVrfs5E_lt>N%`-ea-D(4FTeFw%j zsI$gfL9#mtbVPwI8q3p&&bI-6BtWhxDgXmg3LUjD?7F}XvA5Li>*(hIKh$Xm3w<^@ zXZcG)p|vUlCo=(2O>N!4fqFqftM%iG5Oj@g>P1&C8?9kDA{0{EJ69c5I-WBHL)%C- zbmCj}l;BMjkZtAcz|{#|XzHWqvXl_Hjs&ZW2R@sQzlj_I;{j~TlnC}e_{l`=C7Q;I z1fS%Nz5YK$0m;woP!4$6$#w!PJNzaTQr?LL%bnb!l@pSMU?dzwCwQ*J*iVCg9ezHJZs0bgVJJ1@aTflEwJ`tl=*hfJTHd;gE^~G7%40 z&ohpZxM|1VOqz2GhYa7(JXNh4#Dn#h5>pf{5!_EY9Jt|M!7i%_jh2Lt-il znH@L7TK6^LHjvpR8q=sF-yzT~iZd&2(2rIBwD{u(p!z^WMgJN!O*mUpTB>e*%y8aN z{gnLU^Y~iI$?I;BRN-J>8|xNIj$)vZ{43r3UE(QxKCVN!8sHd-ZgL!Wg=_ELm(rIV z@OQ$ZbWByRX0*>(&5ub#pd`h4vb1j@b6AQ|RVBxBpa^9xk>u}`o>5T1{wB15Mr7}(?8B=o7=(aCT%EZ*&l>C z)*!Ee|2Pb(W42*n`AG0#@Wq^v`YWS@>X|`*Oz|d{m`{SliWUheK`bD0^o@i}sNje1 z{;=q`Zom6pHvvBex;5=5>(UV&(z~yIzdSLYDRd3ZxDK^+E-4GAiW+5Y-)J?&K=ugdmD9nihMmrM& zWZkP-khui%tAB5e>Hv%Zqa8N{AWGbx3UtN1K&gTSxqm@^wES~5c@mI2&Cy}-AvUmq z&p)uw!g8C_hW>asSAxN7j{zh2yd==~b00Hdp8|+tIvY~%#6|j_R?l0yVL1kbH!#pC zul$jn9mnOAR!$_V8dbRDq3KGJf7Rf}^*q%+e z&wLHC5slun#TIkB{%u%Wx&haaKA|21y8>}?6~$!`h@0$R^s}4>l{wZm-7vCME!5l) zczlc+^$1)X2nH9y39*nQy(wiFpwUi906DHGH>b7)53pcfdJ|)PPiviv)@e(}+zT28 za{aOv6bxyC&Z)sBn*y@xrL}oc80NVHTHtv3iMqle*9>>o*jEDV>K&#B>hlY0S16Uyg<*t>}mmDmKjKWfU|7qVl9FSdtyve*M z2W1T$+oK~81#9~~m`f#l6jH}MaYUw8tvLz;C?5XyD5NL@cuw`#2WL_fR<($`K9WLa z*vd0se&cpuO3rCZ2m%=*8)qQXoquQ<`A<|R*fQq_Unui>wfa1$OG&P3@Z+njO4L&o z{;<(N{ZF~48IJI&_BYpcCIX4v`ekZSo2JcFHLWySPOlJ5ofiZMo2%489uFxqvy!4r z7u%yQV{l87*9e>9op3r{Q=bwOeUyXOi*j%<)^cAmK(<6=43954+0P@J%)2nKNp^1> z2MBP+_P3E1e4_VXI^L;CGj!gn)Q(Ia4oyEpIrs!ScIfp#Voetdi?_20q4tfxV2lrY z@rNX0;$7u6R`3UV&!b-cIW({ENPG8t03vqUmQc)j^Ma0V1b$S5mDt%4XdaV&4(!^L z_M8Lil~Wz)7Z$3!|Tntban-@h^^$f*|>5pp&ji&tv+i%N&L zehy}W>BgGMKqonwo!MT&4$DUk6}XMcNuL9<#2dUT^nWP?)_ygydrC?=wc9wYS6rh| zP9QLa35n2ZCDpQ1&GfK_i;3*jgVBzO;;$=B`c4YGmu2&x!ybvya*}9FAc1pOO3p}p zDK(`f_|_U6GDlDfHhhCwCY*{dQV22rn#Ma7A`{5J@D{nRMcho{Wqf^;vUspF3%KE@>8LK358U#jx8+w#eV88BZE z*~MpZf1^B4&6lI+>4kVvH`Uhjzs>QGPt2eNyhS895<$6|S5div?8Cvx-KLAOpPQD?|It6E>fNn(yzLf&0xB*nC-Rvrh zH~!>LsnpqR=#j2%D<0h8Tbd6H3PTQ{My*@yvkWtL@Yg0YT%IT==5i#5PB)v~)>}5o zC}H2HNxeLn$B>>=bikIWfB^V1F$a68{TubMKYlwZjJ;K?869$HH{h4!D@Tj2w zxvM4h(q8}@e^w1i{fDRqrxwjfURvM1weoyl()crDNc&V(<2%*%*&VaMl@v`Jn5gQ` zn`-6j)K_M;l|BCypY~QYqQ}5l2-rrCOT5X7-X?6*EWOMY%&C4UNy2VX=-Ei{zdxKut zX71e1em+y6;ePJe@XEa^2O6>0T7ME^`EyY@Y#sLLM$%~hzHzs08in5Q?0i>Nd6PcppaPB#zoShdH!0v{Mb zU2O1bYl~T9!Izc(79S?E%8p<+Ty<)*1yInU2~LC$=oR_(x1*%mY~+xPz%!5nf(rJW zffmDAXCU!4eCcvuUdNd9wm~fEWU;rJbjDTg*l)Wa}E7zxJkrcME*kT|PXMIfi(Iw)2W(n-6bJnogkc*PJxAjh0 zHeg2_vLNCzltv1Q+iJA+SX_+nHr1DoG1)iq{%(W=RuAk;Q=5qW#10hfnE@#~{u`d+ zoj(z&|K53%7Zo8x5AN=LcFx4|{#z!5ZYh|JzniK{ekBd;@nDgQlxQJD|aU31c1 zslOyJ0NQ2sW*+UjnE6F)pzh}iqKqqH{txG`Ia>gpSj<^S^9wZK%+G1S?WyI!j)gf+ z%Sj`EW&y_mW$Ph0)jZz;J$(ki{vayI+jVb3fG$NYjPjUQMJV(jK|kk(u~*dBk~D+d&Db1l6iO~5)t^7fRI zaw3`c*^jU(2Q-zoan8!8TJdVg9o}u-UUzW-w{eUinR<08I2-&rINRz7uf3BF1tvn0Y@b zSTae9q1rLs&%dPw=6OcJoc7QKoU;Wv{Xap96LNq{|9r>7^3PdoUqwaeJelwXY$LK; znV;LOb95uX(dPI@9hW(%0VItskNh<>XgV%{Pek*p!Sb6vWC-MuL#f&rPQU?P+1O$U z+I2-REDdZE(L?%I6T!W=k&PeO2v5uH-i$b??UY}7J$K!g(qh&mO6o<{Ki9AeA~J&2 zY30-%`BB7PiU`*rhs{WB1?%KO%F_6Lw&PG8fY}e^pfLh?b1r1FAVXv-rT1a$BakK@ z&<1SFS2A!zE@Zd{IsA&vaqiv#~`aNFlpp}Z|&@3jCEBWM8R#Lfin%@f8;^S za3bgd=Hx*unHD~XYhd+)ZM0N`DuZi?_*n!-w$`f18q1}Xd}mkJz5nf{-~A1w>%I|8 zu825a4Ei>-5Tw~5Bvf1T$=UCuM2)2gF(2Z%0}O50m-=&i+nh8XDD*S$%}G5`mZ$|$ zf_VqNF(2CU1rB_^_u{V|c!49RZE|Tz%lk4Py+y-!NaVq?1)z)B>CMx(w^6mTr^5f~ zFb%VMsZD9f;?t_sgUOH29(G4;KReR!JdR}VUYA-XW)`gf5(hTxPMOL-e zGwzh{Z(id~muf~b%|n@8;FZgXZ}fUC8%%3O+)kK_NG6`r26RCH4@hYd??Nc-1qois zK3$%+c(|khBCZkDZ)^AAk{)k78gc{(jTa-zG$5)*UfLi%Koa=gT8(C3D{bQokiIe# z!3R-fo$AM1@{OJqQAFC%KIkI)?4BIpXNA3I&J^H^LP+-u*cj&LMAFW0TUPBS;;2^~ znbmu-($-Dex#XP%8Z6hvBD|^ty9n=->tt&jXMG8rhcRzgjQGBj{6)R_2|D{0f{77o^ zM@I0RvBtoM$2`@oy5^vlA z)Z?Y1Gd6Pi_`z#H$7W*8hkp;QwS&H5a%gn|w~mEDN5E%CU>-RjvIcB}`Zc4b&BYuc z@&3xx5YBcv86oTK?gV772Acxlma!;rGDky>1`ZpsS@l4p5CzOj6GSJ`6SSWm11G;3 zAt(CHB2MORh&;H!+F}h+{I;5FcjDMGMQ8L`$fimpBG?YHYd=^KFT*W9N4&+Cy84g~ z0E`>_G0z?muv4(5Z=Fr*k+a}%J5FxarJBjoE%H@h{04t3V3uSvj0Cpu*F66-`J#aa zg%e2!LWyWBm|yKxpTu4xRh`Bw6Uk-G{gYL#VreG#S!&}T<6YqcDlee@7g7d-EO;` z4F+HW0?lHxQq?nT$}tL306i8bos%}&fHa3XZK-<>PDp;7 z2+Nd0YD|eKq+Lif??U6n+`tPd1n2KBD_1+6pyL95_y9Ofu(n7xC2e*a2{7n-3lqzk$a+KmP+U7?2ZOsl|!f2IqRnCt9T+ zi24Svf-INe`bY-;wFpvC1Nxes4P^Cvb+Ay#G@O)n!-^R`n1vt#Vx7fGIHDL*RQ5b_ z0i0YTO0_B(qL#WPCE#W=LEG9W%q@nL)xg@PjouR1Nze(<1AT~~|IopImJ23%+(-b* z84_&Ag%n*&!I&K&_7L@&nay=niKHpVmDm%mAl2m1RscgxyZ$zQAR!ejFT%yyAM(MX zAmnNO=|k$cz>-{ur1@8?JCH7zrGo(uM}b@@86~ z$EDK^QBVQv{@@8A$-qYs$l#MtNb_!;kgFhVzl#NMmhbJ7B3hfd2rCG-smkf#128J^teL zFMAo;$-tTB-wBqDG3vUVyc>Vbsp<45|*CprOWC8Sjs*>WKtYzR9S z(S{)Z)rPomqU#lgc9RG6a4NY8Nr`>7GJjJfBit2fA^sO<>H8!Y%8lk zW>_G}-g>omY_hkMd^>Ub^pqS;vvA&toSe7Fc2u@V2`#rSNCzxBh##1|YIQt;|LamB zIv$NqHu810U{-EHM;sh3T4aN|J1}&X^i03;zWW|%sUK!vT6iNr+TE-1@-!jM{H4@r z z)XjmgtZoORgkSXQt=W3m^S{TPrFOasdbmq*ugZTL^SR1AFk8VtzDPMS(@-a?8Qni} zBmK$7)@}(2iydg6G@;GVP1AsLM!~8Z&keOMTv2%doN3t6_?7Y#?KO{I86q?tZP4iPw68lQoE< z)UXUFb&%SU?2_IB_q|)>$~K<}Yoj^NL>5SKZ`~nvSAg?lcjv{0IfR)BeUCqLb;_S8 zeMZ||p&)d|O@KlCT3_dr8q;U4)uYbcSzq1kw=m*Lfkv?r?15d4^I6oFZF&pMzgEF0 z|B;zkS9U7}6H}UQJX#cfOR6g6DdW)=D{jN0>avyS1U1JeaTM*$`y|Tl-mCgCtOa6d zJhhJhm4Pc&O=)cBO2*y5Q~|{ZeZRjyBJy?E3aP{+moWPlOdM1rFVU1tFO*75b1m_* zjV~{RWYSrOB_tV7Jzk9SYasI>UDN~nI}B!S`zS+}LJ|w*+oUEM=*Hakn%dVF)iRB` zud2?1wF$-O3JV;SKXfh`W%I2Vw!55Iqliro+3no9wcYFzf9<)V+;B|&>v8p;TW`vx znT?)^<9oP45&GHqBoz5uZIbIjsH%8k+q28P+enYM+Z3Uq_?G2EQXv7`#HjMY+03TC z=DP%|j%30}N*O*e_SjH{dia~psjLn&VYfc@D?*L5usG;Mh(lCf)<*xz;)L=>rJEZr zL^{YcxMarjI)vWMVNOY)fpM&1niXCtcvCDP;VNx4szOi*a#3PxH400(+Pz+^j=Om` z+<)5lTrG-%u|Ks;7#w35$v@<)!p!Pl=mDkD@9OJjU0?Cw0jxXff616+LrN%lmbt-~g160dqQ>#<5QQ-;S=yWON5Ug1S`wwgs)a#iM z%>?_yvAw30Q)2XA$FO52C;49=V|lb3Ydj*nYSm1#?>>K`tnGBiGSr@y*u)4DS$DMG zGU$6oV&q;U6t#Ebi%RtZ`%-3-+J?H|=3o1|ZNeyRI{Q-4j3(U#{uvd>yjWTcd*$Vw zP>itacH2wr8HrS3IM!pW7|UTB37pK@5iaNTn06H6)o9u4ml=f0gOk6!!o1F9CY{Rg z?MnyLc-(CR+^U6dy}`K+m3?%kSc#^7L z)L<*%r_?v;TXCF6pQnzOtJH*ZiOhhWhvyHG_)(qGHl}pTWXaR%%q=M8a}6Vp@F87; zi+H}NxA&pFY}O=uL^f{r?{=5(ttwk;=gyNG>6R{1OJ^>-IMf(}vorHm=opfZO_Brc zUy+>xe`lt^*H*HFc@Y~vW3XLpOw6J>9Tzk%F80q}CWBM+yZ2z&o(AqR&jPS!a_vLu zLt*WymFV8dU8p+h_qB{+HCRpfB9>AkblckLUaYy=2r6gujaMf2RwPQb=uT#|OK-oiClN}buTak)hzSM9+&BM< zGcDLwb)RYVl3H8uU(!cjkuPmSzj{Z-8KW^+S%@0SkJ+4ij4aNgqBihle?_0C5R0|< zv*h~PT(Zlh&Gd`M9_U=Poo*i|5y!G@`}J0)TA{1VuJ4>YBuvCkqrWGT9uoXK9D|$m zukK7uh^Y1L*t2fe{-H6#KssqgfE zSM{GZYM6O4da`Z{n})@I#_wI|b0gr+Ce0iE+*(p=CYdOpMcML{a0cl@)K@I3fuq#W z^drf~uFEwZU%k)lur0WGHLOiK8E5|}GPqx=E|`D1!h3u-OTmF@m@1Zdr0{Oc?E1t_ zdZ=#ZAmirj=CebQR8uLGj_*Gm-AKvG#y<%b*jTS>V40#`Bv%d+ru-qnj)ta%q? zl8pV)?JqAF9!_(de#)gvcCuKTnN* zS=>|v18uyRj_MrRpL8vPfghg|&^rxAy3c4dG`kDZ@h7Zp7U_u_uyg{*dku%Br=1rB zSD-@np}^r)GraIcQz1n3J?V~DiUekyy>ivbv;C9wmGHT`?HdW5#puUQDvN5+bIXWsM?!m7k0`m@Z==^pOke(M*td))D#yR`B3%z9m2 z!9$Hf`hsUhOOB#~Jg<-b+H5F1D!dk2Pt_H#SWrI|TA#V9!u!7Y-ZZ%kyA4oPzE~?m z6`Y*RS6F99&6}Y#txt^$6~oi2;ztGH+yK}RBm(J=2q8RvL0Xl}s{!;#Otg!4_MM15 zFU)+vfu`joO3F=aN`Vybc5n^TA|P%E?LCf3Gw}-x;ytG$wU zi|^itzUjpqy_^^Al<3rk&O8=JtY7cB5{>h~IsgF%J|QN0htbXpGwp2RvLaIZ(Jad} za&};7AHTNmDJyTalW#aYapd6m{h>RyS;I|EMTxg;x1`ltU94NS5-GYZYeXT)!)=Y}-! z4;Q)F*Ip-Zl4aWAS1*n=Cgo!v;cun~6soh5wS)Q6CIyz>XoyU%MUSQ9rYNsa^$jzk zjUE!bsiBxIb0(KZPmv~-#28U-4&TwZz9o${kX5{P&!#J5P{Q{by%?gRF>8G6>@&&W zIP;NvczJp=(|}z}Ak}E0Yt~Y3zR5QuOTc6+efAx<-XjIfwV`PKnbT$px|AlJ2tWMI z!$rwTb<>Ln(E@^)k=UA``}?5LCY`SGCwo1#f(%^4O$ShfO*$iLZRdim{kOKy@C;4Q zm>H7CSwYDV`%q~AQv1`WB^l#l6OIzr%_;WQ4QMGQ&(Sh-<>CSUSC21G;>OCofLWVS z$WUIt?lH_$M;zYm9>%_&DtzoO**!Gq%{GT(FQ3Qh85#GweS3#5TtTRJ+1XxMEVTZ5 zBw->{kuY34aBC`Gz`uB#_7kroUBesQ^uiYwaP^~T5hSCYXq60-% z`!U^iVlgM=GSzf?OzJbLiabnx#XX$4Lxr=bY#)Wzo)?gDm{_1f2m?DlEYAAQ$4bSG zpQ4!}@>K)tN1^@y=LiM=abk zvlq`a`R3k0NzBwl@55=~X#8?1=4kA>5Z-~`4GB^1>8N_IrTzS%)lwG^_2F+V=rW8) zyTn_|V{<3HQ){fKdv`K~DvH)ws_2)b3Dj51q=ss=eOb+TBJtd{kUHoA8dubMzVM9 zS?W_Y8dc_wmx;Yz*yyeF+1@Dqbacp`_V{f)CK0z(O%|LH@e}i^k9e8?g{qv8czGIQ zy#-ruAJ&u;*%VQ#i?01n=FZBJY_7R?VN*lQz6Cyiu!ugsbf3%XyY(?ICgMiMYRdc~ ztEjQ4mti{94^|NEvnz1}*D9E6x2dUKb>h_ugA%6{R+^J+fi2?s!~ zsF%VQ1i>T4fzC~ohN-4v5FFC8%~7iU=T6=6J)6+%x?ejQigGO7roOXd0Rc7Q7u+8{ zcVYTTa%SFy1Z(ep*^O%xoKPEM(J0Tw9*dX9cJXzOKV8>feanFBK@qDo z^iayT%EzzM^60zZGz?B~A~(pVdMHgNo&*udDt>eumTt98uAeAyFKw=;sx5>a?}5W) zCn{H7Bk3_1s@u_mRYwJ7kFfNwrdVOt_(0G8mSY+$WflMQs)2)ortk3RY@FU3TEj9U zC@%C&F4t!5#^7#g)Y>Noyc#Pd*6VGTUbKae#8IP*tFFM|f5dENjbD~}X<>glQ&tpa zHl;kiOMrwF$#Gv5&!^g`X>2(JF-0N!!-!4VCD(Z++pJ(v=1K7Li+B=duZ{7sY*|_! z%1Y-{i&xTf;wzk|N=M}%&C}vEr#4o!+s%i?UgJ0IbHyh%2n~MdFLM_&yB^Of+hr8F z6=IbQr+H|&rdP_3{%*iqabL4W9ecRk7xhp7-^G|oJ@=8bv;MJJqyG%6%uVlXuU{1R z;rS3TN~1i}@7pBU8t-MA9Hci{B*j**p?@{IWxVX1`FYYvrfV&u+j=TiseqyC-YPu# z1I`uYa}ZbNTT|rOOjp9Y=SI>FerMzd(#Sx}te+8)E$)~(W27POK!IJ(C|mKzi>05x zZll^t2l;LFy0TH|N34ljEq)9$jQ)KZ<%lt5dZtdZi8Ad+cw#2ob;k^w@i)!(w8>@L ztPa10p7b(E%!|_`q9-S>$5+yCh45L@GXW3$Tl`f^zq(15Pi^-=>s2XoVWzb3`l5O*%INr*G z&1re2O($y?_nE&Oi3J5Sp@lrsUTj1WW>nBUT*Ku(T>E7G7FN>D`ZA)p6h1&FH^}pt zja@0Z2_xrJzrKQhoGv-uMa{Z#ib$6{tQ>uR83*k*n}nnJbSk$61< z+e#vQvYye1i(9P+h6SMFmqUqjr!U(dw~L#yl_vS)2meBfe8j* z8N-c!+f^C4VzxV zZnwQMER~e}D=AN}hVHAvw-sjZdBG!Fnpv&P$NT?)cO4tl=-l34RylSqMmSdXh=O~N zzXlWN8M&)U>QE3_yi3=D!FJu{Z7J?_EPjJvzZYZw-h~NOiefZ|m-K}ax1{>Bl=2_{%*_l{lq%E! z4X-t2>rr(-m?;$qOE&p8{c*n^rJ9)pDX7>!^0hZvH&|bCF%2g*)=3Lz&h9KXo(xxu z@VvPz`xIe%O`FjB>V!ti_hTCsO`ranJ}n2P*@DRJsK*ELW0iXA zt}((d_q3PxQ>4nghGOq5F-X=BcTBZo@E1s$+|l1IOq2Za1gf*cH%z<&H+nPt*ZOFK zvO4n)blcGDS40iU8pQ_-<(pop9_gh(F5Py0N>{p(nh=Ak$Z-)=|8$ip9VdNtLk-Fi z8XY{He(=X+gX{(a&GCZ1!o^;@bF=i zQdPN^TT#kC>&&)4EZ7#5h~1DZ9ZT2rRM_raxNHX1`vP;*-=zw*sD)QHzKHR>FDd(A zn}<7OIE7}`#$s^YotEs7xS))RzLG3O!d1_Oo$w(qgE%HXW>@gJYr*BxN_}io$@5g5 ze%3l?W4@1){rc$Ri<+_>V1dDs5$@|3fyNU%;j;StMI#Xt>D_z3x+9ZjT#%<_2M5uu zv+k7~&M3IaA5xNO@K7qfYkZZ~eu!W6-idR!nXu{~DL)c6@0aUs6m%%QwXm4ja! zzd_iI9%Zf#>7)B^Vo>+wTOMJ_2`h`*1v{JjY*LgK|ZGS;=N^uFnjWtafp<2D{L+Nttc5d8niL)FmbR@i+F#xD_OQ4=baI z^54dV^(TV1Y~(bB-b5do*bg0n1nWFqea$SBqMt`Pn6ybJDgRvWKnw^cwerPVgOg3} zE*9GcK|}0cn0l7JDu<%GLC(AwL%M6~bFiP)VEsKa)1-w_R`R_~eii>NK9DbQnxVhB zw<5JCy?>e2#!IOk{n9qZ{9rz0*b;mw5H;4Vu$jZxlO|G{w#BvfO_>p&S!LSCoP_TX00k)!f!TTmK3=CQj5oVvPXrN{R-~8(P8b%z?gP7h+ z^jPT&(jB*>ugflCG1eN|oxeA!2fO znb$3y`>ZRAxnht zC=8|dvzEKFrg(TA-;;8gQzIRCjQ^H?_u`thc|xw*qM;IM03iK}@eB&_7O}71EnB8x zZNZ`XWyZ(GSf&e5yU+i8S~PPgyX@k)q8MOT)3Jx@1M2_!>RXL{|cIrZOI_XVo7xq3WQ;jc%l-NG|u z!*DYvh&ga+J+z3qjBNbV#5a!%oEli>C|r_jVdt_`RIy|s>}lpv9}QV;wPS7f7}8%T zjXo6A=IZsZ^v*Zkd*cEenI!yk#obd@l%SKPBXOLU)TRAd#;U=v3KV{Yc3+qgS~snq zVR|Zo?0(b!T%6LCZ64yShJ$J}x)iGV507>96nR6G#e)uJmMUsv9Tc4 zG5Sfc8|J)b2qtOs>50TRBB>)l&24wJW#BCdNkZd=aLp^*w`AGuu(~^fZ|EIO{e@glQT*DvU8^CC@s$~ScaVG zud=7$ z=OKpQsflyz%Jb3C$E`8j81eu@^)SiXhZiGNg6_`EG~HfK1P&1`h9$R_J4#J}HR|VD zATk>XzUqp!Qwvm`ES9bJS<>+5o(Qm#_8-}vnjf09**iIJ_$}J!+ljVeWJKP@au)75 zdUSG0+sUwUF@bPM(#@P_{@FBshhrd^bjTX@2-wpi;w$nds%*s~PoC6x?GH6VxPrX5tzGBes9KX4pBA6CqPro~7s(p~jB z5M0cX&XE5&mXlVF0+D4mUh?;U_baM%0sVqV8B-LJ75poqv>e()p@22vlPXG-TmO+8i< zJntOBA8+#>S-=1}dhy9g&$zNw`oz-QP~HCSWU=S8%;yw3x2Mtx2s#&1*+AVY&{Z;Ev z%M9b<*cG^=v*~)}z-&DiRz-IKBQrc!e!=9ZSJemv|H zK`EK(UCg-SlNz)!q=rL;_i?qBbVTUqhC9wdI{)#$)dEPvLfhC+gtudzA})lUP6Av> zCY*7p{xTKq=(QI9=3%DF#!l&w##)K4_EgoYL0Pppr ziD<;dWG{dgI`y|GpNs}KF;wQc#}{yd=ty6Ls3zr@co|Xy)$;6R zUIROR$|eBmzuouVRs|~WmGOSmX*|E)o{-1gRe0f5wbY$8VfXe#t(NOEem5~!p%rTw z=bqAB$Ys}Xor;|*=?mluXo-Av={kv7aBAkQ<(%-& r;mN8i57O@R60E>QIgC|dXy5HJC+U(6%ids zPm@uM6iKCsbWn<(94dz>=YDH?_I~$%_Ph6f-~Io;pAYvv_gd>(>$<+z_qx_v_biTF zlRbJ(wqz!mF1b{zc}Y6cXdl_6b*GZfLbD~?Q|>=|a-1+A`%3Is+FRx`@8!a3;#abz zoVNAp8b$pid`su`?~_&^ub-499+OuyHZhd^eeDjm#v1-$KRCWHXIxg+_Y{LnbWFQ$ zO493`<-T~Hb6GW|6(gQdq6sK2OBSyV(Is|L4iLr?5(a>?Z_|@vIsP6!rRd1Ou3Hi^ z!9!6|!i8N2m~GpM3=54hEg{ppo^_B|EAgv6M`#pzTB$BN$+Ctw)sqrbe{bzowubvE zhwPJG35VRL_nMv>Yd6(76e%=~bTSie=kfjTEu39-Shn7`Sonp|mfX)eSn>4uWja|^ zsjbp#KyCPqm!YULT^+7oz5KSw8np~*{BuivXuecY(WR%3ad-@X5(h$p;CS+uk7OGqFEH7x*@L-_+!mj*QNtwOYNtT0M zACH8kc#zE0HTCkyV%zo7fXjA<2D<3z&YLbbo&i_%5TTSf;-w5t&5s)4m6kyn+A{=; zhITG*zMG?CQpwy^|IDo=Z$;|L_id#TiM;z|Egcm^A;FqFk*g>- zHiyY5-;QLEt3(QVIj&wi6vccQ(v?i|F{tkX;B8E84C?1ypAK8*PPoivVEzjMJ(YobJo0Bp()b_OUq)fE$8P&QuIlZLL|-1Qaw+L+$(_wwbRmWP)m#1 z#_XzcYF*fs99c4paFSC821JNlg~mso_H-8MLu!8?aUa7ii6+u{OX5B$*Ow=YE`*hQ z`CO`PR&4YWDYDL+}VEz{M2BiN;w<)T}ib;vTn^iFb>36JZLAq_j_+G6nrVJsiR4%SI6y5XO(Rc>&Sn1l|KO7=tm33w!lsp!f zHt)3_?#osDIZ`NvL)=rI0bGbyWj@d+QdF)3Ny1t6x(OxXO7ElNk4OPiM=_cx1033*YnzsNT zthBlSl~C8dE%lG$8)s`P=E~N`d!?!kEq*nNbnEzvhA712pUg}kwB`(okFzR>7A9U! zC^Iso>GX3;>*Gl^dR_S`r-)k&13ETl=SyAImAHmu!}~ErKBSYN5xD8b2{Yn2C7#%) zGk4}ay2QSE_DtayFS`zEWbk|rQLb~`oVSHi!NcCo5zglM2KEI@FCvl z=^GRb#a=K0VCQ7*pr&EkD)sOXeMEY8F zi3v=+y=m*hbv;fM)&r6(Y)8> zl+fdiw@I6NaD96TKJBWv)slSHB`s z_gQaeNTGqX)9ldYSb=v}NmzrlVpF1MF4{zVGn66QnkAh-V&iz3w;G zQ!>@f>Z2a60ekIy9cAlThyuKxOJriPQ7XtLv^+Hp{_3cmf~5^ai`fp@dN4-6U0-)Q z%aUkWfb2E8#eAy=x5*G{#>cRNM54oeHu1<<(x7KD`{GefysPZ}d&rw9)X1IvBpaSG z-fqe3Nw!gobQYswYmT3)=J4iT)W(HQI`wrWY@;D(9oFZcz4Iuak&o`ShgQ07F9;+a z%-x2f&eFtBtdADy^xTU$Zc>Ofj}bPe?OLt$E-uMV`Bs`13FQ)T(hP(84@PyKk&Z9- zp)C7w3rY-uL>hCklwwzb2DLLk&f9NAi(@n51b`1{@ zq05dC1NLGwhQF!T)4;x{uFf-&%4f1gK0QTL*-`$GOfB=bpN;=CI@T$BRzb;{z4djb zIhtx|!i|ZhdIcdpKZhcxdb4g46^l;eJ)e}yRyo@N#1>2c>lCF8=NOXT(eQ0n|94XsW#i~ z90(_z+*4<~$@<-yw6=Yr)kn3&aJ`>2OPf(p^2PO^SUp4RziiFHnrnz^&ur``B$>L8 z(~5~Bq)*EAQDO7U_G5}IC6`ONZW%|0GIiGAXA z+N-HVHbY!z+Bec^w?5J6bxKcyw(lyhhNY0OSDU!t@LcDKV}jU_^Y(AblWAITY*~G8 zYUhz#aFR&#KEWtfa>CRubiGf>{ILc)kuIs$OINjp4>{`3V7>7erQNLH{YWBQeKJ8g z@y~-YrgGBOjO`uF%TAra_ZLsNN{f9kH@)52!VspeI zogF}X@iBZc|2G1cYlIwQn_gU+HS9oDw)X;nNTG952Wm8-t zHFSw8m;Kqe@=C+FaizqDsY_Mo8b2HVI2Sgh7{Xdr)*m_rfROkcwj5m@)+=iZ%Qn1! zl)l?N)NBJcd?etVyk5z55E0&ZTjefKt*Ej`ZPc;liZL70GBwuaSf0nMmHJ( ztc(%<6#$H&Z{7_gh}6v*K&tG@W(EcniRP_N$Uuc{*4Rv}acA%dU?g8J8?SKa=IILw zR>Ul_@d?&4A|}EL^;jCAhPrx>J7;ii!%4Bm7Q^6`Cvp@@JU0%>6(mJ^)3O#^g zgak(DUUo&DZNH3RWNiB`OJ z1xvtMm_`Mu0OMVDh&q0pw#c zKTrkyLPoW<8sH)@xyDaK|p71Xl46?*f+*G58C1g9nKA5bOhC zK%Bo}A5avvj@u6w0tCQ~cyJ6L7cAz0EjTjdY65T~iwP@jJT~I|Z-;=fsBq3vFaadC zU7R>}L5&o+fUkE9?8ZO{%uWT4NcL?ia6+I!Z65FgO8nhCkWAJVp85Tu;Ngby54*(n zEqoYsy0xs~hQ)o$vPNfvy7)V#EH5|*0yfg%JOr08B<6Dp_+h5l>lb;CW#uvrE6;m$ z7FF6{)2A_CO2D(1qn}L+2N@guPtP^}uCnTj?W)OjXqE#)(Ib%~GMx;I&H^Tohp*0p^~fcT=fH98kPUusTOP$X z{b+eu_UpGD*QOQOcYahGqwo&jeAH?cOUNHO2fR_jf{XGHj9hpj511eTTJpd;DmH!U z;_)^mXrB+ZA+U<`!5&e|IR$8RDfqeo*rA(BA<#mFHibadh$~4*_5QMd$)0IjVqz70 z$zYqj;k-)w)@{XQ>*Y42?-{PuEi$Sq|BZ+2;}!y4G+tpLu#(`eZ}8Av9kPK7dkTT! zEMe8nrirW~5@ zSCIbV{HIsIJs?9q?gHxqHrjY}-U?aHg?S|)2?(J{DIy*hx|AYlWMOnEQk=>^Qws7> z?uSlgU<+z~f(aO%+abl^f zXL@p2eTXaRm0|nthhqGya_|YDrk5&!70L@ADnJm>fKIo74RYH4Ti{oe?jc?YoY9a= zD?uO7gcen(a}qzO3Je1z;!_P4fJk_#8d%OU54cZSz&-T&TEVBQX=7zzrQt&Wn?wyb ze2F`tN@R0=4afx~xaBU`3RL;6cfmKHL%!ep`wsf`0e^iPOjC^f_>pPHm2k?gIoD5C zb0fAD`EI04Wh%kJS}-5k@ygc0DE!dpv+pL1Ht7boG7wpmsk7b0wul zZ9O}#)TB|bLCr>Bj*3?_0)2Gb*9hhT8GcD47!Y~j>{Aed;$=n?n5{47{8{ks4H%fS zWaT5e-04W21=O09D>bbBiLZ}JXDUj*48#ntx0IN`)lI;D1|HpJOABNwyqf2~X{D|w z;1@Q5%OXFldaZiLd(`Fm3cX3ld&Og=pG95_he->QR# z4w3O!usvGl2w~M*uy@8n#YWQT?lb4h)pDVQ4C^7^wFAV8SYPuFoB&i9_#S8} z;`h$3DBgJHsC2q>hipmp`PX?+A5o?;g)JX}wkdu*^oGfen&a#ZyKLqidQ#L} z&E2#))r1&%qSrT)u)&=loI8_iB$p*eoH|Pdv7Le%$Yi8>1nHS=_x#*Pf zv&|dN6^mfr*DK22@M|wHMagDPAJ{3vApH~Ks4;x-3D_c9Q$K@b1Jb(YO@juxng(YN z1#Xg`YbRJKt9EoF{!M-L#U=X``=dLGztFX z5TKwH2E<0tx~2qf9RVx=_zy>b3kDWI`B5+r<9>o}qkw@jSHvhdCo*>CI7&?#%|*%F|Wcw>5>c+?HMUOuc^L!6$_h9r$z{=&D-JdVFU?f|L2mrxTlE zdIF88ZAS4vpT&$-m^x5y0x)DKi4XFrn=KAhjLtjxg3Dh#0rJuGiZ%|DY`^^p;1_q2HGT_)Zb29>sFjHExa<_ z>CsuWZCc2)_-(3|0#{?01x;~_ZOCi?xZQ*`T@jwdFf%gdD@K8jF>Di>$1HK|5?VUJ zE;2S387N1=3>3Kg({~vk2uiqqy>9d7jzNoS7nji_pbrIGD^Joiib0cM#IM_)9&&%9 znO>r$!LO!Z#Q^2}U#QqhB$f$0`Ib@`g4+|mq+tPwt>)6$2Kfyrd&>yBf{eOQe$j5J z`X!UZFOtSkykc;zEcOn~L5?#pb7ae|8CZoVU75;ZK?))2C;@z6dmm>slX)@{76;0+ zGL`r_a#%Nz=c3s%?0ThjMQ>=_ex-pJGBbF{dG zI~Z69pzxnCuy7njla)T!A&MqtLu?LG%FYlAMYTDGXgm}i%Z(9e7`$kVwE{UlXD;?b z6#pDk%nbE-%@liwDeaz?eKo#K3Q;PhY4nrS=)9@~4Bh!f=9nQ`>%x|K*jzc)&BdWj zN2-rV9M4A>BJ<7Up>GS+) zrRl->6Bxuiv3`WwkSDf9M4@0WObgi?FS=nc#|yiO>padUN^umzK9~rpoJe+L^ht+ zro?~ehxq~t>`@kq;`I#}v|EW;DSF1+owiwJ@Eh-#ZjoWxhTxoP-72(WJGv5Es(`(2 z^E_ES5f{G%wk%uqG;TMF8&CLgCFX=S5C#F*AxsOci46*VLn~Qdsm{-Av^G)=I{k~q zwc-iekXOeI5-|8=6{doK>sy8CfDr!7)uPbn!pb0QC*m4&4R#oi`Q>Xc3ADd~HEXej zRI>de9VQA-JOs0pkvna8QZ!BYTG7z#%6ARH(58zE8(3KPOwZ51P2J!xKx@%m!3&UP zA^f|c*agwXZ|iz&o2Xga25gurWvk*g3sp96#L&t}mw$W{CW|Be&u+!Off>uDg8PTp zemu8z@b{{hXul2%e!=FWeMkE*SQI9`YXAGjiIC;_-(1kv8m`@eDT~5&2PQ@#WAzyn zcpw^Mswjp8SdQ%4R(yH`3M|wM;?#>f4ZWW#h45iCCYt}Hc4J(`k7K(rw6qaIn;691 zRWLjTJC2^lVi0SEe51XhIFo?1eOR89(g6A7lcwoMrYS;x#Xc+*N%1}QV>Rdn1z$D+ z`zRva_k-A4WaG+TkvAy(%wI7j(F{{^2$5J3iXFz{QRT0PF$)Q7JTpX1Zki^=uRe^` z0tqRH>(|E1t4efX+7ZkYX&^j;h{A=GqnJAy$LA>KD*`d^81gSr;~S@8Cg}A9KPX)k zudDcp5VIHUFYlegB*}=VPqMKB5h^*@dy#QLXHkSGLf%<4ZJ6*6okJNPaQOr0F&a{u zKb42Y0U*wgy?`CYK?EN!!nR;!xg}`++=(`nqI|IH3icb4Fu01HL3r?MOE7EEW*ywX z9*ZNcJgLO&L|bH;YHYb^c-B2^51_%edzb)eLDXW204VTP?qkwu4(03DV`?H}mNbaq z5#t9x!Wa~q#M0!wm?6o$psTu!f2;``7H!}Uv|!d4nHGx@iSRiVOH>GK}BXk6jT# zd};_YMsJH?-7vO|j5RLf@-0WOPdIby^p7Mn?dB!!i-!v8pQSUn?}IVw1(LIaCogsf zk0cOYIXa7KQ=yueq$1rE{%?zF!gIBc*o*lz<#L?#kT`xB85$f^var4F^*lG}C`T<*XgGlw=?1q?h>|ZnH-XKkD=@e#TooAK zR2b{!f=RMT-R0|*!20YnuzvzmmgG8}^Xl#9%vf~*%1vU-|52^Qe^u*5(g$ziqM_Tp z$iF~oEEmY)N#fRb;bsy{51Qs`#b#QS|vkz2~)-3EmRtvHktW#=`i4_q&-}Va^n0 zsPtFlYZfOTa7|+juem10x#sN!JEkxdiQK1p(NT`##?=s?#uog=8vAKXS9Ql3-n5(P zz)$b6R6l;u^xT_rF1|#406PuY(}-B6@bWaKCcgSd)q79ZsJHOxG)9-f1X{Z)N^frB zsdRH3LtxcWTm>fY!40qrJZSp^fy{;5e_&<{{dg2NEkEJ~!r1Y&(tlyhNK9hz+^5$6 z{QWOFWC;Ea^%p-7>WXsf(+pv146Z8Ez8I;PeH4P93a4A*7Qi%pE3P6F@_lOV2gfpr z7B>$^VL>{9dt)r$^e%ik&eWHIRsh$*#VFR01@JH$j+Hh{GCX$-pJoHt2=KYg0&7om z3Rg)>QJLP~1-k7zHn24YzcqQ5$#`%;Q}0#b#v#o{zdE+|p{i79jN!`eUU^+Z z3MDl|${}V`ot^nll+pM63I5#guCDg+zC#*;R$KF*uoBhG4+z^vd#oSY&TsP2tDPKo zTr71kHBFq79~*Sr)U2Z+B{l-4V)!C<=QO9A^&o z<>6maKjx=AG^e(ktdLOgja2M;{;{d<*k0W5W#@OdR(kw??FF@h@ccB5bwAR^!ak1; z3wD^5h^+~@Uia2*Ea4Dp+-O9SNz3|TG$!+FOXJ5pdaevNJ<)8(@nJ!zsb(X^tvSTO z3;N@@9=S%nBLH%6Tm!>$U@ndufHUv`j;phGY*?z0x*M_T4ARHWaw5ZS#59V{N-%?|$za-;yT{ zjc_9wpU;*YzJYg@DKCDJh&$xBrsH4I=!;e*UmdQri7MUgAhyTVjmBwIj@`b}>{Z^J z@Q^$pi1(%Ces`v=&9LT}+uh-S1R@$U&Qq=9NuSw%P>|v(xDAsNp z8Rd=}FwPP|6fdiIYWT#vG1?`I{Dv!OyioqqCbm3j#OJ|umW8IkyT>4>KmTaQ${JIB zj@g_Z<`Yfe1-*3dKOo(Nc3MWwXAimkI&!$-L4V(gDdRoN23i!i{eU%YVxg9A>7n|* zP_DPAP6Ey?VNd^*CuVr1}7<bhKc#2^ z)zveOMba=&0>_)EzqCK=iOgN2J7wZ4L3-~0;gB0u-DFMOu8-7Yos^S3IwpyFt~lQD zxJOKj=N{}Q{??)(79OYKy6jzf!YGZ9rl^NIk2-|Vf(op?`&8dYakgHO=@_8bZ2y}7 zU`lCaY>+VPD@o7GuJ=pEch5SnwEFKMp7`5l@mNQXA{z8aPX|6R8i}$e@6%!`l}*y* znVDnv+9rOi+$(cXxl^Yp3b=Sy*XAehiL|~YgX$Odbn3E6lqYiio3zwM!iw!oR?8}r zW;)t;kCB#7kFh;enQK=Ai%_!&=Qk_DD)R2&d}EGdPUF)1^8l0;hC!Cn!9;%(3#vc2yF?d!I*A_c*i}Hn_!uyiAo=R3- zqt`Hp`S9L%x2Iv9yOkXeiw)Je8C)0af)Y}=)|`Zp&(l$Y@qK5b4n|&E6?ND;ikp5g zp5>dL+Tmhu?L>U+c?>e{-~ZCmqx z1b%N$FdAtlQ9U#gwy8ob8g8Z~?eR3-D>zZGq|3tE>DU3fRYOb2y!lPa#&H4@xDrIb zoito~cEXBbQdGj4veXo~^g-#(2f9-}>!UKm6-GyU#Fi!8Y-kRF*J-#Gh=DCM+{yo* z`MvKRduWXYVk=eI+DT2yOIdF+46V=SCFfc_cj~cTs?U7xmN1ce`~+P#b9??khIn3rky3gW+-wR7 zL6V)hn=(23B!fGM7Huw04A~^pE*|wR{N0VsfJ4wy7LSmc#Yk@QnBqB}Wk|vjS^Ohg z%`K|QRn3i*muAI-^;$Q1R5_=e42Sl2D21dn5}78TmsV zR8*pqz;iS-Kv&efxZYTeXz4=Ddxu2Lxv0dnL)3f#HFqVW66iP+_f?*>LRb`?IFepdG3z;Op65zuu1#m-4Ue?L8t0 zFId!NOQsZcMn^9RwrD;ZiB@JUI|YJsS5EdkDVGIc%gy%Sie-SG9~ds9vxK(yJ~-PO?%eA`ZF(4*K>DhbP8+>=?}MYJhgl*Gf4J7q z;(dWqI%&UgEuE<;Yqr;?@yMCA|3a3pu84;N*L3OH9CT9o*xQeRP{8@%yt81eRXJ?W zSgX#L+=V``H%~_=B0Qp#5CVP(kE~FHK-M~B^FIi}hf4Scw%0-PTWE_pC=e8cAY+`3 zgpMI0s>Mao!;Sx6syO?N2b1a4%-gLZ!vsS6jF?)HoqfuKzDL_xnjW@cV&Hev=wyV# zmlD~0cD9)a6+vyB-}~=@)TTyyHD~Y9_ArFmzDsydc(Mq>FQqvOR<~QFA_r}THR#bx z0z1!R(8>3@|dh~S(^2^OFN%(_p|t>@>Ndn z4*B_~STjwp{<)_RjZAi+CN?V9*RIN@g^dahR+gTAkkfzFEpf1tsrcdjo^D%a?~&3v z7s|+i*SEZ;sEO*!S6X!oD@%f4(%amD8g`LkojP5qwbG6`U1Coe(0MLcFio%Ku|}T< zjXI>2X04%SKKGZiFFx|6WOna2@!A=9%9o=51PNW)W6@O!V^Yd3!oA0${q!aKYK8Q5 zoo2ojHA;DHaIOk2ZSubd;IbqpfSXisEsL9=HZna>j{fi9y7XrVV1){9Wca^V9?nq3 zjSc^upZ`2K+^C9cvt>h+)>=J*wPsJhI*$4L?@ha^*puzw+LL7xoE(w6JM>pil^U6Z z)=8o+^kCiz@SuD#q(3eZ7gA`}E{32f_b(3oi~s&+6#KuEGf1qYCU>NYG1wMrphJqx zrNW@%%df_JXi=qpYDF|nXdGR#)C+XiT!;+0_aA6{34Cbn?b|&qa8@_=ry5qZaPZ_> zHt)XUowe(-?0mvYUOhG&z`um4m6bp6cl;BP|G_hVCTGDKy7ujsdY7#xKf0Zz81TX zio(nb|ICs<>+;t?`2*+Y0td@miOMzVof7NQHu~Fd&C3_o83^N?IFY2C!^Igcq53^K zv&RzX6AGs2wf8@ZIMfka6mfs^n8;yo=QpkB2s_bXuO(bavKsd*K22hInLE*}zf^Sk zw`8cYo~B&E@7Ai@I5GYMbzA?w8^0f6TFY7-UaqQwwi>ts`(J7IPn7$#UP4eX;bGZj zRw1ze&66$_y~OFTZrerrnoa8reNqbosbApyNFMz~bM6EfqL3IU#l5C;a{l*uPD`?FU~RDx#BQJD9qo zqnP`3;it_jR!LlLZ=&}OB+7j(T35c(h%LBaXzjSPg6Syy4`S3)rZ!zC?NocacFI-p zP=ixgy4ZI8Fus2s>mhA9=TUqAohyeWc*7goS#Cc6zF)aN#lvM$SFl49<&Uhmbpd-w zb4Y)x|F`jSLq*OuqHtr#IS)FaUcM&uK;Zgt{|2G=>#(zl6J6GOguss!yP;|4nbHT! zQQZF_pQ--c?FVVs4gh1 zuUT_(iK`lePfa_)|DYXGj{VoEF-%W7GC%01OlV3; z)Q^Q8$+ZXDpZLdQs<)!Q>DsW?1#-dr^t1oX`UT~VKj-DvKlih~!*$tsjl6y3^^)n3 zn~#0AtD9x^q@E~!-f;c=HkL6)VWvJz(`iV}TKQ>oPs?H*E8{|m$j*=c753^Q%O$*| z46!vg$66v95AF9`p$Z}$F*FY2KK*}jEm`3KCgNyKZ7a3+*;r_ zI{3uG#d4L0F-wm1-0R|CXYR)2h-(>vLPqtKEZ@#L$4B(`4aTJ$w}fEpg1Qv$DKo)? zRbeDTOc3pzs*cYKi#~C!7U)Vx_3|cU?yW8Q9`i5^pAUHqJczwIufU@(Ont`}csY^3 zL-C?P(|B9m8k_vS(95qWMeb3RH_V>P^u)Gp-2=ApvP>^0N7o3}-cV^5{)1rQdTUpu zR&sW*X^`}n$}n8J$+5D8F@z+yM}MU&%kU^8Ts`Q~TC?wJrtp4Ln&~A8ThtL-wLPv@ z%sCIOQQbZ?jg-9U`<-d7&XDTEyiJfs-$Tp}xkz>kUN zWW8pw6+S?>+Gv5EcdKwhtdn%rSm0%G`KfjM4QiVuow64tysU_%=8+Qn>YGBN1``4; zyuETRbH7Q~g0-un&V&b@i<;UdTN1&P9BRnx6!V!e_j&4m+wJ}s^I_ann7+7TUtMLk zWf7OY(LTQP1X(J&^R2gPi(|5drbFNZjKUTS_7@!M&2>>u&AGGzVC^yAn`=jW=FsXI zTg^G#h+F%5I%5lGCWd|N6VYk>dw5M{+Q9;f0G*b!kH7t5pg&LBpgN)i@i6D=?l_ws zarYfTmqa}5YtNAxUnF-%@!tvt@)2K7CnNeKiue-$fA$ES^zd*tWhCD^Brp^)$e-Ez z1siY5GQGs?I}}xviTJdCvlncoBR=_i&adE9UPnZvS-)#Hynxshvf4L)BoWav-B&uI z!}JnjmtrAejK8O)V60O_m@OQlA>R+tDVzB(E7||H7FC)(Js{BW+MFz`6OqgR|KuqE z(I?tdwq%n~fsM#TM}*1p#XqSqMQn1hZkI3cLsUx^(dT#yB4P{EzWO{VAS0L&_BYA@ zE{LdQT&yu3^CnHi20uiO4d}&K?Jx&X$@(l}mZ6AfdF0T{u@+jc)~c0u!-I_5T8K%H z3lXs%lp>z>07S!RXT(Z>5lLOeYs|hD!DUA18@MxbaT!e-oXg(ANlJ7?n}&XqmL2aq zRk>&0dT8D~?Cw|Dp#aki@Fn8$Q%Y$WLr+$~b_3j24@?ZNT@=*dd@!Zx)sL1vLF*P@goC0%vW;*VF|22_D{K~wFvK-+yz&f8GsM$XcGr?@ z&!*mDtr^z|?9AB7PL7WsBIvjaX$m?R;YQkZ+gSJm`a~_I@tmKY$_YU&HS`io)%!%z zjpep1wP~6vJZgknV)$lw*9hN$t<;A`#&|IGb$9@HA0`Xa=HmL0Z;UI@D%5u-Yo_aP zIW|umV4E>+t+Ly?lkQ;XfvaB7mzvt|XEs!6p%FHE@_x?`Xgn96uire2GF@3j9}7`V zHJkM8(joFG)3+^MP_FnzrLLG$zCg`2e^juul=ufTe8MovF-`S?y^XS!$nYGRi(0a_Jr!71` zwPdbm7<4qk^%Pe09dFkVZ)_w`+}e?u;6b603v*Cv#!&7nBnT>rRgEg{{x z^Uz?l#FoVEhU`i{95g}1LU>B+u`;Qd6Lc)FxuZ~tcJg_joSEgb&}lx~)9_y7eS0%g zv)!3>`sgHsi5Y%DoSd{p5Me~J`Y(S-L$W!pEG@h9>=-DqDKb>v={Oe}n&Xy=8lBEV za$gH7B@g!ZOt(arG|1Ai+?#NZIX-_*)c0zitSN_=S8gbWcG9SWa$5wUX@-U2p_5!L zsl%;E*+L99n&V6(&h+eM0qFZ;f7&O9H0Go*DWS-N)I|?nT08CUz@bnLPg25ehMm|S zQdslT*+yn#TzRTr2Ds0>lX`5j=$_E2Ss}DJ?>GOJ@1i83k* zrMXzA+_W)8f%)-U#&QLnVQKH7N+Az|`?z$z%G7ZljI=?ehxNzL; zY1l@|!qD#58<{fk$x(qX4iwR2E&qiOf8RV@1+cGX;v-efvZSnaoex*`-nJg&I0Q{G z2P9feZ0|)BH~;6=Apv*=r7s@rpGXdEw|HYwjJ{kQsUlTQ)iS@F>_@MdzEsD)<%Gm{ z()W0NPoC4;v4?egyU?_1XR^(OeYMd$Y)aPhJCxqutW|He>$JY9-ew9d7vP)NlF=my z2kWLi2$LO`7@pU)?)HJZ>>3O3LKAY;WGYcVqJ51Ik86p40 z;#}=RrAwjRPm@_{Q?(+n`Hq$%M4vwdEe;6LBfr*VUT*67|NAIH#NQhMERc>W;yW^czrC5U*y6P%(lT7C}@nViDV>-EnISp zAHh!v=9Fe$#YwQo26xe+lbIGP9+_ARZ|$Sk;wQ@SH^f=y#?P&RzZjHq2fd1zxtcn4 z88*0q8i@I3mP|E>q~6wB#Cr7V>K=(}W|@4`I=g_G2jEFte2La^qpL24nvH7>-+z5y z3;K;5rnY@c@9WJ{Sy4Nq?nrwa^l`xT^!?8($bP)4uygNV80mX@&UA^i2|A@7KbezZ zW)kSRudnt_#MpQnX%AdxhtHeEofwJ_yjvb>)_>V@7>-Z=9xMC~)9vs@bEvo1;IYE3 zc~x(NX4F549bA5NZ!-HZrp~I!>xmsNP0clW4u32{-dW>-%NRS(Zwl$Ze0Y7gT}x6*%?t|iShmW(d!0dRG7Qd2Dii_jb^a;mBC*ay0FAI(9GK{U2h8Y94KwwZ2XE2L9<_?jR)U`$a7%+ajoP(Ex_FgI^icOT zCWYJ>>#Wmku(!43ks-&>Z2A4y%8ReukdRAE{+m@sKC|TQdT7uy|KsYKc}4O&B2U!F zy12TH9P%Tlhn0YPV)%SxdlUX3n-d3f9dRS{$4?I(aTQ6wA4#lOGeP-2veJNh?Q~%e+|Dl;dW|MR`3WfQ_Qj@_I9&m!B|6xT!Aw+@B$NaD6xm3 zHV9vlThRX;D3BXm;Y+F=zZxJ2^*{1yd&7}z>+q|2qdI+a)Hud4Z4n*}s^OPKxb4ix z`k4QbFIU)S4=@JbHnB;O(8d|Jl)XoCFAZ*K9A+-gwi$P1L#{JEOI*r_B^zu*8-}5F zXe^-vF0EWBJ6@sLB9SXsLodo;^`+H>9?2*oEq?9=-#Ft+Y-W1%!Be@9Jsj_>@FN0N zuNIR_Se#v$!99583?uo@+9>oqpGT|o@+n&Nez}R#_8<&qxaO6e|}YaTwnT_HAlV8OGWgB><3i8x^K_AtxDb+|mLcyh7qF)pr1$NfT^(Jn3-F<0~VHxnN!| zX-}w4M{hhySm0wk336WOjPVv{s;WejY)Y~Qq8&&q-{NBaF3EI8OVrfsJNa$_4Bn5* zz;k}YgL>B!zqK3@OVXJeE#`F2%_G<`a1$@&`@11`bY#xe-jRX6dk)-JIO{}`PSfy! zMOQjHerL)NpC#(byUs5vFZ&w$eiJ{H(<{r7@aW0O-A95=~XGWW&sOtOWyOgb0AVn5mbIlmdREIe(xSsCd5gk-CYVUo= zkEg<@l)2IH(h<%Vu}(rj0SV@N9d`ftx9 zrR7#!4E>dsQxBIV;i|Sj?V&9gvp)EK2U9;>nzPR559j6V`7(_TPfq^!gMBwMjg=wJ zKA5=3M`Bto_Vy%6Z^<#88Y(PVimRieGmn=dT5TOXVr`C&%aSB!|D}gBqT>L6<(T(_ zg9Sm+a?XoST{&IB%ys4IcAZ(tIzPW>yY@%QJ;DjI(NwV5q_gtq1H$Zts6!XCWpn=oi60L$xYVz z%W>b1v2)wJ zs_Ws-y@*pG$;+SeoEM`bC32j$=0ebZ@ZC9A5+liR+vaDaFL&bobgW+$@=hdapYvYU zp6T-#9sbZ$;I+<@ZZJ)_IErIg!Sll7=`0>OX}0Gdsm}XI{Z>h_53u^#B;b1Gt{TOe z)eH%_zht#}l2O82}hB@6?r~QG_S*nh2rnq*00k4@#w? zytS-d7>~qU!{V}jrY871mqMnCeM_}%}EjjX+^e9QT6^u$p;|R%UlCX_>jKtqn zyqjuMf=NnqVw#J0M{{1?vOLE6SuD5B=#m~PE->N>clS#RaEW9Dq_^`rcsQXLhF!d z_NmDrn?XV<(FH!%TLl{=^|W3UF8E+OuSBh)jss2dK2dJV_3HICdifU zLK)B50`xczNrsEStE_(zYwmO1s-#tI!B->!vnL77E2O}gmxBN;7r$gBYXVVHYVZJp z$SQkBsZ!NKvTKtXqB?snOWC{-z`<++DBjCa_Iana zy|EeSqU;^cfjD!|oga{c(#bUe2# z!t}D+CQlc^y=5S7n7r);`Cx6~B9KIP#K1|^E@>Cb?V;A{u>DM*amKz(-@JLPd;KQ)b(dDn71eoTBT` za9lUicy~N`1*)?yjT71kz&oqF+#^*5lR8V$pvnMmZ=uEjo{?WYAXT};#kk%iNk%O; zlVG|U*+W?VxL**{G>C|eBWteg7i5xGzmV-AIKU4dIx9UORYle`Xb^(*Srwdr7b~sA z(9Sl+NQRecv|B{(oet*BGtB2^9ckPL;dv^?(2eL9=n^j?#U*Ls43RDG4%$&k_A+-! zUl({ai%8Sb?}DAY60S*1Muy>{#PNq=LCn5UQdilIIQBkwkW$+OHcP?4N%bk5bS*es zm#tg-(U^FHEu1?{m#6GvS4hoY>}eP^TIRYiOO^TNOrF`hI?JW(4ShMi6Hcoy7)her z-hWQ1IL^1r{ENKnMq*f3N`kM!*Wr&pGK!P`I5@&ZleNV@e|t+HhRZmp`*)U@rA7SP z;P}ap1B;4a69i@A8@Re-k!B`##Jjl|V&X}@UfE(B3|xdu`S}5w8LvAVtp!(e4slOG zTq5co;l>ahS-vJN5Qv$eW*A4r5P?lQOi?#%1PKlP&Mpp9C{Uy5xq;xAHzc$LFTVe<5+cI;vM$L;S;}VHG2H}L;@Fd7vT)mYcP6Os z{$qptR&0m=?=`rfuQj+rh0in+l#9h%eS=d{2S~+SY`5pYP@HAzWIZlvxsatBV;UgB zD*h)C5C}=i=K#6ZZcN{RDfX2hgnJ**iTTJ>6Omyg=TZuodS`aq~b=6n78yE=(|t%<_|cG@o7K z0d3YeCmI1&v>Yy8+hZkoQPlm1u1i-EH|8?uuKTexT@bHtlM~R#w4!C^X8AX!FN4Hk@(-^$- zmMCcmL5?tt5x7S%J3BxY<{r2_PMd#&Y+i_r6R0lelFD5za` zu~JFcrGX$r`&|P4X}&8~mf?S+{(-(yOpLwd9_W21@U|iXHm}~|w=?5Xa%U>#hm-DZ zMB3hQ@vLA-^p#vJB|l}?Y=unbwQJ)4an?k98ofSAd_`x>D-bJL10P_HjD>agx88}l z`TZQ+aS85J|LW&Kf5JmPz#)}6ZV%y#7^F;45QBOS>7PTScOIz+Cv!@B0s)tD{zKVr zZa6lnjn~W)xBm!j062ZuYOAsNJ}aso&Ya1uwut;uwrv#XR?AA|?}JxiLz2buDfwh^ zcV*^wx3p#4XiPWuBtyCVQ2zVimE7i#wY=`u=D66QGpZQh&BLe>!jH!&>s)21z#myr z!4^nRExN>aD8*Kv^JV#IFSJ188RR`sEo0lw_A)4wk3?g5Ykz1j!}In&QG*{{*Ip*I zdO?R0legAAl?N<_DR4v6jv_TA&Vd^6pJpDvw z2Zz;{rM(=WI$b`XOp{|z`GEG}W9S259tHDZ%tP3ZjdMt9`{&Sy^_M!~_t3|=!iqcg zI!h&HrL4ElAe3@ySzUAO0KC}gA3$ngOySR%8vlSy;!uY30Hrl^oE`|K72fB(eVTWA z-sUTDd7vTq><Z#w!|lit(_<65%uHAi+^hpO>4Qk@Cr;1(h-*P;CQJ|#{#d=*}? z?NcBn`oo_2lt8c_6QStvuA#O37;MW*m2&>2A2(JHhGL?E2k(Gk>IFE?Yh^8gWmewU zUl`X|3jjbqg>vQn!=~HfCqrON?PEyI9mdr3Q?t4ZcEf%LYz(*^D~-$GwBjmWQ~_|7 z<(Ncc5Z#D4&Kp+)14UBqe+a2b+Ut{#@XX_^ueb*XJY%H}ns>n6e8sMpv@D`ZE<$P;-;kXHW1zE8*TvJv4NPNI{XFqH2ZW91?szpDIN#_67)N zs4EI1=(_d81JJ^I(ck61n8$GLtB7FoK#U3!F*Q{&JnP>M*S&GpCue6X8zXOoW*$aj zyExb&2p{95ypM_%lKF7AX)Jy(X>!^1OFA$=Fgk2PZ1iQyVG+?Wi^s>@QE7T z$?$TAECWucyio9xk_-vyXpLCUpsJsyg_O1;PM@Fdk(7yDQMWTx^SJh^x(BY2rvoaN&!0p|UU z%YP&>0c9Z`E)0# z` zs8jCWQ6~2}n926e|9G{0Y$&}Z!d3PdFM37rg=t&HyzhJW1dn6hS2=YhdNW2EM#y^d z3bH7mfOl*2aDT>)&s8}s@y3il$V1r<%Fy|x=tdn5)>#@sfZ=!iq3qR$^mnx~%o2*b zE56hygq=36s?z35mYKp)WpMs{R4;G!kP;_b2efMm!XQ_J*rBHL8CW$0Z^#oZey=}r zlMGBhB2kBiGSF>&A1cUAtK|XvC^}5VS90J2+)@s_WVJaX#-*xYA3@USj|?S7`@P$^ zhq9H8;O9S(X6Mj(!Nt1;5=5txzf3uM0ART?)(m zM9q5BAhlx&I}du(HLtNJ*F#!T(OjF$9n+M9?(DsLAhoZ+7?ynrV*tFE!7bK!Fh85! zzvq9LH{i^qD{d>u|1%p;`bmxvrl(&kdxd>-FC?SNtBa931Tst#Uk+EDKxPp)#vfcb zs1I6F%~OEaDz07HSFiIil@~(&fSYALAd1SaORtd9-omQl!`UNDzioX) z*C(v}yAA?Z86?Ec)SKMIs_SzAS)T)&@CR>&8Nf%lrl5M0_!xaOLL2Tc zGuOGQEqDjY!u*t&MBgJZfn-Lf`_sFU_CSJk_{8=}OC!UDY7tU=R|UWZ)rOj1nqL_a z|9Sdr+>c69|lQ{k(%WdL>@c19?qw&Q<_80!Sc z-xDIuVvj3ZH4O6mihAy=!~>IbPgBo(suG_Q4=ljys|BCE@XGVsGAaH)(h>Nb)+@*x zx@RI@_?2csR+zT{IEGL|as3avBgo91${M~d1N$J|6MP92n&Ru8Q-jZUzz7)4Je44& z*k+zu9uX`$AgOWYNl5oUhjl5dd~IQ7&5H=ynKXcsz9RgCM%qaKvs4BGly{&g`y2g$ zDpti@CtXfU+xe>Kxt0>zzsvTV$9s24ZlB&hjwElB6y5r11&UX`HOGb%&*RV#%Mq3+NR=t=FgC!nRlyXIExN_}Rq~hS)DCkfz4pS}%JU6;d-0S2D7HN#MeE zdQdEfU9tSCvKs5wWNxP)V1%(?RcKmS9j_YjnZcmqvnZXWQ9> zk5i?782dCd=&~aY zK(YqTOAX#BcVOGppFcl7@O^l|W$ZmRlS#?(T0{406NeLJ1IIOV=U-s`k4XjzXh1B} zh{ne$ZF5eGvuHz*70!t6*nv`p{rmugL+zAiE78D*Q7&Xr>uwAW;4;IWPvIwZtR_J% zMWjJ$Pz-RBAR1&r06+Zji^b2X|L||ac*!v^q1iZDn-2f#4}baq(fRJ5c8%;OG)P4e z=;Q2Zz>_*<`Eu{F;k<*;*8gtAq~;*B;lHE$9Tf=5<_Hyba5M;AUj}yGg|5E=c9uf{ z6u8y{i&rdQlp)Cred0c>VOn0>?FO?BV=hTcr4`|0gb(msBG8WXO-|}J&Yy$e;zz+T zvmNP>hTkasB(M%hf7{&80Ji}SIP8uXp-yfMSSMDP;9w$0#4w#_in<7Lvx+>B*Cd|+ zI=aL3Z5*{6DlGCM>a!&ktIrODOl=U!CdBkHL(S3bYC5E?`~;Yox9)vN1(+(A5HLUf zphD)fX*l~W9nys61EZaZ1xoJK49H3ve(K*_BM#s%V4b652rRzsDnq{4B$Y8BpRXv1 zmVK!We*qLu?=IN>7+?cmzF=QO;%3u^o<0j$X?X zSV4T`vjX|3Du;9N9W@r90MYF^S7<%w_3ty;Vn=ji`UEbH?FID66{g_>K+i;a*~f4h zP-ody3E8l#T5Ea3i1--c>SOTcKqI(-9UlkDkc*Rt0RZg+Cy?Wd6z2q%-~!IRQ`>ag zJ^RdtmHU@y|B3wsE^}evr8>7q zzt@+rSk=pd-F-8*98sph8(!95_tV8xiZlCE``gXRRGjd!Rvg&mCt`7(3!i022?pY;@DV(!`0wy& zm;-y+5lEeWIq~3184_Zfq@+%gv8edS7D)sDsi-fN-F4!!8?3SnO#)z+_&aiWGLwB= zZL4=743y40HjM+&H^cLNru|?V@Lvo9QquFt(W_GUnSm^#afW*Mi8yHJ&A;L-WkmNp zW3c;3O}|K+AMoc5$snJ3Dd{ff4fI@)c=hMhyxceK!}9t zC;U*WSl)i1LQQVZ*^Mio;_JM;0)9XFg2gZDazc(KHIDu2glYIk9}YO(2Q!XiXCH-h zl|YnqF${+l9u{P)cj1SB6k07M@rt{=H8!f=KaC8jenl|)|47W-@O3fMWcXdo1l#V! zF%z(P;*jarH5W43Z;nAruwtb*h-EhKE2DKT4g=sec)CW_LMus{6MFJ}u>9kZIR#Fg zl$e3D_g%PBcdl1>ALZC|u+La;DRw|=GBUHhj4_*sbk6r4Rg^mqbclDjH^~21`LF$E ze8-fWT#C>7XwPO4#+C5kXlSgZVkU{jH(9>wJh80Eo#0j5HEm+DYLy5p?w|At^{v67w6t4 zKzeHEJK>}Waq|O=iV>2Pa?tE|eEcLYf+x*hdjc{>-e&JU0jY0-H&a^+j_EGmL|Nxy z0mX~m_al=8*}%Gk8t0Ivl+UdMqSr;R6a-ftC&83*`|qIZjZ^06`c~F{G7HzK){V5y zR>(XoXu7e9mhQ=un6i~SpRrLSB!dr!g2P&Pr7lxSJKKC1r4+;6{q#;bLceRA3N&>t zV1IL|%6u7HM9_L-Z!Fz0nHF+X0(2t#lq2whRiplX2&LgEJTuHNKPJZOG4@kL;yoZS zTJp6T-;G;7J1&zXEk3<-=)cjOr{pP;dyT061ncTL-rgKvrGyM($a_43B^Nd*hs~-h z=&UQ44B673*e$suK`U?UGa3cY4YM+yTJ2{EU9xOa>678bpl;^L`ZR z4nqJbW?xH$tdY;y!-*hTe7Tul|M$)OOx2s6FmWwzl5t}MV=%@sXE}>q_QC4?46tIn zROS%-ND^ddZQ>0BP}!ECb#P1*KX2?`@pDhtD*y$=c(Ni^@pICm3|d7T`$ZD4)_(@+ z2L3Vr!mh^DGI-gh&1H;w@_aBsC4gm-r*NC%UFnBo)c~430^e`nGw2;I(GABwh3J=TKc(B_JMjLZ-uIqC!U8(f~G|DjTD^*cr)S zR#Aq1HyP6K2AELWYIa&vkPwoM9v|G!Sk5wn=|7B?pN?XZXi7Nq(H zIRjN5Y$9g$x-VIN3TlfW6r;*!2+{?M`NtuOGtf7HNi$G-1h7cYaOK*oS7Oje=E27p z61c&@Fs3ha?j3x~$bX(`NxAkH7{{MAL$d!Nz`?3UQj!+e3BAiN^d^oEnnO!ZRWyCj zY@ge941|(`iQVJfjNU0X-kQ4d%WYvVKF6lL*9_Doj@Y!+xvBC42Es7 z##rBe@XxtH0-f@72*JwAm-_dw^OD2JTU7-2KW$dY3z9s@3ah06T{rb(iha|}c4d2@(?bOZ2nWDGMsO76ADC(A9`R+n0 zZ;CBqLwbg>oaRj*fjRMe7BHhi=F|=FY3r*|gTP+XKR~6m??9!VLq88llpDJjMApGXH|9bXnZ{}Uq8_B2HPLMpp;8d_vn>71>i zhN${mWcv9#auaz5boO7KKH2c4VSurpWC5C!0<>J%alta;MwT6UA%J-R8afB>q|U)R z>|19bRl1S;ocL3}aS{0`%Xu|9Eu(Az7w>=Mhrmm$I}m4n?}}_AbHx@#71R~P*>_hm zvb8}N4f(G6-lt45G>Wj$ZNU@I5j@&qB&DK-hH_TFA~i3rVf1lq(J5^2cP-1|(EZ76xd^otZ4qlD~^?^Oe82 zEa$z0I{YGCWo=QIe1d!ZdaZemQbnE|{2nTX^GJG9{ucua7RX986GML_#-Nf^&bxcgL8qK^~f8GqKq;lNmPbdhni#;0`oQ@i3bjN8_E1 zyvYEj{P*ldc^=Sq%?Wp9|B}7{z}Jqm?}qWNWPTMFX!xb>XzE5p@OvgUs8aR2z+42qB}0jR7U{Gl8TGv8Nra%JGKQ_`g^1*V=p&2{uK)zQq=Dt);`MX z%kp!W__!0pv9_D-p@kP++cu_@H zZ18k2P;w(1NX+K)=UmAQ{{LMf{b0m%8I>14Q<4V+cpt3!VRL5Xla%Ele6yq^^4Osd8bHqw1Ayk`jBv5fD=+}*%!wjh`PCn#}j4hZRAo>y4* zC2Q?1E8F*uSNIC95%yO4m%Me3Yy^ z0wwsKRBaR&5CCs%YPA8wx?)6@2;4+`k^bF8(0|y-rcZ2ytMC0_2FxaysK4@m;k7Hd z70(wJ^%SrdeG!4~uctg;vsU2g0F&(F5FQu^3%i4%w89sz5f~&+q%kvpN$exs~6iBQ@bxL5bXJ;!PsYjX5kN3YD726_g8#>11pjZOA z>z(oX>P!T1(2=4$8@FP>kT!gFoy)=5!2=Rm#W_f-!!29_Jr<14!rLM?+s+xSr=q+l z7UVb1H)CcGRftB~-(Z_J;o^f+kl3MX8-)iOUc68tYJb~Ol?Mt5lIZ({_X8IInFPFr z8lZUqm@e+hT|mJuUPB>(r`!8(hAPVuso>^#AOAjhEB;mw`Qw^isoN zI*{dJC?$5u#3$Fpo_1;}OsKdx=%T6&K*tW>_wA$a?d9~Hs*cJX$23*U)>m|Jgz*mS zapDy?*0fEyCiUv*=f?{IF9VC6DQK%62SJMS9rzs%`dBck-x_>2PXs%Eaeg__wgKK# z^dcDyG>>%w&*o?EO6F!MWJQ2$z{w0b>LONW0Nj$}=?V|8ShRT=76589O-ZX{7(`Gi zW}7|0*m0vAwm4BK9$Yn}xL>?+z$G8(y+Ak_yOH*aywhT{L5LB9mCi~VZGuNKU0iC% zFQ9Q1gG*Duzt~MzAyswk6!@)xj)YfDCnAy@+sgeKb>wQ+g4 z+*{Y-wJ^zTBjrmg!BPNeIP5zDbQw$*fR9rIJ`>opAqMfSwYGIb;_=TpRRc{VmjBuN z0MdIBtcmE|0q)8|#Qh8!u&r~o5_A$Y#sUjM*hBa`E$>ZIbXRnH;$5To%|);yXS{Ph z`67GzFc7w|$Jw$)&?0s5dWSiAZaGCf&8AZXX5Od4#8^06=PGD~0aBYbdRNLI9-IOg z0R*C=sgPr)Zlswz@kBR}xT5syJ7mG9NNran8Uktp*6jl}i$(~7NA%~oAd^h--XO=_ zaLoPoM5Rw5XlB5g17Lro?e9MET$Lw>hwJ3rTh~wO#;zx)RYAH7W+Wv;GdiBoY77d8~5+cg6XOPb@y7KYfwK8t=aembWYA zMp~GI*d0E)!e9#qxWM0kbb(_>=f=$D#5*TO)=LxV{LKb%WBHFS;>SLayIAZ5dLKD~ z?#sD_E3z=@^clOOfAq2b-R_XzfUPNiVI1|Jx0!$TFt9L9v5B=CD9-tG#pj&*p^ zKnC0!SCw$-EaHsrIdhH{Tjj^XS$o}+)AqFDL`2mJm4E>=3#@?Abo_#9Va4s%CG_5g zpnFPBCvF=fnv#zR{T|o6L|9!-WZRRIOrJ3E2;(D({NGycpMIlZmaTwPG8H|Jh%arb zTpZMyjF@NT|BE!D0^tPil9iw^7J%x>RUWrI}Tk3p=!Hn>D z-iFJ3EaE*Xl@|~S=~M<%7t9Z*Z_d)Hj-OEsE4wrwO z`VvAr+l~bfFRt0JMBiy+&=?|WZD`&aB}yrTeBr@ZZ*89V zVr&4L-Q3$UK^aHI(Q+vFJc!4i=G8p<#jw+??Q&xIW_kjOmHBcseo|yPeLQZ5D@LwI z6|B1?PZhCa9oUF(8%)*b=|1~5QMgkF!;j)X4f1Cso6`r7I$mS;dUcRCb_M?0LX(m= zZG^&Eytjv^{rw zeCrR)AMpB)IAIx7E?zUsTF_`8pku^1gR=3dyE~5<^LiN+pqplxzFB8z8REk4+M0J_4z7Ag zn=vKxn%*Act-3#&X|RfxDItxq%j78ZE|F;vZuO$$*Z5KBgjGl4wRIaHLy6#KJMvPi zOMwW5M|LrmS{T#X7@USzibX1ArjX-8U-~bRCZc3|Mrt`FYb^KVtqcAfWe>v8@k_`a z-aNI97!UQz;sKlQ%8bU_nUSe2{XE0a1w~eIzT4Vkk|Z8qGM}IT1m!gjS{pcM*Q4EC zmKU#S^QJ=owH!BFCP~8Hw2J$qdVsI3)(=5#XNwCK2b(iT+?M$%L8A}y{fBtPw&S%U+Gtz@BrH{hsHQ}I1#RB(IJkEsjK4l(d31s zb2rAO@S%&Us=gUVsR%}5vIdCMF5Ubf z(pt8M^UaQI`LP|>&*Ot##?Wr#nmv0cz55Wn1r&0RCesl+#g)(4>AOTrHG!dE*+zR2 zZ*YI0r|!O4#!u$^BNYVqRyJ(K@qEo2xdL+xAZs*LYzu#C$5*&IVobmGI?+OZd8l*ZApuseI-Wqq#2SFId zW%>>4lh_`Hp%Mblnox6uGA~g7q+;n{non^DL`b|x!OkSfTp4Y(2*r)OY)llUtS#%c zF_sK{VuaRuG_kMm$@);Oh*)8hiu^@X?@p~Yp5)T-sR&eN#AFRU_;l}ztq3pIra<{l z^Ar$N4~@SVbY!uO58aA{uGIamb+^CldUg!!T=)f|h|PKz7cQp`4Zx1wGz zi_x?_-d=ednHahgxhEQB_e*J~0LPg~pA`HSJ~;28s5oP%!_NoutTJDHZ^DS2VKdB< z^ujb;C41{8X~KJ^^eTSPK6;T~!=p12Yy)O!jlfCcC<5W7uQfqYt6hmQT^t?5x`#?= zL`M6D$6ZbQsmQXIU37>i8&@XL^DIT>7P#en2GV~`U|^5FlLR~4Sv5A`j&IG&OD-py z81hPHyD;Ird$DhyRxZ~%&(S?T#kw016x~+CRJHkRo84V4OEq%h zevP&A_>x4jaS^(CWEL&eiIBW9n(voVI*EN)i|FCY5DmDInXv@>mF9Mhv+c#N5~tUi znLR4F>4+A^3i(>$M_dr`Q7`ftR+qC=M2nB2$O=GtEn!aBbq`}Gy@-71Cgs5;E$HO& z0_!ym!JBQV^k~d_YyDQdjI6FaFQlp1W9D2`0MeGQb3JBXm7219#`VS`kKV=GOH^O0 zy0Xt4xDDa+u=M!-ZKadFa-Qh$B>Aki^8o||cIqeOdYQyqRGQEz>Lqcx649A0unZcF z+C7EZYX|rZ)3c)~M9$elGYlo)5pCh-x7nCk+4wshPmmxd$+X!YsE9y~r^!e~7Ew#q ze`7Eb>^oL<5y^U^rOt&)GB~=y{27&ObemT7_s9!6%gnVaTF=jt5SDm>8U4YtvMdET zh#>9#Iyr59pd|LW#X5zSP2oa0#M-AO+$vi&#v6}oFWX8-n1txUiW}_6=dtdL@$0g$ ztVwKg4S>S)$^$khci&TiM5d&PAPv7~OA*r&rKq^k6ifns_Y!?k(uT3VVcC~aaxc)D~2)OXFF8C_?-Xb(}@|x)K_Z7-#u;+ieQ1D;WK+^+lg!*tv zWS`3sS{bcGX!zYEef{{2eNwyMoU=|~D(B1^$GKQmUIT2!U1yWC#sO2D(!YPP`> zhx_*w`f2H_mdd`pP=Gw$kO@(tbM6&xkNuEY3MNt*USh;ppCLO$SQ*+YbYdg4f2GxV zdzzhY>Bm0yKyU&|3rq+3@>-d@oLIk}^Yw4j!%JoqaNV;Yw!l@=*+oJ4D zzzfYxI&#L=!pq|LRHR;g_?Y~Sol-rnYimf7B%$=SyQ&E^sKN!MUR0^E6(NzRR#9{b zL$_W(j|%-_&5YAw)tNlIg11SR)$I#QZL_y1Kx|6P=A-?SbQ+7?DmrX?W=sP5soZQ^ z<;HG)h{qcY^Pj&1#f9a}MUeI{91fp?pOa;)N(~Wu_#1Q|>Ujg_X31o?zaZ zOV`N+_umfbowC?&q}F@yfTGKc1u8R`v!=JWYMRTSk+V|L`&OJgO=~)>$cs0|IN>@+ zaH6W)rlr&7DKovY<}**%uBD#(`!NY3L1+c*e|EBLi0rc+xIggpzN z8?TfqO_Ck!TR@($U3r_r(8|HkEh}o88A~Pm@A#r(&NkQ-hR3(;-^if!*YWQS4L>pA z>uW7392OZF&QqCiyn4l_=lNkpy0H)To^ONHdaFzzm~Z=?t1s&9u_{2wN8s0=#l&Rl z6v&hX40vc;$|4MQiYkK(4?)a*XU|I!p2}wtLXppO?wbv2gb!=>cest1*yAojufCtY z)qVYfD8>RgvQw>JN*gDc!GTVQiqk6zm*$xv4(dtKjjUtMULF(sIX%-SC44{y`dwt4 zj;mts&Q3@$qpgS!`A#<*pFbe4x@GS)qI)MXva%MFAhfa8FGJGKpPZs1tNANsgg;_1 zq4m7bW~^DX=;TpU?p^uDY@f8qE`!cG4MwP5uk+!Cd*%(>Gm#_P`=4S)D!_f!BJ7a~ zG0r~JGl;3{4G}|Y=&EeuV^W8v9G-!k-ADtm#wW=nl}ay4aMo)|aJ11@4@3xqeYx{k zy@Yu|Hpp`KxFibhev40~eQ2;_`*gmDz)Rm5tbh@s4fb96ZV1>_OVA5PAXL)ta^=+Lsx()(n5m*5F2{ z(KWZd#=q!EdGUOwe(RmwW8zt^zY+4GPB^O7l^CWnqJ1 zd1li8&{_44r;CwQeg)5T0eY;I#=9q|%)khIkv3~lYoIcja^a+Bw!WZbK;t^!YJ99kNseUWRad(%q;*Frk)vg< zwT#EWqQm=E}WZ=sRHC65Pe&$*ipen*kWZR9y;xNrr?m-a5{7|P*Fgq+Dpq&(NSFjOmr zc4>vA&*fOI>kmPse7}w7$X@WLMZk zzMhSuoo|SvW%v08pP5Lo*YeaunDHICrs|vG{&jA@-6+c9o*He zngG9HeNs>z#Or4p|YI%I* z*<2xu)V1T67bN*CP5zPvhz)Hzw>BF~w5*Xd8P~+{qTMit&jwVhr#%aU`WV`B19U{d zk~9h7a=VyjPiAFDUth?e6y=3+y61GPH7I~<`!E|_6Sj*|BgfQweM%DTZai6o^xEtuZC-Bz;SGFWeOG8SebfC$ zjj3yTJJLHzc?e%`s(*V?R;`rdk?JLE@^WKu)ShkmFZwe5tMB`MlSn3k&0e@H^Ctxj zyz`6E;U^3)EtKQ;n~w_5pj55MOjT9BnNe%0B=6RY&aH!{gWI%BTC^+a*1ip))W-FS zeI_y7V&l%b1xMPYMQXvXRP17pk{b)2kF$} z=)UUxHF#}{Wp%?AOFLIuG@?Qkz-sfv7QSN5+w)^ylMgp6r+W>(RFl&B&i{zF0eUpb)tJp{U>CCi4k%jpCTj}(Kxp)d1&gW&&EBw3w#;YQM4+H2n_c|iqnc& z^8t_?mdwcUB+p(73_txWhq7?dMlD9CdqI2r!q;FI-`Z{JTunT^`%-{9x<&9S_ohnq z$@Hqlu3nQ8N-m4tc}nC;f^rS}+hf^pMrC$Pv~W#*WCkUjki`j}>qUv8I9K-mf4NVs zRuws}sP0u>KO3+FWFV8?sRc1A^6iJXXbVrnF|!s)`sDX*irMy&caf9+CJDJrJr(5S zf@ZwRD#1-z}bj$zmB zqnngPF0sw8$?3=%|RmT0fs#9#HGGIIsG=NT2hPfCfa{{~l+?wl#$KfgVV z_#r-botyhui&k3Lz5$hJGdB?`+6_Dy3ynMzvKH8Z>#oZtdgz%Pn!0&> z=r}c=Q;*afQsu2adoxa}XM&n#mRNiyr9MheXyifCFMXu7XLX;zF2VfJBej6u7CXK( zPMu_PrHV{61!S;r@s8F%?YZ zLjx^EpKk0~P)qtCDjs2(+Uwl&=?U@c+_Ab3^6KP=Z49BZ=`rCqsKIRuy!N(5ZNr#$ zI>*`yZz1+`<7j#N`!Xd9bdnLseke(K>CMQq44%BBqZ!&J2BD9rjo~>-Kr1l}|6f#9 z?X67~aGI8_UsvS5<3jR@$>r-hAg&5FP&&M)utl=>ocpbwQ>Sa929>omFn)Hy%{XT_#jIi6QUM@<=T1e(;5o7)CTGn}vSFzr- zcuC9k(`iBp(#DIF7wM`e6Bj~KT=LK&(%Q{40$UH?dFK0#%oCYv{t>aJA?y1>&Pbwe zI?3HzsmFh~L_y+Zg8$uU#j~#J=ADffnUQjbIMRXo4fiZgjP#7sW^T44O!-wN8JjS*n^$7|i|8lR$8;|{oA;EUCY+~fWTCTa+)Br_ z)ZN$we2_8U)+dsKi_BmTa`(DfTnMT==v(#czqEh^fs^UVEb z(gu7Hg>=yqcf5j{Mq7baXEvxKeIE>~^&TE3>F6{<+Aa;-uWr-i?)tu=@~5AdEh#{r zNuz71^>$oy>o0vRmn<8jwb^|J1r5)`sP1>4&c$z?(J+-p6q*=PswQgQxKK3gnv6u9 zYM36E$XWXfMq7y1o; z*8I4Cl#lGN#@9!rP8x;WUP`9p4;n>akw1%05;BxKm5Zyk`#7Q^8k&8z zJ(Sa%W8J&Y-?!N6MQEzLl}Ar+S^B*slH>858>eZQ?n6zo%HlkFSk;&}zH9u!~)0eqGS1p^45tUxuqYp~We@U%#M3_FCjy20W$rMfgm;wq9 zDi4dF-mCCLsz5ONYU}%)%sXt z&bY~JS^A{5ZLiNY(XGof6Qq;-iEVPRS_^oVXGFZ(@sVN;O`~z@?nx}P$Lm1$=uy&B zsdetTikYS;$A%bDtmvSR?ud!d_`M4rCQ=SrIirc$WeIQWgg|ENe<9WQ` z^!h61XSjvtIuB0J`wxr9}{nwfhIqFN-^D`a|am&LeC>p~5h_;`U?7jQn0p+fygaA|)i#FH5Q=-j$|CVkFZi$oL@g z>v^K{H^$PUyoy^^tRq+?=4l)c=$(`>%hnhP$W9KX*kslUon~}0&yWEEROHU_bbKuJ zG6IS$#zs!G)NCNuGLAwu<5J9@tdQYNHtU@bgppSIj`7tJiZ65OhF45)dVGhoX1!kJ zxz@hD!-ypjzo%Wn z4tfT7T~UL5eW#Wto&$*ulMZ!bn@69xZXA13R5N}LZ{aw>J| z?a^BaU5GcX><-nY#0#Beol3G}RTt`(hqYnUo}eil6eZ)L>`PQ-Dueend+%}i({L~VI+ppPoT~by_Oh0pe$Sl8e2sSJxr&O1&5@5yAzfdYl<}cn%boan&25FbtMMq| zyLJ?-%U2s5!y+niNT$ydVT@@c`R8c=&w6YnaA-`(5hM!$FPVb-?|+7bSEid5>) zHD=SX72WG4&&z`C2hfR|n;Na&V!50D3=#6iaP=ljnJ z7CZ}UmM7CE()HrOhW{0rG!pXx#76koH}aIO!AAEX{%RD@-O7*sN%uhQvu z3~-j*$x5Lq5|xpy%AZcC6Z$s9xgdgg+pkibPalsn*X(@ZlCs7%q`>H##3ax@A8ZMf zI<4Cysj|qNF+O%~5IxGY8hIe8L~b#Oxu>F9rH`yyYg+R*53eoF*0wc{3HR7B&pR-uUj~P6kstc&}+gvc0r@f22aB7-s`@tEr*iS*w8c{ zXPz#fIEdIokV$kzPHG2@&iGY&eZ!dcB4xW%!z=7H5D~L%=LevU>>j^A99YuYvfoFN z(xJQ$R2_^B!$^UIMkW1%{Y)Anl*-*Pd$~CRphpb{Wts^{HexJ$>(kQ7Q<(+@$mZ)dNgBt+HS_ktLv z2RvQVan<(-^3>P*bqu8+3kasDFuz2vJl0k<^l+7O*EuNct#XWayh6f;S=LN-KU5m@ zLUdHVbGg~-y3qQP=MM$K>_~my>1CpvUDzqc@e92j1Wr9YlW^ccZ*+hT6SGgPuEUGt zlCc6p2AE&jE_JoNy*{j6@!>r|$@Yo#BEk4;8Pu@J+r;uB4+JyB!|dhVeZ!)~p^Kx} zIJR}a#?&DAg(~;ET0vkmuXt#Xi9n2=glrd)N6ca=S=lNwYFsS`oMz0hl!;H|&%#4DUTBXPYvpGw1Gn;8shOs{9soCqt4Eb24Ws25REY0wv>{H~rEp=%$6Ff6Q z&FXf(!a{C2i46?Z@5ihy4@JbI->;&-?G9dM6CB>W;F&tApeqS2m<)WvTfS zw~`k@*4xLDa7aFdrp(=m2YFhcc7LN6_E(gHDO!5$Z5f1(V0 zSU%jkMbp)U*QUw!fwg%7VJUJ^&kBEVd5DpV3pbQIg+;`D-)fouSa+xbz(KAiN<^a2op^q+F(-6-bPTxF#uzq3JNKxR5;U<>5L*EF!hY4v zNDsa&p2=oqTXjj5DQ5z#&pIo^8Rwp0suuUdx=*Y*HDX4+bvMnpa~PH43R50#20jI3OC;7I{NgW4RISs_bNMkPbJyIKj-hi|A(SM)|gw ziN=ym(&@V?h2a7~c((Q;%r17O3fm5QVUNpkngglSdV%&5#xbkuX}-PpEXQXOKEDdC zy;ZcoqaTv~P+I&oHbKGbV46=nSaD_R3WPBDYCP6o{d7cOs;TmyR9~VJUP(}VZ5+Qa z`8f&guTvwN=S1Ni+0Jv#<-Czt_(ep30H6mnN#^63iuDi9(1hvlAqM01ArpKvnJ0VK z4@KP=%;9Bs&&PnXQ$ptsn@gx*G@s$Hh;!qP zj3`SmTUxJM%2tU~ob47#^|?%yC;qeOsF5ncy|)p|h$nerbf(|^%vNVTzXb#9C^;=! zs<)N7@SCB98mF=8b`Nu7xrF}a=XHQ#K^S-(8>jtu#dE(>yVfd zgYT=~1@(CDmqkYkX2SlFHVaPU^U!dXE3jJ}+z+Rlec4j#Wsg}9uj(suP3y5pM)KM+ zGJQ09DmXThT#{lCUO#~IZ3jE{S?r?ZqSiOh5Q{RU4v0f#^lR)esj;ZN&X+8XM)B zyQB9P{#2dOMtm{!n&oBRy)i8gm{_2j$hPfkh8sX+^J(OiK`x|$q6NCipH$y{iNk$$ zjs7k*|L7weD0f+p1Z@~96K7}#VZXJ$k}2~-63dMEW2 hR*%;^H^1BasLrD5f9+ib{%i5ddE>?UYe24&{U`j$`i}qr From 739234038bb5435a9e2d7ab6989f862cdbadaac5 Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Thu, 29 Aug 2024 15:34:51 +0100 Subject: [PATCH 6/9] Updated 'cuboid_inertial_parameters.m' example and the 'DQRoboticsApiCommandServer.lua' script and removed the CoppeliaSim scene that shouldn't be here. --- vrep/DQRoboticsApiCommandServer.lua | 56 +++++++++++++++--- .../cuboid_inertial_parameters.m | 18 +++--- .../cuboid_inertial_parameters.ttt | Bin 252170 -> 0 bytes 3 files changed, 58 insertions(+), 16 deletions(-) delete mode 100644 vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.ttt diff --git a/vrep/DQRoboticsApiCommandServer.lua b/vrep/DQRoboticsApiCommandServer.lua index 1e5666e..7fbe2f9 100644 --- a/vrep/DQRoboticsApiCommandServer.lua +++ b/vrep/DQRoboticsApiCommandServer.lua @@ -1,4 +1,4 @@ --- (C) Copyright 2011-2023 DQ Robotics Developers +-- (C) Copyright 2011-2024 DQ Robotics Developers -- -- This file is part of DQ Robotics. -- @@ -24,9 +24,9 @@ -- Frederico Fernandes Afonso Silva - frederico.silva@ieee.org -- - Generalized functions get_center_of_mass() and get_inertia() to allow arbitrary -- reference frames. --- - Removed unnused inputs inFloats, inStrings, and inBuffer from functions get_mass(), --- get_center_of_mass(), and get_inertia(). Also renamed some of their variables and --- added comments to make them clearer. +-- - Removed unnused inputs (e.g., inFloats, inStrings, and inBuffer) from functions +-- get_mass(), get_center_of_mass(), and get_inertia(). Also renamed some of their +-- variables and added comments to make them clearer. @@ -60,13 +60,25 @@ end -- * @param inInts. The integer value of the object's handle. Optionally, the -- handle of the desired reference frame 'df' (the detault is the shape's -- reference frame 'sf'). Example: [1] or [1, 2] +-- * @param inFloats. The float input value. Example: {} +-- * @param inStrings. The name of the desired reference frame. Example: {"absolute_frame"} or {} -- * @returns the vector of the object's center of mass -function get_center_of_mass(inInts) +function get_center_of_mass(inInts, inFloats, inStrings) if #inInts==1 then -- Retrieves the center of mass in 'sf' _, H_com_sf = sim.getShapeInertia(inInts[1]) - return {}, {H_com_sf[4], H_com_sf[8],H_com_sf[12]}, {}, '' + if inStrings[1] == 'absolute_frame' then + -- Retrieves the homogeneous transformation matrix between 'sf' and 'absolute_frame' + H_sf_0 = sim.getObjectMatrix(inInts[1], -1) + + -- Expresses the center of mass in 'absolute_frame' + H_com_0 = sim.multiplyMatrices(H_sf_0, H_com_sf) + + return {}, {H_com_0[4], H_com_0[8],H_com_0[12]}, {}, '' + else + return {}, {H_com_sf[4], H_com_sf[8],H_com_sf[12]}, {}, '' + end elseif #inInts==2 then -- Retrieves the center of mass in 'sf' _, H_com_sf = sim.getShapeInertia(inInts[1]) @@ -105,12 +117,40 @@ end -- handle of the desired reference frame 'df' (the detault is the shape's -- reference frame 'sf'). Example: [1] or [1, 2] -- * @returns the inertia tensor of the object -function get_inertia(inInts) +function get_inertia(inInts, inFloats, inStrings) if #inInts==1 then -- Retrieves the inertia tensor in 'sf' I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) - return {}, I_sf, {}, '' + if inStrings[1] == 'absolute_frame' then + -- Retrieves the homogeneous transformation matrix between 'sf' and 'absolute_frame' + H_sf_0 = sim.getObjectMatrix(inInts[1], -1) + + -- Expresses the center of mass in 'absolute_frame' + H_com_0 = sim.multiplyMatrices(H_sf_0, H_com_sf) + + -- Formats I_sf for LUA matrix multiplication + I_lua = {{I_sf[1],I_sf[2],I_sf[3]}, + {I_sf[4],I_sf[5],I_sf[6]}, + {I_sf[7],I_sf[8],I_sf[9]}} + + -- Retrieves the rotation matrix from H_com_0 + R_com_0 = {{H_com_0[1],H_com_0[2], H_com_0[3]}, + {H_com_0[5],H_com_0[6], H_com_0[7]}, + {H_com_0[9],H_com_0[10],H_com_0[11]}} + + -- Expresses the inertia tensor in 'absolute_frame' (R*I*R^T) + I_0_lua = mat_mult(mat_mult(R_com_0, I_lua), transpose(R_com_0)) + + -- Formats I_0_lua for proper return (as a 1x9 vector) + I_0 = {I_0_lua[1][1], I_0_lua[1][2], I_0_lua[1][3], + I_0_lua[2][1], I_0_lua[2][2], I_0_lua[2][3], + I_0_lua[3][1], I_0_lua[3][2], I_0_lua[3][3]} + + return {}, I_0, {}, '' + else + return {}, I_sf, {}, '' + end elseif #inInts==2 then -- Retrieves the inertia tensor and the center of mass in 'sf' I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) diff --git a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m index 818af43..c8e360f 100644 --- a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m +++ b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m @@ -34,8 +34,9 @@ vi.trigger_next_simulation_step(); vi.wait_for_simulation_step_to_end(); -%% Get the Cuboid's inertial parameters with respect to its shape form -disp('Cuboid`s inertial parameters with respect to its shape form:') +%% Get the Cuboid's inertial parameters with respect to its shape frame +disp('Cuboid`s inertial parameters with respect to its shape frame:') +disp(' ') % Get the Cuboid's handle handle = vi.get_handle('Cuboid'); @@ -57,22 +58,23 @@ disp(center_of_mass_in_sf) disp(' ') -%% Get the Cuboid's inertial parameters with respect to ReferenceFrame +%% Get the Cuboid's inertial parameters with respect to the absolute reference frame disp('--------------------------------------------------------------') disp(' ') -disp('Cuboid`s inertial parameters with respect to ReferenceFrame:') +% Get the absolute reference frame's name +ref_name = vi.ABSOLUTE_FRAME; -% Get the ReferenceFrame's handle -handle_ref = vi.get_handle('ReferenceFrame'); +formatSpec = 'Cuboid`s inertial parameters with respect to %s:\n'; +fprintf(formatSpec, ref_name); % Get the Cuboid's inertia matrix -inertia_matrix_in_rf = vi.get_inertia_matrix(handle, handle_ref); +inertia_matrix_in_rf = vi.get_inertia_matrix(handle, ref_name); disp('inertia matrix =') disp(inertia_matrix_in_rf) % Get the Cuboid's center of mass -center_of_mass_in_rf = vi.get_center_of_mass(handle, handle_ref); +center_of_mass_in_rf = vi.get_center_of_mass(handle, ref_name); disp('center of mass =') disp(center_of_mass_in_rf) disp(' ') diff --git a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.ttt b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.ttt deleted file mode 100644 index 4bf79c91b5870074628d8f0010ee3c5c52bd051b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 252170 zcmeFadpy+n{s&I?$YoQsl2Vv$T_zhzuAw4f)0R8YRZ~rkGR9zRC0ZMrX;E%lsg!Fj zX^b%|KbO)tF0x|krKly9Rn6OmYtK|dvi~h ziwDkoIrZz@9xVQ>*VDYJET5RB3A2(q@HUzbe_j>8mUAPju#^rnmMK+>c4o zI+3aM1WzxvbyM*%bG<2@dwr+e==+oq^P@F6iOZhLxc!pXgx{62HG3BIyi+Crn@gwS zDx;@9sO~KhUuK4~SGBnBxaQcT!nvg6&Vk|xYhCY)`h29xJ0F@^H&Tj$TRPw-ID0O^xqSOofxU3YECU3u_vgKKHx7FQ*Ww1+nsw~ayWaXG>)TN8%X_*S_h`1+8)@ZY@5 z|L2$Qc&==>zU(dawMpD!(wfa5&qFut%i2z|?Aq309;0r#La5_cT;sdE3sK9=OC7&D z6sy5(Kj?GW$m9}(r4r|MYCpi?spGrL>c-eH-+?3eEeTSug81!M_}D`9^+on-RJ5?s(4 z?_Z{`PXv4;3^LhwA7{OE%R;7&tmk5KhEl44QY~@EkP;P!-_E-ldgbz`s|Y%J4o<@D zJ1(!~qOR+)a+p4Cxf2uX56$FOpBjg!XVh4BxCXZJQPNY&6S z-L#L{V4JJ!u$>|!+}{~?p7~y4Zz7W?DG3|oyUH?)qe9ZvZOEwvZT^JRF6O|y=0{5} zldJO^-}X?_DF;2S|GaYf#D-1kR4kkaR73<<4i!Le5?1H^WY&rhT4+i zjJ{s#a1FW=?bXdsR}@B1>qN;X_-RL)XU@Y}ERmV#kxU*%3kiXT>{PB7k3V%(w}2B& z^{#nswBcf|Jnv!Gu_>NVBCO_5o3Cnk7t3HX64tbu_u=)yx1-oypYVkG+T0b@Hr2bz zlUx??!sL|~P}d(^r4&RglrR##?#_tu7H(r@>T^s91(0ECm3Wu2W;F z#0H++#A9r4GUEM+%U$)cQ2b`;{CWM%;jXf5#Zlq*>6~bz4c?#btPnc+OjFrzL-q3K zUJfS9)`b41(v5^gXydkbBLa%D5ge<` zWtI33cdAUT>Aec$>@H1MXp$Uss!m!$gY#p9#Z|%G3ybawpmbYQLFu-r(wKxwu5t0T zT!gx@Y}F^~u#Hb1Yg_uH<(Yi1eFPy1!$R-u9~TJ;OM^G@gv)2Oac9qLt1_88s}u|4 zMJUv+?<$S7is#Q)l(3_JiL4x@HjnA(Wv1FV>u05#3EJO#dc^(dSAV!V|5JfbwTSyh zc=qkViHWUG)*MQ4v{{0yn!87osPADdF+5kv@Gd@WRiYYcR17igN+18(NpO+W9Xa;k za%I?Z!OlNF_y>OT?r;M?=B=0GI=e3kTL(7tDa z4K(%@X*~2WSGi96aP-p=w2wq;_bT3*bK`9F6;4w#|I?*M?VL|om%K@epgqt={i{p= z2VUjhI!7yRMeni?uM#_$Nc{YPTtW327S3Tl#nQVg`Xh3b=4bjdLmgmUY~OZph4B3Q zB8yMWQ|3s;-DS9KCw0x?axYx$5x0gVm--Rka|;)#vcJL|x#nL_er`t|OpTdNBK%VJ z|GMZlCRG881{(f}hW<4P;PsYa z)fMhZI-?s`Guy~{=~n)s6%xcm{?4!Vn7ddSns(Cjnb zhwWps@3l+h&hza3{{lh=il#od%6HOj3X`e3DAZv_A|m7L zNtb_bCH)6hg^KHA4GYh6(@Fa)-*Po35Wz9$xm>L9iO`tr9jZme%0B&g%)32D^FN{W zaCJvX{?@78C%uJ)bMYo=JYnzQGJEFasP?@2fVbUM@-`_Nw#TOr=q1i-q zlH)^8e%dQeTbcJ|=DKS*3q$t+UfAi!d}fyduUvSx`5VcJ-|*Qv=kCvXDb^u-p-CM6 zvKekjJ>LYM=iS|^(3yiew;a_;t|$(a11<~X%KFW$M9DQL*16Au%K~hb zICW>Il=?R_mmAu)Psdv?c(IvTRlYB`R^4X8Mt1tzhIw!*or5nma4sGpqlYMs6)Hs( zR#^Gly5hzCqj%zPlb$b^x zRN@YbcQ-m|L0hc%^S6%7s)2p)807heZXP)63u%v-RjV@%nUWK$=*%iQSl5zYE~J{8 zFSh4h_6Rei{D4~!q49l+%kjt8^*-$xnIGOhPc~+)N)m3qr;_>--!WsH*Gj1q8}S)I z-xv>EKpj5DyR!Jwuct$5-biGU^vXC6rf(MsJq<3zm&DsENVbxvfGUT3UwFLj;ItIpF7^T!a;507WA|TttrE9dVfn1a?7_PN zjqm*~rr1rqznEg9{B-eYN9ScYj-&3pZJ~B5J2gL*bT<4rbLlgI73X+7D|-CxB|)&tM{dh));Y`Y(kX~*U*Fj6B!wwSB4$)CCK@i~soVL8|w@@q8G zUM8&A5v}=2$p0>xCF>3@D%N!{lFW{xu!5dQ2%Y*o`(FQsOhiR(@mzZ5%-NBghq$0n zUC9aE1i7x$j*hQ>nT}mjt;0OmB;_Tv2x$VSRn;#f=!SL9SB=T|1W|~J{<`nO09adj za6*pXE%QD0xA^$t>`~S&U0GSPpGF-V9V^Ss)fe-8MJUy=a~wy+8+Cy!&Y@C5E^StF8z)MJ?78HdpU|$IIQ!l2NR`{I_@YUzfT6Bsn)ezI~Y_ z@!ZF9W%{k&m85@YD>w-bj2yy_m9nJehL;^PUj zZSikIT7T2^BOh2DTkuqN>4g=v#*eP_?|(W;xG$4Z(pNouY5zaeoIjQ1v&Fkul-EON zUYaa_LdId<^w)k=|y?Z;IF7Te|Dt)x=wRsHlW!^(CdGMummi$W?<0GZDQ= zcvc``Nd9tuyCM1gkH#uEt3`|Ed0e|$R%S=;ZI>JtZhtdufmYx1Me*;d!yjLgFHkeY#L$y9To=m!u`M(m2Tf$ZVufL8X4y?o(=mz1Mt* z-1`(Jc$`Gn*DNM$E@?md`?b*9i|sBa#eO`MuCPkpWwT6k-Tw)4e?cR1I$d0~L7p&I z^2?GrGJyJNLh=ezW~6l)ZadpPw@L#oym*Iq@v%vj%C*hkZ~A*T`aeV5E*nV>BopXz8ndeT2O-!hj?iE(4 zFF91Ti#c!A&?})u@P0dvo$&3R|IAVUo$Fz>`d!t>`(bl%vy~Eg)sXAdKLM>dfEZ^Q z%dYF6_}S{?LhxMuvstLkw)c-$@xGVX`(;V&Ithpdmq^I#F}t*?_TVgvi8M<3ixYoy zHU5`{`OlyEGHjG8Zf@DDh1D$cvN=?FOz=;)1@E{g53SbPtmKuh3ykFz&;N1RF7Bg> z&?=d!-?;|=TSxtSUCQ6o7OT~rRY^%W>DK$|o4&ji#e82hN%-gQ$!~V_`yA_S^#oZH zUT1u5O!ORpDUav>bJgVcD{;Tw^XSg`F-BXvhC4gStCrPO^7vuDWzm0UJ^nsd>9>dU zn>RJx8`k;K!Du1>^=Eu^K3D&HbpL9NbQ0|RW{38?cuQVq+^TkHR8S8cnq@wpb^BKm z6TsIN@OdqbzcM9Eau>}vr-aS?v;F;Fy<7i>HGlb%{3ft|P%2?yIDDBMvl@41?I$(+ z|3cG{TJu+z@3)@LUq9{taN_@wYa6XBZ&4<5&f}wfwrrcpDP~#d?@HhQwZpEkTv8)R zyZ`a-&X@fR@9uAeyiVWS`AoY9_>9k}@3vYlIVjyc{?CZ?Pk_O>qig;3_V#`M;~w5` zdh(~P(f_)1{v(gr)bMq1^+6z`D3#9G7rar6=bE@ra0mYpt+m!0-MNPO(I5J!43$5+ z9{xtR;#O&-{!`Y-A9;V(t_~e~Y4h<03(I_k)?~NO>;{)=6MntHDK3b}?5hxdPRlp) zP_WA|8Orl}<}#y$dIYtY3^~qcRGHKNg233aqnFX@dhhZ@|C>4YMJP?Q zN#0yl5?l2{?PqlX|5j37HaQR~{ETYgu7{gc2+S&U>ROe#JB+%=eg8SFkeKfdZXKpX zZzulg_)aeRjEMc-z8@E>;?A;`od#D9)(7fyI=b6mJqbs9E>>zw!d0yP)emZwy!Q{> zg+FrD{`y{jj$pO*ia##jR=)rH^ArDwasP1ydQHK)%M$dM=((u~@}f1WTX=8HkA6P2kAG{y zriH*-&Q^o75xc2(s0bxF^$BY5KhUzfPA!4F>`*5q+5(1sa$E0hGF0DtR_2epfB##A z{=PJ^`(F%=|H!MW7V~h^z^}^a^OU}SQAVG;^!1On+DvJjzv`a}(f_aoF8_S|QIGm2 z2xBPGRtxe!D{o_mNWSyEj)IYHS_uzlksX^so(=1lVV*mruSZz-9!B=;=JgHEXLco> z@5MR2mBf&FX;K9BG>ET}irL93NEhsc`YzhBk-tYibC} z-)C;=g;CkA!@nN4+LfpmGR*hUP94nWW^yX=E|RUEiQjU&Y$MDub>X)woVGDuv|&EZ z>hzDBCv-3Lu0O@>(*5eby2{Adn$IVhiMnN8|7^`8!ey#%0&<9U18}t3TPi{fVZKGO zjaRB(aEOdlo6p2f_+n7`Y#FRG8`(b}EqYw%7nPI*pH88Ls_WX%1O|8ZBI%KxWS5pK zFKpm~X501B-U@TFIK)d6XI<*{`g17^h>x%Xy)Ac|y3Y9LD@7XUV#p0i>y}1Qw`QOF z(P-m&-BG_!FH?T43f>0dINgL*Kgs}1AwS&isN=_M@7E0eOt1+@dE0FMZZBcJ436N6 z&NWxJ9VtU;*jK&&*OJoT^LisQ@Ac!CE`Q)%MrmzgYs^UEKeL;B!a&7&ldLZ9`;wer z%p7&imm2+j4)lj{*k8f-tK+s@%`DncD@*`?52@`(tIy}go-kNbqhGE4r8!&O`N8(z z6GH#0^%(W)?2>B|&r3d^RXPWqZIM-HKc~xd^>^poe+}gSp8J0<`2VG{3fuOrSng4@ zviQO7l1|9K?{$A3j^z`~*s0$RV|N*s&ZF## z8!C3%%lYX_Yy4hGPiunN&swC@p4LXb>$HNDD9R;MTyh8%%O?gl@_U;EF{pOSM+*qP z8(50U^ef!B5llc>)=U<5^-E58THT79N|$dj%@oO(7M?d=l=^KUUAj4vK}3N^%tVD zf8u1c57N0&p5roReZ#2EIPpB%P&c=SjLA_uKfo4p*0Mq~m=kwV=}rbx{ac-VCaQ;6 z45d`72~>7bC}G3?foU(tT3t4Q=E-8Hq*_q}o;YK20+zFV{Ap)tbo4Q2f3y|FAwN3sn&x6pqjSi7VYcUdWB^e$#R)`QB_e#n?VSoSeAFbwS>dyX33dH(F}X ze%BZu)i2bZt~xNM>n$Enl-#}`O)nSm zHO1L1KALp@@XISPWBErs;~P0M`vuQoFXWIZ^){aC%-wj7=0;`Lyoa^puCqIC{*XB` zdEms?iAVM)ew}&4?=Z`53qirV#9PdM<9E1Py&)K0nm4y{uHY9Up zd39quv)Td&Izq$g(yilO&vwO)7-@#5jY|o_`Mp9;*nJM?q(fUO5oa&y`LkB3WZF26 zTjmr@(2UXPT{MT1N5=IOOJT4-&5C@y#~0tlDAKJfFpNPp82PFZNh z&K9PQ*nauy=u5>t9Y==x8_H|_cgz^zMatf7tH|FBg~apYpKFTiYj!THI(zrSHcipW zH{U#D_2uL}gc~<=@rdY3Or!UayQz&evwqPjO?&u9rnP4;Rl!a5iy3hZ`HtJ-nqJSE zat&TSnY@v~4@q8b|8hs_gd*{W%s2Zx zQS?6eCgg7XSpHOHYK!-=9q}WumpM2ZOw!B|9C9=0Vg*t;)+H%8L4x(|dp8L|HYNUd%?d7RHL2PSXcdwoT z&Ou5a6vFu9QrzZ!eJV6d(QyJ4A2ZV@J=aq*97`5rJ9j&l>W<c9BCq;H%<~2WVW$XJQ~3DI#cD0ze0lWP2i2CdKx+g(16>40k9 znUzqIpDomkQ9o0Xs@&e!#fS(HKfT}JUwkpRXpGLFpT2ESG{n29MBx+k(E(Ra*Oer+ zAATM#W8rih7xLC*(vVfUrnRmh;i?whqiAp?C)@TGt3U@|E;Mm-j8GrNo88&XEq^V5 zy6@$JQ80ndu&=+jIe#Y%n>(sd;dqS5INB!Xi;wIM)!`e+(5LxF-qrjRu-ixP$i-u$&a=0fv9=jo?Rze9 z$MVEcTU@qyw*Ua9mmeCmGv^;0>Ygo(A4?opXZHbKN3+?~;|X22MW*+}OAS*L2=8m4 zWb+M2wP)|^)%ray#y{AUIAutUA*LY50Z-r?4%!x6*TJ?tdf za#UbEGjPz9ctrudU_!5c+OHwjC9gJGXrFLf94t8;GI)y@+Pcn2a z3O1#6wla*`vw2r7W7jZMq1MI+8wIFga;FETr396{QK^td4E;dSco#R?GoshFui&aj zp>&b~9ze-?;vDJ+z`NPuVKN-Myk4m%fEMp#q*j?`^iugr5oSa!1CZL58s(W?$W4|m zE%=q7_MgfJz&d z9lAIF$VJ1MdyH4dMgvGKtiJAHXW~s7x0gOXOz7Cc#Q(|KEyqUMibT9rRj5O|jd9N`4y;#sw6zCo$=;Wn)oDrD`4e>fS6z|eS-sFzT_W8= zI*93)JRRDK?yb0KLhED&DHSLAxsOZP1Aw8c-_X0|UI*_tFzV*GKP|A3bIW~74*S-W z8_b)+ajtG0m9!mPkr0+W-eYzZST2pyNH8-fj+FB~!vj?I0j}If>#z01-O>qA>+Uy> z4;rR4xaUsu2rv81<9*7X3~p4_!S@&$low6h4S3?DPi>EA+7+{jyQW$Wo?#q_SD(f? ze*5zWDyB0YQ_}tfc%f(Za6l(n#Y?&Lx?z=C2A$%av`!;iu?IHOi)e#d(Bfr>fmntb z;opsA`(JyPI*Vu{4Vd9gDo|DbW8q`yD5o_UYrl`_B&d;9y1nqvNvyB zBelhTc41AW(!H0~H(T=!sQc@LGClKf$BhtnzIG&&TyxBjXuy>4+f zGyV$W0`j^sdX1-`(KY=cH02wCH;%kxuBWwe(4<0&j`nPQBG5qo;a{j5w7<-0eDU3W zJz%LE%{R`l0A>piz}7S4;=Ef}{j1Rh`L)vK1&NbXy55ySRWzx9TLtB`t;MptepK@{ zsRi0}p_6FJl_ahHBd5D&;1CD8_6f^wQ^8LUW87s)b2&$X7`|h zo|^f9!~@-TS$v*rhTzMBI}tcJ18bm=!^YgJ%h;% zbEu`ZkN3X`@!+=X39ZNW2|@wmQRos^l66&|JpgPAg%p@KuFmD4p@w$WOcS|$=@cbK z%V?A#Lv^L*Yd=-A)A2+WrfrZeR-$%D-%R&-sz$m!s;NM75>4V6Eh1CnrYBxJQ^1$o zfETakgNGW<32DRLbY@~(1HC4(?FOBh;BlQ^W7kxChUx>AmvF(WI~(cz1qeFF!cWw% z%y_2dDWA2UGrgRcBA>ax)`f4%^o$BvaXp~$N^2Yn<7us9HV8tu_4x#<+4>jA@9e)qEu%ooZ|Az1-o!sA}tbp5HS$0IuUiuhpZfXhY46`!r{ zii}7MnpZT`MOQwsUI}&qO8LWGtZX4&)+JJkn^6-Pq0@OF_1l$PRogqRdfBl5qOp?6 ztEYN<%p&nvt2cTo{9Z46RhPU_#}W+i(7GEX$ux$$qr^yaj3QkYE?TWG)YSTA2rh8l-AI1Zxm9_D3H%Hp+o(D&uNEYPn zyLOnhsP?SqsHFOj1^FN;ddXis&3_%3-&V;M4;f6^=1eFky1Aa-bn^PangK0G0R^g>fwWoRd=HMyC_?)OB{M_>Wd!p4;!)#gm4Ks7iME9xU`U86 znn|lNfNBjKuBxxURL^kKSv(YUPd8Dl^k54ebpC|G$%4cq?`o&7Ff#I|?A~tyRSt@J z){lV@h}rOg-2#6ntX}tUAf08cwI;{qfniD##|{5rOZa3)TNQmWp7F|X3`?3QNTr{+ z`(dvjv<8}Z+Kk{0eKMB%z%W6S=^B2@=D$?;lG;TERl{94&b)ytT zx*^f4=eEcM?cYL-t3zb`AT<1;4u91k%FB6`u!${<*7`RSW9CsTc878Tt| zzEV*`mv&4ikfSG>i-Mf@szN#Bw!WBZdEKXasu#C=(FAbFXMBvJW&Pf&_l0+)i6Pdsa9F2bZ3B0 zUqPzG>)!BepaWHSpNaOt!siq+2E_h=W0md*wZhp=P?;9EB4*x`Axw;7?3(HmZ|hAK z(HcR~042micb*6R`sN2)AdOL;mw2f+oiWsP8fja*((OE-49oZ@8C2osx$&!R$eNU^ z5~`(>uA+ZdC5Nmob`z(rU;CH0msTTwp*EdB>!ue&|OGA5gf=J=ziF%;dBm!3?rPKLp{*SdeIYn>7{BI6AtaG9LPKf$j-_ zNy&r)fpN6{YxFa%`4s_@Sw`>vXJi+lYO)3FpK|cL}~DTJ{u( zw)ps$i%fI;ouKVQ{hcPZ&0=>x9yzPACP!obxva??vpcLnE{cP+V@`~=gUKUfIWtif zqp;uFC?H1nRac8r(a)w=TEsESLcT6iF-|ZIu74!au191UXV9QjTubHztpB#DYgUFl!cBVCWsj2h(YPJGCR5Mgh`8i4uBHP>6&=VK%N*{Nt4r9Gfdf| z^@TydH3q936|}%534`rq>fIW+t@6lNXs_J*`~wg~1X@dqM0Yh44y+G#f8Ap?hFCcr z#8RbHVtvuripj7{SJRW$=<~)xXyxD`p-y{lFBuq>670_k_B(GZ^^8xHKm8cx!=Is= z-6Du0v>nPp-=lo`U8P&6gdDI%>mM28`j)solcz^UgPX%qYX|VJYvfP+dG?hggyQ!q zJMWdQhDCrzRm7oG9n*!}a#5&%Q3T!$?8pxcL^mNtv;LJh+`Lhh`KM&$*sH4m$T_Z=zVy+o^Uc&RZ3!Yp?Wb>_DT= za?)l7h!n836YaPUh%@rQ!KNzvb~sZ@yk-EaiM9n*0tLTS=eUiQv)0_kH?!9aMIieT z=esu%1FmEaRIUaPG$kBu2K)#pWC8IUGE9NSj~VqR6oezF#+n+N=Npdtdl$?BQPlZ@ zgqY%UEj&fh{<}omDa2Gf?(sO0WzE@b*)#4@g#0ZeQ)I;q(rcHNj3vGxHvHg~Ru0Ps z${V^IDS7c!sEP5Q*U?aHO_>P?iqB-82|sj6cTf4FnGd9J(Qs3}W!F@j2>p>DfHjK7 zwE=jko25s=5dcFJJWOcu4@|McZB;<+t_OhgQy3*9>^rlPQ8;iLYM@kz6_}LVR?r=0 zLs<)BgVx^%k(=hU=6Wzao$00CvR zzd)8Zx`;BIbaSAGt9rO%nAYK^Jfa>rwkuhhj`&8VD5TT(A%cFquo<7oSOfV?%Yaod z5uc_V-VVCUu}Vjb)?`2pZGZ3o7D?218&m5 zNOC(gfAE`nP*s)!XMiomvke%*#7ovBdM52!TpaPL_L~-nU{32NKokR<(4^Jab@S~S z_^(0{gPe4m)z>dt2{FxyU#N%~*djvL%v=Or&FH01Qb6~JqPRcWcMkK$&5XKZ#O~J0PeVI4*2eB4GX9Y_UplQM#aaDKLv#DqP6hL}qAilzQNUzxscm=Ns z+gBdjq|toXv<-%zFwqSJCw(+q(Hr2N1KEzA0OxcnTZt+c1TK3+B3S0y zXtxexN*BobSxg&)2>y|4VvQY8RInEY6UFST?-IIATKB8@ABC0xuDn`@fB8yHdFsX> z4iG*5Ob#S2SDFcCN|e=ICD=IaaQ?Irs_ek}d5?^x`T|yhG+M9t=dYh0s3a_pY);U|wJ}$*E zV2)s3q=JA_+`Y9I%qVU~+>G<(aqUzU-gplRo(ISLE!T*NzzzpNVITeZEt?L4@_XA4 zJfN81nCqb4?(022FzU7Xt&>k%>>3u`<638H7_~if45^4{)LVkA@wFZ!X{uV4Zh6m{ zclG+zYEM2lx+5biKq3CL2>_Pn$$w614R5a=PHsM*Hrj)F$c6|B7(frclWM-^O)#-P z=GajG8z_g`v*C%`G#}1$-CRi7>Uvu47?QfM#z9_lA?i~gEl8NfG+eBivGHISCT`i& zA@x!TLOgJpYd&nXoRtP!6Ku;7uUTujYhdK8(}*8Tti_-^^nj8ALsjqw0D-Wj+k)Mb zFl)_5GE1!Kaz~+dsh-}EcdWilas4c`=qSyA{Be!=7W>ep2K#o96CojuuL2|e&{&-J zDkR?lD*&Aiwe>Zj0CBe;#)7G68$NKd25iY7Jaxcw7U|Yqg;2PmWHP|tVYH=mr|G(Q zbxk!f5aMBv#+5_f_~1)=%?(DrVG2*{BnR;{?STt`5$_Y!JeU;|#9?O!Bw`8$jkTdB zx}?OK8zp0Oo29@Ls1N1@k#RM#sVeaW!Sn!4x|O8D`xyh8ymiX!S-)0b9XLPWoR3RA zd#m*YMApJ*0uUiQFwa5!NO8a)@9}L9KW|K+@R_3Av{x@f_?XgH0as6TdVu~0L^@Q| zrsMh`F;^*$^s<-a)v4M;x0b^~FzE-Sjn)7m`vH`%`m0L1s!OD>Pv+gT{vDv-QK7b$ z`k4+&#TS%P199L7O$qH~At&O4ba#JH<~*0kqabKnh?VbZV6)OUupU9Gv?Aq}?GRY2 zjwL#p5cv=&U%Yg5&I^jdzby))$_!zkF81+Km7RSRY4S*c>st|{a;=kW;?;=PahBRy zYBQYNGR@mMVByel3qaSslM;^!*L>pavoN5z-UOkNY`oe_$b8nJaPxW*TOHE(VaPXw z-UG!*$*{fE?dW_1u4IENBljeu8qA_C=Ul%5mUj$TN!~HP7^qf*z}28I zwSdAdEFWDr2uK`X zgf345N4=&8EK)VnrPlpuw|ptKh?-BN0Ieh@Zt;GN*y?^9*pquaRSp_GL)GRbBu2zI zq^7c$9LOv$Yzy~I6X|R{Km)EEcS7J_UPlg5`KsOCB3H zg2q~oiN}ksHgP%my>(+lw{?2IFuTRn%kFn5f2060d0JgpBqZYRU{BBZ2q3NfT=GmF zZEXtaWRXGvOQfLYNG}NOMwe6bBsVWph0AfORY{vitNsxA`Msyxmhzg=fCKRT(|Kn`C-(1P{>bF6wiWRhPC;w*F1VSO4J})oeP|A; zRrK*OZ=}~k5k$%*C(TI&B^1C2(3mTc+}xw)uR!ZUj|EC6-3He8T$0D8o|2;YfiFMQ zKN~*#kZxNjK#C!_S_qvy1PZ$xncTpbU+{ur`~D3Ho=Zf$breoi;o{U09yTb%?x5LiGxV5nx^XsPZ066huLVFob; zEb?$>V$+j7ZXH3_5}PtPz(gZb9-BhT?xI4t(;|ktPkqnf!6W581zLOi$@-;t?Ajv2 z=SM805h z!|rFwAa%6lj}yPp_jH(sUcUQ_yXTFYI5$Omf!C=NCl420b>oC(Iy6!E7*a44y=V4B zh1~4hN{@`a`U1L2Ff~_NhWq9{It(~-0~5Ro`({+`RIe0Af8(f152x*s0uJZ_qX^ZY z6A<3RnNHp3#Yv4@uk^@3id$tQiclYijGjfpIHtqY$FrLTMS~#Pck|asgTf!`V#H|M zI~Rl937Mu5DE}bDC=JbapLTP6dN}a8qjPR!d+WFtw}Ko@*ibnz4Th&K$elA;lMarh zkOOVS-gMGWIXsO69bJz+E;cf|G{EhoF;puo6)o)Bsnzlai12n^M;%Lgcv;=)3`v_V@OT} zgFcWgrg2WV9V?;FY~C# zyu53on@;T2^WLoVpM>oGqtbtrM$N#9(mRzb>Y231~1;Rv~ z*0`Z;$2$j7cjlOh=5%zZJ0df5X5PD8$$>B&8g23rcu41sy((!^m6u`EtcDQ=$zySH zI2b+p3$X&Gs3;NA93(Pw+imOyl~d84`4!a9(f}03y>8&yE^@FDzJfdt=lFEancUr{ zMhsGV1P*9GSEK<(QNaAFUrYYP*!sD+(+}t>ECk2gwC5LH5I0o_<4o(pwvyt6XW#dM zF^zO^?iGu`Z8btw8JVrAO$X}}Lz47#P)rSUa|8ime0iddCihYh=4VP^f-LELaze}; zALutXQiVRvB0=P+9kZ%^qTjF*yrT_O@QR{KV#uF17Z)Cu!2v)Qd_+(_scqbXY3~!Fe3(CSa`sqoqecIc{2Ud4BW5b%D z9Ez_*Z3DK)+;!!#o9j2(HL-T4HJR6)4UVK;`{}^RhY;f&8g*v)1yQV_CQj104->_a z2kz96Zr2JFy}|QACV2pn)?eEzfvEy^&v9><^np}75uOa=K2cywPCm#P+2aJPH7(Wo z2<#0u0VF?gElbAo#Z9~Q=|}bpCY0deLEDllIujCh2yZ}>&jEjvEu@<^rh+OU3J(@1 zisc`ypxfR)ln9e;dA0>Ddw?&Bv^84_=r!*|rnf+O_gQwo&^my1%YeB(!5HIb3FZo) zy3BKyJX45J-CKg5Enk@}Pkmor=me=FqRyBlZ|ES7Tr7EaVRns|Celzt7NKzyEgqgW z9q7@3XeT#F;e*)2-~wP^#)RJH3|YcPV5x}>7vBUEz5?CTBHC+uYG&fR@w;ahtqKL6 z+rcf;&zeSK=RgL5xO`V+Sf;g~`_xB8(hGd_EhywBRH#dG4xkL#1IQq$%4=Ow_^yVI z_9!)$0`dyP=j5|W%PCgzm@EjDVN*dP0cvG@)!HM&Fn~&gT>5yf9sr98vGBQZ+Ntq- z<+kWl8Ovjkfu}}{JWMe?|EXjbxI_qczkpQ+Pkb!^^ z|KcRmRI3s7QE(#NOO@LP2Ue$pl;(^5X8 z$Lo&vXsYo`tl;I$KJC<$H^FNm{_%DOQ}KjW9+1Uy#KbXa-KGg*y|2G$r9FP-94*Wg zKg3RInwN|ES93cI#LKroSHD=m2&){kW=3s8dM||2NNx33W!fY1NgJSxMF>DsK%zLA zvQ5)CY>In@vbMx^+E>(<6FLNMODaEflNwC~j*Eu!SD4xYNvLSb@-bOtj?f1KHDt;% zQCtTW`7|18pADEn;k7&ZcANnb4vzhDr9QC8TRqS)gtooI4aQ3}2Hfp?3eY2t09ylp z@7}yO?|Ki{uemToueH|ltoE2C#`k2!7*`WM>__8X)0ygE6#>D7O_COg{vzdz+-LU;9~!zej=n*2S?l=+#J!<^<V@*4h)iW#Ua^J|W01AkVKFAFDsX`LOyQ!bmE96$e zL=)@>e1I>yN{%0Z2tPSTGdv3vmFO;%Zy+3V*1bN#>}nGyEc^C63NmAqY7Id;EifE- zMA4nyKzxxD9Wo%n)5D9Q0){u^p(G;jHsAKcUHIS6gD$#{;<25{4eVq_MB*cr0mvtZ zs4%!0f!meD3mkKNi4T>==UDb@q_J^)JV>4Z1@b&M%Xe*r{_q*v(tiDQP-p`b-War3 zLyiP~Q$bi#EDaKPWUj;ia`xD+l=ksCQ>oWOSLP@O2#oY($Ch7c+!A{*Ge^AF z>_^=9OB^B~ht;X*jSPG;oG{32@39$$wfrL~P2Pc^oIy*0Y2N{l9XRKeUjUUE+;dPP z!!TPpTY1G7}1 zYmt0BMO_T~Mzaa#Siw|lYtTFzp9!eEMNALpA;Xw)Vm3K?6cjfYmw}Bun9hayH28r? z0%0$NtjHPz1Hq6o!W2-okQ0I8jAZo!=Zg~?wL<8vGEk9&>Y?=FQ5;1Y%q1()*sM|| znpF+mP-mv3IeFqdGuS#f7o=$q4njLaqc% zHl^JGFI5T-Z6@&Y1V|T4$13QucmO+$!PDqFu9X!XN2Y~CO^aYi1n@}>fT9VdmPJ26 z8Pp=B*k*Telb4#SP-MGW2HdCXi^dBQ&ZkXFIaVctq10ofYD!z02`;@fM3**a`@@o} zy^|jf44CxDNGG>^utf$&Ix=XqL05ChY#1(qd8jeL-jm`X0Nh&s(L0qNz7{z7fKG=V zJ!S9O0w&`gzTv%k=FT``7{!}^OcZ6_5t3}I^BiP0_&%I&Krn*kKst1AA&6cy4E{i8 zbe*|qIErWNCk{mc0T{m##Ik*Su3tP9lClHh#*lZSzHUS~DSG>X)rjl@K;(OmoyiZn z<~b0gDSmipES|9dQc&}Pe6a$g^0gQk!T^hLq`Q72SVoY}114cE$##Q|CIcBDA#@x` zfV@Z4=LO~KJ%}UlE_*Ja87W-_4frd`msnHFpp0^?kQpQr{m}RU;FC6B$-Bi!gZMs$ zIG5jr14geSW%VHB>%@dHk`or@+MxxoU~m(2No%jbUv)IY=D>zpcUU`1Aj70=dSFhR z)*M!yYZK1|yZbimhA`;-+H)Y-eeqchmSgKxQomhsQ}v|F@dG-|2gICX9Cp#zdV3Z3 zsV}esR(gy&=!~)hBQUbr?=W6;i(od7!Y4l9T)(c_6?t<^%!V;`5@PDyG$~FV@~xJ7 zW+@5=O4_t%=XJ#A$!Z4Y-HQ34t17I1emLs+V-W0%a(vGs^B*X{HvT+J6zL;UEIkG! zIHO2?iiqO;)X+f;(ocJa#x@d6En!0bP%z9$^=)v~Cjc6QiXf8-$~y7HAQIA}iYF(a zZFgO%h?_ONmYz4ign5hgDBJT^_32wy=cSPF$T;;pfhN1M`RwV@(;+|^r9JzGHUudc|*=GSqGP!BPna#1wp^aXJK~qi&YdylKJ{ z&$g*_gUEHRDllCd4}FoZePe$}G6G5y%?F!c!uKQ}27XT#V{ zXT~F8BQaHgdwD3e!~H0P;&bLuRzCPbSz-`LPz|>nqlQ98ROl4M7G;s7AvY%>-qJ=G z$~<7~^+;7o$GGhcoh72mL9kAZktWAyks$Yk*<-e}qB00-N^c$9Wl$$DH9-PG2gYUE z6z2RQ+M~lJ?G7W^_c6_RCLohR1%Uy6_2l+aPwTT-`20_L(VZxgG;VXa-1%w(T2GR%=Tj>DCQcs zZ~c^!Zj7O&IxnKh@(j*omoEZSQ<-7OKcC%3h?RGm=hm-#rg2gUL%Xz9C*5OU9?1HE ziead+To^F|Rf5lZSyip zbGvpyi~V=|)%SW%uY3bj=yxg;zZT@dha^CV$25W$4#s9^J)|ih5GcpLy9pnz0nk8Z z1moptFh2=;VGwLl82VUG{lPwSws00Q%xCP*Hza8UO`2j;=+~gKiIA0Z8(j@v9Z49o zH9s=cUGK*Mw5zQOAk~0KAeCFIngHD zl3cJkm6Xbkr*#<;UnLLD)o7F73c;+7TGi# zR0SD0@RLHs9)eH*Jn8_hYI?7k4|Y8yJyp2T5;dr^@i1H@nuO1200Cu`gL$M-s{1on z_cmDE>_-Y;_~Loj@h_jfbyo<_v^IXUDBM?#Fe>XlWu58+jyVSzCH8GY`&OL0-@vBy z?`YT+r&9q0u?U7e9x3f(0Ns4HGr!LSCeIb&S1qEQhyev-#grkxWcF+P_ZtC7&%n;P zmG0JW$qu4wZeWpQT`oE!Dl0`e6@aoT?SR-DP zvt-(+5PJG?m@>ko10^{R!^l{e?4$;KFJIRIBX$k4bjE)EBvtc?ergmmLW=v2y*D&q zaKIKxF?r~h4Z65_xYbBnj%6oJ!6(rGq6P5PSB2J~3}$G>dv_?g?A^fVHX{fE6C1KQ zcEhVINzl{3&-kZR@BWaB(KMis7Ay}We2=boMOBY9a zBLg1(uMC0jbr3;17bG6rA$X1s)gz8At4z+k(FWbW6~^MKLAujx;8PJ>!0+q;4^v$4 z`|=8-<1odVZK{Y&6FD==M>p6tBzmPe!@)e*1RM|?DP&?D@^@XL>#W0^y$WNQaq@sq zz9tO40d&Fo%D(6UD?w^NiuMp8+orNd`S zmL4Hm2ReMxMAqq3(t%FD=k@XbKOXnP!**BN!`1b^uGi^0aw&WsBDZyMnX7azbXA%b zWJyi(Gf|xYKU7V2(gw^L$v-c;xpdG@s*!Hd#`&l!%XG6*Ot&S+x{~DS0MxztyFU z=V_Pby$JZ@=l+7qL7}07trcS%<43qf`9aIqPtp$j_R=R~?V7u2$uD0l(8!{CS(VBZ zoguo9N+y2A@EZE)r1INK_O9`}ntaP=C=C=9wei};QSK`iIR^i27wNa+_y%1MYncH}(xNWHPUX-sFajcfewpsdbw_)rkXJI;iV{cZK+BqU?z>>n5vMC*87 zx+ZM7Q>dG|+WyML;)Bt1KQqobu{X)|V=s)1U#;8JZ&B+>*Bb^z7no-itMn6V)U?^( zBL|~AVTo9(Atd=dA9lvKPiDY2p?4ajiZwfYHQPMwd9Udq0349^qKAs`*N+dpjlyVi zO80v>IgW~UW6OZ)q3M{E!cu(R%UPIoe9(=r%;3-<>LXalIMhkf#+5Nbg@PT~C#>p@ zp6&T&o_9nG&n%eL`F(L67c{XSa7PptV_L_%h%R4_?!#>)S zytSqSfzs1W+1M$Q{{^pk*URQEHlYsD7eBzEcKSfarGGJ-vfU>PLWK9cS7>We{#JZQ zWnt^5KTmZT@2mTsHKoem7_0ToAdqvk8?xPKsbYlhR{eaOrPw9I+@!kFWP9TuslE;_ z6Fy2gkDC{`$WJxT<-(jLQ53d&;b&J?Ml_xtH*Yl-NXrGMpVa^6s2_p;{6^lvRNMML zuA1VffDe5JA9`Wla_k#4=PwF!7Axq!kV#<>fc5u7CcKr!la1W73?Gq&R)uffCot%K zg-ZdLYLLZuvmGT5?2P~NuAA|!B%Cu@ zae&}^Y+HR^Mg*iDqVC2bR&q-j?JlBbpR8)MMp>LaR5E;JxHWwcS^MqS z%8vss`NuWw0cBruF#|`69;4N4RQ!Q{ zX0$&br4B83&{pPv#hUq`@#tN)ZUwGi11>-0H`(4;C0G9+l*e%xREaEKI87&LKSv zyni;gFI#sK{yefNfR&4?&eWKV7c?_s>`;x$d2}K!N$4KLZq!fl!6!qa0201XgQR0< zLL1Vx+qpzFaS(Zd=L$x$9~e2S~X14WBjKv6X9xiJ-~Tizx+-s?EN zC}g|T5Lmr=!(7E^Wd^;OQth`-(7^Mwy157Klrj8ymfwS$@>)w%jJ1nEX@u5ZRo@JGw*Q6ID^5?j+2i1`{UP$wuXyl5ijPTyGd?z(_CQ&oiekOle?Ee+u`pk? zUaP8umF93`cdj|bWoA`rb%aq95!-qjTIDgenoHqY^=iMtmJmh#j<_`RZhksf*Sicr zBDt*6fu9Tuu40AKQr*pOKuo1`LB8G*wckJuHM^?!eX~K_IZT(2_X0@1src;5gyj3> zc4wo5Em(aa)zJ+_nz~S2*1$&-l{3$WVaRp)qs3Rf_k-3YI3@-ojM4di)b+F?rQfe@ zgxx;B&_~4!fP|KZ5>bHVtr3e`gLl5AtVtMncPbj{qCk|`{qyqhYee|7=U1ZODBMZu z^=2mA%{Y!21V-vu_Xu!*rho;VH_&?;pQ?O53IoXMEK`@PX{Ys9t+WvI^xejnMj>h1 zH`)DzObUA7+N+%AnB(2u>Rd10bGPO^RZ?-JpBktsH(tcc)dmXNuJ#nW&d2xhg678M zuf@{ol@|r`>AwBcu1gNM&mLE|6sMl^?JBm}tq>dlM(Fa1oX)n?{f#qmrX8}@`s}p0 z*o=zxHGXw-->Twn!(|o4OlMM8vp^$p!fKoh#tqyvZLx_cH7H$7>a35xIlMdzJ zCA{i=PU&cuVKU$ONwbhM6olPA^1CU7YPHjq(H8xMH>ScNp~o~m77O}W9*ayPT@cem zmKHz5UgOP{VW2>@S>|ioWN7rnMOBLL>hgqh3Ht@xT^3+iQfJjNu@?!2=S4k$&3 zf?lQfzPZb)?liSvMx(DPV|}--DZ&AKVc+&M)@g4qVQefl1l_W5z!KHZrntYpv}>$=mPAE~!}@sImihO80Q zmc_pabYueMDX?bwYp_9Z?Q4Cn4%OA%qmrPyg>hee*mR%IUwjX#yWU8J3uWt3S$GGJ zB;Ft^s)_uM3z4Qycs;Zb#=-Bn`%eil`-_#Q3ST({efgp_orZQ8Z`+wv83o|a`?T8l z(5EilZ(KWJU5a`X5Zvhj@y2{3rz{SPWtL~ z#nZ^Eo&QtC7SSh*Ei9vVJv@uCsb&u@fb0R#?up&x)>*M4{MF1UjveoXn&}RQkHi^> zL(LPAsY-aGU#i*Ad4UCiFX(+qU0y5>p zfe7W)6|&5;2b~Thq~Pd4kQjLrS;!G|l)Qz8g8&Y*(|(4*Rert3Tj-UgZy{qZUbg0} z@INjN$bzw5ELK5MuC?W3jT&5P(R7@u8r{CQAWb72UZrzU5%jl;ed$5o%@F1UBqI;< zO09I&pqQ+{Fy4qNODMW}Xp7NWk_t)8=d8z34{&F_5*7$G>D^mWj%;c%L)MI9;Ax1EIoc zwb^h@dkgSu)F8XlzaKU3{kOEB%27CVCRdMS88IPUfQD5PKEiG(2_DhD!rqvEGS(q? zXO8@K8bac>knrvNGa8Qt9ZUs}qm4o)pjvtjn;k!0;lv*}hqlgu2`C)p@s@jNMbIq1 zFHz!)fUYr~hB`)4J0eUTu9*^W>^VkuZ8SuX1B0$<)_%=z`l(m4)F3cj|MG2YMSU3- zP)phY7qV6^wG|DC>Cwpar;&c^k&&?EGc|z3`ZfTjDxOB9B23$$%49;bWlu?*1(qa> z3*@4tXmlG_;v5q|y!)_1MDBXMbC0cDalHM1?T5SYBvL7q(9tGBG-M@u?*0Tg3G$o$ z2Ej4(mfiXA%hLjl+j=gRE%V{0qc9tkC;deom@;B1%71t+ks|Q9r!g7vZy@ zN9;UvrT4kGXTBa$>X|z{>sAQn3T$U+KyFEsGz7p*s}3$2-7=}BS#eNI zhlZpov-Wi7n&dZVss5~$N`^23&xN4s=G zdz#_hh>!Wd;Ot%VE6Gc!3hl-quq20kydN3+oUiZNuD;_JW@!RBX?5^n zmi+E;=UA8PBHU6tUfFGh%#`^Kp*ptN*F~dV?L$h2xhAOPuU9sR-snnacTIO1@F<>& z)&iBcvfAhH7!fClQk*?o<3RgddM{709w|YywGW?^m>+icg2&mx2SWJ&7!hfy@&Pt_ z;+oaVo<8rmB50fiZe3pB(O2iMU==IRTUN#@UY`L0!_&`t!xWiN)p{#j=Ffh+me_);^lFZMnxU_`YB09^xN-Sc7#n|DAzaNu6%Gnz$Z-WW zai7n5sXeS`Y+w(Xp<@Dk&a$2ezMh>JOgx81b)?j)nfFPi=D%WmauT^lEe0mZ=~_2% z{zmv5`+}~Lcq9~jxdsP%-G~c;q8r#_quKbk)n!op2&0WLhsU;IetUVb4 znnbZOk50Lptm&wNs&7@;PP>q;7@+b$7kjd*wBvacp~1qkuuGWWn5i*GIiJdvaHBA z(q6Z||GjlqWKVr6T;{Qbd}c{t=#0P}3Ej?xRVVlUwq{DC*~wz`D&j;f1J`duP8vkO#Y=^lsih!swR`aDhGpr0u&GR89YF+;OmPH?KYD# z8OQwQbWdJf=)NaIWg7R-CboAxW4|EY?7;!HDelk7x$fvPm;_L5t_VM)dHsPdm1laJ z8z`(^uqTmj@(K&UgPk#&HY}b-&D$@-zz>^&zfO$D?aZ zOL_fku=B$9Tym1CzZ}u++8u4Da`~bLEM6Xb4{Mz6tVZQQ$UR)D^-PVN6FvMh%Rl?C zGSBDfv%*#zVl~hwAsJBeQl}vkvXo&FWz(?=rcblUU7igKjt! zzR~vAic9;+MmpR%ZZ4r-Mz#G2l*YRCwL5&drQFh^)^e8xF-nKu8*%9i;7la#yxhJ^ zuNo(zzZYiw2VQVhEJT!@t>yhIx@oVQc}zW-r^)bIoP!bgvxoqJffNS!K=qgQE= zcE_`%yZ_?pTgT{f71wxL+SCPohw!SMSdjE6dLh~Z3= z#R#_Oh(=L?<0gqfqJPPAAFjPHeOl>~coMiS`u1J(TKL|UMdI^y(uhNHUk$KS_CNBx zQcy*#@klpgjx8`#Xd90$bO`kW*8> zk3QRNOqp-$_*?{b=<=@g_jvdGZ#^+0UEzcAMTe$m99$BR-LQr4m|!@5hUnfGW^L-; zp{zz~uk<8t0m}5|`=~Qf53eO}rsb=dk!MT&$oQ~*k}$*7BzvSdcFoAnlKvTn9-f$) zbp?$H-B-6q<~X=G+7$l*<{>>w8{fqaM3%Gto_+Jz2g8C&bz-dcxBPFmG>Yx3AJc zvXB<=wr92tkYXiHi?hq^N7$Xh!CQKEP0nJP3HG(nY~zTOz759TZM+9M-UwF7Yn7OoxEdWwtko77V6jZm9fWn6Za-7Oy@b?ep7%~{1#VD#x|9k z;Vu%)M@K2qNFb;h^t)|@TSt%D(J#yzqfqXmHN$$>j=wNADhB)P_6u!*XcW-=n}ooO zc`GH!F4Zawg!6IrLqbDTftBwj^o++A^!@jt}kdmzRoNh1=H|M#{U zY#J=mG`*k%ve1!&cHX^r%0P7aQTK#<9n?@Cm^h01~7#TOz}+IF{Oxf9id{m9+?*gv>e2hko;qHm&>g zNf4yu7_Iv>OKGV4CyF1_51rd$Gs~7WTY?f_Ell3$gH?AE{~24_fuqAKVMg$d#D7LW zf*y;w8Mx*m!5{4|B5B!ne{bZqy%F!fMbMVn-<=Eg{iWLD#!`dOXCFgd{7Q82hG66G z&6gl8Gv79`-I`TD`?BWN&;D55z!Q%{lj}rD*4Cl#Xk+g7`Zf2G@etk3+gnier8Zk8OV92mR*Z@E;dGl_glZ}+F-q2tb-0#{g44FeZO`NChGnBYwR3)K&Lrid zY6Jes^{VaN{NW~bYZO%{RjKRqcgF8>4y`&Z;6_=+Y(X-+8(53{_q;@(axCcKvY4 z&dQ4otF}h4tUR}+Sk&WzJu&H+svht8Pz35a7Z31=wgWoJAm}57^pr1z!90`6V7zj( z=p{+yJQx!DIoTN{+H}$<393M+!PweiilTij;V#|A1e{e-~%)@ z#7EkSx!W#YAx!32p4Y7z_;U;Nq?~ocl_7J&`e4;~nrHO^^ha}j{r<$szUH~@)mv!b z{0#lER1S%Xc$^Ij{N-1hy6;d@~zkFtGx z*T8GvUtRhM3h_&C(IH&|Fp8+XZLZIJZ|kHxp% z6U7ggyLHv>QH-o0uMcOW8M^!tnX|}o>obSQ*zghT`U_g_w0>L$8~^A8a6VwYO;%Kh zObTG3I5qNhvpVn8|J56|6U?gq0@H5*P98Jg4*mM;M^-Y9XxE)x?tl!{UDiFE?d(>L z9@aTk;AlDJl;@9qI;1KQ_tnsrOZP_QzD6`lj;vIOGY!oMtvb} za#FkUSDxDs?E&a#m3TrqzRZT~DfKRob*CAvD4@a2*Wiw~H37pzzen5(QvUs5OTVBv z8mGg#mPx68j@k%`Rw4Hp_Pm;GYG+Dv3)a>_A(SuAv{R$x3uaZeJ|eTyC>il_YNJg?E{F)!`Nd-+V~9jZn1)6K?QrdX;_(_E|4=08(e1bxst{R8!hpUEMz zj$di$fV({zXj1aFY@sz5JeRoOlgS?bI#KgVF2w6Tf0GzP@{1OW#skC@tN^UkFVx|r zG7}32pb=q57xq93XiUeUpQWoMtpnSUhXLIYW&Q+EMRyfCDtL5D3`_Lh#fO3;7Ib99 zGZ&EHZ8>LWmV|yC?r14)xwOwwp(#x?rq*e%Bc>uv>15v6wt;Vi8I^2JhDhFCMpp435uFk z2k>Z>@B7BXBJM!$*#=-US)=d(#HadMP=IQ}^vveFK35aI5$tdOjniiAzUY>~H6NfE zA#@lxYuJw=15+*^bw0Sl74tEEUTDZA3=OZ~DbT08n($R*bKY1ee|ex0W{%V#nX>q^ z{a+T8D8!c4M=U=YBSkPvHJdhuiY`syAfH|QIf<@l;>wU@(o9|cB)ek7!!TomRcau5jDU%5i_zO(*3 zB972h{FLs6`j7Y499k(0@Y<~H1ZA}iNbEYj=H5AU=nSMGW$~Y7d)%xn#BKrA2%0a< z=Bav9>dFWVim|g?pC0=-dW`#x0~(GAxb)fbiG;y}H>vheYlLg^Km$7oPEgLw=T$j{ zFW~L*b>qtjv9U7_Ru%%djv`R$(Jq>BA{13Vl8>y83}QMfyaOWx#H9`p(7s}^LJi1i z?y)1U{LzWyAM34_X1na+j6B!>F9JK;e7dg=XuY2D5%WKxlUc1VLkMUG_6Zi7jz3(E~!a~4&xa(UvZ1>}B5@}h~h$~)qJT}Vk8+I$@-0!^eez{q(Q97I2sr#=#1i}fLymtDA1WYJG>hC zkwjQR*3g;-GcC|F6HWSnk@Jw=BURIRt%{?rkrDVMT%1B(i-_uSYhicBC&5$<5{_4Q z!+D}uEoG; zEh6|TaJ9oHW-czk_NME*Hjyrmq@$k@n$H;$K%10#r9GYb!t>x>tm9W++B<~~r^R52 z<40U-^<)tQ?V2xsG{HO9+bu;W9Km!397=QR!>CoFi)ToH!0`2JX<{ghq;AK1A6j{I z4Ye#^I@#m;lB|6sRiE5jZ>8Jjji=HIQ&CMYNg&=5L_=D~kEtFzs9DmsP&5;yK*7=v z$p_Jk|MFbGb%mOUgc1sA(aL)y5WnVd!LLo9pCqvy&q+D;ZOZlR018a7cETJ2t6-hP zR1e}Lut1E@z$V}E@5GOAxZvy%k^I-3l)_O{Z%=>D6f=^-j%QVCjF;R53nr7spNWt? z4dt0dNDX!9r~pWPPn>pSt;VTQvbT8Ccq7sHh5KU@3mS$U@RcJuy3b+~TRB+ctc^=lPwL}8bT5t2TpWf+6+zbZ8@N?ZG z*+~o{wg0tG@I-$Re%{8rk4%Hd*)m9eZ=03TeRYdZqSdybn(zppqia5Nkiwf-`*YmO zTjrMvURuwXT!17gct>)&4Iv2c%bV`w+I>+`tF-bsB`m%1J?@)vA)@_M6=|?U#vy1D%w0svEYLi;SG@1T1R^9Eg)z9<-}Gl{ znnud+r(!wl6^;kPZrQaHINyjQlvFRtnhkw8ouy~xWAsV6zDKr}humDH(L!lKav*sT9=}sB$50sqLJYVLdJjG z3&4Lo0{5HJAbyv-L*y~Z@dPZm4MYHE#Lw9%lhh+&qoyDs0cS$ANz=_+b1*4eJLkY; z_9XIhK#dA50gM7=!9p$F_l6{Z%XI@ZM4eAAy$Z+%Emz754RQ{S^rz=LuarfiiqtUF z!3u9)Os|9*H$CM&sxLfy9#->qr!D;p+uZ@$LGPz6vPtFriU@slL;F&w_|8 zvW7{?KK(@4ds4OMTtYTqmkKn%6!3%4Ll-m(Q7@DhW>1~%$GV+ezI3eHDJ};Tzvbs} zqwVG2c2Qb|lsvv;q#+Y`FzDn2^Ss+7BA-Y1ZQ5fV#VswJmAkfh+7SG1qDYc}Mb%RuF4 zhpIRd&}6yLa3kjjilznKA$i#1MR6bDNe2vw;v_B65U%ppQQ&z$HE=0y856PWAljhW zwVoD#eua}p={fhHMz0G>xbZ-UIm-3flVdn~aeSydmE4M%>mm?1P!?~kL$D^CIrc6| zG8ZE{gr7#lW;b{#-I2Vc2Uv$RLOWDW>+X?%0WU*f8+$gmxB1RNp*zPb4fP0?K?V%% zPEdCZns^Cs(Aajdv6UfbNA-c1eI!Z{vTimdFuH;$bzozZWxkrYn;i6`HZ5*os1dha zH4j0%i!4k#H}g&V-O)4NlHBfqE9mf!OaF@47N`M#x|OmC1-fTtwrnW4O1-uJxbE6N zV?>x z0gT)W)h@aY%TbjDTh{d^=lWU&R>7N7LLN8a1K)Xxlq1OZ-Q@bQlnD}ep!(AxY59C& zvyr#ZmXb4v%8VfqE#?aSLc$cxcTK>}cw68m3$!BuqeBHyiKJzRZ`T-+7y>|@o^wfq zeZ=LD7ZN+%<@@fPcdsA5hV8eNf)@T<)9!#dO;pG;b$CEIU?imXn1*5ltDMFEoMV&I zP%GLEooeeJPt8ahOZYJUAMx(AqqNg_+pM20{mw1wFNfPRGHVsKW!547N?X#0cWav@ zJy>A4u@Er5Mrm;1;g#TQW=RYDL#IW0R3;uZ=1hdhY8*yHM&e^nc+2_S>pA(OavJLD z+3+R8W7a(K4vJ#EZi$x2^OcOqQYf5r;n8 zc#K*)f=!JUOeG3%`FJNVb>BKM>G7;R#SmlFIw2jYvZoo>b|;Ovw-)D z!Ls`pg3ZbYaUzie>ip*a3Uu~YCI4OUxX)E?V2H}ti7ePP9}0lWfBktpa169IR>W?& z(B`_Oy%8_u7rN96E${PD0Yz35Pz3$OrIp=5yDY}}>Sz2Ma6{^9PRe=xV%y;2Q%kBX zD6J^YM2Q6)A8ypqy|d1su>j_V=|mLwXVb2URJn9V9@s!X43%GwgxD<9*NH;tq}tx! zMCpYhEw=P+@C2>wI;~ksWQQj_hVXX5HyPZlYp@x!UFi}0TCWeDgdDk-ERX*Y>iU9v zo1q)gv;^9rI?liY?3MAIwv2#QHTjlxXHN%QaNKQ`v(zfjT`<=q-s!rI#(m!;%*-WQ zv(H^MDTFedRJ?FxR`cUr!J_c11Gr;e9|f3>--xXqYf!ry>#t)@XV5~7PFuZCG~#y0 zYC%8t^FWP?`ZEC%QFtRK2=Akin_~3hmd~Lh&`Q7aChNSH1dYzCA0gAh ziTa`lD$x|}0(MD3eO4q_G>0;S2 zt2T8>(>1%Vv87G$efJWSk0{dyu0>5Sx!9!+zPa>>2LT@5)JtHM|9g{a`U3nT5{ybR zxJX6Q!V}D%{FG!(yM3Cl;_JnyZ0grHm3#ZP=|1177~B5t^;^f8_i`>^A_|g-&TYIJTy3kql)dW0{s0fKcJB)eafph~ z`SXrz`|q2<(Y5jD=^!h|G$3V1t(<09(-#tuYPoR4`MM>F&P#Er^B_76xEFvWjyOde z^$jI?wqz2ArEb3-P3+OuZ((s%XGrdbd~D8mY1Ar?iYDK&;zI9sZe5&{Hg02g&k91> z38(?eT)X{LnRS4_QAkFR984RFc39lOrg3MAqnbEPR%1SK+kYgxKyV`CrObI4RyE04 z0&GeRP#$RGEZgmyvN!c?F7v!S_&MU?1Y#(4*Exb~PoLA8f37_o+3{qF+ajzL+gY_x zJhIB?TjSOl2oibx32-0mmqmH2C80h1)t05PVp6J*;7fYGdXUalBKHA_%(xwEP9v2% zEKleCXJDnviu5C-a=z21JyqzV?n!uc;wX(lVRgnKsZJ zquyEIYc?_HL)Ii9(5tswbSZ7LbdURWReL{ByGX=f0X$COiWw6x_n4`!n#sYw>;;xW z$t*>6w*3?d*_L%3V~A+u*#r_~VV7{gySZZDl^KzktwJ;rhKmE?&v}9ogb2!Bn`VX1 zXn7m<+staiZC^Z39*p3i%h5V6s<;qs@GZHna$raj2*t+0U`9GSDP6O2(JnJv+*kPz zeXPqUD7P$#YJt^c!{)4ubA8Qi<^&0l;c+(ogd+p*#N$Y7SAV%3<GEH7kpW}IXU19yG$c?v zTXaA846X^`C`BxJhC3=z=9lZb-?Ou=%)Wr_N^)8~8o~zn-?t$#Bp!t=*+Bao3e|8vl)FyRpy5w~H z3jke(HT~X3!d(;Rb%U$wai)*1cvoYmOk33*C7$%Off-cR00=um%&4x)VKRg(dqusT zX%spzb1hhsjpxy_Juqp93- z*Ldu$+;wp4!OoDw1vZ+d8F&Bar3Roab3QK93(_clO+SH8N0DKJGJ^@0eLl!PqVcU~ zT%|bmftSI72#x^ZJImLTyF-{Ur+*-zD1}$J_||a?+!gV#o8vsDMvteP%TgX}dH;Ju zpO>kedgNKB14pA%m-KdysG&b82Hn(y&tyVqopE`nIPxhp*1P0(SQ_K&aeipxf7xtxdVE2H+T@ImnE*|^(c_h?cvch7a~&#| zcUwkK2Gh}~J0<5;CP#!Ep2{}Ps)f28DHlUo2w|9L=Sr6FRgtri%#tl51W1v3Cj#KD z|2hgnh5o!LQ(bMF`R@mtFZNa*AsDd`RWM5wf}deO-)5&!yQ@l4i;!boMI=n<76Rh5 z&D}9i?k9rpBq!QzBbk-$8<*wPE_tkrXr2K_8rBX0CM7q0^N%5TrgcscyN)Cum1kY7T?w-d+Xo+QsYYOO%^y3Wb%c_7%`kJfKuehiCaf* zJZL+w^WxopDjHk2q6+AESw+aoxY9FpPmW5F!vVKA@Yc2Cshp)qq>C~mf~&IyFC~gV zM4V{j+Hn7s+tHwUr;30JMc&hUaYr367 zS(VKKQV%~50;G@Q@@eDIm}xT~rznnuaZybiY7#tSIT9YyMs=;O+3>TZo1IuM4orIT z?jwad+97w8T+kS0JSij}7GGL&C&yDADddaKf|E^B72&mVPp9L`tq}9Sc@MeMCxc$_VU% z^Vx&@tPecL$M|u4xs+Z3AovrTLn}-V`OJ%}QWoe;VUg*5q>|-7|K@^HYx8ijei63? zSD>dSCQeD5S7TM5JwFPZ92hM#E1!l|!jh<2n4hfZtZC^b||q-W`N4 zsZc)`h0)pNp_)4txG1NR;4iUQ?gEYLuQ9$xxPd}_vYO90v=uJ~EK$y)IeXBj75BQK zN}}(DW8WzQS`0=YX^pat;~40Zbjn%2%qeuf%9JYVS4eRAvB9i4iYo%594cPG6cNNt zf(6!!r3YBhcVx_q^zUc^e$_XaZeTg}E1-e;f}W1{W#}k}>|P|-M_&)*6d>M-ISaE$ zQsmu!!7ZV{$Mtb`Ey=2UJ63ElSvZi1@WO;Ul)8Ll`9MVO4*P&oMcK(eXptAm3e-P) za^fapuSr}Je+03WCkdep_ssaoo?WBaX?KV@@D7+IqHz{yF5ReCO&9iD<`mK_n!#@q4BLI=n)Q=U3uR!$b=cG}ychE8a{{XKLiQPX^j>!i^Gp-8V z1GmUN(ae96dM;s}asun$w+CHG#O!+g$}&b&HguvlRlz$w{~7y|Te<8)glc-BKsRzu z2RSD%1}LXNj+y=}+{<(g2AQ{w+oqTuNkGtq4r-q2v{icMs;n1R%kz5ux_?qsmd7D( zAJ!`BO-=;-p_EI@a=$aUk1y^HzQA=i>{qTHp5W-<*RTO@*&NtBOPM;cvt zW^0l2XgPUB6Gk{(BkcGvgX7(I`s;O{(?tmz=F}?cHm11>Do^fPHop9}>uHSXC;4nh z`y79TSy@au;-?@<gVSvmp#@=={&tc>Q22yU;BXQweJG=}{j1?v>3n_*wZLr;`0C)MZ zh+aP^#-p}8df0MLhj3QsZglW#HT|Th z_Y7GdnABE1QlsQ?>!3-Zoe;^dxP68sl0dRIcvPie&e2T6QRE=?5&h)2kLpK2B9aov z!MrK^W`w~PiLC9ePPN643an^t%}6JK2A~{yohkggo_7NC3(9Q$>#!sd%1s`|M1&aCQX{XEwu&EOSxT|-#L1fEp>y#MuJjR%RwB^*+#Td&#KT-; z%H{eQfHq^@T9H~*bJaq!i)FUtBH0inJZ%-+RgbMi|v9~63*=I5nZ=kEjrig=_A}kGM@whgI(!(9z9xmF* zV^UyBt(vuKvIS^V(g`_+28+arDLmE!X>XM?#^(Ep;v zpuxp1SQS9ujQ%KjsM(~jzZz_C`NU_-t(GYB1y$TvX>VZHW9YyIzDgOsLh`L~ly4=X zwej>qz;TG=HE$ezxVrhZ`w%IMYbHi!p$D`7CiyP|;s+#QgA#ANca8`B-lcEb-C7va zYG`EpX5_ypK6|o$+(r>auFn1fPCCLe2O`*Dw{re}6L z3z%7@ShV_SL_)VNz6z2F0Dug#h#VSd$hW@PG2O;C{?pf7?ux(s1>Y%Az;ap=RP+R? zG;YO)qX5VCbQ|vY=>;8pltV-oPMuUmyWD{B2Xp7_<)Pg{CKvX8^z!zV1oH=R&3bI$ zXgC=z6Gx!UL}>xra`DJ3@JR~&fyVBTM6)*D!AIepyzTa?iOy=+`MS64+V@OXd|Lx3v;ruEzDiy;!lYc*Qk80YL(yE*lE?w1;Bo#6$@T7)Gf{$?74HS z`>RQrP8>law3k(Q?mBw2!zE2y{H@v!XAq<3 zzBDR+tI2qOMBe{Yg5b1a&MoD6Hqxkb-9yPs*T!D4_czu9mfZ!&AjmcFd?jIY{k4qC zO;x+KH9@Z{Y%4ptH(@UGp8;!AKbpuF>@fLkH=-KO;8^s3v6gKmMz}GaC`_7f;~r*% zMx>F5B}>9`TU`Jwg960(TL-F%pAoPJFB@P_{FfYv^jkkbtKa_L(S6QpQLwpujK3N=_@+9tBYp3l1AZ7{NbmA5yVOI2*yz z3p^Cw3!kC@esFKvmeDC3Rwkg;DSR}u=74e8`YoMm=Y-f{$RJ$beO>STW0m!*}k~=I~ zo$qa%IKYQ)iL#=YHmCq=a>*oMI^?C^R=RVQP7+2iVu*&bwFgTqMxbfZDi3u1FJ5qo z7~HJEyurokpxDcQCXOgrGB?`SVLF2=yvUQI=CC|6#|vmKC^IVwGqt^%kJJe)}ruvNuELH<9b;;qR2VG-~;*y4{lHOg!u0d2%8s>YNa&X0zBB^q#w=WsEmO0 z5CbB*9l?F>oijFiQaJXV_~^P*`l|i@Lria(JlCAI5GGskbl2$%L=%T(SWcC-hpLjy z17|Q!vZ|)&hl&Yz8!{n4LZS%Gc8xb91~dBW$4ai9T6*{+#r=`5$3(29Lae5zSQMRa zjr3R&XGi9Y*HPuFM?Q7VzO%w4Hlh+te`(w@x4`Ww94npoTY^_^3}Kr5A~IlGekV%J zOxPm|y7O+%ggX*)Haa7gCmIoX|1ww;oZ*as1QxuiGsh6FMoD6NOf?s#e2n*^;pJG* zuqF=%4cgG}G(zveS2fH&E|zX2W1FqJiGTJYF{?bDFpXT9_L2$D{~RE*gLpR5UVM!8 z691XU-7>P`{NxVHKfpOnhl5p*QA-ZGO3=@sOsKB-aEJ7=(}~Fs5PaIYD<7rB+Jhr{>#SWue*T#8F?pa zq}!`wrWKAFgZRtP?sV3dK-;K>)k)HwvtfkImcX1N&!x?D~6$>r3^A3`Eu3^Qm5tjDu1xFeea3k$mE|WD2+fIxo4sc=6iG;a#j_GouBM3Ob zaYESeRmHW_two|xZzOS+G}NP%F5Pg8EsAwaac1=Syi-if3Iu`d~{&n?gPq0-q|Mn^jPwWf0p#>&d_DiB;MG)$x4Fa))mYhIDI;!R z_>3lPvOLx{jloSLXEf#==S{E5Zs4V#I#oz#p8aaJ9-jc(l}LpB$k}yH53aCFtrk#` za7zw+Pc*ptYEqEEAx&&h{rB|Kt2sxKzae{46|7OrYF=+l-LfzNH1g?+`SybVO_JMD z?GEt%HP5{F733kgKaclHRWU$AR($;zjo;9 zCSl00+K|m3HBWMZHKa<)`Q7Z*tRWM*#%Fo|hc&2JccWYgnw5{*mJ;dYIQg{x0FFO| z@mC<1W4p;!(ImEH&l)SIZg;dd`_s`_jwBTD>Dm*3=o%$1s70Ei6V5l8p%|SSURr^8AALfvMfJM41Ua>o3-2K$NC~p%uqO>;* ziNf4={s1z7 z>2S{+BHH_8wPIfa&m`vm$Zkt~yL@Xb&ClxV-}bOLc!3EJPMvGI?g9G50|H8Mjm%nW z>2XI6MmWx#@4hJD*odlMyOu*iR%x~UJHhgWzI$=@eD56UGNVUN z<=~#r<~wB$F@#Az5Oqbm+!F7j{`hN8FzlYvH5q)mig;h+6Ei~;;hQbizgKH~xAETnaC(yC!%gK4TyutElnN}NhCNy5 zIT@7=BaWf>cXEm4fFtH~iRpr%>@__mE72gTNURg`6*ViFd3d(Xa6|ZsqBbKJ=xt$Z ziu`)bZ#knJ*Sz5-z?+H&s5m}{<$A!n=5FrMZ_lf& zv)DXryPEY5?Fm}Ykw+AT_z4g-5C|juGxl2?1o4i3wj@mjjOly=E@-g9b6#dtBxirx zG`ITz=O-90TX&i_Gu#m3<+yJAO4Jx651JG~6e2Yj)wq^D^)a0bDF5cPDipW>ejqeA zAoxPMXeD9y!?AWRazR&)vFQjjPE`Nwh$Fp-9fhpZmTjaeac-=a&0#P1$LI0E2929l z%H471J`zu}xjw~*s!1zdLM#zi$`aX^7+aqMG15m9;L+U&xzRXR;a7YzwS7+P%fohW z9v{|z^z_j7^_%Yy4>zxy>lJW63>BAs2Y;ZA)?=r%gORjDL|g(&&voZ^_sjv+Ho3WK77!gnakaW-&z+Q3?8mI?=0Xs{+#JX zp?A8KDu_mIYMKIt-=_VnfK8p z7bSz(-aoF$Mv#fAd*aGViyC;N9WM7E!+oPgU_ftQLR;pXhoY%yMb?9H3l;es$;E#p zo~|FrsGQ!7pqxxKgRIkp03(Lv8dd!t|Ggg;fJ(dSLGK;^VXUx(v03(J`D?DAco;od zZsGUP+-Kl5w@8kcEdT79<5uF;%R+N&?&=`->U(A2A;4f@lt0=d#)Z84<2B;5#0h?s zU+{bX+EtUOs(W!~QMj+J^CE|ho;E-Ht?iAJ;tSW;Ia7XRD?zHo+SyaA4q5knmZzOR z;`FuTG28>4H@ZQ{#DZY zu3UVGHg5}mczB&5&oTaPgy5g5Hr!4y)OZe+i5nH(*01{M%b%Vs-0b^^F4(Kl=a4>b zNC594G3DkCb0-1<#)9QLWUz!>Gui9eBs|{)V49441EUXPD_%!t+dpyj_7@g?{a0z< zx}oT~&g*_ZH!$mQ_Z(T^pK8|o-hSJ`bLyV-EuK{H%`TGvp&|)N^7Uiz(_8`XU05o= zkMN!Es+8urRTOTB*Q|fJ_3`8_tv88}n{A^Ba51xw+g%~alhAX(Gr;NsFT)&Zh3Fz^w))1t9np{vLw zd<{1by6&QYFEJ6kfhGaDb+;}cOCXWx|5Fy6hx#Hew~dqHpN=vq=p_w0B{O&7mE9JK ziZ)fM&r?pVtSmP-!6NQ1Td~HlM%tR-^3pIR*yXuZ&O`k|j{g}nmG6xI6eF$QBD9kr z^KY;k8wBl`iY%QCg>MtJx8t#qBXQ66uA4dF_ZdQTveCgH1slhVC>cfztPdt3tymO! zbbE?qw_TXC&-TX_ERAklLyJ6SXnlQGP*$X0JtU*p!HLE|uC{2-QG$_@$5fq&H)QT3 zm~Sw4n2X}jEfq_+d_oG_aK^!tm&)&jF7b1Cn!Yh)_>~_VS8V99m=2LPuDX4~93&{+ zLKE@_l#SdQi3Buc(-|?&?5X|)>P6-~zCJ(>xA3-PZ;G93_h#O0@l>JPpo2A#A2k!z zWoG-ok3bEUE@^T5Wuc)5J(1@eZMpb&Izx}N7C9W;eCmdR`+XYJNtS$TG3TJ2B*GO< zh{z&Q61$TCxYmKlg!dFd>{Z9w@yYf>VauV3jaEIY4~)ai<+WA$?TGx3llnK5RGux! zERZW_>upe&M@HNXIi)($mdkT*Q!=^+J;i288Jx?m-JQ!)E>iMXTxZyKS&+VfSl>x5 z0T6rIb`k*#sU5kBi#dk7YWvRq6ifmTk!Ou$sJ39yX-@UOM-8u&k^1O&9*A2U)|^lFKdJ^yXaRYtdsKk!`i3 z&aJNFu_|Tp?(Gemvx56g$nUA9x3vY#>0VgjY4M`&lnZ7V2F(EDn2mh_CaLqc?mADq z>&sMKa}3ToD0*=yoBRBnxMT7{$kWLcK8~6E*!)q+F6 z$DK+qYd%Fa#)Qdj7HV?Q0y`px^f`Q(0 zl}I)p4HQX^kgVD<+=$XM&Psj^yuNdwXgH4n7B$G;pGdIT>^s*N26Wr~y)P&m*>T-T zm=yk{{gu(d;D{9!tl*x z!e0v*&a(Y-A0ww*RM3HmHAu;aM)_7Phn4DRC+ROZ!rv%pMD34Jl?X2eZ4r`#OCi3^ zZMvsj7bO$p^$2)U3wI=EdT+4f)D!&Mqd%!mmE@KJK*Y5bfJzY*O)=T|6ooGtgvU(E zmA{s;#A0(H6WX-gkz66&Z{V#th&RLuy#KA*xdcL)zjBiQ%xQg(c)5Fxw?Ri+$zYcx zF~M*+-sMMGgh@naHz8}>oIQ#690e$}aB)~<`^h`n1kzR;N zR z)=zccQMa4rI&|?ZA%T!=wKwlz23ywf#CA@C7ud=F5v@lo>Pq4zawgnm84` z=pV;7_W$+FJ3HXf14FC$PjNIbB__X2=4au#b@AEL#?&lP*Dj<17Ls8}c+cY9?qVh+ z3c5sTxP8DG@DLdO2f)&!0Y=xN->O1i1RQDOz7ckPe`9yk0=%-{QL)v!ISu=&(eM;& z%UWG?qR~{2lI~`T4KYc|{)ipM4-S0&bE1jH=N!1(zO2I~FZgYgk{Y10y)jU8M^DSP zWtsNrDM&wi9$Mw(fBd!w-iC97MSD}9x8^4xpk1|I!dS@u(Nh-qoMekp%XsJcrVMeb za2>GeYU)aYsn}=+a3kvElB5>W*|2Jy&9Vg5ay9#oW}-{iK8~EDw~ur)S`$z;erx7S z~B{X&rkVR|{T+v>;Wc3K+r4KFt@ z_9R&HT-&OZwpHs3ayryvC*FXG3lej#j%j?^4@`oN4y^Vbwbl+0hF%;_Y%fft89l>?c4-w`cjvsu0NV%HFf z$lHa=OqKt6c3ZV&O`p5GcJIVpTdfvjLudu}5)VAg`nEoEbX!5YyXhEDD?Xnb zY-}bq+``rRBf$~!>?6LA%(bVIpM@8D2u@EwwBZTrHK?5q9i`ih%mKwXO_(pYR3c67 z*AP|Sy3kfcL!(TRZpE{P<<*~Pzn)tcB^SoKwH($>^JULwV+J7tZ{Mw`Jor~- z{!Y}np?ohpQmXvM>skGFvO4vSt$O3@nW_V;<{bWYbQ@^W2&)76j$u}?s?}62A#4G` zxkN2V{`y7U;^LE+^2>U`o`D7dhE|}SSaPH%{|M2; zT^eS8eRY=EJEIN#H8S%(QrS2J(MoVZJZ6}bp)Rzz#PJ?lf@BTTSN~k6cF-3Uq)MU) zeb+%UlHo%}z*!aY?O_`a4795!OY03g7i(rd_`|$GQdbXc>-;dxZQjHTkz z$1#YR_h>qvN!cxq5zkN09~^L37C^Zk&Aak%-5>%~!( zYBbt@^+k&25ea=w=FLerj{jcZJ+tZYi$qVWz?|_t%{wxQ5JgYZ;Upf`nhYCOf)%tr z>*CV@(QPlYeLL%NZN+H~JKkiKm~?3Ui(0QPOkDdup)?=PUz3z9i4yZ2gHykLbYwM> zN1H72D@ksxP1~-Uwtb{xtPa-l0mjT{g^y137p1GeuS?08YS*T8-xHVH-uM4lI`g=! z%d~xuTcwOkneYxG$)GqTOD2c}s9`CjX2Yb&J}Rkz3WD;mDA?qa6)7qOC<=pNsR$^G zfDee_f{d|*Aj&F&V8|jOi-PbwuE*a$^O<)_tGAo`dtc{up2yibbGhZ`L!ARopN>WK zF6X&Pac+?6zN4v;BIU;zTG7{Ht-EZ^Psg&zBUVA+0&Ya+jH*4HYBAd4=6&tue<9GsMgFzWE_1b2I!yY z`v}jj{98VGOU@Pg$_o{|O0;V<^JD25TuLY~9UyPRFf6j-!NXI$0@aefJc{Jqz~ybN z`)igScPrrjK6hdUDYAyljAtI6>- zaV>ucv5-H3>O?FT84cBLnGPP6YtCEEZ+UH}jn@|jJL}>eB(av~%6<}C`$uqzV1t?7 z`8JdE$>S05F0aW_nAW=Br!Mw!=%z6)%PGSF8K(3ea2c^K{ft69!dn-A=YFKlvGB<` zh2A=RL6)^6!JOdRN*_AI^EQwsf+`e;(O0i=k8W>Xs&h3|Eqp=zQgPW`km-pEJ~f>( zaNUWXOTw1Qjj7xIYcNW>`a9ZCa9f~xIf@1g(Z_p8zL<{l(biS>@|+^q!oOUyRD`C* z5!vRInN)gy#pH$QAN;;%^`eYO0y$NORE#5nd?HN7pV_i<$y#+nh9&cxC0%P+{E>dH zHcer3$y`Dw6D}ZNYnOH8BfK3~E}-X2bTjZRhwB%(KfP1v!g(ODQ;Ewivf^ZAP+-xr z>My|m?Dk8A^US3=qwY`>8lijB)l=6(-z{JmD|`>QfzC^kvYo=C);u^>ADvut3E2H{ z26{niWoUW0laepB>$kia;l>G~zjdN(N7BLOg%kPF;rDx@&6>V8M8DA3s`U-`6E}_! z09V{MYmnp`WL7Ko07V+%db?83WR5fnQd$i^L2HpcccVwiTg$$X@IxhLve*xyOW~#5 z9kN(GcGq$)8_sXNoKk#Z>N^>r{r)@Gx%Ox}ocs_OdpgY2YsW!5V*aImufBY6h;H*6 z-^q4s!9khFNFuACr>vRl=~cp$^FO8#EMoY@SY2{I;Rb>L11gGa*DuRMtEYVzHQmqT zk;A52D;6ikwBjL8|JTP=YQELRdK7vPeP(f)>IC5?EwxffF$vUYi5fZ&^*3+`L9TEq z8y37sG|5+Pn>9D6fP)pL?C-&A3Aaf8TSJ(&kLTkVQyYA7S^{1{VHPWnh_Hmg4zN+wvdk`gjZ4Vbs|_ z>qhb%lyZ@D_{wq=udzM;@t`%s1vwff6rOuVbDC6AC%IGaG_?_uO8qa?wAGh-RF$5l z*d*$BQv?P?TU+tzsKP{(a zDUAuw>)J8~q4gT++d3=nR_BKM!b}~V>Dp4MFxq*d*3;+>*CGw&%sGBqA-<|?pW~e* z;oST}H4x8rtof&`Y^}L}Jbd8&ty%9AIQVo+`eqH2js+Ah(q89n5RgU+R*1gXfO`I2 z-@@^f&SSMLcVm5`1LNq$FJkfIvTVa;L?TCx;C;0%Y@v``8tZti=KsO&+kUcS3;)e_ zx@}deAGP*Tj-B$RedhM?q?FB$XdJOco>ni(Q5Szj4nG45rb?)hgb&Nc|4(z`yyjc0 zswij1J51J*CoiHX&Iwl0?vfS+p|UBs`j9{Xc-dO}Q1c|y_-rw;;bg1ccG1VbnuDL* zx$5GnPUq<4#*oO@;IU8=)ini(0*^-8b;RRl4eSEQUvdW)bBHUPO?KUV%H9}W1pw0L z@BCnB?wc$Jaiu}=AV1`9y;EaATRxH+5bR~9{E)WtTD=eD_?dHd}HGQmn-!9*Mr z*c@Uc?(;`w>yPWu1a-nH+LlFrR5^%<`aarFg0(7+T?(SwCNiC!L z{mFv?+goH~yZK(vH=I_p;x-A`+s}nY%KDSYrSPpV)hcUXw_t%E8sj_=LLbDuNuAe> zSmQ9fPs!r}IHdM@zn0Bml!o$|ycGPI<>#C&E9)dm6QOx%%EfLCxrvh?pVH%OC4Hkf zejb+q1+osh+1+v9`N)_H>=schlaL_y&D35#sqwPqp{dg|U+yzDq&~b`rL3+?>8mj4 z*co@z#aVe>-Dw{{vHjqVrn^4jOLzHAhy43d%FrV;B4r&L?(TYndy<(66B~qKheru< zn9V|%AfWgz=G|~+?N<^Z-kf&*C*^sSZ)2i=SBTZy-AL;kjorwPRLZY9;*KP}rB1pCr^#nhUmGwSR1%8~ z-VgIj4L_1W;^@4|AMB=MMCMxQqg8dc@68dxVl;H&@8|b{N>uEdbZS&7l7HW1KR3cPO%7`#cdG?>|^76y?Lk_rPSDk2$t7C&$ z*$!(zB_k$OvA+JMYdcD0&xx}gFnv!isT#F&R$yOKi7zJ5p5uG(SIH9R#NGYK6pAL_ z%KDoXb4PRs7p@Ei#By)vbKh!>TDxd>7jG>HZ0JODmUhE0kbW*u;~_Jt(5Q8 zVwL*LhcEbT@o$k7gaX~uwcYuKaw6Rxilf$UMcsUDlbc*3mzWMF<>1E}a6)CG7WHF|3ObiA%|X>hlT_Q0 z8OSHuc6ZcAst)W@RfQ`VwG1Q1sk)P|{_yY4dHcrwblR<8^iaf%Tlbk*=dl)gquBomV=9Q87L5%16$*}S0z3-H#WWU# z-QH}E{@kqYrUjCZ!sxoiC)^G{$=-xqtGWS0^A*SUK3=-(5jOIOafeh3k}hQWCj>q? zLL+$M!yC~SlQi^pHIHpRU>uNQneFTRx$^6MHyRabS_)rPG;X^m+Ke~5{SRNUC)N1* z79ZH`6K)Mg->YU?JyV`uE1Siz0;-n;b zq`Dc;dhGnLS^{Fo*@!#BSF5GwOUV*Er(<(pl>1mQ0;9LvZwPGl%oHtym6ALSr)-rEqR%>!PCs=+ zI`#fl`j;YJiYL04N(2qfkbPnn4;(SiB73*-y>NY@2apoGAPW z2X*CaZe5C4IUdnv@~@osEAUhf zm8&M73ecGgIe>alK7^SJvjb-g38~5L_?d{S~1VdfRLiZ;Y?I zvT}P>$iyAYOjj}9A-;AtJm~36v8_tbUuzy}q9+{R{tm;V1;r;))5^VWNwMvV$aflL zi>*8sb3(f7p=3629Zk!-eJvpY+UP>3E0`C=ebZ z_(CQTdk*7?#PHTb8!m3zFJtF>zMofY2b?lY!}JG%wwzTCu2@VN^GR%#{?Jb+5R3m63d`PQIAOd#aJlfka3p6_32!P)q^}b7`7kS-@o?>VQ{7*2AW$M zcb>rtQjbR1Fj!R1L>v-DRBaH_6>ks}LK}(W%EhR2VS9ZYXq|;m`I5pj4IWEoHdwIX z3;|F}mKIk`FIj1+n#$3|pvJecT?%Z2I00>MBMLoW0?K0s7mzcgdRw-7)+q6)c2`wu zBQ|fq(4-=6U!I$8D{cBgPEF#mDZX#hU&&fGoe&!stHKmnZ&R>HrXYS-kc>+L8Qryz zHbl>P8i4tFVx9)8zIk58juPw8kTt)wVXFsmM;h$-@V4yf4moqS&rsP(9H-Iyz*^pi z@&(U`!*_x2NLs*2gq^Jl?m47KdI5hLOB^U^{=5t$=I`^gs#bP1M0f;s+*QOfj8}cy zbR|VgF>_9um0zPG#^*mb-D~nce9NkDN$5WFgG$nuLqRIny6Tr2`J^CaAvR|e?O|$L znDpG<#&XkikHgfs0Kz0V3zINqboI*6d2GH5S#={AvC;PKHCQ~mi6FO!9)`Dmf=f&#V~JA)EvCL(jqFK?xDHvc!(0B zTbZ>eCE+vh##&}L5|68$tK|_nIVAS|WEtSe5#`XY5`6{+u^*Gxi)j8ytu-m1g~HRp zaGP>ci+{`C)kOa*vmKVHC633e-6o2w(JV?{3nQsYRyCX$K$!#{2E#<7HM7}T$>cloU-2-qWHqJ&>%&s zmUhm}g;|(*J;HatZVc}kY;1y%wY>u z{K+%RP2;XQg!pPvpwo0c*}-YLU{nGWkwKFS$2Ya_RPWN^mR?ZO`u3gsvX`I%Hl>6iXt zp279t$Ti}=b-9@5{Tx0J`cS`Ny8X8B_j5LLt0xPck|YP6wHc^7>~nI`Cmgn`2Wsl8 z^!}A12;&e&ZSDtO6c z8yT6N?#A=uBnGyO_|Zj=+f6NVtk?3sL9c=fXeVqS?MA z9Y71nNe626klevLa=Mn_SfmauaYG3jS`M*Kp66eB#4-~NgsC>2g!-03|vc~p!*FrDRfV|g6gt1gEu@1Ac`G7ii! zHjUe^GokT%idIlI%kBEQfg2rR>l4P1SZo%M~V& zP=8?ud_qWQBOFYsnh<;j#a;9$eb6qIG&ey7hL?!n1gFc9PT?)sQ(b)G9B)^#q80tL z*4>kjF%vl#8P_xEvXOoD@bNwAh;n?yNR_XauN49BZiX`L}QIg=S(Z%~aS{;_e0bb<-1m6@KeJ(-6g zV@IyWTI$7c7V$fhCrjShWgptV05cK@uH=BY){Nd1v30P>yePlPR$j+4X{+y020A=V z$pE_$MyZOz6aMXF7?Q$u=El4gCX{b!`W8)l5d;Etd{BGsFusbn<8?Zkf=W+nV%)7@ z<{iVC!TlP~ClW?|Gl^{$Hly&|QVk!}0Xo7e1Tp#jp$<$wSAREm^QZbVmx2Wbq?F!` z6Q>y6-7k;W{hG9f3~NSq*T#`VKvREv@NCt;{<+oJApj)HK)I@tXyQ?8*BXKk-3RJV z)}fcnrHE6vpT}XVSiS*8J2l)l%f-8XokPMp=2=u^<(4gqS+6^3>mNU`_7HwY8^~w) zFS>7TQDm(j(J#E1@Ini{r~Hv^Pr~ctZ(Yf$6@2N}%CczxyIi}eW!dE+`oFEe9O5-4 z>-fuDU&l!y-luR^9@Pk+X^BFR%}+^+a0mn|Dhr=O)++96?t4NYtJ7_m_C!~!o zS@e_t8f^$cXGwIO^!lI5a?IZ!gY_W^%LCDFapcOx^q?@F{#{{_m)X zr9wy(O`YFMc)Dx8+RnqR13Yl#j5ayB4=2>t`sbNcd;+# zVMdLP$-#N^M#Pf4vVbZPO&=EGG|>w!I%hM)DHp`jErbx!=jkEym8*YseQOS1XFM1& z{W<4-*5QOVfrW&+MT_YaaqTgfBb4*VOzm1XEUgu~QsuMI4(U*b9ke){%cfYDvC zj$=?1t&!UYHTi0^Of!N~e3P+9kZLT+Ev^RAy z7m3Ao0DQ^FwVj`k zREzv1p+-TPP%UtB+(Vi+z4njIIVV{lx)Un=B>GP|PDLGm4EX$j|?G5kmQysPijqX4Qaz6X)Q?25w$n!ANWRl&hLR*Q1w0q|) zlMIK+=R5h-~exse1pBS&J;ic)P zrKz2trX@~tFSVWg?TB%(STgS%ZptY(*{ta_W$N7zA5^CtnWDPub7H*q68svzm&(T^ z2k6yC%&0Yf+bopd;=X0g;*86;R#;zIF?#_gFRTF1&^`Im9xWKObWA@vI5X1yQLM*X zlsCBNI_`PkV;11PhU*P;o0Z{F`WdF`Jc-G?onGv6-GFtE*~q6Gu{`4PqQb=dSWfOm z@PGm+7%w+vwOwD7-T%$kp^(S!Roo2!Q66#H|A_79*-HOE<}sL`%>&lP2+#Z0$9ifI zEv0NDEo&LB!D{_d{U>iY>3{eHW+eJl<2>-Em~cLyj=F5(`l{|^9YIjvZJ)}0BF zA|`ZiweW-USAcw6nAm@vOT_+rWF07fek4RH+DY60EIF|h62TwPd8OdCr7K(5cNe%%Fe+jyOGM&O=i1HmwqJ#89vWs zx6ApL+aEED%_GeY97XF(Q1!8F(UeTyQR3aX(ihWTvhRg5VKiGvJREbW3>kO|>1lV6 zo-U@!!6a3_Zqc_BRxXX^lZU{4urVP7Z_Qn5Zj$wxw%}gm@jH>FBuvYW^N1OjsNIu^ ziYsYmn#<0408u#`z1u9i=lB7)?Y-XmH`1)&LfhbC4_4~=CK|sDvx0WI;J4OaKirzN zft$`dA8#Be^LyI4H-YfZKwxFOKHu4xl0tJ_Z&s|nzz2X zdU4hP9+ILW{;@}Yg~@*$H)qhl-I`&-lks?!q-P)s_0TE)udp?cEMcoK4>4S6aSslE zmy73!tz}5u?QOoXw&Njku#aRZ#DpXN{iN2wY6Kv-71b!5zv%C~xX<;`vCKfe>=s{SL8#M5My8 zinsaZeS3hftf=fPC@D|&@6u_lV;fW!x!f{L7wfvza8BOdJAn_SmA6l0U9KfWl=xkI za2IY*=^O}|b3eT+u5SPT$TVyil~|S$mpcEE5cg}_yc*qo})DM3;nD}F?7_Q zWZ7L9Zetqt&3?Z(n^dSj-7Oso#d@QF%RfeFp=TWk*5V`HRNQdPKGY~6%YswK_u2yM z#hgpCg4z$*>?A&WB;HzDjTL9#lJnB%{sg>C5xpS0BP!GV;Aup}_9b5J?L9 z0o%ik<~_!<3m1g_HiP30sPI!+>F8q|iou))!;<;P4PUSMx7^08E#Hr|E#Cm4gFce* z1~FykR>ZzI!_hnzDMQX3_v#IY6RTIH`rn4>$EP~ez84{BeQ=cq=stFX??SL3tH>7@ zSFbsJA$-HrCt&8$WjVwb8-*xe80KC!IC~6@_vf>Tag2*yoWLPht6%$ao~Reb?lfxJ2^9;sM_9Ns!N$|3)V!xK!H8v|)dJfP z-{$0r_$G8BpEytb0^Mi&gQ{Sa3Zuno8orxxy`lQJaPTi{e#3~ZvEt8pR6_J;`60fa z?R#d#8}t26+er@_zOoyTc4Y03T#OB8F1AE!)N<;=4&<$GtKEp|W4+I~&t@cZyyqmN zfNXmhYRqns&fh9~43nq6z(KQQOwW&gb1=R8Z5wTDmP#jIh4X+k;U z)m^V0hUx-n!~1+^GvjzTa7(&89Se#->N!d67Ls))6;D0*>rv7fp;&0j992M4)lixE^Zr>0lkhVBsDJC{)kTX&CBMws za1~EOw7{KX1C^b>N<+gzR84U-F3Z~D*TpwI=+W;$Lk75na8XIlQx%?_D#?m(uOMA^QK^Znjb1Aq|P~31(mQz>~o3*q~usbv#11 zF6D?#yT|L;Z;TouwsMU(whtECEX!>UDq-Esx)IO?_|n8)zv+c(R=imqcyc`Hp@{*8 z#r1*IGzaL9!C+s5QQ^{D<|I&6s3v95Ul>lN*!5WExQPO9C#B+tGBy zs?{ssrZQAn-Sxp3R_6CK^0K=>g06)mc|Ftz-G#}Iaka7FST|DCJZu3aDZ(|7eheQQRnwFYcz9vsO*D&n-s>yS1W z#P_Y!%-o3+XQ&mkW88;H}LxZVV>#wV-YVz^MXTWwg)dYd+N-%LcMO6ga~F zvSXp!HuO|izk!+r<9_jaiG53k@}C+-?L4L^fLz>t%>#eq3Q-KO-94$no;i~6SJ zXSP#AH?ej08;T8ew9-y!Kpz~l?u6>niJT3-49rJCj#0qvx1?&;jSH&fX;ZL!KizE| zANa`iaTx*0!2&5&;zZncv<{y7NSt1Cu4M5i?CNV@Y+=1tY9JiayJo!MgIYw&JWU!B zTS(a^4eI{}bE>N_i+|(y9pLRYeM+^rRjdB>grq!G_ZF}F@C@P|oa$A@)z5*eNE|z3 z@V-N+b>tKy>}fcRCY$5rI9oS-Ryvr&?dEZ|bPlrTGViv086Lu|3RS|b*4XECdI8@{>( zJ;*ig7Z_zmo}G9naD=h2*;l``nD*@ux5Tl>hJr{cGUG5L6HGgGq&h* zKNvzP$eL+95Mf+ioVxvO0FQj|w8M86@~$Q+UhYb80|I-NvqTs8u$Eru*TKH$d}D8U z;*P)dS#N||(5%O8AAOBH#BL zIg9X5t~m!_Er7Tx!a1HbxX}a|r#0*bxhK;*WlPC$o#~{r0`~I{NkibKWMrR;4{4kN zb;+ro@d%`a1`3}xqG%+JxF@KYwv!Ca9T>Qqe)9+_nf{<$r~$AE4!2q!a5>C*^Z({? zNfT{#vkpylv<@oGHBvOG4@Oq-vstgB>6_&rc=!FT?L#09?9GCB>jlz*_*!;%JHPyF zm5vegmQgPwd+vG-*QJ&;l`sP_J&#d(H`TanWz&I|r#$r5wwbf|j)MaNfR9ps?y`K= zMbVMtBTY--_7DX5=wrdT7v|TS#AA)doQtYxH16(}oIi_Of7N(tk@5BK_Up;0rQ_Yc zRq=H}>#x%KN{3vKOy#1QBgzlo!Xw9_)#Fd?H87NZp7QzTu?x2CYAEgIIk-#XBy#I7SP6 znVX=Uqd#`&`Te00dz}<6p3Olqc}U!r@Akut-tUQ#_omAEwl1m%8dysxraYAZBzMW97e?kDH zmV_2?^lX`6Lpf{)Ouwp{scwECUp_V=wK%=t>B6T?dsB!KUhn)R!F2%43+j27gV7K$ zbju79W`1Ur7T#MlPEzM`P`T6M5wv@-coQMaHjUse$_mdrjL!X+axTHjAL4ayR;*hb z_gk-bP;1t1BgGX{^RJ|$sp(MNY;;i@tP%)7eK_1UXl7R($K>YS9xV9tx0?xv8ig*7#l6kCI|exhg)qL1G2o6-{|?YQW0=@j4e)IB+0(Y zP{pKqxrzZ}pY3CkeO1%f)K~vG=A&mh)%!YaxR}`ZD7;mNR48BfK1h+>_sNmI{JyBI zKRCX0jeh1nTvdqu{M=E8&AkfT5O^;>BXBGK{zDj$5gpZ&O=b+TxERU_WmO4|6jI~} zJx#-j+<5%E^#5FW4A4U*}#dOPyM| z<-%l1m`zFTb@WU~S5Js3!U^)MfB5_&{tF2@;*nelz7hp0E62KbMT0L=`<=7g+jH3m zp%K||&obFdd?=?;fLU7@dV0^E>HM@c$I7N9Wm<~n-w9WTOx%yMsh5bNuzmF;`;_&Vl^0<@Y;`qy|U#jOFpAbNxD`jeUr<%@ODb<7=R z1!l_T?;+s)Kry>5P4=le9v|*voT0bFW9*H_fKJoAOy|2^9owrmPOPjw;Ci#WmXm+U z*5^Cp-bXl?1GKWdvnKZ38)cR~{s-mD>~g0mO-CM2)+?=FXq0s81Ml!1O*P6pD)$o& z$9XT9v*1+dyZOpqaS zxSUf-U&?C~$DH_gLwbFI@E?mtshLSk!6x%IEsSJvSQ18+G1=5t<>ZpDs8`p|W{UDn zq=DyYOZ6FZ{v$oO>NCvh{0s%U@oePRy$fxXJR@bv&NAeX9}kFoxDO5>KOQ42-3h>B z_&wW2I0NA8sjljE$NevOjN8DqmzB1GowI_i%{4k`G%&V_-&QuzvtUD-tD9($%zN4_ za2RP*-XP0tvJaQQ+IKv_a-PW!x>tkCv;nS##_Tux$n;+`S_E*p^1zLA9=z~){4}m0Qj^iVxWzJ6^IB9Atk`QV0c36nUgP$vAUV{<*B$>Wbswl&z>9!`y~DqqCoB9No7ra+=P>X zP859jXnuz|xovBrIwQ{+poa|JeVvydk|X^Ofdc)bagNRs9)7JkVj_OE`0j5@4a^E3=o!-E2DXEhk-p)u(?= z@~{;~AQsKCVVv$7gh_YL6YV{GY)@#MmoM?voj)F$dd-|2PG8q=9?bhqIo56j)Tdu9 zzOswcyIdFG?vfSkyXDfuQZ)aOvQta3qe+$L@QtKkkLvoXCYPz)0R-NSvs9IbOsp&# zrLp7w#mh$C_tUgAt4fpw_p8=hOY){sB+lc_ual_t-FrN{d_v>Hy268;yUZO23Leys zy>WlGaaDP?Ysi{<593aoq2_TVO?I^ry0wAW?G=WAtq6)ubMsm~nKGq@N(eJ}l= zryjr8@}4OdU4}Ud} zZwFk^j?=Qg4a50{s_~pm?6k)e=#jKKymDu%9YRDWFvCfiM3rRBkT8g%aVApD zlfFI6ZLkfGdQKR2`G0P*yCyMX%#;oKHiWd-p2;Pvq?mn)g1673`6 z{lpm~Z>nXU>(yN$Z@8m09>NUyKfe1`eiX)gC(qRTvWiX|KsAX$9fd!5poHU%>nP-V zoLTUoI<@1$gM!f^Z}`{jRUVqEau~O7;hiNboU;2WW~Yu;c&QZHHaE+imK`$XqGh|o zy!6Pn%2HXA-E*REr{ium)h4IsZO$(Dvb^5=n!#evO(l0iVpl0l?f&*hn7WXu^7qhk z+(P-(YzF}R5ktA086eavL&vKP>)5(vLRnCvl`j^Jr}!=Wg9JQz*&5p}kqL(GJAfyd zh<;cVmLak@WhPjTx){mXA&O_n!MtxGU3pN^;Tv&Bu11)~nyyG;doBAabO|d<}Lu7hy|6Nh3*?>=-AwpWwr>74c%uWtx%ZC2{fEut)?z zAdVmTZa)q=B(-5(+_v~?VL1$N)ctScIr=+o^fHD8agNCMWi3h{1IMNB_@|6)=mt858sVcKa->iK4% zukCeA#rze%8OXa^l@*+%0B6)VSVzD1^6qL6<2yDF z7@M^7vowY)Lw$Eu-*ojR{^&wlT%oI>Xu7*4R1s=z)yAM!!uP<6DfvCR9Di2fkL%Jm%%b zIhOWsf^j0LO7(ZPkbcDy5*4iA2aZcKUlxpkHYC&xHVqe_c30W-$;fR5FRcS-h1K0O zovi;l2kXS|LQ7}XfqimK{6A7@=b(<+2GN{-T9BoCmPY;E3bjZ$(v)q6Tp$rEZtq^d zJr&yWtW-ODHH9{1QAE+J)XfAa6E5W_uKtc@Sc(1io0J>V@26SeShGC;*mYnUqd8N` ze~JJ)BmEIXIQ~wdZ-cIfSF?m>*AZ5%Y+3C(Hy?0X5f1Yw+N%#T4Z%jL2fa$6V&X!q zj?G?~SAbA8$HraVd5q8e%7tbHkJ*Srz!>P8-fE#cPESF9T`e!gawndK1x`&Xu=lRl zQ2NejnetZEBnz*mn$N#t8#-yqMe>X@Jasj8Jg6FF`HfN#L&lwr3O_5S<$Faj{cYO= zO$>Sattr=uf9Ae<{G7h@87}pI83ZXg9By5lI>O6QEehS@D)SW3&_h^KcC>0kZs`nh z+=G0#YJ}_rXE4lOz3%2K3eue7uLbV*piUDDHpWfW;i|KuTjC`yOu1KK^K-=&irm~k zXoCqZRyfjdwTjdR3|t-yWMYXSWkHHnjJ}aUjlmVH(!cE6$|{K$ELJ$=86bR^8>@Ts zg{r}o#g4HU*Tj#?4W~Ns@v4~{w=ey5xe{HRl+8;n-sZ$Y(v85iL>_24MLYaOHZtOK zpT}({!7&OU2xZ7^io_bh6M+y!3E&JGzzvI`y**Jc zIp)-`AY>7E`{~N1QBNMb{wWmkMLMLq_dH+pEq+In0Pq%C7Zy%vd%bmo??d5TNd?2e z+k>f5-MBCPu2D{sWJhu5Yx1x%UM~#4*>pTU6u2Kpd1wNOojkYN*Zn3<&9>?KK+CU+&10(MjmF;+Q$!8tAovN;1datRg4K!-P z&*699Sc%5Y2yVS^EEc3p_k=gb)1i~1Ri545vYez6A{gSi`?Tt@_{r zBrUNVDs&%w80L_xxt70m|C8Ucwjw6+b}UKmigXGp(h;gGLJ^BR7cYpE8=MZE^t@X= zL68WADZ_BS4nb%_CExlqTLwEQg%Y;UBFyQZ+kwnP6snx%re_OLH~1H8Ch+DtcIlmEY(7B#q9Ks?N^gA`PL`h zeB&QWZ)R!JkJwUg)>1#CrK=<$0bLW5@L^yW<={-UT{^EO`{r9lXy%Sb@jm>ZtU-rA zChnen%KGhA6V$&Xv)rljdZMS%9E8wt1jqY&9=t1|REFr=weLMqhZDWK{c>c@-Y5}G zbq*&^yLwBt<|Pu;B2D>@CguNn()Q=qiVlgJvbMVDxM3DFaRwLW9C_(c)=ACMs}zJ> zWf2uIh znsoW+*YLJ)?NG&_(q!D87;ovhUYxM|CAbtcwA8IFWw>T1y?d z8!>4VyRzMERZEU63@5CV2G982tveDY!u;Hzb?JD>2JezpzKP??gh@t87iNq>CSzzm z6l~T94Bx?&gXf3TErT`m$Z>j;?0!BTPdy0lv}SreAp1(O^)aG09r1|o|UwT9)@{PZqQl-$_v7P@Y^c$_YWc3H8m$XLBQn@%sj7qg~>bah5!x#L- z*~e}RCwjG7?v15Pgl!IEcGEJpI4jWNGvgfo$)O_f^1|zJ zf1SSIBa^i9(hh@j>MTUA-C~6Ew1Mlrx`xAa(+H0RmJrKm;R9BXOL*rDu+s)ks1{+d z#p-WYTCppib@t!|rR~4l&*zhO=5O)=-&87(F{(vzP%^z>ZOAJkq37LtL&*TpAD3OQ zRL|%#a8u*;hSMtc%EGQ+(0Y1n%pje(f%+E|@GB*P<1Y{~hV-DpE zAGy5VxBP%dFPJhUYh*Da$4#P?WPcO{f(+x^*?ci~O_lS#s8 zrsX|r*V4;IiX_Db>%&boj7QHOR=;pKIOa2xc6^Vrb5W)q?6jKfefFu9Vy3a5m4cU` z#@7I?8$*2+GYWJ<^g?~hzDo2AnW?vJ_k>D?alr(NbH*A%BxbtlrUIgKXyZhAJdjwl z8R~q-HCZwx`+NiYp@{)Hj-#q?cDF09$DH|f!T+KQtFP>G=pSWrdi<{jF_PfMN8}q9^{i%7TEfYTEa-HKmw8>*ulP9+=^tkNYu=B{Lk`9v}jICLdg zky)*^U?QiOYACW1pW(RRiy&J|mN|U=f6OCac2Vh_@!ltjoCsi3VWD;yyLFuh-KN(> zVdD8&l<>ZX-`)KeN;u{pxGn2f=RNo7`gAo6v@z>w@`6q3v*20KoEvFdprE(beZ=wY zfCAJC=~*qCv!Wrh4F;n*e)9aT$qTx9XGt*Aifna8s~07l8DWjL-RN2i zw?81?hJb^2xLz1IirhDxBmS?}*eK~gwPQOg5ia4j*mmE-&@--`bi;$bBqQIq%B`Fj zPfRfY)ji;MSD)FS%$@{2IsCXF$%2ncAXw|_t*rM5G`eC#>lo61P}yO8YJ(FeA2)aR zFgA*c3!gph-k(oRB5vmYQvTwH>1|f-?|gFX`>qiU12;V6MNt^nxUkNN^c^NmV?8|6 zv``dZo`XLSyTH9b*3$8k<>#Ro=rW=%!igSPaClZ#8zqgU1CB3&47g#?33P**!U{); z02G?CF-`#dBlV0#5nsj~um99>#50w%yDw6L;V@wU4RyLUXn5 z+u0R5egbsIk)W&~a8^?1thf%yIOe@TORG zq2SsQ`z>muxwlWpEvm9V9!J5Q49*j-!H<@f4Fm2@s)T6=qv%G^Jy<7(;zO8Aoau-E zulDNwX~EBohXlj_q!VN$+#hXK{BFetugv`G=T9Lrm-#)?speap3wh+3vM&MRAjQw)Wp|*4P)@&*Xf3Xe9 z{-zSGVXS3;L#N)1r)+_!k<8fNe}Y&e;NI^p^5U1p9#=+KjCzj^GnL95=7x&zSB>=0 z3(-`}hdoJ3Zu!K2!mUWr4!FSi{AnQ8l+3YWlQi$!iZv4w6&;TVl5F@|@Hfh68+Ti$ zP#wyOq09vPFDw@&LXUWn++RlD%V#UOo++FR_STR){U+?MA*2^_!QIiXZ%LGcw`tpw z6^0Oif1msL3jWAQ%g8>H!nhGX+-q1a2Uq}cs@P=n42F?f%ukIPq!qzLkDf&7KnNl$ zcmiptAkB!iEd)J4keXXun3{CSE+TLpiyE$C7t_!XMTn+585HlwR(HQ8B=+MAWnzLr z_7^>Vn5R*ir^LN`SqEQu{oa)SHW)SSrsQe%8-8>!wdr+)2XuDrXKn#o5xF!9(|4~E zNOGcHpq@vQKE&+>2#ZszihMFR>?`M9y1Jikuo8X+DKEke3tj?zX33X4WEuZ?=j5|x z2Y4jB3x{pW!`u(=jLd*MaXzlz+HPFwz4tqty*ug?Y^!cXjDl*qEZQ=k-y@SX&oiaq z-LRT@F4klx!^2T#7IF!``Dwv97JJu(KQ(v|$#i^~YTj3|hw+_nctTd}u)MS=B z4{4I)P8x2XlQqdmzc9w;K~c8R-Ori}_={vQP)#lo6;e3pK_%RnE^6u0l5VIJLxB)^ zXFlggVL0|W*WsTX4A`CTZ_1~#TV=53-X2i)Fx6;*ANjcELxcWNVim`%^F6(CH4DYj zCRC=EtHCdz$XehmamCFkPvX_mm3XC8i%{mu%t>&rNX^h1VwPKD=cvfiu@ zxeG1k6k4)J8R%T{74Jr3w}J3;$|-+cH13jAf_CH!^C|vwqXyI=MSva5z`5w)ZrY#Xt}31FUpU z_c$z<(95aZKW$ySGlkY-QXz|*+sB$ySm_}@S||AHdXx6ajD7DHCX|<63P|r zoKug0o@k8EjABN#^WZ9V6xS1xD$#zMzSJWQT`N2X8bpRkq=fhw*hwM%1wBf5eg;IKlwRcms}L^Du^D7%k;V&6(s1~=9@`uB>6WyA zdAFZUAGjWCWO$Th19r4m=nDZy^94?=EDpmrBeM6iRj{RSoqav8_yGwohHk#d(uY@c zxFuh=_$P;aSOU0nq;B&+P>8?^<=flERq+zIAGI|jZQvTlG_~Ea=XR`j#@rdHq0&^+ zN;)y`MYc;{Y%y1~+>YJM>bG75I1ZD#4b!!yzOGA}k=?Xpdm@VP$JYtHboc}^2%R83QIcGdd!r89JX+Faf{wF-% zId>hlIIWH_zM8}S1(?9cfXzAS834s3Bvr^xH(NZ zY7Rg{4FmO@f}S>0RySSy{mlFtfDyD=46A(qH3Sg75pHMHa0aQM$k0K=6Z(j{#_vMr` ze?zJUvFCLP02O=+q{a@y*EEapKf^-R)lxglz^_22YT@A;9N-vXHvBN2%n)Z+%1eIa zwGqTJX1?d!&<5()301~SA+jarH4Peeo~?GK9wOCQnv-iYDCzE8il|h-u@ueV`z|bY zPgcA+siVn-_Sg*p8G|)7!E|>5R4c!*{aNCmlMVTq7P>WpAx8Dc;;@yuWe$zpB~lMM ziElKP-D}H*IzZ}hA>ATbh>(+9|2sDrmVNVA8ZNJMyu?hF{F-DVcAP$$iUS*pEq`xme6SH}H~cGfy0+qXykCuygu-d$!iL z>$bQwk3F))rBOo}m~Fqlj-_Dxq94uIbY7$KCP6!SrX?ue?PGclHyx_16%)^K+~=c) z_66ppe&ymRwPnx-uCUl#eo#&^-dz>8OBd%WQJLL!SAW=UdV-<;>`>zOS`2d?hu*Tq%;U@PIUD16=2x>9 zk?!g;k~5oM;`o|pcajXEBk*yd^bMJec#l-`N*wVvn|AMm@&R0u@U7g^iNC6WY-|%B z&$wm6xBT`yx$ZAijL_MTbQpzFE9+l=QDZ5OHZ*o`1W6o;5iA7BLSRNm7sBrVPn9!e z94z&q(e3HNj%3Gklsp#G)!|sfkp-1vb~_e{7Z>|C=v{S%;w!1zmP<|;{hUKV`+_w6 zl(*wt*94{{endbK#SEcaiMm+bn^%;3KCRS~ckxh&A$BAJUu=GY;6T&kz$K`zG1>Na zEbqb9_$vueQ1=6T5O9m-YQKWgHb*nvezSnTTS*up$UxaVKr8mI72^UZpmA#e@W_O* zb51=ZQDRZf_{5-tK}3a{rsDlL`2)1c<{(ITyHcuunWn^vE+?mxu-UlmDczjLBtQuBajLm_qu7B_eICJ$Rol=ur1yZSS| z_rXn4f@E4@;Px#KcQfoOZ_R8Hdia`{TRnDfjGuk>0XvgJ?3XP9-@22q6B^MKMVc8h zq3AJ9IsKAYm@XxrP2j1f-AMKD!niAJzpI$M>-KXT>1hTrDO5mKG7#Hry0+~O+0m5E zdor+Zb)j*ABH;eo6zlAAh2E}&Njr^4Z=7lH{@%R9iBdGCYq8`0+9L%F{}I+l!ahE{ zN;Bm9<{vVUx$#r*B^kgd?fzUIFR}E)rOfcSWpN#&|6j zb7L{_^Cw7o2@q3S?CgbLAuMn=K;pX9ZLjeh4rIT@>As60#^q z5{YO8@~QUB@4&@&xnn{hgcr9&u!6_0b1XYoOGAo1gbXJNn4=sc%p>P-`vPmzKe~!~ zHS7{Pcr-5Q?0C@=ALs{zg6y82C)5=RWqk=C{vNMwzuRPk@3e2tKi#w3;u*VWJiBxh zqNlH#wC-z%BL}U7CY3ig*oy0w--9XVkIN8t>q#W4M{sUTvDi{;4Jd^Ggr~MjZPS%H zZ|vT;!gQSng5u!_QAMjHu()9~HjKTUY-r4{Bwh{kHvCp31fMz}mxCe?O>sNUxS;1EbINX5+jYQezyyRCPE>mEr07{FFg{)TPx@ z%6*^u**)-m@28o8C!!otUlO)VRo>6^lCZwrwdw3|aH_IvX>vE(-5Qi)Z>0!IY}U7f za)B(xj1`!9_p{C_j`Cf!ph{0VbSgcy2lbUmddI$Z-^>Cg_DlI<=kKHA^Qi8IU+#o? z&a<_uJluX{uBhJsS?O10U5IKm)-evn;fg#mrtq&zdx71?{L(__-Bq`pD}gd z2Es!j=)V^#GhM@@Yv>_a{Db4^?pZn;y!*pP0`q$v&PsDTYvL9hSc}VvW^RRkU zXmi6%*@V?m67k6rl*NNa^Kw03;58`hJozqc(jsNynR`+8&?Dx(dQ^a%jn0Xn zA;PHb2h_sWIT;w8YYNBGwn7j24mNsB9gyl~K zEjHp(>5o#I*Q(&|6W3rwBGD~bTk#4-u!aXg*tzuX@o_#FX2G7!sQc`<1r5UvR&d<3!p99W{F$%Kp)Qn-@auS%?%Na z8gE?~LG9#O+~svbDE;Pm2)0EsdL%ql?iRgG)lJJ zihz6zDjO2}*wPsH3HWqE6Grem(_6DhfEj1-6Jb(bPF3G)a0d>bFinp9mJZ3z&HB8ra3xi>Nv|L=?&<$X*Xap04orM-ZA01fKf=Kfr9e6R)F!sO z6617JqD;?qZ`4-DQUd)v-OF{w8wGC$R>%TeQ(d(+vE@N$0sG;dAo6Orp!tItAB?8_ zkn1TiaVYccZ=W!)ya6rO{2GX8$ZGhj!-p($FoO>x%vHs4KewXX5x)6IaVqekX99Yh z_(dDuXJAvn#r&J%*420hOOVQ^VIjm@Ya_esWT?`dPw{V`5b8=k05)^(H`wm_e1)0^ zdB$sSv+}P(J`NP&i$qxy?o-|E>rUtsay+dBHax>OmJllYx44OmHWn%jXi=NlFL!H= zd6zZi+_6NI8T^2Ph;1|xPJ^ai?jvIfk2UOUu6siFg~089hf^}^JATF)pJ}MTc`xOw zdvKk4G-5B*|AQ(j+wxRyrYVB~-VmXIgZBerr#Y0Us3_5|=^wKsE|01= zwxcTK+&GHS*Fl@9z-++CpZkhfFea^?X@fLxX#c?}1F;8$Zzk+hh^~PLr4zdqoOYP0 z;v6HVqy!fskU=2cWTox11dAW2aG;_A=1A~vWFmj-cfufp0*Xx?_IcA)cmUudL`^sm z(T)a*fPE^6;cD`@&e+`9a0JbwbQXStPJsvu!Q#zuCZ~K4V7rvf%<92c*-A)N3BEhoF-XCaxJLmMV~gT~kSe4KvA0MttyR zcUO3t7;$BTsN48?La7_7RF)hhU+1m8Hz0qZ)1Ff5_Pkq4 zQCPGY>uw*|> zP=joz;ZUMK>_$PveuuagU`<0MleI6wfC}+ow~)$*0K_Lc?EQ3&;VDTD%kqZ-TgQb& z!#u5lo_vtZ+VKOkM@SQuMq-b!gZZN$3>^q&lqc=-K~@`~urn*js@s4}3$U)h@deuf zc+Et#eG`V3K;j+n0n1-Nd5f>^I5icX-XOCRfHJOOVBcWhVC9z;0Dd<>?qz)TQmoiB z(?kdh6fl$!`=CW)m4S%}BM=ZAoV2HeC3^t(b6198VLNK+qywg)y>Y~M6jv@&41Sf3 zi~~)Du&%z=nTQ9$SIPeEN7NeXNwYT*1YN^bP1oiPt_PInXP56IVbO z6aZpxBnEx;z$2l!Q9yC-ztjYRn_P?&)=%)rk$I`MMe>yn_3s}Z%Z1BhnT;D3ksWX} z)x&xQ9;jvZMUXh6$Z~Sojx$kMZ7lbXWL@1 zpgHd+KGJct=raW*aY(O!8}lk5<1+{qD1~tI1Cg=z>iLr>UFVOaBF_^>08h*i%jwtg zv%`?(_=XpTWcR_B<~Z`=>aaILH`A0hFm4{}K8`vjT1Rz>0q zac|EedW38o3kddO&)3I-oW>{>G+Z{wWhHGs!QPXd@Gk$Ht>wYi8^ye|+Sk3N8w6g$ zJ1eo|aLYCYTX{LstQ&Aq6NeS$`9c`u%metx34f{(~Iaq{A2eVjUe^D*o`~YAY5nH=-Z`> zy?dPK3eloA*m&$Ei0>xL7c9JI9+Plckj5P` zt*qrmiI`0R)kdU<2QZ*-p9~IQXo4N2s@chq$u9zbuSFumB+o`1;YYasG7u8Bd0)3U zN>MjtFwenPESuiWw@TX04jKW>He;GqVld_Vn^NCh@ACXKR@8K9@!4DBv%)_#AG{MB ze>J-seaI>33Omfhjmu__PaKV{)N05^@)G(&A?r9kEOq+&v&j~l?$);r$a-04De%m# zIT9Xg%gT^tWA7R4t@v)j+Iu)+1qhD>2}iyz)UUvS z`3nbrnJ2daAC7nE$V6{|&3Zrf^d!9*tL|%VgoQSO0-OfA&@l6eQ>7L|8#_0^yZvYf zHRO1v_&QXC*W5 z?K=drN}&1IUPjq2`CwR}c`C8o zeJhcE&Ek8hqGFOcnlwcDtRyz(P*ye(2&|BM1z$5kyfWK2O|`mGzH`qUUJHmdQ`%vd%G(rv=n0^Jwt+JHz5-z+fQ#A_aT)Uv@BqlSSUvDV*RJBO4)MB>98>L>0J>11s1ws-_#P zAZf<}&zKI=ucz!)`}(E}5~QGGz>Et^0Po3@q51ExW-Tex;gxR;zlsHhWvRlb%Esul1bO z8T8<)pHQG9R+P_pABl6nKBxNFt7#MulQ5j$%5!Tg$dzu3b{@l_SUbUCu)vcH6S66}ynP8xvI+Il z5LAlJM)+Ylz1jn%G@ctTVC+?~u(#@RQxu$Da7+mg9m55A1kB7ab>QUa{iO{;2Rc5z zJGA(;(-*rbNY8`j3tTvITmkSf$$Aphqu~Lj-X0TK0O6pKpM@C#LZYl<@NeKEL-&hZ z7#Yj;@e6cmcpnY-8p#1mg7HOWMdP}!S_*ks4fLh@h^T_NZ74|r^BXqKKVV#eD+MSx zAl!zI!OC&xM?DN9Lw(FuAkkKe5ie(8KEs66Afor%c@D+$PaJA^kYe~w0M1z0(b@1c zvk5U@bLSydK#rVfGjt8`Sy|gfR0=`Bb`aHG8$!<^0xvkEc^0Q~D)>N>4EG`1L55N{ z%hE-mx6G-PJBD%Sw<+mo)SomOEx_ zhLV^-6nskiYsAccfU_w?S7ry@(gdN6N%J1b_-LUt3*oJV*$gAmM6zG292(b}cQq0) z+PgrhxRuTAWaO>z-Moz+rs%dlGJI>6i2%C8w-&?d8xWZYoDw-AW7728ki}pUo(Qon zEF?pzg+h*&+dRa^{Ei5JQK6k$x3FX4|62R#f&Y+6F7F{i&lSqt9BZCvK>snHRRgAO z5NFpM*ZlXXN%{OUx-(2LCb@2v`@=AHV}ny7geA`X8bmpv)%=PdZKqs24V%JeZ7Lv- z!@3!hID=F~B!ys^gN)E+V(7daf>G$dK_yZ7>6%Dy8f^Js5(zfW0jUOd6R4CJ?N2le z#+;3(@me>y7GRAD>t|a~GlN0iAqNz0Kt4men(p6mz=jYUkYj0`GJ7O&o_K6DV2nHx z8>m1GRN~VO+UxBFNx;`pyO9P_DG=@kFk&I3v6y6;K`o8I zbOaVF%9TZvn|1_|1rSJShh5O;P4-;f(!ND6$HquRa{| z3<{o{p(may#rYg^%d#*VvPs1vryHzZofQJ*?)GlcW*_{AT3l9)xryb5Z!4zE7SfJe zRy$j8*H&rXfQ~^E>S}h<)Cx1?9qR}bTK2t+X@Wzqm;m9SeLU9Y0it=hG&s2#lT%L% z9{oP`^wF{A?$2BR+vp1osZIs?uun;XKVtzzKPDWW zRt*^I2XNx1umL5iHNC%t*}aT)M8!uuN0HA8-1s+y#dKdQEE7>k$wqc2vOSQD4q=sv zk}BOzl67OS4a;HBVyWHW-|&b9+@ILJ6+Zt_cvcIP9WEnjnhg-9ViV{ed}DIxIXS4} z7(^g?1|xyYwUK?sP~#K-9jr=J7BUfa7%4qEaa0r1K^Xf$=>_qA8CW{wfT6KF#DF6O z)ifdEigAy`{B$Z7rnur3L(fZBlO1(X_6X5VM_s@fvJn4)-H5Nhu8gQ8@p6_od?X5m z`UdsS+besokIi1?nD)O2v0$Z&oIB?+uOJSr>$$#JNNWkLH)2(xoB55v5+NUL#qE@` zLP~N@iiP(GBM`n)(3*(}6t?*~45~nTqXjDi4L(qSMxLB>k)U=qhrBp3^|X-d1%ay* zCtwc8Z$1&1Hxz&E%%wp{1?GbqpR_ra7N!h-?cfLfLhTAo(&zy<&*t5H(0YYH+OLms z<*Oa7te+*u&0(rLt4c#q1xaG3LzD%s?fk!NzsNqo$PEAq8%Y42nBx=DE;ntS^_j#> zabW2p8JUTqfq_98N-T`>Y0Q)T=+c&mzoS>89vq_6VKe|F2S5}AW({Onj>NL-pp(N% zgL(xS-bjdtmI7AMIrt**iG={W2k=52QRZ%w4;+>8S)K`IJmKJ?{=zzg*mP7CIHa(8k9LLLAqctjx5Z%T)eI8H2!i10Se2;?5xX+w&BRw;c9 zW)mcX0|sW$D0F?MfD%3+x@TO<`el|E!ZCfYwyq>ubrXl*+R;5g4-3iWU$q$#Ov+aU z{sr0Mx}uyk=s)0N6i=7OcPl+Y^aq9&!f8Z{sf_F+OuVomClb*clW0E=(n+c@m_OHJ zM26$9ronA0LaDW!9RD$l=i9RHMoxHoA;H%=*gO##XztZiEyED@fKUp@!=<5jOqL$WqTs9k=K6E|aQ zLF=iUk-vPr!Odq&Jk8dlWgHtHo||G^N2R9zf(mhn8p6$w?||I|x;A1D;jCtgv0-`F z@p=8p-q}JPrUl?^-8u$5PH)Vog6Zp5Bfn zw=y=}Lgm1_q5Iy2X90W)8f7^)k3x5@c?H0Ltzs#8+yMDyXlmj7hqJ6Z1y{i`xkChw zPZ?(LXyOsq8unJPpbDE}lBfpwP=2c;ZW(yZCD^X!5%my+qhs2yC<`!=4S@H=2ILn) zQ@G;RL;MnRP_;sY0M@(Z0IgZ6o1S@6i99Pt2wYK`cfMzu(AR5`|E`+YzF@Zhphn+I}&tE zl;%93W#BO@Ky!rz$HYT*%&RQ!!spaVEl961drX@m10v!8ff^CN=^?g8XUS~5d@q7Y zJfI(t(k`SBCXkj-Nr!y6af!$zXgN1Mffps{TL2XQZ~6T4NQ`;NV&tdEnQCWa7wj8> zW`DHM;92slLMg<}EOox2MA#>-V6DD>iLm$j-WSRJ8qN4}9r|WvYh@1basCY%Ll%M_ z2AYur8nsvH4(m-ZW^0)(V2H*J4~^mnj53er(HJ^keocaHuCF_m-oDS5c7~$56Ug`S zBW&&RgQE--dYB7}%6F=9tS(cyJwu_#`}w$oGJ2Vsv<3YG@3GbiU;)I$P(5FE;61WK zi0DPg2HOu4-x&x<+au+U+xhpCN@iV;^N3Rzpi5*mS_A0h3K)nTSwwy}>K8Ca(uWd4 zcmQnp&}+tZzB+*AP{n`e7|#)bl19!nPSY;{9U*3H2b;Vg9x|MPCFjkvaB0EW#ozf( zyeD7Dyx820`U?kw|8FAQ=<~bbtEzm$cIQz=P<5Mdn-j=C0J|hYPRCoJ-ChcC7va_s zOkfG873?8=!~WU>QpaH4IR*Z~Nob~LBR3_%EO{+#LuwDhEKeK^YK+k5!6fAUuSYfl z9F%@LPoiny=^U-)0s0p&o>1!(ZpXb0!fYfSD1A_}!1%-iB@JvYkQHPFu?&p!*Q&kl zf!-K~WW*$L@(a~Z1ot)~x!}%32supy7@>g)9=<*X9EOf_Hu|V^z6%4_&HXeR9UiZeODf%f+%exGchI5_VDz3~HhKgyaQ$ zQ0_*!Xq2SQn;mb&7PfhGzettRz+i;KkADKSaJ6X^)AWf@fT86~zw%)Ae7N$R8NVa3 zzQ0dBnF%m_oRCOsH@SY*%Qr!JQYCtKThl>(RdLh2w)qIE!wSQr%wNqv-TSm_czQA5 z>B9q8-mm62Y49k>p@O6U4I1&muw6{AVm8Ib7+(SY4u>Jy8~oxF0nq6`oW89A zwH?are>x-eCkS=O3Akr9I7=}yul8=}39u&y8SR_E%T(w&{VF-f6!vbQp~o=+v?6(; zy{0J%-v@>&ym}4PwCIw76EI!pO!tI9yy5ql{EMhGDKb{^w)0*F902qOn7p>3WsXcG z3=g|8(6Qm+EiyTwSqj|}w#Le!!}>#3pSKb$?F*?8JfGGwLqrC&RA?0~kZvemN`Kep zuYoE?4r1Ti0BiUie*-{=6Nsiv0v)Cp`pO=pS!Q53mBvgo=KjREa+RB;FWNaD?m>%T zL9-({*twL6%mQVW@(dP)QcLIH!EU(bK5iCSUluYiCbBDXu$ZD5$?i4zDOh7d(mIY3 z=J=ST#5t6e96V{wUzmA^V?mu(@~TwydDoR$RxXsqPU%;iD7(Yad2d!;SbolzpEQ{`+-6+yXl8k|yam2hbrRb;mm-?^e_Ohxfjf7$tR zulPw<2`VM!l)f*2{!e%wA75{FkK1#xo7!kdYgmI*TN+BZBG23AErz5NcOTed?G>G{ z!8}omCb4dAN^E)<9pV=${9CtS|ACUcInEvcTkBhVI zqF7Ij11u}xd$yjInXrhqmRFh+^0ZS%*BiT$@7(!vI@JL~T26i;*DW6$ML_=caw%a@ z3I)Jp4J~Kbj)~<*$I`>(yl{f?vU>L;>X1cqtB`NvC7o6C4u)hu5#8&f-52U`a)kR)Mq zS6g-qt3ad!(@|blmdb=CR=|6dP`;4x1?y!jq=69maUkR#`HIA=R&OFQdn-v^A)d!@k2g@592i z&M3Y^@n)AnjCfPgdrWgqr7AFUVMkSvUeX4G!HlIfQ-j${!pe8rti9qGZ~TtLF{}p8 z=q}dLr{4suqBHETU-gtJNLcye`^>1|l04UGsjVqC);H16v_1cfqcX>KQA0)@oHtd$d~k-0noN;F-)?NwL~eU3 zl!dkw<;=YKr&XD#V6;s11e>6OO+Ua-gc2Wmh@|H7pZaoM3HgOFirB&@YGQ*#J`7oW z34sLJfxZbCAO7Qg!lbix{ih>tNQz2Slub+|1)PH$g7;-eyx+zE)d?IC{DQXwPn%Kz!5MCQ(nFFiOGH6aCh*l~aq(ef()uV-z#uHx^Zm=ro)m>I25@Id1g*<3q$^i#8$8uIZ{n{3 zCkZwqcK}~!=K?VTi_mIV=>0HXZ+1MDQtv(?4Or%qbhV3wK;-(jaNxNT8?03L$t=@kR3A9uDkRS7e8~uAqvr%NUaQOQ8!kUGEQ}9bkB>t5oG>E~wn^3EH0j zPxE(i3|!%KhRL45rv?IYN4?3(T{)t*@ox3ICDHXV<;O*Een;Il-nFYuPx|B9z4GsV zOp;Q*ldTt|w*{@~3JmUFcH)4d#5RYio!i^vUHLk5qMT-{yZqtR-kpFnA?0y`4L|8W ziAxG@$UP`YXj)(0!vb?b)6f)u^1_e<4w@cOc~Q+1$rQ~rMN0wsPCJ|nc6GwP^75lh zwev97K!0HXG_?!YFNgHLn(!=IE<`tCOBr_thXk`+i4cH(Ck`wSRK?*ls5<`?YH&2n zh8CU4IY5`ln1*5>AVk~{AiN|Yk<-z8LLR`h)lm(F6a&#kG!U6M<`1gjwSgd09dLphE?`;Utj^^sj!GF!8Wh< zFbwjL=LvYwE);ApFcK@NB_hI`p|$P?c^8}Mj5e?nNV2+M8+EN%QDztd2DKmtgOG*r zCP>OfQ2E$YaMguT(UG;xo-2lUKII1tghwT$OcA4VukkO<9dU_0&}q#8N#Ie{^xRl`Ks0Sx{`{ zx)0kF7C_-OOoM6Ulr#=N5#|| zVTq}!eV26GV8d~%3|95o<~8YVMgf;&G_^2ymj?aQEGjnbU4`G*JXRZ~y=jZK${^Ri zH-PeSmCAi(6P(M<-5uWdB_Gc)O(WVWA7zfqSN&DExKn@LSsCWM;21F%_9;KX;SuXG zk+uCL%0TuHw16`Z-2|Xv3_Ac97kUqK{zfbfpuAXzH-7T}l|C}0pe%t&gi90`I{CA` zjJg3rB=Cg1u6F}X;^Kn#cDcd2#C^*7kCvGRcQTezx*X*3Br%&~jE$hZP(x=5eCOHn zqoz0rE1EFM5PV3^4Si#PRD*jO!`%Yz|1>7C!UUd)FKn5|StiV=_j$Iz0M=Tx80a+J z4a61@7U91m9pDmFZT4Ww!~KAC$ODi|taH^C17)^D{%^ixAiPQdn!(Y0OP8%J@0&w% z0-dj)8LR-uFPs;8F6_i0V*Qr`Cn-q(b2KD0=$Vmy7T76*AP({&4D^s42X}g;gNT>G zFH9U5;0YZuuo*V$aI6K1bH#9V*#uo2!3iD{D+?N?y;kSyRuarME8nkV2Q~fX;^B zW5Q%h=c|)O8=p7Yl#X}`_-ZtoCwApG6z!?so8NMHJHx-`Z>wf)sdGQZD>>W5qUkhk z_B|<&!<{#|EAX5-swO{IWUx45f3*S^_j|;S!xM|4J!jK}x9&9Bo_bbY=AZP}oa)c! zi97DTX}jBVwpmzts35&baaSj9d@_z_9D67mdG(B?T3iRy`nqyN;Y=s3-G2Lx``2O1 zi#QUnnocu?4i!i*St#$3%6*yRJIK53dz$sdW6fd9%!M8Q@sk(R6*xAfh2;3V zk3%7&@ULxCmyLW)+nrhiL&k0RUcMd<)TAgu?UUX3h%k4}--QB}!Hk z_QLb5&Fa`huO=F-z_AI;M8N&1L>jG$$MdlYXGUSg4CFee87@(XBNVa&W!9)4wgMr2 z{q~9u>&s5zDaR0=a4NB|ZOnUZaab7)Fp#q;@!qTyoo7;6z3Mv_$70NTOoJ}j49Sk^ z1iRVfj<3?EY#-CK^(obg3w2e>t>4yn<=^QoAI+dV%%16QzcElc-&lOOhv97V?~-Nj zxosC)l>KfdFKB*sY<6Ov3{Y;FK6y6oy}#+en8ujB=WEN$BmKH@ZssN_AunUfLRSTA z1;M-u{X}{QeVS=2ye?iov^p)lY3ok!`_=DkMSj`8@p*gCRnrd%gM&l+Uw)sP=dc~ z+>1UH?W?`tiM!oyke_w;z-tKi`GO|m8VNL?2w+Oh3%CEg16=y`N{Jm7${%!(gvf5a zu3>>@^A0_$Qw9#|7E+R{#E>H;N8c&6`#CB>)< zYrvd9MA58nqdTy@QYk>qQ#FI_J#oEHZ}W;tUcL2Z*4AWF(2yBR5fu94`731!fRa|R z0&ysK2HK5#0Hf{^@p*@dFi*6?; z&|X}e8^`^=CrE(Rlh!P{E*=Sq`s|EKO@XCEfitU2I+*yOL0MyC1ljCYanngHB;C!! zPsk2lfb%zEP*l03Q=QY&``;T`w3_eH2kc^^^3MN0YWfD4l*0vVF`w2WMih!@Iin^z zp8_IGN(kbUl7gwkrlhUuNVKjRxSjz#FLRLSh;3D7;?nJ~eej}2IdxmFbVN&E(^DWu z-8n!oY~JD7*L|lAcZC7u$`1iD-xIrh~9Az#Nc7soCH3<(`JXhLx%*x_T>R z9o4_E@>zdL6()WC^zPkB6<(Z1wqp4{YWlf2ZO8Z3D^SAQ@6)X&?p zY&DAc^WF4)m4xp~Gm0{O-3AF@;LgbmXZr56QS%OcyJ=7HmL<`*?gK?BuTwvJY*q7r z?Oacaso?EH{p5y!5jSn`cQlOsIp>aORmoyy%a*2Os=?C$;hZ}edg*{i<8ad&$R-B$ z#^aL5VK)z|a$t3G6i! zaa@z_`E~K*>1U;|I{mW2ATN8l(^U4&Wz>41SO>@`9SbUh*fK75jU7Bq491F`_H zaO`;#;I?j=i?j-yX-q@_q(D>&7^e}#1yfZl9Lc0L2SS^iQ6tbKU{Ap@^B%e?a6DX) z0liKct^@0-u$oIFI;Sog>_OUzm(gwQ^VZ+iOlUUVlo)m(aqO$dHXkn4_Nl#2<+xja z;et>b(g$z}SLjT$8_*#!I*?ASF_P{|Bwq+a0uKm2_RtU@F2Qmn(Wnn0*?=)Ew(}{< zyg=d{SiFT6=8TOj!Ak&^kh4|oB1VN@-ik|tGqB>z!W1-Cj8HhqdT@iJfDMhpcfXs& z6@wK%sB#mzN>rUGNFIjhx%7QvNxgBj-nzbOR>ymW7A&?p#Fv(-pTG1lY%)HrtN+4`7W?m)jr()0d)g)YmNgDHOH=Dp1URk?Mgc~6rz?vW|Lcz(vlOI%>9+OPqq?QU<> zh17)$4>#FQ?7EPbdGfpK_1|tEVjiBD39#jq=5yx;7sfs0+yn<+Ttrq0xjrf57cQqG z+6m`&a3;XzmvmnH`rU%($zRBbg+nSZH?KVT{c)$6Jw@bf{%S;$%Iy6NV0sA);2!?U z*TlLgKje!b=ByOSrC>5)E6~GSV*eB4{`iZA*wPFbrX41>e?4+&7VEJZusMqt z@o!u1Y|IbgqN#-bcez@j#~U*EFm+R_>S%j>pJ`D?q74~g2Qp#4i7Or=Bsl-a(8$r> zG-Ly!bGhMJd(|ak{V_iLg)Vc`TDl?p+B&WGmLK31Usj=eD+g&dulW9Lc^*awNKOk@ zfB6%*WbrJmib6`NV;bxMOs<1e6xnwuO}P~k>i(R)*UDi!9-&dQ!ffWB=#>>EgWCZr zg@P&63#h27SX9wk16H?S-I8A>B!Ewvbv7fW283H9uy%cs|Ix9X5X*)TSDaZ&2K)^FSz&n&M1 zdl>b5wfGE!ep5TnlJ$J@gx12U7H*~ueu-0a<*P_CPgP%=e@7ML6uY6+KOk_FwXToy zV3*DF9~-V5@Xmj$N?o%v*=(Y6#PTW$V0udda<+9Vfiiy`+?VTay@0Ijlb zVk(jPy8?Y)TfWTuXyct*9OjGT^da+ZwMDup_1*6y|6@vc#fodJ*Yr@-eo&NhbGNO_ z-SpR~(W=BqbeLjm9koP!I z-4LiIF6Qnf?d2g^K=H64GNyTB+}2Y|ShQe(h2bc7NH)RYS%+Zbhd&PA5iJ(9-;*z} zl<+j_EpRMc#Q8Yb`ame#u|Gf&)LRr=YFf?@m=gQC0j8=;quo$#=An^@aVm)3USF)z ziE2*RCMOouv4#rp1gI3hm==R6%mmvA%vucZ1Q=^;i!t~KaN+Ey>*e%0=Sel%0^)H4 zYz&DP08AV3)|1b-UU#gaF0Qk0PT2ij8^{|s(j1^HtnYs7deai4P6`4lQ=w%T&E18J}$5WI?cbZpJC7;{Whd}3%d1no>5C5z-0Q;$^EclZ7+a;!t%sE-+3 z5V4}9JDCvOUh&nG4gP#IrTW|J88>j;`ZdrYz$!Y@_CV)ih{R%^$vO8-3Yk{`0ojJ$IH@we&tX z#A$ihSgf{l&)-(I{?(q2>YVVjFM76F+nxnzRb1kqvfJixLbJx*_BSP$k(33k3aaVH zQh-r>iLn@*m~lzV-m?>B5qN{NxtTLG8fIP2tU9BvQoPdy-RFG7TFwU4&(PLgqPhR< zzlD_&KEh;zRr>t(+sUfNqfF%qp#Xsx8P0ap)m6q$Pj|6uu%efIhi&MjeDv<@rNOOV z__pq3p7MJvD1{@@VI+&Ks9#!wvjT%jcp(`$RzKsXeZdbKnMVtX3LW;>{m48X8%tv@ z#cz$#M6o3Dabtsm1muf@XB3R~5!dlF?5>Fy((h;=c}p(6okrF;DhfX#$TWZ#5deo@ zJkY^IIWJ>D8OWCHH`xb(*q<#IMBVeyMdu75)4I8FLjS{%j_Hr;OWJ6_{E0h2EU+zw zb6nnn{G<7HItZ?cd2Og3{GRP?rz3wv(tw-vefSLn}X zzLy$2(dQ#DD+s%@9{bC$GXW|9hI@|=r~2Xk_MUe@zp6sMsZ0$OE*Dfb=#%T@QG>g_ z+*yJ)+sjG@SvTm*p+yeD0FVGI0sx*DtQ-O2ex8C$1O`DgJ4dUg^%r>iX&3pblIp6G zwgpAm-!B9h8i8&mnN~mXqv5@CPK$SYj7l{1Jq^#+k7qUAGvGX05?5?Wk;8}*2&%Y2 zL>mDXr$gV=-))__@Tb^u6|2|sAAktmdG-F*)=f@1S9`S% zI42x%5*Lb2*i`hBP~^hOq0cKhP4RoVZ}#NZv0L&!QV5MCuiW$Pk(j1;HPxQ4Jrnfx z%Jby}BT_f5%y zf+PeT98}3=)8||xtR0(AVn&7wkA`^I<|C)IUJoi;D@_76^oB4cfBYR9#Un9vDPLhk zvs%`Rygc%V<*jfN5=JC{1#&X?VdthwTArFc>a%}D9K z0kA!IlnuuU<3dox0|z9HP}JugrUr@Z>G+PsU%_8B_Wk`C!{3BkXS#W6JvJnPWeeZq zr_P&7vBon@pjD^!$_$`if%5}+czOp4A9Mh=`^KlxW7PvT#K~X!#TBNRn{=LeiOlGqq5DsN_P!E;nSB68-RxQ?OC00HCb16Y z^5>~#-3OhGAFxER57VTbu{RJmxU*P*$sw>z__?w823n6rbM3nL1Fn-Q@Y$VPK$CVM zcYm)=sbSIGGrDNVZUGrDR(lh0IgV@evrzqgeEqG+dB}hT6x57Fi?`V7JfVkoi?n{n zN`0;6YL$Fut`@`>t&pF8*x7xKm^tiR(xC3Foy&B)I&h3zPSwU9|+)63*5E5HS@pZp-p>*FJ9>BE0)hzAPR5 z{E1U1@C|URCUHf9ike_T3E`Q1trjT=hsDDr+r;a67NK&D$)Km21^*EAodcRiizT$A z@biGEIrKz`tfc$0vnRE{+s^~P#S&C7kh@M24>15M_L@=bGMZEk=!uV8k#E&~?A%fO z1I8TRb&C@(U7YUKW-xNZwvh;;hLyNS?+j7OK$8i-k`4C~X#nMAGqMqU#IAd=O;sRR znFPlmMMkp}!6ec!6@|kz;*DDI?z30KrQCG!Ce8UR}()*b<%31_5`B3lO|i$ z4V61|i|yq&209qvb4^KD_kYFG?a`93LXU|mY*9Y+;(9%AeGEnk?~~*B=}GO7S|k&0lI2 z*}tYX?Hb8Hw7dGREx(>ux@#wA=1|QIIrqG^)gbguTdwiUh17Sgtry?4`M(IqNftk+ zB3O%R{r2J}mtUHjq&qXJg7g=zWHmj=oAeBH1F{uo+LzhTYqGl_=@LJ?r!FM$oGE={ zzg9jned;QLN?slWb(uT!vMBTKatm?NAeq5h)~FxEzn7^by&Qb}RGF3wl`ux0JZNx1 zO0&>H{NUA8DBoczFeW_X17cMRNZ=FuT1jXhi<}f+w~{>KTWpWsY)prZ5g1$^Rpv)< zVA&=RLKj-{6a$3=H;>Vh`*U_{`MMLM2RGykFP6-H6+h{0;wwlY?~hJ!dT@Ym#6y(; zZwJ`*m>_g|+ZX`!+|YIB)fEW$%U4)v0ts%CQ13+Hd2lN2cYZuZNkWR(J3Vb(aLlne zSB84P@?-N)IU0Oj;L3rno{OXov!kNBufy*?`l6HzMkW)bFYr)-R|a9xjk#xnHHmpe zS7UvE5tuo8Kt5PqhmXTK*WqV_5!tWzH1$&0-aV(pTd>;k+gUMx0eKJ!9`5CS= zy!T3t9|Wrwz{6>v1ndbxd0q%ttp1m3P!0)<8i=&-QHYn@6DGF=)`EqZ$)>_hS% z$G}6x7i5P342UqC!dFcU1-R?8-{=2o0h7KCEcUv;ZsCaySd9o^~Zl?Nchd*lkw+#c;kH1MNHYLy`gZAX^w{>1G^F9|Cknno- zl|$1;;B0V>T%2aMKfHKG=gC!vXB*1T$@?4s`zTO`(Ad{exo$1L-*=yAzEx$ST2i{4)BG3QF2$BC{lYMpU#Or(tmr<(1rB*4Iwq~B&nG~${)~d;tk(WqBv+t z5(UL_L*Zns9W{zo-O(@$Z`jyQetUmRgyi|IH)lk-XpNCwv2`G6)FZVQCTT=%BYq@K1N)=3 z!ZI%$D=cEz$I+C0@j=WX=)e!P;@yZO{8XAl`3*P`fR+hUmXI#2-uoYRPk%tY1Ut}x zW1Zf1#0@ycLXg;hw49C6B7~^(w4i>0RvqNxwCiV_(*o2Ab^);6rX#UHUXfAAT&@Pw z3|)0ZLH}r%0oKClRe*HY(+UWC;3%4SP!wn|K?Aks)&Ha#{n8Q>V0!NYDn&xsRuyp4 zptm8Mw07ewhW;6sN~-gJeYc=#9`wE{J)5kmO#%$lq5yp`kEOTis?au3=A3PBh0S>= zPimpQ&JBV^blop2ML_QN2YK=GcdOHy6Ee}fs-t(&G8lTa^g64NZ&v+#Y@s*V-cG*9 zytcu7#g!~^4eEChJ%+cW`!^M#U>`oAn|~-wAZT5odA3pg2<7mhFr8e#e13ymW6>hJ z#k+6nL+vtpXj@vd7DWG)I;Y~#l)~e_Td)n~+}OOo=TGh#)Y6bMn({@)8Qy}qA5UJ6 zO%YbC?!=FKeF_d0`$j9FphnNQS`A?lh8kqkMYSA8vBmKB#G zbVu2(abd6Lt({$1pRA@Nh13M|&*FD!e>zM{;7hWRnav%dD}6&)7Z^NX@)822Fmzuk zv5{rO9Ac)g=G%~nX5{m3N;!mpSgQ~lWgW<-EhoaIU9>JaVBJ08qUF-fpogK6g;|CB zpNN8gAzWSB)?LA=u@xi9%+U6z5swW|p+U&>o&=k!8rw#Oa^X z8^yaw5Sr=|mxtXj^X z99s-1igSIXX5BXx{Fvu|PsKtcNB}#oX{02 z2%E>;^U9MuU4cFynu{lTw{#o==FcoDjzc z5j~HxPZh|I2$}uGx$#mf*XTJXVdwiF*jJewm3xIn-};I67z#^&);jLAD?speROdOT zjC00$A3-_g&b)A}yO~1;O)yvASN;36=lu<(t%0V`o;O;h=wk5FtS`#;b--557YC9k zOju++$2}TY1C7@)@mW1bqv|vttOG6VHOqxc>5|M6*vo4gb&*ZoH_r9{5EmXuJwz`? z%SXeEW?{eb7%eHJ3kR{{Jd~&z#QO7Pbn5_Ilqv9J%3 zs~y|iP;r%8K^_+4Wu{}`nk1owef1cxKsvXB^DQh$8A`QfkSEqH^AAo#SXk0Es8Q-=dFaz zN|IzFn$#oEpJUA#{NP5nzanIqwV#!`sSqqYnYr#Brb@!P@WGu7+Y4diT4-0nTTc>l%4+9MweI&VkL^KqLtn9KXWRq^jt*;r(^%j(U7)%0S) z4*%0Qs+S{rb^hX{4uzgmVZ^p<{9^UA^_lnq=K>E!;Y~#^60=*Y{hRh3TsV5n;NBmX zUeS(y*Sn+7tC1=xf4277hM22VP8{(2W&sZ>i> ztH9UOawA>e#ME4=&26I!&zq_}n}w`nV*){9nO3%n)f03(2ZG^>_ZF)-gQn;Q!?zWs zQUu!sz*J-;O=*!Z*O0DY<-gXF|n^Gr2rMgs6+nfUCU|7WD_`vSqVh-7pXiSDjXww#nnO$ zr;?FJld&iS{>7l`%Q($brJ!D*et>+!#z6_o-CN}s|<|07n8 zoZ1K=pWSt-SX{RG%IK%cFz!of2P<h(m30;P8X4vHh5y8zVVeH(?N3m19og@I(5P8S6 zksIFr^1e(w4K{##!w4v+KL>IHG4DP4W;eQ$%&L67q>Xz!K-4@7a@=PwHsferh91pv z;($Kfmt$?kAkw{G*&8Oj>_(tBsX%&x#hET`ck*HrEo0 zy%Upau63y+YiL3K>|(CnVv*5n>g&HpZoIf}RehmLbmJ$y8XmUE=5zvogFsT)VFMrg ziMCA#_qUtW#|famf+?7*vt$W&%MvB=+_r!~AIDWK+X)-y@3^t#cTH$-ahXQ!Z@8u< zrpB@G6$G1m6}XE}PCA2ky{Z}eowqlxtlJUujAwKB0yE^3dQo`KCibbGDB+apyuLJuhqs2nYXA(*w>=un? zSKBD_LU*LNW1|kvk?F*Z(i#bfyE*I#sKAhYxEXtNicizCvipZvdfvH3(Ty&yW@aat z)tY+h6W*FB4Z#ZR^1fd9JL7GwK z++ge_P{5D*Np4TRH&7deu|09eXc>0apV5Cp4ta*6t?K2VLY|Uy-Tk&40<~jjgLlr->vXp_+l!B%;R|E`VK5BATIRW=Tr0p$4o#`kYb zel|n*8hXR;;e`dKrwdLy7jumw6#sTpzbUZSGW87C?uo&@Tv`#p+UlVNr%clB8Up~s ze<>lx!u$=w-!0f&w7C_^$v<%~i2oujej2OaQH9yoZ-cw_ngfyqzU4lvUej2GjTpFu z8^I}L0WKJ#fMTG6_3r4;vL$;t#$1tN(m=53cPJ2krTY4$agW659Epj|hU_p&dRTnz zIEwqQ}0MnZhhl0Bc=`J5+70!Fh4Mo|eq~ zHaMwTPD}M3HO_|e=BF3W*IK-7_Iz&vE5DD&z)33GOIaH7!mZ)9HW&TuYIC>{+@!2t zZR(GIDw-d2#yb59Ci`I%-nQz6qtRWdo^ha2MmnPTY4auT6JG*=DB!zO;=-Z85&^W1 z5gIIqf^f?L7C%|I`0D+y2H4R=!Tol@fp#Nohi5+1s*M&O6kW>XQGas=cah$AUN*rQ zw{}%N*ZL~BvH6gW_bUKXP~VDug~Y|B71r2(0~K4)cgGCHYlpoFpUv(*kLQLVMf)CE z;NTsS4Kk6s3SL~5PZ=i{?pGOB;A?&!LSr91AwVeAOgmV z2|K=1Lmwc&alPWLjaRaal~Ojvek?lsEej>H=M1+sQ_9?9qqs@^cWO67IeC9g3+9WO4=u`G zN!MQb_|9zxnfvcRua`4p>Y9IC;PZ7%gOL=SkK#QDc2Tgp0!(gi`Z|Cd?rYDlunAIa zfnfg0!EL#2A%#Mm%sZ3dN>*vYjtW89Fthg=Cex6eF-{Cs4CecPMcI$pT=&qz}hc#M8MsT5f%a?V&jtr!2&WUaFYaMZYyyh{!q%a}@S$IAxepN(ncF?!B%} z3_77wI3f5rDz|7dqArLkO;Im-=jodqkfs-l>_QXruAf?M#2dF_Q<~(C`Zo?moQ~i5!C=E{U{csz>>v&Hnw*JU0IH_F@AkZ7 z;WhfvTYzC1HE+VOx1X2+e1$e;0gL&cvX|CmHEuBT-Vq8GN$x)nr>H3_sXqb0@=)ND zQc(M^H`r0+E%;WY&eTw}_vFF4ARMbx_vP(GZ;A`WHm>!{f3e@Fo)Pn+RwM=GG%xk` zpGPO&V3F|f{)!#n?KyE+q{w^yR;hibe}9m#Yo6WuWRv``P~qZ-vsC-?~A9QW*arLTgftQ_?#WumOig00mU^p zX9FYbHCb_^FWtxWTF#b+EhHAiG!(?#=`F1w{X}!n#?3rlVl_+vya6p}RI}cn=br@8 z{0;>c6_V9fQ;HBDcDmU)Ot@gxMZ}2Cuz7jcN*vW*Q9@+uCbiadLl+C%NLI+dHNZS! zO9_#<8EJ2c1qad_T3lBC9Vu4q?+N}$p@k`*uNNANv=Z7^a5_O+(vZP2aG|YWBF`1FBdpcALzj227~8xJ?=x&IRIxj` zK%fs$=*?!Fv%z*UQC{Jz^mSSvEeJZJ;8o3*V?8eRTUoC~iaaJ|9StYPuOg_@=3n%fAt<++WYtr3*zUHf_w@^XFqwjttHJ zdARu>%@ew%fthYz-`9^rgM<~>&zb_81io)>!aKos6;yNg2~3x9=Cbf&{NCvgXeo+! z3Zi_^biTIAUJ_RxBp|KLpZ`26x3qd@aJP4ZGdWHN{YX!Hbj0b+!vCS^%mb-T`}dzU zl4WYp$dXB#vZb+;#Iy+Q$QFw1dmP4E!ZRa#A*2*4vW#719ZSlRlI+V7EsiC1l4JQ@ zxB345d1js(YNpS*Kkxf`U)Sq$t`CBUAO%e;17oZ`+0%B4NV1n~R^ufb1UJhys1(XyKddH z?vf;7sV}Mq_UAqbv|Xh~M9>NwGma07Z0b9kVXCIZ{_c{f8J57eSf=?8y6|qxwJNwN zv+18teb;y^pDj=6EWGI1ExLN%$c}Bfu(tB+L4 z&1gCtc zI6kZWC@S2HREw}DaF?wn~D~N5MyLbGF1IPj2$)Q>E_>(C6fzZmEBF)M%n)qZi{v{_skcN>9 zp&w=N81r0_L&R=9X(CG>6?bF4-inil=f5I9 z(P@BldISUyC72w(?SuBeqO>`C^L8)xBziy5(1s{2hQTMX^@9BH{7B-ZlH%7;5ym^c z4lfH?z9W|MXsoV`i40rtC~KvxMrGIXHf8#@+K_)WVZVQ6ossphs4{Ke?M5f+*q*{& zp><86b(*Js%EXzSOv98R(;kjhERW`2Y2?%n@Zqjddz>aJtpI1!JPe{@&VCRZ#GEb2 z#UGIq`1vtux7qs^8g@tYF?cvuuxKrN^_0e~s@D&r zAQBv#6+`=pg}ptw2NvRE#LSr(p8Umqo8SAHu9H^|9q8wronjO97?~0oQ{nzmfBuDk znxHa7w`=T(+!RKr);CamD-;Pg!=k=-(@#_JiWeX>$Z~T4r__|WaZ?YTR)5N`eN#F;g%qw`nH6p68YW>$|aa2!*VuVJBke5E_b;)t-K>H4Rwa=ss>WYMK z^N|eG#R=ry11=zK?1)-(bqFXqpAX?TPt&V|uZjX!s@8>JmFDxm?4m|Bnoq&Cyxfg4 zNMe3Sid=wM6(LRO_?~80)yEsn?f`noO4q_7kK$Nc7$u9kw4JA%!kVf*^2VRb7|}80 zwBX1Wx|9kG~7Y@X^6y@5U z>@%y=WQDYVMHrL>ht@(&$CbRPFvhfRQ+XQnMgCJjZ~Nxw#^SHcJmo)$n9=J)pS}+W zVX?<#;kJRn9@9sST}j@1_vYiXbferjt9{FPn<}?t>8lydZLm5NF0yxH;m3#K3=L1Q zn~$s`jyH=HO3J?H(thG6we5-&{(>9ft(*-??ea$T)Hn>x_2+L};ZxRUm~rYh%cl50 zTTYmKHnBdM_`zRw_I=8SG|EHiS=G-YFVFCLefR99+@W5BryV!@-6F%X?;9h{Rc3mE z+`TbByf9qAlA>uPwhFbip&z;AvY_zp*T5-_G_JdQC2l}uZ^q4G;dCl7Zc4pY1br0X z%vkJ}(IyOtV^F%Lc3$wQ@hY9CH9zA-^Pc)I!t%r)t=bQ3AQ_HNw%|A>COy+J9L!|+ z20)hS07N)yNH347dxcRAi@7YFXR0jst2jpR`JvGhgdOLd&y1wV_EX8NoP)T}iOQg% z;E_2^8!AN<>5G=$nnJ-Dt6EjT>151=R18o}9+Pvjo-@jhThFT}o90c!hR8X|S9a>e z8l2Wn<=mV%?ncl2tI_|XtJFe5q}f$?g_@caEpeT7FeIfxaAj2A#oQl}jDtBa?LLBU z^Ev_!j(g!pTWRufhG*C5;D=%cJ4{-4`;Q@j3pNO46$&tldlA0$kAh7>agY@Oq66(u zkUiQvTU3uk)4Fb#lWJ+3RdMjwPJ_(s0el)rr0)J8JYGwZS9(T-w;WS%O1ZHe`-ai{ z#@J2!|He&kLI>VIWcM}^FKYd`4JDGhQm|zRa|IkgUba}H!1ad`YZ3E%jPuU*h4tng zLc8`EyITKUyd(L`Y6NZNZm}Bwap#rW16eq!pNKuBU0wWURUg#0cgX$Izc08qs|{$~ zw%@i@l8g(!AIt7|ICfaT$M-{?i(ZPstY+y>YJr8Y+OI_JjOlPw2J zq}>fahicA5xOara3P-W*+wj8_kGS=_FMdD!bskOnGm}rLd+<%#pYbmG7AoHtV&I`{ z^Aqf&1l0rNf!r_M!pf;d-RaSJZ`JStJ3Jqt$U? ztwJXR;CEX>!w5J}A6mD_w!s-#7_ymcVG~UH8z>BS#Cmci(+lKP#*oE+TVZX=Z z6_@$G4xB~5>oQ#x7?DMXHA+LDaJz5qqa;EKteS6iTpp`Y2c+dF)|k!n%`*+i2-v=L z;;@KniLvdSa+=cCp21=1YSsPxjv$t`UVp@TU|KfA5o&X>JspTJq||j`F4G{%rJ`>5 zMQyfpBFF|eCsZ}K6Je}*w7&G+5pU3BWXW2*isa(EL%w(CrD{$BQWy8^a+o}#MSeP%2=w5Mak zOmjOA8?|rSpNjO$#>VLUMytT^!AS08rA__knfI3T6uKV$&GY)o29Qz4QfN4VFoUN7xuoB+6WuYmQu&;zmvU-H+sL**nEDU z;edjny^*B;Ptm8Ys+}Cb1YWFfVeim=tK_38f32;HSW#I_sujlu>tXpTPc8|X4@a`S zG;6AroznJrf8$G$Zi{G#mp}QTuxpcav$sXd!!Mo;jt>vB&MX`=J9TGRrQ~Tt|HlKR z-4u{H>MDm>xqY|vMkD$TBmN+8AuaB~qQeeQG1N;3!y_O=Ks|_82)pk4b2L*XV2*g@ z%TT6Nx&EoJ*j0A{yN*%yc$BQo+W1XlgwW^)5w-vglAcFHy1HQ5=|Y`qojJ|;!vz3l z$1E1P#gVa7EJ?$_i}VqPNmMRoSJxg&q4&E%IfjLF2G0Q!^{dtHt#=8Sf`g*q_Ml38 zZs+?SnMnv=na^r`&}P0Q*ZyQnWB-%4e1!@j&j{TcdzKp^A0>QegsS2NH<=75r`5{} z(k<)?dxi03q^~F}JgfuLlEx<70XAOR$RX6zl;>CMIBnLH4EB5+wL z(gJ)E43%KqI-qEDTp{IA{-uhX7hYMm-y`KdpaCJDtk^(ux|qGiKq=8tD%Ca=UB3lA zy1y6#6FXyVUEGueIs#e`5FCo3V|kJ$R&?Zo#9b>WA*nK0h>%q1;n+`;4+?FPH7w6& z{r2!U)_E~u%c7F*+iHuODj$eiI>d;7J!q>0uWc^%#(z4;Bi>s0Zn(4EVPiCeL<~Mf zNYk=dIffOOZ(ar4`b3hTp;h9^80Wnt&P809gn%YW^v|7a@8E*YhEri}O3zOi!;nm?D>Z?HNVed^Yg z5bk0)DvnNbycS${`}!8LPUvhe5Y5;6EnNEXk4skE#~7(6DJZy1d#JQq7FF4Qgaob4E=j3>f~X z@BLtk2OCx%NUOw>L$HSBTnq>WOb6nynG+%PY$6Uqk=!W3WP^;xga!08d}p%F)D{pW zoT#1}mv)bq)m#x51(y>jT7XXolr$`V*`J8U@899?HXXeI)6S9jt|5G1E{rRDRof$k zj&Yb7rlVKOAQ%iD5}h&~J*XZ6JUtzJD`9`%DG0sX9Ot#4%a{{_6NN1i`ULPNeUt-9 zesBiG{X`>izlEnvkgHO1YhnhMc)fLQ-VQnId@i&PimGy8 zebPUa-%Rr<91$6G>gc_2UHO<0QM9@6@p<8OIFT2LNR)B(ok7GdS9<#{__r*U`GHFS z+ZG|A!5Yo27V{-x3gm5;rLNhmi(n_ z-;d(PFIUd$o8RmjP5$z3YgRC(kp87mxP4u29lRVezyI|8Dp3CF&AvpivTfJS>s6TW z+~KRCpW?~-{BS@d2I+@-*j_Z5*#=}NywgwTS12=@=b4i`i$E!wje zeAbw&keo`lCSD$GTCfcptsn-V?&}1}Tv`xm`lAC}Z`86OC7nmu+!Vj52@Zkjqe&M< z2K^XOe#2}X;LO3za84@hZ8fI^ zSiacVrMGhJ;lX%85tYC0D~+q-!f_f!V$t(R?lB^OTtT63*_{K6QdgO#p)WLa2@#(Alh#I}0+rXDkU zW9K{u)H-|Lptc??p0zaVPyNf0D|-BH#W#Dy)>}D-Qn)u-)e_BGf#to6ssJyGK-*o& zAjRrevY1$3v0beXR3*7==t3)FE+Jj7Q3HNR+%LPFo^l!(Fg&JBGNno zJ+x}T0x2dqwy-1S?l!fABru3G*HQrIDY|3$V2Y_A03LD5ZLX?y0RcfP?p_oukV+Z# z*zs;=A`i>{tQd@t#nJRuo&}D%Jy>mwcPk=r9o8^w{j?IjgTn&w<`fcBkEL*2ZtMs% znySY~-y%QdZbpnlv_~g&j5m!!8$e;r+uTqf%E#Qn(cNjBd@y=eAsv%RuU=Y=s117A zr3rBgb+B4p5u{mr7=CyEjo7!KVY`ERDxammQBY;w*Y5GiSd`5pv$TJCrgsx$5w5DZ zDcI_;ivb-IjSC*M{#n<-OBAXJrs{f^RT(5B>%wBIszMSWmMx3QnHb|)IY_8-Z~ArV z@h4+0$EB_{04$0Sn-?B19I-|1^F4jV_np9{x$lyg;QSRpkYF#TgSlXRfiSXm!UjGy zfY6-eW=x8*=JVEiQfwJo?_@W33w)fSdB#Sp>i0-e$O>`A5fwA9u=bJG9;&5Y-ur z#M8VQwIww4{YD4gkfy?4E47X!`n&vItgDan)9u|)*LchN48vdkVxVZWeY4JV&g-rm z_&x6Jq>Jg$2aafv4W0w8T9@8rhsRR4=Xb3%cYXS9u9jugaQSoLHbb5{dEN(E!P<`x z!xo%VqQOE-7b|O571+!d7^-i0tM-q6`xPrEa%X!T=RzEArO8uI<7KF$8%`duHYv)B*`#uvZY5@u@k( zEO0dC3;=yii2claAf@4fBCa&tgethwlv_xGVrx8MSxrY7p?sJt6oLW~-X_A95v%T@ zpa^qVmG%gmIDzfd*b$W44Ao&d?TLap-=9OqE;zm)pSd76Eiypid0XXy*#%Uru%Q=~ zwDIS%!UEf;)SsE7Ar>3qjhkTQCB8CG=1oFXpr`77dXE&3hCflF4^;8I$D{d;PCbp$ zV|z|-06u^OdB9VWe!me*o2;(5Dea?}gP(3;0Yu}S&J8!jb36?1wxp~eK1@h=F*cx# z(w_mASdv1@rO}+?mG!Z&vo)qWTvn&AB6L_!GDv$1eK#l}gtG_P2^TD; zjp^HpVa;Gq6k->z7nK{$Ih`$ATllY9>6y@K{ps%4uS&z)p74K>X|LRpy!p68&h4&l zk!+3I#xc9xm~9?2+ML)<4sa)Xmvs(sZ_j^i93$S3=NKQB&1!htTNT7P%&We*o^(W0Y~0=te!lbNIgHc7GUcO5Wwrvud+< z>d_Zi-%q6vVh0R|0R2eyEHg}&#_6iQA}D%^t%~hR#EY4)sy%14_s`0mb(zbsK~#$R zW0PDEiC$|;i+TtRTYz2|dp3ct8zci(s&#K%OOnu!9S4EDAW#c?Jn-1xHD$t{8A1q? z3u(%Fa9x&q5rNqW-+q9=0G(pg1eu!RMhi!P&>!Qi{?AgB#0{j=x?#gmRIqGB(i6u#{62w# zUx#6cu;Ug8=RH2LZ=whXtT~W_=G}fW!uVF$pnAa8jBa5+=&w_P8wAL7MJ&( zJV#Dg;A}hQT|Eci_3Qb|b!NCPbo5xem{X9uY!PkcFyT@5rJ4asihZhUSPS0mGo$KN z7zumtApS5vxUMJ)hm3igaA}a6b|CBixqde zDoX4xSMpUh9f7W^4iu%Rdiejy7S8c~bM;sTs^Q4uxDM;(lL&5>potr7m8d~q7%)6> z`aLp6&JpAwE)Q_qH1G+aqO%iCA!(#p&Ir2%-5U|x@If0j(R&i_$8Sh|maowrH~w8n z53K#2x|29`YeD=+J(SEi+R*T;Beg_5MZ!c#G2wzIGZ1a@5gku+_-Opp@kXs%gF<9D z0~^-2d?MHclD_RcAF(@iC(Qji>PN+bd2S_rz3`|TEV|nb=-Q$vOs}>ls2CjeML3vf zUWD%n!l=5*$7?3Pm-K#`2CVke8iNhrAkbjOFq zdTWEVpf}{eIJx9+vVsL3gxvO9J`l)?IBhxvbM{=$PD^n22lyAW@*%mR%zK0(gp{`( z)PnFNumaU8Z*ANEw?fSW_Oq^sSMJ`7rTk@ZOaJ3FSbK@0a5eIB=#~_$I~WQRu2pv7 zA`aIyoz-D|G_7*sO=WiG4dLQe`}xr&(Ttw)kJQ)?0>Uu*#I&&nQQtfgd+k+skl*DN z%X_y$!?JTf3U?axO8Gk2TZPh6IAeb;Un+CxF0_}&TmQG$S+2}1(@bJzLK`+`zx#q$ zzyqy-?5lrS>cwro)N!_Pd*0QIVKF5{+Xl3AbvDL1bL8~hYYIJlR{i2z28^F3=rJ^2ock-`%z*Zz$6=+_G?mlZxUx=W6kKDr~1 zz{!f1*Blq%g|&UVQV?Uq#xN`@wSdv4YECL79bGdd^RL}%@gf8S)3-1*EE92oRdr`r z{=WxMy7oe@)h;n5|EG8|;;PLL@ZX zCEZ`~K*QP?XI&;+h9SWg){2O(oY(cC_6{+!3E#SQfBts${qb^(dq0Iros+kpIOxn@ zsF-n{iR{~qR>12LM+g{az)3}w5l7ny%gCky^)o^qlJ`hz=Myu z4XVWVbP_`h)>{H6jon8CuFHaoAC@xFdGI^!gJe-R$Ek=AyqHv&keL(?y(*}AzT2HgbFwS{1+y(ho~z{9>=`>(MV_{ z03XRsD>v^~gw2P-)BrBL;wCbn`(bX55e9G%&|DoF;=BjPf*A;wGj`y4!;@+G0d=oE zcK}&NZ9*}al4zW9N!&a#SA-63!#*%|lm3#VHj(H2t$qx6Rp0r+)B%^z5-m_(7R`x{ zfUz|#6B{w{kF9UvXyhML6-b^H7>^MEW5E@E^rmG(*2U-H_`b^&1*Ft-Qb^zu-u8WN zMLEYF{2O=pOvZ$tC-N%3$dVN#O2|1yT*Lz(E{=)e8if&I?$cli)gxTJW{rnm_xeoUByoFskBBqag z(jwWf*@nW=!^YsrV_4SOW}BW_l6c8WaN$K+;R%1X_9*IY z)36`#rNG83kz|6jTBGqLZmvB-7qC(2=|n^r;<|&X`*^nknvtB~H0zymtSuMSSPyz* zg$wI;i|C;5&xob_O5eTq{BxGL&wf095N+8?c}l@ela&V5{OPmnfL=A_e`8Oupyel2 zGNI2H00-2UeJ8agAOsy0eGWEO2dJ6hpCH59^kQn55p=>E9|No?uqp##O;zS5qVjPC zGt2%QmVNlK8e<+V@u2G>Kvl1x2psx_mwM@2gn1a$s#-7{*rC)#Frz45sL~Og0s?#@ zL(R{)PKDut^F^&RxCaEPa?DY6ngl7qPOr3!5EiM_CB{yfUyS1_hvm(`)A^pL~32@;do3Lgy(cS!gCN`*SHP zdNLrM_2al*O0*orGb>lM&32s$}HJn&FX z(*k1wFsZG`N6r#Mf#(5sg*N5FuS^aiJY zyn!+eSr2*;?8gBf`w{rORBb>OYsiZ?&4Vx4y~;b_wb>%rD=U~ima+HNwY~ot79yaT zrRptS$x=8d#n^kZtGm%IlACv6G%eEoC&P#xVz^sby*l@R_2O%LIMT%SWJH{|-zsz9 zsS&SmB-C6H)5nJc_ZUmbjbf;cBisxvk|q2TJ|WGDcXb=_uNyzmc>0ybzkd;6%lSR~btK%Ra7hcxh{e zalIz(U*u00L+SyDVxnvyY@nX=8-Z)Q*(1z_9BwTh%A1P8*2tXUjaxc`S{2jnjRTky zkzY^vulVd}`twCP4b7eiw5=N)s=`*{vS1bUS$C}7*(Q^c>EO+ z#e}^}Sl1W8KE#b*82*5BlDOhOkUJPAamXBHxeRnNcFpK6lD1~l4V`StZ@^{*)(CDC zh*!ns(DS{nvzEeh10e*Ecp{HT3GMM`O7XWpn zR}Un?P-AQdn5`NPQ>SIQ74rcZxizP0Qp8vrw$5`Zwt

nx$aTwVn~%Obh{bTzCWn z{PHJX8yzjixjbg~9fb{GRxPFK{%m+z1u-+r*Q5wwjZ7OKuUQTpuF%{n4Hje-XgiPQ z5tn<@4-aEZN!#DqM?p#ziXhy~0>~L`M(t{6k?(!9Tu?-Wf<=2`VOKEuNOG8H7H@Qb z{rzm*Z|Yz0V7~4%M|$GxK5M$M6&wez7%=&EG!n{5aZ||dU&U;VHoe=&0Lmk%%~_uJ zo|y9-Z;1vbft<1~dFLl$$YGM0aEw4(xjDz&O1cnp)V0FXCH4UWmy^HY&HqknLMvpY z*D6;~r(~;43A-)11BME0`oXufZQs&1rAMg3nULZUVG^O{O593{0%~^qq zJTt{tPSN8qg3#oI+Ly9h+y5NyVtbDqbsU(^x>d_#!<3OHd{2 zG(FQNfYTg<3jhptgpauh9uBidT50!k)P+{u0%JgAa0i4U5v@Nh(MaHr>RTfVTorpr zMx$b8-rXsNEmjO0fmWVhwLG@4{GjCD8sQ=ZL_Ei|zi61wcG_aJt*ST}Y0iOlGn&O) z-|P{}!*MT)T8wTDfBb?+s>eiC@o!HJ%XH_j3&JFXPb4C1Yox9g)cm=W72N_l#>Rsm z067}~1dVeyP^A`0bW|&XUbA)|^&>LP@rRl4w@?sP^dKH!cR<=|9^^g)Chc`i_FJSX zY_{M*22BQV|F`}zeCzofX?~O6=Ix4`?$+ZFUVVp0oP;$TzzJRk$4``@f_FVb9eLza zKb-?+gKh|87&F8BrtlWwpu_Y(jo&!z2a9+ZHb-RD zBD%W8Y)>(y3j5A!UX5fZL_k{+m7czrb5MAGSpp6{)=^|xs{0q?L7Bld9;LPXBavul zL`^`DI$rqO3$&+?+>B-}pYKYrn54Noa6PN)xk2{6{LLBK%pbG`z|ppmjXxTNsDqGIzjVLRobkeXK#x*PS#w^4?~L+iWst4bOJC(3=~46{ebGf z-ML9Z+O4Ri?(mr#g;@LlwN^_IMfHPTqR}b1q~+7(K?eyuooc|Vp&n%IKh!O%oPKt& zr6&<^zmH!GG~BgnQm#ZSVQ;{^m#)bIAUaj6cdc$S&L63gJ?v}@9Yz(VchW8NJTu<>>BO@pLzd&F*5$-sb4HA^b zdFSqd%Ly&IT@NqDU;x;CAPGy!WVn|W?m~+7B~gP8>E@nJ7o$tEU*av(jjC5FIDxYc zt&Viu+CF-r|2km|Y5>esNKtJ?v1eK7{EZ4kYp^0HtC7JI=&;U4c!q1&8_6+Les7Ie zNQ)z9lDi1Xm}9{OL54)d0D=wG7vEkDN zV$3Y8`xx9=U=I%U!<+je${fEFVF4P>d{O*tG*iBc=TRP-H^~-_%DHG?BAy0Z7b!tO z!y+^^A#k9$EnZPzRDGb94b*uSe0rQ}h4D>PrqHMP{j}?%Ki>Pb4==~*Nux9SuV|Fs zj>)grdj?w24POHOL4#15Qq&C?F93S0k-PZO0Y><_P6rza-&q1SMF+AYaF;sj(E1a_ub zSi-!xl+Y3Z6&G3G*2Slt+=6q)!TMP2zP*%F3-Ffr*`3wrf6K80<-h+_fQ9RCm>sgu z;gQWh%jVA5Z00=gYSox0v`zFitD$xAu>cbG!J#SUBCy?sx9shv`73IrMnmHJfl`X- zi#YErzjxclM&TQNQt!m}ZoGCw6UlQ?nH2jHsaH}!efYxhwb?*uvzf-lkEafFJ^cJ_ z&wFRS&Rf;HZq60NF-!Rt8Y6pFw^=hhmI06h0AceyYLE3rckOd!Cf=;*EjK~J79B|F4jj0G%ppVY)EHq4OfT-8?2>56^jLX{gWTD8Zq z7VB*)fIho*d#x}`VH_4T^nm+y2u*1Vk#HBqr~$H9>|29 zTMd!V%~~lpf8(>c=Z=7*Lh+!3ZAE^k`$b(Gk^Kz0EhlrHF~|&nDyA`;Y$&fpi$!^S zf*29A;*M~qZz^~k_7EJzk#Zu``uyo{Qp5?){1{{otrpgw@lZI~r^eST`befsf~9#6yHhaoK($$h?|Apjfuu>;?aHsJ zhgL{e-A(etc{(#EiHX#GN|gyOKk$-pxlqc$9SKNfRJNZxbDmCL`6MCg~ebD8^qCq=wqBt zAtS0H+)Jr!6Z^rgeq-&xE z41jJ7vL|@NsYnR_wez!UP6{c~-`S-j9PBF4DF5WUD4tY#20M7v&=u0;mi?8k7`Xe^ z79-E#7Smb;MPMxO7Jv!3O3n4d-HnzK0QN(5qlKhf8rCo>XAY>5eu1L-;8_8n^-&p6 zI{yQUUZ5SnG07F*2i#%CTH>q|yt5DQzqUPh|L<(r79)-?&i17-eQ$BVIeWDKtjm^U zjH_AUA$r^;$6ZP~1}tIjN{jT`2#+O(;5~qdbhb6J8TBi`$+9OSv!h*xd&6eU8-D8v z0|v9kL0cD5nUcLX`?89vEu;{34%hO5=eP235WFj^q zzq#h4NjgUK`KJ=31ioF`S(kN(`rO(l^g5mA3w$@&5K~B-rO?*OeY5*U*y3`{qVT(U z=N8f%pz5<@4;EBh19kB5%=ESZp92ZDbV=~fs;b^Jd@dUExH)MJ)AhZ8mC7pI8JZ(g z^f#v+k}ld#vQ!FJu}4-~NFuyh`DDT#xvJxhLZX4Fz^aAsm`BEY|IFhabI=qW`X2_F z>Gb?#JtT^-+HKH;L38#iE=nUb|CJ{fuVUNbn_@H`Cx0?R%|;9)OAWguvZ8BHmv zSb0s>o^eBEZiCC6Cw-zQx^%Z?zXHPbh4~6drUTi1uOx)GydYso z8*fj8daNa31Rz&`;K6#o_9N1;o@2mLU}by_#@kn5x3Bddd+{&2c-FY6r1t7N47^n214Dapc1yCt%|45VcpMwim}z_lwK3Amn(*W6;fo+yQBw9%l5X)L zZ@MbVP1JOljZudw^y{v-y0YaYdOcML+?F5(tJisyQlQnOse)@DBxTU=hp0S^Rmd;G z>HiNApk#cX_QJ$Ojh|6Rk*zV@t#7r*TS<{r6@dMKId#4Wqcuj^!1!I`9?VvODhrfN zl?$DOe{ck5gghu)&n#eNHHWvVa_0q4#ShvnUnS5z-UQqdt~}2!z|n=+)dAnR@KoQ$7+1Bjngi9m9YR-K7bzaNSxHpQJAt;{Gc>|;4974&O65UZyMc)} zLjD(GTF;AGkyuBX>eYCB>utoui4t#=)Q_myFb7 z|8H|YSB{j-_ZSF%?Kewx*$+gQVc(vTo?DnqFSk|J(rj8K2KLSdqn@Ysd*s1Fo4+?7 z=SAZr9J0Wjn_lXRA=RN(DOmikQuU~{&a3tDzn88wbEj$m=maGIT^WoWNpApc&_!ES z5$dQg6xRUN-@o3b3QicpXLw8x)6Xj*!9HjRx4GIjrOCEz3aZnQX#`jfuYY+7@-s;Q zD;kWS@^*&4%pzHW#to-8T;+`ZE)tVaVhHvbAF{9rJXc1F_oFt>f~ zM1Q|lyH%oqhnpMoN&^k2(tNWrPtg2jxYwx2pP<$jc6_Yk#ahHc9H3x{2{3v-1cDn? zAzfkUc--TTCQ`b^`zkC29JqX|JeOAx^lMl}^AupT8i)n7YEjBBqO0mo9d0i&PSjX$ zm=GPls-s3@=o5eQyxOsktKwF?*D}2qPRjuxAK43Y&X(p9NKEtmcwo+m7 zgw&3AjCmI@<6eai52#@1!qhsWIORc3+_B*P2w1-|9at>#CqiJAA?aT0r7h?(;6+vf zovqwGFQSYpdZv|6qw3YbJ0rt?XUBD{6JnV1H3X)$akt+|mINoOx!mSyBRJhX@q>Rx zq7oj?F>wdsE8^8$$^h`AI9YJDyK{D{fFT+~dOu}9xkhHs+*C}VAjqv0pSt+MBWoR2 zw}j3!W)z42S5S&cVBWT39-U`EfC^#ZWUzU=B0CDu);`1s|It}5x000-BZ%CtRbV;@ zpX*?;d5P1Rt&7C+>VnlzK&e* zlD=jZT2ca7!sz_(MUM?O{{rGoOH=QgZAh5E{CMLyk36zrpxPAcN($jA1<5qUaq?Wl z>&C-nja$`NpWg`=rw5%$<&6E*V`i2A&LfihdTZcQW4iB6Bh;-Mx@3&M`)M4cbL{!g z>NFLzib?r`3GN!^{0jZ;Vz&x+{MMNJo(tL)_oh79RzPDkZiU|kpP1kcfv`1ZZ}_3F zDlobt#T^bK*lJt8@DyU#RH%-C8jW@l{ z?TBF3D!{jsN$Sv$mZ9a_WOIYJ6RlWCNQI*Va!t zbPOdtGC8ZmY|{XI1kklt8;$)XE6OtDLksRax`Hl)-V5&QL^AYTUsMGKcT`d-AHORH zCRHE2F!GS(1^Y&JhH%V*(Zv=S&=J3mBL(|eWp5O?7b}cPMBn zUP@XEqx%8oT{L*csq#Jw&QU;m8yOU1I^O)_i%T$T4r1_n`3qXff<4_B3BmoBke#6^ z!UjMNKG?Navd?WRfsPb6z50@D1)P@L1pGr19bE#vJr64($q0{CfJ7(_R}N~E*suKrc<2D2|ZqVAz~7sBpZgYJKA(=~066EBFrF?K)}om~Cx*f+y% z&A9j(8L^Lrmnlj$_bcxxlajYSiwd<$eWBx4oah~dnf&bGhZziedr2KyD?p4H*W?k^ zs)VH*;%6n_lBz&mi~z!3QX2=DHMByY{5Qi@J=SyMI1JhC@)LQdG%<+^ZxuZ+)pQ;k zsE5ULF)KapbZG@CGKId}e$v)x`$3oXf4s38=GzL$|$O6&0}ntnIPiTBe{~?a_r{ zmA6_K8Uyg?z}14Dbs-Ye4nc1=eYVpjKtPM)sc5>r`6jHf;*-?6|67rHK@qFNkPIUW z;*aZqn>biwRa;>Xo3U8rAK^0hrQ=fvrgN*aW0O- z(>)?Ou=oKC@tpAn4bM^SFRU!O|MNpF!Y3Eo?CuvdylEMGr^$+wusnf@Ey}k$>2OCW zsb%Ac&Bd2^yTZ2LeHJZju2o*HxK0%>Rju2%SGzCG!SX7BAi&Z~DT>I7WKK?;PJ1)s{MN80P;o^!0yk78)AtsG-{ytZQlr_$Reghb3AKR^soVG}i z+ZueC)Jle}w4+cE;RN&qlM!G)+SUNYBVGc!)j%o>?WI`RWV@t^!|&NSkg!ywYQwwr z`Co!|T#rwd4-=MM-K+!Ng84fsRMD(=&RV^s-PgTVX^_4P{4PADKy)?t>e6x}PiXve%|xQO%=WG6Jc-EGgYapA zBG6&#pg#e>2| z(q?+!Y9R_ko~}A`oN-#w6roCJ^S%Dq;fJAMMW%sqY(A>xS_2F8^-57@b4O^Y`3h;* zW$~u38f$gKP)P8KIK(pWkT`y}$dA|36@PkS!dE&fFcz6xGBz}fqi=y6&x2Qa_ro&S zh`!9BIca61{jBn_!e*tz#GZ=9D;TDoHE>wtGjcQ?_8D>vx@vjYaG0Kqky%#9-42?T zQwOza2E?SQKJOJQ+DeC?qYQpZ^}wNgz?Q@EyGp_a%jZf*xEj4L%$~~sR~74uKN-L$ z;%zNcHcXX7YpD&m*tr9H?%W!j-sbZVi1+* z4!ggi#0*1kQU0ZsC+oGp2{gHt%#NWw`eJ1$JoSQQAb3$%vm2ee=dAjQuMen$oM6Xu z7SF5RLur9`vX3H213#7>cLDHv03zr# zt=t+QQFYvy1oCx+L#laHp7QuuO{* zMd~Jy$|_RCPXJwiZ}~n4>%yk8=vyl($6dN_3X75Ixe{~-d1*Dl7_%#VSY-j%_@-eO zZO{J_aafRZ;bPOi8+j2h3w1heh&Z*(?(ZiP);pW8q23RK69wSRC^4P zJ+Xs?n)}YcNg|8oU@zClV+${01Y>J%p)6#P41|glr<^VffPC=%=@|dlw15J2a!hKI z;8iur54K1wPx**H7glx3O@a;u?X;l+^1L5@?&K+Zds1K&_G8eIPK}_5B0wes0+FZ} zGF&Z@=8h#Hv#uy{|DPv~NB48bv|2YhwR#3gXpv6s@KogG?#1_o2JjVAC4&?_gjz(9 zJ~QPB=)t4u^vQmt)5c=Ll>7m?+~W*TQD}5eL6J7hL5*XbHc895&w(SG0 z-v+?fYWr?Mj8#Xc@0U+!M<34a5<>(F0LGUXiV>ONe>t7Q`tj29H2#r33jlD?A1h+6 zg8xj{TX*XI^Hu+YHE8P>SSP4|$qD;&V9o>hibfC+AhQiL6;*T5Yi!X2O}zoKaLO`G zo8AMVkqi6skhIW>i5L;m$1!SjUpTygi1TmEYH^S`l@7OBR1gop3^$QlZNA=lzW8&D zV)){^p94w|I{ijfppcdVpN!{uK|D|jk7)q`(xK4WZ)mY}xO&2AI^-Iv9C-1PXWLC) z%Gh6$$9&V#s}`STjy!>OkG<%X^af@+Y|^OGUO>jG)glVM*^Qq1xbCPYEZnIz%=DER ze=f&tY7P?kvnmeo?a+>}cmV+v#Z4z8WS32kB=m{OCybhWkG_7F*XA2V+&h2Sb2cLN zA0CTOgho%)t2+>*PEFj!kIalTK>4le@%tWSgEKYSGe8|_E_OPxqF|K<5-N7 z0JBp|x3=WjV$=LcnIo5@-KtiX$4F+%16`Vs@MqLehBb^UV$?hU%0h-T#L5c@VrqDYbxZdwP zcHSwBCs>Uu)%=;S-sT zGKa7pq1rk>iM1w6CB7bmD>&iZ0zEJ9fk4pV$vnl~Eiik`?3u-&JBo^n6e&9mC;s&V zcAyUaLnrPxCP-G{2^UV_S=deF`UIW$05lQCqe#BTsYZ3+RhH)b1mn?}AdTm9KVRi~ zp5g!Og6p?Uvsgn7;tQ3H%aM#8G(;0Z-z#M}qn*|aksQGS(<3y%+vrjW;cr^Q_c;gE zCv?BMu4MAA1946t$h-l6vqQ|+$+eOZ5^0sD7cDNF`+IsdvxWLH z2w8#Y+Uq0q)TIQGCQ0d-^>%WAcyGZO=jbcjZ<0^Of^Q7cMlsA;1x1{s zAq?LnzthVhC$!z90TD&&SU>;_FHjrsVZhM|ESM+)TKXy*-Z{%VfNL*=I+A;{TS7~2 ziyfW^UAY^1m&KJmal?{Fje}jbs%x0~Dga1FyoEkVUp>X^RRz);ae%Um!L{GWbE}#& zzVO812U>*CfvOL5hry)R(KfBH4xVTF%Yb{Ak^|D+a}$Uuf;cX`1*zSblGlQqiESgd z9+v$T*AMilFJIA^dgw>AIJ2P3qo<{iK!m5T+-aAyZSddd0lX@Xxt2Rz5pYB=Z0t7e z1`%K@y1^?vrtv@SCOlV=uEVn&8M(90fvc+8D^0{M6&gT=G@90#P<}fN4;0wK9A;tt z4I2I)qN#`Q(^XK_+G?PBaXs$$H9t}Xde3wu-${^)}4j@DM#tVb1M zR0m}jcD6_m{pjbAQEX00LLAL)ZrE(Rgu4{e+iD8{ z>|_NmXq~kB{2ucsGka{Us!(++2%qnrjBgPeVYIfO0M)o$=vf@>SkGdiNpQiKr74^+ z<{-~waY)qcnfu>8eMT7i2GT*+LfXnx`!5jtakVHQ0#Uoed>Z-U!^X{epD zujsXJ5rf?Y_2J}|T?=DfQi}s3cqyq6&sXHhn*H5HJ2vAv($R=vOI`0EjD5Ye{cbd% zF37RybU-QbxQo1)Lv4&r#{?h)VoowjiI%8leo}kAcS-uY!i8nO+Q-3*CdJqLLz145 zx4xMcOYkSW^NHCNPbM<4h`X%jAnx7Qzm!Y>pu~nXjY_b$z`>wO@31i%FNOW_oO*lh ztR@ncJ-E1S4%PZ&C7NwdzAMGMy8NaIx6%kC|6$N;F@;Wd1B$5Tyq!Dwie~4#0RA?s zc_d54*v=$tkf`@9^qwyblQ6y7SAfjoWUEaRjDgrGOX3y-#EGS11hCItduW=x!Nv(4?wJ zQAcTWLVI(PirVY6z^DEq6bWFVxhy4e z9Zd)UD(R}StYFcs)SAS6fj`$>~%pfQ9~8ko%AkF6&r9k}yh@#U$035&+*H4b6B3UEyR;sjWRe1Sj<= z`=dDLrxYY713UMlN4 z1)~sW(Jjgqcei@$8g=+ckVnvYhHoZR4Pl@AjZ_JX#e=l;`_G|_GU)_NahN%L? zQn`{rf6v9hipZE3S0vXz;4n#Vo2A`9tJQ>5_w+n35aD)_8?*vohUSI3bmTKe)xyP# zpSb~+<1L|2=zQ=6;{GOUP-AY;OA?$ttFjlB$XM}GbIbRE%D7d1FYa!3Y-jP;u5QcJ z0b}5=GdMUWd1}=yMd9xZ3455v>V-Qwqg~#^P~_k2MxzE{T((i0 z_am+`4`eY&Q+!yMHdQZ388*dktvXc{JN`Cb9dK*xq0%+#dp&!CC1kl#(*Y8E751TM z21dLd7Lsw4aKKR#GP^HE;JPFKNHlG!dMKa2AN}ZEc&W4GA-05SkJGNp0<(ak04}R4 z3S1imBcLo$7Sb3AUEmvB|M2uK_r*WWS_0E42P`Q0 z-%Q`g**N&495!k<6juruEA$Gl3`gLv4wQOC)md;Aj*~*ggrp!|fsw z-5{Rk7wquLz449bZ6%Zdxa$o+@6CQ={O7tGb?tCc&+v*lc2l)5@Z-5mdV_QL#jJpS z39?OVq^yRJgw_+Uc{g8M&Z(z*!QO zB<_-(0>H_?hb7I`euMIa%=Wzn6_@?!1FJ^91dnTgVgcSh>759kTu|+pll6&jc=4o}kFShi9&pEYANo@OmLRUQ zkhIvRT~WKT1}U;t?||gyfmNggj!|X`*}#aB%??GzdlS!77*s;9mp;-nt)P#}hM^%q zcw+-|zh!!FqlSg6mfT_TBeMQl{l&iX|<+s^bi^*tSXcuR7eBbi4fyMJrGVdZJ zAhPL0g@ zawaSb7?@65+yxFu5NXs!lV$&*dc3Hi{Ns3i{4ns&ldo@zPV32y$uCvL03~pErA|*S zCwavpX$~E_2&$~+J1t8-$%PYOtpsuG#L2A!K1H^G4XpQ?Gt}UE!dtT^F)_Gd5bxtA zLZ^2R#LU6Kri)zTfWEMEkW9zm90=ABZaR+-^&GdF$0_5s9S7~|?1sR?opi`ns6`a!6Z?%L z2k=_@R`GW`7$@O!X4#TTVpzZqjCR{?ByA%oc|aFgjvdb**|0;Qcr=%rS75TOK=_g@ z72UJ_70qLvE-2){^!OG`)4Dqi07-7`;|kSAv3VyD5MzL9?~xULUEwu{2y(?+kfN9c zfZ!vD$$|FWMZ#0u=28T&?Gzz^gg>}|Y`3V_232N8cjajlJPJwnd1_<(T@v-DAk$EP zJ`st~*D^lr2kzPgE7nh{?sxiO9ND@}4T%7tx#6fr{#4Wp$v(X7p>0H3MF#9(?9an}{OHHVjv=*sG z2x+wr7Hg}?D5Rr9A(fv9ttK@?SP{iET2VBIkW*60${{5=CpyWoa#&9P&*S}H*L%Ht z-`ZrC=l49{!+n45kWkKb8c?mVBFAyo57E&T$Np>5zJcnMa#ac)RW~GyLkGcX^pl*Z z;{3d7#7SnQsc+cZ-z;e?G8dbrp*mV7M&qaWOCRK&h4f9H-=D&y_hSs!rGinxb5nvs zPt19;*!uyQvO}ri{%W~Cq3_MbrCQ|GsV!8~L#^JlRGLioHClHOc^{9hDykz_bYq6E zD-Rt^9L5FREa?^LwFMYf$fxb`11lutRit=n5oTLebXrE_e3>pPp7a&n8=#@fkAz93 z+Zj^p+{02V$%BbbocBkK+Zm;2ga5Y2KUnlJIQel~5|xb`u0LO}<=+v8PQxMESMy@8 z{o=RR>bUbaevNNgQf?Ug+$LE(5glel=f!CQ3&u@=6l=t$;hZpKH92f zf5l+@WldqO@~z}kiZg%>0J|%hQ$Ozs)OacfNPOp?D(3^`5hu2keaMcTEch2p0xWHw z*N}+x|JElDx3_nQCGe-y8EKI&uBWmwK{4vjh#JykrbHpB(aJCGtCSjcBYDgO5ikEK ze4k7tP&EFd0kGlw7okD&jceiiJ#E{s4s0?xR7x6wv(&=Ock__Sb2}Z5ad>{i`A=b= z!h76sJvE3GDoGw~o9D1pb(@sF!XI#;_W$o3^~JGb5t?U%ze>pg1&mKi<_Qg^U1Ad8 ztaPQSC4YbRF+44aI);KXUrv|q(rB7M5+}s@=XE)jq{&MCe0=BPC+H$8e_MJym^h2?jOu;@F2T0rM??Gi9KcOLwRS+ z)!xcZA5;w=MhrF;G@H-$iO|DRVvyI~rWsB)`9PvqnGr>+=}vfRi)Fg^vlDG>#r(88 zCFg=)ODl@1mXxGj4qD18N8iVU+h2b40O9CawoD?!iInvNF5eI!@=VG4i{57J$k*Iz zCEXusKO&zl*88JFO9e6_8cWpNFD}&&V^qIE?Iiv)F?`9!NMAZI<5rPvx(msQGC4S?1%k>8Kj)7(D-cQV9d@#p zx9)P}CWQr*)Zd+6=D=Q^FpWvm*uiI|L6`X97q-$gI{lQIFM#scr`DhQSR}YP1j?VB zF)vUVmD04QNh6fYy{phED@g|$pxYZeF4MG{c@p(($6Wk)I%W=8H9UoD1+Lm4vqJ$% zs6FeaGs^0cL>%Yj1=R>b&e@zpB>*NSmvyD|uFCQ&;<|8lDf*Xyr;N76^;YUdg@t#7iQ` zZF=q_Ydf-GZzFt;D?6k+WA*Zm+2Y?54Q%GgOmpdfQl)h@rJ-i%4$8&0qAxrkgwyj= z!W)bj=)&0w)(5##wsl12Qw745JFW;%CA$0;($kZE8lB2dD*9OIK(>3gm$SLX@4$8epSPp zJ&nT`WG;8>uNCO1)(dRa-@DM9eqYjO?2S|EfA;?A(jV+we9g3WJS%CRxb78~E8()h zQWVUYW&IdCpxp{ien1bH3KUm8^MTk14SD;KP2o<}jVHKO$@=~u5q62j>jvybLEpR} z&WpJFjUU;(-*#`G&7#4Plhnt|-liD6=P%_ec~vW(#sOCwyz!rEq&~X(2KGfoBjv+$ zR$l!ge&=toOptb+5ZJ$EedHdp&OArHAsbD)ub2ym4;3F%`uf@%aye>DQz= zDhdU_LsQ%bVxQ$ktCj=juk2$2&5qwZ_V3Rg(yNpR z$62XHq_>+()z*L_0d0q~-nqQ4_P9I-V4)WRm&)}iW{FIM+MdqbZm)hPp>1UL$?3SB zLOQ;*Z)^J4f-KDV_w&gXm{sj>Rf}qbjzt1HO+1%Pk!VEQ+5`5zI&3F$J)4x^JBeS9 z3e-L{7X5n*zEcK3dfCf4bL~(n7zorRw)lwT#dmAZz4Y6x(=Ed8JXnljs~=}4yYOU= zM8TQ}Lke6N)&s{9nUSU)GWbWwqHbmjV|jaZcK>u=*t9Z__NMsbol*;w`mz{@Vi1 zU21zr#4hQYjtKjh`pWFV=j}t<1BG)6B8r~%@Hcl`4@Ar=8sZD9^nE>@wk*->eh6wN zmu*z6dt-r2^+3Ti4b3C>+jFJscQ#m9@n8=cpsv~xQ>|zIb!zwOGh+MH-Zn4TQIpzp z)>kY*2S1rMliAb3i_OLjse-!dRrxy0_^F(4K8bPrKR&c@|Al{}yNMx;`_cN#pGWAg zplsZ!M7N~)=`*FjqK#Wre;%>mwOFomm>~n14k(^DePnxab;5?7!N1kv-4ivM% z5Jg8L9g3?znqD)p|7pfs4aM%&kt@u~hONZJwrUrs9HcEmxsDq?cgYm5k(Ryc^}?cw zv<*zi8_UGfpcfl+XpE}Jeh~vmI+txU`*E#zk<+njYQ?pDI2^syY6kV@3J5Z}kWMP3F+(g$DEv1?NhcHDzz_ZTM3${k2Pm$`|$R1Tig8aW!>{3Go;hjA<*$Xj6WDb z+uiQ0v!>Nom|?EC?^thJI|k*KGN?w+jickPzyvx!KT*tTSqmVW%AC;D7ax3Rw5w8~ zA+z|}D*3eT$xx@*T_S{%jJ5P9o$-bb7F0AX*`CLGWn|t(i;bvH+sG^S(+ia~7^o?Z z2Dsvd-v8O1e~k#dr0k?7gry+g!1n=|nsWqesZ*}IUj=`e0IOm*kg7Otvc{ug<}^IO7m=U4@bf*p^i9=w za%HGG#WH?p$dbv#Jy=K`CVziv%&h6v>rD}#FemP;6UtO%C^!201d$uy z0AV4=kZ-dZU3C7E@zg~}<3i16Kf5p7_CNo;Y&nXKi^N>Zcjh@xaqRSVngW^8))0PK z+q8Jxl{G}LaQz%zQ%2Y^@P*C;SIqEjH~{kZ+IKSj+I7G@HHZ734r-5jde!GKD}nS1 zpsA$3t>#h_aI$EFOvnrEsGFgiPdS+N;?B4>mp5LkPNumV+lZ*GVf7P(C7FXy(-i(m z@BCdr+I6XfeY@N5EOPf_0~N53Tk?iP67aQi=B9sSn;gJeS1QBdMdxQpop@4H3jl@1 zvgNgGWY0E@>gML2f)sjw#rXEaF(1P&OXzwzC;y3KLR0Us{_~31)cdji8nrNMv-z$| zGX_V`SRu3lFVk#lu>nNJ8yz2CfAg)@_z5$AKim!#m6 zd7JqFq4FjJXA&zZH?1#eN6LG z^l9q{SfYo{_k2*TB=z_i+yAybsO{f(HkyRN1Nvh6X8(&PlZgg0RD9@|av5;HK<6!<>7|DoJsF+1s29e2z zHdWgS$@VVrx__~3Fg$*k6Ay)=ciu1`U^s}zd&}D1J#&xo*l!rUkql#E{(M5=@0Ey5 z)hRkF4g<1}g@~?HGvp{S|}>7EKo_K%$+`{9q6FPrysQ;*3D7kS!ye`ESzYYW(^P zonD!GI}&KP=!Z!MsytjYj*M)N2m1JI`tnQ5R-XV^GCuE}9=@gjXo3Dv;xp1(bZQfl z`iGn_=MM^4Kll7;3@b2l>b@7%BR@ETPXT94vq;8m3xsSU%lRwc0{_3234zG;YTc=~ z*5K6IDBxY7;M-$lE%cLa_|wRFf;x=RL7pKB&k4MOM12G{>+e{_@3Ko#7ZG;xWv&fzu(?1?5l)j7X^|y-h>wIE*UrO%$5gCtB)k(1- zOOHnG3CC6*K1<&XGb)bGVy0H^SGLydi&}9-k{Hq!&(U3GRq4GlsypmuhW3CS-{ilU zvo*~xrBv+QT(PhvHw8!pgLRzvte)C`dO$i0_Ly)c^5S+J$AKQu^;@#fo6C}_w4&D} zhS{jq(D&QAG`tK#F+We5e#G3k^=1B$-df&;N z-?cNe@+KN9diLI)M>l!3*|KZCa8~YZ#Ay2Q@=(fdadlYI`tG6jaN-3u9Id1gjmo-l>6KxSd4kauiADp^OSw~hx(o0^e(hltmj<6-$=WpLHYVu-_`MAm{p7^WFcb#16Ub!QeSiA!c zj!G*(`h0;14sC1@%uE9!9l6NSjUHXww`bAEWt$?+{It>!_KTsBhuf54-CZSC<#*8z zjAT#_zcQk}LJ#jg#iruq^t-Igo3o;%3y;f5nDXqy6VDxlkH>fZErXB-vDTrTDUjIQ z zN=509-$m~Q)&olyGZXNLMC3>a-W~fb8j4*M>hK>*`&&O8wQMFrD3kkBVf}=r8B6~NRD_BV z%3Kn}V^n3*hmhS!?M*#bZrq(aH#bnUMya9Y<^#`4KB(o4bHBH?*APiO4v<0pYCXCm z_UJhV{Np=f!+*Q*m1e{)2aP~69z{G7LEnWH>U>YDhSx&EjHAjcy@P~cMEILot@fHP z%1dI{57~$Gm2(3HE!7&6-0fTbaAOjR1i%&rXhRsvjG?+W{tJ>{JmYYUtD=LRTmy2rRnLNrbpDLOi%o|DDU2q__WqYm=4QW7!wa z8zWBAE18ptS~IE*O>%|By1ebZ1)qDwYrzkU0xvg=f5DJo9VhhaG{~#1U*|ThFU^z3V<5F-AJqXH36J*k^a-^w!B|F z&hgb^jM=1pyQv?`e40(&UAY!Pa(G?^;7^VGh$$|sPMYBeL@($=CCjbf{8^NrWp9&E zrO2B|!=)m;)94=1RbTo&uK#7u3AaXC9><5mMXT!T!ehR?!q$R=Dn1R-*RM$8dJfrH z{#T4dv{YtJfv(nVWDAex@8gYbtn@sSJJ{2B-}`*g%8g|Ecz;{<%?k>|=0xwioM0Z; z4x@|BmkUgHqzjpib?! zhm6A#x?yExgi&smAV|Ef{Q7+1>5zl*DDHFD7n)qIv=i;oB@9Q646ab#X~SK=IruNj zDf_=}!-iZ6cdE!Fu}w4h>#|_)ATegr%GpIeZN((#YKR+@Fc{!V|%=%dT-Uv1iEXY$dQ z!5e+O3*M~TGLqHOj#Y5b(iRiF8Moo1LrZc_L26w$_W9R;9pIj|gQYY0%nd{mih8fvRX zXEwA%$r@3a1vDKj<_2?ruhKgvD7MecP-a5gsw;&ZG6>gfYLIyTBfADzDXYP@bu7={ z9rNWVWhi8(KiWitA;Kct`YkwNELd+RP7#|*=t@XD72A3xGViLdX58I84-Em9?)pSfWsdK!Px11g zi)STNvi&C6oUberTl}p`veca_&OIuxi8@^2#S`&T(s&>1a+hFNvc(UZU6<(CYXL{v zp~W9ny<|>ell>iDbo6>w5=H&mzs}X=@SvL@cj~UwJ{zti=4Dw;UGlAxecooAid-f} zK2(STJp$7ytlRnlre#*<-C&^$#BzQ10!HSBaoN2p^>u0(@gVD2hSq7Uw+-*#>h!el z(NT^iQEU7czK|nUL*uUPH%U%K*X$WnpQkzqwG=<}`=gaq2A8(~8{&P_zW7A;ZCCFH zT75z&g)THDSExoQDff*wW1~tM>m8Nw-P5!bhC|tMAVliZK}SBz_~Q4^g^PYFhx12P zMBq)HJtRb1u9_I2hxprLme!p3Ca(kS%TJJ`WHM;C$%^2#dEGzq(KIIVsN_p3ji)Yl zpZxEM>eu4jJ7eC3NZ$Dam?;S3}h^$ZWif`V3-|e}36`rJ0?6rSe79XnqWQ?lo zmMV`=NQ_PC9-H4X0LDu0@U6Sev5QT)Qf&?|t;wH)8G#f|+(%DMcD&Ed!j-0!cTJ{6bPNZRnD=r+jv=W`#EVOmt(tEQ>>}W;3`@f zlwa9%7?Hr6bb5BDRXq` zhMX!Y4M!jANWJ0ZQx|XPYt^#!4`!ymWtpq~2vn-=Y>C3k&-j%j3l^-DuRgQPT=cuw z-C0n-=;ZWh%1i!)bg@f!labs=V^p6XtYe|Td{!9%U&{*fr6WR~;^Z{y?MAt`4qvpz zx&Rm3mrg4}w<@OZUE_34nzMOJcPVpQ5xcU?*STIZrq`v;C#Li>?O*mZ9^`un3*6r2 zu{W;5){$NJS$)X@_aE$%Ndh9>jDHJm`V+>mP*&rc^IcHN?A2f3)@9t@upS0rno!qXV$C`{Gf8?U$V=+~fM??B2_kB*)T)Vo#nU6oV&lw30qdqDk> zlg8tSX58OL`dZgXqie27HFoZQ-EQv=J~VOgS*E&{>vvxzlhwA;?2*|a&xuFl07m_u zWg;1)cBaYbb2njgz5&1=Sc+K0BCj^v`IqQa780MbG94}J2&8m1H@4P1oTR$H$~xcH zQ)Xs)~6W&pg;VszI z0!qQApG!IIi@}nK;bWK#h^^7G+v$l@jM=6xrg|77l4;GnWkC0xLAyZc&?n#7Tz|2@ z{F@q!&SIa~qS-h9qnZ67J17=v!{TTR7@3Dzxf^6++Q@3_wOHmQQSfs`C20W~vBF}R z=e%4NeXoqDJBw*!f)Y*@kljcDz+E(_F~g7{whKm1YFb(Kg1{{ed_jgmt`m|*(5Bbc z2Q=ge2|iaAr1KwmL8JUOby?J-7z${@$h=IG2`o7OKg--R<}?-w;4S)OC{8Dp3Wau` zX>C>So%R6nC*Q0P8+!nfwasmKH#(lzE4FowIrgUY$uEw#^p5qa@!{B8+)mIoxhF|m zl?spJg=;gBHR?!-%&ESmD=7#)&vL zBHM~_{c2gGXu)~#^>8Y;>$%<3B{%2EhW10PuUz=s6!n5VV;Q=m09oIqN~bMyAvjDY z;(lxQKELObD}yFMe*1oK4sG4RX7i@-b|4Q)+GQ8;!cXIOamRL~Y33o;7lM-bu%ra1mT3$* z+gvnW|1PdiE450~;Ydsr0|T*=v)6?4miKJ*@JpTo9 zrGBYyd(mlcKd|w|_}B$a5T@YnT^pbHYE;gZKKlE6E1f@Ren%p_?6)BwF?oMt>-ED2 z-Q^p$j3g;uF8b)#zTY8g7F^TLxzRt7r(!(n-nvz9IOxMg@60+z5F^`L`Y-JNDo5|u zh4G0`^Ky^*v8vs%-d|V#1$Xw=*I;j)H(Aa>DB%#>LKZq!kk?vBM@;D?Ack2qr#{20 zK~KTU%H(LPe$;+6l+%JKnW!vWCR9% z7k$T7@tfTy-@pZz!e!X2{_=MxeabzFm$d6Flpm=Fq3&fK&ZzxWM)ERE*&uaXp>*2J zLv4yEI+CC+xTc&G`S1~eS+D2yG0%<`HrUx~XP zPkJuR)izkZQwS;640Dd@9p5T_x8bgBfODOE=2Ip~VA6H4C2cBw=bCKZUS*L1X6M() zM8_#cGsqB_hLrkncwujM`(Zl+v$W1);}z9c-|%T#bsnJEKhm2@o1)|#>7&lR7#z27 zaMB*X^n z6|+y?_o|{*GQs|8l>)oZ7K+pO+GIc+)B$KG=8HPHN>w5lJM}E&;5+qMQFa37(^EB1 z5@{3;-KV{)h6<7grvPu%yNv)@%PJxgXYn`~ku-gMmS9XzF z!l(yO9{8HMe{TKZz{ap)k-gHh4d_5wEAbmY70b{r{Q6h-CSV3l}~3sW{*d6e5~?wtQUnAo^ML7Qx6R-|vE=-yXTjvkE_d z@|EvKxvMv}J{0FjU=VqWdjb;y^{&Y^s# z&g91`zd8UFrxUg_1n7F!OC~(haGm)A?a09v96|K5a@sZ(A+p(AvD}?z^L1Pp6EVgC z=kYG>O)*}f;Y|?CTQ4nfntYQ+vJt8!*QPf$%TSNEzr2=zwrfmK<1|xN>BaRoi8-;K zSRr*2g>s#uc@N)&WKLX#O&vsjxD8$7Y2~}*#rG!S7^JVT`M0UPIbxeDI#R^=qHs1v zG(yg**S-+hwicZ<_e^3ZeEz#zCgEFOMloS0?pSF)OvvcPDV}*=5xJ74?wp&C->c(+ zp5nr!0M`hHsc&NVC{3;Hkb&dmo*7bJ`$!=rT#Dl7m(hELV3JpQJE)q{28k4%XJVv8u$hVIin2?_#RX2{ zvi*=bWVWMgpZAucp>J=WyI23Zi1AeWByUr#8dH@YO+&;qbywHM-M<@qb&5*0s;AE? z*(W%H0ajFZus0zo%=Rz83J0mT(*H<0ATQl`mUs7znq_T)EH~mhT`S z^tfQhd7$#x;4qK8Ivb@)XZM-B%|hGmRsR6(N2b=~f91|URN8!DeCvHO+Q)_Hkm@HI zefVXS$d@LD3EGVf^w6r=i`{%H`vggB`6aR?p2iuG28BCGZVJb>G%oM2+aUF!>Ff-< zj%lf1cVfiS-RD!+N9YSB{;R1Z2-XPQv@j_Fm>&6DiUc!#xV~A^XD6(4g5B|Qxh($o ze|U+dhryuF>4)6dmxOK|9rEt&6eDyQ=zYcG&35H*n5H` z)jKwDly#lhhUXah5(wd#pNWnywa)Q%{0jv!ZgA9yQ@mIV&L{WY*JY(2jg4y89yU^N>Kq1DrHCag{T25u_!3 zYx|ChtMc51!Gxk^o?X+Er?+BqqX?kcIby=z^sL(8I29)M>-mQVjB=A9jaoPC=xjHy z>glzLQ5K$&QAxes)(lh8lMdayr>~Y1Q!zyF6tr?e`Ft`M7PJ&DHRvX?Brg~6ghLBj zDkSzAAfX>VV06`4Zml?R17#n9l+=DXdfj;&WOM(VI9N4%K~>F;=giJrK}}Qh zOkT`M6h{x{Vqw4L3p{`P1?LAge+4Z58U{mApkpCcDNFdax?WxsiL z?9F0<6In7PV5HS3M%&evjOslco@yn+UaGDCg(Da!=u5=QjrEun;8QQ#^s$HYbiuPL zx3%?6e&y5FFXDC=aL$^vtuSb8DoqL3E$m3GJ1^9eB}m#Ee~1}t(SE~@XeQ$G-cCyZ z>nON2V)dx?_S2_7l)sOTPuv^Rq~siPFjiRjjMUBWyjiru0Jm7)ViWzOW>oNmx7}px z%y07?cQ5sJrZtKuia?o82TRpOJpJdS2?9bb4^k4L2vb?WNrfav0~I>Yemv+I5dT zglO&>vUDXE&1}bewx7$EGWzSTy&^2VUk_pq$&re_j%`%ZqiM9X({ttel~SsecHYg5 zG5@!P%t#3#Hm~*2UNmpO#w>5|+i0C^{p`(R_l@7VsAm5Dc|zl@f_8a(7rG}->SeOb zrVMs!^^IZe6N1wy^?$SnGN1%7_X9?yJ?G>xe5^i^8_$?j9C+bwf(6Z%H0-4hS8-8n zut{Q4Oh_|&yk<>-bTUIxDsNgh#2x|fi0NeVON>aGrV}BXB=^`u9UJeRr(aA%;@+hI zCm;AkQ2G5!zy2Gs>1f=U{BOxkUt9&|@oxK+0y2HgygyNOHv9V6iF4t`LLWbnd+o%z zQ^WmuCut^kXDr>Y^YpZNS4+piCsjZiq6+hQHUN=hC%!4qPnr79GxKc@V~;6$j|tJ4 zccwBnfyK$~gN5%~i`W)v2w^PTp#`{_PN`P{x zLk83FUdG}4=w`xK(qksi2z0CN-3B{F4KfnlGhCHCaz_B@%-$Syabu3%nhBFp3iZCS zJT5_jgvqE^4f6M}CP``_wcH^<{#a-6GA|cFZ+u=5VA1^iMf7HS0ZC9+7ogp>o9%QZ zu|ztUD|^^anyPoCPTy~DObWZAy;t(-s}JIKZ>WBjv-yvGjCFR@8?%yiU@tV-|R`}_*&fNdD^S`_C?0t`-)f8!xTLZ9c!8Jierb-iu8 z-Q<>9^=7%eWKMjrgAdj~)3*XWxz0(E*a#{eh|ky8A?2Pi$3^qB7-^ktDt$L6Ki%kLsj_F z^DJ3&2IOIz%_-zg>K^*>soU4AN3&VI9nbJi$$Ytqd z%5D)!3`Oci*C-SW5H0<5p`_Ae{PW$PE-Lu*_S!SPhL0Ctb@Qr@n3vMArTS==`O{AC zouTAjig>{b<~M(EWhm+|0f^zv%mXfcsj zOfPq^k_RWJkm2eR9i105_AM0T30e4cWK%xCwy&jsUT1c-PX1WOX90>q@#&87ut6Nb zg!#=_QUP90BrMjxDV`=O01@Rd8YY6R3p@tfSC-MXwg}VJ0!EPag!W^;%wBpHs|q~s zS^k^T%RSgeR*>|hYY17_Ay+Ykex3H{1><{J{kzhY%5?CB3o>qwkgr(7zX>|)#v^&7 z+Hl63y;_^ml5TF1t_Ge*M`p(C==du#<+jTX+e!V0n|17q$DJ?dS?#I5bHx?yRQJ0G zXI~|REwTt?r-kmT{vmiX89>kd<9|n%ces@;+CR495=z$p2|Y~ zLwtRf$$;r;4-=4$fuNPWsSOEYxMpF}HZP1q@i$DLo(z;mpzAC;CvQC}OmIL|FAIbG z5S8UV0J_-YhFkCktsOD!NpCM(t7?j-7wyv-TqTdKQ7~PIn@4{R%Ve-qyF;+cJY&OG znh6>H&f>=_Uj3oexA^YuuE|I(wSHv%RKFv(Yb?tEV0YX9jaRi&&HODfNsb&H;r-qE z;c#EGzR6E^J1%r;AtNo~mdw$)74-e7E~y@pBI#RNHC|_#+r7noe8}^HE6n|GFN~zO zo}{;6r>p7LH0jYlUGUkbXZweUduS)AWc&-~2O!Ixo!82s#6zTdM+`l-xR>{Bo%xuxETx9~+fDsj)o*elJA zi$chCX04bSSv0OO*Ho9>*zk&|7&e!gfNYU2tBa%RBU29VgV7{5^h7=8o*kn3?`+cc zpDUG@(B&bCPj`x}8EdgxYQ?v9D^~chnG$Uet9{Rgd&9*gyHv3+MFG+}s4ZhnDkI$( z+sM7Ku1amD;I9(@7A z{o}^O{GB0sq>C6qQ5tI}yhGve={K-g;&8?+&7ab3M$)Mm3z!qeTT;y+KQHEjjGFJw zK@PAckn`f&d1z0#hVkbiO9}EG%XT1{MZ$aPP=VWBuv_zqc7dt$B<+B?&J(UB?91AB z?thK@9Ek%83SAUtOpfH2`AQBg%v_yzX#adLN(e@*3jJM-#adHlLdq|SNRihuz{$>> z(AF}%0&Q@}k>@AhZu<8lb*IMfnw^_I%!+nuJga?J{Dy35t{9%Oo+*7^H6^p5aH$gF zWn)8Kt-3;APNF3pQ}i0k7O{R5e?Y+Kkf#cDJ_-5RnX=GKYJFe2W6Qx4ScM&t`m7^HK*+VwV1% zWf7VH>&gXTV9B2xb~qeXXSc_>QQOADIUV2N=J{%~jB2nAWD1W;CM(p2=$pUNAvOkk zsWU_nc;@ap-}!g^RH<|fGM873K+tqHKt3#h(fb(g!`-dh?~QRtU+5X?*OC%pbl#!E zXihii`rttM-C5S~63)$Qj8Ez_nsY~^?JE%YdrqG=j^pS?;9K5u-wUya`P|fCf7Q6J zc#osrJ-#m2P1}-?D%@W4EK{MBp8^`-tu4ewNfbJG8vA zf8w^zb~JdWT-J${GLgC`dBk3ROwAKxprH_@Ld#9eAHWRl1_m{5ExWHJp{`xsZAObp-(Mj8;6%VhQIGQ)D7X2 zhnW-t#O};9SD3l9--yoA5RHK%`np_sJh@_ld1Zzn%bHofNw&bY#Hu<`*I;8B18^WR z_;ky3B$#;XxytM~{P8F2axeN{};^T zJ+CZ0F}rbfzVPgh7C=bn9!|fc zCERWcjZ*5FMV<&~L`ke7OdXu6+!Q8BFzzsN{93@+3BTnA>-c1nm@aKcm!!b7vjQoI z$SECK*=acr`>3FuW3Yyqox^#ET-E z?CX^Bvlv0hJ7>-*H)$3bPM09!K8@=gn78+5sly*j?ceDA0K3#G3u72(H2}#cniNfW zq&ygjJqQ5BqX*tC)0+3p{hO~*zd@SO`It|NrvdH#Iw`(S@NnlI9Wz}fG4R)rPt>}H zT^!?IFd;2nNEY;q`_uMG`Qf7fvpIGFJRQG2vDNe)HPu%n=$v?}{Azue;ZEl*5O;I_ zy7jNW2Km4%CCFHHx})_{_qN8LlfKbz0~!S7ab_m@8l8n`DxlWaoSaz*-DP;R(={fu z{H{{~evigti9%M5J%qTKe=QGTDigOhM+wExGRgc=RFf6Mx9Pec_w?(k2Ds=*WE$>y zOKs}1YFW+pF!QOo)RVi9aPw?NA`eYQeU1>jt$9~yuvst{tqP-Sp9K6GsCng3ajR>R zd**d;U~)F+M+e0jDflt}$sG~&>@7?90^!MMtoEr+xAX^bC)@UEJUBbGH_~WshY%hJcwEG^XRlNwI%`^yo6xQ#7 zG7k&qj-wDqE`5$Tbb9N;KBFvd(I#Y2g{L-p3)t8hZchi!=%KAcRUF=ClSJ>~%pAY^ zS4rDF>Kjz>Yg!?GDx_Eti>O(8M%tQ$MHj&pcf(o--r1XAM})u-aFc|8U(B4)HxVxO zrKm{J-f@+of?FKgF%`XY7rb5K%s9Eb(i7~-7%LYmb0yQr@$D^?lV$~Gc4Ut&xuhzi zUUUi^*#P<@edAZW^OEjSXG#+Wr&{Mb^s$6m+v~!|V({M!u2a!7r!6LQFSNiE9m$8^ zt}LuF4p?}|^^@Z9w73Gg=wFoxEo=*(%jLL>)1i#aZ(E0+Erp*;sTf}$ck!G6Z*aMg zN4V%5JgHRsWUpiIOI2SHV9<+Aa#&I~Gi$WuhS?zvr)39O`*jw#O2g5tSG0V?-(b|C zTwkD4(1qAKW;F?eN1E5d zlM|90`h*W-{JUa_UutMs_ot1S1*5S~#kK4?R6Jq&+4S#QH#>mSEz!j|@0NQlJ_cw# zPP=zcoX$4cH$_RW>DXjV7(|7#he#l6Yq;nDlkVz=jqgXx$hIxlKj!ZOe$1z?5W1cj z@uaO%VsMY_q=|f!@>;y_I*%zpdVYwxr9mrqNOw+tuMd~_ zU^3usmlNq>;oog38>}KD!O@nG&#hSCxqFu*f+7tPa!4N}@U0u9PMCx(`d`rrRD|C; zis?gng~N<`-E8)6<@6Mn+ru(iEtC zjOG{)A!bRC1+dyfvGMq-l&argm@aXp=awK(W^#=rUDooi@74uEj^hU$&21R+bd$S6 zZS)KJs9`9ga96NbiUA5|8l9!PH$D`zo%A<)V2FJM23(f$TbE~aC0=Ief5e%l7 z>Xi4lP4RG>a4j0SOPeBj%bC2|(oYc4b!;&!Le>{^1feR8Hx9byyzIT8v}Mfp`B znb`-$gX6rXSP^HY9oFrwye&K5Z2587SK-%-1d$U+b96d9e(@?Yo%__)1c?kOmBtZ% zo5Y)%Dx(42S+gpK?7lc!Iae6`cCC!U%=d8Peq+Juspwgd`?pV|0`sTAj}Vl2f1=Tl zI&dv#>BFyV5k3vl76G5-SJDt2)!0BpzZW9tezWc7)eGu{KJ*^S-AeO=!0F#Mjct& zEYwBADs=F{>?>0fK8>9fh$Paf;%p=|*@KE2G8NHc7ihQXmaghdha9mvG1!>dSpAP8 zmtV`WH1~hlDj`4WO(i)*jz9%=lSqraBU#E<^*80S6t6T?;{ILcY^TVQ>CA!_$Nn+6 zCdG;=aRzVazRcA+j?q7dUzrnE=AO8;`5k{f1O+MdkX|M?+X11}geH5WusQog0gzds zUNW1%boymD+o|Nb&m88nSI~Uet`rh@-RiElo^)PVNNMYymY$>+tA7*;wj56xH92TH*r^f>^5!$y4L*fTN1fYxaC{%Eq zFR?W5@iQp!dvy4;c?zt0Ls2Vgq=XOrRDMd5af#q%Z##6JiSMlkAA06vt`2emV2JGns-$M*Y6JWZY-kc6n*|X5dk)ALMpM#Vjh2PNYFrY@Dran zt331lS2^OXp1z{H=+p*pY)Nn$))YUscTxGxMXkUs`A5?TjVbT(oR5Mn*6o@M`?e3w zQ*zBsp&h-64_T0%#1;w)4m|z(2Jc=I^M}bhBARVH&#L^+zsk3_@$xUuO*a@IefNRN z^p)XZMxQ;PxSl;W*ye97CCjkprlWBPraL=O!~;~+6uAk)R?I>_Pw1rft)%=tG?CSU z$I-i%4nB_=FG@WQihCR_O;pei=kCgi0nTwi$Gp@*`N5;$5T}GIZ!c})Ty{LKQVfbK z<-n3i;Ib;-2w5Y3^{ii{#G5SQ-KHRvcfmxy>JR*t_Dz~As{i?9d#^F zVT4FI;UUpWKw%nw0HJwHWFCEKD`8C2%47Sp?OvPf058%eO)Rg-2qJcBloGI$)Yj!-l_d#ReD6Ef4 z5@smxFhY9UZ4Zh-^v6OKh$yNe`roi5#f~uok?6(DRpktZZ=7ohL;dDSwG~i ztRLL-&5J=^WybB;;l((raA}z^W}e@M7N?SBC-#b#Aj9K`^7gyFO?5jk2KjK25;Os?nEKxtsv8N0M&GESnQae*`*4k}^ho}2668+(=Y zXqn|cknRrIox+5D7>Bgjl&5f*`k{tr?V@`u%eaJFR{$aXDSogLz zoU_@?eK;l$55@~!GOs2cVSMrfKUGjrz9ssI&}FvgRqz}5qv`yy%594TVaKT5dS}T8 z{IwXcs;m6AXV=j+ zw#YHB%rXn(_IXp>;A|)5;fxtfT~(Mr^Ei^*+SZ9LTtFIL5`VIlZYnLDU$QQwki z2qeJ@LvkjkQL*VDR4!~8+~deK2r$aec(0?`7guKUIE2}aZ`!s^kdAOTS^XMz*dcqP zkoC!jG~UY@krv&W8{pa*zo|6!#LdTpBhrpPUgz(~(R6P5W2S?*Y*VkiF@1Sy43C3+ zNb5a!{)v0uPK%HR+{ye$$E8l`MSc9~0j6K6xxVVppw>>#HNC(Hy$Y859@U4_v#egG ziUAQDZV@4mB$)OERfZS7A@d~tf)D68;eO;QJBb4&eCcs({xXVV-)Bf4?9gwytKZT? z)Br--Fb#5FwWHxYOYoyP$RDsi~r6jmZwq%O7Pw5`U_3E1k zKx}3ae2ftIr<(X?e2O2<_jy*dM+~a-a+VLJE?tgLHzBH@ zlOM{>d0gT;{cO1Mu1An=hM`;N(If!m8}8*OZ||~b(W`vFTGzm8Pyg_4>53~gh{v4# z%zqRcuD^?NlWg5v`j5^_r^a(xV2?*TEn9Cp9&K@FQ)JGjUaMOT_uS<}_%%7F<=r!C z9nWu7`@a95NssHRx(DU2^8y@eE4_o3-{y82{O+g8ZRZP72RwT`aFBR}g(c&113kJ_ z)g`KBUwcGO$=!nVt^K{#%kvKS&!NdqtB+5DTa2)h*D#gYIdO5nwdDE$FCKVCBO_ih zJ5b-uk^+hKe4K8@q+RWENb-Z{$V}u6iSwPb>sy}cMX>|=q}2z1)518NuHT@&fP=3Y zX7wVbz9ZOsoazfE_*N*7URUpq+hHOP!jv*upLG-;AEBqc`cRe?+wArIfI?PY}HRdmsBHeN9ZwSLb@bqv@mTc zFIP$`*MIoE$b2B`QBqCS{X;6hLqQ>bi3rd*xm^SIhN@Uprq2V)n@hN-l*-Wtkl_R? zt_lS%T41*;d9A*t(O5GFL=z{k;m$?Rko_W5uh?!z!@{78>qlnr16LH*3Som0;}Icg zOrxWgvg|Bg_v7|nIWDe1rD~w-w__MXGUgWH6kS%Hjhnm`svl5=p;IGSU}xq;?-J9 zriKdOLF=~9m%*ckZl0$&Lv@A%1?1Q=Rz(II!4+%j7ydcdU^%9E%_S8Sn@V;DR@=MA zFY}EE&`c<8(q?-&ew~%;5W;)NG!EF`AaK4sJx9uDwd~K~8JxfO|2;W(#cA2bIS$o* zWw|GzyM~Ay2em>jr zY$y93mn<;)ZB=OQaMzKc9ZAnj3HCBIs!nw%0}f(Nr*Nk!12Ys2c}x^=g~!%gDm|Z- z^da!+UPTqUqw_`PZ*((7!lSXc_(U8tOh1kI?7lHL*LIWUC0y>gzg93Z2T4nT22g6jE>`LVqux^kf>Z?Vj0YwbY28X``2hbG#Yl^?S|&q zw^r2^SDO|{nLc3O+n1t6Fr7CvB$g}e54wDQR1`Ys)Fu5xP)>uAum zv)6E0R{+pu&Ye^BBZQi*K&6Xp>W1q_iJx5d3s#|Njp+;&^NEMA`31!e#-QhQ*Uj8B zxa{27y0oJ2bbdDrIIKkS;#7U$BKIqEF0R*iX)#Q*sVekEiS*L-I%f&QtJlaiIL-Az zyX2t%nEZq?^Y3tjNEQ@6B zW6kO(ZdUM6%TgSyDX%R!l7GNs*0Cg892Y5(@#~`Nc0CYQIagoxS1$E8HV!IYKRa60 z=Ve`2n*XrCJvGbmk3U=|`$=NAx<1cMQ|TMus=SF#jn9JF89oM&6ilS}uBm!+M-Tt| zwe`PLJ^c5h(N4?X+Pz~*oD03vliXMR%u+r|3rz?7(}QQ=Mzo*D54=|s)22pz@Z9qy>lk_p;}YKY=x!5u;* z5gVqtXD73n1dC^{DROlIl}YE0NQKb~R^Yp7@%J^CSI`uc+bPiYipgT99bJVSB8V63 zOs_mcCd|^2#zdH3XvvWh3+b*LwDxmPeAC?f#H+acvA99z_L$Aj=Zjp{G)&qmf2?`( z6A8c$IteTfBJ5f+r;$5P%sM?_ym)E2Dng~hG}+}L`k=(^r7|*)6u5iyvkH%UEPeC8 zSfa>;mvvK1{yJE49=8SqLzhGQI3dP{I`-{MlmO3+us~wcVQz>=-cGpIu?Eraf10S5 z!oa)i&`6_ZwWtyJDkb@u*`5rJgg$S)iFBdA)w*1j(yYFlkH65o{H^YR36oD$pB{vs zl$xz|a!ubE>rI!d3^nWzzk#}N#>4obz8szoWjc=tfNOOpG5 z8P0Bz0h^l&U|5hdo+}vcSp3n~(_i786o>OXKlwBTtK{=WN4W-NqEH!crj>a8N&t>; zLYduY3X5*QKz>ClX7-_}V%^Q&^077W<4GG4ahPd$?c?&?0d|w>fZ`K-23yEH*fJy? z5Aw(F;9@4`V4oeC9`B}Kf-aJqy!gVT>EJ{BnCq7?&phphjJeKfN(M;VDUZfhF3KY( ztT8@$Ll9a$gvgCFW{KU5L(3Py#F^FVC_9e(9Xki$n_tO5^!}FbIUsg`tPQv18s#-Q zvm?WnZY_Se@f+1g>q)gm_~+~~G%C5qjQ!{9)?LS_E_Ys-v{_26psGZMzCGuHA47E# zU(4%>@@k)Cc}E6RDZ>0#K|!@JIgpV5-^Z5s3RpGr<0ATpP-uG@aqu_;spx8&yFIzI z@TQ?!tOh~&UujU>+N-TLIUWu#*6X9&fqBe}UN@5ffTmjpX}E&@)>v0c-R9>n^zdyk zk&uSLPlhh%;6&-SnYFk95ygD<72o2dtj-Z!nOW2awBIf^|CL17VW}`)@wp-mR?{t- z_m|w4UNrCW(?mSr!&klnv%#l|;BC-iuGg2>jFm6ne>%FhhHMrk2jab@Gmjnj;HDP4 zQV{}6SwUl!Rmc=SU|+iw`@|?Yv1wQMEL?n=Ga=K zPh<*+a^CSPn};(FkLh9WQ#JHqy-9(es&hCM<+;nlb8BXSW`Nt(^V+cmf559=6y&E7 zhX8J|DPV-Km%o;uTnj{bO#-dWr+3r_7w$r)!BU6W&?JvQycpYoAl=^JO;NBpWUr<8 z@v_cL?i1ckuTIVUj)XFqOGTs1h&{PiV_ZVl&A zw4f?uK1|`vixp00pfy+ez@PbMkZt{mGTcRE;$PQ}GpXbN2i7GCnok zbs>+AN({by5~A@at_zU3`-s$mVb*HOVRk7p2-cpURQFYJ&I04ksWJg{SzC9$FuF!- zM2$o1orESjR*hS>CM{u zEsU3$Aprt97Wa5iv_{N&UNI^nVP+{uur=4`^7l8>dSd6~pYD`hm!<2}P`FUqDB2@u zN=P}Px$4qXijxf#n@sOdKEQ_ePJ)^wJF`J0YTW!@9F?tEOV&;bbo^V|Dz$2BkmYHo zNe4j|uy0Y#wWANpHQNz6<5$r}<9ZFwwHW?s~A(yvv>^zN^4c! zH|+i$lTlC0=fACVH5V<;WtuHJ;PUkC0_Zu!O)BC061@^fIB6VQT2lpbY!?1#$zXdR zc0kJ&-|@ZMA$oilg1yA*lig|X;gBD@bCWVuBTpnma{IYom}I|a;V^yVYEO67;8gS1 z4Lg@sbU!%sX>9*u*v;i8F~7$%#l?I--9d|?5O<@|=j-jypLVki-V(P)?>6aK9c;?W zP!$b}r+Y_GNI0aI?K!J@IR%jpyA)h564Y(ZZ$ZJhOd%b!t-`{y)8T6ScEPV~a=U}i zAxGV*!9VwyHdYr#)}nr^Km2&WU49U=WH;I#ZRkeAOXi-&MFr1FG}DpsMxCWJLCk{s zJ#ao9zXziRzB;ebPFz!uXrpRv)Q-)0(AowSJmVS8zrx*8S)>QrH)^ zE}7`=v(&dNt@(MD;qtl}n{ubt_C8in`rUtJ=A%tsIkn#_rgc8&8@2CVhdW$;9fz0d zAv<%KR+Vz$@t2YUUD(};x`s+mj_B5QGX4a`_2jI6$@SNpdLMf>e)pZ;_;tB+9wZp~ zj|us-g+E)2v+xyLiV1@27fa;l$cfVQ*1qd!)tBOXT23KRA74GmcmCfaO0K7-b*MkV z$Ih^{$M$i%4=b9&m9Exy9+7@E!tj8kY+!Spo0w%9(EAjc;Cb+j{5GWd#b6#*bB&bj zT|vSnNxYFrhFj?>=6>?lA{8e6tB4+E6Mhg(#kk3%7c(2`f=e^g1=)9P) z-Fa=_Z|wn{1XM@tPXv4z2m*{rJ6i%iVclV`DNZi*XqsajnojEGi_0R%+kIQ5_qc1T zBX&fn=e77gSjauNK$t-Ki^n&G+b2pC%;#oozi=*MR%Mbw$X6zpd`?G}ebW&^^ZpgW zkN(BU)4vVbVq|hmgFjb_C3$Z0+CCT6IDK=+{g-pf3QtLLZ?+rR^%R^z7A_sVH-_k! z48ix)6PX2KZBq~tsO;El;W?qLeWUgv4_C&SY5`*Q7!|0!Rk`-RUi&s^UJ5A2M3}q& z!4P_$NP$)5-5c*&&Le2q(WGtKa6LnEG0i<2(k4C{QYSZW=-@05L#W6)e0kGpI zd$;pEzC+7F$_n@aGAo{5t+mQ`vslFwjy)`cqSU~B%GPN?iD}AOnJexyUu2SRMf<+) zFdDg~$IGI=-LHZvzOyvSZ46U)_BE|`OBI7y4eSfbzwa;h+byeg4TbwRoD&@@#zkY& z{9Rh?-yY&gXLiJ*i9(nCK4*G)eSW6fv1_V{+8a#U{#KHnz?(nf$#JXti%DM6TlW^@ zh?lD6^Jcsv^J-he^+ZX+ACcKK3St*IEa^4#h(rmLRJ6I;l1^LvvY8OK4I6%|%vDB3 zurXx7oj_SflOvK^nI3w^p5DXyW_UrZexGd(SsNQ1>giRG%Eg9S*e$Hh<__9mjt zQ4u?y2~!3AKEEMOGTga)`^JgL!nHLWIqcPI#7Q*W9wK&$4D>H~o>EmqN;e6?XtBI; zmU)bs=jjl8fk6%}Uvb26J2xIqjw%jzC46T77nMK&v2y_G7)#Pt6<4rE>Je*j0}xC1 zJtu8+CRc7Yp~&N|xrRXp8=L&&8IgWWIKuX&=YoGTajx29ta>?lyG~EHz$txk?exz~ z(r<@B-Lc!19=D5RY%L(6eDfZG6M+fRhfA+1lQ_Rjb0F2~dHvaj9D|^Xnqsbq%)3Qf zz$pQ~IlPNHL<3Z4aIlaybb($9-NgL>1U7=glJBEBW3Hj7*cL_$a)3OdH&!z}KlB{Z zK;4$2htBc|I%8c`JYn)C|3}lg$75ml|9`c$t$aJJ#XU(`O?Qjb=8&P9YNeQ^gDBjc zlvEna=_Mo_6#8DYl3fmYFdq#(--bD?#add6H@!H zg})iHTCVx*tihJ)a{|%+Ah378B7pJq69_x2ed}hz2#nYe9pq8p)Ve^RnDejxA$7bC;V<9M|~d5oD6zV>IjEWEUuvawb=h`K`K8VDIxMc)AbCn!+Ci zhRK^1E^QXYJ2xqV`Z8`g&pduL1;@jm@gy6dA3|_+sgs9QgV!}iBcshf>{|~DVdLq8 z?h~&xlN>IJ!WJ3~!oD&H7_G|sYA=5X=h&xPiRTA69|{L9lO5;MA~(|G!84T{#=2Ba zF;m0fgp7JM(e@&kBb0CWhXpDslpx6Fc&pimATDJYlyT>^s;c5UjEg@leLM&|0~^4h zx1Zk^pHz+lZVy1~I_F_Gs8)Iq=+Z#lQGSMPu5r3Qbsxl*!ap}H^X_f_+iDR(}?eEeqJ0q^jYD1|Y5tTNu0 z0*;UxMq=P~RrFQjfYO>W>XEAa^h~kyAfqsy_u8sgB(&_JZIxk-$2iq1tiHBR&FX|- z*aYa7jk&Z|W-P>C*i`qThpju$jH&S-EOHZp1O5=3iuV6*`@Z$$)clFK+J58Qmd)1I z_m-Jz>th3xF&no1bgj}zUOk|0```AOWavwxKir#L@VlniZnVfCqN5E}=7V45*NU$=*IhfaCaA41X#WDo zI#C-0Dl5J$QO=UBh2T6Qc-E6_PUJ#-<=1$`9TS_fo7{edi#0y?YT%}qIsG6!rVTND*n)=UM(^#(5|O%-}U9v{&@-eq$>yk zk#e{JgEDTd%RwsKa{U)y>FUG&3%SUK#sU~gz{xWmgk2IjNFB(hRT3k_i>-rkQBlI$ z-a>?@_!MVkIeUKP@Z!S!Zi_$#-m1GaiqIuNP`cPly7_9DWUWa{WSl5&!6qzlRQU5X z>xl1m>K>t6mebRM$|yXBBQ5kPK@oj=zf=`^EfrKLBou=Tn!0YiR3-1W`3Dqf+onhc zCuCx$Kkh)}@+I@U?^l(7l05ZdXv_8BC)g?a4jk*-qgVE1$E8H8OBUql4Vi}t3$*ou zTZ7K|C0kj3X}MyBKofgfqnUt8l^miC#7Dh#v7zAtBi?9&wVo&Q$O&QNheD)<7UEoj{%u9AQf2QTPB}a=ZFTEuz5@!={k1VM%Sb&E8+xZ8v=3Sx+r&|5`Nnlo zPO*hxEX!@0I>bUk*nzv=n+O0r(u&C_n8{217g2M3kYc2;rOS28o=B8usBGopdgA|Q zsEqcQ%0Txzao^&gq--#){eiB`H~Y~~vsl6t3x4%d-(U=4bQ|(IDf#N~1NLxenQdE& zUu+j8M^9YOTJx<&u2dU!8!S1UTe{y z)h!?0MRo)cvYuTy$2}|G<=l)r37^Ff@lF`KQ)>|T5W$%<4IYU!L4|0cfQ=zUh6EMj+32iB zbasbGBmTZl@W6w?`*0}kq_mUQKMGqctTH0Xq+}yy>vBt5US~h%!dNw{mQIzHh|5=I zS^$}Z=;DV&nhd5U8yt0Ix+aWG#|VNF{8^xDA~8)U4}v)HnZ_bfXFKbb zjGg%Cpk>Jc^WyVbVV0%s1_O_n)r%VqOP zW6d#=c+_J+dl+e2J+Kv3Uq7;7Pey^jsiO^H?`tAQ#(tL-sU;Q8Z+D#Cj(8zCLSItb z^3<9WMNF)J7;1KSN7%)_YX)eW#MAuEmQ|5AM) zGsUJ4l84Tgf8FlzWXy%!>IEp?TQ<+!z6w1NmGA5C!hJ^7xE=h}+i`1ANDu{#E9WF5 z2Ozm|bYj%1^2xP{`aIUJABSoryWb>ggJY2>+1D_IVN*Q3J{OT7iDsb=6l?GwI^S>3 zHv5qb4EueLU)H4u~9B!HBz>M2nkzO%(W$GIPB*Rlw>v(5Dat_S#gvMj}IaW za)_7~8=|X5@&njT?hiWWp5=F9E~*8U$tjt5(OYYdOe^#@ApWdt&vx#w*WA?TPRjfZ z@;3>-R<&oEQVFPS`u&R%b7grT)x|vhz?Tit50W<1IE+|CWW#E6X=Td~r5NhNl=jz`OX+n8&{Jy=LciwbrZvtVV82LUkl{M|2d z+s-A(9&}w6M5gP(i(w0pn%7m?IIKJPHCwunRJ=+q75F5tT91fQ5FwjYTL%p6He-== zLCjeSTF#L~8j``pSiB6)L~1lkhRoHYMbJfp;|WB{q#8CQf+7_+vz1Kr#L1XB zNmB^Zr+QGhf$aqIW+UYjq6Hg~;L zVr}U1craOO%g`7s8zk6Sv!}Zo86&9cK8skS=*%(QZ)W-t1dv(prU zXH@n80qLC_k$8`2_?bY{K&6MtfN6zd>J*T+n{AeXsF%i`ODgf={n*rIJx}-Vn)_}) zzqMLFVVJ(cGE7QcL{+fgsTXg8YBI}xcb*JNijmLNPdcg4@Y$F7?5lxxbtR=URBcVb zS0)+`5S0k(9jTmUW(BPlW5+d~SRYo7C=NX{5us(X7aGRxQg*KD(afa0`aLhQlWaJ= zHIZLUYSAJIoZzFndl@}E)TGC$i|j=u^KmbIAEb}g_CByJ7UCv*(1O}v5s7D;ck9i7 z0(#(HrG=loDY08u<9hsjdRG3D4?4A@%X}diZIyme>?Itfc(DdwOWrYBc9p;W;rC=2 zh$O`d%$sKr5Jy<-&}d}7cAK%J{icn`5*`!eY1PcwWN4e5!sp=*;=YshvypSgj>sjJ zO%|NZgTI9gZ&&WlF5(CcF_*IK3|H~?4+4pkLo*Co)DG1+Lp~T)gWyBW;-Nuni8#be z!X`@BMcO_6VS%nVeYi49Pah;mme2AVq4L&&mtBAF)HjYW|NRvquMP)S8N?f{Sr)bc zB}rtgOzA3Gyk5pU@01)aFnp7&CDAvU85PSP@aGeH+2-Y6H+>bDygEw%zFvZCSXh%%}XBuv6b2YB6lH$zb3iH&nf0*?CtzMMDJgfL*BO|=!}t+#FV*!xVk zEJ5FGCd50>XD{RiRoJde>}_6nu25=;c-WjSO-~JVlypXp4LHP<-(=rA@aXwhR`hL9 zRWL;;c~v^&t0hLB9F6zX+?#J*>;Dk1!=@jT9<@FALQB2fs+CcqypXy~fCGCFdyo1; zb#%bm+a3hrVQ+We*y{+h4Xl619>TTWJ=I{Wll!_Dz#aJ^dVX&%7{jC(pBLWcE}S}U zRvnL8W>o&0BFopc7lg%ZsVQ4Ns(cLPt9KCiFb?Xm^;>m3#MWlFJ^rT}L4GsDa;E5> z-jflcHb^vee zs+@!{zaftnXBL=BD&FdddUdbiLUn4-lNNE!(c+FEoyJy?)HS@*C7wPP;2KioQ8gCK zqk@20blX9+B3KTGtM2WMj@PdJgID7Dbm8#viC_1zSRULZ6%2BzJIg@2*E7H+@UMK!aw`lhm4#&ODaQC+_6HCZEp|iJ>PHE_rKQhr!P=os_crMro z7hYzpFDhOiO=(&=wufy5pmI-w?$q?>G5I&w`c*l%}VAOlH9)5Bq}k2QaQj*NsHi+&7~z72aEM zu--k8xiUz#2k9E2LaO>pZEU^Ye6@me?x}v>U9Yc?Z_V zCI(IPRGdq!kR;EZ?VE8Hvl9G(<;P4i7R8n8646ScP}kkRmrVwK1h`>yu42O5ihV+^*SQWd+GQZGp=iJ_ zL@Y!c+CViudItDQ>kiz)AU-w4Z+v(Rfzj&F@BYle@Bl}{9T#uCGN~#HD+9KmSweC&Ij&F-w z>xQD0`*16*$2jM<{KQ9*#6Ma>631W^VAw6A8s#I}ualb(x)3@tAd#qV;Oqst)m2w5HLJ+)2t$b0y!kBo#| z4XwtybAPN_LE(?rkHPPYYg01A{zeE-e`-)?*d}3}$TEZC_SSNkkAf*-I{qCIPe~!% z=;J|uGiYjB*1R{C_zV+!Pjkm_vcQOtm<(8?tLV_j3f3aSQM!h+4b7_`B{}MNr z9c0e13Q2d%8vdtzKp9lDVm-c!ioE|+9`M~%CKa7UFg?jE{vHA5au%b}GSrob*gY&R zEwW?O#lI_5?<)->l9>@MRciMP2Z6TRa|?TE6Pie=rc$^idTj!OBBQJf%TAB8h-p%H z+@sf3MFLVGYRhHdIp))V#BT% zwZTfu7qy8GY<#>2Eq_cTm4~WaCOm_)CJ&K$w0*y~LNa}U*goKGI?2`|M*6_JOZF>m z(Gew3f)QYr2~TpD1%jlvH;qB^d-gO@rSFu0Y$GWqHSG^OaLG>infwZI?X*Y}uMww( zqBC|}bFEYUIQ<7n+prlv^4tPF`t-RO5M}13jcJv)!7@o}JsvbjpT#2WJp*R2e`WPG zeS8J_y1`L&pb^$`C}F_7_=;n08wk8WYT&*Rvw7V#^U>9D>j7y0O1*28$MWzlKWH5& z_y@n1aZ3HXPi)J@OuVLDt8Fj|Q?Vh)f5IzA8?Cm6_36KBwuob>FAMfrt);j;V&j9? z$Ts!wg=PpD@X*7&2Dy;iN(KuJ>itixf)M8FIu5OUriyHT{??O|fKv%IEC)Gz=2FA2l#m$&RK)+TFUxT0D`q1MUwM0e%j>6kpMKWakGj zw%ARmytL28r+nzqzVO%0Ip$_@X!^a)|N=>GP>sP(s>^%Cd z*FN!IF!LGNvmx7uivs`o^U-}Uz%WuERPDw4{H`sqNlq-@yX^M$Y22I8?Z0=fn@nx2 zDEGJvT~C|Bp6E+LJ8ILE*fM?2cNw)X%!>_U&f}uq8%i$OhojqahD1$@Hc0^F6KI>$ zY$wuAsb+*57rq=V#qawQULTvWUNNv$WNn~WfZ6*IXnje>!ckCwn%Hjy!=3AeQm6+! za(x&k9(`RMKZ^s<@0`H$LgYBP+^B7+#QlSCoSVPev@0!7NR5bE6^)o79c{r5S6<2L+HEB*DwE#GsX z6EBZ9o~6|+=S6;b)Nl^ecW()qVX0`9n{t;_OCb?jQN#^t39Fgb%?U4gpK(eI3mRHb zFz6mz81{g@Q35$r4}dHtC1;PWM!YzDL*^7y@;8nuQe*f$HgQ1|MsY0cC6Sp=&5-uO zxNy4)0}!RGcEd`#RDgeY-@9DyErX{iR$J7z?ay$=GudVTP(O%7A;OgQ-3EbY-FPbt zA@@LR;3AEq&Go_x@54erl2&C!GaC*y#Pf=#3Yi_Y4Xh4d5psksqb$lfuF9j&OZ{s& zYS7N&@7G0<5&IsC%8bwHVa0O9J^6+T0n`?V(Dy7e2{Vh9A_dkC8M4S$fOqFR zp)#l2CdnaZ_rb#6Im!3jt~69$xfsz6+w@4>NgIM8&1vkOxT6ox>tL`Mz z`jd*RKJLT67w;GDjNsqE-7gd@9C>qscHM(t#U(jP6~pDNLw4~#xoN?LvyptQD4Z}t z%8|thT{#M;?76*y7eXOgHhW$@ksoz;j=}ecIgzH7oqx-D@SW?f_5|p|fO5SPN-Hkh zn-j7kwf8=jR%x-<8iW|1B9|5Gq91b`ms|k=%SSEO4pLj{uMnLLmsX2;hqcy`K>)dKdkWA%Vz&CP4f0QAgYj{@TRk&2lTqY4Bd^_M*LMD zXyc@WQS~f1)r7QinNENO%h=FM8nf5HH$pl-6|RuM`AwBij4v2({MjM-V)wk$ZtmNtEuM0z2y zK~A+-zTe9*+Ts44V$&|gVrqR94V&t--(9kF6lU>}f+v)&|1sE)i%gzHudeVvUbBJ= z#44NknESB#$u*!!&7_5Ix%b@o?iqJ_vCTH33N24vbAW8D_XEHr6^VDbb?GQ#G58+3 z7v41rtQ|K;uk*py**(GOtFig8bNl$;jQvgt8^rYZ>gkl6iUVq@{a1l_20It>90B&E zk{2ZNjYz(WK)0PJf^Zk@J&Dn1%2k(Tb|PBzp~M~|ZZh%(IxJ z^~_k{i>$aB!c?o*)zn#6=iJOp zr-ZuSR$$9Nl$cBCYGWh`8xq7c?f*rzhR=|*`8?S_VHSqS`Mj)_?R!Za2Gdr*UEcP9 zPLwh2cjE4mLgmg~x%oa)IOLc-)e!1r_!3yb59MwAbO1ThHg}%yZLC(J9H`ao4AMBO zl&3Rc{LD#O50~WEq%?mF?3njW1DCGfz8HX;*HIT)z=bS5?$ji;F zs=r02371ZdCli(lL)v7`&>kFi_M^*Iu^N^ zgyr&AT)a%N$G~om*Z^vH@Cw+5K}ssvY+Gyw*UCL6O@kw0jVZF3#O^$FbZwL+;7^%w zZvV42*C->J61RjcHK24_=*_WGxcP@EG2IU6c)^qVWQ1&w==9@sQh=plk>sU~>rzw! zfwa?y^<39FJ|B}TNPLZbU@x65#$jr$NYqQGrJ%xGL@ojs@o;MPf`uL*{KS3V(KG~z z8l*BZUV4hpa?P@Kxh|-`7wxP}t6-H5WXH?dwNs2Znq|^{V;5J-h1sCKx4N|)Y|?yQ zcETokWTsA)&GP>gg`|b{qT(p_V&ey2M`cfrC*XnGh}wLo%ApyI{U0NZ3(VGERmSB?fXZzcSskg|9)?-2`n&G zecTix-x0aG^dPcqkBM#a__;`S^XBG~#`1}_m+;oGoYHYyA$YvG3q+aD0%e2C<}5Er zBJ1U*+G;-6Kz`V({QDQS=*tk0Bfh9P6!l{-U4O*+8!77#UXra_&~u6w=LMedfW6Hg z<+YG5PaawCDmj<|#Ds>E^EeWfW~A`S1|-^M3C$4u^>;hhclj;Es5wga5YH|A4bqPZ zsp#IG&n67y_t^`lRwLYfzA^9}Uh0Lv&+b{LIM46lx3G(lOP=VB>3T~|J(h%bnQ|^y zF7W%~sB>f+Irr7*4iBe4hztch9?C-+s&fd+x%MDiIy2t@~0M|*whr6T^VN3U~QY4Qr> zMcey znQKOW8sR+rp-YGaXg#NUnO?AVcl0?2*Y4QLD@7R>-0Pah6gTBn723Le8b#7Pdfxc+ zd;_juSA@QD2Gzp%qcQ%Vawi_99EBN!nx3+CRagz$|uuv&VDIx+_NbA3EGdYO%A=$DG9#DGUy; z+c0mxH(xxRWC2K~FG@DTzU|40WuZ`8@thn19~Se9N-edq6NTs!7`$xb&5`+U94rKd zPEbYm)Z#3!Faps5m_#3yFBY9BnMQP6-WkIvGAzhH1>~{!+@cLUjnpyKB5X;<{Bdos znzxK~l+QRvW?SIMf)k=)ueSt?gW(S|A1eilny`ODCt9DM9;~1BPKkJ$Pwy-d5COL= zr+Bhls>W$Xhn{D~47nt%Jz(QwY1xuc_MunUb=!`fJkl3D_xIX4R}Nj@nAZC3h{W?6 zxZu^NJYqSGpBFRi#>GgUfI^IKyK|b%=l(~qhFm*hYfS@pIp>w5Va}Y=ykH|Q z#~VYH6F01M9f~u^3o86@?IH0AIiX-pmMZWn1_7fKQn$N(O6=<7G%j9k*~Vr z*2<8e(-D?zU?JNsHOeFYww{;rA4TS8pG4JE?LJ`OkkexhF5lk8xD2Bd5)>IZGs4^< zfY2}qhQB5POMG6&lMx?p{d7atU}Q{cArMNTGw0(MFek~*`Z2e^lbCl zNBy|3p2>s8xu-QVH+UT9`Be3#2%%zy&zkI@V>+!d#E9#~3b};GxU{m0Xj$+Lxpw}9 zu|7%Z{%K*I`cH^Irt!T_=%4&x;s)xg)PKj0>=?t4XL@Jl|r!HAu( zJvOYr`F@6gBh6!dOZevUH|GIAdeUdL03kgPWZcUz^!no{|5#gw2uLga!dcWEf!N60 zOn5$Nd*;M(I|=Kd_-nb?epkm6L7E2VC8i?dRZyW@R-S<1y4nMSTE4D#toIKaof@%W z;IO?IKCNF4(1z$lQTZ5{Wh2@6FyrVVc$&O(hYEhpzm5iTXEE=t?&ZG56 zNkgzh22BdZDvS8~(QvNF7lXzSrXUoYvCqC(_Ag_yX#TurWU3zMiii!;vI|2}`>?ns zwQ-N_4w=8h(>>!zwcbMqSEz0WZL8#K^SQ_+uvjE@*Bg^k5WhWxBYDio5LSrVqTh1% zSo1^CSr|s4=e$Pz96Ev+p(_yiz7n19_o7ELt3Gs#9@=-a5CSbf<`n$?kBNFl^o%G( zW&vu(ZNx+$v;8A8cE3agMGACKoGDHjh!p=st)d^Ly1qEf6NfF8o z5lroTZ-29BPNPcl*Z*8;MbZX0q@h`+C7h0J5Cjp+yZoB1G-=_5mG?s@A0;se8z#QR5}c5j zbqs(Ve}XhrtuV}wM7n@fw!LDXZUg9^LNzZt_D~H{U%;^|DiQmemp|RHU(Mq_$G2jp zK-9gv^gY^DV<&4p@&0&;_{>}ObxN4x>bc7@_LxNUWc-!G7>MqXRavNZd85VY>=8ed zC9jC9H~kn>xJu-Z>%$1lEmyUsX&uA#|fsGCMV8l^YkSdT58jm zRFgxE4@{NW_Mwog)q525>R-iep=2(EK`(O{NrBZ$3}n-1Yi0u5EHp|-I)n+svF@4O z0qhBFsBWJKX9PBOHe-mviq*oCC|vJ5j%&789OXdaWDG?4 ztKT#$VZ>Z$DyGZUIalzELHlHQXih!~OsT!$togIEY&sJ4HnHr$^q_3>^AF=r6u_E$ zO{LVsEpfL9x_IcjR;)WhKc1l$c_srg4P8OFug%LN@~v_>=3eLK%WB~-6~4|*<`umT zMs_`VT(cVbmpbh^1i~MgHB?A1{wGCTkB6)y3>L$vCm_~8ty zF6I^IGg7JiL%|!gq9|OM%WO^aOD?q<;X)WzMdg|#Wkjc z>%_O~%3KS-U$K5|)SA)KyG?qpQcCUTuW{GOJN@sAk&(LBv#bn>M%;|~!s(7xB33zc zPQD^O9$W9|MTRtPlWTiupmAV~ZQe}8jSbboqwr;6^zQ8>F)DycMRJ8UpSydxc3Ea; zrKXb_5=Yf4bihv}i25;n-o)Lf*MG0t_rE)8ooa&}7Y8MFGeZi2Os}Z>BBpOi5tfCJ zFF2LvV;b&|lxDJeFWy-&^onRm^|`oho!;ohAcrL+15pI>oq(jhn9KxrO(+)ox>Es- zl9^M8DMuPcZo9sF+*tSL-_?oYJu2@WH^ypjd~#7YMCXcUi;lZ532W*Y!Ml-&n->2; zq7kyQnYrfG1E|bTZ((h5XI$hP!y_lpZx< z*V9?;z}YH()_e5TQYH{e3c+3*Bp!+;c)H@!|SE zyseIyj>LN_E?a| z>H$eEm}%T*5JHgFf(dWKnKS(M>M}m2JF(*Wa-?ZY+rv#m7hAsO-GxrUe=AnymSsK} z^j4jnOH;P5i;!w~^70c|1wzh^8E-OZdW&uqw_|4TJG$N}*vwUs(%Pu)s|-?v#)xo3 zz2AJJgt)zExrkTD>Ji>sA~Up$&g%Be6W;@Ng{^qP;HR%7vcPNt+Cc?xzFo+pH|jq#rNaDOluD&{78q z?o?a#qU!boigB~`NkLtHvdvz7g3PkripBR-gM(VXPBG%Z5Q}uwv=c9~d6MwAz;Utn z7lu-pX(J+i&iH5DJ0QW|RW3@Q;KBvf2)AQ|8mL0;*!LW!cd03@Qm1lPlbg2|Iie96 z>3@@LVM)M6<`R)sfJY3*r!ZTK$r4pZfPs#WPByg>GlCHVp)W9%!@ECzdh>3X!A;!gw-&g)rR;=?1&G0c-nG z20f00c7g6sSpZGAyDE2_N4>6M0~!9_B(E_4=a&pBb}`QhxqDK8xj56y#1?j}jz+4d zE>%KjL0`(HO1GInr#R5!j>jWiOSb5ElU$mENAeenE7PJD*rZ&Zc{dIr?%IKBE=BPm z2a*T7C$=cL=uB7B_4w^SqE`18(sfD3+q4g)-{Gs3lB#8)ag{5vbh4&HNLoji&2nEs zMB1oty-GYWMOecWVF9Tdug!k+(Yrw(Y??j7yf(2BA#2*(8iPlz3)Uy9jdiMt?6Wh> zfJ_X!Pn(kYR-Y@$=04t;l}3Z4J2CY6D(VC2`<72T+s~Be199S;_Kc-wln6+5LhFU7 za36d&5f{2TZO>GMB8*QGW}mizAhxsaX6)G{WSC8njS8Jg(+H<8)s!O(cK98TBfz@P zwa_|}5cFcBxt8xO$s}}~I4j{O6Lq#7Z5-rY_l3A#?+dLuA4wK}$-6A_1i+!Nn8gpK zT#Kq8YyOGPi7~s-Uj(&KY9Uy7(^(DpyPM0v1~QE9i*O+In-e~c)W{TfBp=$(3!gBU z;L+x0=oKsB=9Ns?x&Bi$<7rv$nf|8FqBC#4pYYk#1eW}j6H=>elDwYypNjk3#;hhd z`sERp8ZYh1y1+sZd2x2!h;;VFOvq5!G_$2#&PY*}+%?5qu9h$ z=RMwJ_@P6M(3LMwUZbXy7qv#X8mUH`T;xziWnhmn1dxs@J-AJ*RNAcz?A?h``L2$} zoK%Psv=O7c8>R$;Q2Piy%?by#PC~-{Gef5_)lDdubDS3Y+{!jO)tnw+Mkl8{iCl>E zqsoKNH;8)1e9sI(2spBd5YR_E(eJmD@UJ;&@~I>Y}4T*O%&V z@$TG`@0?p+I8lvMz;tCJwjI*imWS&FwL8{JVoJp(vvlr~N7Z($Aus!DWNL%w0zXLySSscMD5~a$)cr_z zNWGWcWZmd?k#<^4a`cC=ubn3Oy^`jCb~BRR#uGl>89NCM506;uV{^oKr4K zhS_Mu)#_Sct+SRpxA3!1BI4hEdRQKxT4C#U^>}6c5qXUI%FRaK5mrPE3*QGT=ZKiW zvdnRf>?}e9Hq$pNDCg9*GY3rFd6^TuWtQ-~1Ab)ZdP6HVe^?@!ZUDEOY8JMH{O@Xk z$LuTf0=Yh*hOK7v-(jQ)IqmcS1yZ**tEL*P*^&k?c=2w}dU`s?wEt)_qWX5jxev!Z z%q+fjZRnfq8hi?O_t=YiM`AdBnmI67M-qm5yUX5OwHdf$QB{gWwQ;GDZ0pLpd!dhm z$fvMysyaHxHc0X0WnvgFD`MP^#-Q3Nlu7oU{x|v75rI>L7N8i9L;*1ta4}FEyGR7X zlLgUjI(E5Ps;Ni0dwk-rQbMbo>vEJGYR?W^W_I?7KRf~M+HQO>84rAJ*k z=q2~rsp`Lh7US){Sv`jap9PD} z`3*yY0ip{b@DOjj&`gdFDFZN~oeGJ&_$mA+>Am>pafYb%YgeY7WH3yJVyMrs<#lRlf;Onn^uBRA3f>L}Kctrl<%pY6j$#L?A zFC{+w~E4IfB(N2>1b_pSUIl8xR=lN6Mi9@ z5&ASBZ)9dtKao;)XQxNB+6~U;`|LOEEUbS|xt1w)s_ppY$|>9+ljyKvgHW}a;ysXig|6QWo1yt7Sr(cds4 z?q0t)4U6Ny2pA;{tmJ6~q1Lz)tdnJcp$tppy-ZkjjB0u8*~l2{#^FSpKFjB%{;tf^ z=C7O*Nhn&fe+)s_Z&FFnAIBH#^{V{((k_)~9RoOkjUW+);1Mxy3kqDiB8sngwlQ%M zRM_~-ht3D5BuF6)(PI=|F`;C|>dj=~Wi$nu^sUhQI&s6%F$Wie0^#&V=p)s(y0DUz zKq0u8eDs9s!B3U%YF8aO#}rA#n~Zoh)?pAy?kC8bmuZR(&T*yU^bEkaJ(L)PNFu|K zki|qR0)u*c64uF^N?218LL{fp#D5?y9R0J6S>2F(hM;R00_n9r6G$ml_|Z- zUFOaMzU%++VZU#vJh+PE*B6=)D2aKg2#o4Glabw!z&1$O0{;QctfX|{qTPH=D>d4!0p2ixr9ko^}7OPcqG5id*k8Cz2lA6 zjJ_J-F#fXf!n5UHw-U$}eJL|i$kw7suiW*h)a6w~a>vZoYfYdJ(K_UN{MRW_nwYq0 zE>4vd6BOT^zqjPr*v_*N^op9!$lF)zS9^5)tfb`k%+S_ywMOh`g9Sd19b5gRt&TQ2 zb=Z@DEa7byV0C_d8|&v$Vk=7CL#qvmOh*}H;i6Gt9mkCVx92p^y^%iRhq*aEK5Du$r(^S16SiH^-*?*&6T`@OyC{X>{rMmNzURYh9s~t4uJlM-7CYR-mM2?F4?`95yOYH zcjHU!rGj~`fO4K4B?g8E*=Z>tOQiV6S4no7G{*B`DW z%}1|fk8!A^W>|6tc(T1xY6a9o{CE;$*-s%VbdjvpNiG6rk)a3oEQCw{nHWK_n-BrS zOAON8$1xY=x&?^R%M6pKFF!tBGyn*7Mkv#40xt`k=!i(oDgk-|YW%D2JISIDL2R=@ z5xY@!T%K%xpGUW<(B=gp?R4#m=bZzK-1~DFA!Kxv`q`>k+-?1hZ>|V_wT3$y?M!%oASm^S~oBItBe_DHfyyDzDDD; z?R>`1Kck5wOmlW>)rpyNad_1rumBTu(>BAqFPnOA|0|*d7OxVO4a}9Etqa6qJnDl! zOhgAb9waP7yT+6NzYN1sI%=Td;~Fx9-d1;mC7pivFX+N4#HN{&rLuUR2p!rtmNejO z{e{?EuU3q>f4g&z%a>XEHa_z382M)fH{~cca83L*O=!yx5X-+);O3so$0Jg=y}P$U z1h!DtI6;wH5iRxpVzZhLBFu#8OHLCCbbw{vNS?T&yoU1f`nIYOiH{X+(1bkum?xXd zzzqv5ocEHiuS2uBSBoi^yEPuPAhO%LvEXFIjyK`rJL;JW0F>5in~xnD5?`Vl+! z*GP3jU! zgkvw2Rc%>Vadoy49)|B%8O_UH7)@l5&j-n?t&aBFD0YhI&7G07r4Wim0$UofSw2K( zsC{NgRXXj07+^=#fbxmjId?(y`OT{*Dw-$L+>!sL{jO7R2{5#l{`AG^2f!%lTSBKR z^l9L5T#d`s?j6`VedcL}K8H4YWY~Bf)_dalFr&}3#8!|eq;;swVYUg8{5Nt5qnwgHd6f*4zA8H z++Th*yOeZD673xPKDI~!XMQX?o*xTOkl<~WEa{rb04b&mIl2tL%rb`_>ZH|37W`11 zv;O1}I$eLjrH@hYo^vxaSooT}tqn&f5_YCL*n77Vm(8}gW!Pjp!hL0>PuGU>w zIX+FfFL!w>Cd&u0V}gkt2Axye=2#3U2g+8nj71iN zMu~iW5==NQYH7Tb&w`^wDvFQV&D$Nd4-zToO8OrH$gpx8HcR$Prhj8+u55pFB=&55 z79}`yd5Mvyn~DA2ZIi)8H!~mKlqoJFv)=sstLM-})aVIekg3QWpaQg-(e;gTIWTk~ z*;7d%@=KN^pxQKdv{bAZC+c;-r)+}dS@UM-jOuKQe-egp)sWZ&fRmVOE`nCiwf%G@ zeT}pC;F5xtmr|`pj;oLerBW3Z-bHRlQ5Cz;WYpsRaD!6OX6Gq4iI!#i9F%5SmYDfv zYHGKP9h1BGmfndygKxb<=012mcJWX1v)JE%@p*JVQzU1+a?aK41f=a5M$Vwvnv<5J zv54jpg~T#Vyy5qC8}p0|fOQNicU(3J?MVnUKDFxUb$RpKEZL3$1BGFbRloW0UQ%qm z+*|)=^D-!W_p_Y=_x{!O>hg(-pVQH;wH9$Fd8-6!#k~%^xwt6|yj;ayC9XErAqPlD zfQ}@s)5>I6gkiCBzhu`L?)>;?n>0F4&Y)W3el5jw%g!V4pB^Kg{cwM87klCO5tL%5 zHj<#^i$tqqtVzC`ec}Fa$iZmB*48Xp)mp!OnBQ$$$o%1^Mclir?}7bK10};n!^*(H zGk*)H{$Yi+M3(^S#{03A$#f#Gx_Lnw0Z@REu)2$AWt z5vzT3@S zO+Ku#Wz>(DtLXPujBhB)69#cKacT*E4;_TpO!>{31s*5q1UacrAb`x-6Jq;Ci3o_+ zBU-QAPcxGg0jcF}mzDMV5^>n(&8l@qy-ty$kgOwAYZqK34P^uh5R-)n9OD+jyd4R$ z?-J?<$ZDaXM8(%wDu>L|Ny#F-T|%w_G0@KP5dDVz=@&Lm96@o;&CT4HW9q7&b|h|m z@R#j{CDjkkxA^2n8YaAYQCBtdv36aZdY8dM*zR)3$AiyjcUktVStr~$7toH0QEwfu znB92e@>OL&J2wf|IiQ0ql`{JsF_ZlMDrzd}(LIv^M5)0^(-RN6PIJN!t(Er1k0$xe zmV`HU-*PqG>*zo2);k?vte^jL$~WUI9ANL@>BusP6{)6Kl~Ki=f%p=v77^Kka2!R2 z8%|W{%&qt&05YKw&*TBD2#e2$c*5L+qMRmS!LbnkwMWIs=+2(UAr&8CdQxI-XUOyJ zM_~gZ#O;)MZ0LA_<@h>^f+5 zY{tWYxN_)7i`Spqq`XZt(ajq?9pM~*S#mp0-o&TI(Dv_=J=O*%Eh73I{ylnohKM!3 zRO)o!n}nmL3O-i^Lqbfr0#3VLokZxtOSkLxr-vww+!OH8Xf>GZnMgh6f$ z38O?VdWMysc#vJys~01jE$yp`JM($5%3kx{CUr{%CjMtZ=d#I5OWr~N+cS@oZGD{t z`<__mJSug%<*Gx`__n8z&PFt^`ts<}w9@S(DX<26&B^)^Kg=A}mh&RVTsb8v+5G+6 z714PjRqyspKG_zV-P-qe-N$778hsCeX z_t0L^5M4DQF87C7?9nZX+;ZaG@V~aewTsC7Ks8%dZiZt|o00m1xV-HSP>HiKTLZVa zKa$@U?I-rUnutSes0P#6mfDPkNYE_*{tmmhIo2G1BCN*Ph&i-{{40&j_LT=0uX*(t zG+YvS+a)y!bkY|gV^$@01;EOpi!I-93v)?Q8wdcpKgKOD6$xkd>Ba5BwGZNeD1 zNS-z@XLn8`Q4z93zm5CwUP9!;-KC+rE>A+%2fl|ifgF|L{HVTosBvpi60G5ibyzCE4RwQY-tiReTILiuKwTAkcT7Jh2G?eej&QX_BSG~0G>o2BW zSk*S!WoOBDlD7Q~6q|X$PbQK)Z4ly0YD*P=g3q+|%HAV4KSb-y`|7V|4!-JlHkY2d z`nNg$?77{Znp44wGF{FRchcNGa_hbc>F|y$Imjmv;ZhM=m8hH;r+>%!-T{EdFh*wU*e;!m# zlXW9;icynu<;Iio+x9h{91-^+bY%tBMv<1E>8q+8*WMu~w%0Qk@h(EOMskGl>S%;L zwK)cf{n z`Z=*QEj8FOW2MIYcAm$FzJ&S}s@0_HIL1o`7py&;1NUKW;D~)t-Rc7}OGtulx+*ki zxC)c(0z4QmOCwNYthC)&6T^h)OY%>(-Y3hC`;Gkkoi8po-s$Y_KUrd%W%bEAqwQ}U zk_Rs3VXQ4(@16Z8-v_@uId;7aKA-t0j+s--d(k6EPCw%yhL2<5Lev8gFxF<7kdKs|yRsQXsjv=|638?*FXBoZrXsgjY}={1Qseb8Fh476zWfrDfXJlyZS(vVCbuG8^p5&bKi3WMkaQK&_E zhnl3c69g%I+C&AY=sf=f9iQ|7$v#=5uPTwsB6M2ih__r)VqAwIlc>8m1zW-L&ND{btW4~jI&!d*H zk}Wf$k0KJ<3$G(|n9@1EkCk1yu!pam7HpD@3Hw&#Gk|lo)1kcAEl3;;pjg5JpP0nJ zVbhW4*tUH*hi86+b5jw@iIUCpQK#Jq+GX+D=~Cr;QANMu%^Ci5wadR(#wG@NPD_eH z8{|TX`1!3d>TVw=4>$d7zdh={!q@U;>KrW{PdktKO@E`d)adG>`uHT6$loA#DhvFkI-iuo86lNAq2UL7&IcaWfRHg{$?=fQje!&o~O7#*Fr8d3Psug~(HktCO zDsoNtY0Vx{TidHI&jx~Q&tt!t@j!7;iuu~4c=NTJp_ux+^nKOaPX^)9rfNYTM?_@| zpx3R`B=-46ow^XJlOdpP>$0a0okfB?VXx6v%If`(d24O(h|Mft;SutMxnwNbH;YW9 z<;&9F;<{n#pd(bm&xi>g zz`}-rE_S~#CWrLc|PBJfa0 zmVt2x8-%z|^&E^^m-6a+=4wh6y98QpqvM&Qp!(#ShFe5-R zp)xx8dlT}a(8bpZPA_lll<3XV@pmS8MS|6W8Z&2T3x3;OKn5C`vx@TmP)Fi z9xLkdZp}K-cp-f*IYVZSb#-RyZH4OX0{lFuZHo?f)=!+YLU&Bs>AmZFbi8sTF^?gp z@m!}VHd@AUyT!#;c`TB@1eKBCHmuU%h5bwZ^0IN5=j2(exn;-MGV1F6%j4?$*4VtO z?vMh*PCf-tcz;cgUW&E`kfZyeSG>a4Rv)XWjB@X<$%_GwOqD6a{az6vSXV#hlofJu zs?Q=b4FIN|I`Bh9Mu>j}u^QCtaP9pgu_Mw*oOi+px!^S@*bCw=79D2Umwrlo-tz{% z8f6s_Hn+akU9=7fGYP2CrpL@qFEecYrK&rcoMDX?hbw%5$Ox(``sSZv=&kXDpK~}> z-)oAU5%H<=hWo^^#k1p-u6`5wSN*n2$8?mDC-0`L29;9ZwTBpX?%kHgpXbOj&Myhs z_MRSAZTzcVDxk1dE*)*LOaw<+hRQ4(tZKxdnXIvOR>QwMfFV`+y{RaD-?m1+DEF9njlY{|2|XfLTBE6g5| z(3crDZY*MWtQh!d#_y;-2y$d-x_Vf+E#4m0$P_7 zOv!!vGHX}KcftDgcR`49A*n{iu6`^62>jQyfFMa#FFR_sZ{I#k-VBPKuI$vsu1U93 z+~c&PQAIyhRjf9N3Uq&Vc>T=<%KJZNn1sH`aLXB7u{OdIe-5whd6sYZ@G{>`c~S0{ zO~T3PGl^|gId-@M5nLlBpPw(O306_sV%N2jafUYsT#Wo?cS?;Eh5GRJ80<7uEdh?_ z``yYE=ImjjCz{`~t)FQRINd#Cp3q{bJH(@UCyC04m4+7EfQMCIx7&?$M&PZ}ZpV#j z1{N<|x1wbfF^NV7M59{>4fSqGWhmYm8V3u@4i^ax?>{AaUmg*TbaDgvuthmryM?2- zi&LAlzoBsRaX&Qifv#I`$5mk-qoW6+@(YXCiv+y+v2>^r&Bnju@`fYgA#iMvX`E{M zYHQ_RZ6>$P?|;paF0j@mVr|XRXAMOs&8xrC3w~n!yK)I+d6l^MP}{B)8IjG@+T0i* z2uO(0L3LhU`L^u<1rGd*&}q>*gQGF=5a>5S0gr>T44K9Q<6*Xv=x4}dO|d)xRX%L2 zP-<#eHrOYdt1lm!|6KGoU<6}g4gO8*T`C!+Am*(noDfU^h6hW$Az)l+F(a_@J-m*U zT4uK=K3YD`@%6>&W~a^H5B;M8O(sr_W;E>N1eGW)hYDIA*ltSfCh^~0x(tU-9l=}2 zxVvw>wtACRrCof*FZMeqMEF4uM3d@teEyW9q$BiAW29k{X^O{`$GCAtp>h}Ju}uqok zpI$Mm%oK^bD2i~e3{*p=BiKP{->SMH!Hc)4ohI+Zrs*O~_0Xh`RSF7U9FE;1^irM( ze|7-ReB7ggWvIB%AjOmr=(qj15HOt}#RePn6R(ns-G{Y37SUUyL3GM1YIY2WSN*m? zH~RF~?Vhdz-R$)HG7!-lV*m=uI+A~b6uX)LBaJ~W&etun{G&p5dE~=8-|8*RQb8akd=C{+>&Y#kctT+qo!?PNbRGnbIx--Rz_rZmuO>X1swP9%sHos{ zNf!2Ig_sitpeFq>sr7_kjo;%_&kgxs_eYCK6Gdo#YX~p2DTz*bYAeXBpbf(FVA*WV z1n)yVLcAN+PC~CfOlEHhJ2fL@o+&dUO=RLXAG>MejUkkiB7Q(S$H=o`UA<<)46I^~ z%MVq!XNIZ3Cws>>>cwjip^K_JE0%1P=Z4FYfb!@np5u>Id1^lQJ~0H6k7KZ`_v^9u zJV;2n_`ev~2L#f2v}^KCAK?ueBR{eC`~nf&t66;h-Qq02Svj38qR+d_PdBKs-xKYx zzlZUs<~Jw4JQ^IO-saXL(;s}h-)zjQ{=eCKa?xHIc(fPvq$v=*$DZCwg7D-zO?k6W zV+dp$x$oNJIdR&O&>plJVe>M^OJW-5?y_u*n+pTp6Te6jTaQY}*u!&B;lftJBV62* z;3clj*~S&vz@&veczRBUY2ApjO0By)DdJ)a>B7!R?}r zFwLX=>`6>yKBAIVNWW1PQ7Q2??Omj=X-Z)YPu($k#`B&DQA11+a$W4>rWEDURPkox z4MlV9`gD3o2zHaq5*3V@6=#LsqS<3YYRowTRcziVr6){eMKVr=eUl8O9faVAi2Z|$ z*LR8X2bvywJ#)+5(@qOD&^WY0!l$SKfha)A0X`NLaC8B!ry3folu+nVHllgub_U+NWsiU|n7 z;4gr7#2q#E+b&gzCFo1zLgSU==WkzC{&DhDDj!aNQ9@yJ=>Mbc&Euh5|NrqBYcwd5 zku2395{62LETtopHQCB;lvd)*q+}V9Qe$Z>qs3AYAxj&^8kz}}8d=Ucwi?ACBFgUj zx}EcWe~!=NbNX~XzxO}C$D?ld+}C|w_jOIn9cGO>l zK%u~Gz6cQlM3}QaUWt&DcOygC)tc9xyMT=V;Wpn4-1_62JvZEp;V=2pemtg^9|TPP zf#neOK_;WKX2fSw7>N32zap~w3S=$oQV-hg79dyyW_!dTVn?UZFu^3(2`t{^5e4`t z*rK1FbA@GLopG52C>epm{OFc*N+41PaW}Z5ZvsaL#J}8W_F!Ghrz;|^Fh|d$@ArcY z^Ve6QWi8Q{EVQ}FFlB>;1l%pFzom&Zeq_JRN z57I+CBEUPR186j&+HI_p?bm|=I>aq$Es_8~HG755ll`us?Mw&dk3USZhcl4?h_=tJ zM&+MW`Uz|x+U`l#!1y^2Q|nwN$kM@M4FB;rSpPM<#d=*O#2f=L(FiOOe?7dT%lPHT z3@{Z(mUVw@k9UBd1?(_R9=Om1U%RU>3)!;dfUF**OMMaQFwVk0SARyQ%4S0OU1%w+ z6amr;AHN)4XxFw)wy-(+D=@Uay}s~s+HdAP`SRxG3Hxm05n2`&%=RF?+Lh6q3`+#S z7N~#_A0EU^$V+^30LWJ9ZxQ?UcL))67N|Q9)JUeRfF&zT|}E{NOJ( zk1!}85uCv64ai=UNJH0}FD!g~E9ZGT>EJ4wSQZX!&{siFo#E7|$J=hmW+tssE5zP- zii9{j!~2ni`0j3gX73cO_Ujw)CICkHfMSnlFfw){HnV9lV10pL3>XHGRU6{#@Ov%9 zunhng?e3eOU~d5&E1+Bc0x>{C_`$RXLfo_$9|60@V(_n7p$2xkgP9_4cffup1fRC= zRo$oKp+Up1A4S791~~V@^w!`~p8=4kOO*It2I3cpfrMBrorMV;;d40%jyR%-Gg{S8 zos+8&)e{on8wPKPLwg}(-A4<=fC+F0+v4-98Rvn+Xc$c17Tq#|Y!I=j`yFUlK0mHN zHehutK3rM{UfWlDYywMxVs_aA9BS$a++e*-S172w{HMEGfBE7M?J#iw?j!~8!W<(N>{v028;7!FA?Kh#OvGt zu;gX%b;JX&Md*c-H##1<_JZqJfxp~DOk3W83yqdi>)wH#dgC(t1^xPD`#W8a4}&ZR zrfK6YU_%2dq^xt-lMZmfeghs2hL4C{(k5q6ZZ?hljsu3C2++toJ_OrMMB^m&EB5+A zrdOlcHoJOhph?g;2yT~PCyDbC2llkRCxKNBzz>vbFvLO#Nbv3f_gzG}={va#z!>ZG zsuv+PT;BZ<49;iIX`Dxvy$=t8aQz`HkP+v`UsWQWnX7$vz(39C>iM$z0B}+syBl?> zC&~Q$fp-^@u;zPeUIeLK{H>AymouBL$LRM@9_Y#UJ}h$m@?E{ld4*?yR|tp;v>$~5 z2UT=81fc^q{W4fhLg-H<=J&Wy0wRSjMP^hI&TnzYvd^n_#`mpLHn{Brn<;P(E#msL zEW#O{zQzJ5az#Ym4FNLK4*+E}viGRJ^$9Vd1rHj%DjjvH!=Hk(I?sYnk5!n*t+_af zGD=v+(XC~pc^7^I7FIA6Szdv}1X+u?$X@(q1k5P?VJw9JWJm<&_!SUvv3D7w1&8g? z_J)EZ?Jd5BzvG z`*DC<$asSFW*#F&ILLe`;*qP}2+SlMpr-tii!i zEE$+3I<6rmyvXwF?Tz@eAs_$;63zS%!;ZTiH-qgje0Na($VnL@^roL-VsBK_@LzOz zP|>dkGoKrcUyiP-X!7qrl%)@Pq=X9M)T7J0GJccdNZpfL=g)^&CV?D0s(jq_F<~BM5~m0QvNdjs+kWT1A!VfVgIC*qp~cibt8PYuBmj05UXSA2fyd6XpjX{HI&9 zdw0iCuSQ@1f^fDlv%fU!2BrMEkQV??MD*jkfRJhc+dtTP5K1FhR>zTOBy7Z!G7B+v z+VQ)d>#&%Y0gy<;-Ww=`R3d&0e+iLxgx?+bjR-+}k-$3O!vQfJ8}gpmZPOz>Mgz&9 z_r>*1-k;()62#ma?VgQ-Q864sY`acixXTnoA_)kA72^w#lnWxB*jsdb*DxWju_p{l zYN_BCwi?)`&J2S({Os#^;J1MAg$VtCzDrZN9-yf`CL&Fw^AZf4g`VJPdXeN0^)$P5GD^g zM4w*8uE<+Qd32>bkT`Qt?pwXc&zpfr<}4`6ArLvlqEOC#fq3eCG5Fj&jkrO8E~f&5 zlPm)j_zEzk0CA9h@g*eA&k*21gu-{KR zH&!?FGngZ-T-!Ut2AO5|r@-5#*#mdWE*H!J_asbmU`zo)4}q-r4`npWkgyMOyU_Rz zc!&@cq2%Rk=S5zC&oBcT+7Obz9*70wj?#C?Xr~QpI}j*_R``CtKmTp>bLT3=k_cv1 zSQj8{E5LKLy!*Vl%}G2VLKUdi4*Tji!rmM4CX-b74ErY#d)jPL)m86qpyzW1XRivR{xLzV^C3ojH6P2^3Ls7rTtJ?gG!C2@5Ejh^tcc`{&m1)O-38{D zuOB71+~k-5yqnS5Zr5Fz6WLY#ABr|Hoz+YPjb3o z^yIt(N41h8ccmszD z-GA*FJ$zUEXU*%wCjn#8!I6kSy95k=|Hu$KsybK#&doJ#lZf&LM__$`HII?#kf<$ zV70-Ect^AU>0o_0exgjAq~!4EZU51MwChKDg4> zPhFKw3`92HeZGED1Y9yJfC%_gJL2dAF0~R4Pk=Ii_hw(2SD(;?udBdS@e(2%2n@H% z_BS^!1(gnXr8y%s7;Do^DgZx$TVQzg1arzy=R#pE3F^f~>c67~HEAXg<`!(!Pxg=1 zjWmY(I5i*ay7BwUwZpep15@A;|E{f#h!5@}tsn>%&IRr$@|i92X$9hm$%WK^A0hH=6 zwt<5fQ1HZ^Yt3=(ebIHsqAyG5I(X&48WKqV5cwfucOfT*2p%E$$*ee>K_Ewj#Q=6k zN4HfR6GHsZz{DL^m>qAPU!QYUH?HZ6=mrnBMNZ%ua9W%(+vcitN)7^(L4*o$$_2{H zMQ0ue8!fJYA?_8}NALq(7ASlGG)6k}O8OkYA!l29Rp&p;f^Bu{`Wtg&^^ zgAU-)f-7L{uKjp$Lk+l{;XmH_v~{gGvXra=DY{z!gKAH3!Z0(Nz@bTYs*{q9rwkq1Xs%OG?^P1y){#hI@|i<8L+k}DPCUm*e|;4_H&m{EDA(| zKq8^Y0{6xU3xY&}?^`99bWkG}nJ^u06d|lbtZOcl%+b?@(FZ|TU*Y@*-z2z(gFG@o z2^j))Ai#u(h$y%{4%e0{?D+`}he=H0b6ZC@tn5`h5lPNPKS zFC!s@&mYQ<(~ltQONbnLNf>-@B?`0Nj!X_r;x<6kywnNo? z-7koRZWRa(yFTs!DnHOff{q0=ktg#(%=m3{fqxCcJD!V#`TVq~xCF5wqNdRYsrRqQ z$`7Fw1iSZ^rh}hI+8{Is17zSL0uM^JipkGaHBun)0Y6*t00%Xr1_amx<2QuArKS7O z`{N+|*#y>_$j<)#$qlB?E#P;7L>qsPu=zfMRU)!SNA&1OfGN;&dhZ54UvSs?Bi=69 zX#i8f>^Z|>h@3OA3Zj&OPx`NKyeCed_=HfV-rIINejnlmuKz*_7SiTQIa?mC^#o12 zK9~|cYQq3nLA1W89lsNMD3Wdd)9PdXz*vp{H8Ux>u6<7B(kHdIc842HVd;2G?ZPu; zJ@^!~Ca0wOy0E`bf?*KEwAnRZ>i~8VbU>;Y&8-1`6&LYHGo@IS88wOI9$t8#1Pc{B)Wz7I@zeXgZMn&}@LxhP^;X za~2z>Nq0apIy`5lFn$>KIwA;~R|M(Cfe$EC)? z336+Ebg{*onO1_csbQ8W^1!_`g7R(guzgDKB>E)W6KL?ja$Bd4g~5YA8wSaCRSn7e z#=qw$37Xqe#d&eUVv&kdF}Fh=?0q*nlB8R|-Yt0m_h);ZIh2}pK#`5lJGv2G87JS2 z{-a?9WxZ$w@jvUcSPbp#pPw);A?kxw{5@5ISsjB<%p4UN;)pAJiWB80N6cAU4s=$R zHKPLd=S>L-THh2F^l))1ROxK**g_B?87VmBhVLFLf|vfIT8pm?6<++e{dZEQ_{f2O zeO~1K2+DWh)!}3>*OK=qA5Gf9u+5##QONy?&{+S<`Tdi1h00w|2XTcdwq8QT2NVOC zvqkVdYsmZJlsdf<>%yl=F%L}XA9cf|{)H5PTqZ%q##9;?MuWrGH6WXDK}iYqmwK%| zUzd6v7YSAPH|+kbK8}{epuD?nInYm8VMn0_>{C<`Urbv3q{#P0s`>we&-%>&&z`9! z?&wYvdR({^y?d=e5#iaE{Je$v_uE$u5BaRYMKTmtY;Jja`>bO;<9}!t z^(!R6DAH4X{(ZKz&(1qm@fv4t$9yQMAspi?4zOJOoDTo)WdCm8|M_IVK&Q9AI_;cb zo)-x#J2r4f!Gh5pe}^Y{BzlTi?D)K2Q}08IiO~&mrTccXyxqv>E)@AP77KxT|Gp>J z?xvnMjl+#QKM>vNX=Nd9yc>GopIH2_YM8kgoqD58CK)YLttRMY(-PqQA$1WM1u!Tf zKl+Q|%<#E!m&-T`umd{KUZ*EE&vAMeA-WXYtutAG%6vm~jXktV` zf8ZHJPb=&%D=IlcThmW5Ds~Wv`rv6f0F_0?=f#2gUlsRz!euCSEe=q-%lc+mvl5dSOmW1|~VQA_&q-Z?KC^8eot{a!alhUmpRk-n)Ct>DwXQH0h7Yg|G;U_(nhTeVacRvcSm*!iA04SO1-+SNG-0NzL@sMO#>N`bq|bvy2wgppH!bTfsaptGSZ-lO6+RJqA+QatXlE#bLQB|*!^cYm-4W_ zDLWIiOQYlo?DGrCS6kl2-es6;Ek{c!NJ?WzdU-DC_Z$i}82!d(J^zUnsvu%UL9+)6 zst=FJv#eO5>n>KMDICIdUHi~x%A@#EZ;HoQj?`q9P`&5M{2q&p-Z9C-+A(Q2{2Ygq z`C2;0YF${%`94!qgOL4Wa*ivGXTEk9SgUnDy?v6a`(npdwwW?>cG_sS=8M2sm zjC7ZR-Qcvf0xgFGc=mQ=`ss+kzA92?Bw z9ggK>#=Ov4o}z9ev}V8mYHo2Kn-zVQSM@i}H$p2mBzWC6Cc`^3ZlmWy+!XQC)Hve^ zzR<+k;SsBwFcp3gZf@Fy5{*k4-ZUk8p{0qFflU_;ON_*yx;oDA(2!>ln%xX7NQEBl zQ@x(w>;t_sYMryz9_rx1$CFY8jGlA-OX|D(2r8wd8h`ml*&go zP^6+}a;AEGWo*D0O6kTd7v23^xcZ3M)p$~AdDSbr`H2LEF~fUfDUZeFea}O0<`p*3 zsXK%ij@-ul>s$dR45mUmn)uCBNY}K>gubzhnod>SPfEeoGmdBG9K@1c^WE2;Wq(l8 zJNsN5m2bRh_Gm*$oV2*8zhqTvPlL9srj`$lxOPhB4lfVpp2b^ngSZz}20<}5oHDe= z+r2s8%(BS$pW9=F!Z%(mTpL6xc5~o=Zsxdlm5FuJULDK0qqE1Kqr@8TGF{uPUvPDI z1S>xu=-OZSy0J-4F^%ws%G&e%cv(@9R<13!LhYPc>iypBNu0vQvZ60Bo$C40wJyrM zTh*A>bpx;TNNMX5Fyl}7>mEw){xy=>3IXHgs!ik-RyCZaAD$7W5dW`!kk)wW+R3a)=AOjRo7md zsbePdK3kltt9EKk>wRpG5W{KomJSzlBa4eE`I1XZ%e<1Tug&(LPxUlbb=i<;eUd`1 zN&Pivw9XH!j>TuZmW?H}k@%SooKO{Ag89OPcO2KzYh7Y?ipn(M$SScIw|5$Cd$qA; zejB;@@pm)(_OSWH)6z_3b)_uGww1LSH`s#yQzfNgVQhzt+NXZ%WOqi~`3{%7^Ny0c6FYe;n_oa|51UjC z=%$UBQ)6-)iwbVA-F>2FyXz@v_cl`tohziGQv|cjn4XQ#2THngU6yCijrHhOy^~Xx zYq$cNGBRb=oELaq)J`^U*pL&pP2UhQ)yi))q#L*>swbf;qSzlch@{487{0nTP?pC- z>L#c?HCk&JcQuk-v2Gi`?3@zXES&ue{}x4d4$>!y#%(|mbEgdbe6Dl-;S&YAIKSP> ze%3e5&Ch{-j|IahC{QZ5%LFB8mf)()_T<`BtRGv@&0dBQDmGnZV#(L^X473=@64EC zTCloHoU1!dw1(6~xEO_MvwQXnN5Uu0D*Q|- zduR1?u8>FMJYB`6ZIu1tHy3@|wG#|MQ}ZBql$=%+`YK!SWanG1f4aZYocewt$o%0V zK~PrRne|JbAXPEu8dp(0QrVQ3zxowdK!LW`#dcY@_T6dAD@iUJcPyJW;?1Blot-k2 z8tS?;FG0O?^XF5RXYkDpQ$|O1k7qn3$+@vfFZ`|;x?!B|GOPw=-jgWD^F@0;V{3iC zWH!u6*#|mRr+h&vTj&oACw((#S;p0Wb2I1dZeA8>WR^vxneE;Q6 z&>SxP@IE#nrYwDjtR8vV7$+UT9-x#@rGMpbR<9zYH_WhErw)7eoKdfG>o&_m2d1bS zXB6%n+M5#x81F4z-}m0W%!8@_mmso7CYvJH4~q)!irI)i$pG)s{vRhn=K#I$Zy_RhfZ~ zmG;Y1)~zXQGn4&QAk-8y)?t0fV>Vy9bKQCmu35%tW92oj=bgl4naq~<>L#v#^~SD||_dz8x>#U3Lr=JU>Zc$wPw(g!npG)T0WS#D(y}pKvdd-IqH2NxN_9oHNC6e)TueR>a zXbN^kV~g9Ct!!zvAO?IKv}?X}U=huROYG7ePEjLuI_7D8ULd%}y%39yp=&C!Miax> z<0w+N^F#Q(r=h5%L1}J>7b)3Wa&nR@U=d!@*qpX?YP@2gBZ!ooxos2Eb@y!4Y$Jr7i@lnFmBRXFes+UN;l>V5c4PLd+ThJQ&#Wb-ZLk04ks#$(D>7ar zA9I6Cytp7)yD{$5>p;s3jT#fM%sn8^t1k8euj}|^J4rpskQ8ith*!ZJ9cZgoiZIiq#JXm?6G3Ek$uQPkHp{DBM4A&4(3(b!^Ol`zq3MN{fUNlR@ytmoExX%xb zK*Vba83bJ18|AxExcKJX3HLw*268%-xDgt}I!5)#Sv@4`Zvkl>q#~jo3=OW+Y%=2B zz|BTz+!g|g4`fASw{GqgUrzv;k%}ou2-e*;n_ZM2B_daBK(=6W6}i72^1Ho*a^ZmF zj6)Gb#6dDjfLsEwHx&SZl$EMQuWW8uYppasLb_HN+xVM|7aED0Z`)jo5cn} zng9*LJviJ2c?igZ^tA}me5u!P=ikBB+hiwBN=T!JwmgFVkr2v9|4az+x~hY#(lYfH z-`zn|>WzDaW7xnCw_g?6G#3@cIhxT`IJo$misQo8o8=RNdg;!z<#qH|a2Dr^NFAl3 z6t>W6`I4|W3fuB0IGDNWHJVO|ft=gCd{eFyd}QwElXH zuLQx}bQ1!}D~<#WNP-3@;Ib}S{yETA@@EVxePF2>-wL;; zBDDZ1!UGVAKt?qr<93=NEzl3i=m!~%y;5%?-&6%BiAF!&y#+cHL2W%~7if+@BO;l? z%TaK}LlOW$t5Jnh#R%KKyGk=#mJL~wR_;RzQAUKu-#)$W&Hw7+viN8MPuPyPvRr?3pkY*-?NJ77V6sAz-oZ&8Lc0^qE zog=@I(dm^_H10T~s$lI2EywCTds<3ZR+%kxXE+`-CXcSceWq@(dchz|29u<@^38+~ zzL`r7b=}_XRYZx2&Gm~(Gs~SGW!5TE`AES|RMNDITU*RFX*Kr^cLq9$8K1Q$7{2!5 zm6`(N!dH0q8R_Xxo!p(>SYF+BZ!C8QX3pnEOZo^EopM5(3bKfhVvB*-0Zi1ZC(=w^ zD_%pVyAwzBI4Ex?3`bTuEbV@C;3L^liuV0Tzw1O7vHRFE*;16SYi8O8^W(QB?nn`f z70_mHANC%NCK){P96H^LQVC27ipJ+(Y^A!ybWr#;Y?`j#-THd^&6T3x<4~Cc2gbHA z8S)45r}g|%t18S4jQd#UmbXrCRX0J!kxH>alOrC1-6omOtHnj>8^qFNhcuk}- z*)G=s-asbDYSj8rbocvP8f0_@(JyNP-fpXHY}F_oJ50RbTr!pX?)zCuO%@lPpINrrjyb>` zV0hoH>D|G%T$Mv6O}Kzi!C#JtKhclD2+Y66Ei4s7^E8xny68KYkGDHtq=X%E_Q_Ap zy&HH!-MHH5LB5WIl`VSwA=cg9`q>9#169AX)`IL89${g|Qi+(!d(S=?$(!LL1^6+p zw%YHrq!LlVYD_G475=Ps)8(74-_L3Zz-u8!N1D0=Dv#7=u?Hp`0kT+t;XzHnbA>%% zG!iWKxl_M0QPw;;5UcVbzjhrBHdcMK{USl)jb4) zOazfs0H|&jf>$iSS4$Jn{P$Vc5M4xU0A`qUfNOFiV6bI_6tS=Y!623Ke@-j_NUCPN zx%UedAlZkV8ttmd0Z4AI#>uMt#r~fY&jar4M3`xPj)1#9M>>PjV(gbS)hbO4m}&(u zZ?*0?I!}%SFq5MIzP1476c2!Jis$z-0tlZI$Kd-r>l!I40m%cgpVzp5+K| zUPlf6Wi5FO;2cwQeNBil7T`Sif%SqVO9XUB;^$uYwIS%%Wga;?g#mPP3h46MYsuqH z77<$IpyVE9Fhbn`ipHC&jf&l5aZ%LG3wNWZY7+cYbz>-mIkaUKLpmb1rbpMr3 zcX_iNL|&dq4KfulJX|Q2nTkgs&0q%EzW?SZ$Zo<`SKqqQNd&;3%j4yGQxW_R7o|yV zuV@t>8`T?^!;%23cla4kU0sz!!fQoSbJvpGiyb#L){VSAg>Lkog8enu+qCqqaSaE`@-ny(Lw=i$qU=z&(FAlNoTtA z1o`J3n44R6$5l7=^R`O&^rD&miH_pf?=@%M(k7Z-QVwg>MtkC_a(iP-jm0#+@n$9} zkbRNRm=j)n>$>JYXo7iFlaL3v8R@_hLY2u+rb>qSh0jGRJ&Ggin_X6h_}`6(`=p+VqJk+-SRpiX!S*x***t_x|tGTnwqmc2y2Wo~}kN6tv*ERD0Lo z?d3nHa31%idYd4{p9njODtRSSie%A`Fvs&O@(+h^@v`1>pTXZ}~jwGT@h?2MLl zrvLW!mv)e<33n6+pYdRYCOvk+)^=gyh$m6j@l(vZ2x5hXq>#dD1HafLjUoZ@UQD6z zKWT=AmRnI&GVzIC~#EAFtJ<}wYT{2X4iajprffvAtmEiK64ct&P5OQkw!C&dQkH=dhh;<1sdxPB@eJ0qzf$@9IjVChHf-paP=Atv+~ zC{(MUwolvU-r#e$)Y^&B9WLY8wIs>7`^Dt*^D$-hcH;g)ZCn3ZjO_wZ!J@_Rw*yt{ zqC4MAGa~u7zU5cF~Z{$J1;4<-@`f|@l^eY zLe*qsofYIotsrPB{sSmH5#SFDOs|tTVM|rtf|vBEIZ@k!K?#mwC4z#`ipE?BN4FE?!CLO(-_Gkjk?#!f|2N1F&}1i&=myh*s0`+ zM&V)yjZlMfYcu|}|DfReD(Gzkc9*|R^XnfCtaVXyUw#+0jA_W5f3H>1e-vBy5F=+I zA7==jSgKA<*niM9(4=ZKmeoUU(XGpO-GJ>g!VAdD-8ov9&6d6yM8)@yIu*pX zlq6UGgE=S#Rfi1<%&c z@mq);92ao4M{UqNGcAP$^FJxt zEi|Kqc`TuQdJscvlEBV8wQqm*h*2H*G{qoEQzTSLkV$OaChl@>W9mOy?=3CHtH;!0 zx>mxV@=@Wue90?oUs-%IH#VWDt?|*F6Yi=!yoIqZ;uITWQ|yN(16p<~Zdc6~^5^u~ zl^MuR>=UvS&f$TrX^T(O#bDcA`_Jc4=;{V!r-$#l?N%i8_>Jskw{02Uy-4<)j~``aDQ-tj1Ljr|jpjj9y|p52+PV2w|PNS*)0_ z>v%@P0U|1%7dmpREbkT~IpF~ltt3bqpv{OrbItj7<^_>=>l|tCfAVLF#(gTemf`wj zO=tCkj4ZQ3qU@<*`u)h_Q)>5A*wgJSXT8ipkNX|VRriuApWxd>xqczXc z)9r@tLGIEY=maL2p={OqbcUCMYEolZYTtjO8}dY~T^=iN7Dnt8pQz@E!jS68YVAh# zc-Z(@rri(!D#%2q9w6QHcDhZPJ0V|apotl4%-{%Euh`TU8*J@s$D{coXpXpXndBg= zGFvAn413rhq$q(;c!JYyE7M{`)s{DOY~bM!939CK8Avygj!nxugyyL@^Q}c-!g>RS z)zqp*33Dw!HxM3}y)u&6H;CYK`kQxcWn4rSe_%D>Go<3z&m$S@RGzvP0zT6UP6z36 zm+d{}kcR+!urp0`dYAZ3$?s+?1_0im0v;m~0EYYre?F?LEpo^J@L~jxPxmv}2$thJ zIhvZ%1%tN-&4%*lm>UU}LqOZ?0)W4q<09ja@FU!tB;7QKZ zb#wFpc-m>U4)ZhEDH?g2gBM9T$pF^Qqn7kmETG)Zd}~>l&m%xNM)zH(>RrHm@xlF> z6On-V#Qh>ZJx+N5UA1h0qn)`9V~T^ov4Ilbm}v`GP1XEAC*t3PO)FX+rB<^L#Ef+p7`eVgZdQ`vr$YH4&(q=ypnE*#eHK2sW?A0LWW3L#jc3ndE{aelH{7 zRy9{{I=w3n!I~{V&(0B$I8Fha>fQp_<{&7};PXhHYQdx{*xBn(?5t1#n7+ye)aDcc zh`DHhIN2BwZ-;aM(`B{zFF7GW71`BC=PC^f#ZUUhHqjqrMGT8stvnX__^Gk4chFg1 zC#S0kkC_dv;aQ|IqOJnI{=WA<#3Y7r`VX{!|_lkQ)MSD~D8vx~t8)#@uPue{FmFE;m?_|aE? zsw15fxo-nW)Pbp}DY|@sMs`hRDh}R{DPg_hWi&9#iLY|0r|=y7_-oU|@6>Kd!-y{} zB$6=um5JJME4JL-d0NqtljIjl4G9^G$MTw>$@`bI+uvhA(<`m%ggb8oc81B{blX;W zO#*`{=#l3xWtEWgWZw?=HS^|TR94;z+z;21k7Gl3tRC7*<>8JcS~p%%9C6#zvXhDb zy~Z_%)uYfqJvwqDohbQ;_4tPylfK%lt1>nxoJuT?sIa9A?NJHrZd(^wlw65YA?%+| zAa)Bbpqv*VL83aSb zgyffMBnjgmE%fPh?)_HO&R4n|tdy!5ugsnK<#WNd__0cDIpXBC=L2ct>gB~D zDEQF^ctA?8YP-u7Ys~p5Y>YYV-YeEh$M(p?3HX_;VfyFsUAZ4HD>+b-WwN|vX-8ZF z^(AA#e=EcQS1!)@7OLT!fqiO~%rrKn>rR<)+r2Ym3lEqt9WR!A@z^D=Fsj&-*j6@m zE?9vn9Kb zuO(&%B`m{YbUS^DcVRJMW_QUGzs!hFv-@9QZW86vUL2mN`s-l%oyOp6PAA3`JKcXB z$*W+)O*!+mznkSWMXC0nyuvW~TT#0U@oiwQVJxg`bg1?3n{jE=u!>FQb-P~(@L~i` z9oAH@=qfan?x$#FFPlCUKX|-E9{VY*r~`lb;_Rv)uBT35^{n@8R73g(ZjIG_m10X9 z&QAf28ei`@ae{Pf3mSsl6WKg_(?s`085A!Wga5wHp8I`nW-|RplH5Mo6f-Bum6V~C z^jw=Si7kpc_9$g1k+CNg4)Pn&m$C&k+vz|2^1s6I&ya>nd z;uo^eu}ELl(8?ce0QY2J>{WiZrqG2tSvk^fpAXm+zZT5-(Y~}@ zoU%S^ckPsm^+t~InE00*1L24f?tBZmuu%-ltI%s^i&@xtDI4WKDy#gX7;j@#p6~Ega0X1ne+F zhH;v+)lp%pW~dCT#~$Xqq+uLCzv?w!P6;s~*e&~qi<}CR;IU0Yn`+j?M$f7~tKQix z>CtQ%p{cEpIhFfVNm`YMut&iiSHdg&qjP9-$ueEfJl&(OBL%!~fx>y|3X+HZRol+6 zXEdHFuxU!@SeW$+*@zIY%vnc_sz=i&HC3}UD0RHX`)ZHb zGGiu8V^Wq=%_a-6wzX-$Ioc*|K{7j7CXG zQ+eI)$gbYzt{N#9%_O4Q`dL3mCkx-Yc*iffdh0a)4e>Bfwnu-*VNH<`D#`IzN)9$q z=R28F6@`3Fd8Ol)-TM+inG5-k{37BK&<5J%%&u#;qWCu#C#W=QzR8!Z^uR;b+gT>^ zty%;l369P|7jB{vM;06ESg(k(qIMn)xNFBtC3(#KZ`pG}5>!LBttmO@8N<6EA372BpLhX3D^ z-5hw!(1Ri9;2Ek%r*@ZiF8C)*RG}*8n3}`aMnKs&Tpid=aSP#K1I)is2YLeB^?j=~ zs{E*Wch51&r}PTtihHEGOPI3F`W)R7*>*9f&&x+Th@#xoQHtKk=0P5G_}s+saBf3; zwd}W~i7?dD`RQ)~b{|f-i_SC#R#V&;g3p!Zj6Km54E|8zZloDnS<%^Y)(Oj7Io4IE zfHmxP9UdsZPepg1^>tiKKLV%twn@JJYq>sAeTM?KJ0;D(A08Cj< z0BPcVwIirILI7#m6F<#m#ykSlQooy(3E<@Ds-36~WXeTjndpKJZve5FW9^$e*y^n_ z)c&G}=s|4Y79v)l$}a`Lu1^#*p#s>4wQnLwBC6oZ1;{@NDRXN*G*06qge0ClHLp3_}Be?T!uo~w$J z{J$p}0%|W`U?tyYbBkY~TmFMT5fn;V0VquXqhIj|WbF(A!B_xvI}5?L?JUpCxW`3O z6H(S#bclaHK=e%{AeQ>wtkr-}J2U{c#Ru?Pivl>?^6?7J*p)E~HepaB<&Uiak)P}V zpm~~r*A^py?_(!GbK&>1`sd#%X#JKkm?Pn$?Bbw0pgZRqXvw&>l}&D0lC)nWQuSaq zTEb;ZHr@rhf~l!IGmuk!sQTEgZLg~*>&l-Qsb;Uz`DM~BvsvL5^@GbExBDZ6Hd`fz zB_rSNEqS_YJcYdLI6P-b(p|oVU_1Mv5)oUa->~vn(Wl|*IViEV8QV1>Q`FCd$i3&y zD4N+qifgIfe_yqwwdO5!?^mVpPRzFmq*W5}Q@89IN=@l4DC;c(6O3(wq?}?S9NNwR zuZEcz`@wg&H{7CH>YyS%oh~du=_=Zi(DdA6zMYsP>5mSOoBm9qM9T6e3`g$=X+-)D z7ixWduXnHJ!U=q%a4D)RHuwyyjj36!@o6e2$SQ5sV85Zkek!l-@jhE^Ua^aAKl=7W zc{gk=s;cUcJvdRp)g6dv zBedByFk-5ly5jS*El4S3=f5V|Ci1BL!e%C?duZTyZYsDJ9kwTja}}qFZ%{i~Mt%fl zCplG>QAJ^jjh%)+Tu(B-aN~rtKQ2<>r=O#XeTrjTC`HKyJd{X*V+S%>2lt~~bEy)3 zi7JsOG4o8;4;Q<`e~6#@?93`YO>LW(>bg%)oWnAC5=!~y;%{kg`_$@qQl%)Ydp<`q zU0w0V3*~A5il_3c_zUYR?{Yu+dqIHE1AKC^220;zC1rPhp@LR1^&I6TSCOf!8&diA zSYO%=I%`f)4{vT9ZL+I#U%9EkL{*;Us`~!RdnQlpCeM@;UlRwpb8BpvD_B4Nq3rHR zig5}g{mzaO(R&h$EDJ@{BW2wgvuR0qbw~4agUlMAsp)nFUzO41-<4|%63Mb5#TCjf z*4F_8r4IYr2G2pK7s`*%&s~y4*}}k*&kv4;IM$VV;79K3jMJxQKL$SClS}b+Tv?bO zTTqY?MqD8}9NzZ#AX)w~a z4V*5DP1pY6B8|4P-A3+T^6J+=ll`omX&AGQ(p6YDFrV9s{V2#ptyII1v$<&c!KYDd z=8}PJ>FBW}Y5(L0tjHk7vS6UXBgQ?5II)?VUl}!}SmC~J0}r-Zw%Lt!&_x2e8Cw>! z3V-vjoo4C#F6~cqW`V~GZif(j9aouFM{3KF*zHUg$A#8}qJ_0%Sgd@^tb5ZN&$5Dq znQLU%AH@?ZWy=#h-QI8_Q!SLWBW#@EE8QII%rh9OY*{UPj&=W8#3fi< zQqEGCrZveiU2~LptJKM3{SPz+_?iNZ6`NJgwidorrKsZfJ@1g-o&N+a9!XvDjlc8x zt+5jNTnybjv+rQ-mK=#wHc(d+Q^LeWTfRhMAv%-^e!vFm#a}`xB}=RFomxh8tjg4^ zeM1uu_Gm#Xx*Vk62p6lJ^REJr$E+E<%R=tA@r=@QQxlbk_5Ev>ju=ZO&ZS8MZ_7Kd zA@YNX)6?#=U?-US(xih~>0 zQXKc%_N(|OV9M{1uHISugZ=)$l_GRTIVce&NZ^KDbdpijtiF+{`Rd-}g8g_}{kH_- zj}~f6KOazUjUuHcW64Di_G2)O^E`H!hx0>koyU!KvqKeZrc^PnH%M=1IS~8zV!wl- zB}uogg;wt^a%pKA*W8_|H*Hkb(mtPUfl9(YvwbM&90^iZN#f9IYxh+ydYJJg-}pN{ zAzLc2Ouj`ZUAz{XljJ@aSL<;(DF?N?%|aF9V8VyLkwaam7P18e#ejMSiNNnDH zJ^huL(QO;sc!z@r`NhL`r=})_?asfBqt>{R1UzOH)AwzXirSvvkNWF>jdzY~<|V@l z{--}#N$->I^x$+)t1Sp&BGM&haTDjJP?lHLm__mt_&VocX;k)+^TEO1C`GMvXY;eb zTgd}?vVxN51`p)xj=k!~MUcm?V6|-D zL(9NL1mUGZTrU3lPyeUM&`#+^|Ff$bmq+VTWZNy*AWmZm{LB<1(IMpzyY}A)mY;aL z=HkPWb2PVWI6|0TmNjpgP`BXz&%o5dIQ44Q@PXMET$HBzmH||NhhEP>2r50mT6Go; zZe3Hf-N{mG$SA$Sl+R>Cl(k-NZt*X|iMSTBMMq60&?8+ou$s1wZ>Tp-c>H!DGD;D+ zL3iFJ0MSn25t`qgcVobUg)=oU!rcSUopafu2~mpd38PKDh%=oAWtk|HM6zO8k-#Nr z@x{iis%2;YVAxW=%}jAZ9CyZpgI8~vFRF(Z|2N}S|Mc|fVg9#Js%t%uwvAQd*tk!q%G|Fgh-`iOOr$WhA)YIoO zW#7(hx?E#+J1ETiGa+Y@aYj%!SfW>2*9Pjb8$6;WllA4@elAN>-b?s1*^B15hpAX8 zRtwD*e%tJQ2ww)gxSPc11^5EANdv1ITiP02rD)dd7J^22ww8#v8|PgaZ%Qw{_H-!I z#_V>dZdHNorW{Tt*~Zb_LrqCDNdik4#7)ow>k%}8PZkv8^E9pj@#J9*g|LPW8xp@7 z5{3RuMQ(*#2+BZ;rJSQ1Fb5QBg!QIk(TYHh^XTzgK@oAAdma}sX-{#87gxRFXX);U zdq@@Ylm&NRz5ZX#iP<)#8}a_s#l@ zG%p@lF-uYYIa;xn2cG>`MmeNfNWHtEorKy~!uh{>e*R2CZV3G4^8!N)INeY}>;HVz zO~h04Up>XDAtK9(3@)VC^Ha(+(@nvl@ut1|+F%3GtR7)OvgV5I%Rp3bDcw!M5hVOA zH))C*r2Wxpl9#RJ!x?ExLPz1+T~vid~h=Usbl#)8}JF$sc!{u%)NxYCr*FJ zWhe=r&~v{t=y3*jW)|D-aNrBLZ{k*Q+T$VilLMz+IcqPeW*w#<3T z83{VRi1N8WRg7SY*ARs~@DZsGtPUW6f~q5Lr4czKjmZG|zH)p1d8bz4|Ht0Dz(bk# z|KoEorqQ4sm61d>6Cwr`jWA-{#%M?f6d6%!Yn_@wR?JYWQZ$ac5y`38P`gW`7!je( zDY8#ZNH#+&q(Tn=>%PaKcH4dSd7jvMd6-k+5ueQFK( z3|gK4mGu{8=I3gc@l6K2oNX*o;{G^zaNx$g^#ChgLIZV<;PUkhQJjRm>d!Lsfs8@-YlaTke*DDPyo)l#VsfWmi~!9CvwvgjdMH*=;afLk=Lh0 zl!TYn%g>zTq;3F}%jQgzvXM7a;m#X)$h7C#6rDXSFGn`?oJd;?QKgZFUwERd_@Ac& zVTPe^EFqQBv^}vLgs=^J22pf0*AHV{fWpdh1DbRFINXw(hLU#)N3`Y-!{WK1Gwn7fY@0sr()Fz@#vOR3m`2Ku9H4j^m(-EmiNF0+NS35R?i_V(j)w zP!V2T{y<4Oa(Q-zAJ(`A?6|3@jKog`pxlybzq8t^H=`iwwnRbvYSWPiL}AP0KvC$! z=(dUIwtGNB1XmHDg{Phee-%s<-v(6H+U#Jz9NPivmMvpcmw?|lIRukuX4+NAD4B)Q zNerM#7##*>ICzK-Ou5LFYx$#y!eW&NXf%uX#SjNq*+) zI_5S5k(sBVnBX#JMp54187W-5_x2SncL3uW3aa8~t*j4^F7c;aw%cmILv(L75Uoa+ zo&n9iF>eX5rp!7aYsx(4Am8qxt@aYIsYbvK0U}pE1_xwP!m?g8Py_5+wlYA60Iq@# z6grc>&RJowS)@55T@?nfAyN=O0#Fi#*}I@c4Vf5c%ph)p_h~yzQ%ZOoaMqZrQEGiM zUrg6Vmau-Hy0u~OvbYtc#^F%btdSn-E&EsAXkNE<@t6(i#+bc?8 z>AaMcynEujOdqa-r94&JaZtIW!ZZ7>3|4`w=B*(uJyfjR{5If=2~XiX)hpE0h&n%% zKuFwx_78rE@o}KDZDO=1aqBFTzYutGyYkb6!XOh$U@j}r)8>;)SIK|&u+j5*O%s@4 zKn4i0DaJ+-+Od$03Rofr%}{n=?sX$afY9R8gH+W!!Atu`rO6<-SL&zQBGc`ud z#CA4X(vb{jn-O@kxGy0ApJcvtr24{ORnlc(T!%daa-2?%5OBp?_|CdJP^EM`U>=Sj zxMHyREXUbzt$?Wk-5ndtab$bBM9&9mA8LWtvkh22ZZ>^O!RN3Lk@zC{*??#joRy?k z%7iz?7O9`O(iWX{OK+Tw^q%q>?B)#)ONnVSj!2Bd(n!~k8U`dVE=*02oqm#c3qTbZ+oy^Aw$`V2oq~`lJs{e2K@Z_d> zUo=L#pIb9X2{bJ|?QhBiUPRTStR6Yw%_OrDM$F{-JAg+D^b7&g<3TnRK<)#ZXw(e0 ziC`x_BpUYOEo{PH$ocbKWPh4cqU)Sy_fFnqU(E$7hYs8)iK+H0^9!gZX$wtKf*n2Og;`DN@aJE%^PwriZpm*V3&r!x!p@NI_J!eWXO8 zM=${zBC{Y_g|PV$c?jv|ZJZ-5Eu=hp)~gUHO!G-zkDPHXj<=VL0vm0{uVGLEJPSBNP_JWqE1wZkhRqx3>bTZ|u_Lk)R@$Rvt1e#?Zfiz<$w*M9WcB zeMjt$>CG~xepjEJ!DnPFcyx(SvtrLv78C~T4+5?bM9JQ;6j0q5m9H6qRXZTzQWzjZ zF_aPD0>ft8kYwqqK*qq7D%KWQ1L3K%ZA(80O9Y6W?Ll0OF9}G19R)=s-rFT0eufXX z18hNi;c%E9Fy7t~AvHz%Rq(=OTXUJ%4p27{XhDa-@4p7VuF*k$JOi)cK8XV)|KOy$ z-23D35K~-@s1UW)GgMWFzb#&t>snOvKwW`H>oPimo^jmYmH7{W5J7iwmc|H9E?Fo) z5OdcGX?EMjzAQ$nr!b?KWqI!VU29t7cE!s2-Z$$aoWj3Z(w!Vaw9=x7-|$c!Ji(U} zE{}304TW_vRCWN@t@#P{FEHp3xDV9Qhc;QVK^bB#zi&2XoV=*IY4>g3vHg{GWxQy>w(Ncm+X+xsJg&PmGlu(7vPn0F^ z;?^%}RR|XvPQ?ow4E@7JHZcq3)Dg4}uw1&m4YT_P9*v2(3(R(K%;XbZU^rZguXO*! z6Pc$4{GL=b$8o~vkrE%r#d1^{(m?D`W%fQt5+lfZSv1Hf)W>F$_>%a-HM%-+I=0M3 zeLS`dg36btprCR`FFwpNruqNBvE^lXWw$MsYe-GuO!iLF6w<5soxd9t_zUtbfKug%YHtS)7=+Hqkf_SL7x2 z)j~pSsNT;e;b0NNF=vK~S#JA)uS{TordYIBi9N8rxgD|RBbp`!$WCDE0%d?!odAiM z$Y8gePdLM!re=V#a4ntju)+`hfk6a1LqwMCkpEIL>jvOzcsn>-w!UkPEbfi_FI1wEaNM6CQ0q{Bz>7xo3!`aAi{Io zyVUFkC)6tRsTlQ7T6_3ojvRlTDwYoDvC^_wN#`1)T37lwAlJ*ZEIsX~P_P1)n$X04 z_!xfPIR%IrA!13(>Chd}fODyr)OZ~8hhEZf4d9y$^m}m|^y^R}6}(YY6&a;w|K460 z?f?jNAIq?)$ES8`9)@HU*b+cgfetS`RwL-l;)w-uC`qe{lruuQ-PY|-IVbv0(AlUtBf;}}HU~%3aRhlYZzB{&)OqvJ0}!lq zm^Qe0Hz9+o%s*TRRE38)e3_E8(B!9+)o+>VEH!UM9i+c^%1I=?vjFdb5^!H&{W$mz z+cqeswgEmBmSucB#{(5Egfz)O+dMgSc85;R?XH}K>yZU(o+yV{Yh7-Yg{`=>gW!dY)Sf<_;6l0^pwgE;s7lm}$Q4R<=y@+&CZeQVpvYFmvX=n!FpBhPc9 zy`PR0Ul3kWfNrrkFXH-y9IbLrLTNISf@W~JG$zVo-H zV2L5txHT=!mcL2C3Irut$2hh8SNCr{%B0%%5ye`qY>^?uw1*!hJA&8bf z2%5bhid$tOm*3p(KNMI)ipxoC^t|mS1nM4+|qRlCU z{nUGV%OfZy`?(;iA7uOZz>ZW04nw!ch(w73i4mp-r>cH8F)I#CTLePJ7M6)ZDJ*m* z^{#Az9hCflu28*0ZW0G5fFUXA#{3on7eH}#RS@_27s(QF%HWL@xq!o|LB6>Ls2#8@3kM8woud zi={q~)I}qftp?1#n%i{$0vlYd_#=WNi257Ylfss5xp z{9go=K!!{Vh{uaQW_&k9>Tu_v zIvkSs0m6%g<2c7gaS$57gBPl zZlO-ULP6Sc5DSXxu(ws=_TRslETfDNKC#CdL#LXvLF6Fp6cSn4pNwfCI&pvvvK|AV zQ{s~xYIyqk62I3Bm>75Ufyu?l091Ley<9ANt6+rLbl<x7z%$>~?59L!)2aY?2m|puQP^w^oX=>{P`?y&iI%qt7I*&JJ$DF3KlO7YaVJ0?HZEQ*-DqScT1A7Rem2 zHCqLit7y&)9yn8fXMUeDnMBx=n-%#R93|sBIj+wt^(xsbh5H@i5fk={Qg1ydujb)S zfbqw)$&o6fSfJr%DnXJ*hHyay%Au&w|$3Nz*U)U9LLIME; zFc^T-14hU1`szA~SCB3sZ@HEpgrKnjtR_8}`eo(}5-&X%@v=kGz|dqd$e>HE8l?AM zLw56QuS<}$Y%cQF$pr5a+tp#17kP4c(2iK4kR<{bw@+^7A&r{|4y7~EEWVu2%j~cV zDb1yX|Ro+@TazcL(+xuV_gQ#&> z3Un%(AG(AZ?hQN%tQvsRaJf(YnW)|<9V*X)rHle-n&I1m6c+5zERlu|Q4-SpJ3)9Y zVG-~ggc4~5#m(}>A`qHOu#8!_I7>^p5Ur8f@21}_T6J+=*&X?vLN9xqHDJv{VZ z2(LicQEIk5Me&}J)NdRY2{!CQVE{F)z4Y4tFMyA_e7!0++w-0-+!i^(khNf*JP;Ng zaKda5>3l#@#o4CM50!bQO$vn`b~Z~784Iz*h`9N}g&qo_`9j4kI%rD5P%fA!h3)+X z0#&bb-VVWm=pb$p3vz?Q1NwhHz^ASLQB(sW1HSzK05+TR0>Bjr*&OI9*QS@@0V+xc$DX(BD-Tow0a|P`4;$gi zi(L-CoH^HeSBkyyuu9=INoeoFE&!N>pAxOe!<+nvA<*R9QBVhJ$)B;cg=xkRzIgWW z9?%$|se<)tW zjC~JZ2qDnl%!nE&;RX*GGFk#JWdo2FXp%zWjx+%ux({ybOJ1Eow5=H@&{sgXVi#n} z2!!?-q~7-5Oz#ezi==tQ<}lS!yejWD=^3=&+u)ZV)23PH@AqPCS`P9z<5o(Y3!Sxw z=I%Eb#xz*@gZJRkLGSdQO##qLTGJLjx(mb`)xTZCK~`ACU2$-=P#*v>Z7AdvB<&Bw z%K$b`q@r{N^~&TvJeAb^vM`{rzQWqL9}cA_bNu=%JL( zNri&%e5i~A^h;h!mVnmT4h``zuy5lu9usO9z9YkCbx;bxQE8AH)B;&j1|Yzj6{$8q z58IPE@ITyoSSu1cELL%cI{Bh>;Qaxv7o`5IpoUOTb9nIdg0GJ=YWug^h(nN|S(F%< zRSD+s-)KM#6v`n$=VD3Cc3Kr!&n5d=47zND3w3)2M?rl@=?iAG0Gpv?RNEuZ4#R&Oi46s6-DC z2eWeC)(R#59zuA+%Pse?i&4J~4}MI`lK8^Se?`)H)iaPLgKTnun;GCwayNYnsaTNp z?<7wkPJ9KWl@a_YoNkX4$@!yZ_cs814i#Sf*6NOJEW7<7F!1)WkAcwt^Bh_1*;|f5 zG;v>dGxsinK+z?~{Kzt%_0q*JM>O#_yqH1AdS>q%OiRbX*zPp1KdQY*LX~x`3U(i^ z_%^y91UfM;T#dU>)37`QVBAbc2dcxBU+1*-yUQyJSB(RU!fG$HN0%qd2xsnbV$@!I z{1p-(YTj-Say(Z-F^BUub>)3!St5-Dy6#8@gOoUK_g87q!PDjZ@0~7>5Ol7B5c;Gh zytpOHjXbq5(tURAC4X^h@;p1;K{Ldm`S+Cb7R?am4;#SIy2%VsYGjlEL8O``s(@tJ zjIdqsjX2#LxM#DArjZIccyLjbbRWU10su#!-q7Kp8}S{xP_t9=slaR}0q$_F1mvO<^a^o?`*OUyO!~jMAZ=wI}&PWWa3+z+n38 zK?s{FXz1|6!t*pc_)52p@Epg7H2o8^=Y@Z(X6CDONNfRKWyV-l5>zHK`*^SZ$(%99 zfkPR4Y=o{vDbE6E;1RtB2mDuZDI^x3LMP6Z6wM|~;F4{rqh)7+;a7#B19Ap+ly`mhw3l5FX(4-J3=k&ECroUi@wIxCYh5hJp*AZIU6B z&4}57IRk8}M)I1fr*;s8X4ocXDFkMf=!|J)Hl|)P1;rXbHO|ocOOOEYMsUzUa$&KJ z)ce`M*5N}v5!D?fhXDKzC=~R$4Wku6c4QM=i9mv2PGYXcJPMiw+@XbvI5kA<8BmgT zGGtGIVmb$^SfZ;ZVhNS!2Y_>=8IVZh^@MwCA!nv(i@TB**rbprE)ic)#T0YBxD*Hw zM{*OI2xOQ5wC;>Nz940S0@Bx#A+GN!`s^hr0f1`drr#RMJ195nC&WBT7Xf|!{#5~_ zcxsgI%(wf~ch7EGF*3@IJbNC#vzp#1%WE@Vt`<%z!~XX54mT6oR?AT`aq=;<5dqAs*o_R=t!&qzc*czH%vSJ_;-pHm&dq&Yv-WQ z|CBDSkA)KJHjs^ZdI>>NatfAy_H+?TsQCl+O?K+>rpye`S(4DRz=VQQ8fAfAqA^AQ zEBD&mIM*Nb(i$mZUVlbX+2pOEa+2dI%=UK!LEd$Z2%hIvS%un45Zjfcp<%cmd?&%Q zbbZmxX54az3Wp;7ffFq$?U20C$~3}v7vH9TE>+~ugzq(EEX^GG$1lQ#sb2!C;WlSm z%qo$4e7o{cwdXYku4OarJcn;jkQX;mYamlz%GrJTMBuK0`$`9qXKC;h+jbD-z1avS z_4Mu--}z8`*(Gz+I``WkJ_L$|jC0cw=D?5P=jlM?=p98SdQ6zTE~6HgnGb&PPf;aKFi&34tl@iCd})GcM)vC1%qsU>B7CNiYELY3LBRmGt)LWL)IBMx4WA z+4p{RW`19P=GZDru-UmgcB8v7maT>hWz8)Mcy8$c^!9MB|r4UgC!G>c6C#+z5vJ zEp!JRg2@92mj>KP0>rU^hu}`7i1}kkN;<@?0D9|!{=o>$1R`mh*2g&&DuKfMIHdyE z@E>q0EWh+o+$&8Jp3(mRli)H8`o;zJ7`;@|@k*Ma>3qE-VW?oHl<7ih^l_ub48(O5 zW_ip8aeaghM$>itW2H>7uNsw^Dv{u;yimE-j8wr2b95=uEKtq&n*F#8k01h&}~na6+kiiN!oj1@9B>PefoacJ5_V3NePq#q`gj<+FS z0cV2FT50&hQn`*C4Nhp{>oar42)L~G4Uy2q;XXG$;B7G6+RO%42yhVKm%*2N^*Z6G3VKPz}yJdG;#xLTqUv7 zIpZJNg^(5Te}=*TFAM|Fk7m=?~9*ODQyy+pTzderw- zx%#3S5Z6ya;>QcevmJ*Bau-2e>uo_1>rVv}XZDBA>`u{< z=q1ViGEv<#x^G-oF0R8Mp$kXOA&5jqut=Fs`@`~bM)%C=z`1wSb4J=@FQJaVSXOwh zf#qL!C5pGcFPIsHds}MQeOBbQGEMk0aiHezIQiZpceH|U-J*6hu|-#G^A#c(E%r!rS;WpCPLh<<+{)2~gowQ|BN6BMpc%RveJ z64+v>3`2zD?EZ@|ew{c8jK7h8jKwFlD?de=r7cJ~DY{?83`(*WN{ySzT}-y><=UDW zqIhFK+5480!*OcfS_3ErUf|JZw@VS~og*AjExH568!TQZCsT&7hjJ2IVuQTCk^=Ee zKSh74Xv2`J3qoOFoEq+vP-dbI1H`#4mrAE_*RQn+?+LzpjXZ^B7Rk z3fFB4q!uL6_|jzc>d9|F;kafXK;Ik|Por;oikSI*h<2m%uM7UM*R6Ff6$U9aiIWCj z7Ua)QduOiH$vXMIce-7YjrXA^_ctbzG%DU6farhV{0V88rURIJB%5r7jUU8`@(pR& zsaVePD-gGZv7*qfgIIL7tpvUWFs~UE+OMfKI_J)~(LaMN_9S^YPnc!|J_p5_(8-2B zkCdEqRW2OKC*V;Zs}f5NDvO;?kxIr;p|Z1KFwd{*uH>iaq_`sgp=eGSptV!^O8_+P zb9_pPm6$4Snzu%M3HLHf4iJmof-0BKk+#<8el`CLlGd>;)gNgmQ~~TVP^1>{&Un&; zXif)Zu&Aha#WD#%1$4~+C}P)DwD!+u#jP&JHLKF0%lSMnGmW ziQiL1t02xj!HeT>4Tw@Eeu9wKe7MrsWWjuZnwG4{EwLg%j|I|(aGq-gsZ4)Hw@GGW z%XBhrpw5JO4FL8Wnzpslowk@|p<8E5t0kI?Zn6Y2G@!>7D52Xzy}=cXJo}BecwrZE zuzlB>hqXde_1GPqbAzcn4m@$+7@~>_}3aEzM(Zi!<9hu`zLe1*Z)aJsM9|Na?Xa!su zW{q@tvjk-crM*BQQ{?ZYy%Nu+p7!m_lR!rdH2($Y$cjBk*9$4FbVA#F{BS==p7!3a zC*J>xIr+N@mt(uuV&BUI!I22b8U)WDWO_jIKD%R!pcu${$=RpZDkRf|4j$QXWLEN? zPth*FfGU*4OC6_X8?18{ z<14?D3ZHj{yGmTug^2XJa$&7+u@3j)R!4iC^2f_!FsCQteI@bv%Cy;J7xn0b9f~96#|(#&$0T^EuUe;ZYk<#+Qz1}^ThdOUtaw3=?kH@963QgZ<0AW6vq zDByHT4z8Iqg@GNGV>M9BR-vyaReefgUaQwF0pf_cp0zl+1jJ@tBM!Oe@Nc6Fh~4^W z4hDn<0&&F^#QEu663|%NAwWB?+wW9@^$w&h)_t>cI(PRcasU8%{GMkI#LNwwW=oL7 zTQtfK1awu1AAdTjRGFr+RJJDts{Q2KGuDdaB|>>t(%jtFHq!0v9zW{-Igke7O~udS zL_s`buJ!qgzqAVFiai8v!*aX&q?FF)xv9z}kL9Y$-^Dbi$Y-ohpAnjtKcFg1jPqj8 z2(DkRGDue_%L2t_A3HDW4T7->>6+o5yGT~*ex6Bh3da1D+~aG+){v`-E}9qg8uSVf z@(*@SV*>Z;9SQQidd+J5+B)rcg2f@HqqUv|Un0n{h=L~lou|S>J$5a7%?wSugY|U8 zA2xf)$d9Wh_7K|;*xuEDiQJ!AjvtE-+UPd15Kec#JhHBpWNl|> z#=Z(?3GZGwM9E^RT%bI&>Y;t>zqK)ZY!qzXe?|uTs(P1RGs3?szh1@RHoO}k##j?~ zcppHr=U+s+l{bf3i=2`MMpdt-X1)CE}KA zI*2Vw7-a|R!QO&dRASE(VEPZh+3{Xh&>BgjZX}X>d~3$k6)*4ak|P0XG|r`$Y#={g~l0$WL;7!1)Ks(9LVs{+;-Zgt7vu?D9d zafSAYC~@KPr+F^uef4if_f5#$m^K?RH#oI|8m%rToGLImKzEjElB`c_x7@bZT`!kP zo3x+4ANn+{b@fn(^Lo<8oo9H39`Aw*gHPIUaU&3K$@JsGj&Yo#J;1(Bo3FE<{Myo# z7_>sW$wEj<&K@tx%Srx>v71ae;!6*@AwN8yb$ci}e^Frv5oNla`kBUCz0+Y8tUDnl5l=iUpK*msM=j+?o{me@3mt$U?lVc6rYx_&-sRz?MNy^lzgEDk<@sL2>=p zz{-DGgiFxMAm=H8D{IwO1h3P7casU!9UnjhOu9>7yS{Wd2=EQ{aEt{OHxeBQY<4Kk3h3rfz~$OdT3Qn< z>g`ZeErx@eu(BM=u6YnoimG)+VY3hxroB*x9zrsGLi4r+2QIC%_2I)T- z?EfAXN<#mZ7zo>Ggc-=uG&F*5Z{@92=W~Mp0O#4C4DZM3lA^ht`Tj2b;I%Bz^o_hD z`9$v}wXHycz!?a45G#jr63}Xuu&2zN$V7EFB`y-8ej=dr0t-C^adR12e}OBzBb#;CP2X10S^fHgo9cf|~n3kJYL zAQE%+lGNc0`qi(jsyYtMT#w|cpl6`@?}LJ^z)N|6QwoAYXIpdpG*&&k@Rcmg{|XhU zaG1LRqu9Z??^~KB^g4iLC*^^JApl{DI4+v8ssMFz@yDse7&th+0^JS?s_8u**x#`8 zz4zt6%d*O5f>2uqJ$iL_%HtWd&2E{@%t?ht9JH`uG%dry`6o?+TO-cq-Se55E8Ejq z;`w}lj#|IMBA@g0(jw6jWUY=VP=x+zpwZu-BD#kYA+F|w|fL3dFvBbiq zKoXEUAfGqRBKVZgaS?7jh>3o>^(5y6pxsyu)d~YT6X>lia=l6-kGt!Uyqo#WLJ`DH zXejzalPp0Y4?N(N|52-~AjKU#;Lm?0)IsSR5eDng|6{_pUSX>LAEHJbnAgAqUdSH> zj^5?~yb(OezYT+HJHvI$7!9WtF+<7^NXePk+ZU+q$tH6h7Q;!pHmOBe_Y50LgK+a} zR-jBpvX0mh-Dic1y0RiQ4=x0~KR`)}dJu&4f^Keb=~tNMrU6iMu^hy3p^ZP`4x`v+ zBE7=T8mgUKLBPn;z{H487T8J|0I3)HT&wJ+D~YFQA(u?wcuO}ER40PdrG5Ia+492a z1oOK`K$R?%WP#EvX0Sw|ozCX~h7ln8guWX9i)vKp2fsJ76=CWdMAR_pTts%r{TQTI3s-~=1<$gs6-21P=^5G>QT90XRxf;gEdC~pMGxA*48 zRd0v;2{+sd0PZ{tNg6V!iGcG#**m&7S;U>VkfYAwXQW=M7|Y+GQ1&i|FWd>8EE$x( z1LAim{|iyf=ZpfjeNgyw#nc*bDua2;fzW&)FumzGBqeThN|zf$`8nuz2%R?p+;B`g zlckdl0uBz=!PVs;mG}UvjwQv`-gW`9_cI}V`1uHo?;63G=1k$BiXp<2JuSQ>k!9x1 zYbdLIR(tAn0Z}~NWV>?N3#r&slym?(rkf}{>yrl8ZPgn|ifLfv>99aS&iAxTf8 zG~yrtB``v$<=4Q(fhG%Nj^zw$((5akafmeyZd^cqCFxus3t??~3X4_aBQ@>7hYx|Q z0FypV?mEr42d>_-D1k<|rZbN1hZy+PuekY7aQQx)7XpAL48%xb{RHmpbY}-xiw2q& zRbpVmN(p=QC;(7Egq1gd_s({BEMHp*zyk1(k-qPnX$mt*vlpSTrN}zSsh$bbXu7=>Htg=_{T^I5+Ei}>(jVF2=>P~<}QUm zLu=isuW6M9heOg1+At7B7LW-+G<&E%RDuB2O@X^= zZ8;2?sqf3LVNk32Czj0n;)L_wUIkg!e|fK7KGXgNMZZJbrU^x;|K-ttdPdlBBH8zE zz2*P%0?}+PEP;?Eg{cNulp868qCQ-*yICd08|gD zqcY1$SiJDZ6+~nN5*efKVQW&l0|}Z>>g9!omg~3j) z_peXj6O3QW4wY_1Mcs9c&Z~TE0Ge6oL>;&``PMQzQ8Sfd6Z`XUF-pMH;)NVlytknL z2UBNRF6~kvu?HboX6EK$Vde3dUB#tISyyBYK3UaejEGDPwqBt2OL*Hn)HqU)1Q5u) zSrWBK>~vf%0uZ3C04&}G`QnqJq-{p{kQ0fHCjpt-M-Ks9y3rke z3$4(k#Lfrm=z?@hP#N2RGU)F#mO&|r_7qw3{f}m&`a7IC$iazL(1yl=iFMr^6hcrR zp;z^%87Yw>MGy@_q(TQuR0Fy#Oiy)e$CUf)&5Nd>(qlGUeFSwp*)qLfoNZ-5#|8__ zb0l@R#<@4tTPqzc#qF@xkNiQW+MK5?b?N8u3$!N=qRxU9m^Z~g4ZGhsJXIn*y=ZAv zik@a_1F~oEcG9!0O&u~aCcBZu;rnJ~&3XD^W)T+M%^g_Tp~z-E$5p!g^NOBr`9amp zEYs1=6s(nheXV+5M%No1*+?4EIBNg-B1fLDU@wl~gjCcJdaEU-EH>jgoKSY{70PRv z9@H^)%ac0k)`&m96c36pd+$1wR<|=zwBV#brH*td=WRbeMk2yZC=K@$%KEQ4RC!+A z&KqnQ4|7e>@;E(tI*u79H6IyaUERO4?rIJiNj>_rsmkujFhtvrRSoC3*3NZYj%wmA zq7C4S_P&2l1)qGNt4LF{k#y*AuF3`)5;goliuSUpl5JtCU4h$LrzYj@Su`BC@2zGE zR{a%bf$nii1y`3+g;rgjcC{

A(&`;r28B&2;8uP_}Hr-CCuNlBVjr`!d7*t^KKD zkJB$4Y_dl4U(olJD2i<{qjKUv^-r^u?k7#&tVUd{-CW*qWMN=YHaSl}(OGIe#(hzD zn$caP@Ma0S_}i$e!n?7k(EKEWq1=GGvSqQ)*^hUa71S*%FIjY1D}U1F~QJ;{TE{p7GFq9brcgTmPo~L_Srt!*+RW0+;}lJBLG$X zc7*hO(;Y$rb?8jE(Ag0ksFQ|`MyP$Eq2zEBU6wbx>&5l1T}n^wEpidZg{H;*vK+5n z(liC%wEFIbdw8?982n&tAvP-PRDUul;N6q))HbTPLx=VWzCuo%=W~W*eLORDt7mCm zWbu9FJ6kRXS-phQw~wTFTPr! z(dEi*yO(*}>AQn3RgY6pjB_i+zM*);v7>quPS_({GM# zR_ZdO#h=2*?zq;izOzXQnUbY6VYD!`i}wTK?XtpPlEdWryh++8ufpAO^r*QxjBdy9 z)q6^sDrAHyG{r1}aJ7&||FYKFQ75pyc|a^YERX-JW1gFT6(*#RLiddoqR&)$BhEGH z4Xw7k5klK9G;%i}zPvNCP-sciXmgVtZd;{U;_KkGtZ*u>JT?sx5c!#AyK*|-oU422 z@K#Z^HkC*f9SV@@GNPQ5X8kxUHEeiR_~|LGbK|M|C&V|*8k86vm(CP6$G5FS>~9Q< z3RF_l8tO6i`I;RSbU+_L>)QINl$6cLk5=7M<=gOMcZY>PrCIY}ERtQX6)8Ngf;P^R zla?xaUF(Mux7RekmO3vJCk~Ku-YCtr-lc?a%WVrFxIU$yL<=g^89If!ehOu=Bd-3g z7gM6oC3|#7`4Ov&Hp?9IMq&_rPKYo?$Jyaqp@Ls|x9}dq1sQX}$g1m_qi>mmEXqu; z!C;K0lUrvg62?~7>zMIvhhD~w6suGO6c9taIv-s+rX)Q6M9#v9Wg0U-J}G1eV(G=Y z!N*umd*32~M_kQ8q^re-80Vn-+dVs+6uQa^S6Dd-2!kDRxvEJaE3fq555-tfJrvve z6~dwkfJrUriOAD7MC4&PzwL@tz@)Cd^sux^c@oBF1SkEEt`IiA;%B!$|NV6ZD_yd| zgb`Z$lluKz;!2TSV|x)*w681K1FDIt;#Xmm3VGL*pC)gFXn7taIAtkSC~_#P)DTG4 z(va>3FJi+yVdNNwL6I@gUNp+7mHWZ8skkd)uRuX+z1$0Q^aa~}12J;?-k1~J=VGH$ zD1^N{qXW2ToWJ7zi>Ag@#765oX-aiy{rN9r5#I%e3lnsQ7|Ubv4NEY0TuVd4wW@4M z<7}aasTUKYR^0Ig*W?+8X4_k3!W9%RExTtcryhh@mRp+=Y}eIe;6g-4v(}KZdPDt? zNPNSO7^Cc6WvynfX_eKUSG(2LWXV~uZq%ySqR4%vIf(wO(Crzg)NouHVvBIWkH||D zVxGn!E}^^GF0ELOs*^YTQ1gc6M9YX0aX8hoM|*9Y8M2IeYtPs*ag@{q@@t~fBm5C( zrfcZ|!tr6D`;J(KmSm=J+t9IL}+nxoLN=+$hL=pYCr9c^@n%_J={>^-uXT2@X+}?yN6&1wIZdI+X9#sWlQ|*DY3N}>2VTC`b_qqC z7nPc2uG)M_X!v7~ap}J8k&Bb~EMyWRIk5Wf0fe*YY;?Vf;Jc*-M%v1~by=AS<9iS4 zhc}(gKhzRa{*sBxyt_nZxv9#~FGJPb^H@*(oM-4iR zcZ&NS&rFTJU{7$$KBmB+pf3-x*lC9SXY-^zREZAoDfrG#&i9;vd@kjVCh_@H!!BQE5g z1(@+bHqu}*3-P4?Q1s0}Hg;rO#CoDT*m0g**We^d!k#g=Sfq{9TSt5_dc^E<3rRfXy31!eH?Y4UQ$ifW;60o z;!ETK;z)D%$cyo1_TpQQ4VGk{f7gxoFT(})q*5drusij^p_ccfyoWd$|96((Nc{YbYFRD$6Ve{UhzN7pYnmqmLK*H$K5mbBhAW*=_f zLF64*!O->0V4EnLW@O5#aANglm$gWYvy?Sj#St4B8oXP7&*jM$9&u%^Qp?Fy(*(6N zZ@+F~W%t?b+!h`qt1I6|wCDWbkn+BYj{7?wp5hrVa7Lq}I@YqVKQ=j2KAAvY~`kM|l8ub{7n>S{quEMe(*5#^sY4}FR5AIp8zNheU&H>ftZOhLt zu5M1-M~zkRZcB~lCK;fuktIpHE?cjvD@74)7nn2<_>Nh39?J6G?%&P)MqE6qz?+Xq=!)Dfgp8I&y>n23-S4!jirW8#P-m1AcHeT9GW2~@N-Mo7> zvN>1P&7h?8K=4 zJcP+(@scBQ71H=Ls?@#_2dxh)s^zQeD8Q6MmWN z$f&%9=f}vmB))ld>V9;V)MMV`zCsZ}C}lQ83yH;C%GNqB>E ze7Du*vE@YmDR%~H$+vbSaC=kpHtye6G>ne?n%spVE-~Pa3}1LL-#6TN z@BvnV)u7AE!z)#&BP%vi?!3#Qs>vj(nd$Iq9lK6shivpi3eU$=6}2e!nt?~KcfQPx zQLdU;+=mq5rS+vZ__Q8G57le77e71TtnQ=h5Mb1cz;DwWRBgWKYwo$TWm2GLbe^iG zHp2CZLGzCJ^{imTBbFzRNRKjQ%o}1E=5P?c!eHCr_`BVTOxc!Gfkz)Xm#TySgeNQ#E6&%`{W(*JGi|siKqt#7wZccY~o}ZxiE-NhHayM&L zB|~M&ZfwP(r_3O>VHRDBRgVNYq7AeN6k<*dJw0S&Nz!r4UAC zcRHMU1ck!jZ9{2yReZBhV%nJ|WGmH3nT36)bT&uKO`8nLVGx7~FD7k%HbD7L#hbO; zgm^t$A{&8T;!Kg^nU9vLv6XHaD~?n@Gtjxd^owT1r(aEUm!~v_Mc7KAcZVf*P9DI9 z7=HGk_iE_)XxF0&@leES*`ctD9KqqA_3+1?k`UFdD|&=J>t(MT>&D)l*RB_Vw2LrT zkjfZyi>olB9oWMbt1K~3U50$EG>Z6SrEGtNh6lF+OC(;r$*FQ{zIwY<&087WU;l!R zSP+0v8a+yHMjY;1WEvS>B-rOrU0ss1xVyPZTkiI!RYt)Zm~uA`kNQ5|L4I#I*5U2L#R{~Hg-^L@%E-|z#QfAe4~5rz z3sch(T;n`s)L91w?)TCdlfBB=J(n()6_A^Q1g<`t5pRL1tDLq-bCceeSv$KLyyAVU zOr+Zbo=FQ=j;{W)@ij8Y-8A#)<8D(OtoJ`$s+TwvtbBJY7>&0dejPBbnsYlW?>PBH zE+%|X#i>A!sAyfFzn9%CGlht39)74%7HDqY}58X|g>N>8IgyigRiP$9wA!1gjE;#GV{qBZ4uF&&xSvn^|fzIA+!qYw| zWyBAv56ss>R(>U4yY^~Yfw5aoeO>6mdG5b(iS8aO_v@QGbWpEG!v}{e3XcSp(ZUd~ z{WZ%Ut|2ngN-@1ROF}m8QeAe#Mo=mCiE=$AH)@e3qT8IoEq<<9J|VZ`HYM_C^C4!w zVtJ9Hj%DP#OP_R4^>Ab9b9ruo#N{5shwr&P%_aa4WfYgmipo zxQcs*cynf|jaW$Yz*rz2?jUII+B$+42op5V;Hq33j=3ay1%CN1M6Kb75wS_kRgH_1 zlIqbZa2K2G?r{yvGw}cH`RM_>25HL80vVl@W*(w&==N~4l>EaQAI-w6-})h5i(lbI zkC*g5*+!`wug?PtAt}umvCQ-0xmu44kqr)qG=kB`nfbd&d)nsV5rap3djk4SU5xTp zwD4cw`^=3%b;C!RyY(#Cx-rrQu{8{da9QlUcy(C2Q0w&bO+Dpzbqky+(xrON%2{Sv z*iFvemu&{xJTlel6yltfC!)>*rDGN`v`dO*wu{h16glNLRMS)!iW9A^c(Pq;Sn-Kc z{RCnX3)|QGX4z=i@`osd@o4GVn@ZYj_A+~vcd3eJ zQd#d&QTR9v2GASR@WKccyn_7a{HrBSo{mmJ zVU}h7*!1m44=xbhm2aCp2fZsAxOaeK9-HVGB2Ma(x9JdFos$XM`BVZ8T*0 zZ%4E5u8B^0Aa0Xl_M|?JUF=Hr@^|~;?JzQHRXmPv)65Nayz?l}b>t2s12?)wtouz* zp_4TARs^?juYS-@G`Dad!I|ukRH`uav#wxG>#7Qp)R)B`h<|wgEFBWv*&0-3TKf5R za?g2gp`-SNt|P|_9$n%{Q|>Dq`64>e9P4Tn$6KibEy4 z!+bnUIh(!AsY!hH8;k?O{V1l;qaxR(fu)Rf$_Sz#{Yw7`uq3@vQ%CfPJRCD+QlE^o zrX<>(Uuq^C$&-8ewwY!r=W}GIYtdHm5n{#h^|({00p!oUvO`}#PiHU73%6c?&5@xw zrFTE|L?cX=t5wR4Ng}OMZLwDN=Y4$uMp5y?c+_nUdABX$kJC6J!RReCy!R z<-M%8b#I{8GRj@Z3L1K;Qefq+y4bZe`?Bx#bY#`=^LwA`2RZV%$5$ak5M3%RU2=?e zb6bk>vNW1;*JNASlTkXeZ1@}#fUz~h0PdK4`vGm{) zY&XT2(s16*DT=0WUoT?$h}9P~@A?oqzETI3AXN3yK_qR~Xtz{XOmt1X(c;oIQE*8h zZG2;>OpEfwusXWt)!1_zM1>o^)Mu@-l4Zl9aKYN64GEb>^=B&=cN@PR3R=a*#qCi0@eXy* zw`}C#RMx0<56#J+nHLhwz2U9rzg_5+pjfVbB0?L_Gt&(G{z#y>JW)%!=|K+gtUh;O zdnN9!VO;5Iqgt<*I{v9c+B`*?+QR+aHgDp@hez4MrKp0N-!{v4DT=l=a4<&KvxAPv zpD|@d$8|>RHM;ZVm~6Omom;z7o}kue~&iAIZl!yRKP-8{}CSs)BNsKz9^} zW!TamE;WAhpc1CzAA2J=ZVz-0QdtfN@Ke+A{ks@kmtZ0mzw=>YXtGPeErs+)@%(og zL+4teGumTic^52XDfwLWfSU?xm{##PXW3@!L~V^D^TtkH$L|1mF|W%`Z#USSK9B19 zhZ8zxFUn8(IQxFU)owrHjyO-Qa@N!D3sU@+$mWm%^HoLRW<=FDROM{()oq^jzqIxs zmZe0a6;&)BdoT<)^;KWJl7NvNenJnJ+EZ*W7N8pFa%XSaIsC+iX0h9iQF7zg!&@ld zmW5ZMLicTvKNX|(jd>oMwLl9mAfDZ@eH&yKb+dp|;q5rKl%lIo!Jks(ESK$AQ znEu6$+OT!a1@#)>q~yDILqrC7n35`+=z>Sj2?1$3nHA}G29C_5l>A^e)VBzkX4)Uz z!^UnpI4&~Vr56$bj?y*b>S(Q6pb@FuuZwI)#z?uIlCs9=I@59|y0UbWywVwsMzP`! z!-YLO|9IcJtfB08-8vh()vc-Xg6t7b4`+obcU9eF2VC!L$?u`a7P|I_)h^eKA>){F zR&3$C`G&PR_Tq&3-=0A{Y4h;Mm0*VM1pHVXtXo)R+=guKfBS|=rfgX9|J8OSZcX0V z`uh?{goLFak`OSlj3A4U5Jyr#2%>-nl!7CnB@&j3y|oZx*bx$8;vh>X#Re)faxQ@a#+fE0X01N)nyTaoUuc zngX?544iAdHd`kHjcu1)#qIZY+*qiQAT#x5(jWdl0oecI@_uTj>2zADQD}vEA=4?& zHafA{aSKqb!{jNEQo!bsq(f)JSyl_`FHACG;iOHlV6YHoteo@brSsEjdem)ocIfW7 zopZwMcuzib=?uG}m)&KKQ}ZaOn^YGK_izLmO2W~C^Gj^T>cfPyo_kisZ`WDmjn9Q0 z3X#of&PKKJ>_@{E-;tYcIUg6MF$3#4ixCE{{Q@ zZI!56iLL9LsRgAU+eo_WCb?}2lLlUl`~0RBvC8^JlH#X6xmBH7<$!A6E%}KK&yHkz zY=1!SSVt%p~85W_5w)3(Ee(t(r>3g$NfEsfhksH#`sXTW*@pe?gij{^JJ>{M9DSPW@ zP4_vEbdnBX;>Uh3{a*J9l(2@NIxZXW>aiKI-E92>Z09h1 z8;z9@;x`+SewRbFN^q^fFI~+{`IJNbLgZh>wbJ&tOwE2iuC_LjbZ1$^_}_nd7Bre+ z4&k)oFvHah3-5^3s+Z` z38XEF!FT30{_>JPf@z~*JT065{(abm^kN(pLg@wZ2kgU zI|ow7f>8r^`mC} zSPw>k*GAWGI<2BC?NoT>ScV+T-uMz;1fM+|M^E8u1Z4onTXE@5H5`D=?tfl z-k!N=yN@?pq!l}zo_eo%1HWQ|*;nM*}9(Qi_ zj_MQ9V4tPy))U%|HlX@<`|XHCE!FPl%#~m#%eMm(AziwpytOxo*Zb6@aggUUl zRgCZtGWucTZD55{lCX3K^V}$0HIXacKa5#cMA(NHQu`5NVlui0iC&S}E>&x|uCd%r z3DPCG+^TkSbs7mvIi-nhmHFM$it#o}ZPZjlpRX0kA!6=f)QXsTixI!3Y=tBF$}28q zhkZKUcL6=h^bZgRb^soS2!;vkI+?CuFEbeaI^Kgnhqnr6MFy&2pHeGiDs1U=V)~$+65d-YUa1(!qhp+LEoN zLr-;FmK_i|cBkex*^xlLvk|h;baI623m6ON&2x@bKr5OeRP#@yD2Ez`%bq4l}>CCIN?@OxNuO!bg7wAQO51p#c4{bLVYk z=s13snPTw_{P~{_lSn6M|Fmv4e^w_I5g2)Q24@^(PKwUBOx}R94whs%m{RYy2J;XI zV_-L((qV$As~e?!40bvdACoZP&$?%dLXZBK<ZW<1^qvB2(q6#jU32>q`pwsOX>5lH?-QkW;o*3=sF3kg|OM)V~RU`&dL zR+WDUB^V#IBboy=0ArYlOyjq0om6sKgq?g^x{{R8H+9cUm0yz1UE;&BaQm*82f&Tw zs%6UWXVcD9AVGNf%|G%2uRTC2-k_fQoazvSf_g&o$`<}U{Uh!>I;}o2oh=P=0P>9((l+z+Y!5Stq0#1nFu}!FL%hKC!vKwIL;sI=JAi6` zsKYi~AJ&GMu9fK&m}YsBbZXW-*r#;);YPw;SBAHZUt>BE3doS_<6!=uPu{ii9`aI+ zZYRtLEZ3Ryg!f~ZdGICw)M&t#w1!h}wth!NneDZJzJ8S0WrPrWMV=$K>DG|3dNCS# z-gaWFG3vWBr3*Zt2xB}(54;;EX^z3J#Owtk{1^WRzt0~7cQLzkt5cV71;;|%V1`TF_|eZoAe5kU2-SPbcrkO0>d#2LDO$KGq6&6` zptT5*vVR0fA~}#ebK=+LC#NG~&3Hz=8vg3Al7er9KANOnoRd-7VAN;h^Y=ZE^nZrK znj{&G5VJ1`seAU`J6W%&3i1^ZkwJUB<-ds=qfg|t5amp!(Lw#yu?tnYZn5V{8aD&m z4*Z!Kp-$?O3qfv(pkihh-ZlS|Tr1PV7f?SemUL8n;TV9yY@FycGPPtAJi}Gh8I>uL^JUD7zeQM6%5UHlB9AWkHqn{U(+;^umlpM^DfbkU z=JJm9azRA`f9P~_P~P}MZ3iV;HRs0lI|UL6u&PC*DBEuBIv(1F8#fcd=w$&E5Em_8 ziIa!k?+*Jn;(V;Oyv{B~avs}eSn~#ST^|7F?TFnN^Mjf;+wr=^(jLLx`FD=8{q$i_ z<{Lg Date: Thu, 29 Aug 2024 15:50:54 +0100 Subject: [PATCH 7/9] [cuboid_inertial_parameters.m] Added copyright. --- .../cuboid_inertial_parameters.m | 29 +++++++++++++++---- 1 file changed, 24 insertions(+), 5 deletions(-) diff --git a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m index c8e360f..5e0d0d7 100644 --- a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m +++ b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m @@ -1,14 +1,33 @@ -%% Example of geting the inertial parameters of a cuboid on CoppeliaSim -% Frederico Fernandes Afonso Silva - Jan/2024 -% Last modification: Feb/2024 - % Example of geting the inertial parameters of a cuboid on CoppeliaSim. % % Usage: % 1) Open scene "cuboid_inertial_parameters.ttt" on V-REP. -% Available at: https://osf.io/jeut7 +% Available at: https://osf.io/9gy7e % 2) Run this file. +% (C) Copyright 2011-2024 DQ Robotics Developers +% +% This file is part of DQ Robotics. +% +% DQ Robotics is free software: you can redistribute it and/or modify +% it under the terms of the GNU Lesser General Public License as published by +% the Free Software Foundation, either version 3 of the License, or +% (at your option) any later version. +% +% DQ Robotics is distributed in the hope that it will be useful, +% but WITHOUT ANY WARRANTY; without even the implied warranty of +% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +% GNU Lesser General Public License for more details. +% +% You should have received a copy of the GNU Lesser General Public License +% along with DQ Robotics. If not, see . +% +% DQ Robotics website: dqrobotics.github.io +% +% Contributors to this file: +% 1. Frederico Fernandes Afonso Silva (frederico.silva@ieee.org) +% - Responsible for the original implementation. + close all clear class clear all %#ok From 6b59193ac0f5ac8905612ceb0df7a5a568e2a042 Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Fri, 11 Oct 2024 13:19:14 +0100 Subject: [PATCH 8/9] [DQRoboticsApiCommandServer.lua] Removed the proposed 'DQRoboticsApiCommandServer.lua'. It will be added in a different pull request to 'dqrobotics/cpp-examples'. --- vrep/DQRoboticsApiCommandServer.lua | 228 ---------------------------- 1 file changed, 228 deletions(-) delete mode 100644 vrep/DQRoboticsApiCommandServer.lua diff --git a/vrep/DQRoboticsApiCommandServer.lua b/vrep/DQRoboticsApiCommandServer.lua deleted file mode 100644 index 7fbe2f9..0000000 --- a/vrep/DQRoboticsApiCommandServer.lua +++ /dev/null @@ -1,228 +0,0 @@ --- (C) Copyright 2011-2024 DQ Robotics Developers --- --- This file is part of DQ Robotics. --- --- DQ Robotics is free software: you can redistribute it and/or modify --- it under the terms of the GNU Lesser General Public License as published by --- the Free Software Foundation, either version 3 of the License, or --- (at your option) any later version. --- --- DQ Robotics is distributed in the hope that it will be useful, --- but WITHOUT ANY WARRANTY; without even the implied warranty of --- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the --- GNU Lesser General Public License for more details. --- --- You should have received a copy of the GNU Lesser General Public License --- along with DQ Robotics. If not, see . --- --- DQ Robotics website: dqrobotics.github.io - ---Contributors: --- Juan Jose Quiroz Omana - juanjqo@g.ecc.u-tokyo.ac.jp --- - Responsible for the original implementation. --- --- Frederico Fernandes Afonso Silva - frederico.silva@ieee.org --- - Generalized functions get_center_of_mass() and get_inertia() to allow arbitrary --- reference frames. --- - Removed unnused inputs (e.g., inFloats, inStrings, and inBuffer) from functions --- get_mass(), get_center_of_mass(), and get_inertia(). Also renamed some of their --- variables and added comments to make them clearer. - - - ----------------------------------------------------------------------------------- ---/** --- * @brief This function is used to test the DQ_VrepInterface::call_script_function. --- * @param inInts. The integer value of the handle. Example: [1] --- * @param inFloats. The float input value. Example: [2.0,3.4] --- * @param inStrings. The string input value. Example: ['DQ_Robotics'] --- * @param inBuffer. The buffer input value. Example: [] --- * @returns inInts --- * @returns inFloats --- * @returns inStrings --- * @returns Empty -function test_inputs(inInts,inFloats,inStrings,inBuffer) - print('----------------') - print('test_inputs') - print(inInts) - print(inFloats) - print(inStrings) - print('----------------') - - return inInts, inFloats, inStrings, '' -end ----------------------------------------------------------------------------------- - - ----------------------------------------------------------------------------------- ---/** --- * @brief Returns the center of mass of an object. --- * @param inInts. The integer value of the object's handle. Optionally, the --- handle of the desired reference frame 'df' (the detault is the shape's --- reference frame 'sf'). Example: [1] or [1, 2] --- * @param inFloats. The float input value. Example: {} --- * @param inStrings. The name of the desired reference frame. Example: {"absolute_frame"} or {} --- * @returns the vector of the object's center of mass -function get_center_of_mass(inInts, inFloats, inStrings) - if #inInts==1 then - -- Retrieves the center of mass in 'sf' - _, H_com_sf = sim.getShapeInertia(inInts[1]) - - if inStrings[1] == 'absolute_frame' then - -- Retrieves the homogeneous transformation matrix between 'sf' and 'absolute_frame' - H_sf_0 = sim.getObjectMatrix(inInts[1], -1) - - -- Expresses the center of mass in 'absolute_frame' - H_com_0 = sim.multiplyMatrices(H_sf_0, H_com_sf) - - return {}, {H_com_0[4], H_com_0[8],H_com_0[12]}, {}, '' - else - return {}, {H_com_sf[4], H_com_sf[8],H_com_sf[12]}, {}, '' - end - elseif #inInts==2 then - -- Retrieves the center of mass in 'sf' - _, H_com_sf = sim.getShapeInertia(inInts[1]) - - -- Retrieves the homogeneous transformation matrix between 'sf' and 'df' - H_sf_df = sim.getObjectMatrix(inInts[1], inInts[2]) - - -- Expresses the center of mass in 'df' - H_com_df = sim.multiplyMatrices(H_sf_df, H_com_sf) - - return {}, {H_com_df[4], H_com_df[8], H_com_df[12]}, {}, '' - end -end ----------------------------------------------------------------------------------- - - ----------------------------------------------------------------------------------- ---/** --- * @brief Returns the mass an object. --- * @param inInts. The integer value of the object's handle. Example: [1] --- * @returns the object's mass -function get_mass(inInts) - if #inInts>=1 then - mass = sim.getShapeMass(inInts[1]) - - return {}, {mass}, {}, '' - end -end ----------------------------------------------------------------------------------- - - ----------------------------------------------------------------------------------- ---/** --- * @brief Returns the inertia tensor of an object. --- * @param inInts. The integer value of the object's handle. Optionally, the --- handle of the desired reference frame 'df' (the detault is the shape's --- reference frame 'sf'). Example: [1] or [1, 2] --- * @returns the inertia tensor of the object -function get_inertia(inInts, inFloats, inStrings) - if #inInts==1 then - -- Retrieves the inertia tensor in 'sf' - I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) - - if inStrings[1] == 'absolute_frame' then - -- Retrieves the homogeneous transformation matrix between 'sf' and 'absolute_frame' - H_sf_0 = sim.getObjectMatrix(inInts[1], -1) - - -- Expresses the center of mass in 'absolute_frame' - H_com_0 = sim.multiplyMatrices(H_sf_0, H_com_sf) - - -- Formats I_sf for LUA matrix multiplication - I_lua = {{I_sf[1],I_sf[2],I_sf[3]}, - {I_sf[4],I_sf[5],I_sf[6]}, - {I_sf[7],I_sf[8],I_sf[9]}} - - -- Retrieves the rotation matrix from H_com_0 - R_com_0 = {{H_com_0[1],H_com_0[2], H_com_0[3]}, - {H_com_0[5],H_com_0[6], H_com_0[7]}, - {H_com_0[9],H_com_0[10],H_com_0[11]}} - - -- Expresses the inertia tensor in 'absolute_frame' (R*I*R^T) - I_0_lua = mat_mult(mat_mult(R_com_0, I_lua), transpose(R_com_0)) - - -- Formats I_0_lua for proper return (as a 1x9 vector) - I_0 = {I_0_lua[1][1], I_0_lua[1][2], I_0_lua[1][3], - I_0_lua[2][1], I_0_lua[2][2], I_0_lua[2][3], - I_0_lua[3][1], I_0_lua[3][2], I_0_lua[3][3]} - - return {}, I_0, {}, '' - else - return {}, I_sf, {}, '' - end - elseif #inInts==2 then - -- Retrieves the inertia tensor and the center of mass in 'sf' - I_sf, H_com_sf = sim.getShapeInertia(inInts[1]) - - -- Retrieves the homogeneous transformation matrix between 'sf' and 'df' - H_sf_df = sim.getObjectMatrix(inInts[1], inInts[2]) - - -- Expresses the center of mass in 'df' - H_com_df = sim.multiplyMatrices(H_sf_df, H_com_sf) - - -- Formats I_sf for LUA matrix multiplication - I_lua = {{I_sf[1],I_sf[2],I_sf[3]}, - {I_sf[4],I_sf[5],I_sf[6]}, - {I_sf[7],I_sf[8],I_sf[9]}} - - -- Retrieves the rotation matrix from H_com_df - R_com_df = {{H_com_df[1],H_com_df[2], H_com_df[3]}, - {H_com_df[5],H_com_df[6], H_com_df[7]}, - {H_com_df[9],H_com_df[10],H_com_df[11]}} - - -- Expresses the inertia tensor in 'df' (R*I*R^T) - I_df_lua = mat_mult(mat_mult(R_com_df, I_lua), transpose(R_com_df)) - - -- Formats I_df_lua for proper return (as a 1x9 vector) - I_df = {I_df_lua[1][1], I_df_lua[1][2], I_df_lua[1][3], - I_df_lua[2][1], I_df_lua[2][2], I_df_lua[2][3], - I_df_lua[3][1], I_df_lua[3][2], I_df_lua[3][3]} - - return {}, I_df, {}, '' - end -end ----------------------------------------------------------------------------------- - - ----------------------------------------------------------------------------------- ---/** --- * @brief Returns the tranpose matrix of A. --- * @param Matrix A. Example A = {{1,2,3},{4,5,6},{7,8,9}} --- * @returns the tranpose matrix. Given A, tranpose(A) = {{1,4,7},{2,5,8},{3,6,9}} -function transpose(A) - local result = {} - for i = 1, #A[1] do - result[i] = {} - for j = 1, #A do - result[i][j] = A[j][i] - end - end - return result -end ----------------------------------------------------------------------------------- - - ----------------------------------------------------------------------------------- ---/** --- * @brief Returns the multiplication between two matrices. --- * @param Matrix A. Example A = {{1,2,3},{4,5,6},{7,8,9}} --- * @param Matrix B. Example B = {{1,2,3},{4,5,6},{7,8,9}} --- * @returns the multiplication between A and B. Example = mat_mult(A,B) -function mat_mult(A, B) - if #A[1] ~= #B then -- inner matrix-dimensions must agree - return nil - end - local result = {} - for i = 1, #A do - result[i] = {} - for j = 1, #B[1] do - result[i][j] = 0 - for k = 1, #B do - result[i][j] = result[i][j] + A[i][k] * B[k][j] - end - end - end - return result -end ----------------------------------------------------------------------------------- \ No newline at end of file From 8be14403175e3d019eca26516ec776723cae93f7 Mon Sep 17 00:00:00 2001 From: Frederico Afonso Date: Fri, 11 Oct 2024 13:38:03 +0100 Subject: [PATCH 9/9] [cuboid_inertial_parameters.m] Fixed a typo in the comments. --- vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m index 5e0d0d7..8650157 100644 --- a/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m +++ b/vrep/cuboid-inertial-parameters/cuboid_inertial_parameters.m @@ -1,4 +1,4 @@ -% Example of geting the inertial parameters of a cuboid on CoppeliaSim. +% Example of getting the inertial parameters of a cuboid on CoppeliaSim. % % Usage: % 1) Open scene "cuboid_inertial_parameters.ttt" on V-REP.