From 0a628f06cc51a9856717e8e8a963fe98df5928f8 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Tue, 20 Sep 2016 12:37:13 -0700 Subject: [PATCH] decrease some gjk/epa tolerance to improve collision detection using very small collision margins (0.001/1mm) tweak pr2 gripper. --- data/jenga/jenga.mtl | 16 +++ data/jenga/jenga.obj | 113 ++++++++++++++++++ data/jenga/jenga.png | Bin 0 -> 286602 bytes data/jenga/jenga.urdf | 31 +++++ data/l_finger_collision.stl | Bin 21334 -> 22334 bytes data/pr2_gripper.urdf | 42 ++++--- .../ImportURDFDemo/BulletUrdfImporter.cpp | 19 +-- .../PhysicsServerCommandProcessor.cpp | 20 ++-- .../SharedMemory/PhysicsServerExample.cpp | 9 +- .../btGjkPairDetector.cpp | 4 +- 10 files changed, 214 insertions(+), 40 deletions(-) create mode 100644 data/jenga/jenga.mtl create mode 100644 data/jenga/jenga.obj create mode 100644 data/jenga/jenga.png create mode 100644 data/jenga/jenga.urdf diff --git a/data/jenga/jenga.mtl b/data/jenga/jenga.mtl new file mode 100644 index 000000000..a89fe6ca2 --- /dev/null +++ b/data/jenga/jenga.mtl @@ -0,0 +1,16 @@ +newmtl jenga + Ns 10.0000 + Ni 1.5000 + d 1.0000 + Tr 0.0000 + Tf 1.0000 1.0000 1.0000 + illum 2 + Ka 0.0000 0.0000 0.0000 + Kd 0.5880 0.5880 0.5880 + Ks 0.0000 0.0000 0.0000 + Ke 0.0000 0.0000 0.0000 + map_Ka jenga.tga + map_Kd jenga.png + + + diff --git a/data/jenga/jenga.obj b/data/jenga/jenga.obj new file mode 100644 index 000000000..b90863be1 --- /dev/null +++ b/data/jenga/jenga.obj @@ -0,0 +1,113 @@ +# jenga.obj +# + +o jenga +mtllib jenga.mtl + +v -0.5 -0.5 0.5 +v 0.5 -0.5 0.5 +v 0.5 0.5 0.5 +v -0.5 0.5 0.5 + +v -0.5 -0.5 -0.5 +v 0.5 -0.5 -0.5 +v 0.5 0.5 -0.5 +v -0.5 0.5 -0.5 + +v -0.5 -0.5 -0.5 +v -0.5 0.5 -0.5 +v -0.5 0.5 0.5 +v -0.5 -0.5 0.5 + +v 0.5 -0.5 -0.5 +v 0.5 0.5 -0.5 +v 0.5 0.5 0.5 +v 0.5 -0.5 0.5 +v -0.5 -0.5 -0.5 +v -0.5 -0.5 0.5 +v 0.5 -0.5 0.5 +v 0.5 -0.5 -0.5 +v -0.5 0.5 -0.5 +v -0.5 0.5 0.5 +v 0.5 0.5 0.5 +v 0.5 0.5 -0.5 + +vt 0 1 +vt 0 0.75 +vt 0.25 0.75 +vt 0.25 1 + +vt 0.25 0.5 +vt 0.25 0.75 +vt 0.5 0.75 +vt 0.5 0.5 + +vt 1 0.75 +vt 0.75 0.75 +vt 0.75 1 +vt 1 1 + +vt 0.25 0.75 +vt 0.5 0.75 +vt 0.5 1 +vt 0.25 1 + +vt 0 0.5 +vt 0 0.75 +vt 0.25 0.75 +vt 0.25 0.5 + + +vt 0.75 0.75 +vt 0.75 1 +vt 0.5 1 +vt 0.5 0.75 + +vn 0 0 1 +vn 0 0 1 +vn 0 0 1 +vn 0 0 1 +vn 0 0 -1 +vn 0 0 -1 +vn 0 0 -1 +vn 0 0 -1 +vn -1 0 0 +vn -1 0 0 +vn -1 0 0 +vn -1 0 0 +vn 1 0 0 +vn 1 0 0 +vn 1 0 0 +vn 1 0 0 +vn 0 -1 0 +vn 0 -1 0 +vn 0 -1 0 +vn 0 -1 0 +vn 0 1 0 +vn 0 1 0 +vn 0 1 0 +vn 0 1 0 + + +g jenga +usemtl jenga +s 1 +f 1/1/1 2/2/2 3/3/3 +f 1/1/1 3/3/3 4/4/4 +s 2 +f 7/7/7 6/6/6 5/5/5 +f 8/8/8 7/7/7 5/5/5 +s 3 +f 11/11/11 10/10/10 9/9/9 +f 12/12/12 11/11/11 9/9/9 +s 4 +f 13/13/13 14/14/14 15/15/15 +f 13/13/13 15/15/15 16/16/16 +s 5 +f 19/19/19 18/18/18 17/17/17 +f 20/20/20 19/19/19 17/17/17 +s 6 +f 21/21/21 22/22/22 23/23/23 +f 21/21/21 23/23/23 24/24/24 + + \ No newline at end of file diff --git a/data/jenga/jenga.png b/data/jenga/jenga.png new file mode 100644 index 0000000000000000000000000000000000000000..1564309d993ec1523412d8bb4809e75e40c92916 GIT binary patch literal 286602 zcmbSy^;4Vg({+&I?(QMDySo;5m*VbFDDGAqiWPTvDNx*sTXCnjyT56_pXVQVf5;^F zHIvEgwQ|m$-9#!YN+Tl>AOHXWWLX&rRR91Q{1F-e2MK<=@b8!dzcIK;YP*TMn47p+ zJ35f5Ticrhq+G1YSh>mMOdQDASXep8Sh@H(dHFcF$QW68SXjp97WBa1gLRWtkc8cY z$3i7Vo0XH(2Oq&Z$>_KO00f{lWWGhhlD2a*apQ3TJpu)DQ{OIV+rrf|m zYu3O%Ee#Z9=une?(xlIXTG8!5Xg3QpW)^0eh({F?0-YEy(!d5ZAG|2xUKiRwdG>pI zc>hUSHXI?N`SP5qc{KFy*y_1)efHxy+w~6K?`qjYxG6JO^>N(M?>ckiB{-c0G*Zt-bxEzNIc z`BV)Hh0dm<3MKEnPo$z;nun1%=+~B*2a-SPvtQraTg{!LFH3qCa`n%~%i`l@5)a2y zM9Al7$82XxeIMDEFx!7e;e>ZTA8pQ?VP~Bi{9or8QGc}DiK9M;pB-%6Df4-RAPl{? z-dK6t}jM=R6EZ!QSqhYbGEFmLN4oZss%N@QRJl z`}Gr{%MC+MhwN2drs41{mS zFSdy0bXQ9XI5B%=hwmPc4kk2Oy{q-HH9}kbd6m7p01G+~l8*~@?CRPvxnJ;WHTk(0 zXqE-gcj0(BOk?`I*x5wty?E|Ll`Rc8hzT(eBET3Y?k1b=v36iLk-5R-jD}NCG3_p- zO?@vq?^8ysQZ1_s)-PnKr%h=%0;wgGA61))P{296h-LfW_;X zaveg>6oO5#d0k|+X$|Td^;x8Wf88BU=+R+MY~QZy?ETkHhsD#mD@#I%TuQ>auS+_B zh_)2xU47ILi_DdtoU(x%OX>*j!tib6>BjE-!bte^-`t+}*aJ5Rp@DE7jM#Ft)Rj*EcB+x5k zLQ@VSd;jw?YS8G8vi(;7M(P>`U&O#CimaFnPE%|iO5X!y`Sy?WToS5q2ihKF7h5$D z&$2GKIv;Kh?KoTtw3!IPrKrs0tLb4~=&h9?+w1J`3PjBD-x2jimJetycP?aOI7+dG z;!k$IFiDQQu*n+mq}}{NQFR_2{$5x6k>X2UW4O>1KAc>;97Vwd^T_ab7j8OjGSxmg zt{UTA>_mtuHj-w1{IAEROveKJ7}EnoIAU`Vjn1vwBU&n>?g%I2eSR#paYXh>Euy(; zD}!L`d_|3i;6Yq`9cwKAd9|Pg|7Qp3{J$rXI~O`g(_W}eT__t#ONu|@mevESdS~Cn zl#@?6c=3aovi^MZgqHIwEv)YjiVNdWAiq(}$X`eeDx%Iwd4ukQA`i|9^#c&Aj|yf{ z5Yc?8z&~VC>29QoK19rg=eK3>!>Bi(2Gr)%SFS(QV}{^sGg*^18bJ;z49~@v;;D#` z+pIEfM{^i!ZdbE-VSM=`AdP`D7-)V2yv?xVNKERcaNPi!_D8~Z-z;*pMZQ&Lz*I}0bS`A^G!{XPDQ1v2kvc8Nec(U~c z6~GkN5I!TsLIps067x+WvMDw)ALfp$s%CuGltoI6Mw4|258KbL%@qwov6R2TET+xk zBA=G8PMYWx%OP3`#tdK7Fh+{iq!wSdu`;t(uCO8l+C@(>6V6$Zi)hYp9{8-DZ;PwQ zApK6U4B<^`OlrkNW^qsILXXA@!gd*gtgzn{_><_9S9q>DIED;=@jkMTm)5)~8PJzlmTGeHv)k3Q*CjXzNN_03EgDVuS}SL||5 zS&72=3~fB0I8~PekQg*RLc02;yMIb1+=R%D_wrVISK|1DgQ*eym_TnH-$uf)$XgyYD9Ze%(-e_Q-7)P~E;M-Ne$mIbErF?0JL^4drZ z7ACZyF*AdS@MtYH?22e8PH*;8lMT;BTP{Y=g^1Wtum2_+#v8Gv)L8VcJuXxVi7g$X1U=CiWY zk$#x_I@b@oDRUK049FDbNHZ1akNsP6ZZjM^ju?AL6!0u8tLh#<;O?Wu!)VR(cg*xz zT|}a!Xs{)<3Mw33B#dOUQiofkV8g979fuD-DFJa)ymW*X5ZXd~;6BAcV8X_R3RFqN zwN>*@fP5$>UvFG-B$PGMlqY%xPM(o{)}#PPGc*57JW|22LGEQ_F|U8d;dzj;EFVPa z`Tj-8KGbIv62OtR=P>?gDC4!K=hTX*G4o);KoGDnLbJbr{w^GRB+z*+F24ig( zaZ;Hz_!40RM*+3vhr`GQVeOXU%0PQozZ(#%K)dO1xQquJ{r9UHyao!hck}}T>NIi2 zuvs)XrT`_4C+Qod%_;RPWruXPsG6ZRAN7IxMi(C!O6vgmY+gn>Cr%Ji^w+c*TgA2b zggoZixzOmXtac~;c;mui^bYdFN$?p)Qh`Jt{#?+KjBLmUN z{}e>}u%eO2#iHk1pz%veOU@@ECYCn3GC|5Cn9t;njq)xEgrKQvB&HZe&|qi30xj-vw>o*a!{3fuZp1HWz-NP7}g(9z?NBnG@wV% z4`!`Rq+^X*w^*lEkO~Y|iAV`BXAi{syx^d`wAH(1s;s&FVhcKj)&X*=ra&qXo#Mx= z%2pQas>)tr1aF1ts%@oh!<%|yWYgi!mwe2x;SmISkl;S~VZD7wQzmmu8jM46bh>K^ ze zD58@V-qJO%yr-I0x$zaZUL2xfj^$O3M5AUrksfFxX?o-sPeiL=;fd|SFokm0Xha67 z6D1dI@riz%@Bc2BrJz~PE3zEfb!2Hy>9PlEZ4B|SQD{BOrActA0$L!tROxRpxfoL6 zY{cWS{rMb*sq6$#odAx}a9;}ubuuY~f2csTSi-$*Vr%@*cibnK^TuKL@*O_^V{bzk z@D>;V=O*nPHVir1w17|A?3|L67I6wz9QuqG&bw`2;Lv;rp5v|xtdk(x7zQXn7;G`x7$nI$d0Q?)yL24_ z%3+B?GYB7OA!$)ybt46*U!`tGA?j;PfPFn=h$jnueq^XFkcf`57yiT91L#0k2R`%bdzlU|g7~p=z&Q+K zj|?XLsOx^3Xsr1@RiX$h&o^b!Dm1=Q^M}}w&m+dRGR(5*2x_`%@Jv2*EtWC;==NgV zsa_{+0UyZ!4614r&i45MYQs690U2F?V+Rq^hZyrOqZYoYje``Ef(9@v|DPLDYb?9~ zNOCYvlf3j|hpkcBo9&}*3YE4xiGd_KBg_kBa3q0*u`j<$zoeQuwaZ3w=6O@Qoer9_ zzC;Aggz{YrUuOub43Q_Q6k5oybGTHmEjq3JfdNJ5Ho&bUnofU}bY3#U$ATiD^$-{hmAAVslJO8tR_hfeVO#(%vs8m;jm8NK{eh#)4LvdHpxYebc zoM9&BXaBG)Q}3ZN0=24}iFMC#jwvzCDtGlgbs3UV8cWw6(|cnIcS-3e{i58rNRL_~ z(;_Hjl0#^H4bJw!IRkMEm}|y@q&X>cbn4$aJho!(r91Yj9zEq>ljF(Cm5g1E(*rII4iu=5)!X#Z%+{1UGcIDv)mSv$(n`SD*nGhXS_BWwFF=4}>1>%pqF zD++(9Fc@ZY)_Ws=NyV7C3U0Y>+8=MHr@=ek`2atPRa`zwl#EVce5h$5y#9gUl25?m=+nZARc*C z@%S1S71JMh83M>H=mzRdh0{0z3By!v$Z=Vz9h$Mei`-g2nH0iEg3dv}%;=dZ9~&p{ z=R-kP&3yOT?hN!=Y&M>M&?iTTFd;J?$(U3o~-6=N*68{4n3V6I@-v63UH$Xo) zFFL(#DkLDGJz}X=$jo&6_O~w>s!~^8D4W8VYUemki)CB40ZAoiQ`@30VLRgk>7ncc zdB-t@0j!)nl(d45aAbURx-L)sFp1?&!Ffc zdwlL*sh@9&Fpc`m^SKbpnu9a>VV0~ZuipZCyVyifi%Li@Rg@9QhK9v<7gA}#{8J21 zRyCbu(&rS_;VS-Ii;Dtgvl?X5f!`S0p^Nq8pu&dl$tUL&GljkE;$oc>(W8P?_(iHt z6TRd`Atj@4`a1;T6!9)*j5eI|D6sy<2sENCx?i-}j!5o&!#f8dy2YoID*u;S-zR7K znvi_{!Dy>VPBrZLe-=xN*fB#FKWbP}34KlE%+s-oTo$#ZY=VoddyXFMF4gS8=zO`oc)&nY+Q?L;oBAexsLMuA9$EatIH{qYT% z9#U%VTP5J!nX-^hgW5pDwHuq)naXo-N+hz;LxX&3uF`mY0mGz>sv*<2)p^w_w722_ zNn(yq0W>FPP&%WzDef7ZCfCFzW*whQG?C&QuUS&2hb#_-m3C>ytW}+v}#wm-%1Z<`ayO)innEMJaHBWOulR3z#04 zDOk~TO@WXQ(%F(-1fdk&WROXUvu)lN-&j;?p+iI{Z(!~vJ313dF@ok279N8W49Rhr??%To zNIgQj8By6scZ-%N5mb$k;FQh=uOUGmXOyUyoTxDxir2o4k~-TM zt8bv5udRn5A_}*lOH?R$0t@(2odNI-~KTq zlDo3SmNGG8>1CKtfDBc2Ix&g4FzfVMP5R&z878i4x;zHxkl{2J=!EI8w_Ukk=)`** zaZ##q9+XT$s$Z&L;;i5e7U`S=%f4ap030b3f2Xd+BLz-Vpft9dd2x@EVDbq}8Vr0& z_L&mM7to#(gDl27fr$$&^ux77U>sqat~2|TEHE}`JJpi|a zS*9!^Ks*ue_WElrHRkEZySh~r#F4;m0IaHLMpwzSv|RXgv&6^wc+2tqgnslG()`wg z3(Xxj9%EV*G$?bRBA2C}s8|>ayEH6&e;~Zk7>{4{2Yqsg=ovRNrPu!NM`>~^Dz(2| z*sX^6Q1mgpQ*)#=PB1BY@E~}9Lu)(x-U7f@4(WAO)vH@DOP7FM`>9;7Phzs|9HwIsfC)5e1#RlAM z-Cp%SO36q`SriUfm_6jfz|zoF(8lbvmN($Ys;N6+ z(rnRFBYeVSQ#ys=wy7|}Fq3g6YrG=*ZUsWoKp2DAcfKyq2n)eklEL1OVES`YPR{^~ zRept5C%DJvCwn%C3hD{G7$_Zuha+l2LZZPPRU*SAdMie!?AMHl!t{MS@b(*`JY+V?Z5^e+1ND*r~3oo}VC2=c566%~p$n6LE-rP)vkWrP=F=&`FYV3mY?`)s_dnDsQyQsrP(6LN0P1r*?@OFk7*`~xA$}uahs4S zuBM$vh`?HSD=B9QsL=bMCObyiR0+ISjtu$P|PRGGnhe>7S3qkF( z^bv2}9s0>E>dMGBD=Mo`R4}|rB^Ldi6uB_6w2@PDZef{%SU@jSA3g01bvE*0YA)|K zI1Jvmo+ZMpyPkbgDuM10xcx`{k!A`U-4i=|W zh$K=6@_Z49bwO>lKdBp>Zt%2j0#`8MACH|+K_t4YC$lDoFU?Z*g35}J>qXPs>u^&y z={T?c-mdp=Aa)DK2Dc_qP7TFNVLwQOV>1;tX zhGNp$$FSrNl}HX;X%Uo+X4@nhMI6Nj#sztKnx7Z%;XTA^oZd8B`a4d0ZfYD(6@Khg z)F}@sVUyemhWm1i>^A6|Ku3i8;?@c`tN3l&zE1ktKB%V!4$EtuS^n`TS9-?v6iR%( z)$*ZdyzWfn_PaS+7^uj*tv%0dQW8)Fy>vqlk5u*c2?ceo%?)uQ2xVcYo?$3LkfM|4&}I9;_A9S~Tc-)Dwe`wkEkzh?MGGwKS318nWhIcv~qio5=KrvD(RZ6R08D8xvjRoja#HCGpBo!vcPqr;b z531|OE=;#?Q(KBs&gc1H!!vs!qIE0L;&ng1HtB1-Sd&pz)z1dw3||E`UZypGwL65jV%+gTM*6A>FRV&Q6NGg>6KE40LsMT>%K4&mEfFOQ! zLdhdKZgu|srnB#uIr2S|FqO#w5iGNroMO5@$H-Wr^3&}Q+&(^sleSiQPDW-KY1(x4 zH|k(EXNpVqZ@z&V;#QYHB+u;?x;6eL&rAEEvVtdX3Eqm8zC?FUekgz+sM=-85uq2Q z5!uwLMj}-4SZeX;PK}moY>dq?d!MBtq1g{dnS-5Z;_=uA8%rs5L^l>`OwG#H=H@Bw zgQ=Sd6*0^42?;FtLI}EL@gU9_avRLCLa)DXMgl3vslu1VkqfrSu{8OL(c2)bqUpn{ z2fQn!q!mWKSyZ+KUobhBrfUC|5bV!Uo2Yij8(_Zhkj3Ynn`{U#>M^7Zx^g)G5q>yXxE!Y#u{|eow(?%Q$M9e~SS+7jB^h%G#osd# zR$H`w^FL?o{Mpsi!b=&sXKgp9%Xg}9kNWdT`6=ml^M-fd%(NmH{Pb*dyb2YegJzlz z#MYO8URpg>E7`BV$&9MdTN=+cB5r3TRp$C^y+7-|hv#fOJ*F|%g=HFv`2E&?<~gyT zgZ5Va0Egf2yeq(rZYe&C&-ev1_S21d$wWsnV{b6H5Z9AiuC=T7o8 zb7~ja=UFRWWQ`AZBPqC2E?(`brcqQtI0O1}D|Qx{-m3@A%X8uOF5bfVcO9lTCC89Q z+@IMm$M=G_gpR!4({h_8Ibp;ZfMGXu14G%Htx>X7V=)*{EDJ`PdG8i1QN16WPVQ2b z?w&hivENuv!FLT>lpGh?*O4uLt5$OGyY%z>r0dDAyuzmtTS<%h{Jp!ne1^B6O)z5= zW=AuWY)H5E3||Gh4Dh&#%pnOg}$m);H20*iYi=LPKQ@9#0geO=)TLYFex7f|Ak z&Iwi7IPB-0ZO>=S9symuh1Y+M`Q7|}CO$gU-Z?Lp z;EJrk0a#I0Ml|C0ihU!$BB>s=(N;#6iM3)6eFA>5Cs*?B)Dw|SV?yG@uKt5YksH+` zX@>19JBGv*8A;7G#7OCpDjE!-6tzCWrtg%p6~LlVq)W*hQjKwOUlihhi9#d+Y+7v$ z>7-DSS9F-p{uopm&w_HD|AwLBQ?A$X>ZnM(!7y<*{yry#SOBZ^M}pDsnNb>^6cro^ za~&RiBCTk}8^+?lT}ZD4X9-g|h^NxlMBzgj_~sXK3-usLT7nAT*MJt=aneEIzB$IE zEOIZpd%-RD!k@WeC&qsggNq0pzXkp2!o7n-jZeJKqG!k}yC>@U<#g<=X!D}R8%e2n03)t`a(b7^twx7)F$@+a)W61$Z-9kha7!Cb`V0BM;#n; zzaLSWg(>kg<8PoLmxR8Z4a^SuNfp)ihC(}8eCJkIWCo$IlYozpIuatn#&cP9CbFH+ zmUbj+VB7DFg$#LzPf*fGmxc79)V;0Bj_3YN*w5zp4K&%$+ngC2^8g;P3qSTQC>i`7 z5jepMI6IqFxpw=Tr;tHP*TE$ z=y>`J&EH$F;c0vRYIJ-%t1BGyqj~Q)Nd@wbiLlQiIw!wi3#dVW<;L6*+!eSQ|GW)6 z;TG=bNbR@EZVdzRd38~PI!l9=Mn$5DB$ z2|x(~6#a)zgD#hTPGW{?4Y}16bO>4-eq@qs-D>P1R+C}ALiy-2+7QD$4!0x?i#GhW z{`@>M1_QW2Q@0~#;rK6iU0YwTyEJ8*(X=7Ib|-Focz-*886(qvJ6d?Vo`|dIV7aO- zxXmlTVK9M^k{$k z;kfSo{`<-DZDy{|@2-}cBAAZL>%Nb0)0O>_T;OjagLLmflC(NxA3uFD^Tm1KQzsLRWprm82 z;^thfPj_mS99NP8iZIN&?M6OG%J9LJkmcU7dEqUuIq--sbk|bY(Tb|mWQZ_)#moY} zFSjCCRuiz-;gdiecBsqd`bT2$+EW5)kp*BD_PnL5pI9j|U}<`~6?3c#4=CmfV4 zxFe~oTsgjd!>W{XsfOUY|C*A=fvZ~}+O$A{!hk`($g?d-&I4>$ROGYhG>Cq~}vARRGbt`PI}0&pV;Qrs|h2@}Vl4F=^ph7kC;{GqfrP=g7mS#+=gM>K?w zF!RP^-R%mA+~k+rNi5xMGBEZ2bgC+lSX1p{U!Kj{qEwN$qlM~2d?L3Z{OodnInEyS zYzcHscqy4w_-ujd#n?-ap{sP_MX7B2^IHAwjM@EtpdxOn2p9iOu+D?CE^+A%E0$+IaAc13i_7tf(%uiaC*h>nupPvEpjMV}>!qaqb{&{iOjPF~P|N~fhTYnw6W_2+0U2D2kD{5UK!$;<%C1THlZJ{-sSddp%6H~< zQA2XGHba}bU%(24ItULwSB5}mYm>|N8yC=tT>B3ERaLf7T{~6fMs{Ktr^dbiG~%bEPvXw#pG9 z?>-DuRWxfLcyDAG-`G%3T=&)PES28)SBa+hAK#{GW5 zt`}^#o|x^uW_`eIu=4h(#b8uRq@30!Qr4|#z<&-G?c+E3xP>ZM^LaAzW%B20=T1U0 zl*h4_@m$#bm$K)peGYcsKFHoKtpy?0mN-d^Uj#H$74kh|I?tbu2mGH-H2JvmA6YOW;CsDLjcAb zFgl_5)P5och!Lg#s*IxX+Dk+d-RX(_%Gszg@EO7%VPCCt*&W>lL9NSrWnf z-GUaZX8cVHL`DZ-Tb z7G`O7A*CQ}+U5}7HZc5^p^DfsuU~xpJ$CZ+l0geE@5m$v{u%d-aK_trA}I1ZByJV- z`;)X5ldx1YfxBtvH+cR{K1bj~*FKk!&*TM|46G9`JFq>YF9k5|1EegMa9!^&408tDvdGp?7Pa=yH?z21Nc ztYf?Xx7~6k`mnC|KbI%AafQN8lC#39laWnveL}<#tOXcORzyK=EP3L#)CUa~7#%!g z9IHda^2&)*u{M^x_e&oLi}cgS9%=t%!E!`*Q@9oG17`?osl|)T8L{UM8WxybgC4e7 z+;Q{S8JZ$EF^=X|FwU?aJZFf2E>NENNA_r z&EC)bd7DZ9yzYOBQ1w=Z*vLs2K|V&ss<(=`2+ieUfYjOoa=YF(7hRL%M=*05N zG0HEswHYu+Sok^wSnj59o?jJ8N>QN{JejSX?Yn<}Rb{SWrj(&Cw5*1H{~h~+VkLC4 z2s~?fg~lo>PnSacw=Q=Wo9N@jDqIUa(Dr>1&hc>{Y`C z!Ng}~OxUOV`AwrvkG)YuiieJ3laf^ZR-%s6@VJhr(FK0t=5+;IUJ;#T;U8^2ede+C zH(+{Ue7fTVRI7d%;RAqL5X{Ude?v4aZD&ChZdOK88elO6wr}&TVjX=?Q62lmh|CRp zVgCE0gX?7j$F9KVLz`IaATdf+jR)ME=Hza+b{tPiS5}Sm4rvYzyb8RZmEQok`F()${mOfFJcY1s$T7k&#CVa?~(uV;|Gg`31rlH@9${H z*`Et0%PUFl8d~mD%iX_b2xhFz>WJzz28a6++zoLxI0}4UkS%h`o6>$)5^i+aN(lG> zz26J&*L)}HE=W7v4&%CNQ|4TE%Y7I zGFZpc9s2aGFOc173C|FwQh9}vYWxQcIAs!=x{Uh6X&2vAcVk->`s*Oc^*D4RcWt56 zyy&4(w2b)n`|YFWERf*OWckDyAY~aOb@?bl$*MvS8!lzh-ptJ|dIR96ylYO7v8{~Q z|J08Sr%!D^)s2=h$i597*1LlH7+!YbdBXZ7NbmG1leCY`FlDa~2Elw<_@^Q*qqk}O zW;jq5pXiL=K#dw=3sL155~)ALV_JO*wHyD60q;k!O5;?3c&MiPv}+VwP&Bp z@#*g3t8_gd2#~!yF*IXY2^|gdOrrY?eUgLzs6`_e>m4ws^}9L~H3(I=nM~_qf2pfj0aJ>Le+|(hwJTs55`vpgEpUh93s6zB zmMh-xYloO`ByNyR8S6xVa$}4urJTl^9noRvGW7VOb$hQh2DD;5RS;~EAT3=;= zqII`(xgF;tl}tBDg9n_BtQ z{LGS`O<{cs`pNq;U9n6=(QI7HZkq<9Mp(+4UF^{%rb*>=crC~9eAw$?(;HA4XVQAG z&}F-L$n}_l`h8h$)D5Hn&oo1F^t&tfwuk@8^~l;)*`gH8z^zYJ{l9-lQ~U{uVl{Tk zehx*c@k!tWvv$KLpX)IV%C*UR&owhbW*z^TH4pQe~0s%gWQVu@g(>#bz(iqL4T{cdJ(HuM!_xcau*5~kg%XSa;WB)SNS6VpK@cf$4GbB=IvYr>*od}srG z*=YHDVA`V()ElL6HJH1A;O^ATq(&Yp_qvAh1ERy}kFd_1RKj4FA-Su$<4?rbKRf;0 zt3Cs_ucxRhwT$C z^1=p-Moua(`O!Ny0xUkA65+z_-)D!LDgKrxyT9d$7!E*$Ihbn((Ho;b8pOlX50QsP zFc9*oY!6yT@?|(5o$+`kMOj{F$ictR+7^5${mlJv=ZZhtnJ1qu#e?-` lYq-APw zXffW%ATk2OXX02;6Xv*eUTt$DqrxXz<-{XhWa7v1JC@*bbiBMX?YgebiES##ywZ0DUP!q<+o1;hk^!HEbtaca@~IX1 zRww-~vV?mclRiplZaYe!PFgc9#tdkGkZ8%BA55%d$AP}G6mCLV_QOYsh&S^3I)1uU-jtS{fs-fJ-Stww~k-kKdAXD z!uFu|ird<}s~o|HsmPRwb2ESbBC()@q}<2H`#AUz)o@9dX0gbHlbetVuf`H`he=La zh46rC?uS9QPy?Xc1sH!qq4&JhO@c3I`Kt6=*E;?EZcpB^tr|0&En(ao@d3R24`x`h zFpmq$@p$8>?wdY~AY=dXv`J^k+0TY|S%XK3yyA<;BxTI)Ja1#2eajUx@KiYRI(Uos z3(FwmoC|<*=HZ28?OloYzz$&(3c%*^ItM-5(=4sl$j`8UEbos6?Vf^w;xQ;axbf~X zW$dQajuIeufZjwnf}CiU8w3bV)<}(jB#rww=+TmCN{lc&u z)#WNyj8s)CQ-22uglOnkIHR`JGL~&@HD;07W@wZxp{agYGF31#aUaBv+zd4^Y~T7# zFw?MYhW<)RVd&;nVN%+27!aw&5M(PO#oNUTQr4MX6Y~*+wkeYoC-Pd*ONfU0Q7QI7B89jGDZWa=G>)O0zD#`L z?n?R!9lqJC3%+ARTyhB3!}Fi{kCR5eyS;lN`uQHo)_j(qe1pMSSM!2Uh8db%bRjFa z=u0wIh5I7h31~^DU08et#U%{4u$xpd31E;(o_{p1@hSZN8@|-jy}m8Il1m%K+{F0r zR3X5Z;zM&hcV)Ek=~|xskawAhK3COlx!BW(hBL(P=+{a=f;!PBFqa2cXTb6oRLj5H zj&28U7b_wNGN@CF10kKwT3x2}f-xo?nOw=3P`CNg3+0ehqa{A^LA~PR#_+RZ639O( z5APk{S;Em-+d!+3ljeu~E_ORZ;=|?)IQ*2y{fq!TvDQ8K7{kM6i?Yyv!0?=8D^jOP`@<1Dh@Z zuoScdOoXv&=y_N-SV3b}CG^ZON18=$S3_J;RnRphxF0-J?#zJ2NUD>q7ne?$P%h{CvO2 z1*xcCe%a(F?s0SBirB8@G1G6ajWLi7JhkUlO-kKDbt<2{`&`f~J5A=m!f2hSA;|{K z$Tw0$W^dWg=aB+MTgo;~_TT+QZ~CR`_!ob^$#4yYt>hP<|D&cWnrv#bemsKeGR(Q? zQ9vz%bA`NY=rtgaPUgdJ;Rc#%q)U|%@>v>;={=7I%CJ^+&-zK+KkZ0gM3aU7yz+i- zYcv^7meg{V$N#~_fJazjD#0`iuZ{Lm&zg1#Lt;nYL#F3dU2?D3SwhZ5)QJJ9SEh`2 zE|gm2FoZrkpt_ZFQ#6X6yhJlokQ0he>6I;%&(Dq)Ps83gLF)tbDovDMlKvW}2)y!( zI9k3&$NPY-iLp%$+t|rM?Lq(6c6T+_Za2rM?R96ep89YSf7Iy(gK>?oblv8HA6M=5 z)~8l3%G9T}OUYC2uF}p0E{%%Sx9j}SK}~_i&x@1G%ODfd@zX)C#YwEY=7p*VO6Ytt zf}RP{v2>qcp2}oFkC0A>#B@pys-0^1^fTi+;|=k@v2TiyPrTr>7o`16*GHmXt4^)+ zaI}vf5I5}7LA*kIax=?Ks-!S3H|W$khemJwe|7$&Wuu}uV9J3k8fkBIj~waa6Xl1o zRyVF!@sKiMhN5N2ILr*TtGM1hlf|4KVP{=WyNIt-Z}h~$%foK)NI&~$T@|5F_VX}` zWh#uYLJH(t2(2(0Sj}*Hy}Q$+W(Ew%spKPvpwBQ$yYne2`wz83(wYcQ28j!SUqobb zyWYz>&Ln}^pNfjo2w^~2;R%Bgn(4~~d>^xJO{a*FgYjrp2Cqzt%&mIV_g{(}!5XXI zh;A!SZNo%0^l=igwAh!jC5Acde2E;+g}vT$Ft*N@Y_*9n*Ei)bp44;h+V@w~*mdr; zPnb*hu?P^mVryB%WfeZ^p|uhmg6T~i7#)Z9@8m>HpBpV2!+niRavo)hZbx60%p_x% zp^4YS+#)Y)&yi2|%#bKJr9RsV6D}&*VS}|5U|UApbeZ87*%Q*TeWyf-6aElD5x$m; z6dQDidYNOWI;M;(zl>e*E6;_*#o=a&6*uxsh0dgm0OduM(_>wHB*76OD*LafbRa!z zB+9Y%m#v*);6s_4yiM#>smx5>Ayp%2n+zSz0>~dCUPi?#mRKD6*d|&p6DJaWm@f;% zF7`stF8>+1INVyaKUsuS&W7tHINj~;4P?_K$7AG|;`O*ia@1M5N2>4GcUDfnwbXO&B53&G*KY%#EvaIvJ= zuO%h*^ZP%9RNMy<8rr9)8LWHtah}S@g<%YSDycFEV4Qub9JQgSXLI&hoE!y1UYcca z=8EMy9ERVK$%gczrI0FERf?0nJW0QYWQ1W7#+iBDGXZN&APNn%)6;*w*)DguxX#=} z;}(xH^A85Y^VGj8E4Uar{J{j+^wX%}t;6C7tCkuLE@3M`p!lJsvL+%rh07~Kh*m?n zqyzhcmEbI>=j0MeTomh5qs)uYJ7+s+5~^Ze=;n5#`^p{CHDy}G=CH~|Fp)=HLGB@2 zfgfZt;2?i0dUC?KRrFLd1$85XepfbQx9vJwg(^^bZ|N$_Ek&@fm>4VFNtYSU{&I0Y ztgD^R-SWh)3T37^eR31EOXH!~R!As}6|tnlLloC{I6_Pf-qCAty*~UA{`)#K$X7tC zlLmde82BaDhy|+MpwCbX4$0+bwB4yC)boJt7XNyOMdjr{$;!KI(3-a+G6y3?;B-aQ;LSYtjEC&e6X!QAS`I}={smc1 zSs8@qNUJ5Rc;ZP@z>NWSlf2y}B7~1PLZ}E5Vvpl+cANwZeW@6h2eOaBMWiO8{i!AD z^Sm2-R(g}CT+{btS2hS};I!aPZB8~Aj=rYZeES=eC*SXC&p{`%Ngsuq{O@o5RL?OB zUTeB&z^CLVv8T*rXx>{@zMi$hPHgXSIm=_bu}xtByjwNq!%B~j)~}Ses~_1Y7d_!1 zR528(bW6Y@7ERI0HU+C(9|%Kp0MRbsg4TiTTh=d@S;bW>p@a@6xoYKc(qdq5Rfeii zb~I&(jfM+t?v2^5T}Fif-ZK6^(g3X7<_yhUSVurEP&(3ONJ^YZPWA%e%cV;CHLMc5 zPpLnud=9tJQ~Q{WH+~yAmWtBE%zRHC12rL|fm5Fv_FmpFGqORp9;US6WMf2SO@V;4 zzHWOL{HG->6Rk8ih%`;1id7`{YqJ_NL_{1&55{s0z1RG;&2l0)$D1Tov_E=9G?h+9 zowkd|bb&feQw!iNx;Q<4!}&4U&ml{$@ZjzF@4a2V4)?V=n2Rk6Y&Twh=ZtGZ#{UL;(%u;J@^{Y@7N2H{bR-l8zeiYzQ zdk!QZe7kONLP;%D?uTT3U5bcwsAo{ut$~mLb$T%>pY1_p{#wScJ??FhNtJ zN1Q$Qa6rjzYzA}*1(U6}W5I@sZsljCTSPvawkEP#SJ|&HX$P*Sk&x`FTf}>2=LC0r zr~qz}5FwoT<$K&aXWKN9O5(-+{DwR-14C(8a6J@4D`U`R7dL z^;6FG4aYCeK1KF_mk^%&)d1+U>&ug99_?o%hR)!j2lL;d2YNNVz7}oVgy?bV`=0dI z2%IeNH4=i?y#%u|{>l^?4rum4&k!c!iAvo!`DngHl~LIkiDr4+5^Gjbsu1p7G_A(< z2b$$9yAi-Fv;+3K0!-ahaSW|csiPJNG?Cg!>vTLABilCM;Ul~&zYSr12^2mFL4ztC zbz|Xj5c)=JzZ{>LJb?v1RVkTubvVO;YkOv@2op+2g6VWSzVjjuC<3iT?@xavpAJl& zUFRIfH|hAH@koLw%E{cNehot8-(h4Ph|-Bvt=-8>{VJve3HBBCYWHGpg@zl1OwcDq z+U3P3PPvI}3_K&4m2J0AyA0wgp(PL*$n` zGIl_<{C_lkWl&XZ+crppba!{R(w$04ceiwRNh1x?(w)*sH%Qkeq`PwqY~owo@ALg+ z_6#%YT4!EIEF|btR$^f_bXeG2D|m`6;- znT&;+7Q10-_a{o@Vi!oJRy=%?^BQbATpkRM3ZY?5%rpT#+YIvj>V~wPF9v6@&-rKQDBGfvhPHa9W&peAW0cOJ3!Stpm9tqd0?i~T z913-0xW8sSE8}zT!eg&>LIvb=fS=boCTaIBsnWXwhu*Y`z0a5-_ayugmfRAAxS}K4=63d{BPxoWnLzp01B*G9CDDeqbWwOe5hst2n7)Ai;>{HwY53eSDsFY%G%Oh_z z3*n3r-?!|OSxVoWNs2bcCwg~reWgh)4QZe4&~J>)#ryNbLrv4y(n0O+=gj{x~W?TDAho#?R}K ze_Fp8bkLmdddxTb&ND$=YlE%^{KyP4IDGKH54u}4M28r#s1`py=cGNE5tDW-a=sq( zGV|-NLp1|K5L)#c)clngx^DX@2mxAMJ|%RG`ePXrrDP2*KB9RK4PnUR78h2^y9*PR z)(Bdm+)_AC+zR6G?3qtmqsUGQbhaUaGa`8Q+vywIeL*2=nXYar?o!3EuK04Fswzhp zQrjYXU9x0ny}hN}kUs7|St?#nq*g+H%HBqnk!4EFvzEQLPzSd;c#x&)>=U%&+)>;I zg){dL#a7R`)pBQaM$O5d{?Yju%Fs;04(ViBz`3vCB>H$QI4R0p)DX%Mb%Kb-3t@X~O9Wn0$BCwR`=aGs?YI>mnkCdH>^zZ^(AxL^o8Vmlea%_bP=@TQ3+9kMaM zkPa5l{~)VxOfKTqv++0LYAwG}VrNYGgaRGXEKZvR^H3UTv_0ljqT>E7l|y&aiX+li z$5GlH7m0)=AYJjQnZl{4BIQS24j-yhf~){Z-uh z_9#hwVxR=U%+XAIN{_^1k}Zvc%e{uf(1)cSlEBsiC?$3lYv$2ljZ-#(8CmabJE^nm z19lMR(_6Xc70DyV05AW9)SK;6Ui{3bdi-V}AK@V2Hhhth0aIo|z|iaW#LNBB)`mygHksYO=soT-hm9--_~GW{#^GRc_ewx+n&5ev<` zvB=6FW&w3SRr(Lz#u~N13uXA(TjCSU%C5Yq8*IH^jb__o=(Z%#BL|V8--1XzMSKq% zsmBV_-aw9v)B zonK?vJw@GQUxy7rJ|~KTvVy@t-_?7gS+D%#J%X;wo@Y^&8Y;iTrAkgom-s+c)~Lx< zGy5~6s)jNpl0c($G>SBACoL?IG8%>bw~mkWydgH*^`Cm3YXN;(Xmw+Q8Ifsfq_!;| z44!NP?rq02x;xY;iqcML0wGvk=fvH}abj1n=cN3eo6VMMtXT_-%^#*fWUCCPoXbBB zU`5ji*Q(q$%O02nl)$EDsm^waI;SyX<5<|TnI5MK*|N$5W|B{~1Nc)$X#2mh7u0U3 zFr-0}=)R{bj51TXg0x7dEE8FMxDLy-Z^uYQzB#F#!)7KF?mta!0o#BgGDyvD z)GJE(oq~$=e*a_cjNjnBzc6ZhdaPXa(l`dz<$;x96MjIUv1NzBNSUt3imCYY<&Ore zz9na=S&VaCS~At~&icU-rzV1^9QQ1>V@wS)X2dmDmH}>l2-BQPjPm6BlJdlOBNy{j z*8z;5rU;1krb99tksM5VL!+#Ol)>w<3j#7qrHvWRRynm5ZXvOaG7_HbjOEYf!na0@ z0$;*US%SF(fyK*{3u^9j92=_-Dfo5`GDQUXke#_jZMOPUKzBg`}U_TdM z%hc~TwmB@M|Ky?e>8u=}Bi(4d#;J(@3pqS+&@T8Uwq>#*Xh)v6TAD7tzGBsv>uUcz zr}Gm3)%<{-FJ|N6e&{QDv7_%qVyfom{|+v1^4*UrSQ5Ch=wn;VU(DjupQLN#{Me|1 zm?(9OEt%YcPpuK^1%4|J7Nm)^5XtyqD2*;?DikaHX3dx{b_`~JKjHzh`6?`xRt1ud(9X%~Uz`8eK|3^>pbrZH`3`wq{L~xZw+8nXeb3)z zXN@46k5Sd8AGBVh$rf|MU&sRwM-*0p+?`&b-v=L+2DJcuqP*ku#t(^y-ZEi}d!*jM z!Z?3FsWu!K|I_UjU|r*e{M#V#J1BqJ=rTELFaz?K>~~Xqt$B&8EirV$Pg;4x#Tu;O z8WowRFBEWJ^y&%avavJec4PN>AFiRBR;pIj$YcwfO_AsM$}6{P21BY4-dmJoogi`o6#0GFs82 zz4^%soG4$GA5T%>{GvQuDUI==c&T;=3WxcHo_&kH9!eTFF%Yc$3i9V0$wWzHscE_p zJq0di)}2l_p($WB1%uzlyWu$;SID2Al8@{CT?ci6TU}eV0h{xSJ(G+qp`|Y_UtSlL z$$cMOiGWLmrnj;P3;lB_yPL=h*w~&4E4P^QR@aEqwDd7LkH_{chWjiBycq%FsiRPu zaJ!-3<9V-Ssf$1$dpWN|`|lfAv`QqmO=;Sqg%tLG81$C98n_2Z7uKK zo}QWh)MFy}8Qm3*@ADG#>Uy)s_nP%E(3?xILeT@qJ+l1?*f1d#J+OQMd(@~F1(vc4 zn=DLruxjG%4jR#MGRcn%J5;U_FrzN8g)ns?JcE--BVq+ro+TYe;$usGS=3|RZ>$Z`cY{iuakf_ah;%hp)= zVr9jCjo4Bpni&XR_>Q4exIa7#C57M&oSD1DdD&K3w_qCS9$|Mnoz z5k`Zhj|c6sdxx!g$g=F;F?tchJ?axBfnU-MG^xIJ6@4d@YX5E%@)i%U=Y+xg-X-94 zeL=(fU{g&FlG$-!-+L$c{FtlP(fwLJVbUBLjock>pYeLv#LOP(@e9ybAlT(;k4mj> zgwB2xKJ5t2SsZ5Xth(xpAtHb9xlrz!=3Q|>wW_r|49mM8+LWzz=saEiEILY3^k2EK zDi}?ly2MmLQIHS&wwUCW6%ppsxVG3Ybxm-uj|Vrj*g?Bpg9tZ*HB*&du&Hxb6ICa3 z?QZPEf+<2&&1DhNCrMk5PV`vvr^ZwS<5}M!Behw)7j9lyX0f?dou`T(E#nC@Z=5Er za?WW@b-Vu-J4^Zxv(3JD21B!@n*UjWnK(mNn$jFi2J_5X)R9Xs33|}J6Ps(J+685+ zlu;UjMhxc9I(^kT%93o<0@|}Iz+uA=giZ@>m*)O+USF&KVcfDBn+5UI&7MHO5r6oA z&}-}mp)6`EII_3$Z$H_eA)<C^Cy2lu_wt*=uaHQ`cpfwTK!WuvT2MacF z*zi=m_$S&auYCJZ8Q4CSSn@E@Lh>BUoCPe64R3Wr3XzI6={p-SI;6(rf@fi>+wXxk zoqzphsdWDyxQa%-}z zSe*;rn5H69t}x$AqihO8E{Wvpkj2+gH-vZfuGJCUAEwfrJ;BN}6H#^0v&bJ5*+t2XylwQp2xMQ=Li<5@ecN9~7_fbDUQ_BR z)z(upE*Kfu^KhnSjhFQ2BPJ%|XMNeat?SexxLERg(Q|7Rb8rO`L-A;-XwisNTobg>FEJ@6?ot676G(}2pnJ=xO1W8|5PKMbU~3n;vH81u#l$@ zc{$(%W-zNWY~~CkCAw`^0J-?~d>pggveEk3-0c+SY_p;424h|VYvIB zLpwiicCUWs#^GApjAU3hVIa$}9ALv0s138K&)@u`_7Ll>oy&oHf~rUmkp^X2Vx-^M z)=0uR6p9IpSEvz*Qi2hsQ(^(ltw<%05m(UU(NUha#(=_mAx!&x+cUboGXA4?BsW7{@}_+Bl)`*dbi_|zT7wt8;P;M4yNucXr03u~XXn1CA$;V=WN)3r6j ze}*gl0cmfF%%`D^>WxP+E~86XdCRTDl7QhU65qkMhUfoZ!~3++74dv(0?7TQ4BdDC zi8Seyx+}8!{rjv3?BWEyz|QXY->Lq57iMegZM>n{5y35D}P_Pu&p%5MA@J69w|Jskk?mP!@yqwHMd z9Ok!LdiPTawIL}sh;2AyQ!ONTqTZYwqXVr`piP5fRX%F1pu7an#b^*1aSI*ei4VWC~KxEBjTB} zgb|h_lMP9bxHG`tCV>)I>jx0b4MvwdKn6bNhk$Y+$F*JCy?1z*K19N`MW6B9_*Mi4 zB!jw&q;n(um5sXrlvCN?)d|vn^hbATJ_fiDA^(^PaJ{|kLi1g$gluFL?2(>FLn?o|my6~i8c-qMhR5C)=P!^jVq zw$yf7SQ&Yb)dbE4zXO-rv)>!wq=KY;FOE*1vHZ8ZYd8(V!3r%0Fz+aeA9hs(utv&@zM`1>|Q$p=F#Bi;TZa z$?vH%IS+KwX?OZ?m~ejrZZU;Bej=JG?wCi=rG71MlL4JI;hyW^R6Ct8`|>2H&Hn^ z{<9b^7%?!VG(LcYL5jEfB?wXE(F+`O@1Z>bpS3Qcf0 zUemQB!XMqF^yX=S^;z_#FO4DUtnSgs_J@|A@(#XHOT!8p#>puVsm=dID%S|Zf(-z1 z81}v-jhiLT<~?7h5P1yuA1UjvUM&W2EOvdR@0QFd->%^6?vuUbfosbJl3|o4Yihy$nRlt z5#4Iy8}AnIhxz~J{V|7{|4rX6P0d%0`0?ny^O}mdz7Q^HFa5%nm*Khp>BCRB`UnZb`KB4U=vLlH8w%D^F)9=6(0cbZdad3 zgNKLI@e0)K%%VNPr#)Z~_~!5D0GK<8`GWG;PM`mDom}vXdii$eol}67^_Uk$oxei5 zeFt4gX5AHmDd|TOu)ATmuNIHD-M&HQvP8YE?1&d$McIr9QcIl&Ui;P0JyrgGNg3aH zGE|^l9Nu|x{uBY^Gf*qmeMu$EG}s(JZOT&>zv1PY^zOPT2^;GEDK>D%B}ff zQE}bfdf}exUyza#zJQqAfc3jrN3n^;tT4}4yvS}nr48A2O{rO(dP&!T7_?zKJYC+1 z!H&k3Qdg}$k{yK;3rC?+siq!T=4(8?Dcvr}fREsz)XIrBs1VZ-Tg5j&9D;2@aZSti z+n~>o|0fB18UD)3KU{EPlOlTS;^>pRT2h+cGmxY$bvu|Lz_l=x%97BjG78wFCg7z1 z1Q4JkoYH`6TT41#BG`>yB5JjwsHTsj*oV7+WaghE?GX=38py+n^mJ{lZdH@jOQVidi0`x!*db!Cw!sJplwzUnJTT zVLIVtwVc(A--q`5H$M$VL*mEj)R4<*Gl}U{e|i^0ktNr11HX~)Ggs66 zWgU4~Q@k>lU>Ovy+AT@V}8=xxm zKCOo22`i*T9+oofPohhiGGchc3UG5)S3~E8wc|%!s}5LDuc6@DK(%Cd{h=8R?b5gX zSWM5!a(2zPd0YNO?Mz^tP(+ZG{94*eE!bhrD@_AW z0n4Sjsc_vCE4<~m`{P6p=*o&Sf_Ew7%ouNQH`_(r8nE^#naP`?LkN46=K5;=4`Vf7 z8*zRPPP2Ch>}6UFz99}(fD&VLnaeI$m+z+ zjoq5)8%#BIO}^ncU^ZPZ0f;I13g(sYdABpSm?nhMf`_Kn$W^PL85iV8dZ7+d9Vl{w z5z);rT0_Hph;|Q*POxkqijBPXnW6;z5Y!5wU<4+WfmC>3kIYt3v704R110#XdR#wnjK(6?cEO_shetO z;O-|i=5xS~ru~fYlDtjTR<9hz)b*a65Bp+9-MPZ4DS(lRTrZm+iOqQ>;g@tMj7y6` z6Z~f;FY8&tB`=PwB7qTKkgFMLCdV<2(VO19!O^+1mEeX?MS;m}~93E*1^{CcimFObpKggo1=_ z+T}G5^?-~V5u)taf66GBW-GXm@P3|AI}>?%Kj902+3qENFMRzs7==nw@`}1(E&FhrtZwbXp)f{}$(QIshF(|xN1Gf~bL$^2GA8>K?Wc0M0 zT%m9$WzU_bB6e8%SOQ5}GF%Yw1(nC6=VYfZd)bd>w~$P$?^HiS{ny7e#k19+qp74} zBdH^Zh&F!iXJo4*$2(63hojEG(Y!>7v}WocA#knGY5DA6}NNtvXqUl|+ISkC2kG^HOOclG%}sPCcGRx)rT67@@8$}shmeoo}9?Z9jh3vy;` zXcLCK`vvI{hTDXKP1Jhb`?#IqMwAm~9ZMVQehqwS+06aX^V4}%qWt*vkFDDwBi5yG zC-;ZeIyQ-PrYZ;Q;KS+Exm8eB{l2qKvT>&;B& zby?lFSLy-0C8x4;Un*t0TfQ>dC8NckGeEuIc&itmY6I!W21zPYEYv2&h#8&x=JOMf z%`wOa`?Cgf8(l*hO^<&}AeV0s5u#R=G3s72#aayyn7lIr9~+q zF9C@prOL<*qP?aLiykJB{!0}6vVOoL;&EWS56KnR40!3<5`B5GFm0TNYnMu{)b4Oo zBjRSRsCPz8Wwt^VDsyR=S`+p=G*|t{lF#>hzXH$Q8`>lyrPeyY84vC6!kX^Yd3}UZ zSo=GZ#*QHW{UJ|P2mCdFN8?d>xjVx(`e(!XyIblMfG{Blc7#>}6BLG%o$%>hUEt2u z?VF-h@gRepv&^F^aA!i+$XPm+^m&jE1aP#nwE;EO1NabUAeqDmlujJ3838D0={EtU zI^YO|5+7!T1j#`!HIO&U@un0QY)T($SigI#&|P1XGOnK-sG;1>Xfdtg-ofZ-3Vi&< zmM9s0Z_DugWxTdsEJPyNkjjLcTh zErcS(3i=$!6U=#UGgA%tqC{lj{&nO930Lep+{#7506VE3=te&t;DdM*+;&EEqIpQ% z8sx3*nikxh1hz}jFLpn3%Xa@;j?4I;4Hy!r|4bKygbot`$&RuVzlRU=+l78Va%mCz z(RCMoZ*M%s^*qz@cy~gy5d8-=oxeyk9avKTny5j^0A$1`I?cMSs&|WInjn^ ziBP0D@Kh!CrOfrc;cO|ZkIJdpy*+kx?0P$g$4wW1E1$h~2tKCg;J@^Zr#HcmyD?JF z$Hty0aNre~j>A*Z6+{KSJVq!93;nx$1+*qbtGsCVIAA94!EM7mb+U38i4I;W*~r0K z`mIiV1ljEQk9#Hwpp=lV zLsHk3yBj4@LA?kneM_9a~9KGzRZ<|)qDvcw5{gj`OXn-?Pqhd2u zi2IF%5l(zIyO(QPOye|X%c-UqFCIJIb8~ixx}Gd0o=pKZ>Ad^riR#njNo90P?!UnmH`v$bApP#sEU4{ypgBS(!;)lV z}ag!!6)Ypt9F{c5ye8ZFMHg=2M>FZi(^$OI;=abNdiC|fun=J*8j2-Z(uPe& zXJNe4;X#?DlsD^(J_?5yfOR4=6%6785!jm%6YHgY)kzalXfW5Ao4YI_dbvV7xLt<` z{;RF%e%b0Qt?;?4m~8S=e|CTMoqCw;I>_}0uW#^2d1Rm8UzTq>cCGu)xn>@~Lv||n z*qUvPpM&Qteoa0eG<*sK@+4Z zKOwz~jIcUUh_%)!JkR-ESIlOlL_?vM-#oMK(Q%3->!sHZR*iv##7-&Egot#ROh=1G20TcWltZs3Ho{T&k9u#|u-oPm}bT9n1HijMT}l9ct!bt?{M5pw?3k$;@%?aGJVE?lqd3&*ilu znVma@%o_qapBSkNXMC3D?3TzZ8p=Z7cid0kX6w0xy%$YBO;671T4X*XlzBjLjj(WN zGhmyLPBzx+W0(0LC9%nCGecPAe_+fmeO#=16TSDKPRT)Qp7G{yyEsSFOLAuaDC!UEJ{AL|ZNP0|vowuVI;} zhol%f)r~ zm6;D0wqPYw`Q&$nUxsKDl)`@c$Gt;YfDj;17IVIzw){0okN)#rXg_UNNQX~ws^O2g z0C)kNtxARu77ATx`&z2bbE(44c!*{dPt#bLc4PY=1r1SnpZ(dbpLC?tdxv_AKfUT$q(Q)fBdk1pwxr%JSm)+LYhU9S0zduIrQ9)omopp|xtHWO{39yaHVIVF`FAw;FU%V#DQAMvC+U&l|py#lu zgfcL`5Bcco(G^eDh3fsS^%YIByQ#Wl14 zN#)4{qe__b*cb4Wn~1Odlo@=4JiIh!^l-8l2m!ua0|&9)m_2@l@x0fp<}=|~=6-<4_N{&4M5PsKr5r?n+`&ldBW9Q@qU zxE`qW4|FZHlp*4Xei};ux7Odh4eadSPkS_8Tl?3~TcPFU2_|$Zz}0EWjD;aBwI*93 zSOV2|@a`^VzhLh>YMtFw{K<0H@zM~T zpN!QPq|MOU@lmW`?KTKOZ58sdM!r~~gk(^JfwB!j?@m`yAWjZb!&h!!h~J&+nY<40 zKhm#wC>T)Zyw*&)ABs|vB{uY;GPAr#T?c$AE-n$G09KGVxn#Vx#ZRZ{!&eA7Nt+*| zz=t}=!lw8ta~Ur6!xR7IBtgW*my!eCjhhF)>TCLCSAN%)K)cJiK)>s+wFZ7Oyf)Ol zb0(#bfHQ4yOklv{`tXf?#RnPc8AorElYt7<+WEhY;5g=t>iU15(V+Sec$VhX{JlgP z@Q&?>?v~V|{uriLMrS61!q|14Zr<5;w+^@ZS>-K#;nw+12i1%Kv+#>$H+T5&+ zx4c0GAB=n~$yLJtPPl%nGWRs6HAzp`bADrev=rd5>d&vmZ(ThAA@P_urSEFJM4B#~ zCI4W58QH}zyGL;u?Eg;2UIGm-<+14>j%d^jOkfAixiM}53f&& zdyFR9eGhi=d#~FD^bTz$U~2Z9j;o~GL%&8`@Ej>*0{fvuboF6C*#2di#pXA8z-TrN zUxd7+)_?!b#oh(#Ln#xdT=I{~6T>0VI&+Qv72$P4)4g9HPZrGpQQTB)8BSED$2t%f z4~HAC?eqPG%rrgrGIY5;)P^lpFUn(4-W>Yr&CG&;f0|>mN}|D;mxN|4_HXj`s@5+< za#7*18f{4-te@(V$B+VcERx{XiM^tix6)!$Jge;L673eOBvs395>j;jRS=&9ddNPe z%KkbMfuh5?f(6=3Ts=a%3-M=%A&ZD@CX%lLJcdihy-pW9&3;6oX8! zKe!3y^*KnNWGLe(B51YitgF}Rf?U5D=dY9eW0hjEVtN5H`fz+UQ`eRG)t%Y$^YG0V zQaxQ>SJz}bzNs!D@0|(M{U1oR^9C(oN;f^OAeodP-UEWste{TX)vJ;WT(n9VbO<*Z?8MgTOTK&ATpp- z`zd}qU55etUWTWCTEF}{0`|;_gB8cgWT<(m@D5{@hZd-?KZw9Zwv!ldd<3cD4{pgV z3aieg1~t7`3-Vtz876+`+K~$t5abUF*1Nc<6m}&c0ktfx$nJy9U8xvq%e)fZRH`~t zkMn%{XO%k-XsXRi=xNNpyykxyOtzyHMs($sj8V7!5%znH&}VSIqPXN?!|<1v)Vp|~ zF^n&EVYU;ph-Htg?|6v|b0!!{V#*X+;!$;Bqt1>tB{63V*iZ+SC8T2KuT9zyG3q$f z^p@R)DJdnM6#no^6)aq?HZl4PizfA~y`_ewhk2I=>IjlKF3H(Zn*Dn~{OMEHfQrHn zCTo>6oD7z)7&T$+peE18^t7lQM|~zd3Ko8dwU!l?M(v=XcPf{i^~Tt?j>zbU&`1Y=_1N!*4X+F$-{c-{{#E%Y(p0YjDy$Vv)I z%1(^3SYBQlbi3ku6zZWsTa`DMMeVzi0loAv=HDcspv`1Sv%(72{GX~TovFaKX zo}!)LE_RRTUjZaT!jzcAds%s_Pe2s&7e5L0bm4kviwZZW2@SZyHa)pzb%@0y=aeVn zjC^XR9cW2Zq9#a9v1Bzc)EWPuE19=Lc%%{#Jc#N z7tqmle)5;y70XQT8J2v5{B)q&oqm@4#$=zL{(3IxST#)7BLd@L z3(xzBIjrUVgCe8Wv@10yVE=>=&9*x$@0S2Ab>6Lsot~SdR0_l?tS|pBuFf(AJm(?t zo6Y<-hMumoI`ji@eG=%_JIJ57hKSkX_*1 zO(yKP;ESb2lNIEFZ`E6PhTkCb<H~H@d|qLSoRnctaOg3?N%of2jAf;5@m`qR_V_z&EwdnYd6BIWb{_Xix|6yQ zL9sj3bBbPZe)r!feSS6b??cRNCRJWBKT+1D>6WClNBB%ck?+@{JE(gZbKVHsT&=ds z5~*Iy&ks@^Ep=J2jSS)`%9xob8{r&bpf%kmCCc%qJih4Zw&*9nte38kLwp>o9qH53 zzYDfz=^C};JYTjn8Tw0_)i~HX1C-IzvLMDV$ru~AJ)2#tpSN~IAD%~8q|it{H0Rv( zc_pKjwZVZr(LC$}+_V#<+4%}8(S}Je<#hrXn7o55D{}U%9fSORO=@XRlK+6LC=dSD zLO}#hi(P%qA$co{N6vT`;y@v;_TNnv*nS=>arB0&&LO(&oN`?ElD|f|5PXiK|54(n z7yB16c}mZS>s3^=TL+&i^HM=L9w@J1LY|+x5CY@~A=8}uzIU{HIJVTzuv)Bjja=Ti zhH8{?paZ*w)DdP5A_^1GHK^`lp zM-_zVnm;sEjBQaT*-hphuZP91j$LgJ4+sb?0l!}3=v~8x^kjUqciD4f+7rQUXby+%ga+pX z8Q8XY(G`TUdEL$2dj_6T(O85SUVv7ezP0A`RSJwp-qqjeGJ$3W2`tXrH&QDx$?yg^us*RQ6BY$iN+GXW;| z!L7sS{)r3k0M|A<@((&|5UH2D;f7f5`rn2y(R)W~%H0g!TN+IVMyX`B&b-0}s(%O- zz?jCOilEeKjr@?@*j#sh8uu`PlUBN+#iGzCse!sx@mKOr0!TnyAru6yPsH@>2K8@+ ziHu%^FnZku$0;#g2B$K#zkgRb%&8=ZT^Pr}m&fo-Z@KI0M5fxmY)o83y%wQ%QMqiO zJDd`dxNLc!8W$*iN)`z65~rt9h{${!nGve|=hj515TbB?hT5N{vq`^RTDaEwSUv~( z<=rOaYE1;30f0(9uK?J@Ihof)RrySS5f|i_0bujt@l)}m?z;hm~Ok6_hdyQ#P+A( ztUjdRkSD9%n>Myu9N-%-}`|tT`C=^6VnTz@<_4Z_RflFIZ2NIWF9G}bP z5Xb>J{QDO{38(Xq<5v0(m5GR_=pwMfwCEf7K2OA18Dyfl=;1MWvi&*p1zKmH2&llM zX&E}f5qTJco;Y|m@;rFPv8Vu3(*<%`=Ozg|EA=Jrgx&>7dm3Ml7xmkjS_%>3_lFW4 zTSBgKIx8;c&G1Z=#gFZ%9|bZWK4aE7sbN-T9Hg!eCLz0r$J$Y+%v%v`@nP{X$ox*Q zMK^Z4N{UZ5Y$Tv8M_H%&OOULmhI@ZvA zvaY6BWLrl0q?B}T+b1(Yq7CwNOIlV4C#WK=n{&QPybo7QCij0>D_8Pf>R%3}j}|1K z)bz<-R*Mnl6z%eT9=wW6FPiFL>NI8iZXwK?wGVKG^%lF3z^vG>X+%MYL9=@x`2su4 zLjokEZ-;Bkx~97B)R1zlocu|rbIfpLU&Y(}a0VhJjG-^sHZ5z6;x=JI^tJ^x1lqnZ ziWvNMGJPdzj^&wo9?#Uw(RS|<{JuOkrF>#MuWoA4kWA;*hcOhe{Ycrg*c3;!WRd)D z4u9|ionES2jg(g*#j8xZnSr%Zr<(J7gmGpj80&`S$hmm}gG8f6wY2jpHOUZ-dKkET zWWRTe(Izi=Vl}iP+c0}5Q5R)U5VoE!_hWM1fFNOQNN=$JY3L?wG?Z^0_!$)vxjbid zKnyI_m>#Zo#m=&xoxxRKBGZ7B2sjEbzor!U`(i0wt|kzc`9toiqo6e%HqPi6x1!4Nw` zL|gL+7eYM_T1qL;35Z+`8f*~cPXlrFs`H%WmUuga;2?iLWR=O;D`>Fs8H5;Y`U}}G z&DXo+e}|$u`8a_I^~IZGh>#FV{Tn@%rnFHSSx7=^J$6KBXSL--hxlE}8oQ@8TY+BE z>r4f=5mt_~Ib~8TGo$RZpNJ5L1QQ;vMfnjQ*YWKVV#VZbAPVaB5X+MA2Y0`3o;3+< zGNCik+H+Y#c&(rB!glDwxV&#}y*nI_#zuN82qh2ZK>sS=bA)U3k>0XOe66Qd#VYR| zb5Y$PX_5d>t?JIFNPOCjjHkK)jh30CEA*e#xC`blDh?$-#fI#ws!WX& z;-tuM(-n!klHdObkL7*{(CH;q-96a*cFe>aTZ+ttZjLujs#qA3>Fg!c8H}3Tt1S*{f5s184 zEbg$Aq(nVrla-p-I4kq+F4JHPv=~b^=+B`&z+;@6uA5lR)E#+MXi<8g)?J{TnvE*& zlK#~3V|ptq#ywnm56%mmqDc2@}n~&&!oHbb(P@x zu{&%jw43@|#+=lp6yJC5P?}d;%FoMuls@9!;wdu-%T6VxXfw@)jh4Y2HR0d_3;u04 zOy8kL$%<;`v{361#Xe*jt?uI8=`w7mTyA|0EhyMyVxe;I8{_k*rh8R>!E)dY|JP4I1k&L)E7Z!TMJ|6OmFD6sv;0%e&>|6q}BKbN7k} zUQUbN(`r~8WEGCTQbTrR51!Q)O?lk34ySiyrr zn=V{IvbIoV%Wu&PZ0gl(=vgsA)Sn$R2g+4Xy5M|P@l|0gKi~yuWmrW+eFToRLz z5PDIools`UW}@b#pws1RH*)z|`uAUYK`y?Uajyoxsh$K{aoA4O-#WF{G!8j?Jx*_} zuEU~po@j20)}A{|nUzAGNE_ZMqV+EW9m&7?ehi}u%&IM5O8SPZ;tfv+&TPhwp}@^* ziiD*J_H?1tDKowME{*iz|N0?Wd?hqgt@K;<0$w1^^Jhg7&$mCiBK-f1S?#c6VQrPT zx!{c7bgMa<(0cX>`ACFI`LPJ(?4VFJ4)Kg~Dv;yI#q1OLG?^vN7dM4_N>5}~y1ssU zPVommS5~F8Rx4wRMc#HPo{U&S7BjT0KB8sgmaZ$KzXyQ&Ua0-K5DiX|iokwr$^BH%;~2=Kp(M z-Zyux?>gFNf6m#5Q9wp$=1Myg90gue?y1XS{JbpmuVx;VWG!1Jos#}nr+O=u*d3~8 z$YOOySU&^i!b+lS)so3YC4`=xZ+fDTjWmCmm4py$E-3(Z;~Z>ROdpYm3I{N!1j`N- zY&C=Y2uyAOf7bS1zIAq;BvplQON8DZgiE(bjwZ!R2HgqoYbHQ}_ZC*8 zLxw2ulRDPt;odJ|ZlXBTAtFzjwRIKIn^KIY9vsz64!(NqWrYn=@ejyCxK|c3wRuKj z^j7eshxi`Fk;@}C;AyJ%uDaZh2&1i&u_uQD$Bw)B9Y$bNt{0UObLSZKt6l`{5Cw`H zC5t$6bckzY)sJZTBMRs^+Gj6!lf1(KB}sG_jl8<B~DB^3OpMMNIs}^AyB&!!2t1 zLHsSOvmFose&m-zEHdg_r4Ji|u(v&vj*&@@Hb2PNzNGz=-X)piMkYufN$RpDR}@O* zEu{^dB#mC20(&OH;EMKEF_=9PMn~N@MTx{-h;k}` z81k>`X_MjKOz}|P3)ZYD$QR!pt1BW%kI<{(6&@cIolTm|Y&5kS!?TU=OzU`dP(Ml#> z?l-{d{cF)SMq09VKkv{ zgy1_R5GbYdw<>iRV_C}cH23idhyF2=s@A6|VT4=(j$0iKDN#JZ{isc!vrXCt=?HE> zoA*Td>{Io%#FRNfJK&v@c0`%3{kOiSDco2dz8&g)Xjmb?Np1|W3XY}8-5Grc-@--x zJO_B^x)m#$9lGnQm14FYqvgf+NXQsVVNL(HA~@q%g%GLGKLMTfR+5o5)Ets zQCyn}F?Nv#PHL7+G7Sw*hT5sMk=&mY_l^#d%%9|dBb+FkO1^kf-)|~2RsF0x%4wn>9NN+UhgP^QVp@d0b_%U zvqiMf3#JV0`W-%2Q=?W+V3D~$!y0^x;BXBFVVmVXrUP?RoMh315 z*g!HqUzvAD6(>_UqWU;j3z7PB^3P@#dQW`r9d4xu2H~^=nlOYIN+6mA99Y{JkHGT% zKbx;V8*kG6gBip?bZmjbRH%=H?Y(^d6L}gPHehCI0DFv)g1jo9EsI?e5+;zdA=m&p zNI|Xo(c&0&E}YRYx`O^lWfIVqp5lcdU4p=(T_opna zH_3QUYNNo&R%vQ7^-by~*WhrPiv??xiMxcEoLo7T{oF6Yzm`Z^P7NMjwzsfPh@Azi zd6Cq{(TFSdPcK;-#I78V`kYSKxfHd-vT9AVJSwcLRujeb7 zvY0%mKT)(D;aD8wi{tVfgW5lmC){8XPdj z`mWuy?D#%ys{Q<6G!D`v+eK`c1%&U6MjWLQMo>b(Me-S4y(oB0I8RG4@wpi3rg@Q{ zleAvf%YWqogJhNEg_1gm_ykkyQ0H~|@dZe{$z=%0Iw&TItc9pGk0tO5lBb0eR0k7| zO!~s{#DM#ShpV87_?+mst@pjE7r3y+V9LUvGCm8RSaCRvCW)@b*T|;s78+J0v8GI`y14Gsew^1Pk74MAG zDk?Ir!Mk-L55MMff+Lg_%b`_J^mY#95shBOEicJ_kp>o6Qhl=2&wM@86vD_pc5-}14Y zVN3Z{_i+;>b)QTp*C=2##J4BPaymR!!}?HisjPOwKbl1&B|3=Tb8zYZa3nzNcViJ+nP_`8m&+jAwZAItnDL>JvAg=tN(p#0NG z+Z&e^iew<(@rky7 zUu>D^UnmSMlaeMYOmY&Fp+KJ(m$bs|3j@6_8G{&smMw32dA2@*Oq-bdgx4&^ z(GZv^E}u)Q`QVd!)!ickHWuWh7{)BA8(NV-ey+=KfmE(_j(p0q*c4Ybn~9I_SFOGU z5`(#kT|}n+->M`RzZRIf%rS1+)E{=r$$O)}44-7UhKHjy5{LON{&t0GL+X#=jOk?? zVocfnO4T{i4YL=!UiYv2=Y4XSL;na@Cs4Q&sRXYHegrS56p^mL51e_iL6R=c$gW6HFqy+;53TX;rUW zsVJXP@G-_^FS|nE3crGkNuSAFEF%0X8Bmn1S9~|%TFBcD{z@~5LiVLKQs`V)zAXb^! zR3Tei-!zqi>?*%FMRt$PtfhTqHE!UogxilXuzB^jHk%E`>z&0HX0}gGm2C-S=v&|T za5GR`eUZ`(l6t=sN;wRNJJ^(r+SxOQb!GE>5#Joi>%HEV^pWNa2wwz!7CcavQ^bVe z|66$EP}8#yvh1VEnEjOk2K)yo^ow67Pyz-Byml9LY$&yR5wA-N<(31JWEf~i?|+_@ zeFnI||4yh*1g_5lG$a$*seN4T=Lx}^Gs8(cWQ;gP5qNw~nq4+ge%*+qPGzeTe$~cI z;DDoMgG%sVuiGe>6ifdDcE6M`H4sD-l++Sw5`J!)SCDAHXc(I-R=zDtVFFcGoWYZN zHz;8s>``)Kl@bR>bJbk-Z5Ge)YC?V^O!E?4=M5>}AOEBZ-0s`JM$@!G1sk z$K`^FvtOoC2LB~j`_rRE3KL~Zg2Ap;vP3z%Yg(+E*os>pQKjWb*ZauIG&#wt^gRN} zysITntyqG&OSuH7_b9wrrxtdL2;+IR>}g~97Tv$B^YJSivb^AoT#w&3hzl>H25MR4 z7qu~2bP}Z01x&84j+eAH%DF_mgS_=>-06gCnmCBs168Dp)S^(neXi@4Xwled`$9xj zMd#jC=vzg;k(&R#ExVd>2f$4IPUi#R$H?L@T9-km7?Fx^vPHc-MB-EMuXFp=BeaMa zxBnUc{{s#-mSXc6`2!9-)Wo-R6`%x!aQzYkXlCqS?*NOi=pvN=l*-WgNRfq+kh4_; z%V<&%Gkja67UGr5!dPN-LXnpGK||e8f)Kn&=t>L#{^A#*Rj@@XYIct-M$*mbm%DNc1IV(WP>JR7Wbm=BB5YeojEnuP=|eUaBQw&}OovlSqGAv=W>4>_iYl{q8Zv7c zc)14uD(jtihLrTKgBr9Zt3+6cxeccl52sF`4z|yfCsO)|v{e9k?9wls(E!*WiW+Eq^dfjnQ-qB zf$gXKt8b2=R&yRSFz~y^Vk zXZLybPqE;F87W_${(UQ@5t5i(89X|yCT~{Es!J^-DP1JhLHSP+wD7rEIGYSsv+IU^ zZF)3vLb;AXDlxifcC2T)0cfH`1ueU4`c`ng7(!oM7~Q9Lvrt#e!ekI6hXvLSk+~>m zvHbfGIKXRfnzX2q{6B<71WZ^8_y=6^Y8RhrclVl%9)7=gFm1cOJCsfM}Lx=#OH6rGG^XEtQBkg-V*B0hYcw$ z4u}3(Bc1BgJ1im{RV~u9%kUXNmm=jQJ%$91A8l*o59bK#!%$dJjBQYh1^%K%!1RtM z;gx6mA8SAsMZ!zMuw+t)?qZ32Na zTQ*(LSEgZsD>6kjqJLak-GiqS4u|D!h>r02N9DoXDplHGsdOm9|_rdZn_62s!bb~h-~^NWVdrw>P( zT<<&NPwH?09W^-d69qC!bOSyR&RiBwJeFgf-tC@BO`=H+0hU2KD;dRZLJ1g+x7r+gmjJdEGVl}3!#cF;i7g{UrqIWv^|mfudwhHK?Olcw^T~lVpm^( z@!HoO;hwI!8d~h~i(%0t(wyl3tk?hAq{s@{AC&yhF$sY-F4Q{Az)yky!(`rVMKI2s z&=F@;SoN&<4QhN2G4Gm@jtS44^uVe@Zz5QHt(3+V9&tTm=Rl6VqQOR)&xZIXa(X^> z7;F(}1asK3e7L?pEs3(xtJIa>?6{IubP`kp{FDCVL}BOPwEFJ%{F1G~)3#KsRo0EL zwhHkdEgza0ohqyqTTPFaM35_!YJ=pl$eM(9jKR;AqgADxqKhA34d|S{+Q5y|-y)eT zHWTDE=8aQkurEg{ne_zml?VVkfG922;y)aMwmg*DfBf%TP+x|3H2(F+0lsI?)(vni z+%}dX_|~=*KI((GszzlHedUNhD*YL#>~;`yDV^vOi? zmMFBuI{CE^ajIImbjCH7)gdJ)7f9-lT#!jnC(8_2hF0I;@2`_=yxnh!4uy=Hh2>4Rn-T%Lzb2qLv$0YQ(Cce*CLuuUi5$%20+ZK@{zH<&Hz|MSde zO;d*iU=wl(^h-Q1B?#_3*Xar&R`t%4+Zus!4K#wu2=Xiezg`9t9ykZc=WGX7hhNu6 zuROL80WuJx2X!)~A&;R*pYFpoNy>1sTV4C*zVIQBDBsV6F{O#+E;)6D1*?p3?dz$E zJO38FzovXb;NaGr|AC#vC=%&|7QPt~4BD+!AfjrMTp4rF&F9Npn?}PZ7sFU`O-VUW zZ%KaGPaKZVHLy^BCJ2hZ6aS#BSewy$keNwyTtDms8vAenBQtFz{)ZPqXjv9Ks=?U# z!=4{Fg_(Z3K&~gQpMp>BDSVcEwB|x{JL*on*pc^y;q!i>Q)Fgch%Np~h6oNDkfk8e^GJvf?<6@Ryn#bFy5c6=1bmjID|ysrLhBu0t&ptYI${IU z`_sRGNh#~l1%xn^=Fh`YR3cmo)iEv$QtI^v5v?eInGimcwr!ue4;2ZN+Qj>dSg%->EUbNUV@dwGXIZ$t1gCbk;&wwY8OeHtT4I`$KA#-HCw_7+PXDegQ}KzrjMAQMpIEK`RP&)I zXdv_O$KJ?`wKD=k3+P^xWtZLB7Q{2wdX3oIDE4aCVgFHi>1eq;<>&QuP`cy+V4^T9 z|4WP@Lfi*R#M|PdGJxoR!uUR~jm7`fffp_E0CXI(seS^PjYMIRTL%f6G1-B1qxz>G=|hg7~lAqX$?CSBPGwB7J+ zFYpHD6X-_5x&}&n#AV7KB=tXWadVn>Scwh$2n^~JXqDy42o}booNrH0SKp5ae$#E#m>$Dmr4&S9HsZ{jqG7rJ4PyNfGTwi%&O;3)k5CzXD9%Jsgg;ohwe_KKV;VIqNvB!9%hLGZaMt zd&?&~zjEa^ef2bpD?9brH+?XfO-Cv)H#Qb?5E}i>fa{5ClIr~S2{zlsr|2IyLss)} z`w3M{tK?(hW{RlGiB(K>4b6QK z8hOeByJ1E^gr`Fcj~z^_`dy{OPlI?CTw$R1kha$zSN7yv0P3&Y=g=mi+wZr=es}rN zhvRLR)C=oQmv?R4TF{pJ;`Gx%;hvNV2_g;pGCQoQuFRkEcu zl=d6V4IgLn4lNsOFEBb@z>uZm*36otnvPDg`&|nS_ebIp@e0K-;--8z@M|%fF&lP#}lczeMQkpIEQsRo}MDO`W_*&nZB zDl*&gATB3FFY6i`UTYuYiuh1rVmjj59Fs6s1<{O1l3Z9~xNCJ&^I3^_{!wYG%8j|r zaUk(3e_THH2PU01`T;mcGMpSEoSFm$3alfnb^c4E-57X7^*71>UNS_$*C7+qpG9-z zQ;~|>@lp8nJL{pyy}Qv!?%bD-ShC2gg~U5d8&iQ&kpt|{p#x5>@6_CK8hb2S=V{1=J;M@-7Ezk=NR(wgdoU6kK z8@fcE>Kk#-x*NF*_gla)jb~a$VE+-p`-YIGyUg@f{SUyn{7Z~hS#A@Wq0>h~vaeCT z3Hj%$f&j`VI34JJIcBp99yjMG#rgV;&KXts&rK_7CK;|f{0_kLlQjb|zAaCblTOM`CJheCr8NGHt8GJJaLOrh2X&;mVNgNVpQ zGfeJ}AG!Tq-&aXX!AtNo8L=VlmrmHJvxkj)YMjf+nd-8H2Zm*t`@9&S`PE#_&$K0R z2WHCBLx1C2u*eRZ-egPG&~S}TvL z+m_25Zf#9eO)6)1x(HM5rQ?kN-#&5%6E7w}Huf6HvS=->f=8p{((}R2@7A7=IAjE= zS9RaX_&u1fWag|n6j~twtk&zdOB=a+{PNA$7`al-K6ltw#Nc9XXa+hKaSe9;@Ukyr zV`1$HoLFg2@+-<@;Zk5g=U6OXVO~CA+2T{(?}MF?^q_89OoRQ=_S6u1Je;+%wdmJo zuk1cn8!R>!AdhRd&jHZ27Y5y5XtFA4oM=Ny8h>j7g1szLl05n9keY{_X^a&rbBHmU z{?U3w+vp1JX0Irv)eeS1MMplVP31H>5>^yBwo5BmrAcZ3S>i@5|3-y9pi~0 zH9Ksh?fT4P;+z!K+s6(Szxt;}J|YTeOotztU(|PMZ-rl|&UuX+*7fkVTEVe}GaI6v z@PW+4+!pR-MCobj?P|czpEG#QUla9RRbP4e*f{33k>-->apCjI_cGdNC&spCr@wd6 zN!Esm(^I%3K_=lQ?~h9_@6XE0UqeNIL)@=3&b>cK$D^40zD%u_@^}C3oip}kl2(}i zfqy`lOI*YU%?>_o9%vlq86^AcYUcfSQF(RMYUUkHXof$#e z4|=2B=U86y`piI(Z++KoZey%daKxZxu?ut`hyJEWTh7js$sk|Q8H{2|O>S;=4kup_ z;$;yk0z}T-pYCT28lfmD7Os+6HHTFXp6KdLa6iS*6SVajY;c}+SfVWExoz!8)?NQW zJU=e$|Hk?t9_LO8G0$N}<)}pACBZ$BWS#_N-%`%AtJ7I~Twat!KEB^tQ@_x` zCv!!IZ<=$K@khvCP4JA7a})&79g(7K!?9Wg#R!w!b|PJP5kAt&+ew5 zma{5BWie=E+T8XNG%%mYT+ekWw#L3-@tI$8tK+(^Kev?9UHGT8@g=-;OV^FcU(m{| z@oj}yJ-}+ji;h<;J?rZz~$WH_kSdG_eiI!>DVJX)}_{MYOmfV<^$j6GFy3BBAL2EoM( zHs7MOMKMV+u`n*TFOnk{wznMo&8}$A20p)~D#$QN)W{6RT8(zvL6VG@ovyOwBx>LA zeSfzrf`AiKy}DHNuz>kICv+;~3L&Q)C;7&5a$oGeXv2V{YQcBt*8lIzP_cl9@OxMh zBdT=T)Q)Oij=2u_M7$_0`*JWsALg~A)0Ox1!v z384Ak#e3ZYdSS`G0g`5np#7cf=?H3Sn#5zgxnl-a1L@pkm|1Kj#4|fyW2gd#C0%WZ zjXMp*n5vBetE(u=II`t&+MX>*IpbVUuyqh^Ne}AgR$) z!P@Hk)!LEq)3}#!|J%BHcqezw99N7E;{^6hS0fPL)RUf?X{^%{Wy1#JeT8fts@ zyJRd8MS6Z}9y00PuJDyUa&rbF0m(Gn6xphf2pS5s8eD+vZzbY@12HFXLW{9iGY&r? zAuq)>$jh7Pcg(*p=k~k~OAy&`XIn6jqQ}6@iOg#^Z}zm5FOdG+lM`;!eeGdgCVa*C zk|7WaHEgoYjw}jw{e3tgB@{(Z;XO;QQQb)Tu2>w|r4WB7&VWbFgO{^Kf)31mq5p@= zMJmoHrO>D{{ zwwV~1QuTUM+uQ#2l1QH=ykVsu(lLU*=4j7I+f}#E1@6T&_3HrteZt(}`;+$AWvk#@ z`VzBI6P_b3Ai#1rn5HVi#j9J7pW9?~GR)lX&)m6lyv~cxa(rd-`yOzz_~LTTm?JOn zp>?C)gmj0x7(ZumV$PIxG}{*^>v#!8mmr=Qm-JEXDb@Hw=soK0#dx~yI??sA$B$g^ zMQQ3>T?U0RL9w5=P?~tSFT;SZP>TE^ENsP@B;`+u$CkVl(h{uN6&!5+rc~&?$Qi>>oKR1i z>PzN#@_^Ex{@)f%m{V}()z5rH`4pe~?)Dj#rWqQ5BNkg|PSD8n9-WlU8t_zO(2jef;gP%uS_uOJe!+dBa$5AcX2*lXL`TH<92Svg zU+KZ1DRhpms5`Aqi)j*2<#cSDnCp#73y8Wh|KK74l1MbXT5$EPKoYzr$PFivl?;9? zWFU&vkrhD858R}^m3=zXJB~S-0F^MR8S`#iOKId9>mz=Mn(JRytnOpY{vJfk354IX!zEPgA71W}`(74`BCXqZb^8r`{YISKPw4P}+!%dxhWp3<>?&TUD9mj}TU#gAS4 zc>z?y-vaYk+NchQVophUXu7DF^J!I0D}0yWWQ7g1msfo znNkgN9TKa(R$F{d6WYDr0wZ}JOZZWqo@G5u^*?6=nt$s#>Nl1**mva2GtIwiw3koT?TU7q%_PGE(js+(D`w~rVbra=3 z8TVGp#Xp9!QwwVBimd&gSX1BU^ii7CUa?Gz(Q|J$7k9ztDH@F{vvH{AnwY6AJ4QG| zkG59BYpU)rgLysY?Ybo)JUG?Jol>!z4UXOvBc{`!y%3RABjG^EjY9zl5m=5UQ0c-9saY#O{{Vjr|1gu!6o(Bl2qL2x>eJ*^ z!5?d;zrCCgt#AlGu>mTAg)Z!Vjn{`EiQ{5+J`}FbXb=`<1Iq^Ac-prAXR3!ATWHm& z;JpLqHHAQ52dN@-$sBUPkXBUZ&v&Uu0gt-JSN$bFV0-FrF^spsed|vOlT2HXtvXes zi(wZ^1v%A0VME&Yc6IW%eCWo(na{7-QMoFG!<6(%i+NG{u;8R7IR8z6Wd00R8N2&B za$(EkOtr!sv}_KNM<~hKA;}l=X6^afByd9s5)uEr&%X{)8nnv;(TbUm{^uIJA%|rt zv5@YJ(^S#OQr&gNsdKfXd!=yhbah^$Da?nJ$$hcyXBZSUN{E#z8OHfYUPa@%E|P)0 zuRQMcUtuA!ffihLP_BtLrm|yog8eRe8$(9sG|$fF)Ji5CDCabg37X-EQ`5;Z@svy{ zPKFm}`>WAmRcMSr-YP-mNb%GA3SA+&5}>#o9w7==!tYcveI&uRDX0478w)Ge@-2MP zvzogw39$CrlQ2G$MY)PU18)Q;&7KXg5s1BvEtgy}6kw6<0T5J?DW9Xzsj6o6=*SxENw*ZP(>5 zsw#`J|E(8=|M;4G9o(~~ZJqd4TE&0gzEfME^DU^{P8k~bm5aGNQ;DZmFOj1gWTG@Z zNU(mRlhsa>bMfUhLGIY*k#Dh-8Jxtx1lHLU_=c03DelQ`Mup0@+nwIEce|(DPG?cj zWx=WObAcp<%Hqqr_0pyd#G2wcTM_c`KoR&2_Jyv>RWEQ0g+-YdsYsaKjVVLblKZ-_ z2pab!{VwkNkaVaD9-S18{U0&#-M?!=R{{yb4W|r|W?){WfgvS) zF*G<2(H)=Q4~FaM(v6OlD9Am?!T>Ba2^XTvrAv2E2->OI8_@>|(?L2!PotTjL?-*a zXW1DK@nw9qTE-jv>Vv=B2=qM^Td_ggQ4A3zNred6Z6ybEI)r6j&uuk&45}q-?@{Dg z56`}ImQz`EuSRtgB{uR818fR$2!G?89SDUNYkLEM;q}$TV@mGK*>hvo0{9Rp&Z& zTA0^02uT^a(D|)=Z)9t}Olb90Q8IqNz0VW&-89{@Gc4epp_~3AbBExTa~k=x6W@wH zQOw4UuYUp^LH}eY@|+?m&`5wWTMRC;<2}zZ7;^=;6C9O|93qaP3lY)rx>}bytinDA zEbfgZ^Veovu`uC2B3D^WLh?7ZWTI;HJfV``rV!|o+(MQ8tI7fmQbv&doUAxnpzYIP zS+ceeZOV7efIqikp9;Ju78J{sX!-_;#tSX3YM#W12HX28DtKe|oGK&d?qKw6dU`k7 zYlQvUj_39?cb^fLML(vty@Juc__M5* zhrRX5V#J^nrqVsu>4RG3osJL?BoI?t)%jBU_YKq2d;6v|x!`W;VROav~z>XCd;jW+Yf#Mh=hcrS~StAci zuQ^NlCrB^W-pO>Qge}hmoiu+zGAnN251-fTn&Od|K^%7Krlr-Bq$1wn+RYke5n&xP z^kJuVLCbS>lhjx2cMP>Y?rv_{bWpO;6QEp>ve!sc4Dp>MFsB4G>i&#hI_2u?TAqF1 zU5KvsWqQf()-QsuPgTAJe>=R`1d(F(#b7UHbKBLFHP(q<&E1uPt1@;i3w{y_$!}|j zAP;y|kV&6{0)9%Lt~bfWhwFN_xrvE3vtvsXRxOen4lst}B@wq57AXF-2-@d&-8wQ# zz<|gO^fg;}YhGJC&K?^r#QZAZ50b=dx%9Zcv7QGZP0&p`Gbwa7o0kU&!1Wyg81onG zA+f(DA;C2HtYjCBX1Eq`MA^Eja?y=Bf}*y)TR)jy8?o4xBI4)$t zo{RbHjy6O6!^-ug%PA>XLakvZOWGjdkPShtv}3uBj#VULXPStg{tj<$YD+-XXIp+l zd2`JX)x#T!55+t_>HMaP_O=^M-2-TOLYTYZGqXSsUKd+4x8Z*vKISf*6aQKL`O3Q6 z{-kJWAq;d-$G~rw@HO72b7_Jp{S7An+LV;&{_J`oNU412`EV=|r2e&zj7vS}8JgX! z(?QjugyFY*#Wdp*>YVF*^M=lFN2~jiEKY(?jf4bJ=!@t>rZAN?7Uknm@*!}H%?W5d68cE6XC8sX4y!9O^kZZtP{ z@8RETftI`3npxe?UDw#GszETRP$a$%EH8*h(Puw&<7>_Vu^DD#@(ZdejPq*Dag{81 z>^Ls`Lpb)lCt0>lTBS7&`Dj6lN^rZh;=UIozJ?ukYe(Xr0oBYr%L)Q-*97L^4A*@A zg|XSLfk5$b0S&vZ-ifn2U9ulp@^%=pKaW&2uY`0xO?irsqax`O63JXEE9xc$D2+6; z;t~<_+*6`3f0k^+Bt;5%lzD)p9QjEIrZHLtI4(?PzVE`}cFuM^stCwSB!V!)Co7=@+|94=rhrH3f-#=+xSUFyPN^@&BogPXYz+R zzLIS(HJI!k`E2I1n04z-Vm4=sUPjgfyu$Etg2Nm*#r83cQ&_(uD7qbMV;AE*r>XXi zMA0x+?Wd|6b9n)Y=vC3{WehW3j!Nvf2!L+_=Dh5fz*?-_=_Jy=uf;#_>^zP0CH&S* zyMg)p#m3DtLSWslwBz|3;~VZBkCT+&YJe^Q*{cq}zv|yak*{KYsKuPX`gZcCA-@dQ zLv{_G)HK`8<#4l*%M0@FtLIu6eK&t~b=+xwcl$oem`UKdb^Ujwad)&I^hdWs%`Vs1 z8uf*ZJo^xn`~ZDikxU}68-Wn&ROE=wPp&Mjl$|m7T&me-g0vHKL%tl&j^_*?|+I02ZH^?$+dd!kH3k?0pJbhU~Bdn z!B_9-Sn&dBoiI{tT5V-*YB7{B>RpbNSY$Qm@WMS0)c%N0*e@dC-Lb)ZmNGb9llwlk z_r&jL_yT~0JXP|m8r`u#co0f>&wR-7db+>Q^*Z0(;k}(V&1E^JB;I$e)ic|4w?1+g zYL#-a`DRrW%}sc1^!3&1JubZ7*ylDc)ku3yarxv{X)DolI{Z8bS{%pFuG0D>L1dtE z-$BejT9&LNa#5)A^6#{j(qm-v+-mVuuu#fXhu({B@8l$vyegljB`)A!KyFOdjj){A zm(kb6zvr()@w>a&-H+)l%{pD80a!b`-d3$Y3tbg`br)l1_kC4=xHoopq11Wd?b$4u ziU7m&eKRhlteL8iE0&y<8_IzP&8pP7+8ba9A_I-MDB&ZtY?)7oL3ca09)b>WNeO)3 z^bL?WfNpp9${XB|y|_c5`If$Qp;x+P*6-e+)n!Fub*KsnkMyr150eO7sZtZ<{BQz! zat2A80aHgYB|-8j?PhM`MV$ELLb{{$kNs^j%{mFz>ei0i+z&B{Q>AXr1!r z>fA_Vf8N=P#B*FJ{{E%9Q8^tp#lwK}Wnbz%q|ussN}YCozY zKaMhKTyLxK<)^&tikD;qyYAsy;X61Klh?il+gtvy(?{lWcU#C1Go$H$&6Z7WY z-k2-fNhWD{!R|Ju)|dPzknc^-k6u$&@fGgDiEw$RHCk~^+~sO;vA}sl*D=UZSj62eYE*(}9)q6q>(k@-al7&SK|rz2>yh1|qq5Ov#+{ z-7zX_lq(d>!Bosdmg9oRAhfp_rGtkUovVh9ve+DKW-15gvDB)`kPTB;iS4AwTWx;C z#8OtHE5<^Bqa4>JD8UXTNL_Rq13F%SZbp-SmN`$NI>g3|TW>oDqyj6?IY*7->VX@r z_+9FGU00R8{_T~9$*1dD@0%Hwdgm*kyXFUhdryQp6WDJ2u-<>PSnf6R;e#qsOefXy zw|Wowr{{kegGU@A#%fhG&ZN|s- zYt0e{Brmpu7+T*(-^Q(n-x5fIk~YeG47xoVJ4f$y&-T~h*X2UlrN1~Tg~U;<$xe@O@H3ct{9g7f9A#9w#3#>YdM(bNv^Cn!S}rAa4sMiR zqpdEBN;ZZ~c!D}@wPR#GVkkXk9INU{<68Dx!PWDPy`Twnz1Jjtzp$k7iyk3nYgv>y z&}%Xc;Na)dox<{7=>hCrN|OD7*o4F0x}Pc|-#UA?gAc_gR@7DM$~?D{MzRIz2I?T#u%{@yKvGlH*Wi!AD`K2Xr$#5OUN=rjEHb~ zQzHw&OfGrR8ohdO!LmjDgi-r7v0`GTR>M%* z3Uj=A2D;ukTz;F_M~=#bPO;3n!y(E8{YIlQq=CHcq0W5G@_BvWLtwhwze_N!G0zz# z+_KE%p=ymEHJbr+)m8GF{}ePZ=8Lc1-tn`)n{{z+uJ_?=TO}ikamPEOp%-KKHE%3& z5OKar z^Zz(+PWeJFS8owQ1{yq?N2V3yIVqprQ;kdKbOX$&xRui^*w2*U%0Dk2D7>q1Ph{YX=@hIT~CdRuR}W-sU-NBM;5<+7#!++$KIU(7=QZ zu&(j46nfvSQ%#yCT{N$Fl{)jlNBrYGROlK6GsHURqlWJGz4^%ZpcS98dmpY#Rn_>; zPj8yQ((TDF2q+Ytg!lxPDl+rI*4H&?vMZMDRKEx;v2~7HCq#KczcAi0w}>`sz+3D+18cHnI5f5)bU;hG-Y z=Cn!qF({eZcAohv+|rnR-g8PC?l9FpCBW8l8oklHK3kT{2vFzII6)R1aHr+Apf{a5wArJNV_=#;-wm1;8oGU-wamPD%zd*7nD>7Gl|X90ul7!N?HRh7 zl9kR|GWQ+NANafcPwwdazzbWixv_znaa&-gH{}y+Wj?t?o&a2$GjttVfdB2iz5nmF z_LHmS6ke}&t8lJ8;6TUy$Ma8KRr}X}Z;{q{=V0xGWP5NHxrLm(G45nC{?5Q%w!}j= zwu(R=sP(x$jb|)+o4J{-UJn%ax5u3fSi zxy^Gsjpn1L3+w_mYDV@=6_!T?`^9s#@-}A;yKz%lHF#5FPF5|$Nrsk0Ppp);Jan9qNFbw(Dza^F7L zvD8#ag6BXLkCP z%HdgYEsn1-m53}uc`b=YfX=^UA)-ZmUC_fO{rO!$nn>rldvc`&{SNLE>t62w77zXbcwq90p(_~iy;^mlRV_K{ z0lF?~1Jl*Vda*M@2!K4NqYFl8l60qUK_&%m+?X{)G&K+JMX~@CO_ws`m!+o?m%MMtGC9+!m@ywxk7%j!>mOhFt;>#H zaX8*y*fY_=HX0Pds?}m!?dBHKij&$$nhOXGx(M8N&gIa$%4I6v{Gp&6}+ygiL@K?LP^NH2L85A?g#H62Wmt@Rm z1$!@dfAy8#fBD2JErZV4&!j${SS$bQr`Ko|{*PWZ|Ln`tZJA^Sg_`n~r4#5hT3}HZ ze)U7kANzVQD`)4%Y&PyE#D7GHmJLnK}c)+4C@JKIUd zRp|$`G@+%#?GI+}{bJ|t$8$-$UpJoah6?NUK#^B@$3xlg$7?jnzx5?^moG-cx&3!P zw)VlVcosapxg>&q{QECz{n$(A&lYxCtxnIV0WI=ylDX%x>~}u4`pJ9yoUt&@TkhxO zDXoqzm!G+R@CUc9z5M$64}RO+^R7tG*4l@2`vb?zfBxf2Fo&ZCKQ~N83ENKjV@lF}gRQ5}$7Lw55mz?6>=s zT5sqlR*SDZntk#c{S#~U*h;}^?v?{?Tw=R;-o(vp68*Z)7anIe4V+v!gcT% z(f|xtE}pNCun2Oq;!1lNE_-8^_@#7SGNm}q;!p+-O$7SpfHmi}My>wcGIOvBO#-AcRifl_he3OChP1M(^f*%orh1A@4U7BzrJc=8({~lF;e|_ zR!#L<&w@OQdb$FIZPpF3Op;}h6sVE0N3G5B@vSAS=p8WD+E=q_%RMbyWtSa^x7XV1 zH4QJH_eCPM7JlwH`Hxo{sW70Op|ww;bER8cG`%2f&m{~Nva>`%+;4-aj&e?mR zfjHGE|HEIN?howiZfcyBwNKZgKJx>%in)EPQ$c^dZbUG(3m7{k|vi(oU?}dhld%>|{Atx92d)V9%9~uN=$%=(FvwKb~d9?D8-N zUolhUWZrsT|4q+p{*zZM(29f%`((G|OtW#@-vs8vr;531vN|i+rw^}|cP?Fu7B2t& zbM1G3u1%}JV(RM-Q7>*lsXl&pk6f(R+}QZXFP~o!2EVhN+fR4Pm9yC|m=gGkVtsTm z8d~W{{+kdls_C!P)BPFFFik=9ENt)GPWVjeJe|zmku%%)N?qx>&wi`_!7uk{((V^t zdTJy^b1WCriFQd}A^(v2a^2D7&ChGT{OR?jmf3{`B$?%x9?t&sj?NdEd))!pp^rM! zT1KE<-uY1Wd!Jgncs}}`=Qm&V%=#sZ@mal6M<$uhz)pKC98XXWJYJmnN`{{3w|{u$ zk<*19KBU9!9p_m;WliX4k@g!ubmVD^(HXAWw`M?$Q38&QH{3q+8(La3fuA)OcFTUQ z5k9sRzho47k-36R%_kdWtW4(P6jQDPH;YD^(2?oYqO3v5nhZ+Ik|@m6(Db(;o$y3l zAiRS3PF6q?g0U7q&!GsipK)tx{E}+t2Jv6X&Ef&pAQj~Z57ZX;TZALNB_y)$eRp=h z_E=U-oz`nH^9R4>g{|*=X8q`#pLHN;x6p{m{-^=pe@lzj)9?CRr zZ+(32CtkUbpC#;tn?~n1c4lcN`eoPEzwZUDYmUTtRUqZ=Sr;cSxFUVS&CS2Pw@+_{ z&eS$jt3L3h?(1)AJdOP9ZGt@$F=IrsB93Ako+TxZ7B>YSmZZwD@n8nTi`h(_!6#Yi z$QIPrqrs8iZMJs$Sy!<42CU$X@ue%wHPmXCx<}8pJrir6!eT`4%U}D*N_%jo>r2A# za4WiWAsXQ2bOx~B{$TcwkFKosZ7<)BHLM&QU+UZ6{nXkwp2&adyA~Jg=BdDbVr{Bk zhf^zU`(HoR{`7r=r&uAwk7ucV`;%+eUX)zE7@fJb54I0FWSu}AbL&B%{r|LG3y@Xi zeLt`JzIXR7`%vDdgPv4}n|Gk25uPr$AloHJqyamG%OSTaWMBdy`u_8s z0({;q=W`j=^Y0Z;W~{HT>FiCZR5U3|jf6PYb61-ud&!W*V6w0ZXLI&o&Rn-KyXSb* z);lOSX4QeCZU1TG!4(~IFAX&-+l}_IJ?x-N!K!oV7!)AqTpm9X9I3w1QP?=W3A??r zeb-S>nS<{CB-$G}+iuH|nlC#qf242PS1OR1*R02ZbCo4xU9fvWHJY4Ozj8yzvRM(+ zyjTh(EbGoAXk+g^4q_lsV3tu^_~#Q@>qlGi&%9H-Z%Ojzd9g%T33#NA5;CUPeI~o& zBA_O7PPf0aDRcCkRqzwPK#H|j#V4jU1~m$zw~swaM)v_Ym$$egn`<4oH(S_5>BGUA za7eZ+w}854Vj`K~^%zek6_Yv4!3(KSa=A%ymI&R)wB24~7EvJ*l4|K+4!6YOtY3T$ z!%bx~46L^k^B?RhD}{5ekf;KIObyi}4qZw01{t#3E`+L2B%nO!d9zo5C(O1K+D}v$ ztJtos#^_71ey~XEck5N5a{`Pl(4PNzWheYwrxll~$cme83-^zz@*VTzb9zJnv8}N8 zWL1E|34dDufxcu$WJ+3VitM%{1&;C<_vyTAZk>Qw6@F4Z&mN0Pna zfUjqZRzq$F{ZEXcR4Cb}Ggf=Koi&M3WUpthG7JLmP+xAR9OuT9&zJD{3EuMomgbtN z7>Nr=_B|)6>o#TzO}3Q?G8{U#Uq4VD7&8C**7T)dle9{9-7kgj)%~R-!)99mzD&yI z|JT=Z-?}ZWC~|OaZx7MX7v*rn`G&ngfR~1HR$aCigsIP5ke7j7bJ4h6uiBrU@uWN` zQIk4V@{2ny$acZL;M;TUT?;}6Cj9J zZZ}KzieZcS9&Wq$SoPZ*hEHa#;K#?P0rLO&u(@ti=I`(5n$aCxnn=m|17|1g5+O#tLw@*5j||*6-54 zuqd%?R#a+9ffVu|qD}?WWQKJ6d#?u4{$WjF!k@i5QN$t{w|3cAZ!e1t0AwKA51f&r zDQ>f3_*tepcbi^@sZDl_O{h`?gJ_~9$F-ykiNmbSAyMK&H_OGu!fl7eEAIr}lLlIf zR1HnW9NVuPg{&A-)GraXLR$-cAyhLVQ^buG1-8{R^?cho*mzO8Gt8t&@EY~fWmAS&xrit@>HBq$&A`YRw&#Zk!y0FU{+!Y<6M%8-VX8>aLq%l z@5xxQdzJJO+eiX#7YsP$oOqkLT|o9?Sz_N(G^_;Sc1fT+$jt%Q!b}!U2?r$m>74cG ztJ#a8{hwbo%Q zt4Gsr%+*fKQ^2y_m-9jI>`AB>kK4B#C=cc>uk#h2GOIU)Cts_w-8Xx)1tF6yIZwQi zV=UcqE*8x1MArPyrc696d)ShRo-87Ek7^ajJwM9)Xpl(Pi)N>D^9f?xP>rJI7hy}ISa&D zIx_+@Y)*l!h$1GAdIs z;7U*hy+pxKG%Qra98!tB_+>%d=#q;?fLLIRGE21)n0};D@wL0zFw={B6R<`?b|)bm zsV-zGI~f?STH@~9Hlr+In5<&@uQW%L>JD$2>>h$!a*YS12sLnKog3qN_9!$AilC7` zP)BTy(1c+QFc~mXF*06tHh)|e%qOB@#{W0gq*Y3Eqqfhq*wXnr4C=@Y%PApuo|5q2rL zurb*ck2D}OsI- zG3APhAxzWsBRhQMhi~T27OWuJKjD`V(icfC!Ye?RNs#(@5LO?atUmp2;SZLjKw`H* z_E<#ZVCU41v9sWMGTt&_iog=EI=;BC!UXpOQ-A)%NJtCB?IAxP+Ta5i8=eKSy&+d9 z)HOz`$#!4ZbuP2KNZbyezp}3+0;-Xv{vNGm*{+GIi^+dhtGWv=WPld`{&v1C+CLAN z^Xa^0j_7aYJ>e$FZusoXjr&SLFwlYwSjq!~#`-<_J&O{-WqUl*Mz&|NxUzke#ZQPS z{+f(*wX8qdsshq7yw*>5sRG9cq5b1;pPZ%JTop5|A{Kxl`17l zA`UvyMdH40w)?PXRIx0ljujoH>*2dV2+l+0-qf5`qN;?n>bTddVWgUaEg0~*=XAe} zDAFF_&W42uvL+U%J0!Rfs)G9}bKEV2YpKG`!QiH^Ctu%&1Rb5g)Fh<_Sk4MA#}m1IAVXq#k=^SYh5L6U)rQ>en}9*# zyf$;YFWEIk3drr6=G#KU9r3W-olx((I)2^sNGhrn4d>Xfxqg?v`*;=Jt71vl&5ZPQ zXuf0*hotA;DtvU(@YVhk5hbEY^CyR|o*Ds`o;E>+$yP0C|EcP+jQRS3^5G$qQs+hN z3yk;Hr{!y=hnLTawLo@pe#6*A5n>E1kzaL1Y)Y3lr%!`L0cA2@wKsiKg8y>VOF?|k zgM)@{+S59rv{(rFDOHvt+MYBDqG|gWSd!0bc#z4~jQj9=Y<;a6s7}F9j7`;=z@X6Ow9O zwvQ6&KoEaTCgO7pM2J<|CEJTt`s<7LUk!L45(!R_Z(D1+SRignJp7TxV9`l6_-J)8@+*56;1!cm1Ut(XZI~oK(IHIV3h||j z>YyP$YXyrxaONQ51t&)=q|Q~2_omH-NA5H@OOIcZ&J`Dqjmdslk9N=E z z3FY&P5?c$Gt-E=7o}-a3LnJMkmCQ*PHBK z+e;q|!FUK&1I zw4UBx`1q8uW?r1(ki}$&D_?kD7sGe32mRLh@w*nrr}t=%?eH$xE)NRAAYF^%bZGfoXC#V&(94Bruy)jPLL!f zqn=}vc>EX4t;t;)%l5_*0JkE|mF*F~tV@RAY&*Auy|?*5`T6&Y0v3W(?YHK~)7T-s zMcMANvq>NX;r6|e?#Fo5og9wSv*^t|C)9oh75H4N@vpB_>nifgTl06(2^#Q>6 zTcd}<839%w98I94!bw*k{1cwJ>1Qp#H81Sc=dBF~lv7!B`oBs#~2*Y3QDcyQi zystwYj{>>>boHt2r2Sum0E)t>qF}#DjDi#;BL;+T z6}`*o5~&yx?_1z|P=*+=ARI!WiFO;=wOwF>n{-Z$xjv`cKo?U*-ywX9T6l2a2eGl( zzA=QQ*0Rh=HMoVq*s79;CK}})(GmrQ%#Bxd%i91Tb zuU*tQlb_BO_9tfyFJwBIvik16HW{WiIw6wF)f)RsH838V+7DsunB0M!W>6>ls=3kU zb`&aRV+Rb}=Fl00l7O`_zxh07E=N8u63=rW@qdy>6j160Xvf#fvg zcJ}ZI#_5~|Pvm%xN$_DTY6tTcL%*HOSqga@tEQBQVLh3qa*`-wdf8MWf=x*rw`QwO z_U@$G5mCIzj>HVW?Y_wa5}ha$JJp9)b%HKFmhADc_V6ufiL@40cLZcFR_vc{FI4@s z|L%nHr#E%1m=lv_Pay+Ozhhy1@nw-`-YvZRAy^ciN(NkiDr;@|q;%)PL<>SD$Z^6s zA$Kpr;`ju1c5F=cu9))RiVoNjPYa0v@3G}TdByCQ6O7waQJipROk=VS6)o|q&b~C% z-y3ohR2m5xuP=_2?XVVN=tI7K{Ib0+WC~?W#(nCY!n=nnCBqY)3BCgSvvz)r)#%n_ zyJh(tw^mKL4ESM6$>53@KA2=Ks^;E_zmhJbBR$tt$=gYPjO&F-R_jq-< zXie=71(EHOy0q!t8vCdDuCTHh-4joY17EItn?EAipN=V*e?LOVjEVrD^WK)knv8EE zDDV}Ks3~r5c%)`4Hkgs`43x`Woq04Fm}g=K*3`AE$>@gjU+)%t)2cPEcW-CUZ!us=#0yOkAl@Oj4IWR~AM>wya z-BJAFwaMTLq?kF_x@*Yo+XpKDumQAx$4C1oH2FvF>RLWKD)}jp0=>P#5|3Ia%w4k` zE^eSI7D-jPk+NhM1TRH|2vf%a?q-)MAaD>Yq+a2&cZMLq)N`=sxWtnUAQY78Dwq@mkWlN z?8&gQdT#uGb{4!`Ah6{IhRj4L6rAjS-Y)b>+_5kbCv|fq*{N-ci(JNNvPLZ4`NNUk@7TVL`cl)R78`I6U#lkol{ROB+8b!Ovdc z+8{1|b6Vv7W!U#^JetgtZxypbTqBuMg5hzi=Eg4X3r+3PKws~SDL_nE#0=$QgUPz> z)5?b@5V|m5_K7va`fk`;x_c2O+P0uT!UaFsn#Ybw!sp23l7Nl2cm}pznvzBv(z2vX z$pVsYJyhN{P#Mf2ZlQqt;dOqoTfgR2|uzyN@oG9DIpCgXM|q#sb`lZveh7%75~ZE#h<#5AZ>0&FZU zG|uVN=iEYe2g?N3lI4Zqdff0eXll+~qR$`Gm7kN>B73B)o#f-U1E2I#Bx({Lv?*A^^%lYtTfI`2Bq!LS!^uA?Sxw(ySr`3 z-)50C0Y1Un`6{Ntur|iBRZMm-WC@@l?Bs^rZdxJ_u~+w*wv31-4;8HLgyKc^Al!c5 zf#xybO|P01o-skI8sjB9qEu}!2x9jdRmlALO`W|-?Cl;<$iPz;O^@8ODDk5=@?Lj_ zubeGdukA0bo*Qdg$oMTpDyl4*8Ch~!q+D@=kX=*cdlx6axqjGlwiFgeBr#iQf!lL_ zpoGH(I~BGBLZ)FX#i|`4O!mC6>ukY3Q?P*5CE8G8SUnI{v-?8VP74p=LEgG-#{)&M@D5?NmIDcyp@RL` z=A0vBB<=-y-*w5ZgaX9Lm!z@W9#!Q#7sM~?*1o$b3nUC?0}$*?^G9kBwwG#<~zaqGCVb6B$#dY!H~!;UV)(-a0mH z=E|tu8s7OWa2$Zxynks@qGE%lxP7FM0gdy;-MS#J3;IX%vKURSt6aDCf9=0}rl*%# zJ!8-28D~7U$BMz&Ar8cj6FZ3&garZwB7z_UvRD!jNQqw{QjmB6DGz{n-~k0$0%Q^F z1ci_cGB$C>$&6#ivw0TJxTn{DuZ^?ZzowU}TlLr9_D~N=d%C*n)_2c6_ndpq`A$v) zGIdMcur?D?+qgb8pn_{|q09vt`haCjBNikiiSI?sP{HJ*%smtkWkD0g1>;}flH!tX zvoDG;pwxYZoD z;|APe%wrYIOIhheoKnx{A|-5sOXySLAh*}Xwd6;qulD=t_6^9v-8*d_Fr{w7Zs2r#l1mkKS1t1Mo+NeZCpIa#7VV3!e7N57hQ-F$*Xe*lhmu z&F-7my|m(2*wX&}bm#bX$F;TmN+vU9n?>nkN6P$NIblDs*Ma@!%sXCM+7ej0Eiam^ zivqCYGEvScf3-r%B&t(>WDL9dTnc{o*WX%>?}%3Q)rz;tbr0v8OPE$GGY5#~kB)xx z6{~d&jiTFy8bg5!fi2EVC3EU>@5k?YYF@af?x}p{c!mF5E$#cZSf6{S z{#V~x1}i-?zapZIkN1M1w$z*nKwtYtAObD(`aj+jQ!$jPi-xpmG*q z1~XGrz~F=3^Vfc&HdQxAv}C^Vy^fk_62$ele|qfU1FoH8OWiwZ{qBdy4$ri|`t22U z;S)UPjceZRlh&{XB)CR@ce1HAVXBV4Yr_2X2kW~h3}W6)wq(GG{ne_`qR zN@_eArsL$pf5G!e11zkH$p7cVX?Wzj{zyJs85=RexmKV@|X z^g($H$TTIhQO&N807&J?`-d)>k0MEU%-!q+H88{0+3-KEE!y3Xnp~j8DKqfoN6Cbw0s^GP}|OiVz47Wn#nEtB0Z9Td}x2E zn3AbD;ulU-zxe!uNIANNZ$CHZU2ppPr|lt>OqS^h8Xvs+JEkmi7}()O;8g$ky62~# z7kGhI6n3TUN}Snz(wU}Yj3i@9=<>9cVOJLcGd*?zkzVQ)_#;i@4&}D^l?SSax7*st zx;@Hj-xE<+uS_Ka5PbX1uEIKjVec3>f9~EY$bU|0zjNC9y`LF-_W4D1Mh#z75f}}- zrRHhw1%}|UUCzhvD$@hAl?;5~)Av>Xdp7}`Q+27tqEZOU0X+L$j|CJY)mOG)k z1_QR6?c>I?PmJ%Dm6<~rkZDRLBL%4MVP{aTFJ%5&I#!RUei5T!j!jL}=_C&x$HCCD zt8-O5ZDuk%kn7LDC`XD}YN8GvOxe-lh7#qy@mVZu6Aq;MlifeI#UW(?FV_xO;{m*g{C-$`3Or!#T`c`U}lcZD=J-8&7fk6 zVz6_@OE@4}_Nj1|J85(JL0{*B*9_RxLUmlmmniL<+#hAgi+6Da?3vO|4aQTS5Bud* z9UsRDVb$LY^qcL+(Y%l zvo_@hjH=stHK}H&ADYrMS1FmLPWalDzT$|=(zRc_zpB%*Vt#2qIBkJZ_1vp1bxQ$O zxCOS!h)t}S&(!`xOgz+6+K8MP|Yu+ov5kfdy>G3@Ic zSFYsIl$J~yd&GNvq0?(&*QZC1l)*GdI_A+VnYm_gb}lvjN5@W3;*kSxuOIn-t}QiI zGLIc8gT<`=obz)Yr78_)K%P9OaKzpb=#3mC== zr;)jcYQ$Br3z3mb2=csyUEWaIVe|U(3%RWSnKAQ^9~~br87%h08jy)fCW8hPq$jQv z=AaKIv1#1B42xP^G66XbViBPnuO%-8$59r+Fku2!c;Exsf}vwGD)I4=w}d*Dg*u(D z`T;wIvRxndhz8oFt$DVk*^Uy3tsrO>k|?Mh z(m&QChF6&4Jg`TRDg}to)nM`TJ#8cGoSMnaw_(`6FBzsZ+5@6NnlFlnk}?w@0o5~G zH;Tbd>1%j6!O(U4vXM9)N^!M&ln3@SPo3$06Qv!Gly03Zgw4alNCA7Mw5zvyY^S=- zny4A0!w&y`aX$5&hWlgOv&(jpq&=sSfkA=`0Xj78b6_y1F83Ze=nki3loyO(&lW6@ z7z%cnC2#-~;ROsM=vpz@?WQ^b2sh5veUvsTnZ)x{PQZv^7h>~>7)Q8hw-d*9*uV8~ zeGI16k2XcO+sf29d?`f*GnEW=?o3@|@VEEvaZc>9ISiX$+TlfyA1%H3dIx+9Wr8tk zcpm4lTdMj58UQ@H!$G#0Fv`EB!d7zUj0Kn|`q*fzSSg29GD<;_fv>bJHHLlNE?}CN zSEjaP)JMGU(Z%E(w@+GkZMWGUAKj8Uf5TH8(!=*Yu+QDK)v|JLsquAi+N?Ta!B_ie zGMg*E0lC-?PhIXSDi$0={L%-j66AyZlbJSPoQ*g@2Fs5kO_DyDxszQR?`d{Ii>O|?8MsC%*Ic5`X8^4p*09q( zf{RY9a6q)IQ^%R*j1^e2v13lmvclBwOoD4u;Q^b$It3hE3s1XC4kZeE7&fh!u?+`$ zO9Z83=`dQRe&ggfxEWU0VtT$8$kuIJP55f|)!1SS$xU3F1t_VSm?Z{YS_!4UyBhXA zTTR7E0{L6+hT~;359}=>AX7kBcXgO|hnrlig}u{94s2xp>R~?t8~HAE$3lT-ZUhnl zeEhC0CamFR$`JrObD7!ehld?Wlx0sYnWCTz*=rsC5EcV9VG(&?Ppc&1Vwyy0x6E5; z|Kq6Cu;-C>HQmYKS&M{rRM^{|c6}waK?`iLhi2>@R8qE4+Vd+J*k&3feLhUqp|CE% z3DGnyzmicmdV^H}ue)OgYnO(FeP&!m9u7~rLHxW0U@tl9&NCF7wp2Os3b@;oM{?t8{r;b-Dj@U%qZYt-U=b};3GnLHi@2HOGOP2WTL-ktOC?M^wWjubg z{0}cR)ieXTK7_Q#x_zvik=+R2`{Xg~v@qL& z7HL~*4Ews=Hcm8BTQc*V+#OXm?_%%nhgZEncy9il-OkV7TcPB)kt~_Muhqbkk>%hr z0WvnP;kHlRT`4;v|CSmnndyePYrPAxAk(OLe9Jx-6x zuN4O5MoZ?lvi0x*_g_!7(_|IEIdjcBJZr0!%zP_@W?d&U{p+XOfAbwIkymFlVSCflyT8OgdBkiyCeGa;#b zITYmwlF5~3U2uH{QfQ-7gUSn}wm~HK8^K?g`f?lP?lX6e$1GOyz3M%FP&G1!rC*TQiIK}5ciCZN5WDAO#D?YTp^yJ+Y?wGc@y1muSz%Zwh`Tpfz+7UgN9eXFO z*)fx7xr<2qhYz{Wz1mXn3<|D2%PsA(Ztr>-7A<(}2d1q8Tk3dOr7@YKFpP>QnarFe z;zmr}Qe)WH4Ufy@)Rv48w`MIwlr#lDoP4YM%7xw&$0|?XUu~51!j{Z~``yDclb09p zudgfy*Or5YPH=wCXQTYsPW$#L%N}M+U9DucH%#z{(^=pI+n_@kkaYZ?iVxiI>EjiU zB@k@20hwsYeB@B+`PVw}2|gE^BY6(h_P}bYQG4c0C8HJ%@UQ;)RO|0gHoKT+oDp_| z?dHo*P3#yq`3R=40jW?jYXDrg5^%?&E+?ACp$FvOj0Ppf$W3laR&$?nVKuTykj#Ms z6QC(57oQp%g<2pYrtjo#>YSp)@n`nZ@H41dg;Q&|gPo?yQU+$OrA|yjQ|DPllJeZP zWbbqfX%K{DMaA@8>3|N7wWMui8B%4~1Tp-lV~b`7y++Wg4z}o%@%p}|TUhZ-Mw{TTVD}LR5HC)87*^tVMI^#P463C#n0kR@}|W72fr2s;DV zC&6U~`T=1xjx#RI0N9&ZL}^?_Q~>svg*Q%QVyZPAo14IIBaYAJfjun(fCIo1y##45 z*{W%9@vu$XtR$gmV5@T#Q{C0g0r7tt?3vPTD9>@>Z(;T~1@=WHHzkbf(2S*}Nc&Jq z=H5NdcfkQjxnR;SFZvT;eC1OzZDny0tg?wR9s>^xJ6zQWDVP+`*Negq60R1cvLm=_ zTbhzd^h{tClwA?SZoR**FY^|_E9)gRJwJM9>By{Iqs}Dk@NBMbFF7J}Jj{ZkP%^C^ za-pUrr~rWX?XfBMx}daARt+$!x}K+~1ccAe8yCkAv@9jFZWrK;lnhHIe6PCC=De`iazFaoE3KC=^uF|oaWE4LTQas`Oj0iH z@!b-34!;0IOj0@2mbzNWfTONR*5V4bT1n4uK>8y3@3X0uA6yr7bi19$fK0Sxc2Ag( z-&Ow6JCed{*SHD0;g+htZxXA>X6h#XZI+U0r)H$e>zhC7URvt&X_A-)Nnk%@(lux|3rge?;OJ71ZrG|ZTMi3EV1?AsXR>7?EO%VOhs?DzPE96j zx^2lRv2~pq#OfS2Wx5YdlXN=VVw!XGxom44>}m=QO_Si~fjvwr{)jKoEa3ES!OnsS zuzT3ATW5*}gZ2P0gF@m z*Yb&THiq2~-zSrYL8>_VCq7U8tjE3%c$)g^B^Jvjtk zbpKv=v@KN}+hw0mp;zWnf(epe+GE`wiBS3dV)qtvYaI_lhlL#!olE2sX>+~M4jUDt zh?21~{9b^%R@T$D)EM@4I~8?%%&=r&LETz9IKE(J&%W#Z{y)usYFqsBq%L_sH)0_&}AMe@iP%q(Z12WN)0a^X*Pt{VDOeDz? z)Jn!wMoQtC=jJ?aMXb1B$$W61`=uwxD|9e1x&fJ}WHtt8*6bv#MBtmLa$L??Oee%b z123cQ)?8ysawB;OHSp}PRE~}n@sBC!U=GNA9ZL)d1Ta}mXrU!(#qggiC7lgKvRBXs z>T)~l5a}$yY|4y!N0F?zklm_#SP^9yveBtFm^rSG=E9>O410bA%BbCq+TFmShLo*t zG+xzvWN$Ic8#S%K!PgvNDl898yRsDQowQiO;I?jCGVpN0xSX&Et-ziqcu4$>%q_SY z_T{!>DN*Ay4|`|if!(%M!317`R5F+VJGIEgRY3i)WK&_LX^X4u8Fo9%V+klNp#bcB zLc`?i8nw@aUs)7S;D{$hIkY^mr}e*te{XieL}~B!GeXZ`{olUL!fZT3fGPRbNqf61 zr5#YkBbhbQt}*P|pw^0Er<|W`*t4ZwS;@(p!KT2z*a{U#99Z==n2U|lK9rI%m6l6H z*#(WNo?po*VvF$d2`pS09`-O&^URRcNe1_!Vb4lP21O5JQz)6lg+PUaH(^&xzDu;Z zJQG5@8M@-X0Gp#i0t_p?-4E4F=e)ndTwJ)}fAVgl=IETuUJUk}x?SzwM6@a$BT_4w z(^pcPUhvo&WOIxn?FXlxBiBOeP^4 zm%yfNsWI&9n0c{5WIw}_QD?W}S{U3J-?u83yGpKT05w;@6v1#{M!Me3bwQQf8Q%z_ zy}A^9;kkuppO~1c>%}aY&Dv7uo577%`1ZX2^7-DYZ}%@PWHiNX^^kSVL<>8Y0r~EV zsvREFm*y17EkDXvha5D^^34Dk-3rj|# z9v@8!`pl4srO+&Erc+&ASqR`!q=O=^&7zQ#jLZ&FMfnFpj}T_6<8`pZI#Kf;aRpBv z*u78%9W1s}mwN9ml@no)s52iDk5EhvK8@Q@FWB(xd|B+#T z>$;~frpH_z+vrj<^hRmdhEXzATPTtNFl)9SwR&Mr*n_OxVyZ0EhlV}t^qdZ;z-tN$ zz)mE;s)u7|)4r}yGKs^JWOJ)vS4++_kBrSW41?m3oO-Kax(@1rx~q>@4A`iU{%a-p z;Z^V7e$am7nwMtcgcKis>0Ixbf4uQWk2Q|(aSBR%Zr$GQMOjmntz<6Fr5;bh@&`}G zHN}Wq>Qr5s!$-NV`K3KpGQP4AGSbi?F|<|y_Oh)qmLoa@S!qWFlnh9<+6Dj%Z>be( zDO+j``?|#w<*;NHni&!9FFe+muIq#7z0Nh4n2qD3J-|OmCM6*nB|N8R-43e*M)&SY zaPn;LwM+fWi++#VMJZMvIGu3YUw(7xPakiXlq&rGY^hvX)a*qt+H-T>53YD;uJ&&b z;7IToWK%UFA5MsIq?`ui%V&F`BBv{mJH^;a2K#ZbfLIKTzQVUo ztcIsn!<4WC&U)1XID=s^D(qa0t1la1X~_V){>-tZsLC`-CP|&HhuuiNK3|lZN;b`N zTqo^0gxw+7J$gnPO7`7*+}kh99a{9i_gW2{0Y4n>z<~TOo(ccz`zwEQ_uTcDcp0QU zy>2&pXx!eTS2CcblWbD>H3fRd-ck(=xM*Ldm-e2LF;Fi9wh^kG46p}n1Ged>{8F+m7-&ZR{fAHe^L2 zh|M}wryf(KiiHezsBLkO8MQOVwE6~haC2{pG`;z~#wHGr@%FMQF=TQ&7C>9Bh3lPQ9;re9Dbb;n6Vq$Q{8#qs24Qan zI)fD!vuPkQlmxr+1zoC!%%U(9cF$3f3`VBeZT97>~agTm<+YC|~kSD8=h6RJh+K3CkrFL&$DH$mZercMc>BrxAq4MQ>=Zfp5(v4$4 z4plOP%k0kp1nBq2jAqQn4g8?yoC>ZSCFets-Eg+rZ_ulwyoqAZ>Al97p$HU3a~P>w zG#X=sDH|TT((<_`j7CsJF?O?&u<-PIb)R35i+}K*Jhs_IFPBx|{759j1g`bHr4M$Xq9bu;YTeqYrtCE7#9)`wpDHoR>CHmht@c zq=VnFY_MCD>Y`vRR|eCV0)YdM>sVW_B054?M%a@ih+ngz(r&aC_z6x{+S9|HM%wiU zk3X6S?8%2pNheABNJ@sMooH^1o!*qNJ8k1M7*#bpD(rrsKk-@S_6)EaWYVN$lAagZ zFyQhxe^Mw09OhnF01RN=AQoLJdb3 zdL^Te&0CY$QsENioLFrL&3N_n(%w@tL1cJm;giK&R@k*c6Dh51O2#(DVz{f-sAL8l z0Q^^P$r!^x#9nMoO1E!c5P!XQcE^JA$bo7i>v@QCJfDBNwRcZp{4MoFCHUdt#=bY3 zm1e|(w!T`gZBk`vk8VsVr2%=W8gNv5=rLE4{K*TyrLLED+lj~T4~JzOTI@XYcI$K3 z7SmWVMgwxFk{R4P`ZEAA_L5T-5ebc;UJ%xX=y13^rL{Z8l@>HKhC$qfm?0|Vv9SYi ztkMV_E{x_knOPyQ+swzMdybm-@7g>CR+08`Fu*d!6@qR720uKmZ$pw~7e@nO_jiEf zap2PA&moSrC@SV;H=lxyn_RJ1X+)k{C!tSlP}E5sZ<)5=TN-Yf!(D&0hNKm9G&fN4 z(3^(M21_8{yy z6W2yUF?fskRROoTmf*zNs>{IMpyj+DBC~ zu(qX2D3TivE}nBnf?a=juEkNAkzmKpGhbV&&keH3)-*Egp*HQ#rToNvnW$ujN_2NJ zm4clgjpo29fngSDzhzhcft$m}4ptkT;WyIskiNWVyRQqdP;X2- z_M}0{aN&XG5s$y6mU42-v~w&Wyu!7>S(J=^sD?nX$p$-CaO+EeBE?iNs*>rL27$2M zV^lJILQP_C=`9(e)6rd;IiV(~+eK{s&JE?YX7uE1^`skzdwJ@O`mMW=rzG>13eWC8 z->AWPDy`UD#6RXia!mp?S=dkYeHkYO)4bKW5+8Viw}ASI0?~yeoRy7SZKY zVzO>bRX7$;Wtu8T8h#SP^Wc8`h~zTvHZOx|6`AadYBR1H=;@8kyf?2IHHlv48N^@-nG%$|Nihb;0%pU{MPZ#r!LDggM(1D zT&gyS6-_VL>=5?7Ajf*xkFN#4Je^1Zk37K(jw2PeM%az>ym3C)O0XS+ZT+y9@`^zk z-Wm7}&7(ydccn@%1}PfUFShufqlx2iVGS3}IC+xbY_Nw-)yTr}A?kFABVXx@AW)?& zM%Xngw3%^ZK-!JNr=4!Hb%N5K681FGuAc%VXqeihU{5lJLNa!{529b%M^!SgH`dyT zdlj5=nud+0guSE1$0AL-TnR^o-8UI4R=1Bo1MH!xtSgO@8T!R@U^i6{vVO`S?eM>Q zKUoBk`0gvUq{bn@7Ifg(o?Clp?<~i?Cac>cy<=>pQZjm@@GLB2NV|{}cT8}1`T7}@ zOif?Z9;1V_T8}co-iabz*&%)&4Vnx}#xW&aY}-nsWCqP3qa}k}uo}Rq84oMSC#~Cm z`?}KeKX0C_MZs|5b2Jr}>(P8cX4q2U@xAiP_BRhy7taKpU?N7W;Sk*s=P3|N@ma!>>nuY+RTcoD4A(V zT{=l5rC~SXid$F@&zgiExRE^O5rj^cN-&Bk?Jjs!3(8pzp~3d{CW`_nKE+T?1Q5b= z)m8^ma>Zs>vj+Iq;SW2XzC5o;?|Ktth2o(QG|Q~lyUp3RcmVcymN4I&Zf*?No0Q$d zDFLA>Gv%rI+%pt+HG&cLBoWd}y9PIIn^Dg9}jOkv30R44jN4a_L+jzBv?*Y zu{y5k$#`rfv$Pzxd`$t6#g=PI*j-bcJF>FCj!9?BaAuochYYYwX-J0}mCR7|_;K`L zH`KNgl9{F5k=Fe;mEStvdE;0oDMbk&zjUPiga2)O_Ub}<*i$MQeNI`>d&lgd8YLst z@8YDBSYu0jqZ6N~=mtXYy^pG78g0GfORXlONP7= zv|>`nNCu>_+VNxAQu~yQ5C(x?f8?l=Er}fxF8$ik_Q50V+pjE)V?ZV;nZXVE90!0& z_~KY)YCNgPFE|Aj5Lq`!SizG`Dlg+DHYwQ+zhn+-a4)&^iuv;ZM~R%wYVg7gk~7CV zXf~q9QzF+5?y!)Hg%m-P_ek|0KS$kcfyiXlPc@J-j z<8wG8pG1KM62qa+F%a?G66jxzW|=0>A-W>OZ>8D&-WbC8xzBs(Vwq zjL76Tq0=Gi7L^X`!tP4B|NWLG;{k5mC%1V_wvq;R+cvaN!>t|q5GQk3k?4b+vIjAf zWBb%<<5QEvOi9wi0<5s!>D?uNtr;avmVm3@yemIdl$l|lE=u^pj@e+s-`EroiYVyC zUN3p)u?hAB`9UI*;nF@;Fw}@}c6GASo)Y#n(w_4S%Bh$afc*HdZ=cuEQ#Hv<9F+D9 zN+!^9Bp-|VvKmI`)#mo%}WW`G@oGocZFvFE7^;JN*FC@4Q^Q;S)LL+MA$m_e^=wC^jn@uCEyW zcm=jcdlc*(N7`%csOiUka%~1rI2l#RZa+Cz14c+-fK%QzT5P} zDCv!cr}Om}D%V}=ZJKhj8IT$!GdR+)&jG;lDbbC3x^x*D*@oD)eI`!S3S>T6}*7wn~ zp32M1H@V}$p2H$GqUyld6%hxzf`eX;gGDTMm)AoNyC#X8B<+p1LGp;jaKh4_26iG0 zP9g2u#RFnt?=6i#*q*kP~ITd$rg!7kS*nW5iDCgA2-*xNd0XRa4gJ56S3 z-?8BQ*&Wk=_oLNjLP(73D*x@p>X+`BbMeL}rrXN}y;8*8kP}uKC9`eL#yxddFdaU& zR0*htaI7tLrLJ${Lgdp+dr!$YwjrPn&;hU`Njt;7wyMi52tMroP=Urqq3+Kl-sO#9sK z#El5q&gxB-_W`WiM4SOz5jU^+BnNF%rv($gQKE-@J}h`*6jUacEta0bn`P;87jA}sYmCWEH z@6XzEjsR{rqP}>ZEXHk)a1Zdz!0v3dscQ$%6*IxuYAs^n=ndfl@#-+oTvyK$lN>{= z>i;@EJgumM4oW0dqmPo0M4&nm7k-K zPfFOEDPDEJ~x z8Xb1{02sukIDJOg9a9g0q>fttyv`-i1pMQ4dwWDqD z>ykWIi!t!J+YLv{S8=NHJ0nA~8KUE87iZZjbV|C>Tz50%c zLN%?l_h2u3x~ZDN;_644UfO%GZ&@%DS7lZ*(xAyu=3za9(%uJq-+ACp=clCJk}-w} z0QOolK2N&+`W@bX9jYf?n#Vz=+)_bveCt3JzGC$5vBsUsa^Sl~4=X%jC6{k_C4$E@XhLz=kKs6|;7$5A|F+*wEk2C~*9h^e3on^Xc7KIz~r zDrAyxfckT+yi0|lG2SXXdw3@S-<%h>$*0k~;4Iu{P>jeQ3geS&QNfcOIjA&{u7!Lf zl(P=;Y~xgcuBPJ73AhDt3c=3+-_a%BxbC1ga=d&b*em75d{JJr-Fxom&7_A1kK`La zseoGy?+njp2(X|{QOEH}T25AAPkNw+MZmo`I`LPZTWclLfC~~P^b4aAVCS*8#sg&T zpMSje{V#0xFb1Pw&*wk|NEQZoNo<>EEvuIn6b|@8FTB&LCWQadF$1l!*}-uukA<>j_|RMt4C^p!x7iWOoc(~YVCWa~*hJ9!)98v|XgWXtl3DS=BV`EGE_66s` zJ7*sL;h7}Fuusvq{^i-VfBgKs46TXi_O`*Urf{-vP%@X!JFtu-rx!kXvJzgiJvYvl z`u-_jm&U`=XR&G49u@W=)-t2xVEZ`RmMXO~<2feHWegdVjQ+3*Ro&3siM7g-ab#dJ@3dI&h<}>g`z4~lHk9qXdy2ca zx;r*FV1{m)u`zIt{umnBLa08C^-4xcBOwe*`!tPgisYtW$_wEDh4Ppe!I#XQ>Sq-W+jSp_HLj@jF1&o!#N`C+5az1%FB;4t0Bl^?F zPrrPm%{3vMCdOj2PJDJ&1{M79xCubu*h=ulCzjtl?)%C8UU2ohb{BSTbVr5VN^!vQ zK0Fit<&!Hb^{@v!JO%hVm?^MwSS_GLom=<={OQsCm9IWq(P$G`!ykWUdfTisKJ0Kg z>bS>Zz82=zV|wVA1Y}=4pozI~MH&q@9QLGxyLg96yKfqe%+AAPrCkF%<(k7 zp`BkxMWPdd9X`BkQ(}vJtsT9)gu`uF+A}MeLyMh8Cy@#l?)noO91cjQhg~;f#bUDe zkzr?PH@tDQVP}B7ZOZBS2}-61d(!v&VAmfle`3;p$5r`Tcjb%84eRjG4=;B1{j51D z-QMaL+%r&XMkNEL%v>pPNB~^uryq32k#<-p+_k=}f?8DnpSLRklB2xNea}6+t6g14 zNJyXqgb=qRKn83ON=%4NK@2v99YY-ARE2QlEZeD6*<~D4PKX286^BZQ4M9*T6~#?3 zmpKG$5JD0lkc4iK_MCfq`p7$ahSlu!|M$$!x=Up*yEA=!{r-3S@4fGJ0=rm-;9=X9 z_6F?IqcbIA$ojU!q`e9DmcG2$q)J;Rrd78e7^#)RjW{zfM>MIA43@;K2e1ZDn;*OL z>KXUnF!Sb1vY%g`ShXOQiD_Xbb)u4y7Q=Hze{=_O!HiJSMVCtKhV$OkVF$l|%iik2 z5vM|3)NMPEvI2_}XBv*vEbUjUN-pd-;^F(+pno3uZ4rFPhz?{FB_m-0;%RD}@(4K2 zsHW2mDveavqc#GbZ$d#B{L-X!YK@u zmEt}ZkP&qZ`bPh^qjJylxuJq9aMo3N#;eXsm2Iy**dvUC@Z;*u4-VgcS??JO zV#piiDd~97_Rf6Fx{qNxT=!=$jXy#&O2X_DTzXbU->@PHsCET*c}38~Tqd)QtYXOLP-drcNTF&kHRr9BLGi(WC4AHzdMly<@4)4We= za_s`_pIZ{&vai~*l7rFMI9OObtJn9G&Xmkp$$xmTAnL4D74Re5g2_iF zWD^+ZTWSZeOXu}WRx)5tya}+k{63tyYWoe?E3({?L!n4lq#fMoTh{k%*>9I?p@rT6 z@BOb8E?OS%PwP|H?a8>rU5QZ_tXRqPB(*aZSf7kLEp;G(^U6n+KP_eAmfD#~-9PMn zJmiQ5VATmg+l5^mRbZd-f`m8cl}P33^>PPfvngb*L5^WdlT$U0tUaN z-9wQ{^<=3xZ#s3mQA}#S;_oWEd7Pmz3d2XaXDq-2C#4}k+VS=!;=Zo9PSmW{(L{qjJbYu@)C8~x93&J;V4VrieKWG0*D zV*>yeQ*tqCz6qLX>J3kTtm}G>fh-oa z{Q$a4(Ik(gR)YcHC_o8|s~GX~1wZJ?U_K^@#>7jIE1yORC_|2`(yTj;nA*6}J4ida z4pppD-o&I~8L%K|!UATR>O@+!r{XHCl>if-2LWG)2ojzYKKzxl)9)P~6>NTE5pV_h zE1ub2zV_Von#HjM4!2WyRx{rZ{P6za+5>MC2KQDy*`z~wFJC$%b^Htijcz-z+wDxM z8!LIck2-(;t07PXe{^$MWS)*5v#Rxqr0!O)K6y&37x2=oJS@H&N^DRBhI!`Jg=uLIc2w&<4OZ-t7-eMEkJ$P_aHG+=LO zr#Z#kfW2Ci)Bqu$Al3eLMcP3su3wwJ_k~XJ%jcS%nbdaOg`o4qj83mj!UW zv){gGX?!ZM?;WW@l#X50WjyDhQ5Sm&;9KtogrVO!KYjh0j1sP7O2Vb&b1sX92RBLk z+^l}(8L5qf#jpx$5QaTN&fUMx-E?7A3xQoK?Gu&Eca)#J(;lvvH|@we})-*;uiK*rzB38Uh^f5OjC@A* zp=EGFE?i?$r$kIbWT}ufg6o#42BYS9#ERgXCUVo(+<>5+jV>3N@thHbR)|JpFNewdJ;&5dGZ`{ zexEUr)^;9o!1e#=Xzk!A`lQmFKHTkzGtC>x9mM;HwC>K zPqBkVfF0`nXEKY6az5_YMyAERU@ zxzWvh5EPlgMHY0jHf+{Uq&Mg9zF+&P$M> zSADLUC{f(Qvzn0&z))$R1MVEd5i>dD!ka-VZrSV`x~STp4YEAc9^unU@M2~#f(p?m zpp$WpZ`DQG*Wk?5OM!|&b<}JUgVcNpGm>xvptCqp#hF%S_`Y?0?=2gL_6@sYSC}^} zE4Dk7_uk%bCy8_goNT7^i_+Bx*UBcab38_q-aCW6t;1(3eMQ-R*xq%t_T;v5(o)At zIFd%n#l}a%)NWtjYw5va?jr0}tbyaUIh1TG78F71lx52#R4#c+(rP5>FZ7CVhkH2^sN7f6pEj+>%tCFmyqr>hP#)ZERzg7IsT+=QqQ_=0FFucKbx)=|vl_;6sw06#-*mLhyT1qDT^7#+SuYZ(W zds3`jle+2c;-Rr9+$x>GZWt2b!|>10>1MYbos$ zVQ<!Dy<|AmE3ny-@bbRSyEhd>Kzwvc0k$oRh+lAd&;PlQC?d=B5H3KF4E{ zG-51@Azc?@24}0%n&J6;n3;70dTbuq0Jp*OeeDR-s(H4ERwoU>^JqcD@6s^8iH!IG z-I(#&Q)35-7lcp>Rj?okdXPd=@ND?nC>l{sQ<q2e9MBaI0J z00Oq3rUT%*{nDQKJ$lEm3r^0lY}f&SfHOB#z``I=`OZZ&%s{M|WYrM; z>OAZ7%j1GEy$~Dx=EKSxd#Y2^?cxn(RcS-XT)r}y2yb78r@Ql+v9XfZmPy@xw07Ss z`Dz5K$BtSDuuHZERHa>M=Z_hNB0e;&LnWijnt+L^y@j+l!QNc|7Qv)SyKcD0wClPZ zyoHT}1<@R6U0HFQDV26sGPdw3l9rl@Ywem;Rx;ZU)t=f`l8UR3`|nBqLP_h0^KwSEU?fX(Yon+u;6*%d9H-LGFC9(3YVzk1nrL+Rh}unN+X@s2HaHU z<;6`*jWH=H2VPh+>IHK^cnAo4PVik0YiK24XwJhIh!8+xjo>r%%)!Uty8K;533?`6 z2NBl|d9hk1Nh?e!UPj+ZBw^NYVYLr^jB~UAgJP?C~=Ufsz5Z zw(hro{&Ifjr#12Vf-vm5)#;w3+Ai#htWbwID7|)Jhi^$o?EvPWlskak7M>Yy?$DT9 ztoT$I8uZ_*$}zgVrO{%B?1qwYWyNF6+}B-chyVMNb(vQ`s)CTTd`6$F{@u^#?*3{& z`z4(z8F5uNm8#>$WE3TH+I;JTeq-Cg)|?RV%YDP{KR!D8w;OtA(y% zY-3`-ySg3j`IoO1a^=ttWVqoav&?KFNQxSs8LKYC(JsxFlJ z9%u&VKu7gt7SA*W(t22I0if+2c3%9j@`tOE9l*Zn?NXr{x(?vG>z2fs-B_Sx;3=ef zULftduY7HFdT?(Ql(wJ{2u$kgMX^N#W&`#x-7fIkCkxUsc7WO3cnLWkKOrg?uC4*) zl8WPOlx$K88aK0QEwux}_074wrZK~9J=koxzu>yX0I7hWK zm`%e{emDbIN1rNX$+eRBVK}!Urm;+L$mnBN5OS}2MCuGN5L2a6gBO}!_$90m=FfsR z0Z#`Aj!>r&Tyd=E@t!U$C$&D5UZGe&SHff;Q^u}c9Q&8A48S^+4hwAeV1}%3U!1*R zT{bZ_*u^b_7cWa>FuOF>8^&lmrhRK&=E~F4Ovp8Tuv5b#=Jkr$ABEj-Amu#gT%m3- zxI~4_Jlk@(pUDi+6F~@*c4>mI>U3Y)xtoP;;aJh-5r76#tz+hqY9*seyV!@|zjhb) z^`|7VaZ%vm(Nn*)vvSifhyLr;!r?L3Y6bhJdG{yJj{p6pQJR7&dJGWVrL)Zom&QAT zT_V+LC$O`$`@(a>-F5~$PPq@q7cTwy*3!{DIuvCapBl~sKTOo^Ef<1L)2|vzCT>X- z+B8Xfe@egR+>{x<-3#XjWBJHnX)3zi6-pFk0HP`x_{`VWrUiR=a1WdJRBwHFWXpc= zqD3YZF7ft(>g|t=>>F{SB)wSzJA>VqIkoLdJHuYC2>T1D2D&pPBb~SU(WiDxX>Zc) zO(}6-iDXj62eWo|QMXgORAJMWVkw-A3n1FCB3Y_LHL09f2s_F(|KPaWu1SRt-|^(w zp5a=QY*o!w@>RbrPbO)qmz2AFf>-mns6E-k9SN4fTs+wVnFgB3Q6G& z!C4>>q^JdzZ;2`nNAq4^MuR`$e^SN)0x!@+4Y;YIOJTUli^7iq60k@(18C!z6}&FK zH5Y9UiwOM5v@l*N6SI|04deVtk!(3W?-0O6Yt-Zc&yr3A1Y0CnYS6c#@F;lv0W^_i z=(K%B<71tm9tM!*AGj{f3pU1ZyUWI~6>kp~SWilWrI&)5j+w9qwy#KCqRaVkA$f|mB=(&O1pI1sWuJL4lfkUWWMb4ly8%I zc}*j*#1_$z^S)3NX_p?|g?)Aw>0JKp*Es=Q4{J2X^M3Ji?*7;E%jTFX=UcNg`obCJ zfzjH#2WuaEQrkOHYj~F8#gdL|H?7N<)H~QN?9zSuTEGz1HtbRgDVm?v3G6(OQt&px zef;(VL+76uU%d!R&yVC>RZ|Ai`uQhT!6%RJGhmHJH>nF| zn1aWEn|WY!;Rj#ti*8a6jl1{0kb8Z1r5thA5VEd$6O~L9Pv)Yf@r{F_-SF^%e8v08 zv*UkrS#NaMhlZUWJ~3ViZ^DF+ojliCIp1_Wi6;}26_M&xpCgv`iGAtq6u>xa~Oqi`16?XV~c z)`n%N+%^hPBfrZe!41I^!_B=HJmi`F;d)EN0(o*N?2B7kkiSzk%822VW_*`A#x6&S zG9n;)C2$5<5KQw#edX8-LM>MKQ1$U|K9?cFm&}+-m8?GhXDX&;lXw!-QR>as_=Bzm zlb;ioY8j*vaN;zLH6^Yn@Yip<6rJ^-y_g#7o&ov$Jf&hm_1I8_v^emiV{4Qbl>Z-X`Ps33@5zoo8 z?$(PSNhgYIUZ}Lox~O42cU{_PF$U9BnJ$Cdq*$Htu1rK}cZH2vaJE#C{OKm_8&)LV z-etAw1MWZx;S~LobiJZ&%5fGL9pF-O{5f8IXiOJ`ZkqL@@q2 zPut$l>?l9?UKyf=C9};Xv&@D4`mQ6+wnO%ZM`}m%E+7+SCw1a`@H&D$la#RP1a%bc zn^f%b6xti^cQ(Aj6O~ooa`XFJ(*6 z2u@MAW3~4o`|+)%S9VoPG}Ax;Bv`bo&q}4q&yz|!-~Ftt4%k*hPFTf;U*3C06QFh2eiKgCYd#CdRZl@hjmQjbqWX z<6uOHs?bz>Q<_h5V|ohL9&w2|#=E-GASHD@tUl+h3;54m$)%QaO|2kD0qy5O#D>l^ zKCP_6zCWYGKbnQE;&3?PYOT?<&BlOwYG)zIQ-f9{gWhPl8azFcXHfz(8Pfbda4S1@y2!8b<1L&tNiX^ zC&~!FG4&e0@2MOL|37*Y#XIJ)_m` zOdqqmLS@{wCGF8O^Y`o5?|Rn?C|4nuT384HQzs04&ujKG;0oDeSQr& zBMw-}rlqkh=Oh@;r~$DL7JXVlKoqS>Ijq=0+tsq;?PS3g9>)rJXt5JVrgC)91HJ;! zA1c~I!$zlId)Ry2TuK2zy%r$M8&!;qDvRC$b3BR|I1{ApmoAR}&yK=#yNdM;5nS4{ z?-ehaTUs(zYrx2OcWjD8EiY(da3gcp3~l)g{g-=+9?j5B1zm0XVPkK1dFxIDbQ&xm zx>`U)xX~+>Y2Goc*e%;9D-_ejjSx$V611!q*4g<{b}rubC48 zCkcLYbkGD1ZjMWV2S#W+{CF&Dzq+sVleh98^pqiV2|N0ztI}{I6VQ{n zZB3I$c3hyxYG04}r62ZOFgLPkX?(#{wWUcKVPs&XZyYdw^kxp?9FUPmqzzYk#w2yw zG@XDDd^{N^XZxk5QOA6>eR@W@bxqS>JvC5oJPFn?P_X~@nSpyZWi(7LIi${l6WDJb zje>Y`1pp+j3J~t&I1xb#Fs+)4JS`CM7!cN$rw>?*mWQw2T5_F}$<;6p3zR z>yWk5WS4=6Gg4$bP!8M{sj2Ss%PiCUkiZ6%?ZUqt&*G+tmK(qA}YM-MKD5ZPygRI|AVT`*9b0A|n0emXNLFALEC+=83pBLRYQyY+%A3Fe!~ySW#qLKEr;P^ zYKDcdY`AMxBf}4@$B~Z9nS?ZP+J48{VAHAvAs!#7+_AD+S#hWYWMe;hX$;jM~uD4O%7H=ma6bTxnB`(eFfPfsQ^TEA=NAf^#dG~QlNC`BR>%DZHU<{cE#ov?h zV*)0-8c5rJq!Gf-VhXar-#%2Dkw z(^OZVFz~V*a;9-%MU1~G))Wz#i2^FTVMc}Jo_A;*`zT=PM6*} z0tI{K;N(EN2L{=`ts>oM-wQL z1IuPgpm7wtZ9Cq60)kR0F5C^olPkL-=gx{8&swkSE4}hTiEDhERifD}L>@S&Q=i$Q zG{L4+`RV038y>asNLAodWI8pq-SRWZ63JwIwVes!HB};30Vk7? zu`SYYQJmp&4EipJw)-S#sO~gDVxQfvJalv0eUJBV-C4jo>9|G#@IjlG#lCWRI)RuH zV-dSgg$Ld$Td>259kksWMN_QM%{C_XwF{#E_={}W4|sd{0hj#thepvrg4>$(aQJL8 z;e5r&cpo74vN?g;4lc+w%j1u{oU6C%=L~0muleHM;>~LkVU3LU><1d>h#05)8{Eju zY*y~Oy7|uUcMlW-av}vf7`Ue98-gskYdoyj2MazeYM^_4L-;OXx73nnwD0gP){v2b z3z^fd9vk#($j78_(H=E zj7j%gnZE6z?y_aoOCo?kzWMaP%9;A)w9Kc#VzAXGh~GZy!8s`afF}*)l}B(li2_HA zT`{#oP)aI(n%lZ(iSARuu9d9dG&cf=;Uo%A*^hiJSP)bo!=ZAU+o8p1weg6^zmZ8N z2uo4ah-$GJ?jve=*qWBeKK>`UDiD8b~_Yp0N#`}oj zV%}tJ-elpzc@fH>2!s=ix1W1C$P~g$5D#nO#16XZT>%hBi5=7w)NAA7*ky}i1p`wH z450&2EIN@jcWq}^jQcMu(hyA& zyP~+aBZ%0&`CKJ}C;<~cL1Krv{m-t+{MQ@$x1JsZuV`GLazR9JfuFxPdHt#c7h%UD z_5r^XECW!46+3CW*G}b7+9FPHNezg7@pOIj^7xNl%>^94qvu@c&0A4j;(}PsE7fGN zYGjzLrv96`Tu~FM?N=?2KefGZEL%4W$G+I-v+EW_re%~+Mn+e?<399D5>YX%kvVIo z_UE5&{=>(5`^PB;h-ug{P^1{CrWSR!D2<8T`|>5p9eE6E+mlhRz=BF8LIsd9w2`^^ zj3{RJLsdrE5EwfE)hZ$CG9@1~4Mo@7)92T}~; zK>9NQL!b~7B={E|HirTWHWgHeal)S!k=T$LrP-P|aj-#f)0~irh6w}H2ySWUo6_hK z=Dgtq&?oGVBrGKO6X+IvlZs2Ov9=w_;oaTM0-{DzXA9a*8J0wZ)$SAplikpOxgzqk zK6jBK_Lk)q_$Za-4oJZ=K>uLPgaG9*Z!8$=45*e!i<%`-zamwxmq(=OM-Jd2e|J zU{XeDz_$B=b?}(7*qD)7JWb`P+29A19L_~sc`j4(mM-(BrC!LC&{S8#3LxH$UQw%pDmb&*x!_m97oU%xPV z;oL|l2U78#0U#tzL?_MXaFq<4V$&T0ClU-CvnqfZaq*(k8c3B9idW#Tg9XP8LutZ; zUuzN+J))|KOk*h$4=9SjvUs{eFv@6~R7D~fU{YTcmc*a|0@fn2c`*@{i1q@B;&^Oa zB`Gm|G#3iv5HHvusVV`&P6I29L*`rrKWeY;|BoItAK3B_;pObuBOKDLweiz@Fo# z8Mxb3V2};U^mnzYH?B%-SQHgShP@jHBU3PK508b%=^EB{Z_OE_*cD0m)6JQ${j~4- zU5K_6M4qrQAMH1#v{LhA)1;JP#mIQ)2puW|4&>~K*7l7{Vn2R8w{2gkUfM5b*iUUQ zY+e>$*`)_JGQM+rS_J^H0d1e%rnG(If1K^}c5K_W%?6Ear?G9@Y1BB4ZEf6`jnmkT z*<@q;N!t7S`TYgYyFGW`?3|-xj+yHk|GVbqr`*E;CuA}TE|iPli}b9-w_VkA7mGiW zU7F`wj3v+g(E>WR*q{5G*AB9W3{9!1QxM@z6g!fT_udG{$e4*t>O%5ywlrI{dUABF zdy)T`6@0^K67sdy2Fj+Dq*JwSF}it2gSmtMKD2crAQ^iQ=HS(9J9#dlPaClJKfLc< zZ|l&Lgsxtb9Fr}viRFzyfqmfTZt{Qm8dS{>zvH87__FyDaK+A;l*lGp13l+{cFTel zR}((v{==%fUC?c@P=JV?l%(y6_$)WTMpsq@=~VbJ4}_P42sAp$tc4!$i66FLn8aAh z8tvy*c$Ac$a&s13HFsB5#%H~7_SYQ6%|&N<8An}^@&Q@Y>N3=!`kz)%y&RF&z1xw* zSGXArNT?%WA@Mvgl7WFB=X4|LBua!-p9(?|V@0Kh10;6m6{dw<)S7L%7M6o2UTWvs z<1W$QImjl?kqmqi1)C_}++>~}X7wW}tVYf67yGK0;5V8U^ZiL0#YZ4Frf1(eTA(6|T{oHT zRoJa2x^!}fubw#T*GkS@adW8dPo6qf{u&$pTG6qzP1CJ8%cmpl$BLTU#oM&k9ZuIj zP)^Vl0>qQF=u36NBuOflZIILO`x5(&?*D4-ES<4rwc-v0x zr(iQ`B0ODuMoNj;kBH88VL#WXmPg|;H9_TV?`%~L2qi)k(980(i(&_QXKsC(tBfKXEuY+kT z!eD_*9tPtJ^k6+QM1EeD8oF&p&}{kAclHWzn`Sq;{s|K)U`;nZ#AwA2niDhKzS?}~ zNirOWIKPuN?^i1xr`Sz)uhjCKhDg$1qWii8DML#hKhV0O2{l6}O% z-JSIrpS6$to+?Kg4TdasBTIwQ6texxV4k+{Run>b;g5T#->P9ND2r=}C|S7Q4A~Kp zV;s9(~jd$dh2CNR8@fu{Br@V zO@#U|lf3o8x<67he#RXaEw|5VtWM@)^ID`b1&7*hg)Y&@kHf7csFt6c3)z~`x4QyD z+T&7Nh`H9Erw%8U70i-1ism5iSy8?)X67?ym-Kf9>n&2aYaQL=;oc9_+K+xup8G1X z#OtAJ=vp85LpeRxk{{TFY-_de9)@a+ZFvnA3QI=VzQoNOU2A}{x~S@JW&kS&r!tCV zr*IyOQlQp%YO7pQl7gAN5@TLG-0xn?VneQ+bnPVV1*t+H}MaB6mMop&OQ8qJp6B;azR&UctM0^fV$ofdt=gKO}B)&Q} zyrY7aDl0ydL~FL?3YP+WpKH+L_k>vvP20HC$amBy-SNb6w+gl6Q9!tI8tiNbr2u*d_ zLb80tgKtNjAOzb{g9uqwTfQt)S1=7@-<7E!3Zr!Yyr6|_%$K1VN$4U5T`gUJ=0dvU z`Ad|1A4Y*P*qK~BGQ>lwkd5^|0ZJJjRd@m-s#EAJJK=L0d{S^ONZq0dhGbD%hn^x3 zU>Ho-uU}q&QijGGRsi14$#8w2=eAP>C4S&c7;yAHnN|hm^B}!};{NbF%+v(hu zoFlO=llfig_QXtL<86a&96-lOexM`HYT#-ppXT3ybkJs5Nrfe)eZ% zC}W?bO3u8A?8L)GFSjpCTAVOyBuyLdN+{EWwW>W&t(AQ{8!ct2@uiq;d1mTR>aVG; z3sWJU3^2D;=KU>6{6gM$d*xQ?QPc$M%^^-Vr(P}!=Q^QN z?mTa&W3wItGkVR(C3I0G;H1A>94tjWH$aef50N61z(AOY1J@Qg>sqCo?Mgf`aCd_? zkywT{)j;Tf#C|h4l*u(OT~T4vyfs3_QCqfuiBpxCw+|)r(sL|7vBG5v)Wz|dM$51L zj#gr1O9!Xgj+q56fljQcKw(K|j);j3(UzfSSQ+7w0BsEOhNDU{us0Gue8L)E=NuKF zLYGDEiy}k++67h@BZM_}tAwg->(!)Y?&c{h=0rnN)a(8u?Pp?tI@I>vU7l+W1UrG$6o_ zK6 zMA242bxK_MJQO|T|6{0D?$gi?nfs4h_EIbOk}`bk!e-IDz5){z(v-YU@_m?1iVN<_ zXdP>K(zbHIZ9h#5I4J+d(KI<@&CkGHH*xhkR=aOjeFg@L#^|%b^2`=LmdbvK#($Tf zMU`B~Y4YpuJ6w5qtSQ`o-?i5Mtu>6fuY+8m)clZ_@TjP$!?c2rlTkBv9LA|0@q+7} zOq`p4d;@mE0_>KxiJBKy`f*RsONcmJZ4R+QP^1`PgM&hcW12znae)}p%Qf-kU@35M z=-Uvbi83^4b~M!DP!Y~xNUZL*Uz9+}&4b4&Af%*3z+k1Nsx@SfPVd(JJa}f;eX5_| z?yCJxJ1xBLx)$$_oPMoX6W!&sPp;ee9Sc1H9p2vF{CLB(?*mLdW<~SM$oB_4eIzwT zhz}QR71iSPPk5yqA_S`_9BmFw%W69k;BOu~B;mc*n)nTVi|>y}UUuK5)x7mRMF?G- zl7DtapdGF?_{uNH_BwKh;D3g`6Ov+9tVe;L0&=&OCbaxg z!F>2WRQ-oH^6K|alU_|!pJ#MchDxnr9Q(R+Pn!P7DdWo99J=0?X7_c_7DwuMBNt{v zk{MbfCD5b&HpZZweU%n04>L5(Bz?eradaLup&GZbKVJ}6WxDgzpsM}$m0C%0mhz4E zudUJ4q_KE)<`lqvC+^FLA%Ea4?NK$Bl>TNtlMu~8VOuvcQaM?700yLXs{#bsq;x5P z-wgv6)wvCVCS0Qh=}QFN`4*4Nc>QZmG$TB(8-XnzZlGX}QSSQ$s5)upN*ZSyly(6f z^MX>JAkHI^?G*){DUL^6M|1NWU$X+L2U62s16Ev?7p~p!2;!-qy@J{=kOe=H>)_o_ zj10^p^FsMsXjc|VR?vYKL4Nr}Ocn6s(n~FTSjqVS&C4D_3wD!1nXO5~Vz~@J)w5OJ6M{Hiy z#yfdmw=rC-XWI4r^)%C9I^oH4OZm*-`?3zZg1;?feWiZby3)1QpC{ni`+Z8S^R{?z ztad-xdOp-_n(6pPV8hYvOz|wEndSYB%&>&It@>3q?axnUitdyMyGhP2n;TbON7{v0 z*CX~cfbxCV0o*N$f?s^sWuv&e>yvS(>5dn=Hi++^I-1{*H+-`tM7zQS##|fI>(FAt zz&nKk8a?2z2pyJRzHQWxLBMA(YxiPW!Kk$B(ctCok+J8N4_gSrT9X6?pATUBzZhl@VVOi;TY@FmudBVC4kv*>z@Itvw}jF zOxZFB1CfEMi_|VxqP%vpdW#IpZ817s+0HOe4z=qzox~H6G;x*sQnef+MBC{?j?x*| zPBtAWP77?9r;|by4JsDMVZ@*{rg8;wBhjc^x5!(FCv8K6RCGB&F7~bTiI7vfx2a^; z#hufGs>dV2DY2&h55LOuJPx$QiQAEul-;x1z|C4kk2 zq){?(OwRi~3Qjg~=h5*&6=I{gmEG7Rfk1%JgXINh?QwRf9?!1yQbbZiA5*QZ2aR80 zLz2m9P9RhF_vo0-2i|WOwLendTA6|Jg?doJ?U;fv*?oe6BsbAu?c>Q6pSk+%O91`6 zPyU536hKaIPgDJj11sa^tr+a|_A(GJH#&{|MMi=b!sXEEq@QC2ruP#eR4xgP^1?P! zdC1iM1(1NlR9ov~*|CX&8kh#)kp8$GNSzSy1NGgN}4`su$YIhic(WkNr_ zd@)^e^?!!6RBbG^d6MYyPeTCt385uz&Y}oTsb)!9cRIUr=v$*7V$A{ysrul?agoht zZE0u+wuJTq(+}^_ahp3ot)b+8eD`I`#8_c7sW|1Qs<^tG+};~NA%Yw?C?{JyN`3Vv z0Qh@r7}czNIf3w$05TC!m_Q}md*b@W`eW{gu`$g`sp_EmpJXAf!<3LIRe_%0%8p|B zrDo)WgX0>!h#I&LC!*QGRq4PHzU~B>HZG10b3N=bec|6Gv9ZoP5q#nyS-_vY`Wq8m zKbux~Y>=Pm_S!K{Y*0^NZyWjqTPT;#KyQWoKfieAtf@-e0PWzlMX#cn9&rP1Y<%7x z7WG;WEW6on&z_f54nFZt)7Ko>lN)vCMvu$U7X@~=@2Py;%}T%E8^OIRx+6MeKd|vD z(YzkC=wuF5ReE!99U}aV(WnCfofu)!qooK}xrr{H3o*GA&CE^DcbW^T2)vjk(sJYt zXToEt{4`ov-@XW#cpx)43Wrs*NM;BlM+iD09Q9e@gEUh_;n8+sUj&s}=nn0`fbc%Vv8;6g^x{vs&z6dST*%w7w#!EZ zAAVUtF8pnTd%c1^t!Kfva{z=Wy6VH(!+_Y}Z|1d5@u$g`({rv4R4n_;N9>Lw6h|(U z+o#sy@y+yE0Y-73w&q%Xpg60~S}r3fSwqkmtXN#5)L1=sXaL&WFmGA7{yc@FE1_yG z`zr!0;8tss-2z%m}^<~wYFAINDdi$u}U%K zUYg^tfQ?Ft3C(@uu?{8)^zJVsg4)}I#tfTzz<4A(p8Bo}DL+Syt>}=>MeS$5jrHdW z@Y}-0dc+{Vt^KWpg#U9he=It`$31l5LGa6!fy(pP9Ybe@uXC;czWddH=q*vfOaJ7e z&?SBZz3Zt@vEL58TE8jyU-KDnAtid`qFtG7@;fo=jz%bJVvQ)EMJ@|*La{7mp$;P_ z!28leSKuI~NLFf@0fjCiz_Xr7E6n@`CP~v^2_i=n=K#&l>c-@k=lNcf+8$m>kVQYGHVUDh$GH zY`CZF!uB6s@W$N88Sloy3SS`eo+5=FrgIF1@PY7xke9dFUGg8!Lrpxfw_zre&3578 zYkJ)&(Vl}2=?H-ma zE&?b5<+nvz3>=>CEGRcTs@%>Q_M^1Sc(<7AK#BQsSEfvmCpNNy`VNef=KAo))41vKyc-K__oHN?$LqztjsEIW_~IRLd&ZqCKk*40;3fZU z3I0a0%i`RImisd@hcAMTbvalaSKRLoUJ4atQhHWnU!G@WK%dUx zMBZO~l$9kB8K6_5<$~fQjl(BAA5bw8a}mk? zn%INGI>+k}VTfceo1`H5)X4+?)3#)28^=D=goJB{`+^(+|3P|dXolMmKVcuPaSE=+{l?0 zcNs$7HILWX`zG8r4`ijJi*WN$>-5i0Z;!uBxG!VFUi_KZt_&jnULm<*ZhO`E4Tvd( z8d52RbR1=#3uQc9o%(rppPd_FPAM5bdD8R>ITL0s<4AO>zUyz$s8Xf|qqDO7BGlt7 z)5vCZL&CUD;oq9`rXd+jgtn!Id#caFeTNELc`domD|sq17RLgY{LWgX0-N&j3Ggb= z;2X!52F-w6)Mr$6Tg<&LkgkQ6Z&VSgS6+;rY+ee%n1m^?jgM|N=@|v^-Q3a5u1!lB za8+bT2(fhcaMd&=H@Xn5ssk~|+05}9tk}@)S*M&Ceq5^i0xw+$Fg~rz{MR40NHwsZ z{|*IEKA=EP*LesEh^n_1N`tZ4X+he4C zz^<9$4j%*kUGB1}t--C>LA1UG(r&m(h*9@J^f*G!~v1ei4C%kM-!YXFm_p4#X?Kub9OO?jbL`5@v@Ssk5h6PfJo0&E4p|kYUad!a zw$U1Mp%Jh&^`%(_x&zE~SZev=eEWjKp6*Zf9Licxjw&eoMQs(}-{!tzxsAY>xqQtV}@D| zPiY_!v^rmeJL}kt(Ye6Mrr-Y3eO;17Z(~^h*~=91v>I@cA?yX_uBglZkm+lCsM`e# zm{bcO3J~xKVSW$W0o#TDP-hy5x;0_0p%620jqOQy!}X^9_0NP^HVC_%VW__7!^8fT zw*9?gfD!-GebaMoz{z}dpFI!o&Nrc4v3*m%!g4aXKtOMG5&zbk3DS`dd{YN%C%8ZH zye>4RDmoltJU+N8iV!BEzS^I9CeOaSCStLfowxYQPIFsD8imjAr3odcFn5T`r=%cQ z72fg6>Dd#&(dA+c(f(yXyMU32{u5EK*K3?$t8wdhhCz*zob^5}smwM=yOxxRvEvBx z*4kK3Ey4rS0PQDbUC}sdVuLwaJ2$`whl9?4mC^-0(H*@@qn( zh#jxwWCT~jAsXJbpRDUqg+;uJaaigAbXsrYiHDf_bfk?H6R5k19J~)#Sm)95M3A4h zxn8C@TxNk^_B&SZ0=o^P6AtdkVeR$zU+O-(@(H*Z^LU-EC6+s47x>xTB7gd7;6(oR z^tKQ?RBHj|5d5;v#CGa>4j<0e`!`|U0wy=!vZz24mawC8H~EE`Aeee{3j9Rh7f1S`LA;&h$O1O-f$xr4 z3xo0YoGtlOxVHv!R|mWD&0y?p-JtDtx8EynI|AaVQ_nOC7n5W@g7t6YdNDH41EVlm zTkMFrWS1(Yv&lERn1->wNEg7d=D!8~g4Pz+e=tN43l6Q*KPLQMWup%?nUH>O6R9Ww zZ|G!bmNl`kW*_+$1Xf8zR|+Rd-&iySttWD0Es@W)N}F*AYe9Pg=A=OgV*RrKCb^0% zx*x}MlwX-}aN^IjZAh0zRP#axSAAB3d-3oLp21>*0h<>Y>*udDUN11LjkD3~WON+( z#)^ZERTiOkVxRnldvO^uOm3rGjO1WeU~gpu{pu+sYcs&o4=zIs6 za41g7-k{88Mq=YdQ~Fx^`BjN>tDgI8uCKVhV!?{}g#pgji zypc5NsSAfHh=m;qK(-vQpBhLYI~R^Bj%?`eQZzQqeMM1gXplWtNTfgnf=;1e!!Y#P| z0PV05;9h%sClBUI*1C4m8gL-n()|$oB3ZL5kB$bs^GZnn0~&8sYN@z*D<9~m|Frd9 zrkRJCo9W=WjWhDBqRJtLqABOjD;n~VjEic(BjQ%H;Q3BkAJ;MDKVPID9K&HS2FAjk zLIqo9f5O^=9Z~f#!&Inmjs7(f?5QD+24%5xXcL$mUnBI`bb~IdviF6fUVUg^0$m`Y z(32+JD;5g=q)piNGr_3vjbP|8I3B0E9pFRd@|fjzrokGj8a3jrNECwgP)Mg8klH(W-CX$2M%F`VxDE zV2G-eQuid8Bd)igQ%{e(;I4Uqe51N&ie+5|dR?j6MrO`rJVQY~uR6)H*H;U%-`0Ce)3b}kLpR^;G1WJ#dQn;pY@qCnofH_a>A8 zPFrbK>v5;;I?aoxyfYxh9_|0)zmV3Lz}Uavm7Um8{}#zkt1cig=Nk^n20-`i^Bb`@g>Q2Ry9zzT@r2VbD9) zv0)HeT+WWYuD2#;#`VkA&c*Hy&+X~NuxQv@>|-+a1_)-lGf3p(NZAE%JFpCU? zDi2NyS1Vr-KDaA~HRKabs+c0D9-5huWpYX2v?bZ0Pa?jNm1Z+r>n?0`MxI*+de5QT zA+JnThXsFR4Y3z5YS9z8z?P}Mr+7Xt?fVo!6$ZmBPPOk0Lc&5={#)Vgq6gtOM>k!5 zUd!PxPb6uE5g0I@-$NtK13YK&Z==Kgeir`txTg11B#0fu3@EG2 zHVjZUWX^iIQoQNDKzv!1d@Y<*Cw|9=o28YC>os1a#;`$Ibx^pgOeY#co%;#fE<_Us zSB@8#$E^sqX8>I4B?Dk|jG(9h=4~MBfAv1Ry^jKFAj+HgMj+F86y;}04tDIvQH6~< z#Dc|Xx0hXc!t&7)vg%LOZK`h6lZhpVw!ed<+0+dYXPDSPyrLPPh(?cOhB@Z0A#Q)A zPM}CwCEfb+fDYRvL69g3P)$ImcTlt1r*e(f9r8a>K-lBhLvv+DJV0zNRU-K*^vM{ZjEuW+eHsABM zq=16GNMY7hS}lNMwq)O5^L6)7BTvJ+X$E_r5JIC_2z!ONI{A1d&V{wR5Nf!u7@;vL zbe;vz^PK6O9%`PQHJJXCFN8423f8FDcO-lH=)O48(`;BP{Ms11P2H?FR$jmwx;PgT zBe_o|%Z5WwtqN9Af)M53LQ%;cLEhwzm3N1f0y)Dd61Q>oT^Aa$hR~aJx*49s9pVII zx==cDxMCQuEKa=~X&%~{kHcsfuzVVuYOj|QZ`jSSbW926mu35LJ>flFT97c=cCfea zH67xUqc7b(Ekyc9vbqJdw=UGGLI}f1Vyj5Hh5XuPHW> zf_Cz&H^&U5hH~kGQP2qar|+<>szNYS(|h6%0XsVQs+V8g3;s^jGtPWf_Mt+?*iOS$E*Aex(Gmcb-HZM52@b?#Ta;^F*Hc42tjB$y<-6y#3l2|K zd0%B4Z=OSjOieuwx>Ai!_Db@dS}Y~()jIq)RJo=WQ7^?j>sk`d@|4w+TgFr+16Y7R zOs|vOCkC`B*qSPOxLy@DST9_nQLBTdIK~F$EA^z$^0rGN4UvfrRZ7g3KgF=hr-9Wy z&P8KZ%}QzeJz~+HnnMgv7%Q77B+NjQ{YMf$-^@WMxF~wx5-gy7U=IP^0Y{zV(x3feS{y9cDY5Os1v6iS3-uS=_PZ%rwkBp)djWb{>sa<8!|9DuOm)N*F>3 zaxh*yv1tpO#w1d)GEoV#nUU7m{H&n;oP*Vs+aUXbWz6@$Hr_JfQ3k$><|2nsm}JIY z=BDgVCVFW(k)u@=VDB7{L-Sm!$Oh$*`wF;%SNV53V^D31Dz0Ey9jhsSR5NZ@x6H#n zaw9vAFLEY!!7nq020xUg|A#T|mE)J!mL~q{lkirxMZ`J8({G6KJ=fL>0BI6*6hI)d z$uV?do5V$>C2BF&O^~2+4CQ@+JQ|nELvf*Sf-tQ|tgZfwj>@!NgSF{s>DWD`Xj0Ch zg`^13S!P0RL1tINpKt$+no8H0M5d#~Lv_9$iz)-}d>w~7x zj+Pe4XA85A3cpGR(@hpYp&RU?(ItsaHie)iA*lFI>ARiu#;t9XC^6E>jE^GGXuw+@ z@SQf4Y*M^ep$UQA;EU>1WVHwqK@ZvH1ev_=!3pt6nm#r?LfAR}zeGt2DvZWU@gW^I zkXl}fBDl9{rZ z@vi-PnR$5Jn}RYpXsT4Imi4|FNBl(%5~dL6A#>J1qa}O7GMep$e`< zLdu_S6@#J%w@UCGjZ;xgA#B+U(cB4cvzGuAlLUBctMmN{l#LEsQRTjfK8Dx#I0dnk zNh#k`pGlJRArL7*Rma~P-BhdWuY7|56Rc9ES5KM0r+vVpi@xEzyd0>T0nVek(1N0N zu2BBq=nyYPU%W8zX-`Ed_~|&=U<3elfqQc~W8*+%1j?vEOAizkNE>7R8qB7G?AAM5 z1myZm0>_n8z^n^PNFY~5@j1G<79*s=$Q#`auWCsc7O`wjvbY$B$qXZbZoamFISY1) z=iv`w!!mrcDP%_KMDlNTjtT2la|Mu@H`d9CKa+OiD)?C|=Ns$5N-R->r<_#`xM%k} zN+7NAR4%($sF#?*Zz*9x%qh^{!_WJM;ILfqSK1G-+-a2Cc~Gv7P4jU$F>=u02E}(p z&btZ18Vx6e)yR$jrzYtaAb=t|4tt?;nGRU885A1>gnp`H_pY4T4|xe~M^wT51PR&Za|#!=vF4@r|#B+hz<6mb1m~fvY?7PSp=7QG4R=yEI62zJImT%`n;P~#kprw-`HiC?yse)7?dWoTs z_|tsGw=4&>Efo_XYtI!*(2@D~G*G?P6uKoPF9Rx|X0CW4BWE96 zSawu#HGV~t59dYIKOZK7o}6e)Aqr4X;@AUZlifzgf08Cp(+adNcZgW*1dZU&;Wkv+ zY;Hr+BX`=aXBHsbz5l{OpxS$qg2alU%2lr>|76Kn+D$06s^;O0=h)_%o|6DRRqXbj zP=fu^5l~XX{~9X9ZCE*rAfL=f0&!Tf2;SJjb^MU;11v2I$%Dk(-~=ytdXu+|z&p~p z!a`f4<+~K{5~bTo7G}YJH?NcBvzDbVA5~(5>}<8i4G|uy9#hmSvdjpCid%Xl6o~S3*B&Ns6W0?q&mfJane!E zG+quz8CVYPOzXfP{4%U`F%k6@1pTtwJ)1!@&HL(bHS*_=EW^J5F%?Y7|My4GbU*=K z;Ya*c$2!2G^ep6k3EY2J$oJ2IFS=tg+r;IPU3`8Lo^KyueK?{F8zWD_bXC*0QVp)% ze8Og~Y0F^j_cb3~cQh63OA0TZ#;;DoJ_THUq772z}3Y^!P@icnb#``0y`8D&bHX{#El3r%6!l(~~# zGAl{1NXC;@0Xbs%W9POd$%1)Zs5hK05kGpn0HZp*EUF$hbYL39Q=hzI@?U@h2ZT>| z46hyepNsKYrv541_&7C1_=P|ILIWw{Ius$$%NU9Be1t-T+cedQ8W^;oGTtQ@3v+`j zCz~~jG89FPE);f!BFdKQV+Cnl2WbFlX63kc)5|;tDpoa8?SXlJLVzNx;3(SI|T%=NCS@*@C+FP37qt*rFE#7TWy>>|>U6maRA_)g#JEA~lu zEVLvd>dfvW4t6S8in9)d&d}||6-QMN<1_NfWy|ka`Z=OeiP)m=y1ar^(PfRg1TVt7 zDxrdn5gFzRB0fETFzy>-MeFk!YXyibV%AN5i}-9)4RDizz2gm}r}o^OPkzUZhzQMT z1{3;sGi?7f^7djuo%=hp6WJT6^ZGb6`p?o{Iw$3FTK%3GNsQj0V4ps|bc^t#x|~gI zZY*ZBvy#|>s*`OL)1V@AyxD8|i{MnX$xIF-%}X*QlSSz^owG#K)jQ)dJ>BW(!%)PH z3NsR8{jIL;a-urCJ;@iFh?3c4E*Ib~B~PZW5$V?WZoUP=#&zh6>WqB;2AeZaeNzNR znVLt0sa{-?V@H5MNLj+Bc*3&-`bS}?rKg0{dLev)jjz`~AMmz&M)a!rfVL zHQ{jdA0s66+8*K|AdvHh;X8)y@Yl?_fkGEGs=aUFLu1|dCDs2t`DMue$#MVnAQ^S3 z(jMayl7xR2Mc?^mb0fFS5Z=oS4-0P37EKIQmnI)nD1tfIaYRiUzjl{67+D)H%_%5p zao|yY-j=nlu+{N-k9b;!~QC&f7 zrf^@jbk*hl!?WGTJEg&IBa%@Leped*lFe&7F@7x>$R~ksIVQfY0yJ}_jC@HWzYnLV zsIOXSqb;k1QNqIFuN`^eaqx6w^r2*|)s25#-uChgYwbly;L1fN#av7I!-a;Q!_tmt zCCyg=c01!z-gXt)==fIQ`75k9Xy?b$<)X7dQN)s+w8X!Q4F?CKp}DU!9{tXl4hEIk1~k-6#YX>@q@ACEb}j} zRcx~w7wa0Q|K~}QSlY(ulmGdT>sm-cz8gQ+$4@6l+%9)Qr7(eV(o*1O5yEw*G}b%} z5tgk%HPD+}{dFo7Ud5oK=sBohh?5XXc+AkBXVuyiPYcR3<%GkTzR0^TosNLfR4F8V z=6hZ+m|%J8-?ZFx$l^^8SE1J>+%YCQ=F15}5Fwm)B+zE3Ol$Qfk65w@^$*skNDR53tEyvL@C(Hgi;k3)Y(RZdPL>XeEa%7Mt z+xsH7tQDpeo3@uH2OBGo5a~1+Hl43gHidSoz7IDm_EljM=ZCYHjD}?a)dU{*MG7Cl zR0jGiWrj6`yk8KH_VM@ZW|7qIJP`QZ#6P4p0@w(!c#xy{zpAWCv3PT%m&>rwMKvw( z33Hs_(8(Ek{igxUs}O-(1OK_|EOSFrCXh<@uT<**^q@af7N2nb)?-3Ij}egJ0VGNN zv5H`9F^-L(9B|&KXSxu6oZwiq%Mc=u_JdvD*&rvp$EZaN7sS`;KgYZceIvr;D7~)a ztqHTk*CGlPrr?W;{+Qv^7UMUJSlVd3C9f$q3%eOYWSy0ce9iU*q99*jazR1CS`oCx zX4UWr>d+xqT@^uWw{!TUv<)5TUCmk6z~vAcl(j@$&4*#?*e zxr|Jgk`*R~;Vv5SNZ`@;`dJX_^1>KWH@G5{M;@ zzWX-_h3n~Si-SO1yaW-6z_3DLmm@^HlU2Sh#Z=@RWXX^AC&pML&U*OJ1^Zh3lxK7+ zx=g$ZLD`sJsQ5+3|5(Dil*kV2n=kJ&vZdq64l7x@5NpsxF>DQoW#`z$S8WzD^koM{ zfgWi|Q)MFP>YHXQFA<{M?fz-J%ksf;nlw3`Kedv3(#M8xMHqCr*{Vw|xqw!YUQ_^- zyD_H+3mcfIIM>K%N^Pa66UdLFVAy?G{y-MLBwion1w|%L{xU%LU{8)6B#V6|qG zQMRf2c%`va_tyhw*Otd#tKi}#qd*B~Q>`Ki_LOY9oFG{GgF?c&%I z&Y_gU0uCiNWyd{yH_soSn~a<0CgEBq{uT?(p_6Qu&SxY)Kb`|MQUa2&NONKe%)6Y^ znfatP0#q3XmNBU9EIZmMH>furHJhO}NYQl#;j!&`Dc~!4!qIKMx0LYQyUVWABS+>w z7#?ou+Xs1f9-Q!h;ZuO$51XT+&k^k(n|F&I3jq%cqQcnwGY$e-6tqi{Q*abqsH@T{+QkQHqP`dTRz%h2$@0sS%?}XaWq4aPhtsD-bAmyVv|D7Dzz zWFYk*oov>TI)~`2#H<9+-b|r#xyY=+5%N3`UmRYVUDy%QP(5^br#KHJS?xT72fCeTk z|F@QSmjV}E;lodSmP#Q>Rl$0o%l-=ya=V$3xFC{aAla?%;yAj^P3R)XjjJRB39u8(^r%>KQYnlEn99ez~e^@x-Yx%1Y2!UbAKYESup2d`jCnPHsQf%RH5q zt7p&%;Wa5q%K;m$m$zIM4u%tZZ#03r`%9%d1^%Z6BiMKXQpsAa57)r!7es$vzaq8& z=O^!_Z0;XWOH6fLY;fdEvq#dxEE=Moa+eBp2CDhG05)&bI9b|csgbX&!B&ElVoI*| zM|a^GP$jY$1_9r?!?`kN8*kzAG0hVRgHyGZ#}g$bKs9G;?4dR|-OXt>oZUacij#)Y zDx{8Nd{Myj!nef^UJecmRZ`z7$B5-?Eme_VXxN$|v!sJju9K+@OxF!bI9QA1~EI+J*M)!|{PQTz4fttkX*~;I*9O36bX5pWEJH%s|tuqBrN{}srsXIan zRVduWc2bUAK^i?217%LYIFTG}%6d?5*m+f^FnS$9AQQ)OMbD4ZNQ!5NLhY|kLwl*? zW0&?z&(wiHWZHXetd)*E&BOCkY9E z5ZyI5RY-0=Z+A1KZqbo7)mxF!&OvCsL4$Gy2EH&IQa4=|V1Nen7lf8Ls@(bDqBk&> z`U{Z3h#CGvyzKHl9l5gq%VNPVPX~|#@VNdbOLeLT3t|g6M(5k^&$$Drr(;pn%xAFej#O=bh zV15D3p?|K__S`uG=^j?710Pw5>jufG5d|16iyNGCi((hvuUTLr!*^Q(wd|+Sn|c(p!+;!T3S^OyV0kqMJh0{4=jkdn{kL-S_dNk3NG> z&cr(OhiDF9z^n4W_tpxO2gl`jgW(Si^{-$*Rn4G2<8>=$N6>+yd$!_%<$d1|Q)Hz! znG!qs*-Qyv5*gAg*7_X7n0qj}e|dpcr*Eu(_{5Q>f2y|YO9R&sC z%94;qQSX*EX@d5md?t~IBrU=L7`h77C(NhHA2i4 z!*0i=Gzt(`Sg4)9_=gm*7=7&+(s%lidftbCyoByQ?%};{-vzeai28kAG9S{JK%X;T z-BNmx^iIMVi8p9d_jBE$WsysK3QeXK7u^mI!Q)yNdI1&rVE1}~fc8GgP7){h#AV1= z+*r3}-jWJ+`CwqAA+GVLiH2L%G7Jh!Vy_yam*N-F*$TGhg^3`Gxxoa!mHY%WZG1ga zp1BI;^@R|?+z+@X@DitO>%C2NX9!Yj-8GsyI#tV6jqjr0qPc@~GxInId>9WZ8l`M1 zZF~r+VPF!SQ{li`kp8$)l#&o1=SxC`r+rMfG&~UCIQYdZ6aOWT;DG9#fpB9+dzSx2 zy%_v)M}l3bzq2nVMw-7hP(du(!}c0O)YCvU1R>8UPF42-`rs<{6rz6icxBcUwZ7(x z(or!ED!SSV8>5ABO(vpP?~|4`t3MdVfK73u&gx`$eNh+pVo@xFwScX9%kW`nh z>C^2etHn(bd9`&22l6*P_W^Mr_t08i8fG{qK&7i zd#zvp(o64LJ8kH><-lLW=d*NRy|EwDi@^oRYpbChFiKzI);)iLAtxUOS&5*r5hv#=`QISTDnVGYG{$} z9vbfG=Uw;yW6k2vdCvPjvG;!VAq``1h`#7EGru9U?p4Mm|4j%-Zr7xK+T1(;Ss}}$ z+XghIH(&XElrFG+?{8-W2Y&lO66)`tP~as^wt>aJx01}WArlH|4K*7{58a32dk+!d+m45xf3y35gF=C3od1FkfHU6ZS$B}e`OG7J z3|a`ABL0W`vO`T>Uj!OkgDfJ`LU1svwtjapOigl7F;@b9h)i&U$G&{7^cw91B=01>; z&h_@7S~z^fYCO!$*r&(Xfp#nLUzNYJkVDw&(f(MyudeKj(d#N(u#A>Cq!D*RviR}& z6INGZE8#3HbX3t`UxMpQKuFH7aULZi$`%Ahl;5-Ey%!Hq#HYH}T5VLox;T7Yd)7X-|#9asy9Hc5I#_h z`K1DU&xgd%2eF%-w_Ts5;Ai{Tzs#;|05+SAc%r))sNxT$MSRBQj?lyifk`pSRu0A$ zd}HpB)_@Ei3-Z?^XCwbhP5u=*VN-BV{X=Z&crxzR6aUiBkn5KBFuow!AeP1SzA8n~ z12rcFiVNV&DLyuh=QN@E>5^=sxr~#6pE7!Nov(sY7WY2V)7fSvk}QyS0UlqHKJ}Y5 z5u$1_o9#q`qs$`7)&gxrdD-l`Y0(SDFLfG&qJkXUk$yP;#?S$5rihqb`-&dPFEJ&U z{JAjOXR@7n?zW`SH6@ltc2z-6n9Fi(?E|&a&rCtPeQp!m1}law^C?&}Rv239t_C-t zHz98rLz(qe5XEYvh|2DYA-4_=w5MTmv4B|ghYEqDl_RNgHt21RmaIQ@55jHHVloG< z^4t7t>%FPw^ziaWg8iygel`WeOO*E5Fb6g_7ppS&tEXA%;wfsSS~T^9CGU(ZwO8oN z8x(eC#FoM0&99cj`PLTQD7m_5izOoW7Lg<)t)3n>Z^@~!(cSkpaFOiIr`mYh0>sg@ z*ir)FXN}5HN})@fu<7eznQE${uoVs|svVff7#qXB?&4m%r0x{dFlrX-vR6(3_&*_y zjwO8mWMeKPr(HsLKC_%myvvp>tx~Z=b)bg#_kREU=?pS$A%SU`Unu_0jS$Hh zW5M4ap}>9~m_a3&n&q0G;Xi2>$l=_fio%T2!)L(I`FhUSeq_7GJh5W7s&_Ps*iof^ ze+oDIHA*wC13OwgG3Dc!rq^S<#IaW)t!9gR{rDw5Q4qJOMH`3c;)qRVy3i&MzP7$x ze5?!t?HCok!IEpv+jpYm2Aa3y?iu(Dt0nMj!`$AJZIwg183zxiUwSY+i28( z@79w?2S%t8W&q=N{pXA{@%Dn9&%v!x%H>z34510!h#Op-)AZjh3$BRbTNC&zjl2yq z2AIFhNTcWEqNzQi1IySeHmUPtz< zegWcgmWBj{C1Y(SyE5W>6%V8IADc_sQRSivSfvY%^HvrKC63D0WAJchGan1_@%T-| zA`}!b7>kw#u2r?s5&LaEy-BF~`s;3EBjC?=LCMB|uFSRl9{Ban9<%$hK=6-BiY!&| z4%dqLvD5|qaRrd{WO0gK;X7!!q2E{`4=dG2oAhW4q5(E7edEZJfaY&k`1$L z`%v-HAPGraCITm;)n2@++^jWa!94C}l|sey3|R2BCOh4Z@o+bxAz!}N(lVukems^T zDudEfMOvDON&-JL1J}1@PEQ5_?u#+ zK?*tI#0qZMbwQ?H8(T#TH#Ml4h0m5w2lP>CZmB#p>Ptk^+G^L6K4fRexe*hum@S<2 z_V!}A>s$j%F&Z2bF63VJ4`$ z#ZV*A8q~(j&@XMAwZp2PT9qo+S`C~IT7J-I-h8OYe_t*nm9PKSCR02T0*z?Pc%{(* zVi^wX5Y1UNcmc{PCvPmk5_#nT`#cyn>@C0SdD8`CmgCY)0zaDWS$k~K2DY_se6xXU z1a!YfU2H&brqEGrUE^<#?dGqOA8JL~l4w9vcqh2QxmNxvMk~WHsftE|#NoIn1c<&5 z^8Q#RdH2gHA}5&Qe@4{hell$wC|$xZX#%QD?1rm+C#JcjQwq)gp@tv4?v8N3r-`e} zu^6h-nRIiOc;!(mVI1$UD&RzKPCD7Sea1ed4~!}&u%Ymcda0ijM$6yWMHK5aMx0jssKO|cW+7%V-;rdVNtC#% zD{hzpd&>jpP@x`RmHctz~_Y-GQS<$g@DN{vr0mnX@-i(_|6dex`ep_rrUI^^wR|0ohr%=(jp>gMmR~4( z*2kNA{vyVZ(QoB|)`VBg>PM=XT3B?txZ3CSv29a;S2qs49><<5r8<3Kp=}6|*U?4# zwJ8R}dL~W}6k7vLi#(d=^ zN;FnuBa@8m`-*8drD+e(3N*`k8zp?MupWLOj5yG;z*pS`r3poiKLU0d0hd$bap8UZ zq+8CAa)zY}?9SZ^XCwEd%@KE~++Cs-KxbF(=RFR zd5I$e7U#J(7Yb6tD+tuMQ`Ux7gm|();eYCt7Q2t`h~X^LIDGHnF+*4If|OCww5@mT zWFi3HP7X3%V@ZiqD~-}4Z1&KwVF&}U_IaM=|Ng>{z*hnmp|Ab9rQyugm`Ui6Bif_) zgRw3;hJkPm+Mv1O#B*wQ1n&I+Y8;D@YZOYg98SRQbHDLR|E5X(;i-rdBxhiPYi1(h zl;e6&*gG^D^9Vd!LH@rzg=|mB#%{ayvP?w08jBn>nE=uws8{zywI>0l7X@-N0d>IA znDJ1k$8mECVaRUbU-WD*PF3X%)RJvb&0)Mc;tf?$e!1n%d~eV*qK2HunAY5OjPR6p zxh5=^#*(o#)fjNaD^kMPvuFdlKm;n13bvm~IsR8qXLFnU>9)>&FAOnJ|EBB;E6l^d z&PZt8aC@VQ_@wNPjs*|1KoyN}ymYRaI<74q(spM(hdo}610S~%53kj%H9T2;U%oB%PsAjn{gY(c8E55?ej+xEXG~2h|Up(h3<_5 zyaRuRwF`5cY%^{r{}Ce-Jk*c{EO4jfok3--KmN@hQ>XKg#kGpo51ieEUa#y3pX(u+ z@F;wmkdzrJWN1MK2U5|r+9IQG&}nJ-57B~rco;K?Vsg?_ zOA5}2D-)6j-KS}~BN&>0_(g*?ZUvT*;B`?nWC(se#J{UPrZt%WShw4M0tBF0LJ#4z z(k*Opu=Figb=(-yTAq0_dw*ex-8$GmZ))h=}+Eb~A!-+q!thSfJWld~dECjLQ=N+Xu zn?BS-XYQ!rx<7w1y=vKLrYj=V@oF{wYHF}HT66Lp?(w-_IbtGO=w4Q(VlW+5`;s)F z@Yw+P+DlidQ1-G%JKJ3cIXlLUR}8r9a}OJ%_P(w3c(i3*+xn@6&%aGnjLR`$jyZ0e zv5YwX1C}2B;0IvneyvKu?M#HkuX3p6X(3Q+kZPqKn1g8uIo)SZsuuW$&5EMQkaa^atWK8}dVJaWS*RXsa{voNlgOJfMRJ0P0MmB5DmB%#C7%+V^o@+U#xT{Y z-m3)8atk(oeZB5N8ZAzBX~)!erCja-3zBH7_}7LZR2!CBlG+*~&QP+v9dUuGDxJ|*Ixdjky_ z4S`fyofy|vO!i7$9C{k~&9-K+9%CNv^z5BbOuIR`mYJb`eHAoH zPG94Wv5zh$0}bCIWYDQ9ugFh3)5qNIGj&v`i#xs=mByLdXztlSDsap3QjVAfbxc{BGXDi_Gn*!Syw!$^9NZb zsSM0c%_D=aq}#K@hxdS`i{Q~h`@~}xw{A!p`3NknokN5M6Y&tsVDwA zTz8T!DM}!d>O~rN-LJAAM+--k7OWEPp^gx(spqhmaMcD{P!caE^^mYMr`32tT#o+A zWp=Z!qWm%{fLUtqJp{o_^MFaWZf+y>wlYs&xq9xDqQMRQ@0`6K>iL7>OmjJV1G;Qj zuh?>I71LT4!QlfejS;*I%dAM?>y!tI9^pqClk&s#Kjq{FIJIt_`#_;PiwMWR|HC42 zc0Z$0k1`DHYI{#cibai8a$a4gRpVOP#_6q&*<1jq@n_6B+#0)G8@ugSOSSrBJ(9C8 zEK6bBVwQ4OT-aEan-)gqN@!A;)_qF8+t`xPR_J8L=J*|mt_pRRa&LlzIVflGokfZw zf;BO|eJz0?G-$d*6rpdv5+`X_q!B-UN2fToRC_BgPB#T8Hrl!QvQZUyu5+8Q!asZh z0V=v#K}Qh~>zLS#EiggLH#FJZ^gV{2Fm8GCt7%~9FQ$B<{g8H`u&`-smEc#5J|kY>~E*DvCv|Cb=lKC3Fq{i!a2pgq>d zQY0t=HXl`u%m8Q&jvDB?{CC)|VcPbk2?f5f-w7Yu?myK#EpnkN)FzX8)OC001euUB zZfBz*#Z9o&S4Vsg)UNoYrizLnRQv02hOTA`hQq7^b|peTe!-!&4F4^zd_Ya-S85Zx z8>u@+4rtANeJfWN(|}Jgp=A|h(GP@~nWJVybTQ3SYJ8%p8W=P@F$rlun+jY#a|h?X zWE$k-NbUOaqKG_YMS4YS8fcd<-~IGj5rSk29*||oHPjhy$F%Mu{ws?;Y{HiD%A|T@ z9x2%RRFjFfy5qV1b$niDZDfn3lj|g$y-hF^XKM32S)4To#df+uu~uYU?#IrpX`>C@ zpEmU=HM8%Xh;r=-YF3cr5hf(@hWu|r)u+E){|~Kxeg_v6g}i5@*TY@}stC~aBOK^rV9Ti^M=T+3uI(S)ntU-1kLbr)5 z&jJX@TzM5>cW5&XbhAXP_jXdxfu+FOz$!m?9&;_T`2qVF zXFkxl)X?L8wJZp|jeXm_KdNuizy-2DJu_(w<0%09_!~|1SXN;sK<$4M4bgNE$zPpU zQ{=O|d_X)@{;U{LxRHew*&SR3STdh0nG5Dp<`ksvJJ zpUx}`ZP#Y|FV;>DZXFA7+U0I07(q$dPuX?Tu%jEqHY%gwIt;|OnNhq@yG}SDvCNYo zZJ{*_BRQZ(^f9}!oW}Y2pnJQxYe{}-z!2kjl**{&2*=LtI7n}nh*O7^jzLSdhAqBj z2C)gf;#A5iiIPO=r0`>f?d!FR@0x}w1DyZR{v$#noilOPox(wW!< z{u%tS6G*}F{}2zOskNj@D=1#4w__MP+&j<+5%)bkit#m`aN_9*RG2OBhIGF28&oBN z*}EJrZdIcMbncSi?)shmIOft{mymbwOMK^P$jCOx?!_6F1ZnmGU+do^R>IHPh0Sh$ z@z7x&WgkgrGZe?uRkn!!{*E1v#isz&M2GRb^iVCiJ><@?7vvt zHej-9Ht_zZgX>m6p8lpDX~8X_Dyy}-(4%Cc9=XZuK8Kf)fg}XD!hNnW_iZ{PqU7jX zjb8q;BR{wA%zQiW9G^t$L*MheLHG9ap`mY`EiiV?75O%K@g##NN)CQzan-zbK=P)d=%xe&$aK4#U?f3 zNQZ0YUJtW4gIPksn(tV~dEs@hmb|QK<#MHHHDk)Z@oD5rtKpc)?z5*mGMJ<9olN@o zpfB!%!U8)P;CkSusNvdEv51o}{TT!`l?FjPU_MDbPsOp|N*)GL9lNuq*<%IWe3vbb z84s6vL;(>5V5tTWL)68H|7DQTgIyYJ-@llm(6JL2bb^?oKzN3~>IId=E&EB$J`C@! znC1`?-88cA?5H^pf^WvmW&t8K2W*r0tVFfaf(!E%hEJ)-mfmS!7pKoVGKB(vwNAw;8JEm~?N@3x~!x|IpD@VLU5u#XW9B|F@Y^79L2^@MeGPRau&2PMS zFOM~6-M94YE!AW!@7y(-XQ=u0$6!{;!pL7HLghGo{WDq@I)3|HkO%Bc2HtPAj9)6r zil1U1TZb49MMs4(97I3!PmeQBS4();CLMd9HfxDwKvD_JqX~BIl6?gYu1>`BVPtep zya4i}`z$I^$I|S-x^m^?GBl9v9`a|zn}I+^!dEN_d(DWiv;R>EIk88Y=Xp<3@%6Jh zEbz8ROxMJ51r8BV$lQL|JRbX*`h|4EjsxrMVT5iis-A`?s+MFgx@JT5E8k;UN zDQUZNE?C(e7g5+#COdPf<{YGX@~Y)%>O}-&5i3oP5E_(D&l49Bqfyn(F8iRAT=Mxu zwY}Fb;`?UO7S3E6uMsoKs6>4Np2rkl!p=X&RhCxJqSZF7i)s%d(^%O3v18n(az=Vj z?!Q;CN=VA0^PCoHaM1dCnpLx`$J#gBuGdLDBl@nli`dh<$d8bpP=tY9WS;E!o_gf+ zz|zxU=_dpupgMk`Sk*g)X4XkBC1WaG6z(I_9sa!B%tD@b`YmQ$>fhPn6hhC39G*XM zfs~&~TLQsUqko))7XvgqJzdCxtwX+(U`ZTq6h|swVh0y1646+xdys`|UH`cBM~z*{ zLt4gGvw6#B!LjPL1QboTuvG&oR``@$K)lubPVeZXU`bazqGo-x3{`C)3!eNrn?fr+ zEVSnRQZKo3YLyPV%D3nWc7kTFFf0K+&~K$U>PU9>joq)z+esJ*O5H_Zta{ndI-Q+G z@x>}z7}<3A`iI55=bm#NVNO7e`%_9%z~Z8T_d&{2M(2;JRr;Y!6JvCNT3=t zN}OCuH*9wXwQmH!XTM1ai-E?3%!PWUfiEtWh(NAde?3YKUSt7_So0V)BuG(~o9V&^ z589Vb3PAdjFi2lwP3|c`0RF4?8|vvwhRXkQ#= z*xamN;ZvsOyJv`BQAMr6()eDmOTjeSI=dohP*5Rp5I-6lYpga$eZQoBsJiB)OveDA zlGs`faIonXxj656S)bi{edNJpRAOZ5EKQ^AyeWTK?5treoxIh7Xi1WSK2x*yb^$y~ z-;rD{_9WMI6xYNtHL4(yJB;ZiG#x>O=%qqWL*sHoLSphdZCwEroZKmVy0rJUZ@@Ms zK*ErDX$>vu8_e;HZ5O(oZa&(EtjtG)@3g}D%gDk-x|*$Hgpt^R0gDh-0LH%|@`|M= zI{6>Ol-GU?QQnCYG&glIo?rFUQ(oiHciQCFYBn`#P{;-QNU)=uvM_#R?5I}j-v)4u zx>f7`hK}mO7T`0Prq%hz$o!!@+*VJam$ujv2~B8G8S~`ce8-cW+f&6_mrRcXb2yA_ z6(8Wr!?>j{W6{aXfgi;vtNol1+|}H!hwG|mYQPrLye2-@+$bjbeJ$R#1e?o_ds$*& z*osWA0Oe=3Y(=`tT6y=`-YF7$(oU{1dpfJP$6k9E_)vTJZU4^r52e$*o*UPb>Z3wDd=PKP~;Ek*tTOnIp>WOUR_k zYE9siVJN1cfcJy8KPSexFELL0w&m1RpxlLXfYI$lEqyJx0q!w|9>FTOjPl{{d7}tb$Lb|4<3L)0jtGXo{-!hH$Tx*UM%)MIqNW%vQx&e3Rr~$^Q74jFO&E8(#c#0o1EGkGkgG3n`f z1_fHo^X}wJeBk~fW*CbuiCB8zR8GO`-Nd1>zs(%WvBsA)XMejRF3df@5eVb>YD2D* zD)Ae@;5uyo*oO(j4}#=3q<{R0cK~G|vC7{_l7oGk-sox#YktmVu+N!S6bM{UyVtgf z>YRVzNXPPRbYv>rPCVwd8K#pt@+usz7xTdVE_>{nkhOORJV>os_z?RY%EdS)gOuB1 z#IX)7Xp}Sq?HQwDhzw2es}D+@=rqfXux}7K+F>5VK`*%yYo-4^d_(wNSA7FoKqU!z z8|LsbJNA&nMRR(IwZmxpKJ6G|9eLpG48(PpsOtKOk>io43;ZJ`{%{d{@}hzmC5|xq zng&GBM+Ps{B&&P^#XwBKT1X=sn8H9YOP~=}y;>0-w5UE_x~zl@#sh8;-G2xzChMtR zsjS&^e*JYW6L_@$Jf%G6ckxbB2a{?0-o+tcC$!(o&;6pGy<^I4|fhOEEI+x2R#kScjvjm83B?^-ZK&dW!=IxKH3buQr^g=7Rg_Ro=6 z0-Tj?vX#CqNy3F7;%*)U(QmRz|_~$tm>BA4WOWUb7MT|5B$|6> z8N#6WJ88N-I&il@y@!_+h9Wa@>cmv4G><^?uiE!w)L_5KB z-0aQRa~e2W!mEM~U9Wq$r)bY6t*50OJC-_E-S^hD;HE)I^2f1rzp;63=XGijL65Q{ zE1z6kYR+2Mp*M2r9^TrrwrP)|^?TGu_VvLpdVdnvORzPa0%?_sj{4dZE#Q}-iptAT z-uLIlZtxEhBO_YS8O!ocXaDF&gs1H$|0Oyxa`s}IZZ^=Y&LIQ?0YFa&{wFO1->)t@ zAW+z7a8!I|^NA^et3>v}iVtC|u8w6wXiS**5RD2`bM$DclW-9vq<^aVZRQ^%Un_dz zQAInYpA}9_`@uppIIhJ1n~bac(yL3E6NUlDrt@>ncw8LC@Y36NWT@41)I`zz%g=`P z8m-yHe###Oue&hE)TJ$C4vP5OPB2ZXR~hLk!!4%es)_507@tN2FkbgLZZ?1X49r*# zyztQR;#XEKttM-A>^4^NZ^@#LjG_jq^a&UENU&{5AMkdx3pv6xFtZU1O@&Gr=KGOZ znL78?`|6ZjsW;X}7`}5P_b=Er{~EI%2J7e3eZQX9_58fy^Bff!qZIL+Ta;67Eu7qU zJ8;qDzxmuf*kb#avG|*ZR^UyY|4Bt!^bwL<5oD1E*X=Z!5Ax)btAP!=D|KqT#rn$9 zWh#m>Ae^dr?*u2)(k1*A;y0DQ)bcYz3K(aVRWNJNO6-@uoHf-m(wf1k4nU)3CD)BI zVM))AeD?^#gSkEpTYR4Ph@){wH8F19EDu$h=^_SiQXjLNK?Th4@XfqT`)y2Zyup~BSR3jK zn3}2ijrqMtC66ViqnY&y_nQqwstB2R8ZaK89992_0%&`LH{jWh;0!F>rQ(bRGUcH% zaYpbc_h6tklPwZ6G6X%z-2i=ucY-N~L6>f|TM40`s(kgY)LRARVNX5Mmrx5Mf@-3kaE`xH{db6sNW-PqX^yc9 zOu+Gl5>2}wE%;(U9CT`zHD6Q$&W%aun0x`@V*xjNw_Tez{v28fO*3kJ70yyNzTeZF zy0o@sfjD5wdfy7{X-T^Hwx~?iI~8MF`}sE0 z?&ql%t__U+HA>D0FQLzV)51>%&qZf~4_~@m7o8c8ZviJm1EpdZ#yWHmXu4ppltSup zus8P|I|NU<+JO0!d;V+$!w)dP1QpUWqOI&pntVvsdrj_TYtm_>Jj~{mq_h^_-ImIv zM4d7{!1HPG2+r|g{}5emq~^9OI;inwX9>n5i3rT!CJxWC+F03N(E0&6N!yIUTa0Y@ zU`>J?5tqK!fv-b>(8y1^>~xsBV*IO4T}PGp7payxxjK4zbgwrkst!#yr`n1wZTONu z>NQczY2rHeFrHo?m>ywe$7{ZydCyA>27*1>4Obu7%y&%viFJ5plWIN@vt*5TZg?Pj z_Pu*O1?M~^z@x%T_)D>k_KsMhS#+B01$!={nx;*CNMuD=t#~5`Nk}~}y;Io-FXSiM z52=ACS~(&&lDEY=^$-K=O8>Mil;_dT2db&Xsnv>&mx9gGQ_l5T*J+Ls*r&Vp_^#ih zrv#lHAVts_)iR5-Q#`8gvc15tV8iH=MK)=x7y8V-|aU-DgYcc`5i=M+Dv!&QpL44JGpv%_%(B<1Xk zusJs*yZod*HBiYZ($GJMp>;wda257}dru^au%x-9G@TZzl^+ovBOF-2-dB4#lnGw? zCK)A(S=m&j0k90a)?68a8IvCyx79VI`WgUf8gsj}YQax!3sV8VHo7hIx%_xOwQ0=o^2*1CCj^wcy_4o_K{n zV~S{1??XA&Qu?$xKmI%sc?^H1Bb)qatKl{fR3Xpzs8DOAB2?2H_qyI)cNMIn6maYn zzkZQ;Avq?LMy9uZ=P%N7EAe{TKj*y82|D9jM)pO>@(CbUgq&0n#6vhi#hHNM|0E5* z>FB=CuK&>Rqj}{X=-99l*lBTfq`Q>b!*6|4wDOpu%($mk-!zX8Q#Fi#55>9)6?CW} z%hYs&Fr2J2OUk*5-!||QBIMG9o?LyxMlf2NjE{JKMx}ctE!GtclA`2z^Zg)Kpd1gL zPb%kN1!7r4=AkaClpjA5=y;lt3-YcN7U z$At5^goze-ff-RL)V&Q1yqYrfpN|8?DybM!$fi(Z3>7$VTF~+ zm)Y92=Lgn(D!q#NRI-=f88L4$-^o*Ct>yY2)=iR-F$L~zC3Qb?_)d{?j$zwh9&-3j zygugkdc7R1DTO`<6#7#hcQo_FL~nwO{vYcG4M=4c z_N_FXy5KdX{H2K}`-gPs|M=Z|uBr@r`JipM)-v!GqC5*Qtl=l_9|j5}TO()*nP*-O zNDT!n;pC9tHIr;SvpNa+H;}Pz4!K@D1O^?`>l_SGIXypGz z0N@j{R;dj){(65vHg&o=d|%xTD@8kpRe5R7_EV1qn)eev%QOPzcVQHz@bqjs#kHk& z6@#g-ZJ6FIHm_}BVHM@ex6>SsIM6aiCtI?qr}B8B3N0&x&8p#r+&Wpo6VKPZmIMKFk5vU2~c8e3rYA#Z) zX|4^Rf6ePU8R}nI5z#PtH~izw|LErIX_$2`)Jo6y88vcZs>}JD zAa{8g5>q+|>fHszR~E8YZ#1SpK47{L3-aIPqaXP2Z)|P1fRc3r#VY!1m+;mgT8E6rWBA+YF|^lTL-N(GJB`gpJZGw#;Bx zpp?Un!+y7TwoGvP>13?A{@m#I5#mPI>%sG`O~>_%+T_EuCwMJzS3culsl8Yl6wfwE zrRNue-9IvfJMLGGKjDsQI%`TG%z`5bK!)WO5K6ftRTd58Dk}YgxZRC01|3x$kbMf{ z+nntcj&_KUsz8NM^cu9$_<%yPb@yt0W*Fo!HrW7dT3CM+ zeE3MtQIyE}m3awYmz|L0#|5m5S?GIc80CDFvM?-J*-x74QfhJ);zpWc#f;P+@u1#^e65_i3m0%h}@s-!1sSt?jI+-NWC9 zG_JN?<*eaWf8$|l{c!{GU961^#(A-*(z1ItH^^LY!| z76H$!q%R^OAN>RkRpx<2{!dp|DxKVc2ihLhCV{_gL}0;9#;}if$pod?CuwlLt>1)E zfwcy3$4c#^Ou#go4Ihw-{ike2D1Kaqhi_D$%i6Zz64o0MNOj@E`tX+)ykGum613_J z1r5L#`3%)mK-u11eSKaa|ldkr<3qeRD_03jh1PR zWVSRH`AMZJ+3FSsaZy&8Z8Aan9blQ+4W2f%TT&cqlapACSOUb4qWb`UiqDKP=sitO zsl1GT0gSgb=)XEP1>Clr`fvF@a0ig2!w-B~K=*l>H1%_0Wfs}z=*18q&&yEe-OVqO z>u3fZ9hnx$PM=>C)rHe=ll6zO2KGv?zGn9bqa4$BI{pGKa}Otdnkag{G+F#~?N=Ok zzc)*lvC@CI7-Tobu}n zgdY17u>g?DVwbWj)U?UA54vaMHZtFE;rW|}&XAEYPpA)}CEb$TObvD<^Hc~z=T+u# z?_>+CAVir>g5(L?>9c9sqdWcQIS&2wR1bPxij}0YB+F0SCq>9k13N7pxIc-evK`)Z zOjRo&T$+T#14QW-kM=E2oa)$pou03jvgavp%Drlv1aA3;cze$SEzHGy5|lW~ zG0L7Y}vfum$Eth)_L!nz@h*5qmWN{t7 z$!!@S@-mAg4v7Q(%p}EkM~hi9@IZbmtaQmnqEz^f@2wW-VP+b7YVKs-xt^p3U0N8U z$Tk@>8--lYBc&*Xsh;xXDb8SrQt0hRIkWD>B*2U{xSIos*bZ@N5!iuR#gvWYhkDig zx+M{LJ8a9j^6A#uzEK3}b*L8f{PUxtj2b?QT@Ue!TDv>v6z2SKH=&!-j~D;vyKI!6 z(hX6rDk+2Z2n-Bxc}{NNN}OH0X?IhU7G2E1+UyTzy9W3mg+^z-A;v7@5Kekg{Vrp6Lf93*~-%1+!Hu4A%7GL1*j&66nmC!HI z4)&bj4jKg*ILPqP34}ch*lpz_r)FDrlCFP_l+r}^#q^s|y#qcuoZ{c4J#`raRkDk? zs&uk6&8|`-Q|)4F*Bt|Y&(2=#w!iMMY>~fad8I*&fO=WO5t3`~BLhC2zeJ=xANUHp zylz5_a`16px6b@t45#Klp!s5IyMx`n>Xok{aE~HpnIjg)N_Oe?^&`JM*L@TaGk*Ng z-s`!OaaLHGwC2jOJ6-T`bDOxjBO&Ylh~y*up%+GFVZME1#X4r~Vv2dx-BJ{yrWR(7_a|{JW+W zQ3%ayQRJ_hQ2UiCX!&-4%@ePzvS&fi{Wzy zyQrzC%QfFz8aq6+1JkjG*`_Qp1UdG`;wz{4)A(=7&c0%PMK($$sL_((Sv~!-B{0j~zs@zXOCY2}UpT>xZe_og-(M%L zdlyy;s7WnSF=5)rkZ218+%zTI=~|pxhydae(PO;2!Glh%ebMyrqrMhZF~Tr zdb6#HY!Q;vUgGa-OD-!&;B@LW*rh(#xAa7$vsjbst)0#pMD%ZhI~-Q7fM3wJPlrl> z%{dC4dOEUE&KOa)BrefZZ@}HxM3I`w2)`}4smYtzXA*NmB)LbL9T4+Cs*`re11||w zEthFtD|QOz_>^HcH34G?HR1i|ajq@_NjUM=rR2w<3=D5>J+b*Bf+d3 z3>B(U-Q!aY3kx4RGk5I2?{A6&k3|?R+ri-Ho*bvIx_|ZFSji-R+_so)p}+&N!a!;n z+~YC2a5&>kfaQ#lGP@4uV>GFSD?AwcWDy4ZFz1$sgB(;k7W58--j0oDnQ}EXkKVsDHGmovJuANwiZ zJuRn|cAY^UoGHk^+^{D&$K$K_q8nH3^pRT=U-$;fu?q6zGF(qdES(C?axL5PnB4B6 zsWI~70ken}%b#-O1ez*`g5xfq;@^*YhZ)EledzL2sLmKG9Nmcli^xt$pAYn&+3lyO z7ZMLUM_)DKA-nf(;9Zvt z9d%YhX#~G|zpVurV0n6(s-r&gFt;9Hi!Z3bJ@uND(7%7JNSZs=Ie@xu(5iY0n7i+x?t(gtm4(`!eGtplIXM%s1RP6Y z!;Xw7ZRJpApE`-KyJAP)Oolu+{9}nu6qqRG>=(*l> zZ}j~eowP}TQNI_XMJKBTBvBHL;AdNtjX9XGJ?Z~@`L!x`z34s(at#04w@Qkd3Mj6) z1~{Y~3IAHJZSSF+pP$gOVObYKNQ0hLz_5^|1G+}fVli^Jvx1HgXB`=?!maXI0%yhF zRlQCtG3R2Vbe~dszfBDC&*p6oBluZ^Fx`ad&Eu!Z0CXJvxJNUS4Jwj~M#-o&F_JjE z->4Jkp3WDA3(INr6#yz`O7wLIWM3;0a2gt|&+bKtD4i-z7YV769bQi`o?ety>9V`P zxD`LdO?s`7*PjSYg1>&}O6?mBn8M-lAkrquWw|AJP0gDBd-ZcNEsdsJsf#>^@OP|091(J_i(!PA7213WBF(!ZSJ~VjtR)k3yYF{gJ z%GUZ9tR2=kB|m?HoS$Y$xeFP%6^Z?LY2ar^Q49$ox~itdW$1v*(Ez;#V7-ic8%J3+HvhU6sV_H}oi3PG?#+xLHy{%xDR6eJV(441Im6h z3CLkBpTan1nj)A}QHR`_u4iCg#Z#^<)G^36lr3|x1m&w`Qx4TpAwWH}XveA~-cdSE zvWfXa#q(s(2e2oce3-GzowDBo8&{YkN$QGgB!0L;XR(Y=shOhc-RP}Nmx-@hm(%di zLAh!*kKzUT4Q00RHY3$mh9cW2<+r48H*X@f0QncFUY`U^jC|`Ap@t`NriWJbXoj0g zV3gW71Y_`^yt^UE(k9B>sGT=qc3tC#F{3cID2nooaW?$%k+nd9KE70lEpxpL%%ouH zWqe5cr(G;=PS5as5yM#<5du%xvmJr8(v9>Dp;IG)&v~C5oty(Mg!iQpx4zG!2HuGH z9i6NJkv&uNxSmZnnyNS4zeY7&U*>prQR+0@zkKz&2Cgo`f=gq;945vJ5p}n|DUj6S z4K&_UIBbCR^;buQal}>%?v#84_Xl+00BKMJ-hsM3?*;}!8e#CvT=lJLy8=eY(An52 z2KN2L$KG_AROaoNQGc+SQjSGf7*-X=_Vt-Y1z+^PY4#pds(S4-Pj)5t$@17Y3Zbky zu}C9x@I1O$CF{s~;Bx&A%}8Y`ZPkJac{#<0Uclz9iur62cpr z_jH*FCwNY1{W_h+b(<_7s#Zg0>->gAu1}XqQX9`>UCgZZ%V{xA)&)tTslljhx@p%YBf`Px;Pe>sgfz^&n=ty6Jinyq-sp)nlsJ~9UpnE#2b zXPal1$Fv9q3t<&?k$ZV6{CVDY?F{nKLjC&Bw8>QI9(qcbpE3ist%v^1q**3j^hVyJ zymuTb>|QdbSGVm45f51>C(o>0i-`Y4w|2p@&o!U<|APA{f4)Uq&iLObb=1HI6)`zO z7=c=39;@zdei*x4Oi+}_5i%h&7$eny%S1K%4HgiqF&Q~>K5hLW`qnb98HFq6K#-%p zUHKS=C(FDklYhUfbvSk+AO)d9!UN&Nz*nLQXQBN^<3+>_)#LuV3Q9Cg_g2}Oses&Q z0P16sLD5D0EjRrIheKookxO>N!4GcVy^{yl*MgP`_TmyIy=_IJ@T=C9lgCcd7+gSc zQ9^b2m_=?Xw`-rw4aHeQ#9Z>3-)#3>FVf<|LuvFh|X}V<4%t>|WvjA?m8b>2Tk-Hf>CI$FS+HX{MRx=V_Z?!MBaEsR+?ET{+xVnSk`b0HOlQliGr3=s0fZ=bZ0ZQyHjS3yE4UDrUiu- zTlI&bI~lX_eHqsCO;cm~sDcN5AB>sMpd_J|KHI?wzxwyr)kWXDx-=_Pfq-$qXFV)m z%~|YKb71+Em7H~-CysYV=~3j)5@5z95wnfuHlZ`pSnJ#%eE0(ciPI5`#+%$Z`W|`2+^T7bxA_MTb8l09PG&z=Jft zB7>BPPA&VsrNfKeL~9g5B?M^lVF?RPo2at~AitO~R71I4`Z^xeNQSED;z3(geNQgl z2G2!Hd1bMnmj|<0qJ)Gx+UF)aQDl>mVCiLraf`r_VfmW%=B|l+S#FAliAi9JvMALG zA(tQZebo#%ro^}{5p58zxU_`;O&iK za0`Y}&&XK%A>`&U^7;D&tUga75#L6GQ*j=%^R_cM{syU^ockKmr5oqEDYaaGod4Y7?Q$fA_TQ_$TJl?f&XlLs5{3Z`;GZ zUMQ5*UzTPN>O!rsZq5E_dSs*+qt>}~ur83{x@fz?MHmn`ZY7EacAueiS~-e@s!h-b z^h!kF>$MmJ#c%YUp>$~wx`nHc4ZTIe!sDR6$yX&{xKhLTm9~iS4-jT!N|Vn~qOdPh zWvG|^>KcC>Fru37TPvL ztdx(v2TvemEUXddc`Cb^&AZ2K_s|FHq6c)~Pl4Q3!UTo}Xw2?6WUHKk1HEO90AHX` z2s~$Tj=Z39K}scB7-kA!_!8Uj%&8Xpxc^japdvj-#r(f!yryTNOOeGGNeA?wrgv&XJPtyjB^IS zfrY@YFIIjxb*%a_>A`KxKKfWp&651#zQ=pkv$E1mA^AF}$*}$Xp;X$Z?z)QPi|=OS zpXsd~vAJ~d^O9dtyPK%Vnsn7Jn`K>>1WV5|VvSjUK(Y1B8@3u6geGkG9+a)Y@BpKq z0XquK`LGb)z{RbZ$I!uLB!6rB z7ZKFmNh9zf^d8*ZclJMW{ReY>{TWuh`oIag8=WBky*D%(&-hjc4|-dNivr_Ql~uqK z-4jeP^En$w5pIL!9@ zf=gkt%3nU#9oGW@Xf z%0?l!L1(TqUj0Pw&?EcICH>u)>GKx_zTmPyewWd16AdLKfzG_$^%UQ{dROh{_8xb! z)}J;4yS`CzRz?DTTEF4V1)C08QZXoVLVAH?#7|iQ`2P$)`T2xBnt3cxxN43 z8KX_?lWZpX(@6@61~OgJv{NZd^@|6cp5nenf4qK|yhoqiN6l%@uHRP$9zQoH_i48m(96E$~>PQ$%KqI<>*pOaNaGxbNd+eDq7e?6S6H3&8=49(ov7AF!x4{ zzorj5*gjA1B>abG59ic!@NsE%@%(RD&(l#PmIcYNRx2tLoq7+>$^Xu7dZD#tV)e5b zz8O!-Q=3|hPMMr=Yz@4w+wk8zlfF@2-7nQ!biD5@RBN$Cgv?7qi0T~$kkhPsHGt48 zTPLW8fB996AoCh6-hb-cK?RHyA6~KHd#jL|pOOQF;K6uQnMNs}tNM8fK0%~T9j^m3 zMvAFl=&U-{j;|JmQ&U`DkMnkg290@@aE~rpIbm-FfG)3uj>VRRSUJ^E2}iS)P*R$U z&#|Z;W*1!K2V+{V%4v%x5 z*W@7vlr(pzFd6f57E7i1e)*_PYL~Ak;GO zi5Wg*m)Gl{gGVDf!Np3!aqY8*^=t}*@WCokg!ErqHxq9?T|FU4)Y*@$m1u8&u7=lJ zP>JkDo*18mC08)SMN;pWCEN8WQ$Xdl(k!JnW!oTFeP3;!-)gh9h$FR?jAu83xgn)D z>r|3$KKh$&1dVUKw&O9Eh3X!54bNqlOy)ow$gu8=OSaR)CHRvOfqKvPcIAs4NZ`N* z)JuuMUg?ie50wdiFoJaE_FjMfJZ%NvhUGfO_b~1Fr!%+h>?-WnZ(4el zB47i(U{*)Izd1ORLgfBOc{yX1!#7A<3aHI*am(nzd@z9QD=SDD|Fqm#)Y(Dw1}bdf z)jwApNWgf^CBcEFyf2Xen(3nTGRXBA;HzFvj^XeVd5jJ^r|x3^MEA4dk%eVR!cu_* zec@@u{gODfGWq$_>EQ6JW8+D%tB(Je2X|ITQG*17Wt=BoIW?5ei?KA9X#+6Bc)p$>yy)Q zuF1;o+d9A5Xh#S5s}5BL(6#ZFo$Y&VNvB@9xfnHd0yND#ws|B^h}9tOLL}P|A{Z@l zU9c@3a+tFMt#Uo+0|OzvXAf8JCPgkU?K;1ViZnLaulheJlRiPi=jMaoL+r*%_wCUA zDep-eNK^D_`0qjQ!sDcE(@gj52FdnE0pS$vy0OP#$4v^JZGpi@vssZWsl3JYf%wb* z4&guCR;!S<+bXE}A^$VKH}7rl5>| zs2!czCcm{SfRxYq!1APPFwi1CbkAW7MBg#df#dRGB;(=(74Xy< zWBGjLK@Z(oGOWL=&NKn6uV9dQV}%Bokf-0iv)3>Oa9`&MUGcojHq_|xHSUXQHez_K zo5<^FOjKK*0~XhfELccpqR}ifX@27xlJ|BHE_QY=wz^TdrM;3UmXA_U-y%5MP;Pc6 z{9U~fCCKuPA+<1vd~-e;5HD-;NV zZ5tFaT|4<~`82X?K3R$KQR`SL0W+5ONfsZgB9uV`R16`1_xdPSo?IB8)NJ$e^fiQY>@44 z;2orDT22{Ev_<&OP-E`vYf(|RxNxwgmuJ=X)K<;)FSO4e6~wTl8zjNQ@)gVp43W7` z4fP2f*i3%-GUHUZ^>&{-Z+{>jUlWBf?2FZ+bO@qkD(0QWCD;)AP+=Z*l~YpNH=SPO zM~zggmLUIE6vj%qPqgN3p!sAk+>>`3d!e1PyEUs6Gp)!A{-_`VR6)7h6Luri>vX78 z05<#`xU~v?>cU#|`^#X|O5J;)b@rsU*?4Xc{2*79`$j+? z285@SxB4@EV1Wu+s(~{8jD=^$uXL#KEI=R>1wEwPC$C=!)iq$lz>R3vo_{SbYw)SM(97_63#8*{!^2f|t~? z7t+mpdCZxe;tAu)BYwrj=0UIsM+7{}Vd;m!0|b(E3#YZ=>Yt}^8DxhY4=*#-6B?&1WcznCD{v@#(u+#h0_i*GL(yIKoF}C0FE@FN2_T6TIsY&nyO0fZ*qc8GI zq*Bi6Pk;l(=H><6$~)ZW!r$fKHxuMa{DSAYOKoJ2i2IW(HLR>1Yn5Ir>4hmcABdhx z;ZkEu%T3Y|{tE{&n;d8x8U$);Yf|WFv0X8~SWuDrKChIY8XFEuniDS=M5-faC~(7u zK2(Xx!CJia){^nv;fj`)}HYBPTs8MZZzORZ291%4WHe8z2)H538 z1i$A@X&?8yOp1_<(?-WrNmwX{Yw5k`=%1hE>yjc&)fXk574Z^^M~V`!2}zhD`|j$( z0(YT`aD5zZ1aCA-)^($`nU+o2TnPmVU7Y7vP+J#`NuV4*V_X(0zV7Me#&( z3oUQ`6*6Cy@gq_Z6n^UJHHZEf%X|)js`jL(fR2WX)PNL*=~I$v0Vw?}9r!P`DIdaq z;p&K>a;3lJd@yM+E$dWrjs8T3x+v)%y4N$n+4X|2{PM<+;}ns4WOSL=*H^L)%dA#{ zV#*6Ik2ahcsdF43r4wFh$N^PO%XnRYppT?K@6xTJK`x~lnX zMd!S>N)HpG?`9v{>sR?tes(+l$s;&Ee@Ggnc>L0U?e&Xbm1zBEZ_{mL@6~>ngI3r& z0WhC_Me|d74`%GBgSUebL`pWS=!K|5OCZoB(AY6>og(5t5A%0wMODEl=W^GdEiTmS z#eql&;&f-hV_EMIf-h+yVE_S{q@s}k`Xf3`sxipa93MO;;v2$D?=F-C1D6)7S+S|h z_wYll%@XKYeuZihcuaF0;KI0rVWrGTm=nz0H!Q9pUym6Z-9pOPNDA%egNZ{-FbHvW zf3Cn-p@^%|>@d|=R#U02xRg0;x3M@_DGY`SAl#&c4@0|+9br6CNRR|x$&JF`h5F`2 z`bl(vS~N2{!b-p0*KR`spY+&eGH_u?K6^29CP@(o{+B>|v;pRF0;mK>h@e8g>ENTn z<}8FFVB|{lv2rXQvb8N^nAghgT1);g6iM-z+jhM97~i!C-U!C{Gi}ULFY4cXa&H{C zRyY@KK$U&~zF`$})gB=LLS-)(Ie&bBqjKlg)c$f_<#YJzG8U~}^K68}#wYqH8?3-V z_b?#MLrE3NnM(P#-gF??&bB;%zCe6tuFlQ3u2Dkwu|Y7%Fxmd%Z+r}yR?U>^;l- z`KqI$k4m0fRjWpCI|Npr)(Lfa@cVsb&u$=IE~OsqdU5Nhc^l~sjP}G_?N>o++t^et zT+ywTH-H<7`cwN;hFHw^ed8{X{^KfL9TUtbX*m|I-}B>%c1X9duTf-rqA|?8K6p6A zm0+j3x`>ET_u~j$eq$AAIL6z{S%5x6UTE%wcAu;0%3EG_H#b4LFxLzRp&R%X4G%N- zaR&{gj0ADme7dhA2{?F1+4mr@_(o>Y@aUo;>7ZR{sY17t5LyZ%7dUxB~bF23) z;DBUfv9|?RcYzNY?miS5^rLfKA`Y_7oZ4yzv1~bihl7;%8&01>&2Zc7H%SCf|9@uq zaQ!edh7g2g4J!pBL&D?fyBWJ<7u80VVCM}q>tE#~-$5Qrn&T#NyaXs=nyHwE$BL`) zCYx&%C?JzYqwSmT*mZ2yNXew`d0#EX>zDkhOqmD`AL`k$s-~W9=g7O@nllTos+g_J zn8377$?4N2V#AWzY3CH936=_Ct<_($%RNrCR8TjJ;*v@?7@eMO!GpLu1`VmWHa%7e zp-X)sUX7a_-1(B{v)t5x9VS7UNX>WJ=y<5M5nb#V`T(#^DK%sQ=>mF*fj?vNe-i^3 zLR0{O#K6-Bqf51!M~G+O&EpC3x{L@fL-8HRxErg!%(RWY<@a_P78quSp3L7F4_YwmFfHMxTjSb`lY@vVS z)G9}H&2;>P`c*M5pnDgAk#2H?T)~?Zvi`OOtUc(UJ|12P(zx*56@CRg|EyEZFKkos zrBh)Vig49Q%;iC*RLuy7Da5A9#4S?ghm8z5onhw7L9q2&EU{wC%vJm!#Ur|1??!W@ zQ}?vVyk~Ii?Nxa$vtDa6wKlW0+E2gJ6l%y!luYdjoFrVKuyB0+YN~83*=ZA7c&&M6?4lz8I@9H&D&!Uu%acvbReOH8^1_YbXixH1OP`9qy4oyyET4&Q z*qKPZwWj&uX0n5XuUukXJ|+aw@Xa^p>cl^;MM{0eD6p;(E12h38y~$s7d5)&AN*hg zt+8ff694FiV#Y(~v(($i`XZZ?g7GkeFuI=qS)eaK7qU%@(teq4p=lNGlc;Caikn5O zEl=ye#8-S21Rd+wr8N_CFVda+<@WYr^9p`&Nah)_RI%EVPRwEX9wE z!}$kx-9A4`ag#Hc8zA@UWX90j&ooT~aVh9nY-ArZJg-=8BW0Bu*&pHHy{}7~0zE9oh7`^zlXeOPduh=&d`TOZk4T=UGl$NCMk!RgQ-BCNl&gixdm0o@n_5xj+D^o z(5tEmU>|b~+cNq7$0N19k_$5m3dQ0zQm)FX5a~28+Tg6bUw&SA(E=MDE)9D45jdvi zT9ZBZgQx8hv+!Eo+0j8eObkX&}hKudu*m6 z%n>PkkZxus@UjeKh(clqnHm`R zqk{j|c%D!Z8v!YWfM|fq9`1mKP%Lqh0O5z}2jS60VY*vc>w@3J3kcF*&>DrcEu zU2J{~aE82H*!sXHMKvtvfX`(wuec6WH7j|4)u{1f;rmv4dWt>DhY0g@_jKpnNIR}f z{0E!l+<~t^n7#8ROiA^{G0Zw_~_}jJc*>!{mjH=z$+MD1m(* z)^!Dctv^pG7a6P;HnK}fS`QDKx;D@eDJG>*!G<%z|Dd=|UF;}Esma4Q^pzQf+ru}8 zY#wz9Mv~2t@qG#M5I2#5Q%CS^!fw!P;0{XA#KK&R^x#W=ZwD;$O___|lS2eohxDui zG^@v+4b})3__G=&Y5CK$Z?4yWE@uca`jGgap61IZ^&pT0qdmZ0u%Nn{q_b9-RPi$` zOU<8W#(N~8I>*ag6uJ#PXR?@d)&p5v6td+;)%CR-;an_(i&XI!v}l0il-tJW2fS7r z$M^qjWd+k_Zufqq6elHT8;Og9aK`C7KZjJ^CuVud?axmFF|E)x+?Vmd+`0b_Yb<(B3lH$KhYa;&4Je>MscFu29l>^t*>WL_- z(#Z&}JIu)ml*$O2)K*DBAWKwYgmJbAuimk_+V@KIhKd*njvxfRLXw(UAi5_YI;X2Z zcEQ8cT}HFA=qR+19vo`VQ@-d5u+=CzlBjb&-XjhfnR;YRtb0q=K*w$}yuhl0IA<{% zxq>4i`Dbn8Kb~67i_Zz%gg$$G2oh z1Ueq@)vM+N^Ib?4k$Xxs_)KUI+Le7?V*2+$rr#O(De-m3qu_ThVN;yR^B8^wQx z36EA;dnFk3TvHxhMe$j&WOk6w#tx>8DqzaQf|TaYij&4zi6V^H=cBRZR&zztTy5v% zwYE2vU!qu}FzIJ&KJ4y43m6%!IEbqjR)Loe95ZZIzYN8$n+Ma=_kjDZb0XiHl=Ova zgb|a=nCsqukvLFqV$4-xA6I=G3#t0rh?KIifJ2=^b0DA+J%(g08dQym>0uGrg`}&I zoY{f_tVw6dZwhl6Yf9fL$(qbbEa(kgTBJ8QkE55n$#uvYBSnNZFg_T+jZcddYfbrI z^g#%c+I?1zpx#?2gz`)91&y&FM?b4jv2lp+3H1^X8$Brazpod!moQ*OrN*Q4e&jA7 zRi-&z`^zOIK(GbiNsT!*;Nc*qfH^V5h>kW*fNZ>$=Tx(8T$3Hw|6!r_HGTPB`(`Xt zF8NA64T=B(bwrohpp(M1`Z&d*f&eVODZPQT8+BMxy&>SmlyC*pc%Pjq{U^`(l<1Xh zz74@-4)ny9BjtUAl5e2b#N9uvN;kx_l{ELVM_cuFjhRM@@E0bwSUcJ4x{C@aw@ppc zp%82Y3tC6QskgTneQ7zx1y*A9+;f;MROmh*b*SDIpF!!-PyXf8UVU46ci$(?AT#QM zCs3j%rs>eeVay$dBKGe=H}YjWgtZYCk4a;*#E8jZoDAHYiE*;H9NL(&5DO(d! z`(WLsOz$}A2!_>3kM!&pVK>{vyiv&0Cwz!Ao><=+9*$;aHuq@v~TEBIux z!O0&nZe*l-&NZi9Dw#ldzX}LO{ijh4S~}#xH@&gi`y0bVLGnX<~Zh}vid0ej1h0>a?E0Di|z>X zUTaVAW8|DVC5SjVuF2fk0C7WC^?v+7f@{Lv2}7ZP`{{vkiR>zv-@RMS;swoJU?63X z!1UGUTdYF^1sE{r>~cL{@3+PJx-}#^8?k4u;V29`7!B&I5e}0q4DRQU=OjDLP#;&n z6yYT|zKS4{n?%VG`tr7n#i}R^*1S}ZQ$zX^M`>TDLe@P#b75=m9`B8w_^&*@lQcd zOpSQCClrvag0YX={{ROeaEo*68Hs8mAFi#R%;5TT2Q#e|Q+Y3oy!vyXZ(!0YQgbkL zBGX*O&QcywmuXtaS=w9EYU1gYRq*m2?osx&H~gKG8ZSekbuv5ll;_9Xy##dSm+z7b z=;za0a>&CV;BgX(oZU35v~puVb<1UrNf>WMc~olb4a=`PTk5dB~A2MOQC~icI^OEZVSkxhqYvyubQ?CjrnM^kE`?`&2HXPAn8us>&3v9DsTNWu2Xtd z;GspU%b4P_i&kz+YtgD=8+BBp_wd%wH1IUlV%w;Lf@b}w5Vjig{zhEDD!+87;auQP zwJKWrk`*Re8Tw4XI+@u|ByVLv8Ed1&BaEXZork)-%#Ey6Mn~3=kp!z|sRPzK9Kt;& z^_AO*91*z_kM>C#@!RwrQKfU)P1I`w?&?|V5FLx)hZrb!3BI2StMgb-9YV}lP> zHE!+ncMH4wjP!KYYc?br(hKxbIvV9t@-bTjoP@WMP0$yL)l#jxPIV?W=~v?5(ko@+{l-Qz72k+35sSD0Q8Pijvt4(J_ZjDRReECc+AWpC*Pt3rBQ#1<-!Q6C3a8P_Su-oDp0=ou@ceyjNaL7 z^U$>f7w9G;Fso$(QJ0j^F-kv_Dw4 z*?mbwkf9@B{>rp4Wd5H=nkr028YAV*VY%PSRm*n7;k;WV{A-)cPfNX>D-@YjN_5CW z48faI5V6!SQ-*d3He1CE1klg2X60lq0rGLHI_CyprZic}7VP$g8Ee@-3GB9(2jnU+ zcvPU!Cr?qzR`N(D>+dx;v>(KU>N8dXFBcunqC#7_;8&&zxH(xL_olv^~zns-zFC?kph>$*0&)EhDf-76p&OBAPZ`uOO4LbrdN!Af^vJ3iCxk1 zZ(sKoo5#NtiN8tn)Xidi8=1xZ&i^$KMhno33RIo|?A3|yIfBCeBV1i!MOua|jF5l0 z!9V6_rw26pS4W4U`u^lt0`ZzxjPmMCvD_T$a-{11t3y9s9>?hO8WtG@cty>G@nR=lZNIbYSJ-6pqNnt-tStZ^P1O)l zb+qV;B05`K^hjcLtjN?6t1!Q8h?BemjpIy1m5jb`M|jIx|4R}SB7%)~|GO|=(E1oY zrLyzz3#7n6#!n>S0L2vGXv$Z(Xp3$M+-e=xBWT}g6W~}#w0E{tT!JN#M#1^!vV$UW z=xFBZ!p3Sc861QVfYf`tsKK@RaOUr4l(Obbm4f391%p^Czxqp9DQRk!vFQ_<=9o%+ zYToG7xGjhw?vyCF*edxU)eKiAC~5$5Sj0*`&V_;$$G#jhfqm!u8a`;^X}bEbdm1&k zGnXglUiNnXHmoB4WfWVw?Qh|=>#-X78(Plh0Zo0-^xQLF6>Zac!FpU^#>}dcJ~|va z(@WYz0zRh2tuZ>t68le}+7KKH*0+a+QyviaXR=Doae8&9HL_Nev09R7;OtWo%A#Z5 zMQQ1DP4;TKZ-TSs(0jFMB~8e+QR)4UR~Rl*b_b2O7MvQE74A^r9+Y?!BTIs~$J-;I z(7-(3*gS(nh#~hn1>Zn@lu6IRBKTf?S$O*F?}s`M8$ku`+JaH&J4tDYg}DmLgl}>? zzgMY#O4ZuQ==;V#IbS|(PmXn8xy6w2Wyi$--8`zwrnf>44e$E^F zJs$)-`0Y~uS$KNT?F+bnv`j+~${Y6Rpp6Y?>mFChpt_cwu40}?OGTGLq_QPS0<0(Y1~U%~oBNU8RVp!o^d%bT@H}9WC(BT5oojMK)*NwtCHL z%Q;~wFyeLjM{v0W7EMs#M8*)VxvArX+dBlHw7?j$3iN6Dv#&(lz+^sr`-m;vIL1o% z1;^aBq4WcGFPr`^zw!RvG3}qK`#PaKOe%2wjc=NsLBGvbkHQL3G`I9WM}z2c#2IYU z9~QshqXke)FUSw6@V}@g`T#tjMeZAvD@0Ck{aOVWP&_l^;PS*D`;yE&mIUUP;9wCC zs^3}EoaV|*yfZ{}+#M5g@pd_*bEo}KFRLS)1~7aTWiR67t*u|dQmV(%V$aDfis2&; zV0uH}9yvjZDPay)sY}B!!z5bJ7yTtuu-2Ryq0iWXn#xSz42t2)m1)Uh7jKk+E?ET$ zG&HeCP)XJ3@_fCM()#4E?ZTg8Th$$~HWm%$#-o6autNQ8BNrz~Px>3j(LaA$ffIvo zBYU1WdQRJ#VKhZHU0#rq7qnQ3f2hf@71kJ4=kupfp^8Ijl(|_3vh9U4>$ZrNUJ~@H z4+GsVnv@Chr8R8O^4i|9)n$CFp5imO%p40>G)fh-Z(Zr(;fLy;n~0~*LnHk!5BtjHN_$XynscF zqEsEv`?MlfI@X{ApAvCg;P> zN?kdsS;5Ohj`bSF!9=k0f|x_=8`WSW;M>K7_u_PB>mk*JZa+HwoNcbfp>4y%6gsGU zvH0x8O6e1$Z*Caq_2l4Hz%<99YF`PHf?M4D>QBp<*Hl)<)YuhZ4Lp*9YMX1Qw{|Co zQuwNwWq4YRMMnY47VFjPF(Mju7Zc`#YXpY#RYTZ@++OA+(=l-_gV+$cug}K$lSHBTr1QuvOPm$K`oPS~aPR@_s9wg7%R2UtwysU!6XM(Ahn#*GY@wf_ z@#gE^Bk#|74L(v?_wbertNVQsYrYlNT|sN&p>=$gWvj&}Nx|YqUuFO$B(R`>(|D}S zHt&BhQf)KUCg$}&9h)c!!~O?UV0me+J3x(Zp-OxIbx!@ex<>(hP2LqDCo8-1{GNLsvMZu8@S)|uRZyxl^*s{b^h z8$6i&q?ds<2Ovd23p=Fs-x15>VLoXDHDcOo8V{IItoEkxf1`4R?qD``lh?WA8p=+p zRdQgbwRzuSy)CxSaK%@EtQWUTxa_gV*rDw_JlW8V!}O)0W9=^0f7*hJH?NZvdtM$b zw6F*?uvV=FUq*zJyGu~3YBTqXd~I@;a^>BI^`bxBJYR{Mi*da%g>ulhRyQF=i223x z_g%HULYqQ*{3b-MAXGPp6MXdvext;+Yj`alrVci=B)+hT*U((r4hRh@0@g1y5gO76 znj(!_zl8mMu{}Z$s(QcW*H|+D1R!WLWHxXX0ez2c$b(A6rT}PY=H!SiVu3wXZq zzS%$*^W%JCv5RKE@v8LlW;rJ7>joVhM<9;aaoEJ{kYkQvtN&!Bwf;v+FeWmy58ld(PWw$a7z2|bg<*1p-9 zCj2y)78cU#Xqjo^1&pt8J^a~w9_**{p8Nz{g!WcQ@9=CICR^Xn^Te0ST{b)mT)A$K z-0xQRZy*NG5sf?8pTp=%DzoKmX%OoHb5Hu!D&$&xMcdZ;Y?>8cv@!2!&< z+q5OeqvPj{F_OjHVFN|r?LzC7GC5g@gtjaTg*nPuOl78!!-CwtzD4-k=`bcv*6zwd zx$VUy%pz8bUBg(`Ts=RYU1_$AMhHC0${liPG8!)O&soiQaywGy?3oG;L@#?h22Ng! z7@l0nb0`pT{JHTY2toBfGWk;Ma@-F(N>5DJJZ|Xz}(VY+Uni( zDm8iB482biE;w$f9BC!-x^XNE0;U0D@+v$T4wd&@mbZ9^Og;L}4YwJmM$9OhA9?K` zKs)~Ry=WjUSV$QgW$5jYp8LO>0~*mpb z%Ns;b<#W+KRi9ejSa|3<`DIteHi)N8d&j`I_36KLYUM`AJXOPNXYyFbS_U@1j%m_H zIo3zU@%*GLIK-BvMgwJFL3H6Ys4Uc9(i@Tb{D5Vo$esV`AnpAh_Y=LIBLZ~i2?aGy zjUtS;jT{vx4)rO{HIY@>G*{G(tvYg@TC5GJ{R9QGyOA-3PISdkzaGfQ{>zVa$cURr zJn*azt4_wTFszD>Ap=hI9V5NXyLl;xFZsc5YqJMNqx7lF5TujYQm>|~cWK8oHN8vF zr6jBwBw}Lro#fxPl$LE83ArSKYxW50@q~+U}HVa!=h&BH!3}2zx z7lgoofXrwrPS<|Ch#o$`gY{$nCn(EDdk-?lP*wJ)UZfeGr=1Dc*uG0Ve*JBH5AJ|G z4vW?ynL)CC^jKFl&&)2-CgqqCPB#aul!e0(|J%W1l^ZKtm?FjFq6ELZLbj^PsWi>3 zyxymU)($qB&wKi`CdHYkA6-;VGBJJF0s+|s1gi=@(e!Vq$|eyG(%BrBah<GH!!{!d`Vxw_ z?dLcv2y3**qo_{4?DqAVG06zp;VPu&&|LFw;?7P$Yc?L=_T$Zm+>zQro4ZBCJ;B?< z-d2);w9gWQn$5;3ysXpih9rM@ZpHCu%@$jwnhtZM`gy)o7Y#eN+IX9XMGV&uu+Y0+ z2QRjqQmB*v@U-tJeP3C%hJl}>m*+#wJmFz24ljot^%7+7lkLV~Ulc*8dZrg-hsE7t z@)B0jq0@>Z6_M>PA21==QEIE#l0`G7U!^P@8rL%PHp6#vk6o-i z?4q|ox~$zQZ(86=f4?_YrLDdy?z$np8oujcO=VnJwO5G~@8dNgMsS#g;3zgz@I^gJ z-ar>)YE2-a8w{mCP?@?DBC~Y%?*@$5J*gCIUxZ9<=oqlLeX}6^|JYr?;@jSLckIEs zP~HhcV5kmqkTT=`v+LY!YW4vfo@_-*n759rQwt;$zFGc|R|s}|pS+Gn$xZHMzt*U&jO zn?K*T=^7roOaw1I5QrvMXk&2g*2YOYh}-k^cUnw8dO01HCi`NLT^6?oY+pC8~39$)wPxT9RU zu2$LtL&z0%nc<-MZoMk-1iI5^&uDg)9;i%Wd}z)<8G4coFv?p8NKG>!pq^)UQu&{6r)An2A1j59ABP0MX3VU6hI@9OqQC`2D! zZa>d&U<)?dO}6Gt3*O0pSdin;OOs3pslaQyWv?O97iCiaHW(UDUoae+yjo^yZo{BsyYu2Y{fwcs}?>=1IgnIOTmbBm4&x@CY zr6HN@R^QmcZ>z(yTK7?xL2xda^01PR?wTfZWO-aV5vd%go8*<)`*7F(j7nu4Bb-r8(TE4-{yd|S zYq*%wb(|m~xU5ir&ts<=8V{NZRm=t6xgWegTgo-kCVETL3`^=RhoL>$pN#6QZQ;_k zV`A;E4Poj4xAvj zaUJ=L4#`#h8%rT@4-w@R$@?YvJJ*QQYYDK)rE|^(UH8c4FIXw%hT)SNdYOV0fY<;nt!Kr zru4bi{FFvJ%o6jR4q-5~I(!{faqy=HA}3F>Xe!Nz$h3f0^Gw-a1$Yrp^lMTzczNmz zY|SPHVx*+hO&`kalhbO3&sB2!GaGQhrFS(ri1tjdbX3|T3DX}kU?Kf{kCjlCE^Lq!Mg{G7|2+}qzOSYrTc?mBp%tg5IUovMca((%P58U=>Pt7Dd`#Wk zwVtqe^XIk9gJ}y)x)oIaqXQ{6on>#S2EH&dXv#n?CXK`X{MA6G6Xzc&s-*$E9wAF& z*79vCuNx)pIbzkVTHtD!I)J0qnT>?lsqdtaRe$#fgwMN}=8tE|7+g==i-PX9vSG^n zb@IYMu(|{VVe4~tHk>t*icm-A_{LdsXfMNlpK_lqIn)=ED;Ga>3CilL#z{0PRzy1; zw%vZ>4PBbsf73V5a=Pz;ed_ZA=7zvQEM;t~^$&2fQqYC6xet%5CA)`qOFp=KEvr>B&6#Oq7;*4%#_-F-@0kRdgGD`_9=m*_EAW2l>J2^cluz_7 z{0KT~QT(}ENZ|;!TD#iHX!_u`+7bio-4@Uoag{rGmRz*1=7)E*Fx0+^RYn?FMj0e!1bM)u2$jX4i!=xf9>0m9zO9?=KE+47sBO8F(Up`$w`-d{>)-UvT)Q{&qSYHjOL-mCj={Z^rb7orF?? z{#AX*C`(L)q9cd0{R#OGV&=Aaw5ur7)sJW7?qCs|nnXzYXr@QDA-H@{_5Rno$GC1> zn3B!_jA(F?>hfdl{)!hq+cC4cSo&WF<WJ+tQWXhkfB;5=o6;RvO*)!iGIo zid99Ll?x}iNw@yhnkGvE&L2vtI!4XPI?6CNW!Zbr2s|o1;$rDXV|Vv#u-vCMe)=VT zd&Ila#2pAyhxZr~=gLqQ%rZ&mo}a4oQE)w|?`nee5WE-tyX)4u9k2p630e~d<#7Xf zFM@7Hw>gUZnS{%XeBD#cGQY({xJpF5*a;5U#{eyH)b&5hfDFFN{?qecV*`{OelyTJ zjm8((d&};SB!odcIUYo;Tuj=v&$=ZYPR)ES-hwz+V)lWnr8jU*Es^nn0^k?~4u1Gt zj`fNn+c1?^o|IP>T|u?nSBA_%^NYfbm66nGNr{kMq|1#i&Kw^M-7)u7$p_`pGAu&n z!QFGh4Q1_>zOoYYY=StvQE*~zSd~I2*RMJRU9>vxCeu@lfwR632xgd!(4I3Ni!i6K zQOfM_^3cMcd#D=U4h>mA6oKy01+t>3Ho{N#=VX4!Hv-(W3M3W5;o6%N$v59%!Nt)4 z!>7xVF};NUBkL{W+Wvy>L9DnIcZyq~xRc^8#a)UOcMa|oDDLiFg1bX;FA$(e(L#f? zK+wRZzvut#es=d|-hFfL%o(|J&OFx-1$U!lx&{f?PRIICM&l?gSs47V--`(2H#P`) z?C1Cwvp<42y=!_9|88vkHwFuThps`Ur1Qn?`Jd7a)`~D+i<$hKK@!PM5J!Ry`!>m& z2>=c#mVA$Xm1S#0%&D8{)Rv9$X1b{iuh@v)M3B9S(>xqL&25BAp1rk!CHhMyCk=)# zH+$qR6-T17AN#R7x(4Q$jSJKiR^#_>dEbQd-F*yb0->rmv^MtFw@=ZW%9o~@YZqVA zt*A{mvXwf*Z!p~AH46_(QcyA8mA`-i8W%FCy<`p?uI zwSXsTp@F}0WOA`uRuh3^&I6o^Jbl~fkM+i7RZurn3x`E5!IJ{EFpFQzI!=S`7_P#JZwB0Bf%6mGt|(V^H;{UkFhuij0u?2?-vNj zO|$A)x<9&CAOoTl;D0oFcy?>S^)C_xlx{^Pa27jR3Uc8*bZU?@z^7=d&e*Vp4(Kv4?i~IsLyTKmrhcZP!+sHolw)ko- z`$<{u4>S=LQo*Z)SI~I)${~GBEcL9JfA-)U9aKT^{fo{2>Ya@IdjTP)r{ z#U{8Ake3+Jk`v$Bm$jKVe6H|#l)=96Lo&8i;c^BVH`JG$rUwoCTe8I*lPas?uu0__ zb^H?4Mm-@p@cO{Tim&nwgOeS9Dmo!kPXs;+w*8^J*+G=bZX|xxgZO@{zd)hGt*z4l z+|qM%)N|G751fa-D`ZmgL4Dc9x@QHk(9X>vI8|m!{Id!AA_H5eO>_BH;9n027KRUw zhNWO5OLX7AP%LfXy2^C_v|Vnu%cV%2rC;#phnQnax^R1}g6zt?ZM&SuNp({<9$re2#EQ)UE1R3bVfJ_~aUBJTQizc#Ses(%erQ2`WG1GYJ>)Glebt%4eLy&3R@yfh{07tr zBVqin3HsI|XtN5#P}-{7LRV$k}r&KOwvIo(O*Dbz)LWmc39M35jH zGT^4Xk7;SO#CBQfRI)eR2}#HbI&JDt{_@@R(;CWGv>bf;2;+Wlep~bJ;@T2U4zNOV zp9t2+dKo<<8+B%62U-nq^uDQ#)vA2l`;%9^$`NnWj_f;kqtZNnU7%Fpgm;N z_T(beuY&t29C7N@FU08cRvlvzIyO_~ND_oav(z%PH8;wu3&_>SrIWm? zxaIOZo8D^A-k0l8{~X~t1fek#d-aloq}S?S|P3!OjgM`nE%{a(6baEMK1b?uuS+ z#KxCBt?LE*9=y%YB{h_K`Yyj1udMYq+^Sui^w|tVAFZ{+Q`^Hd*LK%F!vWBK5$A@p z1?|i5Q^VuUY)MFXTEZ*7`3-|MOYS-)arf32=`h%$25(+}uZF)1yf_%@>iZ|c>|4cp z`5y$sdlrppj25C&dJ~x*+9q= z?bZ|5&!5kppCONo-k{juTh_N$bW3&CL!qS_EjnH$d0rN`wS9a{Qj}X3*lcpdB5O$0 zEfKuwF^jox9h8-VEO4SMfH>{xyXh=U>PtKn2+Pb?k&zs%Z}S`_p&YM(}~#G3ryq7^T~1Lz>#D0%VNilUw9fe zlauL`9w+odTkeq?9ZdV1u_ZHB?z|u**AtFv4s&pfuL_49=nh6RhGqRv9u2#e*o;FN z#NR2|cW;Cms>gC#*)o24E!`#X`TGg~?uzusuWy$HGQ`sZsgjoG=vo_gzi9$-$OcD- zPhE@Ytus7Y(AJ14FTdJsKlGJk#ly+LQcjlh5APx8qPdN#dPNWyc1T?IrU+!$ z+HxfR5Gb`wT&_jEqUsE!Onf_%Sm4J0rBCWSlH}T4_y_0s1W-XG!sYDEYxeCXYPI(R ziU)C%u!Q3e}IB3gnjcaDq?&3>Y+$VCnE&iFr*@3WwiU4o36u3D% z^%33HW83#Cn}mrys?kB06uoEXDRi69@CR*lCSj}0#aKJYKFwG!dIqAwfm`fIPT)Ef z*3fr~q0SotbI0 zf|Ho;aT?D5IkWG(G}D`s`~^Iem>_zK-uW5#Of$4nL52$o6iSu zt>hs8hp`ctQIgiyP@Pxul56`?v;Km7|haW^D}3Av9hh}Aw>0tX_P!cFZhSPRtN z5T4oJQo2nR|85_f!ragE*|T+shp@nJ<-60vMKH}y+cIdtoh-@Ly9Pq1~uOQmI zYdLtY&0i(axa0DklK-c(P;G_PnD+3OM&EhbFJ+@G5d7Oi5YA3AdP;qD<@?4j5|7IB zN52&uvo{5HO~CVQAipV6a>Wykr;yv{yq$o@ya9(xC;3Ms@XM-3((_Xi?N2wnhcf&e z^UkNJg_D6S!+wSQwual)6qS{I*DM29!I8f7V`K+gFQtO}e0T zgz--t4ftExGWvAWMPI`c9uoi`Tg@R%ZG+DSpvLQg4}MMg*2=A}fPV^UtHOwDZx}w& z3VJ~bl^*H^>GDpk&vhk9xQ9{}-gdN*c+Snr^9iRNijJKI&-J>i@<(@iqMx_tXG&0i zhuB^4c@F;_o8+XO0D&ouRzFp5I+aav)LzUO8A>BK9{F?T&N#m#YiKZUQLMEtpV{W* zWGPAkN)DxOB1zf^pK24OsBPTW-S*Hv-2EyFcJUFO)PM=~IYrEG*#n-|?TNpbb?XML zJ^BWpJ)+K^=}{nG=M@q`0as;cfV-dj85_79lE2;Cjc1bjL|^dwFT6`&ZWV*)ef^KW zeS_D8&Kd_@kngykcf?-yu&!cULwja9EhtaTAAkLFeQH_cMO<{}JcMZs{9bJgzSy<5 z(5Ro{F*%#H*x{%-|Mh-pBo)&^`_TPV%rn|EELPxnSTeUz#@zoQtAOY{ai8|l(f8%R z6}Y{3upS2&M|`=QZuukrb#%ZN&tmQVSHh>4n)%uC(#wS|gpnRkvMs`VYZ@a-iRq?y zAfBshim?K%R`Gq79Jq+88mLi1d!6orM(*}Mmn)Ndd}XeM1%Wq}*@%lhQrQ-R-&*MZ zUL0xErA65CkN2megCzHn%%|$sp9u8-<_!x-`E9`}*eA0p6fPS52 zF1gA>+jh);aH=91ut>-?nqQ|Bgh51n9CDg*g7>^!rqRFMzO~-se;17U*u?sBO?g)I z7=s45Oj8(u294}IO#7OHu}TZY$st97&MuoXH216g&20f^MNY?pf-4g=(Lw5tKMikV z3CF1Lm>mVrb)Vai@7yKGAxr4mli0z*&du+%?dMlF`hV{I;4~R6!2MZ$frY98o`?q} z?Euc_qJq*wiF>7`p(q+$64lRc9vQbl2wf{I!PZcsrtI(9MqkOc2i3qa^6m5Vju)`w zVgR!E%nGXV{@d>mNCZhn%>}?EL_ZaE)BzXL$iy;%Pid-@EhU!Y+Rg*+@if}Iv^_sc zZaIsrxfnNuh9vVEeEbyR&NYZ#yUrA}*OR3=tR z;V$E{NAr@#g1yA#C>A278m`M+qCl1~yXtO4I$^8dmyGnByp&Yla@*sCXk zAQp)bQP{(N%rE?U0+UTQzp5Y5j=%uLQflLm3>?a|C+{Ta%{chxC&}s>E_Lz5b;{^_ z&YHpW-I0?n0EeHciWS=i&u-`~@PLMpEl1#2`v~7f$q%jbKqPv8Hxlb&zj0y#>`V_Z zVT+E_ndhKYbqb1#R>%?7)yq%hTfoh?Cux^hXR}6XuaHv(T!_oX&QliD?|p<|75FgEBMYs?y+pdte{juabCw`f?rzWQeq!NDq|rdZN^@)&Fw@< zgST+?oylx{eEpJJ0$w0((QMj`oE%)uuQAd3YnHEu@4sVLZZ*IA7e0Q08h=?u{)b3# z9jBlTKng-^7*Bcb(q9VB+0HL?@bZc?CRLFbOrV34{CuIsFfp(J6NnJgXW<*=P z({bkg9|kG;hIWndy}w$1`;I__bNzIRhG2ZPllss3OfVyAH|YzdvG_83tG3zv{$gqF)%V6A8J{e zK}U>nOn7eD#0M_DKb|^HaJQi$l;^$2gDzF^e8rpV_-7=+r`>vd#LK?FHo^S^_YyF; zhWN|fPWSDGYo$uF z4ngQTi{xZJq8Q`rPFRaiY8UuFD`&JAxJ2{&ufF(D3LECGc?DI736jIA_!q0;H0F6F z1f6Vj%k}956vgycB*F%vZVrjk!%adn;q^oSWs1>v{sh7Y6%e35aIv*-8e@vQF}nWA zw&VvtOap*&PVkPtjiCo(`RnxfAN{b;~t<6GI8Rieepvo35EBtVLko+x4@9= z%iUH$g(u*#0-DuV7c#c^i~@3PH7Fx#zQ*?ppQbF7oODutS95j=X36oi%o?BK^G@x$ z{CB=L#Gx~az`y?r41zM)$A8B=9v)O-lryDN38(&t!mf4O&F-0nd5Iyf4t1c!QFOW= zdd4j4^s*=^UC!vYc<972In?=@UL~Uk4a+dkp!ri0)^7qcU`{G+0P)|pTC-;U;u!R5 zQ?BXP;Gd&MdU1@&r9;@kC4Y#PpYf6TsL+u8Wf_hg?FFU0S$2xc=`U>RQ_A0-0qkpx zzKIlyiYS8{{oX;g@PhB|UY-_S=C?CYCv{DaJ8lIf_;MHfOI}6dqc?q~cA81u1?jx2 zG#M?K>daTxYLAdXXH>7qA5&VdL6Fk|D|JbCsSdxUWU^FwKk?dt4qtjAlra(-l(VSX z=o%t2eYUDPa2r6`rWO|r&?!3)zTLXr@|^EGF7)izcFUa$ci!hMu-I|GZ7dXf#`DF- zEzdZz1f2Xxw*>$GKJRcdtn8;YGB@^O@v-_dnPVqbG|e~Mg-|v`fHnw$h8>H@E9b=T z4`ENKK&?_2Q8De+6u%vXvREJ)M!Rb6M6m;%z!FU%byq6hmZz@jQj7?atNY2*LE7(l z{}w?-y#4^!qM-4p9P_5u4n#41%9=Ph8&P|--bu4CQ`Hbr)dpXW7sbgLOQ+n_L1vO4 zS&WuB$RmA5DGMqJ8dsagIE8XS)RZ45O|^PJ9Voy=G`dAyUQ_!QuR$8UyM1hgxEY3D zLM%d>sbS@{CW?k0R3HAJr7>3TA!O-NveCI~=KfM2< zzAt=F42x)m;C?>i-yH!C{AAR)5r4C*js$T(S;X$4brbO= zSe{&05m1h{l5li6EZFE%SwafAJsORT+0dO~cJQTy4uhMMxHp>wUl z0``1B(-u$?QJ;)RQ5N!oh<3BXhUV*lhSs&Pt(#IbtZ60n_Z>nEXW08JvK_wCll%;4 zEWS!-!`rVRmI9kmeH>>+sNj+DEcn%ZO1}qn@{;S*(Od2NPu{N_{(-f58e^Pm4>gVPq5$3?!EQ`B0sH!h<++Kl#tMX zK$1aqmf3+3|4Zs&O@_myPM(@|Q86G^m|7XNv>GVy71P(yfh559l7DX(ndnd@U z{L{+*V@geSY^7ogi~U+bM))jM?}>%HR8jh&3>HwK*I6OoTWq$J*ezqZlf(7F^&F(< z#JTO^(yatO#{EP~`+*09nHt@dG-v&N}x{)-)_ zhDW|WJGtpEwlqZAxYt)0edshMO{ji|GY8R2h1_yURG1BkP6+>5LjEN&y$>#VBnww| zLf50&Cp44h6uOzpHG7$jpW|qr=PyA9+W}ya{43RC*(VM!dHwRRgzitd{Z5%p*3pt> z<}NfocRsP+QK|v>Irt9#q4LVl#+xb9YRG-$vG%-nsZ+}fHxWS!y|t;6c?96$n2U>+ z4CPs(qNVyuTiw$T2_`-gX#Pp#hEcFpOdAk<7&oIexmP53V3^kGX-h^ruQI3;uJ58T z2_YY@kUC0`h6exodqC4xYmJ*I+!MXE1`rgY^^jNFsiN>FfiKNw&XCh?qs%Pl&V}Ex zI|z?B9H-|@U~`sQp}@n2HKzp0sSE3fnJXtN8&F-rMwTv`&^dXah?pXHR$RNuki^$J z^?Iq@#Z_wq@TR*@M!6CfLT&Uv05bck0C8pOpB+|7Lf*7BDwV`9V_8IEPh}i=Y9Fb8 z+-8b1NEWXTA#sbdWu~p5;_W4vPiWft6^pouZr&V;_pKY-2*O++fJkprm`ECY9xcni z(peSup*3hK6M;|NI>zs=Fje1u8C~YHht!=J33`QmtFy3nFA6y;RlIBMfNcz6Lxc>#Z z`u;Hd_01aeWBi*zeZZDx??b|Yg}gH=G;dxhcBX% z?7D(c=1G*v$4LgG|4hn~V~IJbU-Y%ldxf(@DjBvOXPShO5jMKddawU3r;g$=40rP< z>yUTIB6tLW*}~+H{%#0o{Rrhaa9_cTs>BDNcX>0Bh}U5Dka_W(_fn2<>ok~k>hLX@ zwSJV#V#m0%w2$F(bH>eC!gc~f?MK^;;+8xYQb+4jpRzyFO9}%f}DLVRkWf1D5*CPU#`Hsf7>9 z(Ut)Iy}mokleRNv2MzjcERF7zW)#A}Wy#0Mn<)Q?jYJhK(ix@VB`3K_s#)O9bJ0)2 zJ*jMK!YLVZDu@Q#dh5fgIwAfhAe>FsDxOJ&=n>6lE~WQ&mCNxD_WpF%HD`YP${?;s z^Pf=Iz7Q60QH==7gxb|S0Gu#wYU=dsex7xFw7scgJWJKdq4uy51-T?y<5^|1ly2sw zLp8!(F3MBmqWWZ197v&=7LA4|yJ!q@16V-)4Gn+rh{Aju4Z^t)!!-F6aTc1PMJ%i5yIYS{F5kvvRS<$Wq6lu*(MB=8U#@&9JLhiC zYp3ivQ~C6_)c!%gai&m2_ZE3*Nts>VmWElEI2p-g8Mv~Jd@6U9U?-GWXlTw~!!FyY z_RD%3voK`fsjaTLVOSl5%L9KDwdd;9w_khYqVu93%Rd?$@(+9S4}+=_iZOwcUldtI z+$R;|{g1qYI3euh3&I$bLvuq9bmOAr{WH9i?i8O?(dbDFpS*ZA%0)p};s+?>om?E% zSa1k5W5LKys~TCt-Sq9O<1TY!a`PMY10S+OQuL<~z=$CgO!fdXD2;K!CTP5U>stl8 zAHadQ_XSqm`oM7YRfX@?WZh8&#{%#!Tyv%7gg|yBZ<)w`9yBh~a?!a4iYhgo2E=bZ z=KM_*hvJ8s>v{U&=N}h7%Ydx3E-^`wB8*B0+a@oG&(jS1_ zA(J0=nUm0(8@rXBf^@iJR^NhT`aQ4jg4S-$J#CvYAAjcGYShW^tRr)nI+0mwl8>98 zcU-)zUrOj(H=3u0&rxPLnU7OfZE|40-sdtTIED|Vz$b-ZYhO3Ts;qZENBpm`;H`K{ zEv0ZlOzi=Omah0n)?x;4a?;*pD-v(dmN_7S(pZh9km~4LSdj9p0CE&L&qyD6Q@h?F zKI)n5$;O~|_49BBgOb8%87XYiyZbNiEYguGtYjEM%ceyZiSS7layYooh%i)?maXsO zq%egg!p+HO97H(fsa`&3GEqlNR-O&Hki8dT6Ue)r#qHy)k9q0;syS|s*z+5%Z?2f|so{s!SG{X07g;W5xuPV~{61jGHGe)=G>Dwu3t4L@xEV zMhG|jFbUo}ll}@3`tcBRMD4O3a%~iRk?eb0VUSUZ3&9~Y+T%il0fptUz3WJK_SSTH zd%lPy4H$;bdR?{EjnSpXSpK#=p4Z2InY@9i*iottyL2x$P?O)7J%gTx9}i2nh|EdF z9m|QHwp19_zn4d)d3V~p#6GTZQ|<6U1Tlo4AO=G~zeCn1cbK74+}u~i!XP8cNS7oc zTucBC^MB}I-s5snooe|yUJ)$TTJB@%iUG|fl=uQYAKuP@YSTbb`HL6g94g-dX=9%Y z>#{6;|b3ri2Juzj2nLn{xMLla+BK@xj)!Z!NROgEn=Ys+Nq& zcF{0x@x|2J$4l=u4AbbNC!7RRDvQaVjGN>u5@kX;ZP$mlH}qM#(4g*?U~e3uf}hm% zKbrk=ad(B-&TLrjh8*wPHfKcxe|jFBQxsreVsm`e6P84}^hOAxqF)JSJfIn|rwXQ-619fT{LzRL$|U^BzR^!L1P z0r;QZ5~O388n%>t8b{#>3!Q^3pZ9&mlj(@lz;ucHASK=O-qtvAY?_77h4Yk7UUj9_ z;xlyi_e1~VlcKOz_@Upd;MH`N4I1c3ZW?6u_BVb_X);-=pP+m^$q{II!GeY7xn2Z} zrMHDoH&nla3kju6vvj|tJf8b48&RPrP4uq4X5jn^!oUuYpI#QI66o-ILYA*CWA^k|LgD{pgQiSP7lXXIVEnXv5kU^8!k67hF?{q0*QR<>6|KA*ot{Gj2uDk>^rd*k8LlgbK0NofTwYw1i{{S@O;)$4h!DkeQdD4@TOXkmv@J)hs zMBL~)l6Q<#>RHRla=2(|dCeN5Hz;WwiQV~AV==I$F?B-nt`%Z!{DTk5Xw;fRtR!l* z0|NNU%_G*8@u{(i1kaVHuZ6AIB4Dx;a~K!HC)84OyduJ5c_OJqm<(4O{fuPoE5>R< z%%71MZ*Bo;1*y90=jB#>9)ce--}G`m_?mn@moHe;H0W~oqbCi$?81kHJ}mx3@22s) zOzG|L>G6jd)(Bcunalf{RqpUD>j5f2?}jp^8wBuxeP@);iyNT@hIN0L@XEG{^C_98 zSt8lS*0Cm_Hu2Te;C*Oa*!T3--?c=}Hxu+e?>Nu$=WrX7Y=*79KCKSo`VL%6bsc;! zT#w)~kOVY&ef{8|zOe%~e7;btNToh&T4Mc)v5iHOElBjfUbS|XKE{uX_zr5Y{dlZf zhWBh6BAqr2Vu;iEeccj>#gS9&{X0xSnXrqbO&L`)d@ICc0dV4;lbz=-5$Zb`@iQ^z zF!nuo5e*h0W!Ti@_iSRd?o`&F%5xq2HI;@ora}E@ExAk>ZZ_Aq#Xrj<4yfM_(ds;L z|7az_#O1Ui3l?q27~;to=~sy8uFNUpJGfNrUSsNiBX8Vf5LGQa#5jRQFKySRo3B<6$3=t)v&y-80B^5owXX;8_GdbQHF*@og=AGbuG;vbSKXi-7%wiY( zCSM}U3A*fxZgVO@-s6gl3oyl53J<>W`(3M8@(%suo$D}yr#1z9H=5^Sq3@vAPa;^a zNHilZo~8-&4eQtW@zTyFA5*189!vQA_fdz%)dz-t^~~4FyT(~IG^PR+3fwIZWq;L< zD=Stl8$%qbS+&}{SIVkXOSn#grRF0qtvt4x0Lo9>!%g4^S98Px?%MIh03GmBG60s>nFKL zpXu}~9LgOIb&W#6xPkCk_Ie{yX&!U~7_(IrVtr2TQvx_lHpi7T?3fO)QMqrwTCxOZ z&G5pLv1&}LGJdVUDo|lDJ>5tGR$Yl#*%`!~*`-aXB977hSJ@2BA9&o?xz}97MA7Mr zBz2LA4a=-|r;GZHe*`YXd4(bzfvgI*tIRrt1zOCFd1cTRph=xQ(LdB4&u)4+{no>E zDI=o{Co*4>xRWG3jx9*mQVp00SzhZBqM4ysJ1z3V;z@5z-mOiPr(22Osn)}Tj`_L? z*LvIiP_QOt{md%X58!Wqa=#REm_rGb6WFS+X(S*h52Ir(8}V|WBzyn}HWiKMCkB6g z#@PBQuZHr=Qj|?YwPP&}3UAM_cmb<262OS>C?S4evG#v=8i(@vxX3ubFeB2~>X2 zmEi%VnSb9umyGw>+t5wNC20xDo!pab_$&y`73$ghSd*^M;409tUx?0sZwL3TZ#JT)v7bvX_2A&eP9a6Q0v|M7tY4V5wtL`KmTl zu{e8^NK|V2B}+lF&gL0$Lv-|=1#Cz+Ny-Pah}X2s?I`e0)@3T|+Hie`IC2RdZh@~l zijM^IOXQC)$};vzSLjk@Igv;nl$kzvD56d!S(=OpJP^0}?fvtCuO-PadoIhqi=ioU=wjw|Gx&8vI5e{P`(liZ z2(Pa_U4!aeZP|zXw-d((fAJFiw1F#nmW{L)vnO<&&T4F`Epja3WTtE4|3P5KCv}f5 zo?2r1tCl-ZK8J}aiVq93B#k7ROkGK+uzq zb`)+xz&NJa+;s<)mnzE)b=>3FEA7_Ckaqpd+*If-bfd04bEHOKVJ<=P=9%(wF4q!4 zvXU54?8)hbb064&C)qFf@_q9a*UdXssR2Gfc=&=3QdjTYJVcUKOzbk2qGR`qmM1crOaQ>H~*tywCBNgay(K z^P!^s_;Ob3LlhR@723)`h<*BWMWQpx_Ma}biXBlQK3C0nZC-CKzt!~mhqL)x{dd6Na3}^!q7|6HW&bWZ^dAp-?}*@clFx*#boE!oT3KD8navtcy@Xe zt#oeCp`ea3Ws#Tca@+KSx4yrhOYxey)>^b=Q>?+dw%ZhUh|Amde|pFQ3P1z8rT?jZ zXni_@-@F?q{)+FHYE)Ctth-&bU;Tu+_`0$EPRLL?zwE8PVtRHJxA_TeYvxy-3HHq! z^t0l{@cS1?A4VtBq%KW1LD$xyv+j!Sis{M^{pLl`qGYEX4)(dE#@X@W`yjh6ObWz&Ux-i|`JkM2` z5qXL0y)m=hK66gIh}YEa^)=s~i3O<3f1C82dpS1lqdIjIY-V^xo@Y7-OWnoAk-x@G zO}H^6_-+-85iUPk_>mOgHxZJW&n_jx;}ak8<}%(`6oXo|z*Q*yPF26XZ(c%x>b5&e zkV(J2MJjb9h$u+7Gu6nizW#u>z$e*n_KxC3wP~CdX3>_G`SbF?J8t?~wkmNS$MLxr zG%X>Bdq6e3h^)!i3kS zCX{%sKVaD-1jVM(J!eFRDi+}okdRYgqL^7VxLp7BYi?T$+42M2_umv0CFtRZ_(vXA zYLAkWKeaM@8~^?83ZQ-}6DoQqf@e+Q_|l-^tHwlI^sXy-<%M*|>lE_25K|0im-?1_ zG5uv~yt`n_9YORc0`Hc#FWY3`wQ4AJBgxdJ?*j+9hFZ#=zPR1Z5Fg z0t9&pWA1;UnBBeYv%TNEFsEVe)zWB(_RPt@KpI${f4%^t0z;Q(7Jdc8DNPpvBd48m z%;Z-3nA2kbzx~s`<5G;(;K!QX%-`Yj5(PR8WY=qLnZaujjx3w1p%QZ&=AOn+zwJim zB{Lui7Rg~j_Z|<|EA_-RuOV%joJpTy^=CA^=3`{#;m+pqGjHn86hIR*AJ5Pp6}>_8 zuYhbQ7F3YAjU@PpUHdd5{$GYTy4X6#k7$J}=q>lU(rfIbmpqoN(Z%lI&nWYR1LH1H zp2Dog5-OcQ8^_m7f-w6aF~HWI7nVOT_f6}Y6+BJ^Yw8Sf294+&7KVMNE zBA%pv&%VlQ7_9uJf(o9HI3*FI@z^SV$?9ls_>GV_$S)7xD)FBVV1?k`mNH)jL( z(|YcCd~I1j+s_QV97ncqyN^J{HT%pnQ_$-yzyQ(qLJ*%kyE+OlIG-2(_(Jw{DSs}c zvHZ21b#F+5@J`;g9Y92mE9vjFasmF}A~YC@4m-nc68y29=8-w$v?}>EGIVzXaH}3F zK8$wZ5PV#hwQ3|Ooxj`w^I)mM39#R8CcvpQ(5qRxr>ju@TWW8+v15=bw0)@66!DZ$GdoDF%)~_c6;-4WS((_ zZ-KR1g;f2)YYSsl{j5T0%qu#TLt17Na)?vewf*W*Sl_3}u_r$gYYoY^4tz|%Pd&U5 zj1oV?xq43hi(zF*k`%IHq=?qj0^LUd&W4-!Ten+jZ(;6JIA7UHb3`{RHF`Z{#Kwmm47W;AG;`&WKR>FfVgR0Tr zvM9OSYF8kj-eMfgTb7C6a<`oTx~-(w>>O(uIrm??j%%);NF4DC`nfQR(=Md!q*WW3 z4Rg4Ks${EP7WG-_rpQXVWGRI>j5*Y{X?O-eSFkZL3Vj8gEHJVcH(nr%Lp}q&1!Z!P z?Gd+ySn9$fA4e?)+g_j z8i|Nse5&m}MthTh8lR|*jy?}Il$dMC>a%Xg_{F2@b=-JN#itW_?vMkIhvvMp4LMsX zCNA$s*Z$sy-jmhf-!;XnedRTQH_kkTXxjA!Cb145X}VHIek`q>M@o?GPc^4Ntemr~ z4QX?FG%^LiM>YI6a4+Q}fDtTw|3vc!&O0#Gh20IUzyzrvg3; z5pqUy`5*6-FmfE&m@V8;RC)A%n8KQu^DV;3R$<8**~n`O9*3zknJ*Lk z4gdC**L_H`sb!IeW%J?M<6V4P5r9BvjY@Rne#HVK5Ukw*i`E@@SViKFgx9^kED%p; zA^F!@v+!-M>;K1-;QePEv_}(=J{7`0N3uc$dhh6cK_KID_=Y9&w#oue{!KypBLSw0 zqtt$F;wKWFKGDT-rli`f-C^8t*Sb8b1VM=)@Oe{i1W{7j%c?^) zV}^9H<0Ac{TCyw$i4rccBC?^nz;3OBKi{md%dyC80D;EO_19?+Q-?vvo>T_=Uu3UF zB)iZJ&Z`j}9b4q+y%Sv9MJ(oT%Kc@3Ih%n`P`@A%Od#NKDV&QFf%pU(E2c{L>>yuc zdc;U`-tP###!7PnB=)}VrtKU?y$vihe%*wj^weHxTiRy)dQ-+x2C^dg=Wh1`Hg)&{ zO|0XVq*a6aLo`iae&*kh>SLiIOcycY31v}I$W*n^kFBR4+9O){p`y^y6)!f-@gXzX zcYHp`>^z$OV&Psh4|0`%T|!gvkX@VG0Ko#3dRmt!t*-qY7*g0PC>3zO3Z9PJy>12= z%r7ZR!rW%)mnn~QM~cVi6CDv@y6Y9*sck|d6eFJpg=aMC1H0Rjrl*!`QK12@DyGIo zx9#nYHW>0bdXDPgBwJ@dxSXxLBVbUWHX?`%tedzF#PzW|!@>g!Oqlo}kTLs_X)zTL z|J+A6q0};*IRq=_f5aQH;-#{xqrXF%AuxPLA|NgBxxHFC7EF8F?snTBrYR`*hZi#F zv9@rq$U-M?Gu_!7MUHeG5VP6@`CNWb*HB*E!#7d$a!HWk=DIB02>n|V zB%aHxab4^dYZnvbkbymRi_i=h^UT(q^e>apn1-{L?`i1rka_>` ztF|+P6;59NM9YO^yG$6l<^1W~d$b*YW;o`KbYBuxbDdf?O86ByilxC-23H?oQOHPdy0H2w6>TLsnq4F1x)9uawme%qeW^POXBH}n-{ zvUw3_d+Oy0Dn{j&-q*vR%Tg;9CoCecwa>6qdOoC5Yn=`=()zb2h89U96lfVo=l*sh zlc1#fKEYosX!@3oa>kWb0LLCSgX&wZOl8q%`yS$fAe%X}J5?(C zE+D*eSRHfdyKOmeglhD4poGWVM2;iSR&h|;~ymB zCV6)uF;%bE2cO@3DHF+F8pgnwS`j2i>ybK(W~#Klv9d9=9cxUjjYkn6NmQ&0N6q_2 zUy1NdFKW+)(IP5Dr2XaHDx$;WWLp6ibTWsXAKWI$k>?RE3qgD@JJoDxX>NZqNtQyW zT9u0h^^qA0(M|mn7E7~pdChJ5CHOM&Z#*Ur?-&A2m-XCa!|)BifgGbIdi(NTWq7nX z+4oyL_tkYTM|0YQw>bBYt_ETqM>4;R69Zj7TxQlUXH*WLOo49Hx7Ds#)|M5xZD@nb zU&ibRkIWn02A3}i!tQB9?Dj(*DAx+C85*0QjV4Ntow6CeYwO9*!LA_SsrB?gYr(}q z#Y*zq{X-{CNLw*I!Sb#AWY!w5Dmy&4vq-i8^c}%7{_(HnCReSDJ2(rh{Z{n_w5B3P@@!k++BJROA^PdTZcnQIx?-O zt;W1}4}lG57k17U5i>6HAljjgV8-|vFGm3Qe*jPg7s1>1lztz6x%~(reI`d`+|chy z>=-pMovOpeZ?qpHAI(NYR;m4bz`}@skG4(f}_b~(y-+!WfwXANKqb*2&s^ix-dlMn2C%wwB zZlt_R& zy_2tv+c>j}I4-~#+t7V;zZi*HBK(IcV&7&$tmRZ&)e0%*2K)(;f!qrQ*wQy1MN^hfPWM2feYdNgwU>f*xc{3+`0EX zi{n>itrOn`b7wc_BKd}co3!_hG5?I9fPIY~JJ(1|a!Il*8~gAKFgiOL+xi^N9u2K= zt^NyQB>(pvs;xt+xOx8zV+cS|Lk#dB1HmGq+Z!GfX}-vATi18iw+LTejTGFh6B|1^ zeud{O!Gomb+|45d)xq@aj_AwfR9Yn;oNux-SMtE96Q;H+lsX?46w%Km4@RQd%HC%w z1{DIEu$yS~wBD-|OL5z*MKWrFhKlhEwQ-ZBXK1|>jxMfi=k=9l5xA0t-YUdZ6e2#r zmn$?)3Nci}#Wv_K&Hb#tfBbb6(buUM#DFg-Dw5+`WjEp+DFRd2&!vV=N=5e#eK8;& z@3IEb#7O#4W)+_@VLRnY7OaEb(!md_R_=1o>t_C;u3HugB4ri_Ma#31;=b)D@lUr*sEAZm3fq8M; z(1NyueW~qNj!=Btu~hNP@ctC%C)2yK8WFcPF?63Bd+;55e6AcOTq>@9^IHeYIP) zf5KEv)t%e7`}FD4-9JJbu?-c?feq{G#b(fAKXe?9=hJa}VW;`if7yqsrD`c+1Fj`s z^@8=7%I67-1m~_}vbBE)!N%cvO5Au`k4)xXLI2iS{vf}I8MR;Xhaz(&t@JhXoO>SO zh6dw<_k;|Y7?MQ6CU3Z0YXIO-^r@ZIw=;~E|fnN9S8%mIDG%gds zJmc;YyT7{m$LaQeoT}8J6DH|EJ9fQ&4pq4W+7xoy`ew&tk^HAAqu#-d9`L2A^PqZ< zJ!~Mg*3)nkG5p>aX}ZO7uqz&_M6=NfOikVK0q3WS80PB^DDc;VW6t}qbTsXlDKbW3A&`h`Manu{Q5?i2kq zZaN#C6y+#PtP~FA?9YUsNO9T-$x1)QTXM8!R`@B!(r?7umN+9Uu0|c5)2uvQ6*0TM znZaFH6V#ScbrvmM@tpPhZw+}LUROLrKNpViwI^|rGj`2caFHWy5?&_t#fwPBH-)J1 z2#b<9#;$hF%D#qvVBd1FSTeM?^4b}Vp2axsic7P+j!{w0gm&lhGFW0yt9vlmwsn^G zwi#U+Xt57)?_u&7>Hu8dmGteg+PIE=p!Qqlo5mw7{6jC-#3EuL0gP~4-<|lQ{UQ6h zSAod~p|z_6h*8&_?evHxxfj?0uYcxmVtjz}8^PqcW>b+HNm*#*PlWKVrz+*wd2M#!qMg6qP5*eeeW2KAZd%08{8Z@zE_3C%MZFb zLKFt#t$kGG8d5wpmHq8yz3qJ2Q5QCiTRiI38F`Mk{xJkU@Dpz3r#W@^S0zbj06-C` zesgG?DIdH(Q^5D|JJ$4mp#I#|p9vC6hh6FIaoDGlxSY`~oHa+e1zG6TvlMs`BiDnx zlcQB?+~Mh`yGts|2UqY7tnCk>{E>$(QNG z=$YH7sT*yV2q7HT+57r?-dW{?BwbF89*`_Rl)u} z5?j5H_Oq}`1u1H@E5CYrA>v9UEeyx!eNF_sJe1r*3~Mipt~tQ%BGT694L~=Ij)Mq% zg)(Cqw(0oVsNEypEr1!~ffL=dnc*jK*?OrIt**ZLjDvHU0`pT!v{l;uQW>T*#1O)v zvmPQUA{^&nj;WBIV|53;Zl;+xY5S-S;iw7?;Q{8U)#Elvn&2l2P-~{z2ub$6#aP)% zitXV_-@}rzrdtta`+_Pz7s$0@h~FLaujq2yPj^X%SROxBM?t`WDW?D@yeR>QtVwev zRHoAARHbi{ghh3n0=QE9x{TNG+24Y##tf3bF%LDI9pjhTsVouwb$Gjv$jN4Xwsy)w zFMqEB?);DI^L2TZ!O0p}YMq=DRpjcp01R-mW znJ-(axvbB?_H;hj4o&apBrjn!rBJL$~0ot~Q_~ipKK0__diT~+6tMnr^s=@to<_^J%s`8sg5NzQRE;kod`U#j{qr@QU|PY++oiB*YU&Ujxp4yP>&`g_5u;`pf?a^pbVR$0~)J% z;2*<{vn1`SUVhxI6<*NrcL3_A*`othV`2(ZV{xUrKg-rp!$Jd;6pSgxj>3v0<-kuH zTP#<}jrr?eW|V&@R=d_^E5P}Lylh*%{+(}V$SAI0(0VfwaM6g^^3Rjr%0b=Tf!TZNun$;thkp_< zW@hBrJyO*FCt%@0-i@d>jlmnoRwbf)7H44kk!&s#i5j=;^#|@?_;woGe1mr<5-s?g zqB|=h6an~1g_*JGf*PJurwW>YocZq5+QL?}Gxce=2%0(wZL}?VJ(`Y{)Zb=6!mGFo zS2cOCkY*Ut4`iqFfl+__`<*&oI}w!Z4|LtN0G|+d<#|3Mw5i#H^EbWoT(oL$2|AsR z+cb9tkOMD;Da>5TE%qI_0ytOs5Ck7o#LrfWnbze5>ofJck6mD+%1~kMqMiZ-5JRGL zaNFz)e)M{+gDV8o>$?lY%e3F2@6@Uq{;u_CWQdy1K|1GB3eb=WCJk@e{q5}gtbomu z2YXk$0}CxQzicgxG0??iFcr=Ezztqhzoc7i%YD+6=BbGZ{rml@ zz(H$H1Uu#C-DamMGP=z}p5}N(1^jt-r(j1o!kd@t zaVWuD=5xHC(hD9yTbYXj`jLS0OI6(6%1VHgnH5P2uGu68pc9vBP z^eby@=Dp?dQc>0f5A%WA5D>oaXqq%Xodok{e`CPKDgVTODd&vfxK=K|q;CLTTSEw7 z1??0iE(sx3B272|%}p6+vldr9zS>7ct|t)HMSV)IXOd-mIBqlD+rE%FPONa;M!;t$ zi?+p;yUSEfa7)Jyt)$r%@v%93KTavdg-T=uPLW$*OP#H)H0Dnb+SMdxO=LH4ay~v- zAw66@naVt|V_`#qfrRoWUlO^jlZ~jr|X~}7}f>UkDpTKZ+dGSCgVJO8)eg;7D)R`G|u}b#Q>nWPPfz6k;L|@X-vOBmZ z?tW3u2Upwk1Vu=s9%4Py)9+Tt!xkA5BPv@vMqCnp&$YrFSQ65o6muI>##g^lbu^@% zj|G;^Z(${%)wo`n1C}O`pQwoyZR!jgJYGYYpxAoaIzN!CxhV3e)ByU{0tm@aI|>*A3391AS+^| z(MJNmlYFj=AmQZU(Ic-|%HC)vMnJ0+xDtD)342DmX@Q}!@zubX#rl9I=p+3tNc$4@ z3ie1X*^2kdm_ksFNHQ150grF{QZ&{4!q-|1hqiriC&O?=H#&IR|q}sQiO0)Sg~A^LnwG z{RGq#3BIPHPt_^p9fO%;7trS$y1mpBS@8k~tAx;r2=%I`PauDJfN~6Q31vY5QeC0R zbSAs5@yG9obH!;$42(n_Aec*^6wFmiskat!)H3xGqE(~Qej0U*f7_J}$sL@{%wHRM z-A(FUT$|0oyPN2Fe$03Kio;(wPxVmZnIQ;w*Pwucd~~&>V4HzivMdgVrP)u(KEDh` zK6Cs8&PS+zlhnN6as&s?-LJ;COT0%+hV`YxA)kpbGbwPDY5C82^-N}ECs$<|6lF{< z#FK(8F*PMsm@6evUB5x-W8Hmy)1<@c|t<`qa<)mIYszv^GQG3Nkw4R7ZessC#;~oV6!D85*oPYirT5> zNnQ8sjR+d%oe=a9BYBl3+xg_kYt9ZaRX9Wriq8#_e#TuH_>y+D%oE0YRnFkQZWgYe zoZ0a?@nQ|7aCm%|4y1~`rQ#+higdhpUebHiIp*czsl?Z%>Mi4{H+)Pv&GivLWQkiB zVB)$7Qzdn?GXPR^E;)Tib^W{0e2q2g>R&B3O%st1>mKZVWlllI#SBvUxNF-w|KZu$ zHpTBI!rZ}>vL^i=;)%OV+<;B4@$MUttkw~)`}fdt#)XVgu53&!l;a{dQ1GI4{jQ)i z6|7H7dnP*W`BWxK5ZRGX z9@dGQPV|UFZi{DB7+&}*CYA|d(>-4FCXHH`ca5C63;ku?(uY@*E9;V3UqAbfc ztk-7N=4}<~ex6n+6JeI|^WTcY&~J86I{IK6uBbIl9u#YdYkU4d?i7Fbh&!ec?N2DZ z^@3P}7d5Dn3rgP>*0Jyo?2Z3_ZZ>0=B<|pyE@v=8qdWI=_bccrr%oVRwl}+o`c3w~@B zDP^e?S$-`90_J(o7&!-AxA4!kq8DGMzrdvbR>H*gnrckXvO!#}*d=IEa$>wI#xMi- zqML7yNt-pr;)IpB%q$o~&6a>3UJvdaeUD7&yyS=SL|9_*S?vAVD04*6B`eKZ%Q0pT zWK#40p5Bi83n&;w6HOsg2cKv@^Y=J_MmXV&P2WmtXURAEVFLt1or}o-oyyUhOY{p&nrK2g~RDSFB<#}0~yx9+aDUSo;3D&Juf&36#G}j0e z!#ekIzbsbzQB=wrg46V4XCpb9=e*gPM^F*@gVw(2E4K?EGTk&5Y6yq@~eQTIYLjk1vGz0bh?4Da8F&WOWOMIKa?V zaWy|iNCM8W9m5)ZcUI3K_GrDyU_oOs#cx7=Q$!H6?u2FNkgEa&EXsU_lDismLL=9;bAAOES8e6N8B^faFpSg3`qpZ;kq#`GdQ_L z>E)L=jOz-Osu~-6A^P-w5%Mb^Z$UvErh8%Oh9V+k*pPN7j){EC2whDrFmyO{5EN{! zgv45mcS1ynJSapRhqAla>Im(ZS#0=0dI2{||NIMrZJ7`_%@%{@*wm>pHuzk%$P{p# z!JHsVbbs;d_R9Tra^2^4{JyDc=e0!Do~SyaVKds z#r-W5$hZhw(_X*i@RPr1LI=|ge?E@`PBvaP(9WGLHOF@TK3HfR!AJ0tDpc|iMYD~^ z3+NM)3peVLapeqHRhv4oXaY}1EHySUi=he=qbcI5@2S28wwbeKH%4?39EeQS%>+;C z*WF>jI;LNv`cs40^Cno{Hbp}`0z6M<+!xB}LrW_BPF`eP*Gl%aYy&PH#=)OtyI=5j zOD(Q}G6OCuG+!q)YkYTPbvD&MB0rTVyiUH&KH}w7eUYk*9(y_fiY;k99S^SL|g z?6#yRSEATL`~PUZP6A7& zdWf(>NmO)8)GdyVpDoxzsvPYF|L6}eK7QE`egkJ z_?|zaqldo)*67JApN*%;^MXEO{-FG%(SUQ96Z*+M%9of{snsuxidpz5@O8=`HsLF@ zId{7YIaVv`v@dj4pMs#I9-R3RlIwDKCwtUw$M(YCiZiR{Ezy^64~==2IK=+fSZf<^ zzUPF7tFN~AjT+hRwhZE*cfTWDo_cdV-I(?ZzKXm-=bt)Iv|A8GTOlAXT3Qnzq=O_3`#I6;@LjKQnEY6SVKs(!a-4lF;Q#c|tw*MecjR-y}%k)Gc{0 zd#^8$ZYyqEom^s_PB7q9&hO)@n>!gn_QchK1Zf1S=xYxKNt zPd`||u0#4*CK|3P2>x|?(-c@}T^_GM@?+n1sd(ij*0YwhVZpdN(S$bWb|>t&$e+kx z^AQkH$xrs+!BnhZVpWeRNjqaxqy!5C&N~Eh+J-uIf=V|2dfs2TFA*W;Px5g*uXKAJ zRWaLio_WR9kNOXB=q@btLW|B`Mh%9azfP{WYB85f$2*1|KN++;J1_>O8H9YI$DA|! zZ#EBRkhyJO2nbYl!R3KCz&cOKAPzsaEMQTiUMV2Ghp6$Ou@l}zz`J`V1quvM`DyU#s^+dR0+T#tLXHHI%B)nTlY zlnz{Iu1%T2j;H>WhK#lc>@xEW57M^Vwm_;Udd-=LJcYvzNv2X2Jz(z7B1$;FH~Y(z za|Zxn8#S=Z>@Y+EDd~gvE*q;#6%)W-KBNtqap-T zufNoPB*k`Uvf}o;(%>&Z^DeiY2%_yyMReAIY;{Q+YBRYM2BpT=GF*#N(V#B2ffQa`=h zfEz-^%7(u@om@a_2aSOTjombvUpWc77{0o6!TYeENNS`Hb?T@SV;g!hV%hUXz+NMR zDSjUMhok0;yo4?}ZlH-oZnh(Nx^{Y#rSQf4jnG082IKQe1Vv4^U}a2zY5r z0~c|OL9n2qUr52hEfDv}r(u(of8W-07yJ)3nL@A%e1Cm@OgCFv`0+qZOw1HgX@oVP z*m&Mi(nxmuc);~Kq93?teIUA*AD@YQ3(&pR<4 z4}Uq!WyHM+3OxnV57|X6vgur3?Y{VpVJ$U$*%R$7y_PawKom<_?6RVhD=6ux5)5WMoeJsIRwQvP;Es7Z(!UfqK_X}GRBmmj1cM>1)0 zdinjg)HvWoyORH-VLJIko%JsXTOYqpNE7cT?Uf`M<9f$hE0ALnzUe7BaG2#N=Y#)7 z@48QnHU~Bxf~C$1nsriAF%-T(;+?2>@mJtMFhB6cb(cMA>b+cWX`EjTBNs0+I(x&+ zCf-vkq#XofGAGqfpH5sU0ga3gVKU*nol4%-JF+og_AzVUQ|CiZAs0nr?caC|2^K2l zjh70?!CS0I~Rj0a$8HTbx7#qC{ zdH9a2{lD;r-H+YR0fakuHzp}J{R35YHpGXR9(f<$E*EQ(@MJC&!d@oWg2Y5@ncL>O z-O2f!X{E0^aMJKHpO}6_IzP+E=NylJvi!R`D~((!Tp~_|@=W|-OTGR;%*_8Rr_)|m zmhg3~iDx!$7~{Lr%f(`i-}rU*N@p!#7J7KlcU~u*re)mZbSGN&un2)hvH8yKc@);z z1K8U1BidQP`KPRBd)My(dQ{i% z`kEL>w4mHbr1k^3n)6oC_j)*E4cmi6yulJUi|ErK(vB_8xX!YbO@UHrV+SLd>5p@) zoe*M@Bi=kWm&m@Ik)%@f2G(6pKEL`xQ}CvDZpH$B#O4l)th);iMhoQS$NZ zq(4EBGY1JH_aZ4~Dc4dR95U)b`TCdnEmNC8+h$tm^pXv}ZSmF%q<47Dd8y=xzm3+KPXDLR&ssuTAK70k4>7rYRsqEANR z-ty!EMclr3nn3%|ibz?WQNKf(7&I_BMgsjpb)0j)QfZ~oIr1@y)J!RfVr0<%URyK> z8L#1D_+l}s%p7N8*OEu5i@p~F?Z|M_i`)|R;denjs8CFYuBH(?K*|9>HIx6_{@i`1 zd#2o$r66DlYk4!oK~7^{N$~0ewV{ioX^SK9;qaRu4DXgoiut#JX){ZRo91M83Bg3u zPY=<|5n}ADN0FS8c;?` zcGtXY#&;yVAt6o&KVDs3lNC%3rs2+O4xkhH7Q?pB41AEL{h&}c$J(;x@aD2EmJame zz1yU%@1$ncsuw5lc)t-)FU5UaqV$<=?|ck5pQIP0-uzqex@z%d_FnIyufCii%Y}ou zI3?h=>kh16!->N~tnYu-uQBjG%&gFTq5bTf?2}+9Jz4WuB5uK>ao!SeM7`1cr7>ki zj=(;B=TUtBQT;98ZzK?LvHT}Zav4d+|ca_pR&>?>Ng`Kj%hLv-G#8nAgV6x%A7 zG{Q1n+#;vn{abEr*1&QFsAT2>X=G@}tf6UCAN)|z#&!OYW4En-wT_Gi_66FGOP8Au~sdOfZ183c) zMse3k&|bdxhPVCgZp%VhC&IR2egDMOvP^O@Wm=qLpSvCTH&?UvLgn*uif|tG3p3%% zMw}*OQKskvE=beebgKR1b zP^;f0O>YeJ_CGn=+~{~|Gki{|GJL5&Bgy2j!PqqCIL&*z(`4@6TjyjX2))(=Yy|l1 zu_;d5h1E>i`+0$j~Qn>7LM$-XdJsFdUw$lm6+xV8qx@{K3)Y^xD|& z`hF%mL+7VPldeg^!sDCPQh^ydD{Uqg+L|a5AgOSJoTurBjgR7P%6>Ik++a}iQ2~oMuGb73<#Hc90vg2g zATnTf+qFU{8)OWhw+C+IR`LNu=u`)q!TFE-Dfzx8fAbVw-?pV?FKK6zdCvtBYicv6 z#eB!t#+y3;w_pm8@zSN&ziDT~TOY8-^@{}}VIKM>jyeQO);nFi6#qz9q1O6aASzyA z#WemzK7xi0n1eY#c(pIWyc;`*y_S`)22U&1Ng0UB5dMRb>SVRT(cw=IJvVa{ggD zgm<8hd3P#KTA={La!Bmy6vlLa9RP@8S#>4)*_^@qpkJ^G)|;lQ7sPDg&H0G=0Zfm) zHHLmS&R6Aw5dl{vz4f}!`&_7?6@+EObzeHqt%t*TkKbICutadZ^-h9-?&tKscyAT6 z@1t-<4MB#dyDJ5j`&woeWQJ87t!kSb9_)Y3C%=pDgIOtW@Sei{1e8~>+S<}6v`;FC zwiTc5_&SD3%(0_vNyy^4MO=cf&RyL>M=hNYv>hQHP9 zH>YL&85>01o4!)@v{xzDeF`f#`2mC0(%S?Vql^pI)T;_6_kyEjE)L^wVdwm!&5ZS* zjBOGd5y#`qsB8t-?%rNJ^6&g)MIbbgnpV-zSAIhiRh>45Y3ZDL*y90lQV)iIpc6uwHxLbMAd9{JO>;)6WC3gLH_e}nmgLK}cVyeA^(FABv3Aj79=R}&(8WY^OL1;3V z?$S2op0I&Zd!=mzkL!8o_e)K|D#2RG9Hqiu9!u2n$GT>B`|1=|E{b>5t^RLRt!(OM zB?Hq(W)$)0%5MOiujwe!%FXDu4oWk3u6ByJQJ9`ZVr>+0Pq3QvTfGK?iamB}0_6*5#R$2<4(@FDr?S zrg`+&1zgAIIJP!7_Ahtl0n=QezQpG!Nch}Y`jkS;9XYz?iCn>&kN zz%=qrYp7vKg~}Hy0G2BjF1~gEtb2S3-2MVv+#-LCmm4pZwt1~$YWz|LJK~M>9SX1Z zcd<-1@B%j$jY#3iwxP`^5y7BWd_#DUg}d!RJt@K7kI6WQ`C&MA903Di957|Fh13U5 zZe;<)osIW!Vdx_Q3wM4@tR|-&%bNdrEd!uOR_FMz>$`%(6<86qC48h{#0ag+WwB;L zs#Q|M#No9eq-E#s;#^OmsL9!QK&s_U?r`;+ztasqco43P(_c-FA|_X;Y^va!)jCFYPH6VyBD>jPyU21FzeEg&|UEW zjaJRqm?ZEl_xRh}+lx2gM#UMHP>;LP1b6is+imW(e8ivmb@$E^2;$`i|^W9E#E%$mi!7kGR#*?fS@Cx^6 z2Qhv4)1SUZeX4fb%orA;V( z>!oqG1!}6YJ44@^3M5#2Mpij3e<{um+e;PYfm8ov+@o@bsTHA;Rfk4*!;ivHAV6hW zE(}jUEojR+pNfe~!2}Z|KU4|Ng1Remu^ZJ>H$+b(2gfkBYlMNZhOQuq{LqHfH*q74 zS4c*q`txM@b%_^hX9>?gRIcLZFnBX`)j;a^36{p=S$vo*w(wD2E#PoFcjtD7QHG;7 z5E_{`QxjWjQuhgpcLi6!6Uis*K;^GWuwUaT7RZ+IE$@0uxlh5vzYq5NqS2zwjl*mz z7~`LL!;@Sy=#G+VJt+W7JP(bGYnt872~gVaGoanim8#Zy1(-q7`bj*s}}Z6pGVm(0>cXD%M4?H8AZ+G8ZseHY9Pw;E{w z6)%j_#hN_hSqHX|<7?&oT;ZId3srhidC72!9>!SohZo2Da(LfcNSnW*1Pj;hG#*x$ z7}mcYJkvLh1L5f;nQEB3J`oEBGIL0A!=aPar>`l+XVXV8DQ>=NpX;PNLdLByHN zv2M6?N@@%z8V!S#u(U})$Aow;fxF=se4gb}#-Z98WQJ8k!S0wJY#iK&s7>+!DTphQ z&tg{5sKG--4az7?hX_d%R3pMrr?)A#)tKW&e{K4n(=5`J)2s`%_~Y?4Srg?D-PHQn z#uW_6O=!7?bAwlkd%pLDQ{L{+ec6)+6Bs7APNh6n*tkRy5-mj(<+7NGW*M|RQ)|Yk zJ)I&n6TSY}fCQ{U(XYAA?`Na}*s8nWO&w6D`~H*1g?Gw@Q+ccWgTGLHKBh0eI3p!` za-x$!3}aARU!Hz}35rS#jhsv(#Y`&R?uk17c#<7}kYwgpS$>OvczqHz_7@F%i)G4y!0(L0m1q zR}|V7O9K?%>Z5CjI*>600mNX*K}LcEKwDi@8@2aCnL_!Tb|zk|)U3V}jkU(iUf`Nf zHV-hjk(m#qY9*9b_XQi(3x=*C4EFN~ZAb2J486vl+m>B*E$OhKgP9rkep$v(#h&x& zE*Z~N7M19~x4yu4S=@;(*y9%Z2*mE^S*WiHV|lB4CKDQVZw0E*wu?bhg$!m& znWQHz8=`kzwRl4lwj@d8z^6uK_8i4SAyX+YA72?$r#A!&U{)2du_4-uIc#%G=-k~w zDPk|e&={xOD5vIoecj^P=GrR1YEheaC9oUsn>l;7UYfS=WPOsO(#{sk(ZGCq)Jtc9xl_0qe&R6ga5Nox%!sy8qeh?lAin6e}BM*r+9_G(DP$};7OE_xFRE47Kq&(~HQ@?vE~tO>(l z?e$N!59Y3t30p#OVKlq-ze8eH78^1Rh#l-kZ?6bvNtqY1A@5g=E%JZMwP;i$3c3?nsX_;(QDaW!CK+I(nQ zdCZXx5?O#pgb?ngObzV00f-?%OW(gjkRtr&a2D5LlQWOsi%CF$<}ms{*c%p< z7S^o-y@_1l`qe%8P!FbU3`T^M?u!@EvAgJwA6*d}`^O3X*_%R4Wp*Bj*s^6! zi_R3plB8XpJ*9^<$Qw8w;nipk)|^%PU72`j}grzYmVIOV@mJrnt#2S@v!?fkF)k}Vyjs=mJ3b9CW zOJR`aOaD#wwHJGeTjhp|ho)gL`V-vcWziutQiRWO)sKMvHJND|;WR`B^Oq8ty(#hb zWo3hFz!0FRpjapm>-v|wOQ-^Od5pKzpqU;)UoSy*B0_4Y8VO>rkR*UQuDBXKY-X3u zJZ!ygF1!?751}F5m-W*xnwt!QN+#j8O%xGqGbdWOi5#o;LZZE8nenkFVB!my`lgk{C_W-9C>~mhUdJOWRQUR_V|C(^#nMN-ml}6t1zy3&(o-}X`147@E zW!Xw@7-A1^4h-R0Swu+9%t4z@fadw=D#E$Qp%+$g0BWOnAU=h=rkuto)9^LZD3L~e`A9|YbIQC+9L0Nz`aY;py zcu80{j>;RR=NzAf#zeM7d!uwOzc5^X7BV5t+At(wM$l38te|Ah4$|{Ry(16w)B6B{ zHy%3je*W)02BT17L)SR}KuZGm&XvE2q67u+zeZob!P*2?%XKU?&4uG3hIWz2Gh?+HtD zFvR^0lD+kr;djcZ>A(Z5PI7ZB#BKfz>>Pb?j${bL;kc*Bh+&cr0o6CKR`A)~UulS@ zd`N#>CF1a86>F7$rSty?Zw@6;I%uthbXJb( z#R(Jq7t>CPXR#s1SJVO|&1c0mg~ra6evI?G8tk8gI@6zFCLweX8s3lhC1|at9Sh;D zq}2UiOYg@-M!)X&{0BUsJ?&zX9G_4Pnga!))#-c~$+TCGuGJAQt3GF#Ito)3V%V$- z8dw??|DbI^IqYNS6v?5-jm@A!Q2&j-a&6zrj*9C*msnv&I>O^8f=P_IMFRL{w7kMihv}I%~3&b&em|+IGa4oRWO|7j~8o zv!d#Wq0B|7od`|Q;WetARjYNQ_;;%XU{>sUU=6|&f{%YlD4P`f%3)fpxLxp+`@7Fl zaWJ$WyX-p{ty+Qsjl_I8fvc-r~dGxm|GMEuSG!QhhQG2iOxVp_$~I{(y+F1 zRsq&0Yc)5RBK}@KWT6AGH>~xa6t|%bX@pj-pTJ)0sfBD4LZ;`xz*|raC*;Zak9d&q zPUSIMM4^XW&w@b3C2Cb8Qx2!@tRz(X-99*Z-*2~C>`VzlT{89U3kx*! z1@*=nBA*5G6L$o1cGGGpbN39sM2mvd?Sj&k!z4v_}J+$q1R(+ z>FB{eJEfe7*8VCjS&new8_67nJ^aEBcfJ8T31i!8# zG;bw2L_-^PO3+Jzk`6-bqo{}=-a&Xr!+cXdA+F@dB3B)_z;%~J=whwC*3^)T=O{xa zgy_c*tG?;K7l@*>mRd`uG9MY3ueqnL}Dmg^DB1-4pe1_(RRAF}0yhUmz7sX6Y9OFIZg-`Xo zd&x6qX>q2J6v)Vx5ddVjz%G%Lpo}^`EcRH3{J20P6%~}N+LhlN#90s{tx{0vEW}uY zAsr-`2YLDg7M}CTFmPGOYCa?r$+k=s@bHYb5=P-7{^+RO=sSpO3>nrTHZ~=c>Bcuo zQN_V1@^md>qfzm@!6;V@(6T#OR`l#v(Y_pox!bCw^9&-ML+`n10x9G+bc@{jd*lK3 z7<3~4oE+EU{nrh7dw_>J*#G>`j`eRsX3i`9jJ}Oo|HM=xnHwtfykh+!Mvk3VI-Sb$ z_H$BvybA6`Iz|Ulw!8$?CAAu4ly-HHc=BUu?`v&kW866ag7rb=b4&D41%_>63fCsY zwDG9?E6xDcv#5s=W8et|c7RwuGY7j{c z|2=#)eTgAhq~y#^Q1DfTO%2x)Jgh(LD}+349NTc>H}g--6@#TLVJ{ST;tlR02MJx= zG**iP%v*}zGt?aKufZS~y@iSvUckz8>^@cZ6O3~)w{FE`P&T%lToKA*V4|?&kft0^ zRV`Tt7K!3@+nd_-LlfV|;jSy6zHFY$Oh8+-Sx~(Wj1q3V7K~m2^q>Lu+w##h3|qNs zA%LWp{21|;ZmJTVRM_<~@pXe_uP>Fv=##Y}@_192TK`b0<;m(^tt|h+S3Y!2YcEpc zf5D~h(_xhC={vf#Gpbp6+ll%|j&%sgP`jY${QYj^TgH?0%tGL?Fh2xC>C>^rMD)Z9 zdCa4!!UxYSVS#@MA&{XfKAG9tL6Pq6?(Pmjx*KU05Wh463(^vT z&#wCW8=g0QmVM>y%$zfG=H9s>JM2Q-#-ezk2LNm{(U6Xa@K*%$pOY;RiV+LoPzM!R zM$jpesgqzsK^?px#ILvwy3{{`&jno5V}g31n49y9xqk02Xq+OZVM`x7p7=^~gisbs zk&2)|)AEyhmkR-{7h~VUzShV2?g%3=MoQhYC(n2?@fR!Gz{61-BNBC#`wovjg#!*}JL@&RBvd8U zW45u{rLrl$nL>_1F07t6t!MLm8_q9Qp-;y|?xopnrBsR(?P&FF<|B=F8bKBg{Qkb& z^&`@@7p*=1xga{G4)5gdh$h%HGJX+jCoB=JH-ZH=Ozm!bj zNx4EQ5M20(6u*c_P%g44o~j8uaAcl_ZiBR$EV(=^<*_MhpLv5pj{ zGCYOBe2Ta{+ELAdAp$+^^c*%#$q$NKCFoN1&woYm4SCE@TX0o<&YN^7!~ps|U&^*OT&_L%5W(qU$I|bB2I$ z5>Ho0b592RtMM9UvE|+xI}9=NhVl?bI-&1BpFwLjA{t{qQd=Bby3$>*Id_VE`7j7i zKdrsb6xtkn+aCq|Pu~PR7x4x_Lx3Znpq&QAHd{P1M5&8H_@6*HjVxx4gDY}<`yw`G zXQS!B0P7q_0t@P3v9;i%%_qU(couE%=8B8!gi77@A>` zprWGqy+qsWd?e;s9{9+QA-PKqrqO2K@4A1FWVkF)r%K+jYX`qOubK=`R+S14xhgx zBBhjtfvZTQm*u6m;hVN1vrPEesE3x7%NLCXC?((I=P3|eG|e(l5@tDMpa6AX0griv z`5GZj#u+HqVO+<9_xaOl2;_m2SG!cx!)~4{o|!o%Kkd<;Tu0uXa1^9EH>%l3Ud1a* zVlJi$cYmbHF6s6!TO$%O*%le8bY2`Y*KrzOSry$L-_3qhcFhF?)PIG)dg{SCA~`w0 z=?C=Ll`lJ3I0pCp&7t4lfn5vQ$*POoPym%t`c>dcmP=KVHMg8*#2QDcn^GFB@CtRw zPp6bq?)L+>?~=W_!wjJUQHBcTqkQF^*p28-B^*n03O`limfbmrB2>BxpNW9%cX>;4 zm~?*y<3-ew4a`!;LW@A*bSkX2{K~3tQTx&{_Goo%Ea$L=ecSk_yiI3UL&Ia`6RU9w zIIk3kO2BZ>Y)?wHvgxdn_sP7}{%qI?0xL%%--k@LcE9U#ry;q@%0Uw%kQM3_4DDHs zR%&})!+#XE$yj`sdMyA*hIsIJ36A)~xXH-Cx&>UmGM-bgkh9p5-6aV}viKLDUT}ys zzIdXymSeOHaYfs5O|cVOMOS2~itLX{`_uIJ?8>BXM$e8Y>PX8Od@ZDumjmKFU@Pm; zcqD#R2+PKQnFGwoeg&yjS(}z(pe2#mU%#Nch+v*wl8Jx#sqEuce z(8A)uD=LE}7#w%NvYS-{Y0M0Cp%~}Hwnq;El^s>a5XR$`_0{Khl2WM^!-@qT2OLQ4>+Se73@*&uVd2V>A294bo*|&w-wgDk#1x@ z#C(MB;J%xSLjfiuApqhFf2v?i;2Pb|zvldP=cPnbt^kZMAT?F>wE+*(h)G+#WerY@ zsdi7@Kg}(JcoyG!NUb7H{U)py$8(-!LqS{pjR@A1+xFQ6NAao|s~j?#S(@%TUOqC+8mhH*ZbNv19oO&&EiDd%9S)GL5>e_615;tR{ZCuJF?ZEPixJ8t3OlEz*#g1DdI9I zXWhJU=CoNm28|H)iCP7%N0v~6&yf)pCNVmgr&m(tD)#B+yBRsAOq1@`GRqYb@n_RC zgkuI6QODslEF=A2oZV$UiXp}yGEAjVAtuI$iN#Wr&a@d5k8w-X9Oiyhc%Zo~A+!lc z!6p{Mq(`K)$=v?_&e|BaAO5Z_V6{c0_94WBf`V49l#@@4w#}u;M}kn)rJ2euD<}I( zA~sU+Pe!pw?DvA}7;D>7&UxCDT`zE4h%K+I0kfmbnNSMJrnIdPK|j94<8RN5Kwmz_vKw7# zdxwFwuiMOkojRH#1ACV`O#`gcx@Y;?%4KpDgAy>vQEXksJ z{u7D%h}xfiEF1~GfM*Z^6Wn!?!vlN@p();1{xJ?UAT5*iKQKiI44EdrTzW!qeJA@F z)dM3eC#ZsjmjXk#$Ao1jN5U?YbKa~uM@fSSr>3Y2$+1cy zZvXbqt69M_%xLrk7!G>n95pWJxU&pXIks!5Qo#7%$sLN*d1(yi&QX^w+vv>hRB{~>b zgy$%w@%^Q-Q0n@cFS(_+G_|iyeQjmR%11IGaY&q)HptY@yHe#^GFs&$5-Zj*0rY0s zU)g=}pcw`2fZugKcBQC~A+7bKD(hFTSnb*)$;znKsf>jD#zt01)u(&*O55Q5koUZ< zO%vmJEj+D?!x#<0$=-vR0&!w4js&RZ(SP8(T2oT~7nqR@pI0$7^!~Z7yZ44u)!=Oe zT#N5n6iY!niqe0sd-wqT#`pU5f;gA*nJZe5$4)FU?Nh}!gFX^Qj+D~4GEcuDrb#?o zmBzc~p^qhI46dO8RRT0K$%1 z5AoqP=3?N@Zzy7w>qMNWfD8R-%9k`?C?tzweHvzE55AD_wN_Z6NFA&{LQr6e<4DxN)tFe*(NsNnehr#{Zs3i!m>(|wD?B$Z zaVTIt<^GX(?S&^q&ChuP1kYia;k=}QV{=zWM#v?FL?~rGiiyxB07Ntb#Y*rYC9f3@ zC(c~eO_UlvkL|OEGloON0dk+7(PyWZYuP6!+ zveqB@gAe$2snjCS!U_2oJVonPC9mibC>*T`k7%!zhfE!|_QDU=AEIw-_0<>jl4j{6J8|K3zKehu8^*V}YYEc9^$*D* z0`HGFz*0Qu4hcK&!Jm2z8BqUH?1|~_mQr2L$S7oJpXp%?x7hA={Lr*Y@$m72Y(?gD=U(XjC2khv6VFzM4G=A^ zCIUXT+rqK_BOKz-$p>-lT%L)rrliMIET}Duec4h{ig#)-Brw$jvZ1T_0V9}B35}1Y zuAWH^*K!#ua2=f=D{?4)8`g|5S|uu$TADPa>7yA^N0mY1_2huZ3Zjjwfgw1*%xlNG&{=e~kCMWtT1QzB0W#&fn_UIy^>kIdqvsB6Ag&OzTy( zn{@S+L3xDffb+5bosO2W5Dv9#d!C58TG-%a-)D1ciFX+XGFZc@$M{8w-YVaY4JTVE z^i@+QSaY>_cw#Z8uen|w@6fshl0R~t<(zERrD9s8Z7!)>@yAaMhS673Qd9ZToot*L zimQe;vt1Du%Iy8_Xlp9^2&zAv0pg%rF|GBr?;P+!hogna|M&wNApWL5pGa{&__zLe zYh_0t@I1=9{tt8%@j7zqFO*c<{ASK}dJu2wInHzX|Ndvo*d;q-E8aEXo2MHy`(1?m zmh+vH;Z%OCj?uNMY_NLibOU7{P*UHhwJHx@l{bqPd;EClXP*=W>+DkjRgW{pkQ{lE z^|p+XOO~0(ao*sJPdf>cBUQ0pOkHeu{#3PM^pVJ2J45RJh0gHTMT_7c^u5I&KkE0Rf;J2Uz9Jie zff+^-EaLQa#c9^)zjo^p4}?brHWC@>das9HqM5J~aiO!Kw`%irw2C)=r4j;$ixEuN$=qDzy- z@M^cBJo6$wMtJv0sF!d1RIssx11U6?`NIXN4?yQ^F;|6yL4y}EU~!P8{y79_sf0i1 z^4dSk)Yo?q_=^w*9xk)~nHD>lR=8bq>olBy>F@{EM1ZujKS4W?!_>oFW2yI_isBOF z11-k_i;_dHi7>y+Q?#NXz0SU>B?vIw)ic?)6FPmqqQLY{=$41r5iVb7w;?0^%+*J)w=AsUtPxRTa7UMCZM^|m%+*5~4)|^XS zw0{;s3d@-wg7FR_;~H+eRTzd@Y)^FjvcSMAL?0-M{X^GwZ8(Ug#i^h9u(SPN$Edp# zC}CHE4E_r=L!v$S(pviG452@ue)i23UV>35zL}P!9K(J$=nBCjJ%NN*DC9V*g`zo3 zEF+g1=}ktix43#~$l3m=*OUHZ zl?ZSRFC&N?mg~E5Y#)PEA2k|pD6N>xC$}-PQe+uO^bljzJP~6ptSaX?tQV?*#GchT zzun=d1GSZ!?>gR5%gtBC0LVCLf0K$Hq!LlMO)+4;V`#@a?Ea=%mPsNy$@O4>-&t2GU=4Ru(noryvm=>A!ZLp9v`Rjn zB_x#Aq`+1+M77RxP4O8dH`<$jQFi)0b$|5shcxj4sym4k>{98G`8l+=GY# z5|@eAjv5OVXqz(cV%s|bjeB0H8?xcXuGi$X{NACJQLel^??t=`pVxi=n+ms{c&aja z2UE<51T@!pvIypt`$|OHo@wJdVqZ_^L3q6;vP+A1@O~qX<`6#oZC6L+bzVU^Rc45f zCZ;~&7n9Yls#03kDas=}j30^^kEd-Bt6PTN_>Y8@xvHei5wr*m{{d|`ogvND;1+4P z+b->KZT&|VFryS2Ul_uNq)>MMW0V^TM&9SoU|)@ll06;;{%>VJ5fb1CLgPf})p(!f zI~(P~4;4f)sEiVG^a+1r()QIu>{Na^d9<{KEDX$se2jJtoJ1JSv~Khn{qko zSqBNdrliYQjZCNwR4~=)zjP$4Y0FOspP{OTd_^I*AZo&6N9s6DPk@^%Y2V1HxFXU_ zqu{D&3cLqMh~M(=!9dv2o*<(E<-0uv9DT=A;PWA zRkVg#N`Q;1gHullXL@3WB+~-QZTs$V$AiJl&qpA$Y%T5GCSgL2XhXgAb{EI2-kCcC z?3bHm3cieo$pqgfNL54h^KJuL>7kU4dO+%7l_t(&nPqD$a$$~dT97c193sHW1bRij z7-Qg)#P`cXK&Z)&27G?u#=?1vpU!4{z$ez19rF0V5HEn}Ha@zr`wKTz%Kqp0E#FuR zVL#B;KN`}NPd;4rqUMyF2LUTW>1$+9+3XaIT>~owtOaN4ToTC|&iWeZjX)OTE)Kgp zOcN_WJD#ROvkIWQUw%B9I^yF3CuiS zP2o&T)hJ%qI$9mdKF7Ba;jsnp2KS-2+gkEHVJ1`&+d%I$_8 zSPzxsLbOQjl`uH>y9)TPxSjxUh=)fs*cSYsC((ysOAvu3e&?AOn!$b`UuC1d$WqHx zVXT1NC<1)f?}iUkf>_+8$cdqvd(0>$w~AK%ajZcv#HRv}xGyeaJY@G#%NwII2PohB zpWj1+(5?N<^~W3!OdU3gb2*vz=xYoTL8=Qz^82xHD`przOzm7lPNZd6I^#f$> zuP-fZ2@LC{t*SM#?x%xdretz3PMcDJCg}A%?i}e?VIM>FFi{QDLY~EgMpWp80XGK@ z+iI&43_}9ww-aUTit>$J-X)I91_vTINen?}`)$>3djD-fawAjRSWmz)W@k}^&owL$ zO9q-B#zQ}U;uzAUHWw_$#VCw2>=on>a0p?B7g<~H;I5lfKIJ2MC`Nm6cX~wR9{lwt zA_y$H@Pq1|P&50AMfx6`hc=@@sSovhZ=>1=AXC}N9=z9{-b+GgtnPZXgr#N?!uG2Q zTDD=GK^yiLUWTe__Q;HGeV@-7uowF8tkx9RKf2DjnM`!sVPc{ArPnz{ao^lNv7Bki zM?i;e4%PcB#YeofomK^=q$D=?=PRi!Y9!uwF)8ZQ2Yw_@zr3+TH9K=S@F63utj%S5 zti>s5yU$eZ`1(%61wpy(cJ#8e27-1oZuAYZ<-b)i z$N4U`=$-agHS=Pp|J)Em`hPT)gR{;Vz%CBWyCm@!OagwNSV`DKmrBK&v?cpAa=wGM zPC$fez~E9Yv)C3!u^}1dH;~5e3MArcauI%dnYB(1H?Q3K#%1m`I~A za3*AnoI7%{%X=shNfz&iWG8I7Vr|6tt;fmpsZg2BV2OUnP56aDajK!Hm?+vkrb#K# z1*CRDPh-k&#{4oUC#7m;rgV?ODa!ZWiO0YSDl*&e+Gtuv4H;}T8z{1oMLMeFEk#L( zKXAXPBe+B0%kflkjzD>KEVG^Ql5 z<_{1e_@Lb=vBqx_{R(Y9$QHVmEM}bfH_ehiDOtcx4gL!B{D&r_0Enm8_u#+q(O)_- z&yH|PWxzi@4B*YVyafEwZXGQV<`$hbWubivjI9! zJBEY~7z%5TW<@QpR>%d?1`_;8vNTEvBmVBe7reS7PH zgE)d#VdAxvBwH)BmkNeVl0Yh|X< z^%-qy>$6Ke2wauFHl3-|_!P6uJ>VEY$Pl2S(S4svaHw0u?ziGxrV#8RGs=ma)Oh@r zqGy6SlvPR6i+9{u1!%0zfm;WZ)G6EZD!Zq(+aRo`mL+O2?ZXh+;B;!~w%Z7?ckoy~ z-eY#=ZBWO>s@_*6nMBtx*Wj6-s?m9FqQWW2s&-x|y8}SWGV}Qv??^!iA{^S^ql=_0 z>6QyNF3n=l9;VZ2GZG9gst{W@=!B~e}MSn5<8J^;0Y)URiDVksky5JxwZU+ zxrw@jHXRd{NiplLI)-md(OYczJRK&DI?hnmC>{_`B5wuy1k^3h7!a4&t9rIoP`Kvy zy%pI6D6-xgLqY|W;(H!faZ_)$}Iz@ie@5x&9#64dMpb5@3;i0|251D>@+F!|O zCH+I(h`^mpB9!_v-L8MoayFFr>HA-oo}){+A%t+Et4)uqZQ;qnlvBT?Ux=tyKIqi$ zAie6#8|NP~2EES(X>V)|4ovP|_G=oj?rR1%=tSJwiu;za=Rdg1n{zFOHE3zy7`Pq1 zbfu*Ab1K)DBLTWZB1M~TkwkR`wBrf>EivJ}1gO2d%Y_c`OYI2Fq^1hg}qp)D6^Xr{lWdc(KJ zQRsg2`0e4VWEJ7gafIW)$bfc6+F|$d`{$@$$=&uoC(T5-5<={7qFX<36Q5V7HrmBy zZPJTB24I(eR-x<3MW`|PYl4p?nTV*G(+Oc!1!i>BLNU5jq`|#A(%o-WVWV5vc6(&@ z?c?bjjdYLvt-%*q!su5k^Dm#oe_OovE!2)3xs83(+Kly^E$|m{b{^+MB28k390?|Z3&&owVHEkJ6geomYsoO*pt}1#~knS zv}1mGL}-_!!g$kg`L&RDD)jExDRbpuutNKJ1A@hX{MF=VJ`BkoU|u6L4^BoD{$o$z z=d>a4C(!=X`-?_|9JLfwfR;<#5QerIPTJ2l|D5%HleN$WRi#EuMn27Ho?(3wn1xld z>N9t}ot(sZ3b?N#CRjkTav7g4&5{a8P6plc9o?T+6wCZ=<`PTQ!s_0o`QDa4>qI>( zB#3v+RTyn>c{iX)dq=Hn5XyOx9T{Z<%}L>hA4ro{hiVlR3*;v4Au&ocR0{1T1q8n| zR{7gz5!1|k@>}8B7VzT=ILH-uIXaK3kLIj;G6$DeMXteblenMG!HEN^AU9SP?~Q^c zkHKj~^zi8iR2L1ZzsDa22+T7O}YN@>|B*t}HR^6>dP5{bJpuAg0L~&2I9d zxuNp5&JVb0#)_bnkqqqMc#7q@ql(n861(w(XabX6oG-~e}Th^dKJ_RplxaD_CxuEkVC@f$@!Rx z{-_WaNY+V?ql#m<|2$H&I^ zsEo!&Ol;gcf_RcGRr|WoCu}Q*EQHuwMmN~@8MCsb>zBW%HEQ~DieC6okrO<5E#&L3 z6q>vu{{@G-bhBPO1TJAGLqJ{28=IKRe)dL#W2(zy7QC;l^f3Kv^kFlJT6&ki#3$_mPFe$;J{zy(f~B7U%1IHv3)jjvI+5 z)$&5qs$ER%M|+jPCe`nhHEt9Z&_aD1pK968r0ENT+fttJIg8%}0QJ#}FTbNQ z`{DnUX2JD1wl!}rX2js?Y_rAeZqVb((*1AQ;sZa1O25me3v)3Yl@w^Z{87&+#pRwu zCNsHG83D(8_QH9r$fD0niH|M&2&9-a%40GL&0yzUI2&WqnJXJU&6g{Wwb6c&FvK}EICvWDur`aqJSd%@;Dx{5dw0In3u8XSY>`G~WC;Jh{hperLZ{)hS3p%) zLez_tWxVU1{rInrSSBw7vkcn_uC|4?{r3~b{S$O$EoUQN-y&CRleF5LEQqBqYKfv6 zTt3}Nd?R)Gz0y;xKH}a;7zD4-tRT%R;Z?CL<;^PNBV<#j9!B|PT2&Xf8a7@zRD21W z?Pz9=Coq<~j%u8oS87Gyd9aRiQ@c@)z|-J9 zHSm8Q#CAlkeK^37!N9_QZOm5uG)pkx;L&Zi#La8W%ltEXtMx43Tyl&=r*x0=HyC&Z#j}_F%Dzlce;9zHPS4^ z!abbgVzeGLOlp-+1Pt>$o%<^~+b2STLn98=ZRqhN?2!O_Pv7m;W%Y0ynKZr>?p)1g zA)AjXUif)f3ZPpx$-@@EAprlSLjs;7)g&?r-1_2J$FpI&QNXsuiU_6C< zAjg2frPE5Y3EfJlvkrwt!=nf@ESC@<nXMx#AeTJeaS$!|h00X~-|X*d~{S>N~Pi`Y}j>sJ|oXE;MPLHOeH0NDBpR zy>hzQNYw}R$irnxHMq~#sG`YU-fiP9G!-PAu!PxuheSrSRk z0PY*cN68M3{(F7c&%~(FX(6VoZfjg+~>wRiiBP z>lC`FtaEp?^~!5BP~^Y~<5BW*xi4)~BTw3LeZbRv-8R_b2MSXF5%lyYX_|Ds8p8yl zDQ|~4Pogu7n#sh-uz*~eS@Q}d5?-o0Mj}zV{&?d}g(=7E{5ukG_VxE^L$#RIQv4~_ zpn-XV9*W_}7c^kE$&Lnb!g=rWH~eLVK_-YkS_ogQ`O$rjr8Ai!DLCO`B7NKpEx~9d zvI!qJCEAB-s?yfN;UFOWuIt>GrGp=x>0AE+%c{+h?k@uezI2&O{gFM>D`^ehB)bJ6|{098AcSiR!pUh^3{~RSl>D1^+c%z4{B%6XynmsNc@a@&ZKC6!R#(rn^>>^ zmP3~1Fs;II%Ij6tMn=p(h}qQ9CQRu1Ohp7nIk2thP|32!6xBy4bmXP8cR)JQ|N6BE zz%BlXpe2s(x#gT*7op=R^CUuDW0k5)ER8I&(1hxHtc?N18&~k(Sp5di@1eK)~<4G{J_QhG>7J%^HT6R(Ry za|>v~P}C~D(pB3~`xTXQiFlodsTyB~nkmjN)0Z%X-)^PT_}fgR_D<|+?1}EYBjQwA z-O^F^fXmyNSulKA_MIg_OuIbKi(V~dJ@avyBP`X>HMxbDZMQYkE)(8Sd(8PdNJWXn z&}JYJzl1OshY=s0T<1+3bFGdhAF`Y#W?|-*rdLj0m6V~9j#L4?=EE(i$`Gii1`VUd ze$)SAjrmLEV(KaWUh%a-zrkuWJHf+8LChUI?7xD;TR2|H3PiMZEG3V^+5_K`>Ml># zYiq-9T!RvfTD8!)Zy`lqYjRo29N6TyKo(v)tH0vA1fI zjLMCmRVpG+&%O_=(&Oa_+U7F&_T`cX`tqcVA~O&(GOLgGF7>L|{Pote90-mA%Beb1 zyrjK^g6%PHy=M6;+c8~=F1K<#qBi%2vJaY)udJUUM-k~Qs>*am6EoT;YLMgw`aqc{ z<5iXSV+#Y*@Ut#>^79fPXU=jZ3yw)O^T8r`d?{8%a2U=;z3!WoxEw^iRf8SdW`Te3 zA^q2Xzs>F5Z$W*X5R(YU-WkcJ68dX|1N~=XlwZM0{;Rt4FeoAbi%<4NZR-M ztKBt2kTt&IOXLeuU8lPABQm<%@rR_9I<(O=-||v30CHI;hFXV@6(>6#Cc|VSVI9J@ zDnS<*?G8*d7O7KbPTY9;0vBt1@y`nke*A0$vTbLFzOsZ8hg!1ul>$I=n3n)GbJ{=s z59|vo(Oi}O-|(EQ?{EW?LvQG-36unBt0*30r`{>0nl?lG7(gvnOSYmU=T$58if~rb zVx;8&K*vHVH-?!Ut&y0tR#x%cu20k@xfubo)ux49szk^mmB}}y$(xN$)ER%=wa~8P z!IUa>Bc-C(*6527wP6QY^@tDJ7Vi=_gSKA7_V5v0g|bQkElud!h!kh zueWJ-^c1#1u`RcF$M}Z~50u()^GHIxPUIzdmfZqc5!8zPO^e?MfdA?t%ppy@|K{BB zI`S}Hm&u>18PwACA=glk|4q7!HE^jp^nHZ-xjxPm-I2Jg2;$Ci|6`@aWg(R!Qy#zd zHphAxX7$829Rb~^uZr7cR*LjE&lJACBVis2EV?p^gNY8~HKD2{HYzB_=MK{E-!Q)} ztkd0lk6!7|agk#4c^fG-?3gE<>!;4+*}^Gmr%?S$i4{9^O-(djBEX+7JNPWUjR!+D zaZxms`{AKx+!0-KkZ-mD36*4Lrc8;H8Lm`L;w0CW&p_cB#tp&h6BCW*Zkdi;+^nTx zp$k?U$bAq2Ka=2@W|OA>l3sJZ@ft}Jdger&jPz|f4eOT6pm_Ci59JlG@06k1)MX1b6f#(;-HAf)?gke@I11O)Q|N4KBQPx3|I+P?fHjG)^{3D`g5Sa$%sbIZlM$@IV6 zJ}J%*MLc1M)XL1;-fo!lvstW81l=&Li|FTcM8#6lEk@;><>YOjnDDl*u4oo?Z~2sL z-OQf7%8`xXPY0RtO1O|qr_MHN$%zfp4}&^iTj!^KnCI-@vbER1$DoG!pjUMt6b`-7 z-|HYAmFm0~_=G|B*xyX*93QMN?@{%NnU?CAF(&MpZ_s1&B`v=pr(TUK@v1WY!wy*m zAFTKmp1x;YXPv`(<*k|~(--!T@8HV%02g|_aqa*COm_hxug3z${kmYMfxxs3Mg#oq zOUUc6$x>JFw+#+_o*j#(w5k$`b1jz$>*lWKLxJ>zh_>k`g2X>n1P*7v!pQMC*AP&A_ zH-n1}PZxOCX{4JM)+38yYA%dD$%IKrUFRaL{l(OiLPD_}#6hn%2;(rdIfU;%nyBkx$xSr~n?j-3t?rDD)V%4dFH} zo3$dfVb%3ewLYPd`dO@$E*lY-4L)Hl=~KtJIU{xU^9t4hix2vViNv18?CgKtL=B~1 z#u>q?dvG&cNp|jEd1&yb(onVv*upZ4K`My*(Ld^mGoabYEE_ijN|U=cru$hzGYq7e z(~uNabu3sJ_mt!}xXLP7C!ATJg0AI0_CfzT+h4{IN-*8)*q~M^TFM_Ms{-)mK^dvO z$Rq>Pe1FZ7xuV78UVpmSdZ446`sA1zRxQVzL*v)NAN3p%QS+5eRScfQ%(E+J{vM}B zWfxm4qgmLH`3rW2z7&#}xi`%;gj zvNwlMC>8xm4YKW4@<`-gUGnrKezUU*275l>wcOUfKCW7v9JRTzxYLcnbc}xT6|h`UiX3iB+BeC<+^FpnP`(Z&k1|Jk!5gIAb4=~ z_AT*0AsMhmK_JnD>0h~VKS=@pip+da57Jl&(l60ivmT#Q2~p;D%tN-J#~p&nsBLUc z%4luUFuGMJu$YOnZRfuREGG<~G^bqpOgKFwxaZ~O4$el!LKW3OHg%}tlTcDarmC1? zhdxbh;TnlFXHl-q7GbP3{5H9@SfqODj8OU0nN(9|39Bz$zEe5~W~TMhyk`P<3r&v4 zEXofo+>%XVy2>#gbzTiKK<@gscp^2Ow%Ar7C7DOPjCNlmo09#OU>u;E5pW;?8f*m! z8E)R{hyJ=};|J6~jM#y^j)G`$h)vtmFGSc+XnQUuBC2wI?yxIP&$2(9n<@}x;I=*x zbnGwlC5BYHvQ8rEdL}%clf_o&9=(+~vlaf@fKjT3=c?gD6W1%5vlt6|Ga{rW#c4B( zO_Whgj#X@f!hRZw`tv})dM@r=ZNGELgyoKvwqsmdKLf5nE3ej9R2A~|R2il^(CaX? z)v zrPftmo3+W*3Z+Di>dp6|>JjDcad`te!)FXj08%?f>Co$ZQfIrW_eQG-^fBE=#-A&- zi0)t`^GhU5?UE^Nk?jTe*3h``F07$zEwbyr6pwE|t_jF$N=$KKwaM=oaze@*m5Qv9 z5t_$$To^~KeO2a-U4*;n5?&r|ir+7HA%3RgYafnq&Dz8&4y(!B+Of$u>Gao=hIfdZ z0e9KkM#TZ%;6oVT$v`u-0OXIqkZ8)bLPm}a{yaV^_SS>#PD!153SmbH36)4V;;nUH zN52S-g*+rmDls1PUg3(iXry!;_9B*ogtY?@>uSfalE6?4Xe#1VS)qJSkzv(RL;g4e zQET#XbA%-*`048|la*i^)U>hzloz$xRs*bguN?Kd#FOmCdXR^3GAs1WZBi7@#0A05 zn3C!q$~)-^DPnEXC!XbWgFN)|At&EjkW^QvtSq6jDG8X zC0kwS`SW8yJe&_cXR~6~VFHl2e6I64$6Tmsy2`6vL`Z6_hI-;qCI=J$uqr8#JfwbTGy1g?~o(-xCY~UJo9iJuT|I-6!{*rgyJy>{w%@ z5br4n_l%LBB!_FM0q_zM2`{)W0ZaUBc7k)M{;2LBq~FI_)j^%C5-CO=@aWyoQwSA^ zW^%gfX&bUy)%g_2El=pnuc565Di>U~{B{QX*Gnk#u=NL$KrMQ|`&GjqeFg1h{AUTt zw|%f8LHA;#w)U_T8@9_xwG*Uk64<~Tk^{ZMl%T^E zh8-xl5Zd*mVPuubtqK>%k_~Q54(6z>3_ntDHMoBc_sFPX>fYAFfzLPlshD;(>9b}g zpB0b?H2}CZB!YK}(eJZ@S=axjvpwh>2@kotDwR;B0ed#-(n)PJBNpuH>?fDWVvF?P zraljB6`5@^$QX9t#8foT4#z6MLs6JaAi}si<^-L3t6hoTG2z`dSH^TIRQ|T~Fm_O5 z20F7z`tWN3p1j}lf3Z6|R1|cW|EDuB2e5yG0ZP84oPhmF_HY^p2~s(+<8YW~FnLbC zH^_2WS2HSqWQD!+C@JOKN;41XJA;5E!K2_|!$w>bsD%sFuJyFQnU^RQC{Xw|)oMr; z?(g#9-e>PITZ@-4Z&C&cp+!fePSm=R=tYw(lxpS&`&6k%9FK`|R7t3Esh_U8I(7cE zKL6?WEq9{boUf(u^>f&TVN+%M);SuJiPeKZRC1EOXkz2UyQC9xhSK&3Kyj51d2sN; zplB8MZYvTntS_&VjB|l=;{~kenxu!geZ0%PA`SUl$R&STy<+10r@>G?T|{&#{B^C_ z#=tj6h(&XpXS8bQ_fRJ}$mBg+%nIP6AOzm^+-;x}xJjC#mOIjRh1~9tkwTdEd1V$f zXAwT)E?T{1(vrs_<(nPOQo~Tr>e7V?dz)QmXbcupZU!$XH5)LSRAc%^g&a^0bE~o0 zP0}U~IcGcuK`;$`3!bJ3D7Y$VR{lE&#FpDz926)B1P{2nDyhX#K1^NnWnmc~MtGd~ z>`+^oqBl3@a}1O*KY#ADzo>F(Tx)l^q&#TRkA6KFefy?rrT~T?Kd6@gc9?%AeMC{B z6lnk->IAE~1Vcw6FJjyfo+V@fbP@_iawh&o8DsUU16DEcTdADY2|rr3RHmc)jgx>S zr&b5Veh{wxw}gAZbTJ=}Yj(>~d2X9^=Y-20nab_ki%B-QC?S-Q69M(hbtx-O^n{rvlR5Ee%qGA_@u!d^0@0-_Kbr)|xx# z-gD30XYYN|c!-z?@Y$CNbqk&gIEaxc#^$3r*Uc}E-1UkhC7m{E_-j9ZZHzUn6Z(Dq zrtML-DNlROG;Z=vP^zWWLA!yDN*ky7wq12r_dK~sq%?;0TedkHl6BfxhjV2A z33n9k!>lSO>`8bV6DL?znk|H?`?S_ne;Td9hqD}u>tHk!FI~Us%$wxH{$VwB$*X#& zRE5m`q;@S%V^)ZW!a8L=;B$voK3cu<=n;%`=N2E);Hcb8nTmyYS2*2xL09CTq; zF!&q9uHQ(1CVMOBK9_DnqN7aQqs<4dX~9JJmnR9bm*oNUb&BBU;epHN@fYCh(;oKj z<*FFt<#fR06Xx^L!1w3Vm-nw^81TQ`g8%S$r*AOi_xIkHbBTA5@Q)5Z5B#NY<(4qf z0Z^O5A7_M>!TWaDY7P@38KT?)tueBPo-Vap&E0vVZcb;BheU>V7PCRqmm~DFq;|%C zZ_+EL#VrBM*3Pi@$iJDTQ3P3DQEZV_P}D^`D>3ne6I zw`G-xuXKhTV!T~OwO{yH4;2cZ+ZC~Gi&wvx9edpoZa8d_cfq1++vIxGCI3CL8q0jEl&+K zS%OqicCf##%S0J(q2!7Fl<42(ukUR^+K=`w7OdT2&o{^qQ|7VSd=s^H$Jhq1SVu>y z89H7&=hMN{puLpKa4}U1p14K8&$m55b-ZNg%K~dg?-{lXZm+thze8=?Aok7IDJmBD z=+1;KBB(ZOR~Cgz%9L9R1e#t7u{z7zzRlfXapsswr!MYPAr*$-eJv7}0k0_+?lDl{ zzl^Ky$^@vIdj-J(f%l%!n9MJK=;_eg>VZ$&T{eh1%Dh+|BzRJX#AHTCh>qcwGNyk| zsPNvEOiO)~XN$oJ^Q)DJ!z*U8mQ0^0eEQ=pp!ryMNY!3q!dNc)y{$4THYd7(_?P-+ zyU6k02W(5|+b~$zezpZNVtD6cH%m#94T10W#Qj`9k71>%PiT}Bynp8&MhdHFWKHoW zWF$^ZSF75v!CO1IJOwf?FPc;$YF(d58+H|njpQ8CJ^Lcm$!>)ur2}o68i4~?fd1H;|jJMG+}@Q6^w-w488seU~uv0 zd=v&CAS*h|2cD}GUJ9LSF-&Dxo{tl6ZnyDDC3%?Mu{@&`9r?{*{5Y0vUK8*d18TM;B&F51qXvITKF|2}M#Xo523m&lS8KZ{jN zV>wu&s@!6E=iZvmGGI2xd8R8oCXy+sxC|2CQ-H@?S)tot5luKRuu6VP{eBz&dTSlCpqU8D~_2?c~2_9Gd|byx@xy>QR*|QEXRW@jo2pYTFRgKI04$*OTFAYX%D%Rj!3o-p9%dD30Dd&U*W+SN-nSDOvLU z^xKh_X%;0RvX8U$UL2!nvg8=QEO0Y6Dy8k zJ*K~b*(iA9CR%AovT>wKk%=m+WJWzo%Qb7sW1TQ+hxZIXH(UMc_A`WYQ*JE0mQL^WK*3C-i(saZ+8fw?cr>YN}{6;u@Ns=pGLo;=E z=l!-2qlHvUwM0ye#<>f=#^lpgnYnLl(vzQH*k4p_{N(w^hUfJeb}j{$yG#XT|03FF z4OgO~yoiZHIum}M%v4g!*fE0Q-{o`}UW9~J-puA^Rp#U*nzfSR<3vpc6@P2!6kP3T z-VSUv)Wz^%PguU(12K*oF~nzrz^4&{Y1TsR|B8D}x!|CtNcjvNyy6QKcLz!c{zCAX zR~q)|Z7lA+jv%C7(~@#P9&&`eD3o>vJrQGQ*m?R`*_MWxI-|j$SlHBwc663e@H^6Z7y{v0wlNqt>c4_r zRsZ+gZh;@%CENno-97$nKc^|i(W&EvO;ji3#klkvY_BRY69%5vC|+QiZF3Dsyd@pB zS8R4UM(v1dan{$dTuyf&EH}u%V=Cscz?!ZL>kbsQ6szZN>Z5&(*42N?tK0yh#d>++bb&RnZ^T^3*D>zpSjF(`#6!hI)5m$*18{u2X zCG#7q?~7%VIb3rL=)Y5Xll`={?Be_1Vh6s3`pE!v#5svuE{aS`E6JY(=^)@ofF#r+;g~A+j4Rmk?U)S} zfc7&sMW%#aN11w}O%3TkMl2^dVs5&@v_TYgS?ILRR9vl%cU&T*37;HF7I~*+Jn}Iu z(S8MHtjJ{12pWP9E5+S88CvK^6aD}7mkX%(aUt)tli~M2s1$1c(Kd^*0Kas+6e5rzLWG!|Hkeh9A1#9^{Pt-HIvr!uqvId?v6&$}F}%WXq3lkmEB zSpWD;E`;iXP&hw#7Z4guqAYuV=|nbBCm8p%;hG)wL**NCo=Nm+zoY{y0Qn1xe5##MaFak8d1LrT}a|V0~+EDJk1-l`SG$la-2WHxOlC$^8MnH;MzYPw* z=6{bHZ-A*Fl>9HkA4LFX#dZT2y{p<35;xr8!%KFO*>okDJ=)DD{H6&Fo0s>wpa5nq zg>JNn$?qRna=0T!%W_yw6_C_~W_uC%EEXqw7-i3b^mu=)uqTyGVyRk3mBB?QhSDqX ze(2Qj-*%w}xCVl=H@Y4 zl)dZ4bzW)$zbfQw3=W0QrH!xlU67NUp#{9O=rDf>ImPsoSI2Ztn`YOqFFVf2yE z*_Q=1Ui#Vw$Ql?mVZk}9MDA|>iOOF7@*1AV0py$lG5`-jfYWjd9kQq`bJm#und2-= zOu!|((_Dr_%&Q*C0!~ZNk5|Z{rt4<+|3y{&%S9AV>|EP5BrR2bW*0lVugdt}MS}+j zK!fezh5N?ihRytz%E5|dPEy;dyLsq56i4N1e3+@Z#x<6To4=61=ww0f`9Z$33qSa0 z1yldF>P5wX9D`o_g3&dI$+j~x_2%Kkf@N?urEsNw5h%D1`jR$+#kL~2Yjr=)aw=&n zC@XUe^)BWp5ciIKsS21hSK~eN~u>opbTg4SJ{2YG7ZQ)RTlf7PMey>4IT`@P3<3jFj(7t@B7jUr!W%@4@>G1Nzc|V%Bh|?z`Zge zM6X93tqH5vWPL5P930R#Yve$_0Q{tqTQauLPb(f?8L~ANgC`Ngmj!4XD35@TF+EIJ*^*2B)%@-x5I2=I|T+& z8>NKAAh(e$ejs(DjD}-vdRmndmmIq1XHoqsxNxpj0sR*Bj_z8b1i?_UsZ!OM)enD= z6ObuEzz|fBfGe1a@GlSj?BLwrZvJ<-pxjM!1i!vzegI!AQ0)^tqQleWN&1*s5i_+T zzaz*?b^x4gt?^d1N?pTCuYu_8`T%0$xw^c*u`d4l32OAaFZ@gqMsP#~)7rCEu9|pc ztft*n5zMWGeP!^_ZWcQ6frFTp zr)21lw_HfS+8m;ah-3@`%j5R!*21qkq>`PWm6mBq;#=kK931>`E;+bX67+}#TDxZ6 zO+t#>abx(JibrqBf7x`8HL6zTU$dH^XyLVRz}N^`fVN=}{-7k^4Er4W8_AEjx|^<=7MVj6@{cF+1N9OXCVp5*9gw{3%YT3xTBEsF^}$kEAqdZmvoYz-5-az0Gh- zlRzp?ptbQ%XJ`fOs3uV~Jt=Fe4h{x!io>}L?l7_c5MCtP&dtLKA%|XbfUy_sHsX*#~Q8G#xj#Z=ajkeDTEwieLs1NYaHa@6AAXs6y;N70WpiZSZ45>#STv(Qhi~U)+ zGjS60HplCg6Y^%zar(982YYv}$27BR_;UBkz@3gRGUp8G+f4Z zd4*h&b~H)6txgJlE$8Q0{FcG@tUD!A#A2%@#e@bxAcJ^A8EGejFdreQ`u4ABnJtpc zGaKoHvF!RCn!!1S=3Rb+eP}Hqh$zZudXBxE#=tG)S^3P|*?-lDv zpH4i>tJqr<`$h)sSZ^)hTIZ9k(<{bOsXUJ(^-&13_D^ihcc@X7#xV5T8Nj{t6>ydJ&DfZVU?-e8U0r)W4sT4*EY;;*ewKBXq@-a1!4vvmYewl z7(P_dXLB@X$Pw4hPi7OIA~if(^T&48kDynV`PS-I&s9I9R~`}XZxlOHGWaN2b_un8 zvaVKL2vr}|d#51w{l*T?w6mochU|#bIqS-V>{M>@c~%X<+`io`suORhE_n)itF=+8 zfOw(u$)kex<1ywOj9wmslpJ2b8$I09XST5Z3&&CUIf91ou&?U%=jD*O|2;?Ur5PhX zL!OoV5HN2bc#HPGE!+GOgsg#5&FgKlSZ>)%7FV5Qiexq$m(%X;{LnjzMZVO1D!np9ZNY67xOoVu$I&Y> zF97uXEBo5$gudHmlZ0tF`Y)E^pS*`e&{jXZf|&fEBVD9@7dXmURQjxuR8pn^U{)j3 z#6CJ-D&9t#Td0eReinRVV7d9p`uG^T!`~yzB!5Mp5s4tj4R=`~>5(5+7STG&1h$U7 zIOXpKT#hfCUw%7SJG09C*7!W|6z1Br!frR@XTN{$k|^8muv7ZZijkzCYup@tbFP8B zL08GAfApEtHxx=QTLfeny>*J9rzkji&P(~?JZo@DoKvDMc%kY{IV@mfZZ3sPB~<+t zh8jDPQ{%VGW?YQ`>1hQz+cZWL)y$1ZDKf7kYXrnsVxSr-)V?a=f5j|vDpd*#q)<-) zi;`5|4=?aTZc#`*FfZYX1VCHDjt7MCJ0Gl9GbXiBiK}(D{s0a)Y=c`_$zy3td_)*G zR#NCTxnsx#5f$%ft#wkB8BF4!5?bB)zxfg`V%dti5)QN5sEML^_ygPj+~l({FC`}Y z0Hx&7qZG#HM+EeM(mN+%8nO;=X&MW#+H zcbD&zEGBwX2kvAWJQ>g z-KBuL_SZO{5H={nA@wU*nmgO5AAa!CtqA!6S}nh`R{<==RUrEy2jj803$ST4P{t1P zeoV90f~}SHz1V(T^q-&P9-z0qv<-bD>*{`D_-tMkIbo(7cXqKdEgGK%fjTW^n`YW4 zOQHsCd6KKV7JQylO#8VAY)}v3n4jzOlD5*dRaU`D+jf+gHY+F)UcF2SYrG@6c6yj^ ztB6WhWZP(5?^`q%GEM&YEi4@-{H@gSmK$X}byfym>M8ONTXZp(x-LZc+3dQ>4GMSJ zExDDS1pI}IWj%V$?F1*0rB@K*Wcs%G9;YYZ=m1i{_JxY=)kO{I*%klGPicS0?^TEX zJINBc(6lC!9A}lzi3(Y`n<(2f#9-4Sbi)o*&_Jo{roXCB9$9cfl4pqrmsG69fYx{1 zeVQ<3(lW0qKE%~e$pWo1$<@Lwx+wbr+(o$QS8tG!fOk!W(RJBph}rJqw$XmMQEem_ z_PR$w2+099CzFb9e8)?rZ9uJukMPyhN)Oog2?V@HyE^c-|5Cdr=|7bTS={G3oTA|gb zdO3g4IP(`;(cYYsM`kVQwRq<)sI#BQumFr}%f_WW)^h^Y#jCB+DHT!;!=2G!uj7=# zFU$R1tx?hZUUY`63||yfQF~#3A{N%sL3(QQvizmS5|wx>o@CtPKPdtAezw}+e`j-d zcL`wM6!l;Cgkx)u`mqNR&C%iaM;Y_KC4jWymHp`0(?{kPY}|niOCirJGSbPmG3B2m z%lVERx871E0AI)jeq1`~Y3nCyf~K->yT_h|o^T6UJ&2vCp0<9~)@LOc@jAS@wII$3 zL^tm^d%j6!Tm`mqF@w(yPT9AJcXeQ`@)l0}24OHV9{)?Vx?gKh>-D@jJT9M3l*Vt5 z&(7-;2hCFHnE-2kVYRocetk+>*0_2hZ-lKGiFqi5+VNKND7}4HaYGZ_?aHVckv>Fy z!~pKo-uO`P(D1lFi$Nowj?gW+cQXd@aDXoe{j|MoXxnwBbyZV z2Mz~8xJO7TL*Z3Q3LqcG0?wKkpqC3RT&zJQZBBSgVf}oiy+rihKQdh=dd8Z)S$;$W z_6MgjmQIM*Vwws%Jvvn#yETfFpx5LaXX;WGz5Q5*Sg`Mmhv!07K0Hrd1&!jL2(60y zSY~Y1zZ;VlDXge?U#HSW$xQWK%pmlHr;qq0g99S}R%?p#mBgT^{gwaQ@q)q(_?y!U1^ZQ9T3WW9nZWPZp@24GqXBdM<*z^kuC=zIp1ALhWv{lLvbHzB z*&?l>wgt>IdnX_;9xlRsiW<8!X$MNtf>Sn*3fdlrmtqnyg{g=MJ!35`#@POGLW~iO zzMq~i%zXxKmAs+t7?w)t?ZRiCaIA}KIlnhl^!8s^ZMI1HZXN1p7|(HSYfBmxhZ+sl zd}v{b##pz7$GjC*?SV5-j>IBS+AXUMZ~egtCRpkTKASL<8LzS)_`6H}utxtjCCFl1 zE!ABEL#aDTAs--?KIMC6e^I|j#9MbZ)|FV)5S9KJc!AG!j>%v4LPz?V!jH-4x_(zr z+XZbJQ9n41kkpWs`b?lpb>K9BR_v!8-wLxAgp%P8x{uZ)!tKML?{2oThf*gj$W4764L zrm86LS)24OB|Nx)^`4URZ3^LkeU!Zq&~I#CIrz>SzsCh8o263!TeZ6WQZrasfjFLD zo;(&eb%>PoCOF3^nW-Zf9Y>^z`A6M*=QJu&RKsL@45yL#4}OK?O$j;sSTl6095H`$ z=9A#N(P@w=I>lxJr&bY$VsU#r&>6oZ7LL%q?dD5Dy<;$O2WTfcRvseKivF0sgvIDA zeDRz0={HsW?rAh&Dr>s$mOwd`k2M{R61+cHc71dS1vLgHQ(8)m(iq1z)~Q}cXkhJ- zx4-z3QmHr?|4|T7wC-f7h*QLuS?#%WS=U1+BS+Au3#QTx|7S`CujvQ@tKV4++};;| zXN0VB$#TGLNINj@KTPcBDnSVWEa0qIVKmx56;lTniA@`ylc>UhOpXtgyVLBz;vQo= zA_UahTcwm%*aK3_3rLoX;ZgC6DuD4`&Ode>5=`?*a&v_FPE^H+o$bj_Zk;Q=4YjMy z+p(T1oV4##+?hr-LKC%yQAs;Wzf2vboG7 z<1IMZQlE`_kvb+cRSHzTS_%*_Om9A}Q8TX!BbZ=ix+5&P;K>-%T%h+*!Ez*Sh0Ptg z;>s$@LD`QwMsoDSUu=&XxnR@oRQfh6z+#_mr+X>J68k>}N@eNc^9I9Y z0R`uV{!~GPVK#65c9z{JWzTCxqS*=OBiZ(s1^-XAmB-J3OP36FmP>BU!k{OELiB@`krwn zDACwm0r>0jjy&ZU=Y^fn3Ux9JF|mL7YM8jt+)aGb(AmpN)}1+k@NWjXmb(97PpCm! zEZ|yD011#V@v49VKXCS7e_;K0n9cXts{vsP3*#Gt_#;~^Zm|Oc$8Dnisuj+*e+E~e zr=GZ$=h(=Vt309D?UWrhc5PY8e?S4h87JoYo%9a$m++Q5sE#G^=ApFZjjYxgQD{nl z6w{?~br1XLe+3o|y4E$vP+KOdj+W?R6h^1Ht=`uHk{hi+f4&ld9S|*&dywm^*(csy z`4V5A-K{sd}yYCnL_xtuO!bwfZ;0@vq1KaI5@pALX2`eqj3&b|$G z$qOibK;ks|<09HUnkuH-sh|x%3Dj?~1TvUJ)TwCa2F}6-6aIrscKbJrX&wkPy6yDI z<5)G`Kj%ENIr}#(eLlB+IdI6ZhacLk(TphOjpTFOum7_LDCXg0Qwl2c)6&M08nxM> zQ!HH-!|x`@@;mOPwBQwB*1&KfXyu`>R?OO^a$*|N8_1WNyeT-ss}iZLlh(E= z#TTq#G2+M0t5BNj#*c<%E947a!$DAT?=)|&shjOQ#+zhwT^*8h^BXRXcRv|D1irYAH5cKcPDhaXkJ*`x2VN zK=P2_f;A6!(0$HO`HTYZNDQlFd+ExR$`s|ul1S+9794g{#Te$ut?#~D0%Y5gl4yie zvE{kF3niG(gZE&MwB$Efj=hU(f}0{0(NvH-P5o@nW)>-3HEwCk6_DG+euG0C9&awx2SNqJc*GbBjTR0>d{Y`R#I3}GbCsi9YaHLg zPkwNnoJgw=&7l4@IulM+hoOYE*HhZIBKn$hMM}2L>9`EO8R*E_f=B%gEQqoyb}^Q( z@etM4@DeJG%SgAPlWA82fcgRt7jv?zyQDf@Cw*L@aT4Zq*noavn;A1t|jTR zJ~_8I)gSaz3++3{@vO;qX4P5#yK2M|B9h+u^UI{?XDUCmrW!cPb}*z#xv@tAQ=vEv z*@xhsQ5$Ymb2220f}y{(zj1p||5^(V^Uuc6gGR$2+UciB{MpS?wKeHXcr#+B;?B3H z4*QAS*sZp7vb>7e(6m;8w(&o|t_7p_+ zE0m!LO=&-2^T*q@BC2&%^5L?|$7&L%6!=aW^y`*$T(f1JdF}^_Q5InZvK;YUJ9SSx zgHOeKtD2y&-Ey$dK(gv#v@WIS$p?G(^MHp0{LcAe=qmlwpCt4xPX~9>YNTh!LO5lo z_R!F{gUu9-%Zn|_??@moSdn8gKaqqDG9lr*YFyK=j@cn(Z)@XwgDGekr4KXR{wKZ$FjK%3^LnXE2dNwdbZ9(9X~ zu7gZh%v$^gVH!NPgLh>qP61oHPPl6`1=O9duYPuW&c*e!;?BYYNJ*zdNWBgo0e$H1(rs3D-&POK6!*Bm~nq_oA)lg;v1fx`r{unHRs8AgD-}U|e>Ek>J z^x$(f<697zaguTH?(OEO=v;BJk(tUgnoyJ8pW{eJB-w?>v~5AWLu~EFH?VQ#E#I0mh?SxtYGts?#Ml7Rl%*eWSlc`p(Mo!%yBkSBVDuRMd7o}zRbVo%jNe9}D z209R7YG>7)-;&p>@z$={Z0K@ho^m8)WnzOL-eCc5v;GTHa4tK~9t3bj*l51| zX7A{UseZ%#o28baB$`UTE-gFFp)G<;h$>f1w89AGyd{tqW=GFj!s?e+Lt^~J`9+D| z*DA)s)70TF$8U@xJjn%Dv+&{Vn~2X#>_onEId~^~)w!tGcV?@Bv=E#t@})GiTw-y1 zrp_%K=JOCbG?suTPOFoc2rdrr?N1-=C)@wfz)@$*n9k-V!`RZvv{dtAx&iZ?{PxTjmdrjMEF0!m_4Rxlm>7(hnKP+dkZBwbs5P0&)@qtm@lh8=#7sY$ zQzkUho(|5bMYVYgVv*K)F48fdqXOon8FBb(ReJGXm|*1ivnNB;f=y3-m#esCBN!8W ziB&VRWTx|T%n+TyuGV1g!zGu&t?j~y`u0DdjTkrB-C9cMzlePdtPdiU-!T8Lr~HIq zEy?29T3-c}INbCJ@nwup6(h1uj-0FZ{F(i0&PoWI(7xV7XP4~2!^G0gzT*>7LS2%A zNfeo41iXn39C4qEzT$TkH~$iGnvtz@K2=?wA+s8#U{-8lMeS)hle<`3!Y-Z?jIoz3 zBNd1E$b$pRtX^~zY}7=H+D0W2V$U;&zLFm*&bv!$_0UJT3CtQ6rb&^+7i)DcF06K? z-YR%C{JQ=KE|hM}G==}^4%yn8=O7ynXTvq#(t^;R8L}x`EsJ+M0kY_C|0#JBwn?BZ z>h~IADPeJbu6Q-^d3r4KBacugL9>z=9PMj4hRMKB+!b?G%*Ink`?uD9vec5#Axso& zp(5-YQFYmn#yhku;r^Z zjoO2%cXzbH!NXi;k`)U-f*)V|=4_mXg|G2;a4)Heba+ zwi3-)-F3}X=ib40NHyH&U-xZvHu>eM`Pg*i`vpU@mdSlAj%YKS+E$iK48iSDNHOAMs`i`3)oy0|MJ z080&7jCZc1E*#CbBV%&m%iOU_h0>9N{ue5|Y)r|G+pQ{YH0;(5fonN&)Vzb*FUrel zh(judj9HW%up^xm-J&zDI&$Z8N-iQQv+9@PNUW8gp^6XcqK7qvg4dmFQHVIzVJ|;tRx4gOH&_l+>Cup^AAZTwHSU(S^)S^w z8qer=FxURE_zgl3d-UQ1d@H=STKX^1zi$I947o7;yO7J^YT|Bbav;T^^F~2E{+Tkv zet4^bbHJCp_&U@*gQz)sUo#9MRsCS@bm%x349;u5V+GKuAa=6BVpp5t@yMjxhuFI+ zPYj&mSly=59rpTaUiYbU&Pd^>Oz?aLsGWM*BO}`ld~OsOQF{C1i;=wAahwk|tud7e z4e7RU)sC@P;!{j+^6;)cc#6Edd~q~2*X81rj@*|%tBl)9ngHq}%{5ai9OG3p`%9zh z!m^}xDT4HR9oYixz*ph?S28kS5!m7KU#kC#OBwj!ll8A|;=(A}OOb9f;yU?r}zH|n_o{JrU9 z)Is>U9=_RecvD039pRxU*eC^Tx$&5cxG}f3ZwoO%+k*oMn8UwzLSZ&I()XIIivRvs zd+a{@!%60>ZyGnLqbi2Rf3kmYpnaNhNoAAHjhc6^DT@s|j7Z)}u9+Iuc@q(fzJlFH zV~=cu12U^CXgI;^)8G6MFGvQ)E)&)UQ(g544JwdSJv!xO?Plu5$2RGO7dOqCeb+R? zqZvngxR>VRosZ1$EeskAk&}O-u4fCUU>{uT1;Vn>m@JkC6gnzIHebhi5_Xp}GR0-? zB=z>e7a`{uNJXhx3FASKpA-R!KiBTtkUa;6egtO0o%?G@h6m3AfP(>6HtN6fi$y`} z=6_8d0L~9aCK?2K+miM(Ul~5>5MrS5FAZu2+E7#Re9%fL(DsT0TCo101u&5tWwPxIy1konxPw^fRu(#>Ad< zsVN^thdJ9!LzC<0`vM1u|I+gu+YKIsNDBr&x>x`$)UTHKU>j3c>!weQ|J`Q;{LtOG z&^o6;el&j8+m@$5!fRxrvm*YhMJC(h^H>BP~v~w23(;!KF3>mZK2)0wlMCWQ` z(w+^s@nZwcH%fNSr9R@i#cepVNhziDBQ2U1K%Gp}iH{HXoJEpeN`=PdD;1+WV2fZW zuR;o<)nK}1K@H&^&W%=c3`ui&c(cr>R=;;tJv#n1dDU?zj!B6MJM?{Q+N7wyq%IoHLh?eddPQm2;T z@v%>vTVZ`=nCVkUywjsJbPuL@ES0LF5WIy{{m?Qa&L&*HIEiyd-uKktOjmOt@8#a4NW(xzFc}1sSs0n5r+mXLG>(bRZ)t~!fD0aa-B+AYdy}3k~N%r zIu@x_lYrxu>aZRC)aqXyhgK=Y+XFh-jtT;7@9%!$t?a!{IWQwg9ePwBX#a0(elpx4 zjO{b6e0iXNcz%L$H(%FXcya+G>$i{uSvmX+{PediL!0**$xFX1`%YGHSwn9xmDz%QF+ zq;o_lzw59P9CbARVBg1O(SyTv_#QfDz>z2XIY#0=MaugRk#(us%3+UfBX6#312RN@ z^4M42mU8mYaKIA9d)*7Xpg{q_ znO#_h*F!w*0_)K_?Nr*~`YH7StEKiN9P?8n2KBpm23lava!0G^J@|1Oj8)JXq$~7GLlf5w zo&H=Kn&mn6(rF&GN^ayt7ik|OX}CK0vIDl^LNloJtcmQF&LKViD-l>po?ysv0KXZ< z=wCAc`JJcCL>}M_MF+C4z(OXQ_uZOM3azMvbEWZ!EyaNh`}LyP*0n4m=wTANE@Yd-Ju5!cG)RlR~&rYd~- zUmT^n%p91r*be+Yg6p>MGga|{yd72|#;%#u;YZ*&=cPa5mKpg5{ zb^)?Vb!bxw3H|I-77z}5x?*Ec2rpVQp_y>qm<9c2ihTyJ@RF%AJpAL(_arU&Eagzw z=a)a$dG$ie&dnNMhg5tdr4n?V%lvG}_KClq@&7W-;D!le89l1?D#EJjHNa#y_ zX*Xp&2*byg(@m;&v|srxPv0xqh3f|sKtDSurE{@#VgHri{lo?J^+@klhXC*XaZJzG zoJy0|USUZzh&Mv#)|D`%Vg)nZ9@fnM2Ca?L&Iu<~5XcGYkvzHGO_(aakpzbnP#Jm&BGJ2kA;<|yBZuQ$7rHCk+wO5;3k9h?ay}5U)asI zV~vWw?~Mg{SYbJR1wU%)gt%cObOMVBV5zm^;p?`+ zcjg}hLoh-2y$JLd3AZ93v#a0Gfjzg<3k1sOefr=x@&G2(<wOwd@};&E?90> zHz4*FiSpM%vSS2(JN)=(KRr}+Yj&ow@vK@LuX9kiMtz7_PJTAV zjH73~da3zIO}A_avzJoIQDU>UKnMZdtgTHYa-F>LlyH17F}6-@Rl%^sp{T3Q@=cpx z0R)XUN3cAzn;vls8*AXAh92^$nx}0PY z9pANf+3q(s%dW%Ef9_G}=QZ{Tr6hZ=6%QRF8Qof(LY3__F?6?C#AlTc{W$j$k-c7-QG+ zw<82*W1!rH50eeT+iDq4J3vA!r!$TT=5O`fKtkOMOO|a$Fp0Q&BeB||X*@nH94VlOzRk1L&@U1-jHSPQqs8_AbK1UguH_|3!_XMdaK`;!AwzCs(Jovj z^^!xBA0v*TSHiVcjatx(LF#vrv93MR_;j^0R@(=e(}wjrr%kio^fRlmCdS8iyKxRK z(M!*{TyuOD3YV5-V1G|U!gQbPF!-*xD{ua4dy0Z{dAaCQ2!VRm8$*R6So%+==f=ma z?{IgP{Zdg^Kp$R6aKXv5VhEHnDn2L#UVTCgS@#nbl!E(?tf^0&0@1>;HkJC4^+Wce z)0?SIo0RXW2_{LP4c4_aM3$4GTonsmO6k}dy; z$|Njh+qY#V9;8NKaXhvxsNI?Sxi-c-&K2o6Zv&pv<^bRc`RjBFC(q0VQu^PNw)rfq zF@p#^%GTr#OI#;9%YyAD<~5S37R&872K%BiZFM{or%YTvRY3ky@ZtcVgCb*8NEFG2 z-Y;Wx<*m9xK7egZe&h^*j~_&Wzqk7pz{%n_)lq#tfeZ5uUlxOpcs5n~TfP_kg?*x@ zx+;&lsWw7-dq?RQqh#KY2Jfut54Cp{rjCc&&}5c;kojyxm7V{a&xWTuB3t!6Jx$}+ zmk&Kt7wN|)s%hO(8h&nFfcS;>jIC14F}WWxg496+EY(ve7$aWx#E!*O4Yv@O#i?`lCS$pI_R6kn^vBN5y|voFOIV1RTL zGP!K0QD6Ga%MN&FLWrpmn0eAF{~b>A*-xf$VZmGUS7G*3ynTp7nj(caSZ0lYO9eK5 zKRl)cD5*y+707h9W(A{fAj4J2bhf{oN7V6$+YP{S!%x6AHz=J%D1<{7@Nl-E+!4$z zwj)XKU?ox3GHWY!it&8EhVGbHvQfK96vbS}HvJ9AY_`n*&1P$vtqoX)=CvIEX|=9z zs++AaMm4^Mr)+3C`j9}kcFtuQmC4w%!bd26`%bmv>xZ|I+;&1xcyH4oC_d41yd+jE9|iii1iJVGH5?wehMZ4dr0}L zty_0WP^?9X#CuP4B8g$KKdp~X$6yU@buO5!4>P0j+F_fea&R)24Jlx2yo{?~+q5DW z2aCFF#}OmCxDCTP^zHeWrzdZ@oJ+1&w2iqlk}f_w#7}?tWEf0=FykCbE5st@oNSc# zZ#bJLWH{T`E{lC;6a(4iO%HXMtDQpd#N2(Qh-%?{AGs`Vrk&{F=VeQZcX`FYo9XZK zVB;A`?52Gl4zqJ7z)#N(h;FsjyyFMO2e2s^B(+x8PtK!2hgQKCN8lwU&M@Y>OkvF_ zonhGD`g9|p%bsAPIh6|-e=R%rtFI1d{Y~DPJo(IAP<@4*5U^_-p@NMd<3zd|*Ys5* zk5gd5J>q&Z8MI=PP}QTjCc&P4-cB z1*E3;%XwHA{EMTCS=HI9CDpX29|yIwNX9RbFVHL%eS${BaQRAT!A6b{Tl6jY#?3Xb z`nCi7nD+es$OZ-cz2of#ju{vvIC)z_Pi+6++57&o0k7ju=$N^|^k}e7?1?5Bt%_+8 zm1>BM*4IC*F~${?!^dm6T}^fL#fL5=BoFi+vq9%Hd(KYf!D-JfkI}(B+H{=um?n^m zTi6x_<^eWeZuL)Bb|B7Xw|xOKl+a}#4bM`=<2ztoO;PG4PE$L}Jp#WSLTUO@Ae_B0 z+grFd1bpv!jjK?)zm3P6bBNMTC#@A_A7GOtF2MYVjX%}WM3@<)e#z+ zNlC%`4XiN!$OldPB};FNTi zv>=^=goH?UcQ;54-Q6jj(%oG{OLs`8N(l%IDj_NeoIQj0^W5(_?>CSy?%&>5t!u6I zPx_d9Wco#^4N+^$9U4Tv?Rumwa_y}3&thj6K}vmp{u4UzpmRxpDdOj!hp^v(_>Nd* zCWmM`;=W)(c&{1KQ1zZ&abSW=xhmO^xIA|W`YeY6*uYZURKW9!*H9rsA^t@RQQeo~ z4F+8RXM5|^9A=LW;B2J-;B0x9C_})53<8*`-FS zLLS~KH50ifkw8yDIEc>a7WX#~=;VQVRrMhdDB^=IWw)brt99&CF2)Id{xPnsdipK0}o&0xpw zC6&!mdPkjQ0=tilo3H(1+2NkXA>%N7sRVGgj{wf*QX%FF5(aZ_Qc3JwNa%ZbAc8^r zYn|Ke+2-x#=485i2+Kx;m3rbSx$F{+34{)5>UfNEHYGM`)sgJnK1EizLk)>vmV2n? z6+w1<9uPrD7vD0UZdYoIp(i3@6_d{9JD^Cx0=T_R6$kGBpmSx8L0u!^Wd?L8J_Gy( zF;$_=ym9E;d#ja*Hu_X&(*OZu=anvpH)xXx(V+kPzrI9!~zsI2Q?&wo-JnD*ftd#Y5rIyiArU zXkIh8h&<&dOr5blUMBp>v&Od)xk-iYS?=lgUC8i~8h)ul&VemA*Er{!Mf%P{F*YK` z=*s?3EK-L${>r-JDTVSDJD*Rh{ci?6iGF-^p>Tbx!4AF7?FDp^3N8!3p1-S|jvZ%h ztQwHz4BJe9L7Z{|;*ZehTYVA?Y^E)!+$ToTTiLTwrDd)dyU%&j1vScCSf?#0T^v&? ze(hVOq}J!@IkOx>G8l_cb`x`+M;eDZeEBK*!`%{c3bJyHmHk>)aw$ZLl|?SM!Yt z&ie7fSO0ZuJ>K=Axb2Nkl|Q)6YU5WC(qb7#%>zz6)`A2f-#X!r*nuo`=zDW|hb|9W z;}EW%I4x@CdjV&0*h77CdLh{#GBD+dAoSCAxa&nt@e%d!@YrlfVyVz~mQYQfv6DnM zbuuqhobp@*FR~G_zOXaU{e9pXdRpLSAZE;s7=8Hg_Gr8DRqh+I>ZKtLfM>hlf%0tC zi!1_J2$dFr1mp>RSn-Q*tq^z#1~@%*7tEM&SYLhsJA0*-*?*vHF@o}J$J0+Gx@GQa z4~^b5@TFzr7JQiLNh zQ)K{2W6@`v!)YQLSMwsSS4!7fw|SU4VeURhsT+t+Q=3LCnKd`Evebk}dLo^U%9Q`^ zsAg_6znDS!0ue1WIklHDzH^lHi>iYL$rqy^la$XXV`tL^ywYu`t?b)pxIIadh@!GM z9~G@v>Dh^u=)^`E4_OgUkqEpgAJ-L1MjnC8vHw_QURgWjc6kZ!nBDn2SNwA#v2utQ z{#-KChk?6lsSQ#cBlZ4p8`6%Fp}PySzN5g()uQL4&>e?g@I#ED4cZ}29s$4t+hEFX z`%_Z}F+NiT4<-bLa(6=Ys|TG;OJaqgY$cj7s**6yrfkewFr7^Y#kw-O zkau%QJ@%kqkPOh-sF;VKI$NzpD;%mSQ~9i$d2Y&~w#G~DDJ=B;n{L}Ii(H|I-m~!n z@TAAk`Vh(Dpa1G?q%fTgx?rz5e!13x>1=KP=xn4t(1~&?QrIxy&PM_c^NgJ!@rF-Z zh^9JjLKcBN{Md%DY|(1Q3nQyDq14{aC)&T~>y&5SsG74yRRGG*r|aeN4u3l2ZZuYc zA6pRi>p=91#cHU=hQF#ahWLjgJF+`yw2;$PBwdT4pLpQ#F%&R(n9-eN%>TvNLVnY( zn2v?t!S|q#Wp3GJ33JiqnGQ&;v)INeu#>zDHuNOf+hYJjkgA4-mWUHRxQU_ zD8=YGet8ixePj;1A^g}o1V`8hboFc7LV*Zud82(Ngno~MW_`cNWKFgNAJzgv)E_{2 z3+1%3+BigzIx#r1Ty0V3z0eWPY{s!#ck}^9WW8xR*_YRLiS5g4eEu8dnE_u{dB2Iy ziKGt2gq-DD%E*2;#<5Qlx~aLv{TI%b@E2zjD#VYY+f1Bh#gp3wF3`Zl?n> zcA`K>shDy`D!1(F3;R_BF>Pyh3Lh_ zvIGmlon?*zT~VOZ%1prlK<=q?3=t)J#}i7d1)9zWq`hFtd3;hfH(8H&F!k0>Bg66#IK(aC^dNlzo!~pUcpGn zLyUOM=ex^^Z1r@_Cn3t8LKSH=DM8p~B}M={R@qw^nG}k%tz(s#QRU>_Hkf2B#~~|~ z>ULlE*d1Vctc)E7WV}gbKd&jy$1_ddSxMu~Bjyz>Z?*m{G4X$FHe;aspI=Z7(LXjD z?ASWpH}B2$ccu45*pPVWCW`oz%-x56Tj$XcJH0xN2>p@J@ zu`DDj6i~ON=^`#>$a}ubIFMA~rlB=rJFu(1tuh_1(CNzC`E0&~Mg5POmkrq)qXu6^ zPjyz_7?A`1lR^z7vKevtl;e)Nga#|1kOvXSsTRIHIRP?ZppRCuGpaB^^}XE*dI$oZ z?b(7Uq|Nlu71*T#NsT*+XmH9yt6|e|`jf>Dlvi%0T2FJeE9}aZsZwp7!g)!@>}0{9 z_Jk#S3=I!fRFnj?U4$Lat2js)vihqZ!LU#r1xO6y+L<}*=)1_+h!90 zY&JQV%?A3(3D|56t)9)m#T(8I7A@3fqX%p@AmRsiqeMRU9Ay{!4PpQ}xJuNM%dlO_ zD@c$e9K_Z@JXi{+s45rPI#jnPEpoMLHPN9z;X>S%U8z~9j1QqVhIrT}u*qyeVIAq@ zoo`pQ?E=qov!+o_Zl6pusYCG;{xz>QZa^laE5QbH8Pj^8&iiw|q`VncmXk$tPn4&E z$2nRwXTM&O*lyml51eb0MOq8%|DxFz(F3cr#wbzG%BzUgv;`efEq_chzZiMt)-vQp ziCj|Ta8ccA*h>SGJU@{lHrqpKwwk{*n<7B7!47s2q)#bcUXD7BFlHq1cl;vqq7sV(^ zR4l7M*}CL>$r5ea?}N3fn8(jU5YIU>NVOUhi=vq#Jf8p}oD8Jmmc{3a??~;Ow1e|l zn;OM-oK94cEC&aYvC*cqhU7BG z`7T%OT4YzuX^OItX$ApdY@mmFK4yQy{fWijVfR9+-(?mBx)TFTy@sJS#JAmq2I+Z!D-0@hkQ|AT0e@AX`9T;A`jX#^o&~p{P}u zZ7}HUiahTCe^fFtX<=8lZUtnv>7+e92EiBW=?^j+$|kpTGjl7#iO;&VkTR-ylzT{< zQZbzWG(Od`m5rfd<^*v2p!x80$b~yz1<(}%xDf6}R3);7{+wdg*9g!42ih+Sx}70; z7WA$CaYMLhS?I^@+{w=3w9hPdlCdTFX;PbFK|XLFxu~C#v5M)KlLLtx9dUDB9aP`> z@M}$;kl$q8)n+E%gQq+PED+b5g{L^QUcOiM;0_RGR7PxbW|ItKg8zEZxjOG?r${rF^7z)JU+63(DS7#17@jtG69STIpY!*bK!vrh45Wj^g4Tg<4D^li1kIMjU&jyhf=z7VR;Oa&=L>1DIi0y3NT zb;@!X8GZTp%Fgs7gh~)4h3!!$l#pNf+;lvb$JNtFU9$U=XaxT}2HEpBOGYH%C=FQTXwNwZo`m5_ z-V=I6N4j$9Iun0;(2fg@fDJU7d;oF5+C{YiUAAjXZX7zg$B-By|C z<5INW)>6Q#{iG}sQ>AsR$MmDkFv*KSsjtrFpPz4s$G#ffqcNT>a}d+pec8@a*rqnT zMm_T7I4QM}^KHILmK|D&ix%bc9l;@#fEHPSK1LSKw^1I9M|Zyco>t>v*X0B<3I ze8U!jE&xCWSos&m2!epR3R~@fUeoX<#w`!;ZLH?c*c5i~3cF>QYQ6!LrD+cp^4s-! zJQ>q)Td#3NgZ@{x%ol}H4nB03+}~A_Jbq4mi53QEHg&${Jn>Bxdl=0IBFZw~Vt6#T zUe(UZjs{}mvJ+dTo#ojV^eRiP?N5l=pmz;fj>yGp4_fwK_guy-IknNokwvg0dFN{P z0q%6XAGGcqXO~W-qYm^3;)^Txbl0|%`OV3z6w#Vi8OkpN&}=x)|DxGA0GbVU6C@bEq7X(|nG5y}TOSX>yjhLa)%liq`Ia^Wj=3(6D>TUKpZyB7)rtWmLWu>$k5u!8- z%)6CSbcWtX=i&X(#uZr!tz_Q%#hG@>vX00{(ZAr;G^it-kUXS<{z|sg>dFnE*(isp z1mp>3LK?+AP^GJw;tFlDryCsAlV6HI1~Cd_v(V1;h3cK#H+u6cZ4!Czi`s&(!w{dX ztUYc|9dLSNB!0TZx%}Ch0zI#`P}bUacvOR>w$9gI4!j%`Gaa@atfLBUIYked`S90f ztNClQ!M;ksW=nwDY|zbR!6ycI`whTmgHA3-iGOXjpYR7VVn z0<{~}qe&TA=r|Or({W3&#Zh=q?HMxmCHod#Ce>LLGRqa;y~}f(nmc0}BqZT_v|%&H zuU$jykjN7J91klnpl_)>2B00SNRT{)pf;N@%x0s!_3GoxYQl3!-8hK1@tw?Wi_I+w zy*9ALh$6rql$WZBe5^i8R>DG2~m;%ZN)%G%0@X_i&^ytUBB6QW-|7sM=f7LLQTq;saQ620UJ+o5I`}i^<9=V>8z>c zjdZ(Tzl<$S_qyI_94%f+Zl)8hKC3T3pDc9|DR#7?t6@keEmXNoV%-9wD}0a_G6gZv zK?am*Z28j^3M&;tw;Zvg)uWGNTHUEpDRdC8nwn+|_Ik@FO<>{yv_RY&1+e#6(}2BPM5CvdLwRzp{sXeq_~fpGfMN^{yqr}-U|Tgu)1XW^RTl>(X0Jh|Okr8ErKG?j5e(T$6O#QV_Aikd-PQO$fMnNxV`WS+DXrvOx8r z>tLa0veOBqELI|hFy--}-ULTm7-!Eb49;cle4~E5f-?K+@M6Z{t5q#0cY@k8GfJKD z*qW20Y%1_lt`?#jg>XH0mBHhT7yHPEcvhswq9&F z;yC~gtN{{~og8~{L1vr(+#!r~2Q#Qc-`~j4C*#`&UWpVgA!>tUPbe6Dn?`s~WCYbW?EszOL*m3W7pG;_&38;vgznh$ng6^?_(~xue z{jW$k)RkO%vjgGZx&GQZPK*}Q&1s}P!FI)jaXITEVm{PXNIBT2Ag`|DUAC&xB~8rE z8fk@&8?)5UKZhI2IS)Kk>s=$QAR%}1H?%#hkipU?k2{znTR!CMpzuFt>@CEDf04~t z(CW4zqY%rr?@uxH3}@!6s%O;1uf)8|AF6TjlzJ344M-8%l6f^H%QeNs$dL!`Ad4!L z;R9vW2vW%?N<$DDZHLjv#!#vimuUTzdbK+ZXr+IE_sPBUyY*XGp&s<)_re5Kvk`im zj1hJF6nXRR$Q!zHWa8ZX8WS@e(lwy*EPt)6jdAhAK7r-Ew88?g1$$0o+qwrTPFsg~ z=dW7JY}VV2x^BA@cFJlAP{ddDD4x8E|I)F9WqPfD3Xx4ZbBJ1h#_I(!PxInbJoCw1 zUqT#49_T{R_;420|C@2 z9!a*69C=G8o{VkGziNyS43yh+cxSrY?^HD>FE9X%4oK7X9trkfZJ`W-&M`QRTdhOO z20(WT*b=V~2iu3@tTi|}p^BPSNKhiF(F>wPsB#Y;`=>+nJwhYNrMbe5WVGnM5TrNu z6QvZs{MJYQ_56BoNqin;P0E0!8B&SoRT97n68{#)jw!&DC#@)xF0bh-qAeHJRL{GR zj%WV8bwqiE14k*dlxysT!BS3C_6_d)%kj$m49lguEDWpVuu3k!BAY#l=Jqi?rNJ5d zoMH_M<;k%A0Uh2*thiIN_!4GRU-QK%5A7NX>ea`=&<5sxUa*+0@Ic_j3;-~}k{#NB z;(Z-xPm#UHcl%S+^ZYUIsy|jQ5dI<-^A4HHvZ>)on-svj{(9W8!0^JMOa#lFD23+4 zh95L^R6ls9ESg641+O-b$(qCPHUZtS``2;ilDe%JHDuJ$V=k~?o7iO6RY=9vLn|GQ z{fwJvSn&?S2%y=5e}5eR4lb`MJ*G(GR=P+cZfH-=vgi22B7jaYp=3IAc~$dB&+dDl zz90yZ`LOeg$;dI#i2%q1!#2HdHTq{B*-{&_XoLRu2hD=Q>cmYSCXv9~v%_XYQ<tIVu-Qt#o; zB=tr;BM9{7qcbL`ei5=-oX82!S58VXXn3Y1ZzQW2kSLILE;VG3SXcS+n>-?<0{8sM ztDzyg{*dbm>n`RC=bHr`J5cVT0m**?8chM>wX6uLA|U9$1NkXkKRwprnQ(dCVxwyk z3F+5TM->O>C(1m)F8iU5&0R#y$z0V@yy29Qdl%T>?PC=f+#8LHHc#+q-oKsM#ngb1 zb@s2!y_%;LDigl5O5{N~g~@F7O5#c1K0bBGN3O$7`9SlDyTiZFHuL^I`CIwJHYD-IfNa~^Bjz+?qvHof|6;d+z*ugq5SkIV*}%waMc zEL94S*%$zsOoz9_Xzd)y&W9{BuODT0rsO zS5&KQwJz7RRrI;FmN?30!okedY}NQz2@cjeyl&d`e&8%>odP?$VScSAHO~*Ht51tV z2--mAwK4d3okaV!AGOIVfn?D~H=B6fPd>pxhmK!pZ_hm-&A|ddKe_>729`*pA_}B_ zQRo+2@~_Z^@|V>9u80h&%6WAva9B!DCcypN+KUBq-8(_Lq4MJ>GNa{lnXI}%X@0ll zJ==q;mq}ggM2^~PMap>p$ZVWYneCObIJealBH4dsw)o3EU8C0{H9W?AsuoROUDU{8 zo9)$@=l&(L*=fG1qu0#8{SC-$QRR~QM>|yilG*k-YAhoB&U?BsQ#B+GhdJMDV8d$l zyinmnWnqsOVr2iWWBnGuNguwzK597d+rB>w4_{%g?OiyWsXxmoOXnBwZ1__|Q!fg_ zQjpB>u=;A6))Sc&7A*0+gU^p%;l&IxPX<(lE~^zc3C*fUhHk&`YoyHDaZn>x#&v1u z_fRO~`GP_ALX6zUNI3E>dts47wea*@dl*(}q*1j%5O`~}VU#%*K|CW_RXBSk7L9)c zJ-zB`91ENWX4Ns}Z77SB{DN=_7JB|)n$4|0+)?|1W)u8q^|;&atTqyDVFM^01-f@Q z1$>N)jXzaw{J>L$tD+hfTu;QnU$__ciV$T5-M?_@ADazDv>u=mVQ0IG*O^e8 z4Yn%$%VvW{`~I=nEE8Rv|7)|+N=wt*BhHq`W&<``jrl5D*uQKxfq!haa#^JzYJi{V z8mc-?LAUYkvcelbXUx{V){D}pUA zV3uhLnzku$8B6GN5nwe-7`7K(Am5N^twO)7;!TMiwyiz(6LsgeW*KtS=BU%=;uTcR zXywwb*$C-!idm$DmAbqL8#gBZ`@C+%*jYfE79D8wonKUG2kg+F&&}>rv4h9shsQq? zi8)}`VIGz|tGZ_JMG1LT!ng~@p6qy^`+8e?8A^%yjxAyX%x0^5u-Q5Rn+?Ls0+}E= ztZ@kZ9BpQ00oPI{#D>a>{pehVG6vQULIzI0DiE;Qpxdy!d`f^~g+~4M>VCriJ;=sj zBrPm0ozI0JjMbG3+FH`ZJx4glnH3N#gQrz@CX2=#tX;+xn_n2yrOf`trO;`A`SN-B z$cy3`^e7<`8Qbd6ZU-qB=d+Vna`<;0_17oko+=vskNxr$JR2jUPrc&$$)<9Se`VHv zrw-2Eh)%}PDh&LfE#z7Xxi}oHpRG(e&EmUhuXsJHn{TxWn(R09l*C&*DnznILY(9( zK|$*E!R!-J$-dlm*Qw(hRv+FtRQGHZKI1!Hn<&5sP>|TfHPInaHwcOb zhd)A%pOQr2Q9c&iRy{T(k>Z|X%qCza7g&+C#BES&=;U~LSEi{H`RA=HJbXsBj7Mbc zlBvif?VRNA+ef@S%E?9c6SzFi%$N1YN4B3iNpBb^HOQ3_@l%DSP1D!snWNe43NQ(d zJI*dMdw0T6z9l2;c=?X);iS#!i9u8ryApxUFc5 zx&OthYsFvKu)Q?_(COFCyY21YgP+t_Pgtdek|2Sg2pybN)hj!!h) zBcd|~6Rc4|ZMNkstwc4Ef7@)4#RK>rgIxuDRYqJz)Qj(Ju-S9w8sRomt5UgMc0)1| z^+_fTRy>d|?L*D+%xg=O8%4>uJ$B1Z=5)x)j~S*CgLy~wCNM$_B9cCn82|hgxyIo@ z(ulRjX{e*gE#-s0RJCSB%v;Jsz|gRsYh|v5?N*<|)spelUCEwnL&>p@x5Xi!rbMq6 znm7^kt^64sY=#ZF?R^~j@JK-Kk}_N>ZPeo|Vd+!&yAs1o83W`g7r zR{*B2dM|Wo1Nk+&vs9`6P0j~PhD|z_SoA{!!ca~VmC&!n$iY*5aLd+LjtsI$)B0)xAi%qVKe)pk({cQ~wXU^E*lK(i4%i*wu0 zjw{qfvV5S~_yL-&{yUUrV-ldq6Noz)lB8Hv-K2=DzFVIChi1dK)%TV%TLNKckMciG zw3D6qXzRtKfuiqI9q`oMO?h;Tf3GdyxjyZn|5)9HyV+axosqZlKG5YcVEi3Ri@k+N z4@7M0^H^!oix@uW@i3r6eo#o~-NVZpbKldVjsjY^z|sc1`e9qZ;MIHj0}lQE;jiw48qhbk@LnPFvL3#Q6@4g-ZLYI9|GQEGB#F1WgV5;O?N&HG^ws}^ zW<^Cp6_!?eQTh81PmVStr&EgTEwCbZ3x9+iEV$m9W5$z{tf;>^yK%ewlLTQ=PifQm zsO+b^s{QhZ$q+-r@R3Rmo!XV&%uEEpFC*Q|7?kz_4b`D(*CsQeyRS3jobsVBTxuv# z?dobkd8-<_S%jXV5uJ|^2zNBmMdmM#3cU0Pl(V12wy3UcXCMMH8~5bE?EfRPMZA2F z*?i3i`ms)4%~yR?&R)wFljpu_j@i)fmX6?+RcGIc=JU?2Zm*#<%S!>}SF%PChc6m+ zR0`Z-8F1uzv=5H5T5`-`Z7&j|9F20msXLQMwL8Bkf59PT9yM$`tk{|qQi8-yMC`fj zi%o8zwoH0(iQY}DEvKezz<^Ep;=eQ-u-kp0*`RkYP@2u~5IQ#r1^52pf=5jc^3TMN z63|+^gBUzVs;1A5{uG~0?Glex=Yqr=vab3#$VWEf@!WpldP&BCB(-t2iusuJB&RHX zR!d*trqa@@3U5?)rpFsh?{7d>G`sX}8ew;~d7e>!HZ`6q7QRXf4sL%`EWu)J0t$f?1z z4iB6h!iSBJNjJ4|7o3L?CjwH)2+J{*RsLBaCRNx0wS1c?<61D>I!*^&cN}dgiB<1l z+fSQ@?d38O@T$cehLg$#L)b^EX9Fng1xZ?wN#LYSmLO>=^6$bs{Ga`09o8s=*LE!5 znv0AU9Y}u0r|-noqs#6uBFrjXc@}ia+|@d06SFGeh(>=!ZJse@x^dY?N$aG4^UaL1 z06g*4XMI)kksyPXOf_N6W6*xdVPd+}^W;(r{+V_yA9Taq;2={?(!UFi86xLj{1(6i6}oaaiz%0&bcG3vmzATpTBq!rUAoYg)$Y zZS3bA-5lziPaJ^ErUA%o!6i>8P%?yO-{&0+^G-BjMXVwQ+GLA55&L}`K*D#Q>Gbr8 zV_DBD;QOIB9jL$)!46mvB!oiy$?j2na=*~_T_yEM5H*4%30?>2oS+Tc7pvgg7Bor3 zRAK4TiqL7USwwV6`A#nQPkLh4J*mxbU}%l~Lb9BszfQl#ydv9F|C$VJ9Z}yDz?xa3 zkG{5a&2Fg5xCOLk2@gTZX2;X06AvM`fh z;ntWF=wU1b{bxQoqlSz%X&o!Pb`12B^jxfd6lGAtouaJixjE>@L7-F!5tTKU zP$~pNqTb_F?Y>oDK`&xTW>Bge*W4olMV#b^ENe-rY4XgaaV8B?fsa|ZEyB=F=%#8@ z@C-(S4be=+9vcuMDbRWHCeX>RQ32ODp~4@pKM;JE4+)13Pgq8}qApt6-;b9m&|lUL zI_d5YeYyjDt2v)_T4%GLv0Czuxt$V9gLY|grmH0fBQM!TX2+YpAZ=Zhozwg-J@1q? zKy_0#2+JRFsf>l#rgS~cMTTgvnybr4meTgi$Ess|nKjKlaS00;41A%*_o>O3@QJV$ zR`?Evk)ygU7ffcmldGEVV3amUyCn7OUqs`_rsz^vFIU$80+rbci)!7_7puiPT6e_O~ST9p8|Hd;m?SwxEBU}Fd(%CxJxC8 z3jbFBcR`_eCLQd&4E-BWZ$|K#`bMWT6DwF(W1gfpJ9yj{bDE5aB#mWfKiF{BtlHPI zPTB{El`g*b4bHDQke&PWn6$uXxhuX&rba3b#jy%gV&yXB))ceB3HQ1%hN&CuB(&$h zHbt|Hu))neSib_NHQAnbxryy(5hR=|8W_op0pw7w{INesBPk{FlP@jnQN|Cl0mn^D zi&@U1bC3(kGhyRO?!9?`GaoA_i1}7GZ!$CUD056&lO^f>{1DL_O{zAeBP@&0kOID% z?439S*R`NmkRk7rFdSA`odFO;vV;5bN)7t7z=hQr*Ep3kKlIa{iVEmh5HsEgcBMd< zaP?&9su|5M+(Z*ZPpaaK9wpe$=3y3v$5gD~AzqF=_Z1&PI6~9pD0p7HbnHgECO5^! zEFhRi@_Cf{OSPJ)YQU)riMrb6T#HePf`@Aw0^(^(^>+SNKf}@FnKFaBvW1qKsb#E6 z<^?N>ae|w$89LJ2$gZ}?1Gn)ZxLqPRN2Q_`+9sEhEEdh7p=xkABpJtEmuo%Uaa9e^ zr5X}RSrEyfu=ch**3>=qHGqG@LHp^f{VsX$0;~P(?KgJh+zEGCfW_I#uMSS>D(`@{ zF3=E)$ST|#xdeItbYM_EU%+R#P<^7v;4`$a12ak-XM6PQGDN=wSM{jx8&nrJZle|* z1`GD&0uoMUY@0+{YjKujqf8m)Cz`XQjnP)iq926w8uPWtSB=#DhpKCSPpgA;9}N?? zm~8dU>6^8IEcXlv3=3kbL$2+I@NiU>n~@IQW@bm3?{`~bXbj|KXGLk1tk?;a39i+v zI-hX7qoV%$RRh$nmPwr_^Zqlchg*4!9?>JArIs)Yx*x;8&?dW}m#w`4W5`Rh5!;y1 znfH~cj^OlPt7KNT}D8&U)V_$sCC7KYr~0?uD$-Xsgc^Uuv&b%s`)g` zBVBK)c7Q>cE0t>9YW;y`v-RpST0TS`eH)>=k9u_&QqToahtX`ys+q*`k`FZ79F%6; z)4n31jqvWo|1#$lEizXj*yasU#!6i;!UiF)2e|_@o8>11OSbHn=^%wh8}H^>X3Vbn zGNPX~)r2oyNY1B2-PmO9MixxTslqYa{~$fiKuX|tGi0MV#Yi^6nqc+hh`H$ z*E4uli}mA1lbKOH7^}J-DCTL7Zz@?ob`ohy_~=FgL2-U1v~dD| z<^UqvcWPKp(z>C$vWTM3laIlVACG6Q<}{btNBVT8oQtsaq-Lacw4!w#oV=Jj@OtSu zSR8G^$Jvq?d%eLuj%>_-rC}{^FM6W-FyND@b9`b7IIf|AbRh%Jo_nDRC6h~i&Pb>J z9VX#tto0)3sr%W^%9~*1Xd^(?ffZ$xKjEl=(rnPT2&36xv3eyqBRY7Q>3?W88ShS_vxlksz1vpsOg`pr|^ z)M7Y)*N&epDaV&j;7R;1nyv3uZOW(Rm4MxT;x(-UI^v~8+E2%H;_Y3@1pe=-0h(?9 zKQvn}*Q-f_0T|8J8n^gBvwg+{Xg0+<)=4K;MJUaNl`VU*F=}>?x@OTKj9{4w^m}Og z56uRx>gx3q`VY<4_Kf06#07p*mPNV`pxLDUq1k3Fb1vHt(VknT@a;*^iU^QSKCAE_ zl-2h60M{mb3Z>cL_OuLPG@C`gnE18JT+y1rzi2kY(!5*S)CARdCT1)l!2`BO(yQ8{ zfjN6tnUSo{J03WK>cMK_i65B`KQ*gBw0DDFvC^Gd%L$6&0wrV52d^C!K~(pS`& z(G0m+-4pn^O?p!Q(I})O;ZMY-HY_M&Tqrn%VHkOYHNC8;is(^0LR!s6ggU7gtNdCr zT5IAo!n0H=3}YjVK+ufN=Y&elIXmyEL#z^^3Fbo1=AgN10lk9`sxw$v_dQY1acoa9 z&(esr)@_=c>d@CTH1D@zyFmCM__q9t3n_l_@9nh8*=SAw*ZUtp!$DYJMXyS4%GgI8 z`tS>8-@2x@ZZc^_&G|5?3n%a*Tfd(N7ckvVs1h8$U5g=+#^WzbpgB|&;m&bbk-vb) zx|s?`v%~yNe@4Z2yU6#d_Lo3y6_U*@A|($$q}0=2< z%e63#7Ff@Q0UFiZG8}ouyIXF?whQN38P3P0yD- zo%;S(GCW&*)_0i)-8lf}J0o8q*9sN7K9vKcx{+E{88470A=nOnesYw>u2g&rNn*#0 zlB5BS$8whCz0saQj+P|>%IX8n_UJLI#>~|xPc8RG_nmC)>Irj5EE#G)eC7%*liJiw zzXvwiw0O>Y=b|0fdi$W-cyfnoRHnErl4a?TM~Z3rUO>)lqFiBt1S@2m)9f^!A@FDI zqfPrT{8gm14=|c-)^?&N<~Eb$SdKNGT)^OUJJ8sJ5VBVXr@3%zHwW}*fu`iXFfhx; zh1Qn>VX+Z9ci5Q?@k)dgz8R5HrOZMb;Xd{!nk9^8OO~S;L0YCGnq_HJES?L|mRnF? zDnyE7m6EIWdcPhVOlA=-jzIZ@Ryyh)$6fV?(b1Bmm&!Hgdol;tdH-A0gHI4_Owb!e zM~g931r2fr(OZT$dgIeoPc!2QV`J#8aOTR^^E`Q2g^r&xok_PXXR(BL4J1sC)2{1Q zmFS}e7ycRK0E^}(>-6*|)RE>sUe>UYm(td+H1JvzLBGmD67A)N?gaqI;EbiQLc{@R zq6N!k*`?-1fNg=OuC9(RfR?$c{Q64?6au@85RocU8xg{_RVFe%^p-t*tekga_7cGq z_Fy+AkJb}@vkM+oso^P4sfiJgADtkoJOB3b1%f0Bo~5aKQfpjfLyx$XSbLLM_E49C zk%lZvlPPZ1CqDeTlms@1Ze;c35W8moSk40UtHuwR6{2G+dcrflPX*%_NQ?6jVq=TQ zbbfp;2M;RYa8%Za&Vg!PMvEpy-`5Gk4Jo1!Jxy>^rq!X!&s%_bIRxx>EEY6-7Hv{(SIJW>o77Ca#I_(Rg;9dN)rpKxVrux6|F; z200Mc<0PZoiy}Kn0u5T{H=`X@Mg2=RBuH)-pULHw^!YpTEYb7XR*>+=m66tpUaikF z$k|~&dM+c_vk|F=W^8=L%RX56`EDofYIxOxPZZOf*B!D!^Ri;}Dc%z;(XCk@EU}jj zgdnr{KJB76=dj$Q%LHsuz-oUun_OrWP5|wYU@^`d8rTL1{$}~v9V?b7t>~#UwVWp# zqLI*mwk(CbvB!~F-md_bZf;Mmx55kBfXvoS;E$@^;15TsqCqf~xhj_-o$c04Ke`^` z5j2f_=9$jFqj|~EcFglz)1+C^5Ru|W> zMSg@*F8N#d<2Ci3{%QULcgoJto&zT)w}+F^TkLNrS2@qZ#hLydMu1pegG$cdFZRci zZn!pC`Nd%(ZnE-Cp|jQ|Zkif_vovsmlF2hyDbxhSY(n9~tk0QCrNxjJB`(MmWK5`> zZ-j;dSc=lw$SO&3xK$y^p0OS}Tb01a9OHf(5Pb%e01lxwI%bucPNTi6?w(#ji|hhL zT)jnGz~!+oOtLA_XNe1kn-e}^cB!l>QQhEQqc$n^*x7gI2TAHrdHiU`Bs$y zfu@<^%E}e+KdkLX1y}hWxed-c?ZT11qq(_4S4W)?;C+IdY>I*Cv8A22_9N0$IeV`8 zdX6t#FOX3)MEc{@HnevCn=Kr5_E9k~4*?ulplf_^YdC|bDW<`%AI$Q5py)(`Srptj%TTd-Zu||9TqjBTo_w?sBP*doj2Q<=Ni%Lajpf-he|cl^dK|$>&25e? zGjD<8JlMvn^kom^!ZWWnvK9ekpWgiXW~tn_ZCsO;({>UBrP=&guioF1R<&3fB_Y6uZ3_~y1i2@~W$aoPaQ77L}>YX8z~<^Q7D zEHgs#*6L?)qs)uKT}*4tM;d#}C(C}D`f!I-Pnhy9?h`ssODhDwGsQ?=o)&YMU@p%_ zdu(+o?xxKa++x0rH0h}}WXAIRyRvfBQHFCXzuHf>#T7hN5m2 zXnKPx;m2Y|d6_p^lO3%?bHS6jK~n zUG5{uZ|!H8P0yi}1FQwguE?wtI&|U!?jwM}$qs_=0GpMC9RENE1%LARhRK82cFMXOyc6SoI)b)>g;mAiPp#@IPa*C&TJ^RI+SVeY3@;_%`j-S z%94k?#wUMb`a?3yQvj2CLzT#ws&=cA z+Amhrdve$&}YTV;BaK?=`5@leJfjw)9Ccf0 zXNPfA+it7TQ_2lKOM5yaqnT>6JErV-H9o3pR!6b^Vcv)L09HS~MGlYtr}u9uxH&{uKl=V) zu|_zsY)&3l33Uir#q%s%?h#3(>?4q`c{V*-(*SY*Dr55;_;DvnS;&z60xpRIN9C1i0X-w?#F5yWY1FT(Q9u$A8JC!6OOoxP z-SMJ!y4nIWi@I1Q!=v_|Tu3smB}ogYCjKPJZq798aM@BQLc(RK*4pnuX5)e%gvo5c zp5b3I8+58sak74p*&h1&lmRju8`y(WM@v zO%eJsB5HXDqyV+80n_w9onf!Y(oR+@((Hmz;KxVH5PDB zJnL%Vy`G}W`i9}e0DH`9fJ_UB@zv!qk52)PO`G1e53*QxM|QJDGKLEr5cMq^-he5F{5SU{+}Pbn|r5* zz6Fcdr)=2>GWtkr88U3-9Md6)Zw5_FaMn!U3eKQm*io&^gR~sPslv0rcvjr@?V*~< zZ$6djl51YCPhud}!_+#gZ#Oa!aQEh^m%kP-esFuM0x*l0pilgd%>ITouW87i~UYJknqWfukG>_{vrdI!VOML=GGAFY&>(w_>r zt>-=eK@oyx?d&a;4ajV+u5B|=nN9Zp%50xE>}B($ox4>w$JvL4Bjy2_?NsTtBtrVO zsnIg3c7_~e>WeDcqWShN)=I=#hg2%>+Nni_+l0qD}sZ`?f-$1#M z;U*x`u!&Z!-$Ls4Va)k41onwRc-m_BUop*mt@3$!!{E&cj4N^(}X*M{ZN zcZR40xEDEG_^Ei;Up$1HbP4v_xqG00x)rg;VM*jjtzqbq9Mh>g>hxh+L16ow$qtVY zOt@`{Ih%(fRyzY^HX(X|%r*p&*~auMTcg;7)ZuNa4U^PiMqgJR!?=4?((H$&!J-= zC&b7(yr<^-(b&tgTge6U2e*pM$Ph&YQLwaG57y4Q)U9gW+}m9r?j?P~5nP=Q3`#K# zzuS=AnAk_+riK83%r=V!kl75qdA2}gwk=4rm(yA}_QaQYFw&AO8dBew{>)C)VDd;n zFAHiZwa8rrZdP{=aF#Fh}z z_!ygOV8h@{EAKs(ax06kp*8sKeFon57x9#=9bnW=C2WL08dI5ngK1td&{OGmoVAYI1QH2K|xNv%KM-0q4`G6~HyJ}|w>yl;Gsd)k+uY7TqsoK@-{L0Fa< zo~j+a{G~jwjquXd4Va+G7L<;m?JV*)P%S_t|_XkR-T~ zl;G8>yd`7ysU41~l56qmM=9*0$ZaPm>own9ZdqLYBO~|TM=~2OjIhHj%{Fyry#!u& z)C2M`H{?v=0Cf~KJ2txOn|Zw?EbSSSpoPL0@fbKzF}_6*7hl}Tc+Z&ARQHK0(=co& zszzkeHVErBPl{{j*%lBojZNXF$KX5cjZVCBVP_SUFMF5)?+fr7USu#gipK^60AD^7 zdU)<9jeX`L_YHcgg9+RtiOPOe@45}`SCD@T4!*zYvm5Y{HgKW_|N;J@C9WkI$`IN4% z2u3K3@tzn>Y?K@YQk(cy*MsT@)no0W7CTffhz*|XIpJe)InF*Dw4E1}sINz@sXUIf zZJYGE+p}QaD~eLqdU7v5li6?zb;HiZvMx9Iw&zq_KPm z4#b`_MD$;>0BumfLDU!7G~m&G4gB(uzJ3fnKhk--RmoJ_RGX!f!kOg&ca_O0Ox|Dg zGKb3|X6aoxIMxKCEg^GIisi`cRDkOAO*i~tNnC`+@S%XxjV^pLOh)sP``5&pmlpy^ zRLm4`omRiSIoMjrpU7;TATk@3fa?*6%%=DHXtOK0a3TKy?w4Vonu`rKhMC~-6Pb-g zzHvf*#y5T(?r66c%z{_X5M|Y%r_kq-%%;v36Vy8=?Ih9{-q#{3dMj*?Bb(xviv2e- z+c7|91G!;<$ZSf}kAlr7GMl#$Xqpyyk}B8=iCz#xDD9!u$IOop{N7bQp!}o>8-Myl zW-EIGBD0A;li4ha?YE4|CBzQ^G8;HRX4_muK);f%t!$HO*7ORLT@ zum_cI6|U!|_L}U>)Q!mza-KhLvie2{DDkA?#-cn8ytD zyrSLGqPpCBKggv*6%wN4RAbRZN0_5S} zm_3l7To=&YUew(IHL(w2{8n=69A~TVNy-Xk+J_&>Y&ZWvX1hp(sj%i^5%1}6Gl&K| z9K0OEsR*M|>{Tk+D4FF^91SM&r=h%c?8FwG#7Y5!!)L+sUn9UPu=OFib5o&iNQqQj z!_Reru&1s1`zlW}oK~hF0&*ZO>Vmyu{s(6P>w*f#j2gH1B*2~J*Qa1oHn;WhM z4lr*I)C*d`dgG}vk&c(B;8laG8&_0u@sT7yOfGt?^wbM>%VdNbdRx(LVe4qa3l+P#i1P}DB--Hw zDYBo%%?cuAbs?KNXno)OU*HRkafDG>_`m z=%X@@cJ9l8?VRw31lS-qd@B{#w-NbziAL5wbb&Gwcgz%IGIOLqFH#OuQsie#=(^L8 zF_{rovA|R4GqD(q;=!$KDu^{pFB~xl3fBYHD77%*z z1ZK+uz-$FHgaDY04+Lg2A>KO}g@Z)Wh<&5j^yE%?r&cCJ2$Yt;T;3E?&U`hXMQgx6u>R!AmXeC}DQ{Y+_oGoG zZIX&Hc;crTo3dc~2f?Z@@`Z^kPtKCOd80kIexMQ*h_>-_P&UXx7PK7!6E#l)0C%i$ zizSA(uUhgvX z?@j6mHVNt;*V)w{jO9lHiS5%)Gy{RzL;)}xNc{N(W*Y$VjlbeJ0A_1?1hZY9pC~qq zUYa&@V^F=D?AMv*joy_q%$HRwJUfX<*+yV(Q$NgZC|`~kP+KI&`x2O3DQwbqOt+s4 zPm4Nh5u!=`p|rx9iVIP#BK|l8WqP(1J)PeeZ}1ptFZgFqD~C!JnUSZbW=Sn%Ius1*KUn?PkEN3&G>L1zrB} zg#Ae4)_5$e0mIgxnBZdgu%9ks1qaDMvI)GWEqeF$G7N0-fb$g@+{b~VtjQL09!|R= zA^K?=lExr@6vh$`F04S?2RzZ`Y8vB=T)7M6WU9^q!=p&#kM)%H2fZ&k(NGU5(n|{W z%X`C6-dSdcC$vIIEIO0C!MB*ARpfV%s#d4+&KGfF!7gFP@rSMcSP?0zs+coQGEKG5 z>x0RyBKYZk-A$@mQA2z!M_^(9Rh+yU9e3ozTx`7aT*AFJT`X=@Us2r3eP9nri~hr0 zV=X$H|Gw?fz77Z;pEue*c(F>s6+Z<-pL2EiR%;st&`bqTg1SqEIdg`B+5a-s$T}(ODM{YOLEwG2M1hMN0@DRFj+Xq& zFgsa)@zi{)+lPf0H;;MyTW&-B)!)EuYHu>jp1^Ek4;5L&7VmDAH(+9OQ`3|bRb!9h z$V_p+V-N%v&8RN2SH_*;-(oBR(#o@aC!K|0FS?x(wcYlU%qly^eD3c{Mh|F<{eU@| z;rO$0k;9k~sNmi0yZG83AWA)o1p%R_Ec)qv#?X1%IAU(o=$CZTUnCZCD!b5RqM3tl z+yi)d(Q=iUcgmIw;8ksr!gE^g-dE=5nsbL>eu(|`JDuOQa9Zbs{G?GW(qP$Acq_cC zVgW`Fx>H$0rEeVMyvl+gEfuon;?j~}6iYroa>0)SXc6wILU?4b0HsjDc!rCbnP`ow6ngQkXL)k^BF>eL)9>uyq z;U24hk#`l`r5O|}0OKh_@F?s@j~F033^+blheS&({vx`q+eO#DSu4+im$j0a6RA29 z=lbbYaUTW*9IwHOYN@cuiyN4w;c!wHAG)g~UJTLV<3W$OWJ$<(k-cj&|r2vz7-MJO;KC*sUer znwDi;mhs6cTbLjdWNF3{>PDZdsuOJ?q>i}BtqBtEO#IHuioXm74Phy0z&L&%#YqOG zL_feUvylT)tazU_oH*n{a@8+8o_bL0y0JnARNy$x;>I)E;T7d$r@3l-5tsdkq$Ycn z3KGgBPMeTOzL|uPcZ8CC=&!Eb*;crnSO}?&-|zGF4^SJY+E})Y9ni|TaubCqt|=^i zVa8(mpl!NP+1r}1g!|RxExiV{cPX)gXW=rjI%AZKI#y06sl;!ZvR+gK&!#4+Led2a zZN;s+>p&Wd`Qu8ZmefMzh}HPU6O8c1%1e>-S~oh{Whnwz(heClS0!Tyl$)X6_4h@P zt&jqC&z2NGyQQ(rLF2Ks2^4kx_ip{!p4%ZkN0A_CZG_$Tg{px-x}af1BNp+|dE# zYPisRW>pz$#lvPy;&+%M>QfK{{uF*_yQ6qWwx(Z$`A^CRk!x~eqVS-R*u^0lrlX>S zl2|zvzEvL(E-iCZ6$hGi9dsk(+$;Lwd|nB&dDm1r7ft#e|Fn`h2N`=ej5JOKkkEkF zxBZ9+JhnvEHwW!PJ>ZpMhW4281_D{`G5zHTs5uM>XpUccfVp}Teb~JoNPsHei(XYA z-`B7YHb(EG_x&b>Eslis(skBd%#E>>3}4JOKW&jnScN2e6F|@oFY7nFqgzqIEDP?p zXGx_+!+X9txSd4ZuH_>0+l;ElnSz;h7b(71d zy>-?rB_gDahg=hHD++#YTeVH>H^MtE2go`a85uG&kD~or;qX3Mb;W|@4Eaa7;`Rip z!26Bbv8QV+``ciZkmu7acJ~&1aeBTAWE%#k6%SwgGrE9r_}MX9B2?LtuzfqlG@x5W z#UmJToIS~u8ji7;oqq#XWpe7w%+?<`)Lh}s=Vp6?JJATsXKxGnH!$0z9P{kgj0}g> zVlp{b!tQO1{EY{t!kG{NU&3pY0AxS$6 z@P8Zq{2Pt7-K1K@Osz#vp}-e`-gc+w5zOYM|6hXHKy{Bc-X|~{s5SHw0JC)fU^Y;_ zwg&~G-4VP}pjs{%G3|Qso)5`06lq*O`!XYi<;-;;H?v6INFRegV~~Y9;ZuLY!nomB z2Mqa20R#gMfj%?0I#!}Gu1dm?2D8BuUO6QXR^;H6jwu#8&yX0csCO)X&5=vDEx?Yz zm``0@v@*O{j-vZic-Pc}-`~XA>WMH%D&^1EZ2T!t?oB-A2LkIrR^m${h_7V7`;G!k z1K6-9z=XZP_f6}{T7CM)=Zwqa2gvM#T?i|2QrorJxPL|=Ank8c=5{y& zJnzW<{j-I8pw=7_u(E|F5z)~uW7e$8i+5ULGaV!nLj0NI1e!$qNRCWNHY>N$!tGp= zQLAt{SQ4Kex>ad*CMbX|dCRmIzkKwaWz;}EdrIHxO~ff1(HLoJ88R8gq=6ayNto&z zJkBf%#DdB`HH*HKH;5hwuFj8Ow#1E&h1+4YZ{JIKhOuSj0`i5r?n&sl!?{8tE3C&2 zx0ShlCCcb}ZMrJd81V8YcwbZMz91395pS3plptfF$BB)M z6B9k61%G{LeN3TK;^+Z_PWzSnv~h+% zgfux-xZNd9Q$PNQoKbRrpc9)L(n^OxNn!898u1qq96ZnJnW2x0*H@)4N3Kr|bW4@dVBWZuROcZ3x>h62wvN`oTQyUK)!m|a;eS*6dygQ7) znffeWzU*vGdwNdKJms0WzB74?q;2I#GhRK6C@f)2xgYDCQK&87sH>JPIjM-0f`U+N ziHkz5T_JgJrg5%;(&%SrL4XqYW-%J1^(^yv+iM()0ZMFtKwR4J!ZG*+j6MZD!4E`G zEx`odPk;Jl>Da~}fNp5lTUtk4n0POCAPF4COvI9pSE2`!1EsBqBEP!@BHC&55_$_e zZOqJ)oP@0D4}#$=tpvohu-?=AKK!aHwDIELxcga$KB=_49QD?lQ#;aqS#yeOzB`5` z%_cb_*w~thR@jb=C}#D3fcdq(d&&idD2+0s8vLYW*!8e}Ut-2`XZkak?TTf*_%Q=q z@qi2D1Hf#LBIHLf8|WH(NdMrWV{bZ=^ofk@b$dc}Ey zx&48+nk4YHw)^7e@49(ZY8!)b@Wv4G;QaX5|GbJT`21;)XZ4l zu!B%?^X!I14uDBkZQh;oj5WJDR zc{U1EjzR>L*j(nr+d&Hoyr=J*0t&!0h}6Dg1&?Q#eS^e`!<>VppeUp2|H`&0aZK0( zw;@R@RD3j``?2GlG967j$Ib_((R_FK(}{Duu<1h;?V$uJTAucJEuY5AT9?$-uY8pTDDW`-?gUxS4K+(Z1-Z ze0p&yw=g>#23hn%B8%B*2`NwUy7}(w5sVq^1`+EhrPv?-8WM*G|Ihyh%qI2)_OYG; z&E)M_oIz_TIA_+(J#Vn+zfQ3mNIhg z_d^mSKRgx~0L=@MNX5^@S_JVwOTq12{s=ryU;(f)9dIB{Fq~W@%vo$Xlj}xCjjJ3Z zAmF}%@A;56gp6WpJAUFtNVO}|H!IDd6Z3X*>kOSU68QwOFTbj!yDXt!JZ1&OS>k zET_P@h)uBMmM(>U76Y$P0*WB*dXIcD^A=vhqFVgSDsf?9N|1{5X!L~{u4 zB@;k6Ufdo&4GEh{s_9=RSmHi{3i}~6RJZ_H`_aAd-N9mc&9>P)LAzvhb{*!2iNrJ0 zE*PD6$9Pui>$!bf5mk0x6&cnnrl=6F;8ciQa1X~N3W5?D%rgdj4p2guQfVixPbe#d7jzNnAOR%3xelI9%~3SJqwU{yfu|0M&Go8kv z@1^3k67FL?zR=PQ7rBF$E14EPv*cI=trhU|HBF97t=uMYbk-VlS6}1ye~ZY(e0g!o zf{kpL7>vz+RzERo|J}>RBx@U2q{X7~!eN0eFmvO+<@_yq>I?Uh4pm`q+TwzXn^8EE z>W>I$T0_fBQ7uXJ6LuQdhse8&^>$?Rj(G)Ib9g)FDY(2Un%Q3-x9#bq#(xcFi~kGE z7Vu#L+)({A#YSN(krrl^A&S_VEsHdCm3<#+b_(} z?ZL4Mtf*T=Nn>KaqB@EFu4h5r^4$3{hZU!oE1RmkJb6jJ&+cq$@~N`WrU3wD(a3Ow z@EB|M6Cs!`M_QE0V!bbc0wxw^r-BPXkIW$tnn3;z0P66R=l|%``5Y2)-}Ss^Fr+M@ z8Bce2PnKU70>n+T+%n`;ij_M$OQAd0F8OEVt zt9dNLz1FKcNasKQcVIUEcOWp^^}m4Gx&gGxyXyK51K zb~=`|heoL|_^j}+hjDPRrwl3J%OCowJz17=YXtIIkHwHfINFWgHm})ty_S|dZgtJK zp4Qst!iuweVEbf-x>4O74{6RJl$4W7!Xa5Bl^|@czQ38z&2;t&{9K30F%`PHaNoA0 ztl-jqvR|LYvE-u)ksNQ)XlIIjztO{fJ!;#yg65yyg-6&Gklvf|`u$A(n~>rW%=TH~ z(ZShsab|AkJ2beEN^tx~1PKXqtZ|NAI19>Ou+84QtB~P^&XHj)Q`rnIQ?BplRQQ*C zJamRk1xLSGb@dejSRaz)fsbGCCEW_ExK*jfkzH3wd|N5IOcGTIG4(coZH3ZHVp*S{ z734{rY&ccllm+hv9efJufTtlO=afj1{fVjkwra!GJmflS?`!d>${5ubm85h1&5F_3 zZ8zwPuzCt!fv?0-_=-t2fb<8z5F8iH+a5k9lTeo(S9fV(i-#uwnf1}<;EZ1p6B(2o z16Bc7Jr0nSTuAIPM=5^QHnANrB>hxy^&-Rckzso4Ml{>F-DCJ!^~W;_PWD|%Jw0#S zdEwM6U1Tj-sqPlrw5VjXbBq?4;r|Tl$Hd4l^#uw9l`65{*X*u~aWF2I$_PzfpA5&a z?ROJY(^*sRT!*|mmbnj#T@o(e`K=G0B|oMGJ|!MYFp;+3cdUe5DO;F_c#qjeEG8HsIRBn{OO|% z0uEfbF&Tnd-Hip`^40L_rh>N!nj;k0?FSMNMbWPZ+ap#>SA^^>|6ciD1+&%t$6z*n z{GU1yHL(kMOC7`u`$l$@5X`VSDM{`h=tSB@n1<~qU73EBE(cY9Q@kp zo<8xVLrWi0LcpJ!XYD|=Kt1@`;rX-3{g7l<7AJo+$T?S`Z=LC_(VP>z(#8;%3QepL zX-TFMv_(4Q3IhviJt6N6er-u#$zb+Ul)9^u9VY!E=c{qfrH|~;lvD#T_R3_=U9aP% zsqccgmpHYiZS!!FEGyXbEyJucmV3hXOT+uEjLNgIqt=8mHJDYSDJi6a?dC*NGZpD_ zMDQkC`Onl!s!}A(Nx$`ewW4s4o&KgYIGI=tgS%JM!pd%oMY5eCiy029$Q8AV5bdjx)+J(N#6Y;B zkGb$XbS7EWS7LRVt5ykwI`ItStwV~xZxht@)&d!HxZN3l*OV^SRAj)+w+p$YGg+r4 zP*{wiRg;Sol&B8Cvn|u$msA>!z0tSC8#o;!_hzq?WW&tPk|XLu>8h1$K~6g{B}-rH z6`~uRYkdvm&48fWU%KFVYHy-OT@%53*?cl2r%+e2=zXsx`f zaEyVkNp>;wmHqQlpopckgGJe+iv>T9XURHNmZ(8(%PM&H12Ni|?auUxLzf!AYVaa; z63(Q%r<1$!0S)|giQIW}Ca!75r~M?|FC=MEm}07iAH!l=)d^?SFD@u&v|9Ln*lda$ zbwypDaG`LISG)jiQT_Eln==^=YtQ7lu2<~1>YvL0GSm4LwA=Pq{gG1$$Um7;J9oYU zZp?B}MdUZhdR{>7xMI2;`&&aC7w3q|?KR7Y^nyG+Cw4J+Gk!TldscNLL2PCPrBlPe zMSSYi!f5@3A~of`lG*H5Wk^sxlWa{1VnY*KJHN{@6g2=tJYvjenTjiA(BnuDpf;-ekHKs`{~pZd{BOW)C;uaut?FOFY`zwc zupRrJhoOH4voQ#ofM#HEkZ)Erz;%+4^q*Qx#I@@WfJh?jcUt6-A3;?vn%bZ#MbHZo zH@2wh{l;%qq2s!e)9fvLVgmYCW?k~zH0=$u-N8PIwkjnY{;S1zv^Krb%m|yWE@`In z)#6QzJt~rg1VkX)(poE)kdsuT?npu}I$;Tt6_PudlHA5DD^eR?F zuWX@ju0X9AwzvCa-3Tmd<8ihZ@-oMP584v}bYlaaX}(Cs@eZJC0T8tigRfkK zwK^f91W6&$nezRr?*KQ{LiVCuPwX68RHI%7*_E~BX2sf;K)`NhOyKG;%Y$U^-N@EJ zucvGyIfZjwIQww!o#lp@h>49Sw~)V5Ic6LAkGRbExAJ|HG~YGcISaAo)nC?y)3efM zHseEGYIdC`;(z&!DqXlAIh0d+aJ$?hlrX0?)~6nN;qlW76G$%HqK_c#ybLvvOy!mI zTer5r^N+)-uNm<|jb$6zSA+-1(W!8@*>+gk%2m4$)VPlX2`+7*7yo>S2R+jP$2eP9 z0xWkL&<8KoKQLw1pa|WbEj|ejKK$t?1QXRAHESoss7o}4TS2Aoj6ahwI~Tdb+N)@* z`qm3h-`m^=bGr|(W8=YE&lq>!j=~d{7uE_sq{0kgI;5c^)}(cu^MQV}TVMPqF_ZW! zh!f*pF0B0heR$~DPl4UB#9T4LnQ-oT+oUgHv4WV3O;EGkjN^g}G4P*Tz&s61JcHT74IX8> zK)?6D2D2H84z2$iFdOebg4upNgV{FzPrz)F0GLhn?_f4g0L*ryJ%Kis5y`64jxZO( zq2PymoG=geKox!`YS{CK(g>9O163APRBYfksglq= z?T9SbQPp=)qIr{YYS?Aa(Xv5;%$SV3qjNjmV)2zyKPA@+tmxf89563Q*UVDfXKYso z%cEPeA<{}$ZnyGu1Jg(V0G_kwXshSLqqkIUuRp#$ANCPSzzxTK}R|QjFt{{}M2uP;+=+h6*;6f4ydXpP2zBYg= z)FlFi8=&##1Jz61N(rU;3oUEZ%8@DpTgJ*W*ZY1E=7{Sx#lkd2mx?v{muySnm~Yes zR3B30>QAc5sPWl1^6X+?Ak=nzELB$Ej7pqZ{C(^}O^9g@g zUX1uywy9FT3xtErfySd)|I>#YTtlc$nMNL5i2LJ?}8B%{xV0M%-9?O;K##pw4cjN(lyxnsIG;+%>EoaFpK*XR17jm zr#-iQN`*9 z5!ZMH_*8=zaH}qJLt|tuvbkzAT-?i{_7}Z{gUMNNoS2OiWu1akp+9oUE%y|nT!K6v zmMA#7VGgE1pNSyItg41l4F6zzv^jYDJ3&lEjZo$u*K&fbWqW3J@%sUx;fhswBWHAT zdf)mmcbA>@VcAC(GHHV0%)WAsTsnbLF9bR0;zHqzp{McB5wN4*J$%ouh5jl~gx`I^ zKpzNzp*#x~O+d>Ac($Oz1>$4U(l!d2NT@aT!oU)s2^T4m5XNU)56hev6^h%+qy&m; zjW*O>rN7|~vmW;Den3#@sZ{jmSKV(OEco@qT&)i8Ly~e)Ho2u%(J&0}=82+!AcfZJ z8d5()V;96GL?zLvj~_dCZaY(}Y-r+bR@Q#4*tCit#JK-B&cbu%8x#9Z)iq5%@KUqG z&%|d?iX&9rkpK0K?GU{1Q37Lqt29<%yjEXPCsJ(mK1;_gd+sPmC9^RD#&&!3=%NYG ze?7n|$w2np1}sN79QmORG*4F`@%HY<-R0Lzv~tz@*IZ@JwKS9+QTT~p%U_sHxqo?$ zn$HU(CT2ppCu0jJH!#!DuTd5t*CpOwjG35h%)GleyWenMV)V2n(P@=jDvA2Ow2x9o z?@vB$QkI;h!;mBv34?cg^fP5_1_qIpaKXk*EciSYDLcPQ<>-sD(k08~-az8(8wLH! zL9Q#w)}Zo^LD+s%lk1#(>5Jk^8l7OGf!fIzwjQ#8gV-FzPZ|TwRp+cR&RGg8zV~I$ zl*%KdPHmv7*angiGCM@Y)0J?;E5`M7)!h|B8rrmmKMSU>QGtFinpC{)8V0ALDO#3< z@Td{)o{JcXHx&wv`tc!ROfb^Yn$opRWTVlf_3axB2g;HU9s$eFsZ#Oowp)Z_-`@6>CquF+-f9Jgq?Q=F_`Jz<7fotxNVR;2^ye)Q zX?2X30qiCf|Ls!(%J>i~i?54I{m9e9zeFVX68WzFSuRrvehO4wgm=TmS*NnZdL>|} z-{Fg4rzmrWYZDK;!N^cvmXQ@S5PkGNqTaM0AGn6(IcmpBesZZMt60-d4ZQLbIcejzt(5}8f)QO9Flb_3TWt$Uf2LKU z3AQE%*g4_T-nbv6Sbv)6hvvm3p6tRYzmw>K(p|&j6fm8${!wNZ~>4JKczE#dvc4~?f1X1=t0&n zNWxh}xtNtXbW!o59`T_40&OL7ucai`G%i^|+7Edw@LH1-pLsCWF_AY1w*!f*pfKJk zAR^txN=Gq`>oWtgr5zSChZJ)s&khAWQt5Y)?@9+-%w$HP(`Th*?r|xbl}?7;p22Cpm_I8eehfY|I!&+ zjWy~r7K{|L&=1DS%kvd3hUpk3(+Y8sn!${?xtt+B#2>~VTFc{IOx)rfQ2R9_U!iTj zYnFIhDvUa$o=AIXr%aNQ>)kb-)H{e#^g@;Y>l>9?7Y+OogrkgdJu)0kyU-(^Qph7)wbQ^RX}!)vD_DBpGb8CL^qtq9$eD(eMf@y5bTs?181o z#&B?suACJYf-XR)ZFOSMUBM*ZOQ zelK46&TZpz-xhBMi)ov0c%+!D2p{DYu}u-ey;2P~Oo{4)iz*$tJ)puKA$R@gKE0jK zGJX3hgHjMCI((*C&qxC$#k@+8>(n^b&xsfBR{aa*>^-uIod00Kml1?0*HTGazLLJ> z%As^qoxAj5J~$LlXfxiGTC~M+I~Nc$T_fQ7P=j&v4s`B-gylT4_vZ{~Mhege&8$!u z%K1FS6aG5^@Otr_)V>3O-dh@)4@d`5>_I9op*SS?z!|y1)pX`?r&(0Cf*_+Z6Sb9o zF^QN?3^eBKdGN?ZRK`T-feysbEzRc#- zBm69MBLXepWs2$0ch`vzh}viSG5$a0z@tVnU$!Tz9uAQqExYe3`#TXtrBr zdUzaz;y5zab%=TxdU-^npc9yFg;~&1LSKpgwZC&ZMLBuA&(=?SR*^%wFAcVE0OGyd zRGQ{h`{ywMk7nU<%HTg0lKr<8Ls1mF)=JB`m+>H?SA0 zg|G2A@P$`M#P_IEA6ZbU4|Hc{sqd6euxW#&AZ`n+CUADch>u!D59V zOLh|H|7K$KRa-!+fE{YHo|eQ_xUn(vEwswBC>^FUGzg&xk zYLwl~YtGfbv|M-yUrG5viyk>$cqs&G8L+x6kij!87{%Qw&l`geUKa1J zX-cOF;2+KmR`gvo-vmg4tUBJ(!K* zzXG$>Nf_u(Gqru(Jaw!y0a)-W- z?QS$3kGP7}uXQqU3Yim~tp6n(_!gJx7=6evevasLN~xD7r;ZWhu1ZA3fNvhv(55d$(WU-XCp|XwyzduFQ>|554TM}o;*82_D3T_0uV*?H$axsu zATzqvd3iBReOHVwWhaQbaCeE2RD9RXI4-~%gzHZ}VtL$BIo?aNs)=~fs1Z-f!lB-- zE}Ym#2WUz zIz-8M`9p|-GMATixb@wmwvvwpT)?60*zrPn>*3FRO|_YA)dKkHRr~E*n$Zq=%QvPG@Wz;?4Ehe_tP8rom7KA-lCpcl_KzhI8)r8IT3i=l zlqX%L9R3bw>shXS_Va1`QNGon4T_Ch^*tZeNtr+&_tmJ!|HfqryuN7h0&#-uBG@na z5G{pDQd)p)o1)+AyjF|ohKk*2%hza6F^0X+Yt)UVvUd=UA)7dn@F$ZcRgAt=2Vb=c zs*fr~4)itK2(nDD?sVef&zB1o(n)R_-)AGO#`WM045)VrB20d|y6c4&S_FC)(wlVk zMOIsijhUkQMx{1f6z5s0?vf?b@{ULy50^2-l*H&BD9FY%&GP5eK_H;&=-*Gyp&|R( z%LBghkT*X3VEhxHvjd1;KUhErn1Y6-fO;)9c)3ICQ?=HA?WXex3@ajwTYO+nG795J z*o10pZ)cikrQKPWQ)?|MWf*s^AHNT!|ECx1Z}v}=m^_+wUyd-i5eox*6{V|5K} zEZ^-V=1!kHG)iU#UylD?akpEbA|1Z6PvlStR)>>5L32R5xPnva$j$Oa;p*P8_2IZu z$!8Ik|E<`4j9bIUOVbdFRbCt>c_hsNK}kq`DiS7Tu{*~ur=%i5kj#~DP5@aUN$`C^ zgFT}!^R+YL6OwZTw&nc!+rHgA3~Q)7-)016FF`+l>d*7vfKmMbqYbZS$4;GgT189? zp{9kz%>i4sxr-HZJ=-dE8#Gse+IaG{V+G?oi7_rQb|@`W2MfQQqa#y>TMDtDNn<64 zF_PkZ5KMOO;?WEIqCysbzi%k$*S|#P8`yGnSslYaFA(PT=Eh;T_7FGKY*Y^2kNwJ& z8BQEj!oX)?0I*orbK!mF(N)9%CPEG&CxI87~z&yWgdTsI`OCfTiW6~t9PKs zXwTIr1)|3-2oz#{UpzlWuk8|^szU}7K8Mc`jGTzDHl(JhTRaC_93MZWNIf}?mVEtrW zB4BrWi$F0lU!(|sBO!7oGG8vBWaJUTa!RAeJ!%7Od89OmqJ;oFJLJkGUJkW3Rb_Ek zCGoGkNvKj_$1u*Rj91HaF`sjv>W$RqV4fF?j986wp0}?;Rt4N7-`*WZtf9UJdx{JC z>j9770}u?Z)&7bQkKVl~3`#77HW%?Mk)$ij5EaT!hy2|%+5oB2~&VR z??Z1byMgc0u>tX4wPZ9fopFP1wx_V+kR?b0hWjq6L57hh&s^vRY>@~Snsx=9xnY*w zY;GvASSDDpjN2;+Rjkl4%GsdO&@ILCD6T1`faLeYiLIo$r%p;Jrr0Wj{F*W?^7Y$6 zxi1p>8u6s&h?bVw)*h_CjtwCzjMA+q-yOI8ta6Gf3`{ViP>nBbF@}h16)~&icMi5I zJ08W>oUo}NMeh{4StiOfToC^`)r#zgnayn|V(`ykw(@@fvwiq6^{C$i?MGq~cu!Ej z7%;DO*1Gh}er}-tyh;v4#ETSx-3x_+Gi8PHP~Ntn{sM`C*vn5O^a+sF`~_wc`dHjO3jrjjdFq;7a&htZcf1W94#|*THjYdC!Np0()RZ#8O1Hc;?+>Ir|UBKBwXLfpe zG5l<7pmY~kSn=di9tt$UhK}*`8_DWo!7`OKbtscZ;L8@YVX3CYb2c zy;_QZ*q`jTdKaGgwdYpJ0uIR#IHkIE?&S=rZ!cW0`&KQ0i?AE zpF_UMVehY&hl9`m3}&~RW2jkUavV7ixd(wv(RY~IC7}X7EcA~VRxD1Q79E5>-u}WdF>-I9z<78IXG%7 z&m?Y*4@0{Gxj-aum#)gSV)|LS-(xPFoO{AM^+>j=an1V675HmDjrg^D4_{FMw$y+- z28U}3#tS=6Jg6Os_A(;fukq(A!nD*!7%{PU$E+ud%$$rCl;eq>$Wq>-J`o&hK>{rj z%86XDYJR8@DBs_hEl!M<%+Zxf42>jl3|g!4Dqb--b%L_XfFENdjo-tb+9ew~p`zxG z!YS9q*8;F5UeTb^yYJ#dJ|u}VIWvowxMH^GtNuTGvX$MD`oj62_afVCf>};j%kbJ0 zTRAZlS9q|B^4G;k&s!(%TZcZcxbY;6*D#@n@)9m4YI#^zEIM)Lg^EliX8OVqa}W!E z(nr<$6jV@)`P(e|*Ed}z=CBFNtirXd#kZN3%!u0afm-;|NmeON9mhQP7i~y-?#;2` zHr0BYV;{>kJ(qiJ+ylr^MQz~u=I(W@80AtBZ=w)b_=`e-_U9;jUTuJ-Br=&=aj1sz}FOV2~M$7xi+lX(-Om<{N}y5{#fRaMC2-eqeQ5C z+o_NgB3N5>&(pXzgLV2T?|TwaHL39p5qbUKSt-xG*(*M{{8A3%9TDvEmu+)#gtRxe z9Sv2im8L$W6ZbPJtQPd28*Mm%i;A}p?#NZ~E$dtG-Ha*7x9fai2Jfilyq!9$)Cr7f zjgMVud6$Vj2`^rOM7MbxUfV?$pmqt+`r7ctU+jLaLy5X)H4ZE&3%!Je!8f6Y2Oq9NK_f8&7ujY>1dC1f24HIabAVPn!h_ zSr_3$mA5xO_nX0P>7m)MnZSV^6jn_$cUJ_m=w<5u5FUHJTQi5>o0C4pALnw{fBuG~ zbX7;YnQ1=RuKWB)A$}jpvl^l+zuLS;GR9^6!Ut5AV5Ht8aPXt@g?Sc!Y%{RG*B*b0 zOg%LIy!i~%pfUyD(ZYwiHheH7+|cg+Eup+#?r(#VwLcLsUa!F0qIS;VEgg(k-ju&= zI4NkF#A^=}$%SJRoidE%F|8)G8^Z=C$o+Goy=CJMm-w(iDt;iV|+A7WxJ@e*11JSoMYhO_P-^w zc>rWK!T%jH8~gc>|B}r18VIMLd7q1up6<7xDm-GCp2P1+gAQv(P+J9f;_^fIZ9%B6 zKphwl`&mk=1^Rs;W=SWepaRP;BNR;)Nw&aZ?qFS=wi)Yg))3JN8?pK9+2qjGC`iVa znPtyZ%-SLoW77&v2xHj*d7N{Eb@{`7{E!ikTP4BSXq#+8t!2OGdtt#(qgz`zmxq#d zVv7rDxR|h5{A4=9^{7+ji4IAsEI)&kEbiUa)Qls1Y8s9mj!*g+bnHKM6;_I`Z_W~q z6cYy!`$Gv=coN4;7|S)GAYAZz_nNyNM+r-BW!qRg9_@?~7aaspkEQ`#DQItU9HpN- zxW55?K8j%vaZooLL=`$rW}K{?3Mp6rha2z{j!>s+d$CAz#gML?V-4u5NJsLJmOt|E znI=3wzA5IM7a>0(H>o=w>R7|HgqINF0mDe@78u7>l)>NhF zl+(?pQGMl0glw@+jKp&ZNnJB1ilr#cXR0@1d*5}bpL=(++8m*XqJJn5wu=r{r+p< zk6ID%OBXQ9+8)rjtI9^F7B1WsQA@4errLvpL;w zF?4mm)G`(fsrsprW0s!kz)dH!&=1&nk!{71=j=5V&%#_JN$6LE^@IFEZXWL6#XtNp z2tRBSc=-9Q^WmqU{qqwm;O2Y(!=Kmb3LyZlt@Ghe&&IPp5 zt^5B)+*?M~9W8mS0xE|a+xVr@j1V4lXP0%?9a=Y)H z>FMrSYu%rgTG^k}8|9Y29~ z$=*M!a;QQ-2Nhi4nJ+lIjSlzypa{7w@H`p{3EaCu6f3*m?MUI9DDS^^-b$iWW0{q@ zbXtIkv{$l;r7lC92y6enM~Q1JmL6;!Z;*){_}*3|k~EKTfI{AK%J058tISvB7lwfv zYomJZ&FYxM7sdS&xQBUxQ?x&-s*&u0w_;FGn|K*$u@F4(TG>refIgmF(3^VR3PGlG z=a?)-AFf1gJa6ZOO-9z;F_D7AB9tn2x{ig)PF)+PW>8BNRALXoJ0CdYmDATo3audq0bs@JHPB1(`kF!6YlYGjjm(Q%0v_QFhh&9 zT%*bukQ$%6rGqyrmGo|#YfER3(Zw~&yd`t*9axOJq)i!8$LN0i;ICX=ad^ka*ET!5 z0)MAv+7ZEcpe<8ri^1+nV~2>U@B)^8CBC`)JBTP7x@mM(U$O-#@;8WnZ@HC;~g<7 zUNElnH~Ik#nm^4j6ur}iMYCni~yow_6>iCPY#G> zaFDF`KfMh75>yYxZO+8fP@CFaPKb)Yf#J`-7LrIU)W=FbKFQELnV3vKS{OfY@>)^2 z>qoNiy>~cBC6V*`>4e#UpR{3;PKj+0RhkTa!j$vfMX9VMZ?%C-E4Kjkk(5;ni_ihb zEX){M2o28yjNN$mpZf%+xVEA~j3_MIxsWI&ZsR_k)*pm=M%p;i($LC?(2PK*${G$% zo(zCW{R9(XofXPRDg>T;owPVW%3OC>t}x^jG&RexGGBco3^|P>7x5Bqy4nUqQpKKU z7KpE-cZRcyz>W>tUJ@(<`XsnOQzbKs;3;fpJTagFj3J3u`RQoF zM4qI|L>}E3%6`zueW*_oUNMqOSI*pT+w0`PLRV}lCjeDd#LyJ*17)aa^$&SI98;z73+vV!UA+5c9iEKMB6<*$N1@zAA2~8)505NvuksAh@{W0-lW86%;om zBL7=quorFZ<)iuN`TQ^=y54>N8Y-mn@3=5|E5xdEqA?GIxw5pyr5zMi>1%fTd{ecG zkaXyGk>TaXiA_X%m<->PwocGKRAo|&@0wVC^wd7#86vC3drj6_%z>gmuXr8%y0csS zFqp0oxYm6d1L81+Ya!cAPat#{Kx;8>dCoZt0%ITE^9A0cXyV09-&Orto?v_}$9$b4 zr|6wS^El%`nEWYtBpde)k7tS+2}Q&Ze%{Sz++=qG_Bw&oTDJNBh|H#&r9J5)0|}Zg zCBHW7yc!CB!2_WKdAT9n^PYvdK*Ndei7mbOvccvC^>W@EQLs6R@uP)O@(W^bXj`bx zoWhX8j%X1`?IOA;XX4~Tz?EncMcYYw3m2FLUcxY?s}ic)UDaU%i}o^7NODwA-dSL{ zFEUV+bzk$Ll$SXkuCk663-Buh271bCyG*m0CcE#w2i2}Y!a@w}9E0KGe{fOQhTC%4 zVWE^HHw+{%_`jP${6d0gDVbSKTxp$E!mapbrfn$UIUUYjl>t;}IVp?a)Ak&QQN3M$A zbVck5D`U6W;^IeZMxH7t^XS#uGjf}1fB{dvYYk$Js`R4RL({hiK?Zt#D7Oj4Ny)l% zqx#VDZI#K1feLl|rW_4Y2VI6%4}24J46hr;=JhhggsIPO--WdE&wr_k3L-sT?R%Z{ z!TcV^Y6I;~ws*7J0^06C!sWSsLJnXi-M`iU`C;VcAU> zL#^X`KmQ+)+1Q`SY&js9XrJUWnQizVWVW-wGccL$m!bv0u1qmnhDscJ7{?gRrnTy> z*Oj>=K2bu*2+{pe@C*5&QI3I-=jX6dpc*_+Fi=#WKM058jD-VFIai^XR*y?a{{RQh z7er=j`A^AgdH*SyE%!epv%SauH!|DJzmVBtU&w4Cg#RG3UHk`Rw&s5&v%Mn#690F| zY{vgxGF$Awli6B8WVS71&LS4-CF>$hFIJ19{EnJ8zJv@T#PyQlpxoWKznUHr6{CX( zoX>-ZNXnvbRHEU)LFO00_ay`6z7XwlP;nWrcbFkpl5FZwbWRK6iCu68cGg*m zCzBK;^JrFYSTqs~Mjo%&SN|*&CAbhnCW{K`Fj}pgN9fmNQ`7S8ah;HH1q{+06k?g3 z>nHA(=MX6;Q-=*9Nh8B0Lnx=%2ssvFr@uR1|0|izM49SRrOBXe#Si7Ljwl2&7Q>#5!TbNx~mI=r>=)t;iH^-jw?E0Gn>=V-1oyQVA|T zDZ;Ut^hi9$T@nV#R%Fp-Hp6*>gf7to9&&D;J|;bv=V9*_pPLpST}wGi)O%I*zYK)s z*sT_-?ea_p>38)K%3(R@-g#F1Uxb5mGodvg6nCI6MKDTGJqt1F=k=~;k9}7Jbc~dR z5enMbRtr33<+z%a-VGU`2W+yAZgYyz1OOkKAtW{V5u*6t=M%g+EYdqQ5;xW0L)j`% zIxTF?%&r+q{0TP@8fIke7w<(^|Ci^cS(kBX(@Os{{#XrBa z9ag3lCJnB~lEG0X9nELi=y3xiWQWyY1_7xY$6gd#3V$#4hgniN+rpgQoIrXzMIbDj z(|6jTS)X}QkPFC$O;`5%d-@kcz@_T?Z@|tSpad)b3f+BX8<4!_;rQWq+ZqQ-99#To zjmabq^vQokW_v&KGwA+4V8n)79~c;eCSF;rAd|^7NMO4UBdVJQ%VSZ&R%4z=`bO4{LxFkN0J_eB%(k41$^};>7)Ihe%gX(+%e!r?xtx4R_(uvm%9o)jq_NR?j|YfjO_JBqgUc z0rX%$hlyL&r?zu&<@OFFc#mCx@x0py+Wt!EdbqYteklfZKlJNY^0rxr!wh9tb7hCuM4-JXmv01xP}}LR!1NZB?ahOp=D?-Zg`Z z+L%|V`*Dn%3Rl69Sks06I#+ewoey$}B^f7%zfadAeN~`OExmf?2d6kukTog}mZO$p zXd(tg`&(gJG!G9P1!By|{<E00P%DzAr5p;(VzK z`F7etcAi2Med;SpYNeGOV{@>wN8)%N%3%rXNkd|4xUO9+ezJL}`)9ANPLt^Az1{%Z z=#O6qs;Kle46+feJp>t)iyYFQGJkwAYT4pZ@MwOzYkbXPUB25RSwBpxIE-yQDP))WHOoQMS^whaDPW4w0KN^e0Ic(z4Af zKDnqbv2wi~gyLh?QO zU@_A4u64X4sxT;|)*JexMYvd$$XczDwkoNHN0S7Ygo^bs|52$HCze|!>!xAi%)kC=q=W?8iZPh^BD}J?XiFg zSw{!cu>IHoTMH0BbHN7dH|v>!Sb6RV2$Q+ z=Me~)P7HWP2ci6~PV0KP6m=9T+X|q@?)D+;lQS*Mz{K> zQC>TOU?sy}(uPhiy#|=C9EdC690+@5-H-_4j{*1%1{w-8zh`-uyZ%x+;NARl{~Own zN^k6hqE6_sc$3P_ljIkAqG#Y@egly zZ;$+tRPc_54CH!ve2?u83VD=?)P+Na_Hy?tn>$R%u!@O1xqc{wpA19J-t=)T=H&vK z=xyrEe35W@o=UymM}4e6%@ajoASy#DFdj$TtV!Ij6;DbDFy*0BdHd>phk}L$j;Ftr zfCWSSr+6+$X)ijt98zT1ZS(9;HgfhsvSz<0%$~$n24W9-|HOxa%?S#mK!{GVi!Hx# zut`B>uS4kdyCVOG=fXUw*^{tD2kbt6NZz8KYC3lxXnm&qY70NQOo}h)+qWDVTYysaeZ`>Y?XkiDwR4*P@s0G z^SNi}LoF8Q@AXo*eQ3v@zy};xf|XK0n4FJcw`t# zhbL$+ybp&q3?W~6<|7R>gCvbO!uD{8pPG$NqK_I8Und=E;Ou^o9s0HYyP$+@vc{2^ zZ8VSfltP7=*p|G=pLnWEL>#pVX>$sxaNTV+T*k*oe;|s7y&i8~Yeg%ELrwEGR&Lhh z!;zi*&>a38Ou^7ZNDgms83e>1_QPArkch$929P9oTrOBm@8W*RBjdlP zS#8RxfRnUrw002oWB~~^QS%WZFh~#vJhtOkBD29u2@}tlnDj!W;+YL^)%4d+V?TLr z$0J(e<9OmQNV{+`W3J<_L;u#hk}LCTo>vbs8&CV1mE`20>I#M~|62MU+?&m5{!*Xy zTZfGp1CwPyA>}OIIm$#P;U$c!>dt|t)q4?!Gj(KlrL2C1h!=J%vN$T73WP^u>!!Y6 z6lxw}5kk?Av_ZEA<_Z7gTd#>u-^Tl$RFW?FIDQ}lS2GYX6mCRzpZji7oSiDvwi=p< zmpUgS1*OG0q3>a!yl+%Rd;D$4m_<(9$<_C zk?&81OKeR|S;l}RQ{pgylThM8u*g2b_aRh}*?-09-Z7njra#mBg~t}DM~E(X4|koA zj4wTHM5?2COuY3*ecnLlb2DVViKnH8a7b^#O-MsaOxiP|c%KxX!sGDoM_U4CYEA`~ zfB;LCB0z}jR7-vbA2$gk{Mn8H2@l7)OQ=Eg#+VM4AHynvCWM&x(>oX|sxs`p2pB*f zwIzm42f3H;EExBV%FU8_E1&C_zfxhfsfeqWkzQxU*(nUnz)LD0!*{Ir zmK}VVEt{AL??%qtTN4|e{KFDaOPu3c#J(eSoOTFht6LYejzuPiUAB^JBB8QrQ-e&O z#L4`|G?h7V0NR}KCxf785Zs${da5^IB&W2=(42cbXvphn|=F^Ny+ zU=c#X_=kq-D3*)^CGQ_-^Y%vVsjQd>h)eL)e#C!rb^4{pk&NuZVW=?hi`9@Y7(Kva ztKWPl_2lt3Xes7vW(@J@C*)0~9Xsvncq37ue3Ar?cA*LOewWHNFZZ&fpjnLaWWF|f zc37f|_LCOGu=;D2j~56;Q5@{UZ$cL}@o@^TJEu)dzN0`}o}Qx*q#Uu`1wpcbq=`Le zSW9h>vqoGqz4gkQ%1~pG-jAD2>l%-$iT&owD0T*4$-W!tOo|dKDFyB1lkf&gCi;Csv(REA$p|AbMjG?R}b{kR#Rr#bGRw z)jbXN62pM*uO3MLx26UuzomW^l~4u6jkYT$N!WjQ_0wQsM|~$KAkkSXpKMLVQdVRr ziK$C+Q6s3@n_GYMJb4%QYtF)A=Dq=?X3Q(`5B!wNEEB@D7Xd^HV~@Pn;SbcN{-u!l zanG_4poH)v*`e-VGk%=r?8pDhBAP#o4uD>SP7z^{;Fn9pNECYG4%z%Q-FLR`@z&8! zW0HL8FvApOd?Yz#79IKv{FZ0ifm~Wl6jvCxm6Asn$|}!X9KdI4v9WAHSZ#gq$Db?i z#B>2i#3C}>z?7%KdT$`Nf*dw+^Ii8iaV*F z|17Msem7h*$g{o|U1{5k%&oN(l^)EJ(o7xL;N(p?X2qvkWQ#tC`|aU(Ud#AMx1o#&9|EyiVE+&%wp?VI66u31ZP!_r>6_z-_o1CXu$!h+*=+;l zvmEKkR&UkM228OegYvV&YTrs~3idCj%Tr-hW(_NUFx!zFc0$v}U%cu^>lS4AfLakJ zhEDf}yG4gm{W^9cwO72Z=+!RGx&!y*%}7kIF&c_X^E~W+@52?Zdo52F&ez$fu-6!^ z0*oqhztvhjZ6ZWRPR%3hYe5<+;PH%`&8LQq=LrmC;4eH}R)tJ(2N<-7Gq|2Ffo=m1 ztiJ$Hfv7fRo01erq)=(InV$%H-Y9ex5u9ve{@6@R{I0N_GWs>4-ZbJECPmsyo(yvgK|MXky@1Na_Ok$AO-$jV<*GjcDnsSRKY^LUSa!aQ?1=i zD!;z!b^gX>r4#P$0u-PLRM7;jd^JEO%>(|XxDKI5pP%PyK$R36|DCtb@MX{&`?29E z4Fa$XpsyYslgZ7(|E{Hli0_T1&i~riL_b>>dP-U;t0JjpbB;nARkq}ix8;XDrs>9t z-yf>Q85ktKip!1^19$~*zyNx22)Rm&`N*drEC_K)x`B8fYU&h6^r9Z8W12J$Or$%y zFDm5d^KnrPI|wR!Bg0-f4@4ihfX|5UFP|cYP;Yt1-tXeeDBY1 zDooT01l6;hM;kO5cQa>~35N5xt{qpZOnVd)Vf?h>!^mm^lpdnB$p!CDX);6oQ~gld z=Pe*Am2ZCuk~R)=?C_~zpD!N5j@vW_pkfa+kdrTQH;J!ex6WY#6SgSU^}qa(J1NW6 za1X82fAF}}!1cIuP0nXv)1G^5{kEss=u}!MfTiRN`-trxeP2!CKMNpArW@e^9V+Ny zA75nwd;{Kq+Ie(ee_B0{2ZLBCdBHrWBDY{!7LbYn>{S;Hgo7hPXln^qH15$QHZ0P2 zO9JVnpZc)`K1icxMluyZ_mG+|bBo^?l9KAlJ;>c5mg45W%JdgCn#!S{rd8q;;mDokZ53B7O`}G8InC z)3sG9T)jHebHra&b#!q9Mh^3%KT)DXop8;S9Kv9VcTf#1Tx&t3#@t%SNu^Xs?wl|# zGcx9sDQbUYA*Qn)8MIc(N?I4wU}J=0(C1(@=>Gvdx1<$M-=_Jjx^+DUtzt6ymFjsC z1oGNF8p5XL?;8DpyZ-Z}sW3=s^Tt;af^MJeOjUm}?gAxw4T{J#NjI@ICL(=<@YX(x z-;xS5m?OMz4#nLt_5tCfSdS2Qah_YedO}j2Z;CS9dnB?EZdhn$F%=VzpoZvEzP0Y= zfUU>ok=Agoj-zAFN;z6<0uh|Jd=sTc3R9_|qR*5-S!_}mwMnH)ARmDuXa4D#v|`C1 z`M-eK$o>m3+aC|1)W3qDpc-8GZfq%(Ng6m>gT|YGaj1d+brmSwUt|XZL&zrnt*P;N(>WR^*%>Ks+ z+4Y+a$yv13;Msk-jE@57&hlrk(x?LiS+yg_I;b_`m?yp(R67q9+EHWan%!86L90~2 z#ritx%GWB%dFP8ze-Sw1R@Ub1(=Su-b)a`oC~1yu1!9h~JG~Vnk9lfp`ZR}wI5054 z7~}#OccBY1_3|ubrv&MBgI&-9*YHfaAVoo7*xhJ)qM(`eeIFIrnN^3 z;)oW+xCnstPJK*1xp{!UsT|M~2qn08MDwre$fYL?!`yTE6x6h0>)r(IwLMr%!%${q z7|pjWDIJtJ;zURj!AkJ}hWm;a;KHF2PDL%`vOp}NhK6zxvpK1Bf*4@{B|-BSWzrQ1 z{2jBL@AX<-q_`_H-=G~YFy_*F5e(5naBrc9gp=&XyloU4Z_fH3K^KrXI zAVnn;O0CiOzICR0dtACQZ4~|m$wPZ#^2jZxd*@KAI4SwJ$;NL6UDTu6;<<=ACZXfj zQ}o}0U|l;W&&96a^>QBG=s8-q8)Pc6YMe%hNh^wCyjZ~D+mo|SI~3KP z-v#EF9IxlsHOz4!MO7qjsE45JzA?9OanD5RkXckW4mN?hn=dgI5q3KHz^)o9)K)>V z%;MHG3CndL1S0oB`LzDA@*;5id$RR+8PA?bejQzl1^&D`K%dvcbTPtv|A}31#r@DJ zeXGN9j1M4=clkL~Vu6wcT}M|AX@p8S!TCI}7KVu@Omb??&scj#rGcbBa#N=LX`GBl z{ixcQ{(xNun?)A_rc!e2Y6nVa2Q~Yr2=qX=c?VQ}!8W9n z5*}9|?k_&e*vv$VRmPGBM%CnnRlR{QIvr~G7_^e^K3gFeHo=KPQg>_6^x%_R- zbjxJi_wdjrbh756!-+0mqPj^ZJyo(%h9e1_1*X}51?ue) zt)13?P{1})38&P$(d2PQfmN!-TWw+juvqehz0ac{( z6d7au84I-ue3fJ~!X1gH^;_K;V{f9}h`XX$qY*OkPJPK}2g7jD_;9XCg;tu_Hkg%0 zw>*kf0XPZn*JpXT_j>l0I{xiFWU-1}|2$=S=`B6^aCRw6y+#!zbq^f~( zn&tDliJsM&^-ME*6oq{%ABjF?PdG&jUw`4%JD#P83Al_?L); zHd>aU-m9ibgTY)~hCsvbc40YHF_l>D*r0%<*IfBy-Q^qlqSvoZ$JT3pdxI{5{z}MN zqJdR4bti%yK9EWZIfTz$9KuT6(zfk$<_?;_%>(IHfQr}9D{N6)Q|4#);7@IEVDr%r zUaWL^*04quMLr;^d*p#D$#0K`0grN`|1Fx9`WLZZ;Ok#g@VIfGI$LHk?6Djtd-cz#9|7SU*U@@D=Z za%adkhs70$JOZs{qX!6Ye%u{cKWzv9biu$bTPGppkW%nR2CDoJ1h6=EMS%kWICtMZ z;D9%sU)~QY0j$AESfGjiD(`<22^5V(z-YMGbgNZUmGl2oE z6Y7v#L+PqM;wC+A8jJ8|z}3e;S_untLOw#;enTB{eWVsSOqCUyEfq=Ioy}(A>czH%@RoSl@{Kq)^w6npsuiT*Yg;2aFQJS;u+3QJ}X5Q6( z!%eo3#$*hw3l;dI6_eiMz9%Ns2o z{zX2p5@5IsnEV+x)fx+j$N|@&bwic+f7mOBQ zv@#Bfv{(M!m4}>L4ak5bI#r_BJcA^K zc%tA0$s)aPebV&2U~twFa8K7vr&P_Y*+tAX4C!`GTZcj zLS~Eq7c!fy$Aux7%$D=tC9{$LM`SkMe~{U7L1ea%(-`~1|4wG}qyBG@*|tDrHl&A> z<-a`N|BTGm@t4fT_P-^wZGy;b4?I*&eHlyRuP<(ql@lw{?S!1a6Wn^(loo|31*VZm{A^BtK8i;d@O*8*RMT&{L&*VQvMzE*)ML(L9OesU_R# za66fhAJiiZZhY#GxQ1|i)75s9+me+lRz2w?i+U<>J! zecb|mcM)#n;$;K=V;S`>nJZ%#A^IjjSmmw~R3N16i-rj(PSbgls79Ecf78o(RVClq z$?H4H)KoU~TKVH#`5n@-$>r?zcG#l$mxvR25ERZF=HcvaZ}_gxAX}|zZ$V@G57ldR zpHCv+S;0`ahtGg>DG^LdoLm}TwKzAOQTepWit`b|sK7b-KpfJ6Z&J)2#c4gpetQ(_ z%YJp=AVxyEV1c@UT_2?}^sX8Dz`raj;GvB)q{NqR8T{8t*u#A*<^mk=CDb+FX)W2c ztKTi>6DA}8b*1L3B-ebN+*QOtIip*F$M1)PW6ZXTcj5}<`|y~&gV^scEei3hbz zHG;tcNS)4MKolAQ52L)_(&a%Kzsm6iH0o5<&+}TWYMb z*bAy{OjD3MZ`Bq@*lq#;fD<+TODyY^6>VOQ4DJR&olJ%9hrAZ2%2Qo@t=xI?`|%^@ zZmqb1UZX}^O|?wZG`3lentL{m(4tjJ~H+G)hq)1(RtH6!2E@T$_Xf{F`M={p(;yWDd)5 zkymybd(2nzNFEKY6u*Ma0os}W6aPR@6fmgnA^*B8M&DXQ%t9~`T`eKo044e&0>8;^ zf$F18F+^fLu^U|a2L(4ZzzfCg9pcaGrwo(k;!IAqUr3Ixt?QAA465Fx4^nURaqqnO<3=>O6JGOL;>v)$LSu@`UsS{EdeNv8^ z$-@>E#Vw2fLZmd{fe7Hg*z?%8=JsL$W8>S7?WHxa-p<+*Te_oZ{HIkAdXoi7Ci1Aq*F9epJ9< zw7ci8<-=F^>Df$=9c`d(HLk9pI`LYyFw)bY1qf}BXNkx?2HeHESidXLK8r4Z`O@Q{ z+(>8N!r-=aqVMquxMOcM$numizL`}_k7I1Z;PB+BovHN=xJ0#s@R{srhzVOKYjHrn zTZMJj6u}6Kw&|_siPLCc@G_7J``cQ>CCPkB2IjXl&8Cz#<&%1CQtHgXbtur6@hF5K zi7q*`jRbZl%$3qVp*^tI*DtqF*IDkPAOqO#@J#)Uk={!|IJ`q2t`I;j&HARWV3}*j zY-7sK;`?jHsfA!sNIK5-(=GL9TOXVU>zEpZy;QHJ8~0G?z#c8*TAZ#`!umsBNnm_8 znKp4J@(tB54d+$NAot($zdoGFS@d&K)M=|;XuNRTlwr%Ia>q^*U8`9riw>)_bvU_6 z-a{dcl&nt>;du$0J|zx3;=)2W^gS+sFDz%6>mypxuW&2&e~l-EF7o%Vn~=Zw5MJ%- z7C_sR;O5S-8`OKR^uz+mJfR1?iY#UaKp=t~y~#};yNg!Qg_{m@sY&YzQTr01)g{x5 z24U*SiaR%fT)v?Xh3^aAt1Yh*cZ?xjUR7N&iw0024EqS;g z5^E1wj*)rH7u@1#`^tl8J>4hO^<&G2b0*@xh_%U~SOZ7IXa{L-_pMIO`8AZ{f%3u} zd#U85Njm4{K@4`9Q&wtJC*<*yS1Pk2&2#ZFC~T%ZXuypNqKwC*W8-;$)H{ypC z(Z_G(-~%Fq?h>IXFv;yrSBc9w4)hN^X>_t!YdK0UWdUeyu9D)ClHAgQi!d5T$8!Q$ z22O&gl5Xbik=Vv!yl&cAOdVx)p1WLiyLD|W-#SJ@!g|T%x{-5nj-<@Z4)dD&3Yw;N zMywVLB=jG6Vwjnpn#4$E4mkc1)cxV9-Uy}GSvC9aLC0?@QkKx0$))oWv5}cQnZn5K zyfQNjEj7>aB+REdd~5A;F*Y`uX3aMMvJjG_DqAD@!iZrDw@uM*cZr)&_EfLOhz zurY~3D@=;^jV#*h+uX~Qb(>5dkBMf8a_$(4)A`fS+7GMt8jd8Qg>ZEJ7e^#zqv24X zNEb`%tIy`<&UtjIV3ga?zoFdh!6-M*xc)Sz8Ca*kj z2F^<BnV#aQ2O90M0S~fhcfXVVAgcP^J#IV) zG-|-O=k4fc_C$KHG26}j-vO6>AM3n~z$afEFwXVx6QP7)u=^>T(f4H}CTz1L^IKKO zZGg4&zy^S^qS--@xNG$_zVdGM)}P7l<9cP*>tcsoPkW_fClgc-c@mUrTMgQ^$pR*` zANjj*-x^p}^D>Ke4iBM9Rc|c$3)K`u5e{s39&_lnL{STQEAW!jsPbJVz7nXj4ywu_ z)_j-`#XNpJKPXSHN}DC6Du3-0Sjxm3ccM^%YNo&gqPb-vfoN_pK;3``>C?~q4i_jd zVIqC)#sbPTuj3_ZgEFTFUbS@8#uu;jy&7;7!woNxh}?LW>RZ$H0fNIJ2!c6eBFSdu zJkBDk_QD9;;MpL(VFP z5?`g+e)CL~BEHVcq1RsYu=xPSxxL!^sRo!=94FKR;oOdYF!7uAzyVE)p_gh&{sx4{ zVmyk-gTLu)JbClaX>z+4Q$60dh^YD$(#|ZYkkBQRP6lWbs)cJ7W2}{+wW=4C?Fg4O z_hzOjL=;S$2q|&VynBSag0mzicyj57Bc|d|>^D-0)hf?PXaC+g^?87%P-We89ySnNCBX%}KCok=?%?eAu@h$h z>GE6EKZ0JdMh4{hx@g8fZWIqw=104O22Do0Lm%RhdQUm=!ZuY#YVJMo@E z4%HyW)5s*$c5&6O-=M;V8n5ec-Zo%*BeXeT-B=QBXJXpdZS=Wk6iydEB?E)AT|RQ; z6m*lcAIVOP=4#0|c$>%-7SFYo5>}Ym`4g3_e}Pmt#GPkW-e5j$deD_0ZbsT-|lT8pP_<%lXB(Y z`rIVs@BJ96a`&it#oa-7@PwN%!%|Y0xMVx7ON=ar%EXG=%aWH z+(1OPF$TNhbAS~c+a-$mZy;V%W;k|KWX@a71GC;5drimSV!=53$h^2m&!h7Ht2;J9&=4c z^RE6|+%eOlYId(!D58K4B0%ndJaMG9qb|8XveuqFhMlQ5k2DzR##1@aRu_v{oIF1I zyMBTE35MRnSVe}=ScH(&Fvp>Js90sC;?gPlNSFi@%yg@1*?5P(NOK+eJv5rs*f=`_ zP9dnV(ff!8J6I{2&nO9*=!=GHPy~|FO2X_?RPb7rNKdW1j-wYmdZ*1RUG=S;(z+7b zMJn(s=akv+m+iz#4f@L+6aLnYeIiPI^&jtJ0l+=pv&WKMA3Q;Pkb;Quo}tBOKJvlA zjEN(eYCh-SJuBDfz`dJ3eD3Dt=H|X_#=aPS>9S=r^4(C z7&jYJ+wpX5w2z3Z`T*c|^uLZ8`}64treE(o6pU4jhH(Vh`+T08j%ntpfo0(Kh_QM) z1ckis0RL3v1QD#i-yi-HULy|JaM%F<`-}t6mfDwicjtE2f-lt@**ES9-ErgH-`R3f z@`K_}NK__?N|E4CrXVfv>8k@;##q6SXvWgsXc!vg@Ml2Ox6S!)+`jt;6MzZlIAr~vp)LhJpW~;-6^i9&qSZ6Ii{4FwFOG-? z!I+GnGh}6Qtn#d^wIE^0Wl|9sHoJ}5X4W?gsZ?$-5t9>>ed&}JcTu>swz%OwbQpV! zl}OHaG2PW5p%yv(X!agL!>-?%!7icT>fnwy&^SpgEZ}wdG{{AFUC79>w;N-abGzgd^8lmNqs_Mz0vbrt$bM3wqVn92R=8o;0f{uY z;2|HQdH(go6ux!ap!lDkwrgnw2jXVVB!3=M+MHT_GT-U5qJi_R^z^5Pc)=e${4e>W z|BtYmvvV(p=fk1i?W#g%fyi!uO?e625{*X)pzOBT`BgFPL@$;4nozzlG@(UCU0{Rf zzA@p`iBx+@QuxU5K*1@GRVEB?NjuTDG0nPGd8~8Go=c70PxBb4-%(wPTsB?(87oG| zGzsxDebvQhLLK7okjlx60Gn04L*M6%m|`q9I1KD2uc(rIcr!%J(Rk=C(YLh;O#CVx ze|<@C4}xbM*O51R!_>D8^={R5tY!Uc16C2W$hL#ocU-~7DYtbRz@kRRUf2ihk!(C- za1@yQiHjok%Ljb07D%6JwtL)dmgjSkT+{c!&DA>pT!S&6j7$N zhsnliv1qGa#oJS=C^nn+AZ@$Cta2mghC0XhJR!?B@vnFnPUz8mur zCkWon1)izok$Q>3O9K zk3LyUH3;^g31fUey0kEB=)VuYcghm=FRQ>?g>w7=X1lTK8#f>A!{wh2S6pl`p+zZ= z?mGlW$Wke>9(Y$dGO8c_uF$~+Je8UG*FbdKuRkZ3o}khYiG$jT8ujr`1%9#EwO0JVGiqb)p{YX2Fmnj;*qEt+^%g{@f#}u-Jn`hhp4AA8H zDe%fNdtG^s@7CUi*hPSsT8yWAjOuvuI2~xEemyAwDpWGAQEs!+HA+He;tCh!*Ab|< z%n}bXGGh1ra1&UXkB~G)IckKO6yO{dpG8D3rTNUDKG4`|=00K3(DAg155l_z(rH$m ziqszS5AYlAbx5X0Co7*LOAAx?7WP+{R|v9HdMMdWpNA*G>-YMRt~^b&v}`>hemOZ3 z{baYAocCDOGX3&s2=u+uV4P5U7<&7hRfDQ9MNhFq(TresKQ{9Rz2zmaTueyBeHsef z$dd2%9VMCkN1;xK>citJyH6ov`$FsD{#HxZ2O;PS@yNF<=wU1^=5D z7AX2*#s6DY<=IEy1kGAgw&(A4-!#v}4zgbUal0E1Tvp-*PQM9QyE*%tmDVhMuBCyX zex#ewuv9$BcW7P=fn&tA*OAP9i?7D^241snk6Y$-&$@Lge+Zibr)HMkTmApR)j0;_ z{l0%cdzp*Nwp+GsTUU0iRm)tqmu*`M%kB!RWiPH;bzki}{QmdT9$jbW=REK}@N&s4 z^P0{LJ*=|RD>XSN+e-;K!UdDLj|z0j zUypBTP7DI=IJ$}mYhaJTeO@kea#8^P*cj*C+1Rf`g7Ttx7*ju-V}suo_j@P?*lLI$ zv6;o3Dz@Ea&0d;DxT8+inq1b~qM3C#7uJ~hIKZ-fR>>lEQJDrRauoa)#HM>fgSKvd zcLHZ$1dMbIX{AEJT!EViGd_&+gXZS$H6h&89?JD*s@MZ3-2kgBTb%a2^@x6Q$@33X zK1(X2{uB5`~wf0jvK>4K8`-5ckE|KZ0MwY-nGwv(9jJ+A>`49+@1Zac; zl35jzpGk<+=foF_a`a1WmV^>Qh+w;x zF0nFrWf{*_k<0aA%y0`-bm6rDZVHNQSiW+>tPqKuRH^JgihGOtE0`uR}rJ z9Q8cq!*Mg+f&Kd2kRC9YFnxX%2N-&u9#FxsC}ot*0#>5*>Utnx5mBWpK}fe|T`sf2 zJLOsOCI;D_Jo=rEizABJiIG>@OpDdu7bmesQ6y6o$_Zus>=(N%=48?(xh$vZ6yjcS zetlXJXr-w$SP{DK8Q3MVz{wB63=DJ|xpSk^T%5D#YHHt!47Ev^BRn}=3&C^l7?azh z)IEUTLiw_qy_C%oFQ12%I{BEl!cCrt8i~XkiRrJX-ba=bvNG5pXWv?^3jOk=h+fiz z6gsdfsb3|-ExT(A z?d2_j$^@lgOPMDpzsFb#&G;!hBUP5AhC9aOy<>i#g{}vLZKFbYZ}7{g^Bg~~OgcRO zXx6|mkGr{Xct7(i&4W0eL;(A^!|Zp8uev0HH@IzLIQM+Am1XINb4Qi3As?OY&* z_|383Cn1f2(53?Wo1n}yy6Tj*85RE4H7%h@CL; zjPZFY9MltIsObgEr338#`~X$RWT##XnaanAzEQH2u9(*{^0xM1tSaf}BnV8({UdF3>sEJ)4SZ0D`5 zD%L!wDp0v41!7!6fa=ZHcByB|^);#<@Vn@$#fqQznZJHH$O^*xcqPNA8!t>H7gHcetmJS-mm3#AR8&}69FpPl3TsLatB}mGcy$h7dks&-C3To)>q~HJXKsliO{QfT_5&OriSV*CT)4jOq%2*zR-1Zk_TXwgWItkY&5U6~dy&D!ao zb3?Ya)rQTdzi*$vfI@EhWg=jY7eDwq#d^wtMLa*fL`VPK99`g}7vdBdgd(b#eF(dAI8utuRFAf_nfTxNbh|9+R!e#qt3apIOuQ7*APW;iQ z$q^Giu81H&U0{Cm&IoM)rk0M%I)52;p#)i&4l5W9Q$FGDj*?@9tih=LzUX}$)>Yoi zS`b0ucf{9a*=fQ7cAEYeKggSV6qBIs)@e(_t7H;b@7cOdzg(n%Si{2uJ`Q^6H$ z2^}Ytf*a}*?sph1NBN`m-xxOV!7oyk)ZVEibrvSt3|D+vyR?mUuGXX5y4SMyc(g?F zzcFm-l+C;|Hw}eYQJ7P<#9bwfpwdf`G3pQZCd$$v8{QjcXA8dj>&dp!rLZnK-&-km ze$8tgbN6iF$I6D_Z+L;{1^H_I!7X~C1ZuRej6{~h-W6S~k8vbf&;PldfX7y1JsE>| zWRL*zD^hy8H^TXL|KocY*b?=bJ6Q7!rHHSrx*FL|M)YjruC#@9t$>?wU>th#TU3hV zua%K?0~W!yrzmc@^X2m5-ocR?Iu-kyP%IqP;KNoyWs$Hp((UR3nVShVz#1-*K#1t^ zyb9Rkh43|_%p6W9#AC;R;$;*r6v`&h+=I`u(+XgHnKV?Y& z3-*AQBIADt8#VHKvduaD#?+ULi!toKJALsY~t zH43jAKwdh}g!zRj0`P|3+0CrAZb9KT+T|D#Ne2a`G& zz@%ONf4{=B9FWZhDQ-M#`P~Q{IM!rvZL^VSPcq+T_|#K3^{^-22$)6YSVB?W>Pc^W zGL?oz@Eyor_J8FrwdEE6-a&Io&8bwTmreck!5TK%nc}%cU8^+znv)M;k`@D_Nlur# zVr^+~Xe0>GXtzr_0!>4PlD02;n!G%mRJ?$TZMThXr;8eP<#jz_t!>bkY2ID-$;buQ zdTlgcCO!sVBsyq<&5Lt6xdNf?O`D3ERDO@RB%Y)m+Uy}9A(rCz!FX!~9bo1yH`jjU zQGbm1$6rPqtXHR;{L8ySgZRmJH|}gh^s;Ha&@JIAto9ZgA1;LE2~lHKncRzy-Y~`6 zxXSOS!E)*Jjd1}>1ZVtN>O^tacM1baG{4xppq zTBc|23bGOebX1~R7iQ-KIuC9>HwjJ*`5hObe6|1_5A^q%AXE_-SNObY@K$d$H#=Ps z$|)MFxU@x|Sxf3sTgjw#^_T6;Ug&8ZsnqJ&e5c8G%U11;mh@Cb7zvRr zqnl=OJMY&kMuQ?E9l&N6JL<@Uhf;ioJJnZf2dU4DGB4M=qM{ zJQ#vRiC>@GQSZ}MsPI3Bgz#`C3RZ%f>x6zi*S}(o@Gg?1qsQ4|g*JMeCsbJQEq;oJ zy#Co$abVR4Uj^|`#!E44`q9@}LDU>mWLkXkOV>loXOmd0=UZ>SlxNEzLKvfHlqcLk zHr1Ucfx`C}Q`>;gQRVTKF|?4jXez6#J+M#(P%jB6Pk#}h(qe6-1ZpCw=e9ETqdRR}N}IC`J9Z1Id5>Dy zA<(YHt73}1tw>vX_c{-H8EMKyl_jebD)ftYZf)Y*;vPQTgy=;6oPFL0dtF>M;aQ3l z*W53O$raX__$EvH{<2jeTZuM8P*nfScK6d46lB3?Kj$Afeij)2YqGhX*AJTC-%h_g zo3DFa0-!@yF`X#6>h-DE#Y!hdiZJCd-pUazK%?`PR3~;-vNDX$+4L-qEHqh&K@>;& zHl0jc98){B2$~!o``O5On9gDqt3i=!hP8x}xr;QjwcXfjZWHo3*3W(jUi)CP+aRbh zQmah$x_9z8`i8-$nx*~`KFZcC1q%Zs;=6MH_fw_$ILf%|FLBX_Cm+AsGC;KKebhf8O|+RZR)D@pOMqeh@*{C$P}Rirjl<+t+b6& zG0`3q0fnk%W7;JuW6h#6m~vyFo54~XlQxNO?{4z*;;G;(WW}~)R|n#QO-Ysn0b2Xm z?OEMjsui?P?KmL5K7wmp1 z`TdEMp079F-J3qg!H}>l=6XfLFo>0Ww1TwKgc7o@=dGt0b8IjN;;Imrhs{O+QKX{) zlg&qc`c71fP25S85eyQ$Gu1xHp6pcWmb`vUu)-6U!^o8)&6+f&<_>dSuvl8T^6wNO6i9MZiJhv2hqkjF46m+y%=S}(r6@m>8<1b+*~ulrglW| zEaRu9g+3HnY1`W4w9Grl;plj+SSR^w8h9mt!dJ8#$;zTJQQ%8*`!|SKeb|hn{W|&V z(r);eG@0qcQ|p*myllDzC>?4>-s5!@80;@4{M;s^Za$P&xOyYm)#f5MA`3fe+C<_KH@x2eEi?E=~?pm`t}Lf-T3^&^63)- zSk}iLPFE%$0aOm?@+=7uH!Tc{1wbg2BUR>pL@GeFKEy?;ykt=L5FZ#k%wAL%zK}~> z+ec_;7Se34&7Frj`)%Q|VqB`Q-WrVX;q-FWG;A4)cco~>oC_Z)B?rt#p$A(AM3*nO zrti`tP)7&X_A}jL1=vAzi<}ELxn{U=3yFisX^rH;Vpah+OF2EjsQK`ZH@-S<)Q~%a z0UXoD5#HYm+T^a;xd#SI(d-7J3n2f5wH!u<1s)%Xq#y+TWx2sMij(pF#MWS4m#?hA zs3(T^rZW=eaDp4J!!Hn>D0`xJD-%I-P&1HK$);u(aD3CA#6=!{pE(gu3rJ;GcjoiK z^?EHSMQ~jA07)sM5ySx;46UanoB+n`MVRL%Z{kf5Du#^P4Tf=d*cyx6xc3)+N-yA; zuA^@Z9o^v10XBDez$!~g>Whmn4`)mQ&g@Ko@B(X;IB8)($eBzplZ=$kI_-9gLgh|n zankzFO`Ev#2BmQ<823ZF?k1tjav^0+^?&?V&(q@j%k$?aKShpThU9)({+~C4eK34D z{oee3FVqH%mlfh0YU83%i@aiG?Md|b{Td^&VifkbN-XA^J6|jUcg^4`ymU+GY=&+S zCrxsO?0 z5&&3-2>tIl?H?O19`-+hEt?*R^aY^=CT?eu4|nK~fX%>!eJ?1S-5)NCsMO{$izX^} zf3$4gc@hd+Rtg@XSHbYX*#_EvGKN!W;0$w$G?D#J*lKHv&0xKf<+3D_x z(N0l{KN~!QXEQ??+jn0=w~Zp9>CUA*ERz^@K~^>NG7)O(v?O9Q1zjUFoSphNhS`=i zj&<=xgUD!JVFy^@;M1R{A0{0W!-ooq5lQ?hM;AvFqC8S7t@twz-kW2fcJ?RyzR~iY z_3k;ypfBkl{q{vOggvfCyYV~9>AoAxF({Sj_3rzIooo0*wA}9wm?18MG!!Q|gIs<& zVnCog*OP0bUkAT@6ZT%2AX<=13ZOw!-_PEQoAjX1LXtE#rL;j@mIwYcAcA6wEL5X) zeNF%sk=vP2`evP{lv{)dhSp+rqKkvsblH7v-58jgT*q{qghWddpgla1Xy}@zZO`_j zM9)G~w3e`r1`FG_%Tp*YMOk`TYI(E%ImVKzD4I}5l6Kkn)!0k~`vGV9Nm~ywt>vBc zn=h?x?&PyiWyRKW=!T1bWNXL=!^h}v8(s?#SC@i~_X!*8|DLFCjo+iMrQmk=W%NAp z?$~jE)(^WG#Y@2f{1Rm1FxJyHVY$=@#-pcG zb0y}S+h>T-#}83@wv=+F-g`wmOjnBC?$9 zo$Z_GN zE-xbRe{K=fxGM){fk~6vyCBAaU?*v}6LS1kGrYRc--00BE+9`^LrI8D&n~fFIRkM& z4hl6rlon^m8R;r*S4>HSe345I&ejT;bl>Lq=&RbT8BdH6j0`3_NOtzd)QOyF2kFz> zjqYlC+B^j_%u!T!N17}5>#HwfF!S;u;ZU{}Y0el{^85P*oYnAkPR9wx@kxAZE04YB zy@Q-Z@}hj5dq2n;*WF2w_m-*GZqE)E?Pc`^tP7!J-ll^WTa`V%{q0x~YUpGy zMnoxg|9-ll3jJqLOONS{%{eota||V|sI)L;Sf!<5;z@5!7s=5?MVo|0RR)$^x(zgA zu979h+Ki`+vq+;?H!%7AxQ%#W4jN7=_`EQMDwU~c)A0jY#B19Hz6J#!f(hwbI3AyJ z4Ek8gf_AsUSCFLXpSA7lz!X}?dGU-suF~R;?_N1t)fh5(5!Aj~Vy-yKKU0Vg0KA|^65><^wN)^O*Izf6KQ)TDmjS=Y@rSvDsf#8 z`r8hmO3T^|qYpd#5L4zlJq~S0*o@pCvq^i*^mw!(DEv}i|1V?nUdm|!bF%12v-4jK zy-|Z+`nIXX<2J>Fp57t2n5ma9oIO3T&FCmw&G4YIOT}gqoh=D{7~#(S=0C_8Vk0dG zat2RL$~ZkSVsGqsTHJ;g5yu8iBP*$ryaQ@la-LTD!Tg@HsPJj4`Urx{=#by6mvU&A z!AdEnu_`v)Vv+|UZVr6wJIz+rmlI}o)YP8Fe-W`o~ z1p&^)8H`+4)_$8wP{W)Fd{6T4zMNlw+<-bJ_5*963(MAe4_b8`d^KIz&HiP;i^4{?_XVZUHQq@g8wLMa9 zeEl7PUfZmQwAx9jJUkEvfG@T6teNyRO8*I2HNK;GhqZbQl2?Z+D6!{zTX!GYCrNjX=g(92i;7F;P=Uj ze@_W|DW?q#)cMn=$j-pl0@QTlw$ArLL+IWx=A&F7)SyG*5Xyy=SNE`0lfX5L#q1>+ zPCq0}6aXwD@i!sHmRdZ(7DD6bX{8Ix)brOiE_ZVCfBcY8pwow@TkzAwMZ;eNm`IvI zbvT*_ZR~-A-8j%4Fd}WqUs3xVA+4UtVPWSHIS@%zXJ8@R(dXjQ-JDO%By_-<4-dwC zrmEiqexB41g^nIqwbHb%uC9^!vX!Q|5ic^Z zzyFSxwMGbE-z=!fj|VZ2KE$?gr74mRgdx4HIf718+Xl zm4zaU4k>Vh{Yfh;z<6UYLTWxmyDYCk??EIfq2(j#Cd+0R{y3PB;vY<(Am9$!tws8G^Ro+JyXMTn?Z?*LjXn0(DCYvKMD zHYDFDiun#K%`4n6qynmV#rnvr2&fjiAF*@AzIE7`@%L%Hw+?#zVGMWttFh`o;Y8Q} zu@rHNnVd`rRjZ=jKzSDr*8Cio9ag&xy1f@0YB(Enus%!4*gAt_!Jdm#i>tf>w<%OL zK7UK-k}`0uD&=cnGH57KR7$t3b1WzBGt9fmaPW!fG#fiVD3j0iAj(*(#AJ90{UaF7 zDfToJa^(oQ`XFg0K0{^g@r7drf8GF**_AUMweD!cAn3G`z~y%RTFq0G>@uOx?XJHCV&f}SXh+@gViDHTGnRS!XlwOEpk~ZeDHM)RUlM{>AO_tGB zpdGR%eaIfj8He4$vgnyWGo@1a-{C#NaihTVt>Dyo&)wfRqMGnV5~}Cax1Hv}g|LlO zR|B7*BGO$7@^p7xjtv+Evw{@BaP8GRGPHjB5$k(jR(cLm=OQzRA(oyo9*PWNh*^A+ z^e!BmQB;F889ax^7mt>AXY%DP8O((z6-leKIp6hqXzJaG3f5U1yFo zf(!#qO#S&?9i8g+1T96?E5abc{c+M>9s5LfZ`-bRa+Mc`*q~E`i&5ZIQ@DL&luk<_ zx|yp&S^e#Eg?avN!uiQKFs_ekHq_a2P+#Gc-m#Qd5ZL3wa}@-ns(ydHB}Qx79YOy{yT^7lyi=kH)* z$TF%D6H7BVmx^c)7^ZVa?R6$i+tzYFCVy>tzZx?J-lfLC;N)}_lXd;Ti9b*-LjLJe z#ZyFeWf?{CZ$Ye@Dcrv}yu1BhMGVHsPYwPFvAgAA-tQaRBP|?+rS1t*wGs=FFyyUj zd{UQx%oI5X9cln?NWoW=QdHM~3n1p(hrhC94A--jKK`zJ>A*p$o{G z#uNT!r@!4(~nlYo3;A0z4qQCd0t5M%4 zEb}-3<1iim%ipx=Gp&Vt`#njM|FY>NmlFlDVsJ`Zmpt|+)Q&FU^Hk(w`NyIx+ONptMQIEoqk+)MofD+g`MuV zBh&oQ*{K9UZAHcK&znIUgQO8Q*WO&XjqZ$QDPc%_)zUsxZbcFbu8enPxjM~edBQ3} zKXCg)YFPC8*WwNMEUByQINLeYmkKn#B@WIsDBx?$R<>61g|+Xo?be@OT7V|Av{14q z=?7tc7=B!@Mk&I!{gNCEShWo~Qk}KVeOl3oK}<}b58$~kOfJ&8V_Y6^{W`JM*S}ga zZ&&P!>~2fIO{Rh(8P={j)akAbqJ5bTZo{d&ptda(%J(BzYQ5mTEM9P5e~+bqz^q8b z85(N(PfW!&Ium#T`>~uu@czJZK|cU}SsVEp`$nM*uZDBpN~;cBR#w|it|E$^8xPNJ zro-AcBBp%DyEEUZC#@*G%d?j)~l@w0CfGO ztHv752;(Sq3Uaw`WT&lHdJXJM60jMtB7s^AYLRtHv_$*=W5aJ45a(GANPdTWz`yn$ zls8IZ`6G?6v18n{tSvR14^-9Ptr4GRykWY#xfC_p!=oFH$s+qPQa`NuaP%qiTvPgPZra+I)A*#)O0?W-)%BkZ@^CmQlz>-N54S+ge0< z_(uLUiiqqzdQY3wArxN4>-N^Q54yP6pzf_{dI>g94sZnc0#ebq$H#9-jD4iRK|r|F zpZlHh9!6tq-mNy`#`%fv2CgVJJ){A)>2wK`=>&==3)JbEQ|t@WI?Sn1CHfZJT|nU- zyNyn59N#iK4e>IxCBs-N5q|#7PYO0xd|biu`sL(Vk{XPJW^+6#z2&k^T1FL5ZMMl41WUvY{QM17K_;%E2*bq#VI<132aU>g`>7E!iv7(8>CEh56t&7Rve^#PPOKmWNZ10i zPLlYe%Twh7$hZ}zf+I2Gy$#-vEEG7Qsm{6JWHIM@!RXQa)yF@kwA_9416LF9-2A7C zg9hkG!2k|*&*lNCM{=$rjk+s8)06k|2CSGxX24%%9FKi#ttxdGrg3rD=hRP{T6ljJ zX+z9#KRz2SX4lLRc(r((QdikHjz6W5)Iujcdi3yV9L%Hn(bPvHf!=#RnLdy-#!5H( z$d0Mo)5_V~o13#$EQ?Cdk2HlhI@T8$L#wm`Ly-EG%B1)m2fi51tZSfiKV?DVbZLZ3 zvKn&eyv0+X4}GsuBb~XVTTtOq1?GO=K8H%@(5tURRF1PEvkL>X>c3svwUOTq++SA> z>PZ&^+g+AVWE}yAG0B)-%NunLa|p>!f29IuOW7@aV(NcmLi((QzNi zalWO%xA9}8{_16>X;LLAPQ zI8Cq_J5bf3?s5J-%VjQUUZ1ea^&12=A+nQmTYd-mbiMCuV|^|Vb0_Uz+UWmFX+RdF zm_f*d6Nw~u1g$N2svJsC`TdcUu&c=&gv>}nYLLq3SeK%`FBX@lbox`ZU2>_pL$QYF zhP`teXBXouf%sznoW#?@fspA(W>fu>^F_vv@4R&ZkF-U&S~=^9X>Fn7ZE>M@KQ1J& zAdfb06GwnG`4wfiWdOKnU$2Tr=9A^HtO)uWiT&y~gYI!HAKs**FG4k>kJRAR`?W;) zmMzMRYpEDF@50-eRNV~0im8EZ{>@no49mcxew=9judVkxgeZ88AVb8jvcL|HN9zk9 z0H24*Pl{IeEa)o}ZCDzo97&@tq<2}67_xY0+de_RWi;-qiMySQsi&7#YT@J1PHQj| za+Qf(HeBaPH8Njvq8P>X&B7?_)9ZSY1x`Jy9}#YZ3I;9HMG^4J&=EGDdPu7^@9aO0 z3A8gnJjQ1mk@W|;nX`Wnv}9N^$VqIW%mtXSPpc&I*D8*|;Cat4xLjoLMrSPPT6{$R zZU4lV+EeuWx2^sa%s@%X9Q3}cJ!Cz)nrclN3meawl$9B}CDZPgB+Ehyd;(0~DOzbA z1QZ#ec9rA;Z$Hgfa3w61)Z|LvSxj7iO6CTx2s)AV?{8}Pc=uvU5aD8!t!6yN1=yvH z*j3;f+tButmu#Sd_c~dW4V#k%_YaVn<5*eWY^7H<%!!lpbXR$wm3|1OJuZoQ>-}8} z=nn=5V(rwv+KOu1g@8@Ac%5Z`;%6-*uCY?0`>VnSD$|0B4XB_MWbOL@I&CP8o_|2* z);5;pEIAJ}FZ-#mO}(eCt(u+#Bw~N2c+KhcF)@OM)iHQA&&zhvdT6&aFCwgYEj>PR z@J6ZwYQLt}b`UxYc}3oiPi)NUM>^(}KmERdN31_dm(l*~0}@Ik(#E=Iu~IVzwd-&X)irn@HpYx$8h0)-^ynw|1%IYD?QrG+Uz#= z+@#$^VkzowKGOBm=Nz`+CI0j@rJ5S9^@?fk!n43tA;HONu0ON_=YN@Qzy@GN{&t{tXtwBrGfQ)+dab z!<3E?^6bUeO;awZZd2l3zpCk=_D@J3?}Ir0p_gvz|8gr(?|T|dE=DdVh>{g;o@+~` zg)m}Tew4QgK_CQ{<+~O& zpUzJil4{uMAJlgruCp-zMi7^>3_{UL|LP*3eF+obLMrLJRk+y9-5nTbP3}}?960MU zyS4gvq>Djc+4H4pO$0$ythO0UkzZ6Sa1a&C%b{hG;rb61OW(SA3F%3=Foag7p!4R< z(B*s07|WhE)A$c8R6oj2>13&_4(sq%IM@o_P%j9*nYK()!-WUW)qJZ6iXCp&;_Rz0 z<` zQvrc|7-JA3%m4Pj>KXAP>HfwO2G{dJ&U2L6@VA(xR{ylT>oR4l;{{n-_7cS-kwDJ! z4?=ZVda+S{s{p0MS~?^&cRl5p9-oK+mJe@eESA?z0=t3O-yB~6Sbp6coEmvPRtFy4 zsRzyx40_Y}>ca5(@?mbdl`3RB?SdLC}#%Efg)89+`a)>`0!H9CwJhyrenjihs z)bV`xe17Nm+^ccg0LHXr21zvWZh4`a=?eCSk6iYb<+ zK?!--Lz%x(-!f;(?k{CE3#cmLC`}o&w~l;Es)P4==Sj&U!^Cn}!C&}OB1d2&Q$2KRel2tMO3-yGY4#gvH8qwg(oNW2S-GLj|lSZTll-Xf#eok zOBg`hX79pU&=QuHPxE2ks9Wk(;63hBGw}aNP@o>zMZZRk1Wx%V+!;~j67Wk5xNrR~y zj){&n`rVyKpMeFH{@Xj=UnHyk{e`ljyC}%gATzbn+)bowG+=m_hYiO#(QPh(vov3P z1&%#o$ul5}YP139bd`CSxh7$n{dL_&NZLPtawP_Mxmn*tS~*VnMMUwRB*SC_=4t*n z_22@3Fhz4riM9aoM(%qU8dk{uBUd$M`SeCCl&y$ zhVxdJJyhn(6XI3IL1Te@-|}I!e(S#3Y~27Jf*v!u%;r0lWR}X#F(WM1IZMkS@&CY8 z`yg;t>-7t`D#2lnnrcO%cfXy@5CIQ~9@59Fd5;ve{nq|W%rlai870ruJUV@67$W($%SI^4(kl_O5V2kM=>77s#qFaCeVu3LLmY$H3TJh|EI*ds0&2_D+n|nf%&bL}4p2se>aV|J3AsR37|DH; z+jJM%!=M%0NBs0;T4v~D$lh1ntmI4`>s5BL8T6(!f<(HLVWuBuQ_wCzD5w&QK*TPI|pd4pG26U0y*r@QMy9Y`Z$x! z&2vLgGkvEhh_Smd;I`W+x z2WAb<6ZlP*)*u8GkiShnBXSYK? z<$pgv&~)87*5}$46?G-%xhSQd{b%45x**&Xqb@0(Mp|~&eSQOkSgCw26Ms}}d@t?Y zC73Te^`hmO%=dd_h}dXZ3U4gD@@ea-ulVRB?Z<1_hAM9Zs2&n>!1l>m4eAyhxCSZR z`#qt*7wd8gO1s-NUl@f&%tVcUUNF(E6AVZQ@Fz_K-*?b3aXWYlE3t&Uzx1gQDimM( z(e8HtM7WTn%q5xW2+Z9~YoI?j75ai=}c-Zrjr%cUcYj>iL zKg{SA+Ht~Y;5zz06}S4j1H+e=WAmNPeah?)($CvV076so@MC;4*fNL$F+Xxy<$M-Y zkFjoe0vPZlDvf*2Hs&XZNj?e4PsspNF^>4yOE-zrIh;CJI>oh*&G0x#7 z(6C05Ab{z8ZS`Tg%2xVgtDxo~Pp-^*RSkxeORl|+LRHfzOO-0?A(QCaC>Lz_^2XO6 zSz7W=z|O1_)r!>}K7n`LwpVQESEiyj3ocWTI3{|2Q>5+fZCi!YNS3Y`vnqku;n-a; zzkMgp64t2^sRecJ2I&Y(>3g_)wQR?tr6kHSwUnYUEEc-HLqb1mW_PGod$c5opQct# zs`vVmiQVo*nE~NaWdtzUDjVb>V-oC_K&AW3^+FqXGr> z_N#A?`Cr8kFDV_fu!c@hHQ9~OlrqtV^+Y$Gtp-Xn*&z0Am$Wjvn$$_JV1yNE=S>4< z!I)lPQP2Pl+o8QErHRuq8NUSz9A0?%T|O&AIz)p9vW9i;b}AefsNdbP;5Rt%{+m40 z3@kgv1d9Ir+GVgkf=_DBR^MvxBjm-cz8kTlS}w=fGY+67%xDH! zAPImiloMfNpk&_e-BOPaSB|ty3$Z|Sqz%k3-3CR$0EZ!^RY0>CSGFRs^LRgD*7R+V z`2vAnELNQm3g5(9Rt2$oTggC`(u*kK9h&+D}C*uUKT|?-)7g~#0S5Hj3gxcfV7efsBq$o4qX=OUZv8; z%$hI~lqkcM&n&FMO-@>*4R)>{0|*uC(R2c_LxiXBImUiSQ&yC$^qA9lowMF#J3Dy4 zMU#|-!b%udA`jNM)!NcgdqF`7pzPo$mB7{FFAo>5M$Gc{NbUsP&zn(19&KiEmF^(! zA5_HBSP=b(f?^m9Pg&lv#xFljEq|*TWaUx7@w z4`L!2es!vlt2b&x=|SKPsAn+LlYeEvEy_^cN&v`fAcW3z`y5Q2vN;o1#NTq|*^Aud zd5iT-zv6J6{KuVvrjgluQqLd%Z@^mz{@4ntDctRG+F0kiDR+I*UCpm~oezN4Av^H3 zw;)d&+*H$+U^&z{`xvcNgI4DKG0~~CzP&IXr;7#AUf zapq=`-3Qg$)=8SXw{Uu+4ydbJ5__hRgU7;BP|2L(42#1^yGM~LW!U(ad-+|SWj&pq z2{eK~rV$fA1q*`elmAnX)B|@sd!t4H14aKyf~0#!LS7=&If9F5^CBRsfHy#u(nWIg z17#VT682i0G%eP+Rhvqwuv_%X+}ET9{oeR^V{%PR=9(_p)eyduwD=Yh!u0*bMBfLz zEdN+ee0Tm91F>y*n5qHu`aWQqTh8#NK!p#4c>ly2070Fs%duS}4Vklx5CTfcRE}Ah zk9tnUb7U9kqt^4hPIWE^QMJAFDm{^$@PP-_o{q2eGx2W)fFD#tpa6S3d|B}MpJ@Pf zFR*|cRc;C;t0qNvU@|Rz6iaeUph8Q+xC~9(G3T5z#h9H?pE+f)YbM}rlACt0ufJF} zT7SVg!OPgoIUR5nj&Q@yeo0!gXh;@lTT6dqc|(jyaIO!LVC*eo5ma{)aJ87_VG_<6 zUXI2GfM54FV87DYF@KJ?FlWQb+8XI+KZfXZ$`un0k^gD7BN7JMbDvX&&Vad?SqeP2 z&|_f!Eu-6jRy$h#+8_JN7Hoh9rNw*f%~!6gIQO;alphDn;m038yj}~xxRBA$l)+m> z((fC9V|Q+E&?mb}C53-i8vlx44_tea8To5EA0XQqvAfyfmYq8BzBnvE`ziuZXoN+9MN}aTuJrOPdpB&S0dK+h9w)jY9Ykw# z?fVnwK>BFTT!y|!#QNVBkub2D=aE8`qu#WHP5Vy-Hc4Wl2??q+Lgika64y}k=n=Un z7%5Kn0~9#bVlC{w*pq-@@?bZeQ34s}h0xe2&EUkDj07%aG~c3@5qX#+ipwr>kl1B`Xai}BzvoDv_l=pD(7>*f{=fe}o6AR(y)u)} zg`v{s;2g{&^yM`MqkME_1}CCaZ$}q&9$I2?6r1VKG?ETJX)8fN(2B!^iJ(A_s%-gRd!r!33R=X zJCtT>cWn8oQDN<@VXnCG-K8<>M_orIroK{H*Kv`4h|jbAwRFcba}XY@m?xO7N#?Kk@T|(PZOW{Wb$%Or?t!9CYJ{hzevEm=KL9mJ4_GLuA%e=TKh7&u z#VVYkb9R6d9c}(@CY7@DUE)R2EO}U_M~q{c3~LE1b;I}LQJcRK$)m&bAdfty%T=h_@e*g5PhBmpT0RDXuAb-B1G6lgkr2m>s!C4sgP6F5Zara`H~3w@nh31 zTj(-s>p8K`nH1u?3pVc&v2*#hY{DIkg&-+Oo)Y7U5gU1>bK+v{zd|EhQ_dj{27ch5 zC6UpTsO9S)!eUh3cAxPoN$n$q78ljG?wR|4WnFhP+}jpT6QU$qFh~eSZ&&o_W`tq% zsH2StqeRpUBBHkt(c9>ZI{M%$A)<|5Mkn`Tv|u(4=1gox6_as8hRvthlUeDzt6LtOi2Ht1pkyqJrI4|C^S?A5!QWrIZLUv znv-c?*hn6>Dpi|d&y zVmoMsxp5PvFZmk}3a+gm!yCDkxA=;1>ze`sk*B|$@-SuDE7DR^aDIAknTT_1t;xh* zRfPT^poNQaeVkYc9*^%>!h5DjlHExM^JoD;EwLJ( zjy+FIZI$@&hK2Fo>{WXDUvq)Jc1aAwza~1EZQO>-j9E_4IX^ZEel4b4(i-;|%+iPn zdYnw}TME&?X09ijZXxQ~tELcJFGND4&ml5W7uuoDZ=>V=Z2;9xSDg%cb_g!1;P|L) zEvJ(5d#{zjiAt5j_lyajd9$5>w_uY zqd%}*7=t46dO08e-1>ZE=FTlOLey|g5mU9j0>&#o^e-hg$!7RsE#POk=T!7VIQ|J~ zIv71YW;p-oe*UxtTP$8}1{1X~Rg{OH72pJRx67`LuQ;xMj_T|z+5Yfy-*YBj^PYjl zY;Mj}7Bkm?b20PNDRXP%h*j`c_B1f$?r)m>FPmg*b-sa4c>2_w0Z|a6sgxkv_y5>~ zmB{P0XDopIt=*w{BuNdS_|>8Eem6v3Wbk+Kdji?8D6!0p)g$Hhj&g*n8^vFo^y*IS zUq+xaD_~h9pdV99GR-S02S+I3Zf3~J1w)b#nJF~2AtC((6mi^2@Qxs|7eWMyJl5XF zTr=CU&RVu-U`m}3XUjU~C14)RtZFf}_`FSu9Ep+isyGEHa0-4lS>yl*ErFCA8=CA)l`h`wX!lOj#33uDlu z&%hDSr`{n*Ek9-5Aua+cpg9uTNH|uGzF5VqmlOyO`ET3cJ8Aes}JrZJ8a-DWn zHX#YzvMd`V+r__EVd~@{%QB7Pa)E?hE&J5gV2BAC2&Y;su5g*^n$Cq1RV71u1P+r_ z`i=l1qmnBvz0kvoLTN%${^ihVt#kZOcj0IAeSh=$T<7}!>B0pOjSAA0uPF3JHOSA< z6ZazBaGbT{&WX92Fi{A<5B@; zP!hyeZBNkgx;;BKbR)7ZH=uSY&Y-Gt-*(TedBtZ=MhQk9sK$QoT^vIHASs`nFHD+k zI7li4xXGi=mM~ijI+=aCU*`4EZiN_65!z`n1h@QIEK)g~HIR7~*nbHo$5oxTC)%n6 z?ymVtOB|&RQQcBm&6jLzwNLjS)0dyimfYULs@LR%C+C6)7}bdC!E>kYBFuRX&bK{>oVU1s>PRYuE!n_qP0e&N=JIyRMtip=mQb&VY&c?>FFX>%t- zSM`}W(ZZ|n?nr_FfvlgET#=N~#>+x0z0v%gW`U5%>ovM<(m<5`>(nbv=zo6Xtc$6D z3v{C58+KzR2X)Ve$|ZT>*wv-27jz_~V;s|sia#_Cp1Xo3)cgM-Y<|=jA{o65t&O0< zFYVTmF1>b5X-tqAO+4qJu#|b)gIU^%M}TA zvU-R5%4A-ytYD2&`AGz#yo!ac$muT-w`VgP zaHe?3cjG#iD=gz?_G)_8 z`a3n~+0#pH%s(e}8m1brljZ<^MJiJBe<>(rUb5mcHgmXRr-4k4EfAD{wq!HAXJ*wH zpE)cu1H5qz*Drg*jAlK)*Fw(kzMW80wAJTJ7_?ieL1+ZTd0pLt{c_Z-*!E99o%$)- zNm-6w6a#slc?ZXqgPw3!)U`T@pm=27x3x&&(~O$i(Q25-ZUBaHgN#XU3*FF1eskF) zdnBLGz&{0n*~Q5fv1O4Oh{*ZgHddae1!5Ok+FEIjZZt)8bsl~F8XgG;373_5^%iSB zGow7ln{9(&g0SS*?9IU;5ajv^0{c4k2=hTyzzR*!4Le@EZ4&P57c z(T6g;fCOHQdU0mq%MW(hs7cskQ*W^t; z@7AOu&Tsnr$Oxo}B%teoV43Ni=*hq>yEfG&doG>zV|}GMVsbklqjK1w6%S?SP|E`y zd?BtAi7m(ya;ct zQ&@v4=8N9RRr|yL%VxH$PA2CWSG8Sf5n3uiz#zwl8X+Y^BjI9%$<=;(&NP9T`3Zyw-AS^88wNmF#^ z_`{K%d8y0}ZRH4qEjL+nHEB~neX70Gt5)L69@Y&YnyRQ4?ZI-}7TIQU-^sU`uYoRO zN?GV_C)u5wKagRa6A1#!fTqDn72<%ZEl-$4(cg2x3r}m~yYI;95+x4bvm7TsmkWU_ z+mw*(^dbVjEb_vvv(m7lXBS&2&6k~`lpww?XnGE5@1y94mFumuw}*zyr8#k?-br{O zk-dia)aCX{+`@tu;fupeux_w}!1Q#JoA_IZn}I;R-hrjuV(es99ZYWC{qTnNwTS_7 zZqD-kj|GZe4;Wr4f7*IjM*gi`#fWB?!g9mYJ2uL?2+<}Rjd6sCM+qHZOl81%@~57b z(r=sCABI)*C<@*6gt_WdkT+LR{IV1Qen-dBH7zAY@0eheopC}>X+b}im_yY)CFj{k zy$xhqCfA!oFsh0>OAFmUDv=^cLe$_`+aJ`D)RxQGf~Mx(uW2a&jfBzneKiKORDi`8 zMiYI_)Sia=vl}--tf6WxF94=;fU{hO{v74YXZ?M8p)c~wOLgp-Bx!2j8nL1>7(y!i zxq;jyX{Ky9c!-~ce_7{mh=iT9URe$@nx1_pQUmfDteD({UMBrT%RJF#_%q)wQ%#(7 zvVxPg+m5renOMN6kwj{^%ffdKLWgtz0U{R}sOq?6~*s_^)P`P^*G z%zZ@)(tgz_QWnPYRfkl3S-JC&-jwCj=WgXc!EDFx8@H{Sa$xz6r>J1n6G!jBy-daM zK#!pi`pBI(11X`85VvN9$0zJ1Iy-3?SNMK$`O^LK=fnV+YXSJJLE?vNm!Ae$8-!7@ G4*Dm7v`BjZ literal 0 HcmV?d00001 diff --git a/data/jenga/jenga.urdf b/data/jenga/jenga.urdf new file mode 100644 index 000000000..6ca727c78 --- /dev/null +++ b/data/jenga/jenga.urdf @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/l_finger_collision.stl b/data/l_finger_collision.stl index b12b2dd9ae6da9a07d8851fd1c4e3475ce8b27a9..b4e45652b119c0cc46118a1428bc85f7505e0c96 100644 GIT binary patch delta 8868 zcmZ{pd0dR!|G=j-)$^1!?R!zrqb8+D&CGd9Nku4;tRbb)qD4`S{U(?2x%M?mxwdda z&CEI0YZq>^WWBcRJ6Zc3*L7b{zt`(K|IB%x&vN$9S)TeWI(Vnf;(@KTIuZ#gEksue zGKs~KkvwyLQ@Jv`{v@8fq?l(O-8_m0OJM_ovEMR9QlQ@KVRc*q&xM{LFCDbz$c1T#lDh0|i9t z@@!4=GOTFGB%eCM99_&IL z@l0L9DlEN`LB@cI9?!0*tio-Eq>?okAViO2K9z04x1}j$6HL|P86%5)9Hg5=%wQ{} z**ky5;|!*d!O%eId8`OAGFx_>WS$N_;;_vH2X&(sX!1?f_r?NnZc zR}D=iSEfR#lw5)QA=_gbtN_G$ULuP4jv(oY&`=zI}5M-aekBfsO%hK5=C* zJ{N1Je8El^D%-432hTbspBR4&0u8KHjh{vXuwl#NNj0 zecU0%$YYlkCUJ+=)ApW_C)A%)NF<8_hmb4p6pAAz#w{$wTB1^@MVo}zXz0Qik}_!y z+N`rpxw9!&UYx8@+@HS#S{s_1o2Bb%MjDz5ZJY;^FO8S|0u0*w-O2eI}Orn6#U+)Cg8)^n(ERkw2LfVhb!w3 zg^}`4HZ3f~TB1^@#emy2=&!t3GT`%J+|AWjdA#<8|NWrz8d@G0Fy_oVMORezOEQTC zSB7U^ls6#%VR57iVks5+u11+D$>aHaEP|dvH0v&1VwOk-!d#YT!o3K>gC>yiu%G44Nqh$3wvW{O zIe$G8^)T>8*5;SAD)MVUf6du4Po-G4(8!vpT092Tl+__!*lol!OGEWELPKrSUcy?k`IFQ3zvNx1nY z!u>0t*Op^y_YOdT(>sv^(7i3s40*8?+rFJZdO{+l;oJ7&vtK5X*|4fD&&FC;p{aew zkazvyTU(CRS!Iu=?9Cxnufek&$K(h6uDm!im)wRi?dU3&6{ETtS;Pc@5;q_jRV0le zli^r9-YD`!2CCVdLvH$=f{*Q7jo)qy#t-Gwg@0C~dwUnwlg63VrI|vq1V*&y%c~lB5d7u{q;>=)-JuTAo8j9E7JGIP=4vN0cTP3y5Q+o7fS!nOHNv`Du9gUpYc13^3uD zKJyKPsiR_u3(TanIH@(N$j>KZVXq0#`c~?ZgU^PMO&j5X3CFtmeZ{j>qey=vu;|FK zSw}jN{?CKRsnZZnv3i4(u+-F_SgeA)j-2__lBH-_*Hp4OJQj(X0_u*|ifapOQ1*r( z^7|wQ!8^lGY1Q!Ff7@T172>WC+0eMud^`gkqyzin0CX_rRCnj@RIYEY`e#D_bdcI% zw&G{{yR()KF1Brt5~A~oJ`6p&JB_>pBQu`emc12)^iLs1 zLjaj^inE8Jm3M9ONmPAX{IibV>npCKxD1J8LrDfcQkEm=hr=c_j?LcO9qk`Ho#<|b zIx~)W9XAmza?T}kkec(%WK9~{laWJ8z}K9YhqX^3z2Bs346QUcV%J7>h#6Lt_}tdm zB&<-IT~;XOD*o2UcW+d`3LY=-z3(cWjf37#BKx;wph`GPz1^M>M=E9?Mqbct&W9x= z48*Fa_4s`uQY55h5RnAZEvyyR_5Nsyi>>mn zS<}TbOl{2 zi#V1{12;>a88>e??!G*g{0Sp1dG=8&OH%D0L3mGCY{{{G3c^U6Mq6T-2!|~>Mhzv} ztgVJb18*#OXn?)mJRlID*Pr#@x$^5W*K)5M8LE zTDMCbv?gULvJM_v^Q_y_K_ttu9qHr>RyOX^19m-d4)nF*8PA7%mEI*+aTDa*@J7#% zEl2muGKG{)k72isE2Dgnrm=oDTssQxP~Bf*EQNwg62)OKvE_A>?gO&*l)nFZU9k}| zY-LQrYb`SFV23BbR$HFoE6db{E}7UA8Ym4{&q8NLwL`<9wVh1*=zg`b76d!GBOFcE zGLJ~ZSH-=l(DbxDqu6&tC6qkzRL`w>p$L{VD8xqxJGPyABi#0n-glcWR~@rv z&117r!8+ew5KGqQD3vzybor_1+lsrDiOL7;8#!{t)Z(w6d$ln=@`XQRUMs~GRLkK% zwY~94%6n_y$uIR&QEbuo*mby6wu`^!qI2&-jQRpI?J)}vM*Tzu1<8C zUjXdp7)&EgtP{@;i~kL0>W?GUVeqRH$K3k6EAl<+NsfcoNv5x(uOmp?!b>MkzrS}e z`tlO&oIQ0)V1ToXm9M;pax)W&d^F5+=9rTe1*EimrM3g?cjnoX$&uuR!h~#VgvZXD z@%>%hNnEVYj{}5VCl|f%Rfo_{9?Xgvb=85V?p1#URVQ9A(K@6Gw$tpI#}^fo9~)pf z-0j3OjUCK|8!LCBJ7C(GmwtX`+cOn{I?JTJ7e)BjLRM#)zL()SKVchGbarR1bI!st zO)%*LH#+l-yy6Hd>6b`~p{)zg40`1(yj&MdvLKMs3lA5eabYh~1R0ciyPZZ$n*`Dq z%3OH1c)pq7Ya2>N5xC;Qv0H{(2&M)RWJEt;T{*@vcq%$PA%~m>xhq`-t+t~CyL8&U zlPP&R&BVoio^sK|Nf%Jb~JE(@`aK{jzJgRwlv=6Fm) zIlVH7;uZWxG0q0Ck$fDP7y*A$lnDhAyr zS5bEu-i2qM&tU~86eCD-U{M#2Fd3Z(X&8^nRs%^NC z2+nTww5!`%NVfPoDOG2kx}U3IpP!?MqLx<}#i&Th^bLdzlNnK0vsPW4%}H!84zv3XKMk zN3m>MAMDk~M<7RGC&lB#PU4{>CkkIX!fhGH=+AN#O1>_`7}|UAOqAI%R2}b57C{iD z*j}%Y*Q03lQOKgSvF0nPD>5d*P)_M{eI+(M)sJ+5tCU`3=An0H$>=;7b>$hG!5H_A zjTc-%Ny*I7mGn8FCv<{TN`B?Xw0%xQ;m1(Ym6w+ItkXt9ZC9DpL9$t!0y>^D)?}Ht zurIv_3E`lpC&$Euj}U6nM7$4@JbA{Xz+W(p>q=^14W+sHLBepskhF)hl+JOng4OVB zJRh1pdA4dxqOccT!IM`(H!qH@y^tmhuH1pw-i3HCj`7M%5ymX5#@}F>7oEYDDYQQ{ zI2Ddll6sp7FAp}-{p}+q>zAnr)2@ud29e<6O&j$|B^0ggujvRe-aLEf zix*0?$`b?vMcy1+c-Rd^1>^~9Zi0sDK32~}9kM42E8&?pZ`AOMH}b5TE<}EF0!JTL zqjm?pQIl?-aN?~84DxYhuWc;STHVSOR#djoS6xO9BNAvFGU>rHG5Pz@mb>H0YUoX=PQC?gS{_0lB&PP@ z*}Gx;QH)bOdAJ{b@4+!)6Az=QF)<_n8mOw;y%sh3j-dyQ*1kM*%(1 zIA+@K0?N(pr(F)-e!TQ*(PgzYjPa8(m7YyV9#g070V`;}(%W9?3&&`FO^K~iW;pEo zUgyW_N6zMjE9TI}-&6XMU#*xAqy2e>rF*(OprRRVJ~NVtwtdYXFXEK9UslWQ(*D%6 zyyt6bZH339ozR$cIO@--I#|EdM(gAWXX5nnnZgw1P~0qUD&C_JJ8S76-Q8DtXz4yh zr=2SCLq&^Iu=orsktC($Di{8dfPA0l5V2&P|n|n9o zb?MD03bb-wUU~MY^2jnH<<#E`h`55{N{O9HBz%27s_#8iSOty>x5QD5lFEF>%L7%N&Rw+@Q4McrQ$@c+)#$ zTY+b~C4^vhdr#5}0tH_6{haXgC%z7gXQnv)Q}@TeSR%F-r(0Tx`2@_bc|fr= z>%2znN+K!un~pL9=HZV|feql8gWnjTJgE;22=V}4KR(t%D4qey0q)E?qZH!nT7yo( zh5+8EDJ6?6{cQ=l{H+uG72wJo8#RFFRhiO*P^&o_Gj=y_&_PWIvbTcNQn>d zLG-2T`X^L*sUL}i;Xyomt=n)R@n$RXxd9dhaZKzsl~A=fLc1OaRo%L5ir}_kAU1?o zl>D<*g2&9+bc1ycrbktuSkgP+K=2$2LxMT>>*KCCtivQ_$0JY}>~1*RT7|xk9%zDH zm=e>m1ea|`o#9C^Z=6*)h1|Qf`G?q{w}*~B4Cu`>zdaa6CMN7eQ($Iqo}C;wnk3kK zLi<<3AH6+wb8O*3Z~E5p@F{w_*noW20gDihv9m2kgZF*F-61T5M(4zCWc{THC<3Na zGS|%#ro>LuzJwi=4iAqMyyBN(SGYw<8AzjC2Uk1@+V|n*3uBv3gB5z<0ABi#83a#%cuJZ`2NQK&0BV2CwJ*Uu*@ z51}rUW5?^&p&_9o$ebq759639)pJz1XfOfr4WkFA{IlrK8!==iBvG>dn2gpO&mqHM zO&HIvvOSKj92i5s)xbGw=vk~U z6sIK;bz_pSw)8kwaU&jU#T_gT*WxhVvJkOEY%NZ=v=Hw>qRlP5#kZ4|CL*;KUsc4e zB$7z_vFZ8NX_{eB6~PhcMUv&Dc&ewl!ywf_)2rXxyY3Bzy^O%*_&f z^;i2qyMZq3q%ApQ@Y)RAD<1*|a>j|W9Fpxb{f9v&mG7W&<>0h*Y+?_kRGvL2hYUKJ z^+SGz${Y9R5NG;kzwa#=MsmiJslCfjdqt#+@ukH%2>tc23AIKOx5cUA*q)Yjaw(9c=qDp-o&w^GimJ%U!pjcxI~b6M@!N!3OojJs@>;0 zlFU8>N$051ErxuQVOCAkl|?l=>(43rFBqvFXyfjmZCgu2z|A&Ku;b)$#M0)DzgQw3 ze(@BMNIv@vAqmrNsD0dx1@TPWv2e3Wy`*@tT$OgM#gm>y@|)92Jo2>}aSI9{V#g^9 zoYV)KUHuP4U;lsS_79&_ByygIBK~r%T)YgNyY5w=$(|95VOJR=GGZiU+afkfe5rC;I0c6e>geMl23<;_edniA1u-Y95YBd7?cTkwwJA zAhvE9%=`oAC8YVDP$<)1fA1WmzGNcR@Aw{92C?Pz(Ct;B>B$0Wj zcy;gHn`fS0JSrjbl=(d`!_zbV_WON4zxO%)`m66*!`}Oxwbx#IU3^rpVV~Z*QQZ#c zNhI_3u10lBG6=tZGS6JvvtPZm;R>F;zKCbyAD%}8=4`_;>(BCeCw?_28DXP{byS?T zChT(UJ*KDj^pRUyzr%SNW0iq+*8DnE)u%emNK~hJ*j}fSNLox@VW&CM$T{1`fnrJR z#uQEbI*E4l&BjiiB$A8^#n^mb1`!gw_Fq18g*v|UfYRpS2yN~8eIV77vyV;|aIyfZZBMnI^r-QHv0dC)RYfs|gBfI56|CsOF(#J9 zxa-*rQVi8ycvgL>7+);UARi9G^DZ2_>1;91qQ+LiV583&J6tTr|4`|rXOc` z<>HVoS;Q2EP#S%74W4Z@pY(%;ls@Vo$Db4D5<@sZ$z4&1Znw@8KEr)VKFK@rrL=V7 z3EiYT>$$%gZ<&xrrsu#QDaTe^JBLsHIGY?l2J@vH(_Pv}*mHdeu7ENr&wQC>BW&<4 zz+<3Z%F87GiH@rb*=*H?(4SqJ};#;D+BP(0b1$St+e;HkSdq4{`8`|bgZ8p#t?d`35b~R6k z?%1W7v+IuP&icEmm=>%##hq16zR;*zceRK1?fm%KUl0BpQ0)QZ$@ko5O^BCF5KAT} zbkVL&YMR#}PyPo7$_5?KB3pcKXk8XOpbyZ_&QOXtFE?W*BjK`Biev zdXEvz%ZxeMzl_3gh6Ely1) z@8BGzB;&)#=fZ5Ffe(~ykNk|(uSbzaaA$b7^t^8PR zt1MEpUR$S)HI{1Yf^sy6uK)YtO?u2D4W@V18+Ml=(T9gVtZjI9Stfb1cqzU-{ftiR zP3%ErL%sP$FCn=fo~Zlw)QJNO5?EVi@45tZqWlh$!b+BBUWXZIi;PW$7jT-AbV)qY z72HI7;RU5@*$RB(eKJ`Nw#GaY@|H!f=1mojK?J3*`nl-L^JKve@{IXB|2Y{r#JB** zcBG0ofl3^z818q_jPq3)nFmxnP-nCpo;nDkG8a;@;!} zq<7<)!*32?llMs^3d$+@9;(ERUsA{jXza$Tt`(#E(POn9b2QG}Y7 z($Ixnl;R_kQN^qTk^r|%c;m>+>8Q3Wi|j183{q2f*@r_R_?dFCAaDBS3j<8u*ebgI z6?-!T8v{r(<&?{ZMIx0?9Kn-Xv3N$}WKf;tubyPm7#QLDn^qzLw;xbZ-2!q5u9@=8 z-6ivJ!|p6$JA9>7jDk>3%wqBy`gG^>g8C()BV)6PWD8p>ehcDpI{Ws1l7dEb$tIy? z&s9H}O;wM)P^gs5s!&~6F-<+eaJ|x@<*-WZNg_FVX+3IxkxsVh-&Oybn5^y?xJ&ur z^&ZvW@EOq9UCw$u%S1PnS>!E&j_#Z?xSDFkj>OaOPamkZx&L=yTF-pC z+{oOyc;f9W;So&i!84Bvj0DRm(PTdqQp%py4IRkMC4+(V;Moy619H19mK-gDw>>!a zg76jZ&YeOw>O=3I9Gi5iHwpPCnC#HPc#5xgI}78@0|~bcR`=x4%;j0gc6b(fAT95- zK=E8GXU#m3TQ4$)`){h|oCrryJOtap5<9 zo`G&9XOotb=_f=!RsZ+@q1$Dh#+68xcuqkXkFtqtYKHhtL6Mm)i_(pVjWUKbJ%K7S zjz!7FsD45&8S)oAHRG6whH&)q$s$q@a&uZSWFA1HMy8VM<6xLMr*dC96a6+No7|{M zQ~uxJ^hI|XJm_S;`t(oNl!~l(8j0juX*xbzo+X%t!%=g(Gs^m++Hs4?mI`Pw=a_f# zDQK-rHaQACEO=(8b}l-ao<$NN*n-bHdn=51eYmeqD7O9Mx=JBgN{L{0PKyY!{b_DCe{Hyl;g4$rYzBF^^WyiK#;-?K^g{psiyt-r*Q zD~qo{jfI@4TN+P(&Hn|>h9(PM785a#%&>i}_FuFcfr+J+t9THJWdECb{A9UOEelT~ zA_)w)w3Qn@TZ=5cY&5fPFX$x8wX|hV?|XoD^p7Ae&alUlW6zIq5uRMJCXe^Q9ZQbc zG;K0Ajc3UUkji;x>8cahw>XXb4gKXj>+;QtNQDUU!2^=z9J_T{IJx!2jK5c7;6P{J3B&P)>x6x zP-M+BoA)~E%*yjfJe;-W*}|eRB*L{jS=$HRTYE{j*!RPWz}1Fl+MZUb)um1NJw)5^ z#^o1^(VOxN;rY%N@RN-@MQ(V!*|*J2&`;`<8D$T4?+ z?}LV%_aR!??5Hp_G}IIRG=Zy*oZ&eCB4p4G9gaSFWxzWrShD#ZD$bZmo=t&xCywcP zU3m<4KgDU&)~chCo8M$OSX;+AU*4is-VNk%^*Lq!XKQSy_s8& zZ`Vw`+FJ7kVw`yc`!#_9u!=rbfBa45^wJ2cK<7+Pi=J}fuPsMW8@zGmrK?8U4@d_) z7lqU?HX?8;M7k&p=X=%-46B0WE?&%g&P7<8*U*Lzf%rjQZ=O{ZSPFS|L&;4HCwp`3@(EUg!YG0i zMnG$Cj#(MJ5M58oBAH;}$}{Wq52K0p^Jt|T=E~<)+N{D6sjqYwBNh-^%>P%*ixN?% z%qfv51{dJn6@Tb{s;3unQBD=t@?uXCiHGwtyndh$nPcNEoDMBj&)Ya(V|+%T%1ADS zpIqhA(@!#V#<1U&Zpbqib^h1x;CawYXUe75VDpkxvJ*_*cqY221m{J}qUm9<8*lu? zYXKP_323o@1T1iKXMXP*t-iP`kFKiRjc1!Z3-L|EOp>w>?z+*`=(Py#3rZ*V-T>>) zu?KAcuTf4T!$*LM;-JWUwRc7ykyk>hJIB1~b`rnoGMCJTUG6;d_^)VmhBTodxaH2X z-&U}K97PK=7l8rCF-Ge~Ba@+*P(1YIcxK^?5bX&UJE0L~QhNHR8!|K)3d zm#F*0BoB^>sW2kWy5YhHDD>djZkt9D7hgHOal#p@+i&YhyzEt)u+s$IQXG0H48IHw z5KJ#XZ% zYA(SmN~HEHI`X58#Dbj{&-~qR9QV9Bf;dAYCG!P2=#^zMs)J>eoW@~1JSI`-4VC}O zoZLz1&jtbyZIrC{U(ijv9EG2QT)|7X2bAdg!VrZ*YA-3%?SO>}1$$z>ztD9-KQh-9 zjws*ZRBsLT8h6Ua{ z`(gh~A!guRT(=o2yg9b@)?A_a*b#iV4eoh!Oh!(sV7jq}9)`w!ct&QOD%4tNaXhFg zefP5z+Rr@4eIbpK$$;L1ahIVu5lSiTNRSKdcb?+maGTQHt+ql~)LJ|qq&_@Tx!G2D zc-4*k3H>SY-xGzhVI8{RFw2K$-(1cX{%M+mJ4V3{AC4LSDNkrC8>#IDH>j}ni!YjK zlOuSa+2G5uigTW5!k`@C^fB=BrPYyU8Iott5z=9rFK>M22Yi9?5!utL2$(NHouSO_wQ+=qNh#h#y0-K-F@ z7OE-T`t>1_ODB;5@Ql)+{tJX150>KdVBMEzkhMx!xlcjpQBJ99RxhDL9!^>zmy&#y zwNQ9|1la+{DBar`LE=u-;3x37FQ517h^4ToFkE=>QHjNer}*yMxh@a4nW@g}D8bLo z(*?0)XO>#sOF2(@b!^N3yDj^a6yoFqGlQ%32e+P9UF#Q!wU8$YgwQDR{0z!Y@ zaC|;5?6ic`{yx&(-?pjZp{zfzn%@_6XFke=rna%<$?=)$r|df=a>t$eNa7?fk>ua9 z6Oyc)QE57K9l*){c|I3^zm_GWu2-u-HNYyovv!J=g=$)HgRO1L?IV+yOv@K5u;qyC^bkXNQA*Q&4I9;2G~atXP< zI#oRZe^+)Co$S<;>g?R3As5vTnLzKb(+Bd*%hKMc#KZvo0h=i)`wT$SJx;3E!xc(- z=F8EB=2G2m_)N)lV6!?WE&{iMB9Lb?&s3@n5?0g0J}yw9cMb{z70h^?iYh$P1YbBu zHCFw&QaASaCVU1yP*Oj1!pxm)QV#A)o?)tw>K<6f6Dh<{dTU`#G|A3r8T>>kj&~r9 zk4~#Ef{s#nasa7rHbUp%4W+MUURYP|NL1jY;u*LUgse>ce};?35n!kO9ejmER?(qVFa;69Jk^~rkM z;a-a_LN?-!*|Y_u*T(forsoPrkUO(-N+g+FZ9y!d8S%^_SsLkF$8BXm(l%ZA3Rxy7bXjaPo-7jlc|| zDS6a;6lmIuejp_!lk|4<@<#<34Ra{@XM_qRpDS<%?4ndW`2`B?aUE}iTa*^nWTJ9M zDe(vW!Sv%j_=IlNk07qlcQDU7`A-zuoArtJ14tUoF%u8v3GCVk-5%IVRab7BFWfC1 zh4tYYrT&?D!qMgVx)k_I4X*{nkkDKs!F4?N1aa);hrYP-eu_Hk2uuy~>N?Ff4>jj+ z@P*&wAYL|N^?cIQQigWCyXp&{g1q&%10T#Yo1Vs!2{VqOJeU~F zvnla$WLB?FsJZ~w2K#imt%Nhd9Q*XyYed!=5z{X4Hke};+7+R9)gSR-a0%fVVWuD1 z*^q?7VH_prE(?SQ5sP%~@B^jO6Gsb4iJPz|)KF3mwiBw%-0?7Y6~ZeIY+8uU44F&L zaXCnw0>vRFZvIFl>yi(mil$U@8X|}A%p9*(sD9IIk^;*pNiW%>qsIo3NT{S#toedY z#~Pp^&_>Dbm)+>+u}SoxkcZNXM%58C<6|`Ouz+EqobjKouaMcg1Y#h02Dzc`?9K7E zXtrT4NqY@PLpj#h;10?jI*EMy2rZ$s?8*BR?O8jH9!NdHXqe>QKzEv>>8Te?sk$Q> zm0rpsS7AXI&+fOogzA4zAo?1p2;&$@k)iPI0Z${NiK^;-jv~jWnvxta9?HvX6*EY? zRSW)o-8EkrG}J?SIV)564rxPqwrf=zGQ2uP_)7_UhH}ioWFsM~Ias&>w}-3(|0&$uDg}W{nAgJ@gOf**mGhXrsw@eD()O4yTQo6hFZzy9=5D+o|fu`T)Fq zi9ZQ|8{xckWa2bkB76>4ZIA~@r&JEBPN>K^3fr%mvJipP(2Al#&(#O*QIjO3WHy>_B! z4W_hXK78avncjvh^6T>qymx=T4?K*N!%SjgTI+Tu6N+2telUXXV$PWV-<4{3b z1xrVn!@2zkdgaZ-)-LdX>MWqcXFkrrW+i2Q(0!B}JD`fTsB7nA`CAw?ij%3S z4~PDXaeP$h3CI}bCd;H#GwHbiZ+~BO0``q^W5y@O347Rf)Cl#Xc%~ygTG;#T7HxqT zjiy_hn;{teejiPTfs`(vk_( - - + + - + - + + + + + + - + @@ -55,8 +60,8 @@ - - + + @@ -71,7 +76,7 @@ - + @@ -86,18 +91,23 @@ - - + + - + - + + + + + + - + @@ -109,8 +119,8 @@ - - + + @@ -125,7 +135,7 @@ - + diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index dcd28d826..320c0b6e6 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -28,6 +28,7 @@ subject to the following restrictions: #include "../ImportMeshUtility/b3ImportMeshUtility.h" +static btScalar gUrdfDefaultCollisionMargin = 0.001; #include #include @@ -347,7 +348,7 @@ void BulletURDFImporter::getMassAndInertia(int linkIndex, btScalar& mass,btVect } localInertiaDiagonal.setValue(principalInertiaX, principalInertiaY, principalInertiaZ); inertialFrame.setOrigin(link->m_inertia.m_linkLocalFrame.getOrigin()); - inertialFrame.setBasis(linkInertiaBasis * link->m_inertia.m_linkLocalFrame.getBasis()); + inertialFrame.setBasis(link->m_inertia.m_linkLocalFrame.getBasis()*linkInertiaBasis); } else { @@ -464,7 +465,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co } btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); - cylZShape->setMargin(0.001); + cylZShape->setMargin(gUrdfDefaultCollisionMargin); cylZShape->initializePolyhedralFeatures(); //btConvexShape* cylZShape = new btConeShapeZ(cyl->radius,cyl->length);//(vexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); @@ -481,7 +482,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co btBoxShape* boxShape = new btBoxShape(extents*0.5f); //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); shape = boxShape; - shape ->setMargin(0.001); + shape ->setMargin(gUrdfDefaultCollisionMargin); break; } case URDF_GEOM_SPHERE: @@ -490,7 +491,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co btScalar radius = collision->m_geometry.m_sphereRadius; btSphereShape* sphereShape = new btSphereShape(radius); shape = sphereShape; - shape ->setMargin(0.001); + shape ->setMargin(gUrdfDefaultCollisionMargin); break; break; @@ -689,7 +690,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co //cylZShape->initializePolyhedralFeatures(); //btVector3 halfExtents(cyl->radius,cyl->radius,cyl->length/2.); //btCylinderShapeZ* cylZShape = new btCylinderShapeZ(halfExtents); - cylZShape->setMargin(0.001); + cylZShape->setMargin(gUrdfDefaultCollisionMargin); shape = cylZShape; } } else @@ -748,7 +749,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha } btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); - cylZShape->setMargin(0.001); + cylZShape->setMargin(gUrdfDefaultCollisionMargin); convexColShape = cylZShape; break; } @@ -760,7 +761,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha btBoxShape* boxShape = new btBoxShape(extents*0.5f); //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); convexColShape = boxShape; - convexColShape->setMargin(0.001); + convexColShape->setMargin(gUrdfDefaultCollisionMargin); break; } case URDF_GEOM_SPHERE: @@ -768,7 +769,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha btScalar radius = visual->m_geometry.m_sphereRadius; btSphereShape* sphereShape = new btSphereShape(radius); convexColShape = sphereShape; - convexColShape->setMargin(0.001); + convexColShape->setMargin(gUrdfDefaultCollisionMargin); break; break; @@ -1166,7 +1167,7 @@ btCollisionShape* BulletURDFImporter::getAllocatedCollisionShape(int index) btCompoundShape* compoundShape = new btCompoundShape(); m_data->m_allocatedCollisionShapes.push_back(compoundShape); - compoundShape->setMargin(0.001); + compoundShape->setMargin(gUrdfDefaultCollisionMargin); UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex); btAssert(linkPtr); if (linkPtr) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index c3f73c4d4..059eb56c6 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -596,8 +596,9 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer(); - m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); - m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.04; + m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); + m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.05; + } void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies() @@ -2839,7 +2840,7 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName) m_data->m_logPlayback = pb; } -btVector3 gVRGripperPos(0,0,0); +btVector3 gVRGripperPos(0,0,0.2); btQuaternion gVRGripperOrn(0,0,0,1); btScalar gVRGripperAnalog = 0; bool gVRGripperClosed = false; @@ -2911,26 +2912,25 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec) loadUrdf("kuka_iiwa/model.urdf", btVector3(3, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); - loadUrdf("cube_small.urdf", btVector3(0.2, 0.2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + loadUrdf("cube_small.urdf", btVector3(0.3, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); // loadUrdf("cube_small.urdf", btVector3(0, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); #endif -//#define JENGA 1 -#ifdef JENGA - int jengaHeight = 17; +#if 0 + int jengaHeight = 10; for (int j = 0; j < jengaHeight; j++) { for (int i = 0; i < 3; i++) { if (j & 1) { - loadUrdf("jenga/jenga.urdf", btVector3(-0.5+0, 0.025*i, .0151*0.5 + .015*j), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + loadUrdf("jenga/jenga.urdf", btVector3(-0.5, 0.05*i, .03*0.5 + .03*j), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); } else { btQuaternion orn(btVector3(0, 0, 1), SIMD_HALF_PI); - loadUrdf("jenga/jenga.urdf", btVector3(-0.5 -1 / 3.*0.075 + 0.025*i, +1 / 3.*0.075,0.0151*0.5 + .015*j), orn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + loadUrdf("jenga/jenga.urdf", btVector3(-0.5 -1 / 3.*0.15 + 0.05*i, +1 / 3.*0.15,0.03*0.5 + .03*j), orn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); } } } @@ -2944,6 +2944,8 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec) loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true); loadUrdf("teddy_vhacd.urdf", btVector3(1, 1, 2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); + } if (m_data->m_gripperRigidbodyFixed && m_data->m_gripperMultiBody) diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 1ff054a0f..2dec1401c 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -19,6 +19,10 @@ extern btVector3 gLastPickPos; btVector3 gVRTeleportPos(0,0,0); btQuaternion gVRTeleportOrn(0, 0, 0,1); +extern btVector3 gVRGripperPos; +extern btQuaternion gVRGripperOrn; +extern btScalar gVRGripperAnalog; +extern bool gEnableRealTimeSimVR; extern bool gVRGripperClosed; @@ -936,6 +940,7 @@ void PhysicsServerExample::renderScene() if (gDebugRenderToggle) if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera()) { + gEnableRealTimeSimVR = true; B3_PROFILE("Draw Debug HUD"); //some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift) @@ -1157,10 +1162,6 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt } } -extern btVector3 gVRGripperPos; -extern btQuaternion gVRGripperOrn; -extern btScalar gVRGripperAnalog; -extern bool gEnableRealTimeSimVR; void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis) diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp index 603ad167d..a23ee3d88 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp @@ -39,7 +39,7 @@ subject to the following restrictions: //temp globals, to improve GJK/EPA/penetration calculations int gNumDeepPenetrationChecks = 0; int gNumGjkChecks = 0; - +btScalar gGjkEpaPenetrationTolerance = 0.001; btGjkPairDetector::btGjkPairDetector(const btConvexShape* objectA,const btConvexShape* objectB,btSimplexSolverInterface* simplexSolver,btConvexPenetrationDepthSolver* penetrationDepthSolver) :m_cachedSeparatingAxis(btScalar(0.),btScalar(1.),btScalar(0.)), @@ -304,7 +304,7 @@ void btGjkPairDetector::getClosestPointsNonVirtual(const ClosestPointInput& inpu } bool catchDegeneratePenetrationCase = - (m_catchDegeneracies && m_penetrationDepthSolver && m_degenerateSimplex && ((distance+margin) < 0.01)); + (m_catchDegeneracies && m_penetrationDepthSolver && m_degenerateSimplex && ((distance+margin) < gGjkEpaPenetrationTolerance)); //if (checkPenetration && !isValid) if (checkPenetration && (!isValid || catchDegeneratePenetrationCase ))