From 94b19538a0d9475084a6842a0cf3266486ba4625 Mon Sep 17 00:00:00 2001 From: Thomas Olive Date: Sat, 18 Dec 2021 18:13:19 +0100 Subject: [PATCH] First commit with everything working but - functions are messy - the RRT algorithm does not shorten the path --- DrawObstacles.m | 28 +++ DrawObstaclesFct.m | 39 +++ MyFK.m | 4 + MyIK.m | 7 + Sans titre.png | Bin 0 -> 205622 bytes Sans titre2.png | Bin 0 -> 464014 bytes buildPRM.m | 204 +++++++++++++++ buildRRT.m | 166 +++++++++++++ checkIV.m | 19 ++ checkingLine.m | 51 ++++ licols.m | 34 +++ mainPRM.m | 18 ++ motion_planning/.gitignore | 33 +++ motion_planning/LICENSE | 232 ++++++++++++++++++ motion_planning/README.md | 2 + motion_planning/create3DRotationMatrix.m | 62 +++++ .../create3DTransformationMatrix.m | 39 +++ motion_planning/createVisibilityGraph.m | 34 +++ motion_planning/dh2ForwardKinematics.m | 46 ++++ motion_planning/dijkstra.m | 70 ++++++ motion_planning/drawCircle.m | 30 +++ motion_planning/inverse3DRotationMatrix.m | 22 ++ .../inverse3DTransformationMatrix.m | 42 ++++ motion_planning/testDijsktra.m | 22 ++ planPathPRM.m | 67 +++++ planPathRRT.m | 32 +++ solveIK2LinkPlanarRobot.m | 56 +++++ test.m | 37 +++ 28 files changed, 1396 insertions(+) create mode 100644 DrawObstacles.m create mode 100644 DrawObstaclesFct.m create mode 100644 MyFK.m create mode 100644 MyIK.m create mode 100644 Sans titre.png create mode 100644 Sans titre2.png create mode 100644 buildPRM.m create mode 100644 buildRRT.m create mode 100644 checkIV.m create mode 100644 checkingLine.m create mode 100644 licols.m create mode 100644 mainPRM.m create mode 100644 motion_planning/.gitignore create mode 100644 motion_planning/LICENSE create mode 100644 motion_planning/README.md create mode 100644 motion_planning/create3DRotationMatrix.m create mode 100644 motion_planning/create3DTransformationMatrix.m create mode 100644 motion_planning/createVisibilityGraph.m create mode 100644 motion_planning/dh2ForwardKinematics.m create mode 100644 motion_planning/dijkstra.m create mode 100644 motion_planning/drawCircle.m create mode 100644 motion_planning/inverse3DRotationMatrix.m create mode 100644 motion_planning/inverse3DTransformationMatrix.m create mode 100644 motion_planning/testDijsktra.m create mode 100644 planPathPRM.m create mode 100644 planPathRRT.m create mode 100644 solveIK2LinkPlanarRobot.m create mode 100644 test.m diff --git a/DrawObstacles.m b/DrawObstacles.m new file mode 100644 index 0000000..351ce40 --- /dev/null +++ b/DrawObstacles.m @@ -0,0 +1,28 @@ +function DrawObstacles() + + L1 = 2; + L2 = 1; + qi = []; + q1_plot = []; + q2_plot = []; + x_plot = []; + y_plot = []; + + for i=1:10000 + x = -(L1+L2) + rand()*2*(L1+L2); + y = -(L1+L2) + rand()*2*(L1+L2); + if((y >= L1)|| (y<=-L1) || (x>=-L2 && x<=L2 && y>=-L2 && y<=L2)) + [q1 q2 q1_ q2_] = MyIK(L1, L2, x, y); + q1_plot = [q1_plot q1 q1_]; + + q2_plot = [q2_plot q2 q2_]; + x_plot = [x_plot x]; + + y_plot = [y_plot y]; + endif + endfor + figure 1 + plot(q1_plot, q2_plot, '*', 'Color', 'r') + figure 2 + plot(x_plot, y_plot, '*', 'Color', 'r') +endfunction diff --git a/DrawObstaclesFct.m b/DrawObstaclesFct.m new file mode 100644 index 0000000..3c17943 --- /dev/null +++ b/DrawObstaclesFct.m @@ -0,0 +1,39 @@ +function M = DrawObstaclesFct(x,y,prevM) + L1 = 2; + L2 = 1; + qi = []; + q1_plot = []; + q2_plot = []; + x_plot = []; + y_plot = []; + prevM + if isempty(prevM) + prevM = [0;0;0;0]; + endif + + M = prevM + + if (x^2+y^2 > L2^2)&&(x^2+y^2 < (L1+L2)^2)&&((y >= L1)|| (y<=-L1) || (x>=-L2 && x<=L2 && y>=-L2 && y<=L2)) + disp('obstacle found'); + [blc, qi] = solveIK2LinkPlanarRobot(L1, L2, x, y); + M(1, columns(prevM)+1) = [qi(1,1)]; + M(1, columns(prevM)+2) = [qi(1,2)]; + + M(2, columns(prevM)+1) = [qi(2,1)]; + M(2, columns(prevM)+2) = [qi(2,2)]; + + M(3, columns(prevM)+1) = [x]; + M(3, columns(prevM)+2) = [x]; + + M(4, columns(prevM)+1) = [y]; + M(4, columns(prevM)+2) = [y]; + else + disp('not an obstacle'); + endif + figure 2 + hold on + plot(M(1,:), M(1,:), '*', 'Color', 'r') + figure 3 + hold on + plot(M(1,:), M(1,:), '*', 'Color', 'k') +endfunction diff --git a/MyFK.m b/MyFK.m new file mode 100644 index 0000000..9f171a8 --- /dev/null +++ b/MyFK.m @@ -0,0 +1,4 @@ +function [x, y] = MyFK(L1, L2, Q1, Q2) + x = L1*cosd(Q1) + L2*cosd(Q1+Q2); + y = L1*sind(Q1) + L2*sind(Q1+Q2); +endfunction \ No newline at end of file diff --git a/MyIK.m b/MyIK.m new file mode 100644 index 0000000..4f03836 --- /dev/null +++ b/MyIK.m @@ -0,0 +1,7 @@ +function [q1 q2 q1_ q2_] = MyIK(L1, L2, x, y) + q1 = acosd(x/sqrt(x^2+y^2)) - acosd( (-L2^2+x^2+y^2+L1^2) / (2*L1*sqrt(x^2+y^2))); + q2 = 180 - acosd( (L1^2+L2^2-(x^2+y^2)) / (2*L1*L2)); + + q1_ = q1 + 2*acosd( (-L2^2+x^2+y^2+L1^2) / (2*L1*sqrt(x^2+y^2))); + q2_ = -q2; +endfunction \ No newline at end of file diff --git a/Sans titre.png b/Sans titre.png new file mode 100644 index 0000000000000000000000000000000000000000..26dd3f19942a17b036f70d04b4256419da369c41 GIT binary patch literal 205622 zcmeFYWn5Hi*giTmNDGM4h=K~z-KAgvDk@5McQ;5QF(@isqJ(reLx;qmNXO7a*T66^ z%*{HI45&ff9(bWQFUJY;PpBc zn1evLuMbp}o_iZ^XOMW)-(&9q&nwY?Ays#JMz6GSi$kLe|N8ZN2}}6}!BN2+q?bt5 z-%fcS`sQ>%>`!?Sw*ZtaOU`be+c}Bjr_`OY<2oIrWDZcE0v>q!|uIRxN8;BGe+o) zJsVmi85W&i!2L+=G_sdH+{$db`G&D<_I%>}^~H_)lzOL{!X#@Y3tuF^LQ$ z1N=v~A?COf!`@yr2~?I%x=R2BpTje3PZ~=6^B_35`JFL#n<|DrNOzbbu8M2{rdKC# z7ySdi1ud_J>TduCwu3gJIKPip3}8`r^`9b-{zB@ zYl3Bh5D9c}3C*U_+k0c;W%H!+CTy31C3ewuZSDEr*A9J9)zCW_YNDr=x{OFw$Y3T1 zwxGp^Sl$XbNOXzU<9jB1Hp~_Q=lbDgX`QYC%BW=-5OYD>X?tZfEahe3zGLGU8=F1O zChDk3GK8ov#JfbMT!XW>c8nBK<^}=hP_mv#D8n+(GE3d7FQ@=1tD(JS3<%g>Cn1gW zE(y%&p>IuqpIXypPK-SELxUfSe~j-zc>Z6)=A@B(m)Fo zt4_wJ8?AtvBFPp^2OcAbPbs~MR7wZX<5znPrWjl;yw(}q)c(4~rMlF#xdQ~%zVJ!M z4BW-JE!YpPS4sgBD_x6j<`_&WSK(%3XnhO{W)HhqoYe38zrCdaGC70Ec0NDs$+V&iP9)>B$IYjh%!lhS z7S~h80~SFm<5Gl(3v~=~HGa2rvPFUUz4}xVLA>Brbm-t+U~|f{w>xh5NNQe}f1IzD zu-9e-t0Ln#XB_ZZ3~W;QTawaiJflPiIJ$l3MUN7cP4_QxuKq1fje4?d4Jtq!J-M) z?&*s`w%)DFh=@|rwK2esa~=`%vy8SJ2$U#bcTOnthnaf~8hp0K8Mna6G8fkF{j7d$ z7CcKxQ@B#MBrXYjq`G}$(0zdz0q?6&KgeGl9FcqsB4#Xw4a!aP_QSSZ!E>8I*l#{Z zY!U+DVf@U##*R3{M76ZY3o}0W;#}0wY0>neEpjI^4aD~lmO<9$YDnKl$N~IXHSV`7 zn&N}f2!``n>gD@`JsNuK4cxAGoCW3B^};Y>SuJi@as~Krb9_J>PS!TroWBs4;Rlzo zLzg?8aDxzaekA)vByj?C!58`w`|b2Pbf8zhNBWyeTZ!i_yWyP73P#&9%TGq;7Y1ZP z`R}I4PbTv%D9`Ax75=?(RSSGjL>P7M)NDiiJv=V#QnhaO7$GQKvl>fJ`&R^sD)=pe zdNI7d zN*7(v-?4-)g$y*?cno8KWJ4LzYs`?lqqoW=@^@`p7W>+tY!Tx9wIpIP5m3Q9!wa>1 z2i$Gc)zVrv`L9q$n@g&VSyabeczDO(%Ks~Dbh*9x%M$)Mae!Qy%wK1j1oji9u!O|_ z95Kh5+#soc9}V!1enJkOe;+6Mk}05-{~Vd*Jaob7|2}5j7R~Yhdv`znbP~F@*`8YG zwq580VxOH~k>Wrl+V9_SqqqR_&|)w~|J$dx7^0SO5E(j%UQI+5oK#CU7+Pr zhKxY~6uQ*ntJchgozFd(B~6-*bZam}aY@FhI=hXyj8@R*qNk<#0 zD7PD3mZ#IpcHOL77Ss1kuhM#VC5-#suHk|#6G+EUFV?xGx^Ps6nlQVy`jQfa{dYy9 zF4Pm`ZH0yDvQdJb4dmy1^L}N=Iumgup0oiATwy0h$)l2wPn+b{>jk$9+56@>|E&q0 zlV7u)X&|;@9Hg^hc6CYuFN~F9E62Gk|9>e%WRK02A7pR5Wis74H{bnXT+56jIOm*8 z=IY`&Y33PzU;n?3Zu%3_d;z>%|2-;t@7dxD&NO6{r|+w$Z`9CzqGQVuaiXCekosR2jy)h4_}41> z`{fw_-x;Ic$dvKFO;$>(;nki!WB5O&e!#-R>9}+26pNG+7I-N$|z|sepFXK zU2i)?*U4-x}Z-;D2&@cD4=M+j4G22NVxaEIJ>`>sMOs?RG|D9)qu6 z|Fd;jJJkU~=f#fjo6P>wR7P_)UDMYFJi{{~#@Kxt7C8n{myP)xH!rYWp!0TRXl~Lj zyR_5Ef|N|%wwz_A3wX${SS|g4PmI>p`VfOY$&z$gO2GZlkfAP~+^(AG-9sJFsl~HQ zRay)bYUdAX?`8FFo}MD$i-53N6q8(KNcf+_91I z9$ROK>@Ai488|r|Oj%Ox6tf>=T=8NIPL1% zhYy?A_9{M+zjD=`A2oY=&5p`{)ak3wR~gwy8b;+oIL)lw0B#3c30IYq{ux|y^K#M; zJzeV8P0pBBGadp7$64=llnY`T-L-U@HR^dT=H``O0d8~alFA(L!o4Z+qr%BMc4~Ew zd$DYdnN&|exx}&FPy{8jc)FxZM>7XgecY|tK3r6gVq0NCf}2%{W|k}wwE$rTrL@bT zJOaEfLZ$GnY#yGyyP4W1ou z>C956NjQlMT=^Z^4-{1aP~*I~^x4Bt!Co$Bxj;iD3Dxew3OVi^r_1M?KWO8^7vGbT z_s@ZTms8^PB)N-_uQG>kgwGIk9^nc%(lj+^yj>5^%n0CTvAWe>)88;HR@;s;{<#-Y zQXewwjXy=9ieWD6brorA_VS(!zrwp`;&F%2ylYz+Mkj?ai{^=fQU7;2!43t#~oldB|G!hPf| z7l#3P=e*U*l6NqqV*o-+l7LaG`^HjSnnY|*Q0^)0=V8#s_Zovp=sd?nnGuB8YiD{a zfkX_?eyZ~8s|wSb4?o;umz(!qj&oi8p2Db>791QbWY)7iSyO3&xt@|eDKn?CsaAvgC0SLrC;TuoIC}wCTXfq( z^gsZkql}oz#~^rxo*vcwi0^s?o3>}XZlLw|?&*PB zV2-=%H_=|~G78L@;HgUU+`YxlNI*mk8c?}3P&PaV!R3kbTF0e1Kk`byDmX#13CqEC zJ_fGpP;E2JF)#!6>9Jw$$$2<=J7C& zgR;!v)8|z+qbOFT9L6%ENEF2N_|EKVLc&5PwJm-ylb2|p8kxJyu!Ps=_Ad_--(InP(c@;F_QKQV#5nH^+u}eW>-(D-6Ic2)4SU!GybU3BU;jsx)gf>Vs%iHk0JwgpxfRM0G^p#IUJNTaX^#? z=0B7kw;23%8TNQXeBQ37u@hstvnyh!mA1%Sw<}-mFjH&RE2|-G-M)CbQiHWa5|+Xk z>-$eAW+MXL*m-8@wjx&cyIVuAoYk^6Y_!WNc<&oW(r&Fe$+;~2>dsY4(jqjHy5_&y zNrmX)JDBs5b?=GDHPd0mx=cpMwMN!C!Ptg2hyl3EZ_w(#*m1fwQ8p(6N-n|OM+dEc z<<0%XiaIRwD2Z^Aca}v>*AzuyA+D>34OU}>3vhUy`^L|M<=!N|*M}2EK?d&N>-XNC zqn5!v$l}*khC!HP%?xQ1zn$rtwU57JD6OB18GbNd7#8QT(s-q1tz^2A-EsHM9;~+* z?buc8q-MV-Xg~C!dnRrfc9cA7aTIZFpd}Z^XpGc_m0|UT%rl{V_vB;5*@eNNYnAvJ;%`iHhYe?;S8Aoe}7#nT@jz1cM)=*Uf7C|mkxT3z7{HnJj&n6$;rqF#!g&nSSiv5@A83wbn)Ve3_9*!$k&y_8kuLNJ)XXAth>n-R~Rjm-C=)pCspI|Wa_WhFgkiv3MVlYEyIbPlr~C2ZE^ zaQ+Ix%Q!d_-j7QB;`u<-UW!ZrI8)C3eEWyC)llvUsid3Zy8a#(LG7NgHtOwa$<}>2?+{H*jRqcoLU?2aB{pdFpZbZ*8o(Mf9-gGjp}|Br;pwd^SQ7Mg(5=TfqelO0yGspj zR_yjq75@-XOZ{eIc!Wfe<6E*@O|&!Lyo_*Ic3S<_QafG`1HG>^jo%<;BJuuhZsP$W z{xggjR%mwc_^%@paAr!=ZtzLFb`#Zz!--sj#h%M~cYunDz@VO2_Q0z$Hf=ADwC1Xr z8;zNx&A8#=2nzE@=H)s>l*+7l-8josv&G+6@Zb2^ zJu;F|q*FF40#d|{5;|kfj;EM0aHm6v=ZggfI z#fQw0!;$3GNaCS68Rzl%#5e75sF9@W;r6adJ`zQ=eL%hfQ^5n0R%+wViNEFC8A**k zJ1d>6gbYZQZ7|34&$*alTH6e@>ypkqzh_I$Gb1x~YY{8;A0r#%=A4h#e;jX3sF0-U z+$X5ZbdquQtqU5756x%)i3la3-i1MeHn?H19;b|kgZ0lPz4@h5q9zS{fZuPUpgls5 z0@fU)&YxL4LXgFFAP5nK|#0V!4BeGO2Rsk>}wkqTyy6KDlUomjJh5Bqa%g=0|hzf*1bLkwTQcjNam`|^@RpMhpn3epcrkOzzvsFt9aa(JJT$eAGg293X(pZ(@$Oa&YtgE&z7>wqL7TT;CjX}$pVT%eP1 z#O4=q?^}?=8UIzW-mSr@_01qfx;9z%PC`N7u^+8f$YI?o*!fU27anJ%Ryc7+Q~9p} z2$nr_C55EW2dGi+>eZrH<-}Zfk(t`HTKYcDYs5IAM<-f(TN3_@t@DX3FP&uQS^OR6 zn|%QFH0C;@05#YMJ#uWEx!- zZsfHZ8G+dV(n2jv5RllbtU^T@FNnJftLmbkO#>;aub*l(4ffA-iQswfAi;rX$Qxk4 z?uEGhRcvPx8=IsRbZICMuH2zRLYNi+^=6fALOdA}Fsl_`ZI3ofdp3G9#<=BJNrE3dYsZ*Y)=;HtTZ#F!|8fruMt2=D4FOpDnLMyvhC<{&@on| zLjj~y+{YrFz^l!*mPy@|zI;U|y+0cv0;O{nCWTJ+5_UJp3GJAf_T-ejh6GNEq>IQl0j^Z2dxKyrx=$)3tp(H@tv?Yca@#YhO+YP zIf%J#d4-Nc4TIY3U=?@KnuGJsU$#~P%wDpT&bSS!&Ar43*`)bYT$H&NkO+vFDv?wf z(jJ$jSvshLz-)4jj&qGC(UW_ay9nprY| z(kO4^{e$3at-ut$>W!{KUZmoAmI5`SD{?!<%2QfVbpnV+-vFof+Jy?*Lb)S_T3QaH3vnRPsMMNf65x=D2(Z$K0CR-It+3;&}EAch=Z4?*Gffqh!}k z0UL0fALNKChHs9^oDap!(S9WZ5t5Mj`T04`HG1e>1&9lv)J7g3hugCOOu&lZ{WvBf z7fJW^5db))Cfx(~?nt>8FG^uM-1;m57ROuO_sH4`8cE5#=3@wgatALMTQ880;DDXZ zEqk2-z#Pd&C3*$t^%#2+fMd9qrnxO=Bhm#~%zRDP_U%QHZjJ3&wo>T!RFzJN?(vqN z`EYuJa`>el&qQtwVTWCg;lkwbM=}(-D$g+ZF&Ow53eebwRngHb%p~gw zrLEhi%w$&xWC>a?Trm8W-9LgY_0T`2h|9b5>Ku$>^&w zH69Sc=m~HZH&t+*$C=Gvtw*C_$9mZ9G?2K{{A`Qg2~Zrvhtlc*e4nxR4yd!h3fRd> zN5Ei_+f#8yfY+KE-u|cRXDlKEO<#V70E*oC`T3EjcH_mb8{IdGr`)DbSVoVa;X`OX z2Ml`MX4Hybx7zyja1|&*fLqB_uLG4e0Re%Wm#T#O_S-l=UCLLr{&)4N7zOmEEc%*X zhQ17xF?UORqsN5Z8C!5F^TpKtI<*_kZy6674|p*V^wNIjfgXXo82;M$r3EEhrlo5k z=RgryUxU{XJr^7dl3jZzxIpmyELq4b?{P{9<#~pjpLlh(RZ~yZ!s&dA-y+YELURUC zImTWSS&+JX^NiL5N=U;*<9z3a=!*V&_d9Y=9a|Bu!TJKs;TpC(2FRoC zk12!KON=0`h_ZjmrKV_Od{Q#9HyvRsz&=@HJ^MI!0AsfK)(V?*%kEuksUoC?liTuvl9UDr&04FR>QMN zmEBe8a(?3pBN3M3vTquD$^dLC<8!#u9!dffUJE!N+~fff%zjc(-P&G7x6H7G2~WHw zrmt$_6hJx1us6@isi?$T+^z#$um9xU`RPb@wg?Y?XkO`2$w}{fEg1on-P;LI7~Ore z0>GP%T3MAHoR-24Hyy0nk5ig`w&uAa$lCVyIY-N)yv6Yp)2W$63wkkvrd_0nCF{`S zS)h-JTwHlBj;|~1brHbP@wh3 z`l~+~*_iWdrhPst!!tXt`8(iuX?G3jgGT%lvJ;MgQZBsX==gXJ@NGbuIR*eR5Dx*| zmBu@v=1G1+VZyt2WV+-Dd6K7q5!H|EUunIDfICnSR0a)vx;s`BXZZth;CrrrZw8ie)NH$A&d2F->q z_r&Q{nn%y@gW4QaIXP<`XP7QCnLZ{Y^*Y{Us4tHO0UV{om9}ys4*e@$Nc)kzp)@Ks zS!-W-*q|Y9H)$%rFfor@oL&4k8JPL z)zOBlQ&CVH&FyWqFsBCQ`!SLMq6Nq?JUl#gK0qlS_`1Q;(vaM+6hBmgeR+5Rf%Pvl{Sd;-E=kO5dSQRdDd z;x}+m?z&};ACgk zoo$s>Q~r5TLxon~%8v>bD+j16}6dyQUt@lxqTd!&0s*!L5ur50OnxI^5^-^-Ig&6OI_`-CX?Y=jfA#Lz7#o^B|Gt%!s6Fu5KL{$vzva4 z9cYJI$kv1c3aWs-`DlBlc8Z#{GE2$~5;%8+Oj!cDo8gxjLcR$AjZeU_cwc;@2cU*( z^ks*+#xdDWvJx*~aOgVs|CktgXT(!@Z``B8EGZE*zA=|(x}Nw9YbPNHlf@k;XEi+F zvNU){AJvwhH4XEF8dl$;ikP;4)Bk?%;fJWCwn)^$Mmb)RWQClEEtQ)&zScTN<--mX zhX7zrL!bN>%dJ0RDc_&Aqu-}Fjfjohnt*0Xxuu1XS#dv5#>?WN4vJ%*Sf_WEDfVh3 zN^?jY8XvPn4_fkq3eN%7NWaxyA#iqg$HA!PySz_jix#`gif1S>(spdSJ7xy4nk&We z;tmr%1%cAx3X=XdiqR{Y9mXcWRyX>!3f^ZT@T|+Q;xncSx(y4k+ME0_-&7aSMT-7a zxNTSNQ#Cg+!A4^YaqXrE5`FVaD^+ykV^q?M;#ah9E=a_a&i~ssoQXfPPRl&KzPa=5 z#f|{vv6x|fxtzs!i`&|3Edev~cAr{IRM6xCljIE2xV5wxn75hDCqDTHiH2|Kde^y} zc@3L`mb)6#gqGu=3RdK}*#=~1qz060c}=7CT&3S>(l|>3DsLIv;$-9(Nrmi*+ZijG zdGsOs2WNmUm0a81_cs>jM)OwRQCzd;QcsM?3+sxud8nT9GxIiG$yJMiX$4fU+ckgm z-Ig}G2E@^;R!`0YX?fvMSFPW+M^1$epUhQxMC6YZbo6LB+I-E50Vpm*$0!Nt0lRcZC zlZo6lkrB^0Rp1cR=N4ln^;O*a8yiougIiu#k;dQ$TMTT&{8heY+#bD_RwFO2uYPEnaFUt5VDa=KVar!DZq!iJ2hml;Jme4T>i}T$U?CK_8H5POb&G7=dXK z%a!VoyLzskis>x1!wXz%k?h_^DmX^|!89gLG8tDf&Gb2o@7u4d`&uo?cbLR%W5JAN zHbpOa0?|X*WiYaCe%hf*P$~ECwv0@5A41 ztlK4s-d20D;1k18rBgcSa%CuWD(I{qi{8@@aha8jPkvR^(`uK5>7zxuqxKX;27%by zMZonZ>5$aeKF#CS8m@H#8R%AVOI)JQ=7WBSZrRc)E{7&7HO!Z?2DuL8Y1m(eCPuoE zC?i#%di8FRu8g+0lDdMdoP?aOqhE9HWOtW-Z)Q`y0SreOht$rcaZ4^~X^&)9n<@<8IUXs)Iw%Ar3>x?r(b^ub!Ur=PhS zo_>QVHN}c#REgd-sVYksitb=Mq~lz{ewu_8`BV@$ZmHh>a$C|XUd<6!D_}T?bZ~O|Hi|l!QjX8cwvShI875b9*Y#Q-SK8%U9(c`gPjEDti%Bcivbw5IIyJFm!~ zCM;#FtKzDs=4iNp!fHNHH-Pohx%RYT9nw`Du$Z7mX0?D>=|QmP@_z z_9Jf!f4#?(1WXU5i0nm{{vSvu7>we38nQF?WZ=m*F~c3_w}GGl?3|Z9RO>_3Gq?WB zY%KEWO)b7IGa`V;1)<|Ev2PyDIPDB1rS;B*>|MU$lE_`ndiDF2&66=5sm`D#Pkp{@ zZ5}jFma{DWjf1VS83?LlzD1^UW6$YqVK7gl+DP%9ith5csLdocOSDk##kVbSJxG$F zvssDz^Z`FSm{@ZVMsHo-R@$M@-&vQ?+?Yj=ax(4ofyxQJ4s`deVsiC z&9q3v4QFiM7xLmqt5Gm@^{NeW#BKh{Nm(wbnPE+lpoG07(sjizY zKFj-}M3_X+YgzU@I+G(V5Hp6IFhT}lP4cO~OpKRoZ#bWc#$62OnqK;ovjqj|7m|!z zSAhP+no?AoB7wN0=njG zCv7Pr`h#VG0iIv9(kJaHpr3}Y2fZx!6zr}vb>WWaI`=n=>~9329ZI>Q61b`fNGi<~ z*h*AL&^T;w14yshSlb7Cz7Kc*`2~?G0SQescwHB-ayb@DO1iVsPwJ_aR$?1|Dc^NP z(2PTyJHlj1HQvtqQ-e=pCt-qOlV=52&-p0@B7rlVIiw<9@upm#A5lk?< zd4Yc!{`eLiM|Td0b0-@YgiT?^qo88@G9s2N{juc$7;T{s6Hl8H;%EEDmb%~S+pF?U z`KwA|zNSV~XS$UBzJN4~!f-p%W7FAI?$(O}m-=+6LNm2EQ^;8y^OW2odhhm=I5tA> zFx{G~9rjb!8o_xO)H1L5Oo^n6BhV4xdGQV7b4XFV-UZCb#QG^UQC&5TT><9c+Ugxx}+Xb@8YxnHOX52dsY@kgT}yP ztJ3blMCs9$jY@B!CVLdh`SJJF0ZYLP2~qqp9Z*(4PyET)Hy2rdSnCHXs!NP{f+7Vv zU^8_4Li?|=5f21B5@T$Y=u}~9Uj%`beUGNIFDiTWPMA5>d0KSqb7-cN_lUgvExqL` z%dZPs3Bk&uUXGid>O;a7)<&;t-uA?V5DhheI%Dy%;(7@~;xm@$ZcAS4s=4Z^hbaUY zhgyIV96j+{*mz5SP%(wo__Y19Czd68L6#0r)pct;_7=*isv->|vp0!8T8t%wGS@kY z5U?mX!kUt5uNIsYYEKDd>j)r!S^w(8E=F#P?VoK`Pk+&Zt|vN}4B zqN_DuCKo6-Q!dqKxp%nRR4v1i%e1V-t?}8!w3B$AykULmo(KitRxE!K_0o||?X0+c zU*ItfP^ebkn^TIUawnFgdr#qe_56Uu>Rae$ri{dPogfE7*lO+ZF*V>y_LQZ%A8pHD z-YqS~fi&9vkj|SjX1C=@2kKo;tx2D4{z5W|N$Lh7EYZwPBMEppjWc=L&W)g8>GCJe5zf6zIK-gEQp3?Z5Va~U)` zcPgEuW)&}AFs6jeQKv~pYblZt^9M||t*DR|p$%IBR+S+p5{(+$)(y)w(Wvw z{Nk7@>^jFw{H4uAn{ucrqfz}lqIA!{shW^!c(2p&Kzq%`3p*KTIOh=Xx}dY$C1fI& z&WcUp22GMf^5^}@?_Lt8OS$EpCIVc$a}?oca<9m&2Z=xZ_eZsk_BY3hfZ<&ahUdUw zCYX*#6KImcqWf-jg*Y!BTKFk~mPZF-8obWjk+)8dC-zflFA^|mS*xwCPr{ixX>J`U zi+DM+f_&myH{q$@dk$C|muMZ&m8(e0xeNI4;SUF{X z(NqT*ov#l+CSWe#d|1ukq^Wv+ph7vyiUr^!{^leUcaDZ_Se>SWemOV7qZ%{radPBKt8CxA$fNVn@Ja?~O z3Bu*>v>BtEA7U7IC2a#RzMA?;@^Z(Jp`OG=w{Oo`#()Ul8vV;}VVD(pH%m4pgUGp6 zXrqnUsa%TbePBEOL#0qMx=9&Uc}4R)&7lTj2}jYON*bo`npgH(th7=NVdZ+uWm=zA zx%i&h0nE*a82}?hPP)xNry_z0f}3RBGT;#Z;A@4jQa59fZqp z!!vEt=0WI$t_^88*gNlYtR|QV`VXb*mkK<%T-z>9phWe8Lh5K=QK{W+op)X6mZ-JO zMBs5fZP#R;2FoX-hDx7(q{F2KkFEN%;0o`>te{F(HuHXE%y_-fYWk0g*(bg<=TBTl zoO;0s(NMdI`cK$op>5QYnmc7;z9Ltwh3Qf>MCcD+sRefwUZ@a7I12l{1$Rox;4hd^lA7OV`AX=*%2P*0euTA~jh zxrKyYzn2_e*4#lw)c?LB39mBIL`D#MJ(QCGa&#GCKHu!W_dUrflHN>+Xa(xBjFR7- z8~Dn;XLmoAg!q|)&Cf47*Gs3KRG8i~@5s*PFq7cxO$EfK8VkJf^*4d$JzS`l6p;Vu z<7e#ox!b1aEps(4Nc;KeuRFlJaHqHyNy6$rNu|}aC?cx8KQX;vZ_aB6jZ9Hvd*9?W z^#afK+MS}u*N8ixOiP9crppi6kbnQQdUi?-grInW1ZlC}K!V=U7vF%UN-YvGaa8clAoQCM#xuo^C(}4;#G@rTM*epOv2) zX_MNP`^IYzR<1P*jD0(3;e8(UDfehYO83Tt$xX6|#Wv^3Zl&`uI+iNt=Oy2DjsZlO zA%j@GhgEth>)I8FY4jOgPgDrPo@BsQ1c6Q>aZS)j16=Fs{dh4i;1vMEf82S=hj@vQ ziQtS-mr*fpd$!;3KqVp!;}4#xD^%e_%s>!S$5rj&!#7TfCesrOc0~Yo=Phnm=gGmvVJxd&_8KUKgSoJ-A3_a;<03yRRZ*k;Cp~{878# z(;WOA7a*WRwBW;o1&(BwE&;>uPl4_=)-4602#~d=*MCEj1N}u4c{uRuKr?!`NucHE zSp>y3d7#Fgxc5V~m~iv6i5G^qn#&SS<3lX^>TPVs_8sB&!^lS0h!(R79+x z!{W&2h4s2=L~Kh=@Gf62!;9~4NSRczK7Myy&~7{}MR@K(<~ala zhg0@mE_Y=ge2PUZs$gH2zE2Dl8Sm&~1}GJJoXyXD3)RdAAEHu5u7ZtMR60xaZ7iRY zkWjN-aI`~~%npBg>1p#hGlSZ9fHzOENnuL=3kSn*g3+tSDWSE#IJ?#xpL1^04P~M9h^64KWpB zCV?I>Sg;gNjU($5pOBZqR8`~_{jZ|lH076HA3ulzIqH|44oyFnEZqHH=-}!WD+zE_7S}>H(I*is3i)H2SrGsQK+sMMrufAgT&NXRuDE? zy?HS&R{GnQm42$UC>tm$ zwP~rl>p0^d`Hbc*b{@0G@*CVbmT+1V|0VgQ2COwnZK6oK`n{VNG25{7;+yke2!X!E z#Uzd=UcrkPUee%d8>xHEp;J{;Pr&){?`6CsE6x)*S>yrogssgms4<4Rzc9|?Z2s#ZnV^6q# ze-P;Si@JWJ}MVv4Z+jvBFIph(_lb+%e>JYkdYOX-WI zE9$z13H>?e?|SdNTxkj(-KSLy>`WmdPtAm;NeGzr#P*p1Gp-21lZ*Com+J4rYsse# z;Xe%XM^MHC%=pMGe0vKA42D#eBXsw#i~r2Vo5`9e&PgVOU>}l{H#sm%@F}XxSkNVY zjDr;x~zf*6V_vO*8n*aDS0w7xSJ9|S!hL(HumMguSprtFpM+xt*^@A z^>3B|^3zV#{Rg$e2A&Pqb8$-$E>pgGM8=Tl-F|=ICnAY?6J|L%uKfi37g`~&Y zBhI#v{-=_(pvo(*`VkqhnVksYtNm)D;%y%)AH?ddE!*vQu}aGe&-jMcf?JMbYV za;i!sCWMMrn!_un&4_V~>7sG+FGIal$51cpa|pbdu?932*IK>hNy&1CyBM<#WZcNw zQpI+(^If@|=1F%JseDhw$11}=-Idy$PkEYK&}cREIljAA&vN)nY(>HDtv7wQ^*&{g zQdmMQnNbmxYo(#4-GddFe9a0BV%MNH!E38Wiu~Z0_uH?JPI7; z*=}A|(hvD?XQmET8<)t`e0=2|6F!T?F2rSt#eQUgKXan<5~3IE7D5o!!)PRm_Jj9# zetBKhvnyPc=54DF8U9G5Q?j(e)R&mB^`fX!iOq-DM=U7N@(Wnr6!(Ez!90m&Ma!I^ z`Qg_`Zfo(Gaw$6j{@ZnqDQrykQyn?dHb0-7a#aN!GYqM4NG4kr;u9tBR9P$^UF&<= zpXm05;&2`q^U1+6i`lM7pJrWj6aOvqiA%E(oU(4$?bnqnKqC}rw!Q=AVS!l}V2Ws~ z{QlKm&oiW$&Vb)CrTAt1TR~mNmXt;l`YCsI5c4zS`lU?bn;<2IUl>5me%2fOM3D1JC{WfEx zd0#V@l8g$PV!NrnJr^P&l9UWcwY8m>b({D|&bZFZh6B)7A`e2n#rMN2F z?x$08N95{zNj0ir((6j|_Q%-Z4m&6+nDg)4-h#R!bJ{XT$6*f6r@c>x!gB)v$<4ENwd;Y!)=HiHN zFmvdN2YH5c#j?;L?en83+BGGeeeI<#q+!e8TwieV8<1zQWW6Qj%+I(6OvdS+f~SY) z5&5mB9rpVYf~l*N``e_3$nB#mzV_pMt*Y@g1gw1eeYd22e$IL<>}Z68?U==c^KVG{ zCkrz_oKJonaPBSM5_mwQW?^PFE&8_6ynph}Oy$k84s^1xMNW#y6m72ggZucIw=~n6 z#Px!QJVgzgM|2EdzvtCqZO#FP{+gVf}bACoAPz!R&Pk1rvo>oE6028M^{Qo-Y8!^3~U3n za`nA+gZ~sAt-U(~3@q8fJKgdMl-{APKOHWMKN~ zPD$PN*7(8d_q3!_#Lt`a6}B%@aS2DHUxvo{G*U$w=3Is=FI~(PcRl_mY23yy2|3y8 zBJI{&I7OL#zr61Ai&4bNvW4A4zK^2seY(_Cm|iX4 z%vm;Gs+bwwlO%ro;1VNP!F;$@7?nP+Gr&{?w}F751MzeER>#2m5*WIIQ<~*T(lWmZ z6!(QtvwoK)_S_K$gI3aIyapY}`#!PCq|RJnl2~*0CBLitWK;333OyyWC7b)|2Cq2yEcb0o9T;DnJx2~S|)wjJf`OyQd(Peh$GJx=ER z{4?U>i6up}^N^oT4i=O?fx2UiqSAQc!{$jVrIteec|yb#AS- z&lFOwBUeBUVC&n4>HXDi`9ASP`jyU{1ChnAU&|}f_cml{Qj|AP<~qcuZikEEXarU)0GTjTrLa2btNl zRsBezHt161P)<<5JCZWLlPuV-KTrLWXj)8oyi9_T)|p6{?AnZnve5cX>q9xef}Whm zvY;JGqFrfQ(4|Xfv+u5X?d9#dHqC+zY1W;Cg4`y&@iJ0`Zz@kDzbGnLeOYG7CEIp) zKhtvHzSh3*(v|pmnn{Pz2(F!jTIKG=ZgBqXo^+T+NlmAV2PUDxBrJ@l01G5c84y?uULK z#Ir|S^5hJr^QbesX{%mvKJCu_qB9_`jHX2gf+0HvfBK+qP|+P0|KUW7{?-P8z4NjV6uT*qWGaY?}=lz4z`u`|j^= zxM$9}t}i}kHJG&3ao|H1x8-cH++?1A0FeLZ&vCT2V2h!qhnbBg#U`C74^o6Sm-Dl5 zE8)04o}ZW|hh)y?T20^~ns<`bZk5^m{>nknd|D`VAk_j)2DRgVPqG460ISy7`mhZi zgUsyK(}E27YD1{bGK-_Ya|wFm2%l}j5%B0J4mX3BulsaLG2y5@uy$alLm$YBPs1<( zi+qkh${mx?M#5T6jaGGvVAA(PXabonx1fJ|28}q6WpPV%bFR>nEJu$+J`jfQjIh4g zD0>2Z$JlxQxo86ic1GmUz#I*KrdLtKLokdghBtMOgXwVzF|9T(xE+;QC85I`t4wFp z#cbmjr{URp1Png*>j5qN-X}Vxt7W!own3Y#EyfV-I;)yuhp5shlSnOvVj424N2+J4 zHxcjhbyx~$W8>2WB*i~yB!Z*+(-J&Sn1<0tv{GeC6M7I6-RdU#juf;eAW6>J%_e z@HL67r@JrVpBN^#`ch$sd7aIN>!mP$e@1Zn2m;C~KxY~}| zt|p}X^cAm!Tpmlko^l-7e5pt3d_^>&(%ouXTIsHk@>2u|DQX814h0e2%3oY^w8<7n z0JNb-tKhNJk~j;!oM^JuM)^kdy!vx@vqqOldJvD)=si~`t2^*nW6rqE%&6O&1MgDg z(uKLt$FvEiAEDAX)xk+Sc&RaB7*|pD(LoTFq?q93VFO%bO%RT$3rA!!hKv8U8Law> z%9YDbHa>8+oOO;R=hI6iv(&Y@y80U6zgX8aK6-cDoWN((t2z+N!40jPYC;tIn9CKm zu1}qwhcRAjsPcKwf-#s@z-e#S{A~{^;ASl2uwrsHa5ux)CQ+uA2k`Ab`Ntp>@W%_S z70RJ($RT2N%<8iPDF#gaEHQsCAnNG82Z74FWPV!tX&<%gxYEq^plfZ2*p(p>9OV99 z<#wv&L9)l9X%a?73$-BqUDJwT)P^5YXFP3J&?AxK!MYn{&K~%W6F%-@&16gR&lRP* z)g*T!Kr5nbp_B-CK5y~9h=0%LcO*{e#0aD`qjByYjbQ+lCYyT&9#NM#29Kb3i<5(y zgD%C~SJO%qmug|uAu`0tNHp?m8KkdG_6G%>UUc;ZeCPOh@I2b%` zBe=6R^SnP(Oj=C!s)}+CIxf~8V2PR>&yiZj7Zj32VN{fche}I@XZE4Mt#7pR(edUl zH11KQ(!v5+pfg=Sy`%tYK(}e(7_InQMu3!p2C_s)gC`;iEdNwCH{c&vFO{rS)z6J) z>{iM|U19Z+m@Nj5Cqrc(0&Mit9{?)9KjSKw07wnA#(>ysA zwwb?}mEDhXm>Y$?;K17Tg?|inMn<0eyg5(&-x%(1{ z#^fR3!1<#9a0P$2Bjfqde*yy@@U=~Cb?DjZNVp96b2)I?Unhx){6LBhZb3W7P_<#q z*(oxNLf>a73<}&3v;MSVd^PHG`*F%Tqz;B0>Nq+|I7oDEl$A_!RAyS{H%)_@6+Wxt zCT13-W#&CPmrmIR%LiH|7c%l8JJpcq=CGpbU$?OCmTz*#72?!qAwUS#UgDx11lii% zT`*})7{KCgP4<6H#@M(x^t_`(?Ow60?tbS-xqz4`*W zSZkXHTpM630|s=$<=s{1o-d=A`nGf7W=N9k()hs6F3o2TIzFl=k{ceOaQ`QXq4|AK zqaSY#(GJ0n1esrz{KP{0#5XpK|RZj1w5#hliTW3Yd)emQa4 z?sxbtMTV6op$S#8Oxfc`*P(l{In6vY6ss=KAFTjs*=*!D?(S?m1u?C*)U`eG%*i3j zfO3Tf93jpS?Xdqcu@gbV)b9CxPo5{4t4_;ZIdlDvA}2dTs0080HviinAJKsH&6X^j zC#VU5OG7Lo+BZ5DMa@i)W)NfVp>RJtjSv?yHu*q*i0MaTMx-+WygyN2wfYa=^w?4u zPchw6<6r+>Yb$&c0W-edeeSmLy=^=v+h?X_0R}JRKTxGLvxhxijw>2uTYpvZvSl79 z2&3I0yK8OBqUifCH{;C;viy;xX8t>}=@^z{S5-U~TM>*hJHwU*vBUAY_0Ag;4X882 zK02u{K6U}gZNVt{DR3b9M6-sVFsKw# zzHh$UIQYGKp6Co(17?5&9@1hJ4jYPcI_FDz`5B`WXF6Mn91KO(Sek9LRK2l(yjDs< zuvNF*u)jy(`UOS+ezHK4@O8hIr(BR1-yc~VQ5uc!L4l`DfW|T?EvoOck9RNG=W1|N zuR%l^G#CC+9f-OA_|K;tmwbi)O2!u^u)#^Pw>#8f*0jz=Un5UXlet`*CX{ZJ5TU)Q&j6zcyUkf zlBa*R2g0H-4)2HnZ!&VSDgWv90dYVhH%l~&*mF}HnV*rmL>pSuV>s^M7tc>SE`~5D zn92sj3heOukbc)YM|fbn(7NuGbYIK@%)^{bs?MU{MG{m!htt+gJ-17+l^!F-r;D}A z_6vm$Vf6yY!*8!NcigT185;QCg9hN!t1)}k7S31QITK7#IKg}T9^zwmv3YR+mbsI* z`*fP4KcE^SY+l)1b}9V4%v$eYTA+e#`o(I2C$elIK7YRq^NZ6N2M#Ucbao0#iJ2i) zNU0A555j-ywFMF|2;ThB4x3Z6$8^fsV*Q0a+n5YX@=9rJ;~1E*LT5ld9j|)LTDea=sr!@0700Lv&BSp*T;I_o6mrxo~P7kW$Dp%1>Mu*gpeuwO}|Aj zlY-&_;1SWFcfVz4P5ypM*c(rarKbX;CLX!bTYoB##iYjnpJ1dUE6oS&pm7{}i;sw3 z!Z9Rd16zV`_R`d;yvECvGgexh3ur&20O4{ppZfghohs-wjZ(xM{CF=zluB!oA1V+e z-}i1+ALVqH-7!35?5M0dH_H>cF!8`*OU}?F{m!Megt(m{nr2TC7~N1&B&?tp zLHz^!Kc%uBhUc9|V(!<_VPgJ*-w_#P5`@9uZ5JSG{F$Ocp;un;dbs;k;eKK8o#wIl z4*2}?V_TN4zjU{bn<>=&OFzPg{%qn7kdwp;~=RSb~;+MWeJXX!i4*zA4csliAafJZChMOK0 zBCTsOTf4p@fh+BEQL}maUl+s^xkRRouPRxLLukU@34dDeB;NNBai=98q`%Ak8Gat2 zNOjS!t)J#!Xgyu>ulxv6)W(#KRw;2M>67316(TeY|Qw|~@Kb}N&FOT}RGl2Z0McS@nfJ$g^r zfRY`KpAst}`FY%zSdDIU5sbV>A<%KWjJ?;plLf^C$MXTgw1fK2vsNLhsIa2gDCE-1 zX3xL1mz!!_&A$iI;#2cWK_gFvBQ5_u8^Bmz=yA+BULA^ED1h(_qKR+u<{FeDR+#Jj z93u^dO2Qn^xRnlQ`mSl3OV~u%-%=2?L(3g4&>}x=9rC+ch?v^bZWu#@v~9)FIrSM% zJxUXjx5_%l2AoxvC~Ki-QKj#9pWO*QSXJHqv>gbmMe+TAJ`jBz)#hStL+EM?hk}3c z4Hm;xo@`7caDNGZzTBumC>%~_&lA(Gh2hs9Ia}^AYChWdw?KX1vJG9mp5#(F?{A~a zY%Cs7<-SlPHoZx2CN`N9#Q}vVv`xrNf!&Y3imumEE}DR?Xg1;yN)F!n$vZ0o^8{5C zo!jZnAu=a&nsnLS^vU@cU==u&41W%ID*I{9Lypk4&P}H0!ihj{F`@VqD5n-eh5w60 zTLa<=oifh}WDcDX+T;hy4>!fkk+fblw}}E5KmAeI*IN6ym$^7sN1_BmSqEuo*iIH2 zB1u_wdZ~&1E@wk8U%*hLi0Mo?`vQY6i4u`@veB)=K1nDwapZt-J;)p`kWX!?WQFQr zLV$3MW8piUKS8C|hIoj=p_T;%!}Fn|qs)dL4Q6t8N8CH%Q!ubH1-V|Oc%`GM=_@|+ z9M<*(-yQe&oB(hP*qc*asRGw*I?e z2S3YX{vn3{v*Vv9)WVFl+IjkXoWfQ$R>6PM)>A4hMNn?)qbUdc;3X3AwY7Vdx0f?a zaymh@vTrPJZ>fWizcceGIg`-(hn3zOS2fh+_(MmxE)1C|7*&-!j%JDu>;m9de_h8= za_8{vA_g2Xc+M1t2>lS|kK1^|ESPbdslD24qMXjlNj~1%O+1&0%v@#Bb~_NYjw8pP zX$Hg&1gLPXF(c(iswuM1JmS)rSqh0713k~|mpQ_GC`q_XN0goJ`^7_;59dqCRXsLX z@!SOLnTzs~w{u~~bLt<6d1fufhxGxsY-I1@SO($gD>dXu7W_=FGzg+q{WSRk7%p}4 z@q)-OSy0AYut*s|_F?LLzCuAqcv~07Hr@9_#0#Nr3zU0#YVl7HMb|!UQ!^lL;(Gu?y%+E}dRPSf5N0|1bNxYRF zdXXOOp|GBJMi&cACr_)gtX50)SLOZZt68z6lEah=Lf~STJM)JLRS8$ppj66|1Bj_3 zZp4*jj0G!#T6KCGG6+_6w)kutx+rKLInn3f^+8B?ou#fG;s#=}S8+%D`?%qM_Wf#v z;=m-l&3!#F1BlCfet@bphAlUf`}J+tSq(EPyTeeo7o<(4h2=jC`&Gn?6X0xnp^v$V(9JfK;g(~f zK4!iL1;K>MwT5z}l$XEjoSi!M|1Ju_yX+~t6J+&yIw_VCYal1H{@?VMQ>mB6#);nj zntrZ4b=q69!)*d$9&B;=MaT5{Pt{SvK$J{6yXE9hKToZ7HGkk{U?VwQjKWyJRgE?5 z(1~%LkL3Hs^m!tTT=Iq}&pk^PAPmfF6cckWg2P>**Y!OJGc+peU-<4 zQKLZtf$@bRh_j_H8f)Pbk9BqjsCX80yXQrEC|ZS_uF1M70w+AYz6@8|`&8=_GDvr| zL!j(Hggv%a3PsAUo!gW7H`dYex39dW{a0nk+O;0@-YX^>qDlq>tzaKc)G9H*|H?L{ zG5^62vXMK)4}$2)$B3bOP0*)p%Fb+;terBje2g?GXoMJL2 zjc(D7yPkXE-{N0O%!ZCIKZ(+F(-x!nVqk?5${*kD#FBc0?UggiwISiw({l#D>k4e? zLI&y(52Gl!+YPL(eQFHa2hoX#>myQ`p8Dbs>~BDnB*8aGXr>8J^tD^C7%~nZZV5Az zO;-dWo<@df79{K$$*>1S#Q!a}Qu2oguZ>XTtinIOSWi6W48WSy+x=$FIakhcteE^Y z3v}-AlR<|uzXn!v)f=8KM6?dnE<>U!8{$a_HX?LHx%eGS)(Ljd_-sq++)}p!6yXq( zwG!=)yF;F02e{Nq+|Ne#n@5-Fe4nH!i2=y@0MNkdVNu;UVB? zlzBv;aB*mB5y)W|@!}2s8b>Wh9mmnD3}u={=iusJsdUH(O(t0&@<8BHZ%=Su@i8Zx zXJazokz4>QY4~$&%?srDmBB4q^3kLjNksKG`lwwNvg?Jxm^K2VGTM9?Oz!)%L>xkD zOSFFHC6CqBEM-j3OG+5c&0bLq>?OB!#C-QtEG4bFZ!S?{B-3Jfd=SMrUOhz6Ii9(;RxKR?$;=Od?b(>+AexJ;ZD}9iRCyooA-tvzpy&2~?xabRe@oI(RAZx5G zX#!(Xr&IlR)k)HU+Skp#VvS5hCo#?;{Cy&;=CovoWD-MyIivDRN#mCabQZ@-)GyV; zu0LW4s{d{^G-j>9ep6QgUH(3P$FUdc-z}P3m6^L}C?ig8{kZKu~w+iAnX`(ZLi zXdh7b-8K13X>g}%4Hs&~{N-0lmkXiN_`Chs^qPGDv|S3Y3If6QM$5$_*Z~$R!o`1g zNXF-zAgaD*lpWu`xF383WGJ*~Yu! zA>@jzgQjEkZSZyrCaKg*15xhWaD%ka4ig;Uqt|_c=M=ixY|VbC?xHm2YkZ&kTp^*f zfnA(rjEzJ%eWG3t%v>Jgz9rypl2%`B4 z`Qwmx637l}dE$xX49$D@E6s}Kf0vEJC=IT6EbHT?p)Sy3Ggx{4_(-C)FNSK3HwzVt zhPQ*q!q{BQBe?=~a#u+w5_TeDH#|!!OKFCNIWT1(8GJ1lE(-960L<_&s8XLh0>da` z0K9S{cb3j!edz>Ij%HbugDrgdT*m#ZU8g%>U{_-b?>wH`Fja{l>{W_a;%WacGSvRB z-K|fDSNSN&sOv9&!GcEimuf2tk$VFm>k8z+}gcXPmL*4Hvsm&go(&X#D@)?=HYTTmXX-nkg8dL^opsFHKXSzf_KmFEb0<1+A%|beA ze=qr4<1KFS*BLq}zRSY(U^i?RVc^l#TIW^Wd9OaFRL`T6N9s6A4}D%RqVC z!Z{Ev8o&WL!|vRNVGwSUw|d1VZ;9qvSWILMyd)yJ8gauXW9lA;hQK@(Z#!a3|1Xsx znh#iNP7-c=oe?TafIB+PA{9{1FA|V&8aa*z6d#l`Dp}qh!%B?Q11EB`_=Gga)!Mu- zGT4hPj?|DVCUchQ@P4j7Q*$QqnWI#$7k_8SXGz*|Kg?bQ=}pbjfbK4x^QfS)PrHdf zU1#fCtv7K72%@D9x4xPVP~U|k+#WWaNpEj~G|+^X3D*OkxTn4OgW^f7r`RxlI?whB zxycgtgKW{B&P9zS8_e!C%Jih(Rr7@Lgh`>X1(@|bkP=`9N z<|X<9@cvgOUSZ$06aS$J3G>MZHnj|g;f5rtQf7~4+l7?tNpqsahdmr0X^&`+bUbzoDmTWO zz31qg$m$taI^rZ3CS7&4Z^ri1GL)yd=qWq6qFn~8lli-a{hBR ztI~FMIc?g@rr)>`Ii{6NeMTW-6$e!QMWtHz>w0wb*PEicVkt~g4~k@Jj`WY_BGL@6 zU+M!z+>^sRPnQZ$P+?PK{y~>iLjs{9E~$d0!=&&;rWG~1{2l|IS+uUal+!ai(B%`$ z(|IEAjJw8yZicsR1vV`@oPOFl`IX8X6+1M59KZ1}&{g+U*KNd*2w0D%@BylrEw{Nm zJ2)8Ny#oB}y-}XI2Bm)g%LW7--%pElQhX8 zcEo0@=PK#7Kn~4`H9E<4cY?;`-oa`Xa&=omL?;zmNsx{A|A%>_`3QefU`VPK6O#o> z%jmAkh+W=JFMs-5DLE84j(;Eax`TqOsksG+I3xsi z2)}-bY)q}x$e*f#pvNeT&xY2MD@;b6Oi8gx9|Y$KK?MRFfL8dfwlLGqrspyT)xvg< zNSHsAHI~LCz78$soF(y73g*|azsZj5=|rgaySUNp+Z?VL<;vBb_7ZkU){ zcx%RY!13V)61NS+0uHrO7Fz_ydn!qf{BptU6H!pQ#8B>9$H^fafEA{1tdFsEo%}D0 zJF5fUab?B;kLZz|Mh}x=GuRm*0S(gs??q=ZLFkF#tT`fvD(s2Ed|l~oJw8mFcFSy* z__dJokC}*I>2S5{3Gk3dioA;DsAEn*dD3~h}oqZ1O#F}F*eG_AsSEDtj;gDw{Q~24M=o(46N%E)8 z=Tb06cZSYlW-8U2wdRBZv&GeR^N9Ms56(er>wit!(l z6affkSpmWOHWDI5yXdDZp2_uRAUw~Xkj64Xo|%{!_$;`td3%uiPL#&KFcJ5+AeT?2 zra}&7>dE7YJBL^O$$yK$V-)+o-ev!r>e>Vrr5Rm`f`U%O+oS90-n*a~*30w5XWv8Zy(a3U`@ht7CGy?7c zD7Gzh13})!L#y&gg2T~Nejb17Py5N;#N7Sy^FudCJ)v_BC@Lm7=P}=z>#{opQgN z3J~tkOm~0v%@jGvM$jk5(I_xBuQV66qM`C)5StL_q4=G>J`7ZFhF`qiC_4e66t>JS z-*pZ-U_DReGiO0xy9`B`?-#0;Ey>t}0+a$}?im!XdRkpKr_=0DSn5dQNFJ=#TDwP6 z*nTdoRf)>1h1!Dh_@rJ#TtY&5@1g*i?T-+0dCf3hQVtkTzmh{s(h=N- z>R#&bo-YJ1_3lRtoBxbZ_@s!qC7)E`IpH?NuX03POrc@;E0hLc!~1 zI{o8%1e-!w#-dSg@gZBbT5EqaAv|asj^{WTzs-G~HXO}@mR2BW=In`)1=a3K!CUW#(YMhJg>C_IPcT3bZ-V^g?Dd%s%I@WEZd>MlbMx$YvOX zrqmRF&n2n+C!;62=MhthCX&wReK3ZnWg*r)^K~htrNvXeJyF6c*vFbum&|>ONRlm; z!`W$*!1vZI{qdLM@)_zR5fSE-V38_?llK`U(kbj?PUY>joy^x(Bcm>1lBf7k6w6OP z?aq$Rw^sP<+!QaQ!j?+Nvpa$6HfLjySOpcQR$EkiSY*^j7^GqO%yRrKh3RuS@ScfQ zwU*-??K`Ou{IbJ54qb5s?&15Z0Nv|lPtMzP{^Y%5XCfjYG)5K1kJuhW(PnnhsOAB9 zXpCuBZ$|m>!yy7DdbDb&pnkv{)qrIn9KggRcaRJy77ToLT(Q@xE$sp&;t*jL{5{QC z#pr!|Z7#;=_!PL>e7u|ejK=+3T}QZ`#nZ$_#`M!N_G#W6`aAg;sd~Im(CH7wsINNU zNaJ6u0mps3wwWXK@h^#W`YE(3lr+kO*b-p;95rUIiwR`gS-y zt!m9H6p)$UL8iD9f+0~##j1dAAHG|Xn7d09fEDx@l1RGTA0i!{8T+3+Vc4fU9X{9m z`EeeK08G=!dIXr?r>YW`U$F7^l`|&7R8ch_5YR0g1y#v^(RDwNlT02=b|n6tC}470 zFYW{qB&$tU4ZdSKG_R&$Qa49dK1MY#nVH;KxutSC>XhVgu86f039o~qNH&lAp**1o zW}u5minCa7rfm@^efHGiB`X(vE!(1;2)ZU)8!w5mbG|I8_53*U#7V%+2Z@IXP;q_P@0 zT!^D?Y}7my65riU-`!V%i6xi^fdJhw?}CZjfdyV?aPU-^rEb9K@?Jlj5~Vrg-<$m! zoAv~XAkf;reG`VkD6$#wEx%ChV`?-_XQQ=%qt{Gvneu!&CI|U@Ka~R!Pqx^SD++F4 zD?W0))kpmCANuoq*AJU#UtmL8oXAG(w|KT4tc84262T@ilf_H9{FASCC>UWG1m^S~ zu+a~sd4pd6%1o*u7QLOf#8J?`qHxSCG}@&-&6f-TzQrb=EV@%T?9c;T6;N24@KH1? zg?0-yMU*7xpF`;oBx?J2J8fInN2i$ltQTUrDbDO$y7C$d@U;ehFu^{(pXs`ba0dk1 zPD|TVYw;xlV4D9m$u9B2B4 z{3j7C(%%D$pe>ykYxg?Xk1<*k}>1@hn2nbmS zWQgZzeUSuw-t2JoTudO1KA%lC$>sqB>ssRq*@yds&ytI1#Dg39 zt?EV6aVOMrI*~HL#3#f>Y`Q7%$;5n1_8@Fr4D=}LmpvSLMCk++s{Hs5HyRaIkWHVk z`;kQP9ZeTJ=K5x_6yj_o`c1)<7QM7d55EWF$2(-+wR@(diz}*XL3~yQby# zh`&LRYo55JY8Crq4bK7_CGcpKhQ<}LEzvsD6$OX7C3}_43N?i&cn0!ZK9J2A{J{hrORQi`tXW!fAy%;br>j+j;Qp6 zM<%lIFJ&bsB|5t@y}!JwPhjd_{*LEwy@d~C{U^&m9;nt977lk|f?(n2aJ}Oi`JP9& z&dE%VrS=-UH@5lB2&IWK1CyS*881UZ0pwT$0H}1)iANAW*d5 ziyDp}xNQpyfe~_}6{d^?Izm?eXXonxgGG&3>kkikB#-{rPlC8~0!}lku*W5dI!poO zg07)~BEkP+()<^uk?}3W2*1=;a6@5#@7HZ=eCL$xbvq178m7P~bUH8MN8*cMu8K|r z`bLvys7gqS!(Bq|OJAL!LOK71gxRcrQnlj9!DYUet z9Y}jYkkUC|Cj7l`v^-EX8O2r_`FlFKK3B%18&3yAxd`+r{}BtPc4*gW{AAbZ%~ND8Bg6x%_=~Wgv;yhmIIrB2SuO+H~zanldp5k??^XgvTD| zMA*{alOOmV>b}xq?TkVz7U1(_ImLSoqWm~tW{y4*Z@}UKaWEgwT+L@P&gUSO_UVZw z173M{{m*R=2e>0&7hq5~;evu3;(b+42=_4=nJ^>B@-etu!}y@m($^(o>-T zCq>Z|e$Zndud?sKFd8zzJ&ofeAd{sJkH3Y4cKI`H7gCY%n&dx#K7kLMe}9c^yF1n` zl(K+_pDW+$TmjeztasR=5-wn%ko|p-fLWiPe^CS<7km&tNG6nGzDu@HI|-3Gwt)OK zXsh(yBC+6{nobJQyMSPg>A{YgeQ;I#L43K7ys)M3+yDb@2EQE=6v@!Km@oFi#~6Lm zZmxii<&EOud}n>E&@5>v;g%H5@M)&CK0v5U&_V**ppAQyI+`nhqi~7JtZ2H)qNogX ztyO`(+onvAA6MEJfm!zaaQocoOfetW2c0e#2G2E4<<9Ro);t_B^mP^$xh@G-eq6{Y zq$g<%bJ|B37b51z3B7%uLYFHG+Q=7wWz~aCI%U?fkS$X4WEIO45$Iu!K)EG}X8=YE z^(gCbtr6q@(sM%J0dfK9+#Gf%G4B z1FBLpjcMRd8Ul<4rsv&=c8T=l<#~(l?^w6tx(a0*#_G&Uxvux_DmwA!xZi>c#)ke5 z;zgm?5RiZh@#(ajd6HLVl8tWCwL4JRfUsfq z&S(SEkQJ91EFSLNm$#RLI#3-C@5wJm(Z?Zz)O|Xo`VeBN(5Wap?tf1-&47Z>wqm3H z4pd1weROyoMo}UB$||8K1WP3%ABi8vy`*P_4s@=si?rj3xv&duv4jvKi;&jmni!tj z6$(~7)QbgwZ^9 zvRiP24RmpTgH8Wd-^&GIEIlRCC*YMhqz5>sY|bJf?J~HLxv+u&X+9?pfU`jTPB~2@ zKx_zuN`rWVcVkhm5)jatqmYo9?_;tlPCpV)(usU+3nea?(*Tt8UiwiuGDX;5o+`Se z;VxTUF?Iw0A4w4oKz6jB)teq%z<`B$nFkZod~bE&WY5oM?>&P93O5pobz<>rjEmhO zdzOZ=w8dO{fO7Qre3@JsdLnx$Q8#AIXfsPFO_@BpZ_#9uFFJm^#vQ|=aXt9Rcy9CG zNHy$McmY)}7GK@1^@|A5_~~Z7dOB}mnqb!EPZSAr2B1Q?KzXns@8z`4How&)=JmX2 zE-xhIZYBz`5m^Is3^N;33OKU=@G5$DesATY)$Q~-%Sdpiq)~`37P>ssjod`UOBJ2s z`bD*%E)0jzO-mr`RVM{;*<-)3~K+B4X(aAa{|=8#HZavD`QvSb&cI< zE``F776CrTJ0RSAkYB;Qfjo<7nJ+GeLyWZjhZwrnX#Xq@VwKeQjeb_+>a?yIH{cG- zQ+#JLsXO{A!??Vx(8HG50&&-3v@$-qFz}gMk8+pI>m)~Dxf&X-F@r!%p`1)Sm-?3s z!jzJJ3%kEvD)Z3B<4o@rS_}9@K1c>#YT1T08%%pd{L2P<3;?lD%He#QA zO&rN#5GoMG+;;Ca=Dz3_i%obw)?O3$atnY8i*H??i4qKr%Qh6kvjhjK{JiD*mVwFjBs^qm3 z67RVm?Glmpkf+_%N{F)suRrULsf*GV2E}{%AT(KbWbDik*0S_UDf%#~s3}P{OAfTU z9brEE(D=(NN~KE203zw|2Lw#z8D`5dwR6q7DLhyMPnyzH^JQqnCP?{+h0Y5a7RI>+Di->1&)=fe1(yud}6h{cA zS8P3K9Yx)53q+R-Cz^Wr8x7?4u#N70c0>2pS8)qG7ykw2IgK)B$IUmiCOR zEg@(7r#M0=P%?vEeWDsbX0EpISeWz|QOeO0e%3T<>-Xs6pEH}ICC*F=t?O3uMLkY9 zlIGs#kmW|-`4**uo(!-USfday4p8ABZjoiZLgPa2r}!U5qcB!moUJphCrtDnjt9gM z5dm+h8K_9$vqIu5RL&Ahr9zxlV!^pFNx+(9Ez6upB(tm8)$S-Dxq5~Z#CV4t}G#1|ybcG1-bL_IRKhB%iYN!O?hE)W-#q*!4 zo@vuEP_&A};kK@IYC8XzvSm9lSoW$Ma0+okF7YV|D zIC?}Ots@oaygbbM=PRxkAjJHaCtW^LVcwIfwn(&+c9)u%^_pcGqvSs65a{jO<~B>f z<8v)J`^#pA$%sIy#ztB3_uSq|1iUhlvk2&?den_l&oj(*JyQuI_=Ofp-++2~b!(5r zd5jOuhF|RDS&~JG!sj1StH69Ng&u!s8X;tWe%)k^@i828$;gOTgOX%A_d^j}p22tA zuKupV`NG)3dAEboklm9n^9TTOO^i!#5sReOl14UZR{MQTh*<^pH>eK~q~Am&71i2> zd0b2$?e%|Td(sY76tovy&JfvX+O&}h^)EV)7^(^K+Von7%naqMHZd5hV%(mHgx$T~ z>$^WQH3G}FhgfX0t}6mYSJ zZuORS%Q^QOONDbm0ivJMm(BlW)T$uh;VuZN3HdxWB+w|x3!mM)x*TDy8mXm8y|QM1 z!xPK#@o$1T0Xo@Fi~u?>KpL^=mvz-{F+QTF=>#%-VL5dU_L+Jz8;P~n1FBtm5*PKK ztzX{4U!z~2Cmj)zWTw9D34yI#R4NWZp)cQ5D|d3!_zAf}=K}yOTz{O*506O1QVF?< zTCQ>pm?x~tcSk0T#oW&bSJ{AQfjvVwg%OdW2P6kreck&gj#L!=7#*Xm z5G==LP(#AzE1Fz?r)iWOB|>#hW+wY#Z~cq_%etPZWb>e1URZ97z}KLq-ecKo zm~9i&X7?J24npupnR$VP%=BWeULo&n>Lm2BWpMD&IBq)WA^&@*Kv(GIW`#>SQY@E^ zQBj6+)7u{-y*AZBPWpCjSED!70y@4}`FJozrYD?a9XD!_3&d=mNC~K;CUUIVv#(a2 zw`1wIE*>EVkiK$%h=T>c`7CT{qxo#OaS)O*uj!H6MbMj2nfMN-GY-2-QZMNum?l!L z_X@e~-(?R?XHij6fV?#_F5{LdB`BKW-C-=XZW|wCxlRr7TID|pH5Kbw>U(ury1&UY z&9>p$cQ{*jwtrC6KR(@zSL)9e1ggOqbm!vm{;BLcP*CJJO4{hseFr??E7RL%c0(OQ z|1}w^x$<~Fv~z&L^F?Qnn6jPKJktBjWpm~Iw9cbe(o;lLn&0PY3zzAu%%04!Ah_FZ z{hxdat+qy~P8R330zi5@12QUgmt>4dp>S0yl!{5C0BdsE8|4nEnc4zd7TxGue?%1? z)iaCcRtJpgaGa|-sX=Sf$2ylU)f%)S;Dx9&*x)zYT90UIxCWq|)56AUk1x)I^p#Sk zQ2Mg#h5PxpjI}U403M^635Um_*KtHftS>oz?h8vzorQuzLABtxbK9SwL8sitBsX6Z z`5FyisFbhkt2AbD=Sq=QzhRIfiu{hDQ)W~mo5vJ4j6^f1;YUvQxz5yxq}qz2Skie- zf<@q&OOlJ%^0wLKv!5s+2ajji0#CB%HAJPJZx)0>zdcAC$On7@cnqmKOoi=$)lmkZ z%cnkq^<{?N{}Rys`~Ic*r2QwZ58%U(`K;kW3Hove%)*BE0h1s$aUUoCN67=(DV5Bm zI=n_GQt5~h1^J=P$Lq-;s04B7E7IkgSPmO-rRHd7l~gJ{*kaU+Ue)L|O*_*FojOOB zla{vhOSKk&hEdMuWqLCc!FB$LxwHJA^nE7!iA*It9+TOHIBkn_6ScTsbKCP^t6M~u znEK}$-CNfmYLA-Wg96?d&yl@RU5SBVfz5gj`+QOL*xM)u+qudgs5Axtfzvsmj{&9(ysy*++^?aEb*0l2>FmgFs>k*Z>B>4!^tW&VDv@%Jf_ z-z;B9907Gv zu00X&NN>yU>S6r{OI+@YQWc*Zgre}JiT?i9PBlemH`;st-Ol$jsVK=+s5yy?1`MZ2 z(;0*Af~Tn!0*#6U$w+K*QCXU;)@~*Bdv>&+c7z?huIAdK5|*4G8Nj)EtgQ-@^$m^A}#=+r#}}U{0wTibK-;|G4*VaMn(QN-ed3marbtm zFbF+X_{#MEN7P$I)fJ^pyKLOub>r^t8k_*ZJ-EBOyKREIh7f`zK!OH$cXto&E@$=V z{{F)a*9_*GQg78$8LYWuR{jV1-Z{L$T*y$+0l@pdhDDzdNyU8o-<^`(3l(zr=%EanV=Uy`U%;)z<2CgY4qBaoh-4i6`TM8raIhM& zoO>V6A#-Vb?{E8rPv!#QK&Y-FRWv+0pDWT2TT(F#l04HcilSOJo(k}FY~yHTVWk|Y zxOJ6j@G-xN`hTMNrXX!8Y>RDui-EYg^YDDF6X54{Znc2N&Mu2phm39i@6+8|$OO0b z)pyFWfrR2mY>aqiXuTxmcqm*3iNLoJ_OwIsw?UbgI|DX@&8iad$B4(D`n*AwYFs;~ z68bUqS4N9V~VMje=BRV#-TD6(Rs942xy&uuykEg(c(&@wI($(f79?3thSxIyH&>DU6VCn8AFSd6doX;nH{nKc2x z=?)zFvxQ<9^SNu9Fo4B0a4Gq52J!xUgF+7IYqmH8ByFPqsYm~cp2GB#N{NnALWU74 z2~@FWebj0{@VZ`ET+5?=Ri{R#9I#mPA=L~>bn3Al|0x@vqum!*MJ5F<4vJcyEzL=} zoTi;OEQL9$sz`{-Lf^$jW@^lzCR5mcucA#>Rx8=SiLZIKr``X8_-<|!m#sZL$>?GB&`m8<04c9xWU`}p-c;zZbI>Pq#KP1EO_ zVuANp@1)Jc#i`1Yj;A<<_dbHWrD7|U4E=0w?!_iDE>x=P-wUf1hY3XAX#n;51L-GB zDIq6AAqNR~Y3v>SL#>yHs(2-c#l<%l)Bcwg=b2TF8d7d@Ga%e(JKR-`72LZUVxw;_P}$s#3Xsp}R~EV!emOE1Kn?rA=4sHezWO_4`Cu?5FCKI& zlBZpcdc0Bbv*j)_iLRofgo%i3xxtj}s?96J=T35t!nYqftzd;s3R6VQzD7coircWc z`|aB2nV2WUstJdE-Ki~Vk_Iyf(+G_?51`-=WnH>F-H7NmFnmSfk$t);#inKQeXRS3 z_Y#`aVp6X9?TTNwHNy)Q(Wk;sp7@|Za#9HZE5pFpQeRw|5x7=lo~`w~f)M$5%D68c zA6)Oefk3?DAHbVvgv|Tf6sC`ZM#xw}UPWF_UM9u>w|>$Hl7tC?r1UUDivoB;$Dz#_Cc z(J=u~Ba$CbH~#@m4O^cXgz}*F5+3A4sNFF69*|-Yd6RY)BeDAhUDOtu-CSMT>*HjR zFcdIMlMlEO1_wnTuaHszvaAR2Hbn$}9R4zY#Cefa!%|25l+Kg@qQSwXHVYa+{}Cr! z0`^P!4xFc5+Z(}aEbv&Eo%?5s>4g3<*+6p17n3{$5M2h!K1<#?NFk%orvhGCCgP$ zovLlokH+DhG{#nP9F^Yl?oDgJ&M|79ssHr~(RT}joyC{}r2r5HUQ`Rh%BzY_%2-NP z?b;-cm3r%!mkQ>Ro;u4mrCQ_tnwVm6p+Myc`q2Wv!7Qr;Nx)lk^C_yPYZNLlf4d+_ zY`ENs?oITEEs(|rI!y2`Zx?hN|5!Qyox|Uo2!7AD&sELwp!Yml%vvF~t9T z?RdXr*Yr4D#^vx4-n=N0jM1(d{DPT71pV7aoiCia0YEFj0b%*kO&t;RHZDz`2AqIS zHVgU!EV-goS9S-9jc$rO!wSrFaS=&KQ4N|aTyf+<_j3%#Y_$@O!cITWCkc;q7KKPF z^(i1{S^oqe;vPiZXgtAYw5ji%QF{NM;Bs`1( zi`{tlIGJm5>IVZCle5XKJ1yeR@9sARb~{dO{o(6a``L4 z2pQc9mr^oCD8|$RRpcr>)FuMLr%dzU^>Vuqh(O3`@&iASD}~7M97Tk{4Qvb>K#Wdq zQG!8a_WqB)T;PgOQ`DH>;d7%3Njstd$Qii~*=r*(Qx!y;On^_(#cMC%1ow!;81IgZ zzYB#NKn7upM9KXXt+Yw$<`4?4>`?|l^CKG9rKoCDvs{pkIrGBrp`B|?(LSMQnzKGx(kI8pl8#OsHB$V%OQIdm(okVL~0YZ1*vq0Cc2iMB`X& z51)D$b`fw*ca-a-&5f+uW!WMhdP@t7UPaNxf}03eG?eu?=@z1hoZ;5L1fx>ch0EhW zK@r4Hu$P|&(cxm6!Y;xm1VD|_c?Y9I*R0mW=%HQp(R-llf0&*b?&Q(Zij+^S2X+vUD3yLR%() z3WGZPqD_E;2=8&}XFDa%wgoKV0eC0@hjg67))Z!G`tS@i;mS&d{D^F0-*x3aBGO|RHdqg)eCse0k(XXE7rF(m_e9|f!4injMWK2XGCX2q%sjr*a(x= zriJ3WVydDa{|TPdsE|D0Z&0X0ih@>~5^-pnuJ&_L+yR&gjlyFBk^Qm*?fxjza$EM; z+YfDZohsw8(?fy0ptF)~p%r+Ig9wR-rcHbcQm_BM_FF2LzqKAT9=GttoG zdrfHc`fQLax8MGpl-QCH?&Gy;d1K>59dY5ZH;hOxv+>(e>D5-y#x-VzBIt7mR1d7i zFRC3h1YmHx#s)!9qXSO?9cq4CIPUUGfWqF1O;>gcBEq)APs1 zbPNxj-aKIUGocLJ#p50vUSZ>zod$DyO}61PV~L zavwpbvN%CO;d~^GKyex{$NAR_VKi z3U%}Qv$cg9qn-_*WMya2Bssva1arIizo>PvYrW_O8Ob;^l0G zNb_AlP@KeR>G;8Fliw2$^LDax(pkN=o}P>+S{T9?Bs_111`vz@%JLUl5ki%>w_LZ8 z=2yD9$Rdfc95uf`027HTBV)1hEt-@>UFXX{aQ$iLV*zK3dIYJX72JLP~XBWfKxI~6cb>+)NB&` zb)3Ka*c<9QycUu#lDb89=f*bp;+G23?WDIVlF53$svsTw~r4evFbqeN3}elNI^v)NWMsqQK6G@3yT;*!nm#7 zG*K*$TF<9vuRf=iNeB|KJN@aW_5+HClSwws;|2yc20K+!93fsl^+)rTB>pWPX_JGj zF@MiHtkuQ6*$%WgGa6+C+;=&2f?+G{s&%_QKF1hTc*tD&pL4G4OqIL~7`3|Xi>Eyz zGC{lSz@JA_KVJPJjD8Aw4@CCg-2z}ru`uY(1kN)1qk#LeOc;RChuFvrGHaDkI&8}j zi`mU>Gh>MN7#~sh!-8TMV03UKY;0@*irn?yi1!F*e8}3{dB^*9JU~I61~C2E(Gi#v z@c*+A*{EU3dBRdW56G!u`lF5)I-iLN8#Z-L{i*mJaF^ZOHb2w1lIut}Zb!k(tvRJ; z?r-++@DmSsr+uf|?la#3(im0ikI%XEGX0@2Rmngq#&H5gax9x0Vc>`6_bZdE8mZS> zv%WZiy6#_bEk4^47{GghQ9mtls77L;c^M6Wrb>l;4sq&|UH+-n+txO^EKb7)OG#sy z&6TF=+%dKqndfx@b_U84u6?g|XTH!Z!H&TUr7+^;^2FnrZ|q=E3z&2kOBd{40dVL4 zv~9pEM4;96X2%mO+1M(d!bi?m=`BuiWUv(94*Nn2Mi6ZefFiPwOG2vkf9dv+8FB6t zhe!|$PK!WiM;umvio|leD)XI$t_u!@4p_H=p1U8S-~R*GTWLxLJkYhr5%y2??yegv z3{mJmUU_948B*J<`EAHsZm5gx%0EJ zGxWpbR7?UkMzg57te2NG3qY1lgpM-wRvt%ac2XX<_J|++5-BPJk%p|$D{p!a^ekrt zK3!BQq&}!WY@-B~1KQ1AwZS#mIPWmL5yKJ)l(v1Jaw-%R?g{s1)nc+Te?Xl|Ql;eL zGgc;z2%!+m3uHK&-(#D;|GnU&kjodKE0@U`zy*j|VqNt+qEg^3`e7UybY!30u{`eX zIoO}R*H*aC@9ui7bwKN|Ks(tKJsQG8^of=X)-y%~Obv$uUR>;M5t*xvZ_ULouIrFzoOE#kfL)*i!^p9di}x zFa!4jx9tE99wDh{-})?`9{uR7)hl}i9k>X>uhv@j`Ec~X z&-%<)jj=32iG5S?=d>Qjk(KkaNk%6taz|fuP$1!Va>#>mMCzMvWZy%EHRy{wNd@W$ zl)ikSWmGESpj6Lb`-Yn?65+zEZ*Pt>7|L_4oZF#qG} zP&o9);cF7h<@34vXySGT5qH+yPShA~NG6ab`E?dm?cHfecebj; zaN83=z#O-ojk*62mq0dBEEL;a-k_YBL{UT$T;_}3&g(ebN=Sx@>e5=V=-7;O46kTIfCv!2iBWjFV;Yh7q{iG#n~!#;L{C}Iu3y<(AuFF=nWT(@_Roc z`0baX8AJ5?-|wX0>rRtk*AoAS1ZuvOe2XFC$ovmrRK>KP0DET~Tq>K`;+q=QX4D$2 zQNC(hzXmvUf2eiG6XcQ=gJ!Fy{G45`Xyk5Hvm~}cNfFb{8fv3F#jP?yhGGtc9|&N7 zTDmq(i0ugP5f-8fd2qDW2mpG~*OFryN{WEaw|98@k80fv86dhYwUeV|6JDLQO*CUx4iP2HZjZT*E{WHZPdwyd~-5t|9NqAvGvnn9VT;=2gXn!NJJO~9KLmXd2dZf%(H2RGq@g= zj<%T&z;OTCCIDQC#v*`Qe7W6ca5g((0sMB|>1W-hv<6lX_WzC|L$zW6s~(Qcs$!fR zJDje^?%N+a%&HOf2Wobx02QK85u|6O9o`=r^L9@SsZ|0j7B^ zdNt4JX(+WQg)eFiFRzWFrrkKM+j;zcO)vKpD>cQUN#vqAfPxCB3ky|x^`<>h02o`U z|8RN_@c)hH`+j_RXuy4W;WmLCkqAVYloB9nX>c~-yM4bzFkqon0*iyKxGX+1>U=~0 zEA<%8Z9mHacaXuVDT9wC?3DM2h=0MtK-A)~#b*I%L93l8(2OxV8Cs)7EtDu&Wk8ih zhI@?5ApPNAfQjEm2S4;hy%G*V16KAR-ftJtU{(|g4$&yC!hi77{XFZRR1&m7L=rxT zM2&Vb0u+X@H`@#x7GmGSya6d2r(@3REaPX!(ZOzx8NX%cJ4vQ`7sITY*i<%ACeQcdyU%lJ^C}mEs?wBT$$XH$Px2^i5Ljo=? z`Ur@&nt08~3&6p|qPQ*^c_G|J3h8k$KqXCyBQZslcD2oZrw&+^eEA;aM%>10H3=0X z5fhx3po|FED(=qKa;ZMV3Ak=+))+npzdxG*asHqAT$YLy6cpE}fbB74H0DCy4AS!G3>1f_a41wUr_#|6_Hnqg-%nvIkz{`dcKWC8xx!s^dWB21{&cNDe&O| z|E%*A9P<8>y0j0_`^sS`%8R8b&ONFJl778X_^oHx{xY<9@@ zjRkq7gvm2DvdgPs-um_@ly5;H19u85rrieb4a=IIXXtmzK+PxkFHO=QNf);n+#N!``z39b2c z#dca&o@sbvxz~)qBPH=gVCnE6*+xbo*?RyK7e*>5Fo>=S3#=E3&!0c1(y3elkpkfA z`|^0rZ$E!>^XkQdB_)FOf9F<%(-@P^Qe9r>zo8I2wHm|Za=3p;KV7N)(Sgp;$}G-r zQ>B)R9NJ#Rs(GP#64kH2mdQ$nlEvL%ojm|crMB@#P_ApFT|p_%cl+PxKwk~yDJAh; zbMJg;<||4oS}SylMoRB%{X6+6InVR^y7kwVL2>@0MHe7BuyacAxTa9QF#dV zUHml-A7StoXj4yL=43Lxu_@Tpt#=qezaxa6gwQHZ;_rVR!Dq4-amyFl$AX%Q%!E5x z8!5zehR0kw*CpVWK`l2?I+IbzExDhjt4%grpHmfY|iAT5e;8+w!^ z=NA(zk0hq_z5K9j2;d($cTC0PF$hzyw~lwR^4P6E;_LPA1~j46%|{@y#2G1p2c6rf z2O9;5oQJ2s@>EImQ2Wcli-bDKWk{qT&Ly%SM{7z1n8Ad#*{BmoVPZdsn8DU}jpsXP z%F!6Osoz}QT3SV6#4y8R-1p^%vAjN?=NWE3dB)x4@cPmvfn8I6v2NyfudO9XOTH9xi5_jY>qN{EO29@qGJ$pxTfr!sqUPFXR1B)x_3B#+MUOc_ zrbwcg;fwXrqTB$E42ddt>=_giH<-a10RAg^f9Bv<=fM=DUlb+ekkw2^biJRQs3U;m zDRzif!8_1xRYMm7XnsK1Pc0wWUe zQXG;w_zTk<0X=Jg%;QkP9coq>mV9^n{Y}mvl!gJTy4*l|0OZHG1$*%dh`GcBvbs1r zvE;=Ll2{luxO@=HN<$*4!oKhT*j9Q%T8V0XtPGBjO%H92lu&PG#Tl9cEJ~ghJAWuz z5~>4WT*)eLh^VR5${!*|3Q+ulzDSTv5~W1^nlu(LdO`iCIG&fqq*GXbbp&Zna@bIJqPXIlNsU{x5g|i-g=4 zznTsPaf>)TEm@QDU+!g&A~oSRR~QN3DZ9d%O3%lYR}(b{p6XXV(Wx+WY;m6@8P5J@ z23A<@jINd52#hlTawP2tmuO+5|93vYVLfWYiU!&C>A>`qj^^4&gJ`LpkZ>D@06eq}z18`L{e6Oh-kD|}k{*0~ufwBd0!ULhYwqtgW!7_z3(Q%-%jl>yL zhl~r2oHtb}$Xa0u-_8(9>Zwc-s#x;{kE9(+GGA|EX)-AKsX zx%I(a*?AxJrn#}P*^!bVW*krEbagyXH9`%nVl6j)*0 zZLHrO&J%p;qu@(ekQ$ft6I7KD_zbnt&M=h2tN)`5h&QyX660U)Q?Wwqd;pbLMO1k< zIZHL|P%>lEKSE+xTFdKvJoHKa36+RJEQJIxKrZ(sPdotC>HA7FGk~4AVd@;TrR>5{ z&8?L2^BF15-eMCNQ%!$Njbbbi5xiw}iZ-HQh!9QM1fp4X0Jhtgy#@nPe=VwB&Ji#_6~eA^N(Zg+C_MIGlxV%A*Y@SlMm}k|-yTISfn-D8Cg3m@~M}fAg=X8Ud<~O@XXIHvg z?>i2NdLgBs$=>xahzq zE-vm~IA$*QBnZ-ay_SDxiAc=RZ6l*r$Ok{>_6z+b`}=th1#EA5d-x(3^$5ZBs)jNkHFZZpR3I6uOG|n+v~#3D$GL7)N=ei+{Q+xamikVt9j0}(<+B5)F70P zH)Jn|-x{(RoJ5)j2bid{zvd5r#0gM=#KeRSTBQu8Mk7Tx9j)i%VCpWm=ff9uM~*$B zxT5S#u~Y+ZVva?}m7Lb#*FI-hsmKS((bh1I9i`}(^OtQPXvy%uZA0y1P7clO_32{& zH$9S_QN?Fb6zX*fsM%|^VmTG8Tk;X*AoVbPhsUdV&s+69DLnUMZTEYkVzUqYs@}VZ zt+~WwKgZp>VJyDo3xDqdGXW!SEMT$xwqKCCSZH0q3;+aOpy6X@5PsIT4+pjqV|cRK z=HEu)SV0P?7{EEECzqZJX@bfe7HXX6TB6hZuE#F;$+(7W;-bZ(*S*g8&a)@P%;A;t zbB22l8DS`4^H2V$@-DVzpLR|j3|2H@o|8Etyu$p7@OB)*FM!&}BXE}P_p-+X4KBLw z=trMQU`k!=NRo1ciNWOSKH=TucH-6_^^t!jeq+;x{DG2}>qUyt_@SL(9b=Fd!M0{b z_^wu8AgQUFV@wUx$flhzgDH_r38nTn86jVXU_%*=oy7GSqkpP&EA^VPB5CLm8MmnG z@cG;pE{i|8WzErE(5?ICUxL=)M;h&a(`^==P*%;ZJA_szRI!(TM=}zxNWzH3r2Y9F z1_SIzof~a>ZB|(N~+L(NH;2i_v-iQCWkrm=Dkq9q&haUI1Y^Za?L9yvt%VoRxtHo=T0Prbh|CEGrIv7*J zVBIWFB)LxVF}7e5;Sy88-=8=zV)^^3KD&b_arPTkh@--!Ftfqg`IM9^YteIBs=39^_29XlT{Q zlSv-J7UmIQMK1USE^_LUq=XC`cj|e;B%z0xx8eiV9~uRlN&p_SjEnijd`1xFXk3>-?P|L{>`5+TUr#gQ2^!*d(w=JcGMs|aR*H>y48ykOyfHs0CGElKp ziNrc}=TvqDY;x2{O1avt{4l5aYVEntEmOSqZpF)E_EXFREYhe*hz@&>6Z>g1+Y9TIRyQeJe#rO;})O zRodj1?+V)o2mdrj$ZVFiB;%cp!&~zp5%bURl!VbdocX#VYe5(CpYa?}&HXt5}z* zJdA<;D6o!EMx?!}0;UHa6;+^qqhcLqC}kd!;L<^dEQU8oyG`T`waRoHe6UC$Rfr^| zeUDNZj~)QD?P!Pafvz2D^I4$Cb?6ZQpwipV|Fk7TT4>=_nsVEF0FHb{jXL3;*7G`d zF{jXnY_7-*f?eqYFCS;;DA0k$#7BEX8s@mXM3Uyp?ogP9@J0s(#{@(GTcceJj6SW) zd|Y!V$x(a78+gcxmdOP{8%wS`HXhG68t?+@REkcB&btzbLDanJi&QHTHPRd%x7xVz zhG6ZK{Nc>xZexIOw(_2GfX1Zb#r;=lswBWJVx~F;1#D&#oL^5F6;(}qxVhqN+ap!> zfv=0+41)r?Og~S62Mf4R^8DY)poW&i8J@^d5h2Q|CMoGTF#VkiQ2ruhtH(Jh+QR{U zDyH^=Le~AMdEo5tk9P?nM?jN`@4%_4HJqApP=Ow4hOUI zY!#SZ1$bT43F`|#(E%L1;CX4Apj8GXe72)~s6Ex0^3fH{uaiTNCCsCK1{eeZ=vZ>S z(qAB4^s@Z$*XMtfur3n?xc(!VGhTdNEa^vCKhqc0i3P}aZ*2L#LJ!Cwp@WAuSv`Qc zBhX`fOK4Syi3z|xZ%^^$RO;Y{BCC2!bK;V9oZ_x#LJhAwp;Q%VvbqS4xFwwbPVFF7DvN~9S$X)k$YJ)sm&{WEucmx5)*K>t0 z$>!nBKL`5)anSr>+H!1|gh=nNsWh?VDwh*!Dqc3|ypMlFSLfgTUAZO5ln>wjrgOV* z6sES_&P!bKPU6iQo&pSu!7t?iMrjU1kOZfglHTF&iuO3gd>c%Q6=jDsx)L;ceYIbB zm~A3mx;5R_K)hrD{})Az3g?M93#BIKVMOtuz~#e1Vqk^_gz(4HC}DB~6TCDvnbq?@ z7)^HnGOt<|`|zxk2B6FAPd~){TtdT>(cEX5`6d|tR8g7?bhote<>WW?X@HOe4%OUO zpkZ?jL_b5s#jmSjX0IqI!B82j=3@LIUXjS2%48U~$IDu8caD7K#HGWOCY1dwrM5p& zP9qEv7%ib3t*WHqs|oY9Z4e;sz;lVM=kPNKq4<;AL3#h%gZYtNS|Y$*aP^s?8~({4 zY(>DPoC?dv8RFp1(v46Hj*?5>7i8AXQeP-Vh^`_T&FVTsg7;Yiit8wdK%fj3y)vBJ ztsn6ulw{BM-wGn8rKP~cJH5r8Mao2f#-uoUf)Sl*Fg;359jmlYyEaq?b_3R0I348S zVzer3U|VI76z_o+KRd|;L3S;dSE1*1X@Aw+{>eX%Bkjj{OdM{Qe<1^cZXBJ3fwIqV znzY@`c6h9e1p}ROsUc9~U?3wHaN+Tf!7ybNQ5^Sbs&ur`sAcjah%A1#tJbIF`831x ziblMY;aVMj+s$H`fBkdGrl?d2^>e7Ox6MG8BoOhJv$379za$qKTy<)Lh8#BGzXjZr z;qVLnE$>e()jIxG$Z&-Q5x<;;Z{qdZ(&|q*sYymV7(zt5cms^7zaO_P|B>+RfP_ z9Q}57Cilj~?$)0w49;nt07EF$a4W!4D~+~2!!4G^P$(6KUWcEZ!ZVGx!{e=SfcV60 zt3lCvU;xmis%BI1B&>5^e4k+2k9n;I4HZTaHpv+Q3v_c>792O7?F=lj*p4zHeuX95 zKAcY?KtKjK|A;6qQjLT#%4&9k#EqpeGU%}MGIc9*Q4)PWjzo~5&d)Wk^k|$XKacP3(BG-ev z)cb+I$3{~V32e-|34m?!@1V{gB@x%pA1K2L7BDhzYpwg)PLC(tAALiVBSX>|x}M1e zKELf|*v{x?P&qtU>?Fo~{3f_tGMY_v)wscD9p6cSAO;KP3X2?;SO<{3vZO0Dx0FtW z2wj%A;3w3c$2Z+W?o0f=_nBAWCZGYKdu!COvDWWamw0m*m@NWDkAy%x^gj_%&XmAs zh9jt>_7oNBmtF}x(ooJc2?uCT!`U`z0q4lTE*#3*bojKV?@LjhvpYFfM{sD7jMUzH+&KwNbA$J8XD{t|h@m?B37#q4PZ^ z;c7CQ%}5{sDh?$Fe;E&2z#GV4flXL{T>fX=@kbpZ^%tmJI3+-jLjSr5V3k;Rnm0+d z5hzB16wUY?rfmk%^5tff799BF1)YADU}`>kQU7IBxqO#_Typ?eBD+wCcctf2fFe*v z&loTzlDq&?TJ=1n6cH8OYPdJUdhj!_G8pm}s!NBUD&6K;ax{fJHdW=>&83$PsZ+(dR0PtT+1GL|V<}-a{`GS;R7i8j7YeUyFqL*E0mr$Z$UNjaa~0&H zS)=zS?MYMm{I4-HW8Kk8in*fRNycrqLtY1us`axq)HlECHbHEy zQ5Rh~%wSC<8o5=-#m9I1<Hf=QQ^@&HpVx;VVI-VieKeoQpr;P_b5@ec=DK^ z8_(yCE*A4t>yR;;_htK)mDI@3tQ+`T=am$vGn|&!Ns8xp@%EgOR1thsWEbNi^`oc+ z11*_JEJDpAWZ3PDT{KvXHnm<|LPQwIyE5Vqe=4@DdL;s0m#ld z|AtzA2D99w_brnnD2Y}Ih|4=D7shrknS#1U~_1`C@&6a)(LSkheh1ss5qSWt<=>SdQdam@wG`XCxC1lY&KTT0^mnqM|(07sS() zI5o=eYS^!|N_v&=&*tULfIc;v?S9txH|RRZ*LO_tK2MN)!?9rEIF<($@$)&Z?q%@c zKScA$&$X|elcCxjP8X<+58}Xw`@Bm1mO`5+f=#QK)!mO4Sg6$U=Jy@f14WAeOEPM4 zQdTUI1%}F$b!CQ0zz$mTkwE(6Q8msghgIq+nT$!i`?&6>jTN8(l;i=ry-qv$CqqRbt zRROyfLu|6I_3yYC3fGXk8W0U0WtLK8PRFk#pBLh~RN{&s*bKCU|jv-UWN?Y?4 z9au&#VX~w3JY&CO3w{o(CnrTb`L5HtKPla8w?VRGCKaYGuRmPvpsrb;E&aF*^_xm+ zJ+D|r43m~-cpfNG#a4qQPedBN8PBH>zQZQPJ&IJjHiP+_3JIE@rs&h%uL10X9?`8Q zTf%Y_`vre`Z05a#bdoXpOXgufTrw;^Joehf0p6Q z%-M(micF^K1kyheql81ytCL5VBLAjslZcZ@IWwz-7aJ5<3O_GMLrVA$QqEY2iRbDmb+@eW=0(y`xv z+mE=0D6;6PS?_3O8d(jim(dmOLW@1KMA_VhBY1W=w=-fOT1z0gkGudJ;i)LJJ$Ffw zj+-yDEQ-8N^R+re>u&LeQifiAaaY9`r3^02PE=w|L5d+^dwC7k5gz$M$U)hBDvIm* zgcH%u9qBJ;YX+`Fc@Vq5=VFnNMV*gi!sT?5UlB~tjU!>r&HBdZ*XM(_iPp^2BCpp(ydpd%^ zM04bF6uZtg^=)`;zVfTSx%|IH_3P8~4hl|BOH7}tD&69d<8`B7Fu06+vc+gbC0|_2 zJmt|lUdxxu!fb|Cd4;n740Fi4BWImw6bs0q--e0$k9u#8u;ZonEg|E5;?`}M4cOR@ zXKx4#F&WBKJuNmA6f~=|P$%)ZH+oz+G4O$ER2E)pH=-6ngIf1jt)8u3C%ZZQLDJ<0 z1Uq)bY+hb!dd}TnZ|%s_nSV@0MMRVtNfAiIq)x&?@Vg`geboB3A*YcaX&Gdd7kP4I z(M6N@j`*ga3`lXtI6H2Z?Q@WN&EgwGSBBt^AwPhp0ps_B@pMpJHEPzsxgW=1M8fv7 zIW*mM>-_YV0A4grrW#r>=6RnSXt7 z%-(pW<>WyfstQq>+>!SoCM`24)&Wu z;oE}MnC8#JPT54wKZDgC|89VJbUNO4VmLOfCf6)MnAbGTBdJdHmkMF8(U)8KqEWKT z#hw1|_+N$&3Xc^R7wBI=HX~h{&#k|Rz)u~-C2${H< zvs?VVZF%uziT(|ri0P|~>7$uVUc(9*)}3}yTr;0Au2eYu(Q?Def4+95|NGiW4gO^5 zmDhHNnPr^JAj+afea?Z|As-p#9wDxTSGr#?8Oub^VAsiEsA5Lt9o^G_|3fU)yL=S< z;PO4qd!5t7Oiwm{;kVBTCz2F@R$$gG<@e}#cCY=yMvbD7>9-|G&UMdBUsR(OnsOhR z`5Ily%P82tyI*3K`^Pm@|3$znW!StCkqNk$KcWZR=gZU@B^GHh>C9_UYE&1>D#0Qd z%7LEPH4dVQ`FN7iDm7Dx8%sRHX1=G^takOrGG&8cb`clb^cIqBDJ;BJhs8;saLpMk=EGb+*XWK6W> zkr)LcFF$MM3k!ojEyG0-%lZ(LyjN;#@lpmFG-gnJMP)=jyFdD|_oHOhhP+{sBA91l zbN_zh7BtH{oKbH%QeNx+2aCGQZK@OgdSBsX!)@d{iTV9$YOUSHXENtynhBKUEOhzf zzjykg`w4yprsbAU)-`)uqrX+Pxl*fli!UDq|XBH8AHO7+}|Fbn8#u< z3<55J5}{BSrY*ht*@`#<{)OO2>4nW}1PmrfnepEk18e{p)gNFU2mujjSLZ0B*U$hz zr@&q=l^4Ml!h;~2#c3T+bhO^i%sW{YtDMTyOPxH}dx=XjNbXQoQT(SchzT#$)ARgq zP_E}U#6=6;k_s$y_Fu2hd#EJ}gu)+)Mhn@wg}|@R{wH9xWU)#{#zNm}h{n+LS7iF6 z-e?M;)bLN=WcmD2EJA*%2!$d0YP7dSP~;$!9d{74fLPH~u2!6}^B9aRs=rRMtOx28 z{!)s$-1&;ftjS>lO*QXk^kMtoH`-d)W-G7p@0elouI_5&Bg>vEObcg zS0(16HM3w+4W#qrKHUbt(t0CpgeET{e-(*Y3ej%gc zY)ON=C1&WLV8)D;$!rAQSNCPhfmtVK06&ej@q}oIf;28IRphaZRQhy9$zp$$F-6b@ zLYF8iH&{U`P*g5p87C98H*6PrP{17BN1JK0Sz@Y2hiY?sq;Np327Ks!`dbqM{fH;z z8y}fEUP`2r(ncxnPG_jI{I`}ui4S6x4fceT($o^&>(wcU?pLWXmfL*wmnCqdQmNZW z_%lYw3yjEm55Ex@7QLb;k!ua%GSM6mtDH^A%>^<@E3zP>LgRAH4eW$_jVS38du~Z5 z5-R{EDAK}*dVR-*kLjZT-&zI*T~8b6EjP_%b1X1~{+76h*c*jis%oHpZO@+g#j z53&g9_(kYuw^%O+-Dw^B+lYuw9VeLQX1II$&~bn|r^`ZPIE=QGTqkPf;~OUN!ekaDZ~}Fp_^;e(LU`6)iH8g`sB7Z&9G256su|<9eE|_p5goI z+2=-mfQ$=ijYv);uVyc~t8Lep9*aWz)Lh#}H8+5Oxnk6ENTclK`%1% z`u1$ilW1qa9uJECpl6ogvJY+p zK~%i)?_4wgR4E+;>-Cb(3l78LmT-phU@XVu41DCzXwsxHp&~^i>MNWK(MXM-1zDS5 z4jldcAf}i3C`trRzwu&z;8Pbaa7L1mU{?uZ&P&B$Y#GgaRtbD&`2Oa1ucX0<1tk%2 z75t<>c=(1!O%n4@EY$G^Ah*W5PaK8fTHc*l-*NE=iF_v6%@&gx^*2}0W_H`JTzK6# zE1bqt<;G(4g+*C9fE$a%W^;^8@A}??fm%R`&8g?BR_V0P<$9E5mzXUIe%nsjfOP6# zZ18aEwH2N!S$yL;mU`s`IkmSL7$>}UQnn}+t@ucz#wIT4TB#|g>T<35)F0M_6?4Us zx>QrWOQWMP=RWe?)M^`acdw$1?30_4bo2g%=58uS%|$%wG$;yv9yX0ZcmLS)QPa|9 zY_${943BAU?lJlpi<7al7^Um7O(=Flw_VkJ0jH^-UA?OGzLO17CZaTpHZAB5f0a=1 zQ-jk&=q}$YsF9 zztA~1(~qGF-rL>Nv?Kii3dS;d2ExIt!DKY?1g*f)SWV5pJLaSw#Tx)9@Lr|K`xfNIK zL|6AeNP%T;Ii;!ar76_qopeg0A>Zold^%mmWlx-PZ~umuzsYJkck5w7Ja?J+1I;MF zrA(vn62gGeUXR|{z-IN2B<9ObSR`WpCZUIrzX*-WExR>MEUQSAVC>@OXyI(GV@ipYiii`=hX)#Q4+a<9i&j9}h74#Q>w< zl#ticrEY-;#5e?Cp4WHbO+dALI9=pdIKSNW8C_MZ59+~mX3@V+F*wL7%rd z;k2}y11m#((ALYR`?2X(WV9mIJ>Tqy=joe|w+Q`@qXbSjRtgY~5wnMLq35SAnt@F( z&OP6L)fGgUPBYl1l7^L9A^4h>sZgRb-bOcEZ0hpwP7AU#NA>7+XdFZsh^pqfZ}xvO z1gPsJ?B$C#N4J|j(YEE5|uwp6Bc1_J5AB>{4%S(u~C)Na5KFWmHW!%-+gkIfPn^VzE{@F{W!=lXG4$M76ZN_wHL~y*_%KrllAnxmpLGDXgXOLRdA0bxFP*% zHkC}#eAkbZSy|##+bW@_9*QW?laa;{ldC^tv?ZY1KM(;cD-`QgHlzhsgZ(QaTi}Y1 zTiC)zYL`Z>F%qO?tv0WNFNtEbHKI+g{iollM)T#Kwz_`xBeqG5^lzW9PP0Dj;}&_l z7$}RI-AXSL`d`s~SBpRF@WJm==_9CVKA%N%5iir$;&?$oaxCsGQpnhMTe}R7!%5KD*kL#tI0Ucr!0Jlfxx8l(W0ggvo0m0R7kz* z4@WD?*vNGGw+sfgPjjo!FZ@(+8naExa8=XJhJ!W94m=%`$iUMfd(IG0Z#>MP)i}b{ z^?F+M^?s-D#5+_kj0F+@R|pj+u&F%AJdgk8XXVk~e-oo2^N0-~Z*gZg;8{pfu*?n( zo^Q6T#7q^GvJUbRy<;hvNMfM2e=ctP&eI!(FV>{ZoP2s}n#x=r4Of_|ajrqo6ZpLo zb*zcYP(sZc1Nmvw!CWw{Fuo%#Iemlb^gbg4z}by45{)nnYhugGHkh;vo!@kRiX`E~ zXDWVjFfv`8PwPM^DHBMJ{_cR?iyMt9lRqK|uzxk8xkIRE4)Yr|5S29V1+7lyEJn

R{4VRZ_$6(wf1}d`R z%>`zbvHTUMBpN~;_lj9J&bMlva0T^xcSf$(TT9}RokqmLFBrRzaXc#HunMfHG!(zM zwh#J#MMfOYilQ*npuu?o63fAe#f%Vpu3)#H#kSC7iHdOUC|V0gXeqmOGL7jH9XsSu ze3!3l#fa)@qarbkk{BJz{oD`NL$?bu;nt^NLUj*NFrt|2Fv5utXbWRB7Jr^W2M~Dc zcb*5mrb>p~LV+_nT|v3DAC)?qYCVf~n|N`UZwZnMT2_mR!((gxgGsJu`@u{!IZ)rz zdTZ0@tKv~%5nd*lWixhl?nJVRxv>vqFK};26$C0c>|5-gd8&V9HE?Lwwd_V7gLtul z5%3rk|I3%BzfuG6$r_0ZNOs1GE>Kx4m&xz_*HPzfVEf|#eOC;)aFFYO(L+aymZ&~EY;LI8OF=igm;LR&@k1_&ybq)Gu`dwJfPG?@Qwlrc8A7TT;b?R#?VqsHvt7N1!E$?O@bs@hYeNZ)N>9wG zLgqCPvMBO_1`?g&Kn8*>-uc&k3-!Pxbf6c z?2Sx`a}%CtcGHU@CpN zrt&u)?8UXWNaRyaloyI{beD{yN%fwjSU3#e=%(Z(*G_Jq#huvai^v62@Qx; z{4yseWs_+b<-%({{Yc|sA|E7j<7w(I(YR&g=&`U`^&&+o@wP|&0OyJsx*#b+`j+P* z;&czp2#COX#~S1s&4y!~7Sc;Nh^dSFlOnGIxv5NY%>J^xv5f!@0cn6CqS+u|VmFWV zf^A}TDqi3s$%a%Z3|ZIkY4CDIUydiH(a!8GmD_~TEdR+vYU@2i6mz8XQKs8o$&97w zZt+>$otg_gJ@hecr6gE$(}Mcsd)%(m3fJfP3HmMj6h8*#Vy$ogCh&ItXOr>}v+MnKoPZLAp>?Ys6_6G% zG&--crQqUz8PY?@ei%#|@IPw|QR0q`K|jTSLoQh=wc>I}ff1Ewa;kgKi}V%j>iHLuj97xyhwMHChITp>m?85A-_3%-<3LxQ)y!ui4hMl+ zZPh3|o+o6%FESehyvUPjHOs3$+gUV97z9DULTMg+;|`Q5sAefW7&E<`97Qi|C%KuG zOpF4KiTqBUgWuWGz`$pDzE)G>geL)aVai1;yw$SK-o(>TORqS|TY~a}$jRK{8?+Ow z&!Oxc#_^xym8-7#yqO>HQwbfELbGx?l@^|_yop#FXD}$4l^IOJnMqrdxw=u!S1qDW zUI#KTmR6B)5_ozZ1q&1`xwMTENR6EClVKH6?U%}!rBu&Mkv0DQiyN8j5yDpqEms2F z=-8tJD^CdtF@@V8!npaWlyZrJCHjJ`6u2Af9jcx&BEN)OtLi%dI z%N0P&fUM?doP0*15=4UA=Zlk_6Q;x|I~MOxcVx?c#N@0U!X4#SDQi_eH`&*VQOYL0 z92rS%5<2@%wWyU1+Wi-kU$BSFoZ$zc3)HW^0WzrVyT9rx?|Tc*F>{urc~$f@c(DuslfY1t@Gz~OGrrcEP=0^m)C14Fy3 z^-BPj2%(<_$ORlG&2?l0i%1Pu>7@r@*T+v}jO27)I}&JKH;Z3V-F~-8bMiFmspCT$ zHX;W&<7$Ao6(@AjZfxEn<*h~7)kkR=nWjsjk3>IEw|2UyLf;<Ns5i! zpp=B5uXMCB(0On$@{RxthbN2)MZyAf zWxFgkeWm2F-8vOHMnsWhiJ_ve#6l-N+7$b;MI~ND5Dp&O$V8k)Aj)5FX~nB>A*lIM z@r|;PinsZVJ}|Hz8|rDM~08N`FeZ zqbzRT@01Z6Q9mP9p?UmAM`V>^1+$#Q1zPl}aZ_=(fw$ ziGyAU^A-=zNy3-PFG{6z|1qJtio-^o{dM#4^h!^PP9ifsZyDs!aJZkvx!h3$;Wg^) z2}%+PH15GS^F{CTYF(fZOX@_~ffM7~NmEQ-$~VqQi5Mr9wZ}vrLoq1N~!yGS5?jq3mgE z`A>8rwY~te{Vrqo2;5#?^TAQxfnO%SHbZd~QF{&rT9MXrz`P8OLds(#1k5gwOc3%R(A{P)dH zm}#%KnQ`B3KVESpGaIey%==tNv3Df|2s^sv9~WM%270aZ;ZK7Aqj&L0TSRVbqQ~{# zQ@6)+B{=uDg=pP@>XKXkkCLHK4u_UDNci{wF%00lO9E;Hfo%+dtU z+|a>xMCogS1==`Ij7I5Y4~aE#-JDH;old)Su4NCgwNUY)N|3u_us(Yq92Z&`5tr4OxVGSMO+iwW9UA zahy@1aCioZ-Abx)0L?Fg+{&iq0BLfR1^c5QpGj1q9pXz6g1%P}9-I{LR^F`yrN(hF zm$oBtNyz8-;$?f+oGx@;_&X@_{*PjGy{L|Y9t-Wmc`swKQkG|hNJt#{ms!Z7pz$Ti zJei9GL)w_`w#-xCS+0d9Ss4i!j{=jZ>-&YS zytC9(mfpOnY^h%JTO+Y0j0N%t*FO1dtSbeQT$-3P5xXbPTYm2}o)~4KTHCs@``HM> z*JOf<6VKIa5PeL)M;dFfwoS&G?Qm+bKL_brhsll5=Sg=k6wBqTRD#z$_VD`canYQM zSb?*Rn?9+neGgH5DH^Mw>h(eWPP=(C)8q{|msiIji$g|3$hFb7D$S*b&vPN=_%Glp z8ZA*^l>FEC>#+IUfw%Fy9i_8br`UzQ$IdSp7#P>nh1QqDETC3!(h=x$c^b@2VJ0Kn zPyYU&UJd?Ol~9MnOEjp$mLtRD&z!74pdeVyjX)TT&K-k&KgoGGt^#?;p4#Y(L=#1? zZGz}_acVoSa-|WYVHwAdVX-PAQrDXs8iEKj@(c46M?@Z>QSS+_9iIl#@G5*WPf*{j zqv)XfI_U87Tx(+mE=GdIHuFW^CmJ_x;EzzZ#2KXFs|!2jYhNPyT>Ws|+2rR3`ux-& zCKZvc?e#_T+@b|;4TmUX$!nBCIF8Q?uwoXKGLvy5nTFigl%DMynr^3;(@F}pahGuz zNnp+v+wi576$cp}tQu*Lyd=Q=`*>Z{+M3 zi>Q>rD9I)5ZREP0{TwxL`2<5sr(Xi~of=iT{ZuT=24|NKHY7Wu{dgVS6P*{CoBu}T z2JRM%H@D9QnfnZ|M09aKa-SKye^Z4vSvQS*%@CtAmhDOo$1Tr+WfCH>w|%u9S=oY` zpUq2l->z9}5gFLa-&bU?KD49Lp6;_-9lwJ?j(`jRQFD)^pxx|8bA(_>%Cb1;RVI^> z?`&U59HRTPl7t62|I>q0D=H$QjQXFoP!x^Yh~aWjtpDeac7Rrah*v@=eFna46>xcU zl6Qxr(b|88d_1j$P7Pq)&n;>$Tmn#f_HSVVIXu36<@O9HVhJvq{dRglu#<&*4q3Bh zgn`F!wUoFFvY6iHi zh|f<4Ar$I07>QzNZz8w)=P>GNb@M)`P$6j*aI19{F;i$N_RJ?Mul?FaOVTP|be%|a z53YA$p*&8h+3UO>&?4um(hAj|X(yvM2f{4h-+{Ke(}I4L#5@8nMN8zYJQ$qS=WF5_U@a4)_;0+2Aj>N` z^C*NGeag-34ILthu+O6*l!!^Z+0Q6n|7J~~;x`C;cR;+$EBOwd zJqcFXgL zq#={1=xutvby<9;=Q?G7;AKJxm=Mw>BP0t!ZjS4N@A_#vh37f&eIkcv)ZG1U(n*}y z^?T28#`$UqKVYRBx!>%}43dy#IVLB(pWYuu*__w)hLz7Mov~hM=br?!wr#zlVf(&& zI9iQNls3TCb=VzhMP``W{`-$CWp*OeI=B~MRpCma6`L9JV2rxldsobpq=g#XbGfFC z(RwGYUW}y0JyF4FDu9Wm5G?ro`FK=aUt0Tcg!l+K=8uo3?mMc&NbOGe_1C92gtd-m z3G3{MrQsZzoHgs=bhc#|Dr)x^gJ<-8NgKa<3-CbGgu4!dhp-w`$3&J|>?0OqYp99N zYJNIO+%k5v#o;r_%nS*9>D;`p6TRm714f%pB#(%6MrASE6b!ZUcs)JW6dv{d(APXj zoz?~)9#!%^$nIFDt1bPn@}<{@gMT6ycY^#0{(N>kF7eg@am)b@d{zro;9o!fq7?z0 z>wXRtfk%%IJ_<@=CiMRs>a`3Xtf~#zdS>{*XlwzROr(s+eT&|C-8pk(yC2DP3`-@p z3^D}64a+RUo7ZA{((S?|9$3-Sg_?cUl@#Bsu23guI@`?(st3GBm=<)4>u_*@?cOL@N7+R|)Gbh6zt`I=!S7QW-9Y*NhMTOp^_QSVrbH+c#a0 z(Y8Sf)VWm;T-@y8*ek_RZK9C77y>>7()qn}PacD1hEcNTGsZ#TYiTshEfKF9?ez^^ z_feHP!(bP!(M0K`m8%Wf?r$VB1RFiJsWj;Pc|qbkePimF@oD-$izS?L@oPIv>koQB zR6Ld4`BLJ;)hem#-T_4e+I;e~UTvTP;I5qsQLV@jhoR^l7O2$7pG+@)?*!y(w7bEl zm^x1L&&>hcPblH0hbY2?!4SOMHZGPWMWF~(kd~=* zvr5Ed3V2jh$Wv&n`L;3>xZHfK$%OiTcxI%9wO1nMHClqemVSWJ)x-H%rUJY$~rJhFPGN^WDwE~BSeK@qX7vxF1(<>48WKB)! z2V&X&^-g6)!2NN-!)EW!P;K`nUu+yOCX5?|@xDGAk7_|eSL=23@Q7C55 zF%gsT5WI*6Datmm`lq zA}!eVU$HXZ-E|H;g+eO+VG^e05d3Ja35D^W=R1W-3Umg#G+2r~z(59+dXA^jdhk+2 z|2`LR#2_9$N>U&L<6G^}L^=C-l0z2`-fEO)JxxDPDA(0C3f6KaLljegqhkw?pskHI z6wBmQul()d*yR5z)gP){r?caEltEZ$9CATaY56bLk*ybSMT(p2kLVVLsQR|MWquVi zCG6(#o*6}=C!LqsU}w@buifk&R(cqxv5O&N0tOP9_`tP1>YJz^+wTs(&Xavx!i+ z(Df4_TYpsmw%C_B(3p*;D$jGIgVo{)PrUC8|2&ch|j;GOS*+`mf ztCXIyomGwax~WR8x&?1el7`|0X=Gs@J_k@~7Wq7ll%I8%6F8%}UDw)VI!WyzK^yF0(#Hg~+t)TUZJbRjo|U zx_@i($1u3iKVeD0`Y-|EU`+a?gbT|J%XyuS!%MYP-gW8_0tAd%=iF0SSW66cRx$`j z#_!Pv0UCgYB_{$&JxP?~degZZttIP!ZK*LPZ~oaUpX9FIUO0fTagf#vj&;l7PU33k zbACtH_c82Z6LM8A&p)Q*f%EOqYBG7Dv+LGneGez3?Z(IKPa#!=LXu~(j(qn%A%|$h zE!n6@@B&ragpuij&@;PE*R2J zKn$+t{Wn(H-Hgpl4A98QxVH^3&8;hrMoM7H89O!7s7Fp@Q5)?K+N6?W!V#f-SA6{4 zp-AeRk;zUXz4gXC=ArOohaSiAheOmWYE={6kUK9&>>f^}pGsis6jt1qjZe^)r{fH3 z!0rY3U%WmV4@Rv7REtt4#_*q?+VWLdc5}AMeSgeOHvgE+&N1Q8bBd%fA6~}*^@Kp5 zxYc5#!z(CZsi#6#DdZ@a%ZHbEjUxi$QccQMQZ(Y1+3T}C)y>SU?J)Kcv29*7PV;?k~!BIjS z>Hfi(g6LA`UR(Gres?g6(h*|Q=TGAe?^U|@Yzz*$z7Sc?3C!U0nl-Ft*Q=H8x6E!e z+9pr7_gsFnRAJg*y=nS14!+k0;!s#G(6uchx+kmVDWu;@{hSTA`PSRy5r7 z@6J3c{&I7G?~4=sd^@db`v^r)`$VIz_Bz*?lpnT@;Co263zHYd@10i|*A%UWFxljb zNsYEqa&DN*g+o(Z`rr~WC^|)+3wMJXa5|hY^C#qxb$;fn^ZV4ytt}J>K8VbsNN8(J zNFQz&XuZAI$J9ehzKv{|XDRBZ^+Ab@+CSZIj*FbkXUGIzrQnz?0tIdy>zqp57gm02 z-eRIL{MJ9(KNzn9n~U4@*xSP6jwL5sUmQkyEheyD9j=)x6%B}OYZ=dwRjsSeK?VAG7SKYNK{VM}oe%4)kW+%$46}d{8 z)NnF~L%62pz~B=u1?iQ=k$Dk~E^o&^7>@?^u-mGN%N#%-YsJoW#W!j>t>_GR=U+i= zL&>&{FWJ9V?x}at{zGa}-_Hcu43fav zs0_H6-FXBDlKJ%8u!Kec|i&bS`geHk6NlhT8PN7`C%|fF( z^R4dz7v?KkBbeEkjW=?j?Zxaa$&JM7RFJ&_p+Nu8mR&WT{lfolRxy-l1d<%HMFRuV47mjFz zgu0zN&A(jaD{*kF^wIb*D3`U5e~44l`BRDYs*@5EU464U3tN)O_qF?AoKQ|mW2Nt4 z+IqdkQADKAPN7>JP(3Wk{~Mz~b1wm}>M&LF^Y8eD3HL2a9HwVIUyTVY1r3@{fM9Xa zq(oO8+wO(kzTX0v;NTl`+d3a*VHM4SL0Wa1zTF@=6Gs9*i!MvW5*eGo2FP_rw>tk2 zE2;H`a$>c;?KFKd-|7s#1%MIx*d7H#l2Rr?`dPcALnX69KbOfi%ja+_%o>MZ6+D@R zZZF#}DrY)HCmu5(p1GD(QqaWbjFIo(f^~@_96KR&=l{{Pn*o>_e>`!g@Uv~d9Fe2Z ztG&Nn$yhS`bx4T6HQcp2vlnCG3D#VWDlplQT(!CnU>W7gJN~mxd?o)ufh%wZ%UmBaC)a6<+9`4tot zG`N1pKv10c)(YOMh4hIZT_U)pw6kb2$8|Bdi$)))2*9)B{GweZZ)P41#*m`T8Wdc< zDjYmvi#QxTYkc+#)1{|V5ub0wu2XFmHiPA2BA&Qknbvg&Kx=v(TtJ^|N=$wZpqZ=w zuc;qA9Wym0BH?3J^6(}D{3)Cok4%K%ti#7sQ~uMS^!W%{N}#s8#*!9r=>aDB<<58*P0OC{Q1WSRir@W8w8YztNw}Pp z`&(}kd(|tlT$P2A^C6+!FSdr@pOQz#3bm`QY|?*icpND6zAiYqy9vByb!(-NU&OGq zu|$-r0bp}`zP|cS=5k)%B!zL0FL0INTW9(MiE*=14VKh>rnz=1B2(Oa?%`a}{H7O5 zxs_Dn7=wg70NjLrZrtBM>}jZtou3J928Akqn@+Q^?a(c{AQ+`a`)Pns9+VBnYhZu0 zav&02?I#}~B#PS>$>Fl&l1BFhJ)PhvJrU)1S$t#Ls8E@7KcC5Uzgp7xxEYQ_PUlwX z7HJ;K(VhYdzW1}X)t_B)3hKQ|WY8h%u74M_E1jTHj8uzObbWQvn2vmJ&E|p}z76rb zLwoz?L+9ydf>420RXhJNriTMU@rI7bHgp0ZyK|Jp|8?+`-q zWuAz^%fVq*YTxVtEgYbqqY0#vZ7wG`95yRu3VE*&XU^FGXpV7Y8vss1lEQ!S4seaT zpPvOm5KWcW(fg18a&Fq}ma3CFt*O8X6(Q0YDUo>O;s_cbKFn3RUu7tY%oT4&!IXBm zTbn)qP&mX}HE)z=(4H?p3rQY~7!rgP6D`Dg=ZpYkkYkIEdyb9olfV(7U%94Cazu(* zt&3%KLXF;rk7e(1FLol#MYkgHq}p7z(_u2(?k;~C)3?g#I8TN>$!Tr4$QK^iVgP8Y zM|%WXEt2)m1gexuK^2A|AF1mQQ^%S#l$nVBnPlS4`}OVH*S)luuxbvir1ae(tok85 zH2Ty8CbGfb3K>&|ZB{qGSLs+3W8YpRL8-L@r|OUkH%O$%bc>Gz%#`3@dTq4oI{UoF zkM^rm%oknGyQ3;vUAK(O1#^DE?z0v%z!mmZLUgk;$+?IHtlRcE=}#cV;fxP@)O62h zkni24;Bt`?K3UeQf*nhe9E@V=-a~{@mGOS}@H8f^?&tB*nEYH+FIjxCdwU!U3F9hT z2VmH~6fm}Nuz}%VHA!z3NO%NY^Hpjnx$}E9?m|#8tigbtE3iZAPFz zXuGvwkwOOQ*FRe1bCZ*aNzVh}sympK0#UvfJ50tUa-~FxOQEO?*2UoHkz}v}oNQ(@{g2K-f#{~O){nYJ`u<#5v& zil*G;5v@?_XI!0=BpfvmUwIDZ=(+Bb<(4K=1yU0ap6}hdOZ>e*CCZ=4Yy_o=uzV(j zquFe>Y*vf01i#jOSSkG8L|D2yFj(xy%W%Z%p5tY_q6RkO&rda~;ViGe;A4VCKfP zKJU)|oPLf}pUgLX|AsLACBeq^n&ha4?j zc0O61fa5Q%AxtH?UAWjLXw(ULu?T!`R{96Fn}H(1)EQgc` zPDvWW;{N+zTP^k79CkA|~IG%Llq4mfIh_!1wz@hQ zAmxq$V}n{H*%Yu1EgySBid6KEnHK0Ibnst1&Z*YqA)r$I%KK&l`TAiwQ%%4_aR()w zZ9(-HY$mMRbwARpMhp%tlml15Ini~c`tmPNr{nm@Dd!uJ?^xg@>=C|i3)eDfk8sKc zOa;iL&{T%|RB^3~RVjJE9?d2&L=l{b@ouX{RcO<(5#(s9k^#lpj%neK*Ti)+(ilo} z`4^zcTlK9>*bNZ5*lp6ovWB2Cdl%J*v3nj?&D*5jc5^86TpllT`6n~JDCAJWtgX29 z1-f-0(d0KfZgEx&g`ly(M8M3}<>%vaSA|^vP(* zFJ&=}%nkk~95fkXn3m1ooCubREzv4yJWNA~ZjfcPrSBY*7jXso)&$hdbCHRctBtpo z@0VtwaCWpj{B)-0e|(C@rrdm0PY{;+xzHlYQ&^-ZEcjV2bz(X`!AWnC9jkFEbkU!8)=33%!>06-xdjhm}ZJ` z_`lbi;I5@lJ23jdM+mr-GmLhvWSOgXdLfq$>wC+MJHTV9#YZK84hGH_7E+t%GwOI> zM7Ss2&MS;1UzP&u?WHI}ECGF4F*9z5=N})8pAXo8=7U>YNF9PqI>E_bkov+?xq`Z& zwXnmCGP1Ed$gc$#}WsHiz$$J*9Gq1CQ{?y%~b~toyMWc&((~`2)4xr}8g(ybV|NKwjJF?xm;a%t3y( z6&9T(j#M~ocOp%XqgYfTu><#B}1PCqUV92hM<`3qjB?SH}=c3U<3 zbjMahn;o9){XWaOIBm7vdNmm`DUH8LfpLtCrqf1qa*orw)FBQ83@zq%Kgp`fzO%$= zr_BG2k&xhgjT}n&a^3IlpOgzurS}Cef;lZHr-y6w^FBT-Yi(_IcQX+Ez~IhmQLQ}R zi{n>5R_cI&^9q>;53D+n$MQZ3YYwlGH(z>UaH>j;EqPp&wXBzvwQX{qB9u{tQ1`Pas3NRBs@l^__=niW z4?NtdT++$yMRj!JAYVN8f1vpl=Lt2$qacn(SIgxV`<=v^o`f4lvfV|)m1;@Z5->9q z7b|t6>`!f?&1ife`|)Py+}y|SP4<}} zdhF~%q#o3h-^-L~yFoMRK8z20RHGt!o8Eof-sxqT`}ltM;9A_W6C=X#2whiezFecM zX(1TpzLmm?NX2IICoY*?h?LmdYWXJ_a(>uF0HYTJUVwZKni#*4SfK(c zx!aPa^v^B8m2q+?bR!{C0Yo99XcV485pg-kT9fdoeA>Rce8<4T{4QsNk+G8~Y2yvI zg(mNsEeb+~Neg0G@-%ey%i}vZRE^G-ZkH7;)~WlqJ3MKw8M|g&htT}&14K%Zm5c4{ zqaY@u{dPF?;E`kdo>rw3;P&c8yo)$2an&l1pEJzw1ul}9`IO6l2?83q@xfzl3jLXl z-(X|~`mA&eJ_tOOt;}3lBzjH)4j)EL2q+@J0va;1TU*@*oZgKRPOvL38xN1E8@cd% z9H8U-Kjr)cX({^fe-Woo)tkUV2jsAy|H)yeP{B6W26tGz6W@o-`NF~B4|uO!rf9ty zd|JuGR5x&G$5W|wHQU_+SqUxh!oDuAri1{xm?dH%$Wf)3c*Gs=!d1g z^uUV$+l3RA!Q|0I#Y!O15-aH0U>Ho{%AYo0bpP{r{LlSmWP)t^9~dxNV&hPR$BpZ7 zx)B_r-Cg&}CwCNbE(ym;w+E=sJ~~bjOVIoL^(y(oonA^L`v`#CA+*u?&u3IY@FrxP z>L`1!J}ECaPJpHCBS!NTpO+2dRD;g8hrWfMQOBX!#19_&D2MWwf~5vr@^|m`?KaoL z@hAos>pZx_W#8KZ9HN!uz02))<&uuDvAyAgS7wej?>jm42jjTWKcn%kdoh*wm1+;V z3=wAW0-X#^ve-?He{I>re5U!=%IiW>FV^fnXOD=ecvBvTr9#?(E6+D`_l8>@ow^V zTjL@-@hH`@Uh_|-vE6$4FZfp5YClwp@B^SIsDeaXY2(@HpI62a8DRO2n={?;nt z?Mv>s60jd_b|_e9umhqQF7k5`hx&dm!WB^FY2?`QjZl;^XchsnKED#yg0j5hZw5QgOP==LQ_MOh} zMI4k}idA??&nZFz-Vb8u6Du0T&XeuQ-Hoip}jtgd@)xLo@VUI9=1|ZC?ts(?_$Wv zexsDpkc2A#Q89eN>yU&y8}a3C{je%2(A0#`VVQKenc%aKb`Tp8{DV==J2sg7$AaJK zQcSK$iczudsx#qj)IC}*X0BdVfWsU4k1^dQqhB3)$vfhh6+AUvTF6j*`XnXk1+W&U zsacyKIR9$y01%TC(`P^1=L6MZ&7(y2{qder@)+tN)}qe$W*u(6}Zl??xC!!lh3bn5d0aOcF z+;K^hx;RAGnLL3|jT2 z!E0@{xG=(>6QEWgwh`Mq`>TJ>)Ft9lYn&-b10dig3_{Fv6O^0!5lF=F&mNUVRvRE- z?>zUB<&;QHu!X*xSzMI^BgH2rdUIN1*AyBjA2L?(=rY-dQ-Y11W&I{l{{^ZPra`|=Pgq@S0UboeB16_s)-`c0 ziXnVQTQ`As#h940Bh|+k`f3cvv^x4K>e;qL#EfBX$ssmD(F~gxozXS)y)%93jsD;HQcfx z!f^!BC?tB0;=5W)>iWK}&(}Mcx-Q6-n>(P_`#phRgOTXg5mql-kh7+yx&QvkIT^h; zOdr9TZ9_n zaVs|@6@-F>ytQqERvVPD%{*eWSUjK(yUbmo)v-c1Bm~UsH7r1s>CJ6xJQAA75+qkp%!(rQ|u z+uMZdEi{%?i=Qr}gp@7*$}R0648kKF$O~~!;G?-#rNv<4fc7ZaZGCe{<1qG@V%CYln4WjlJWx&QA7-Y z?ZN9{I`2!}o#*O{nQ5!KbGU8_NXJL!+_Hu+TS1`*itPFFh%Y=}_XeX*{~xN}fjiHx zjoNM8xQ(qlZezQ#Z8dfp+qN6qPSe=7ZQHi@^?ZBx{l@+S86)Gm*IFm$JZ2(GS$lZ8 zNP*Iy@~6uU@1*WqlN)1cWIN?Li!!^B_^DUYY4}*#IUTnWNb2KePj~SFwhgIjnJyoA zN)4r%g;-!3msIOqSy(BbhGeR3YWnB(5akQb*}`+ z$aI&<5*k_a?s$#v-(|hNE=Xcd(W$qLD+XiJ@hrGmN%8=Vdd&akQmd0t_IY;X()v=I z$^QkcM3v4>&o0u{7sKE6KkeD!Ha9e zlaz6grOH){am~J2P1m7?RD#bn%MJ`@HXe3^3DKM{*WK4Gx&Yjw0`WghI{^?aSP(KX7uyBVzh?{qZ--Q$|@Hp!YM&wZG9AS`uf%g*J~9rX`R> zB1;hLyyu29<2SfektgDxSOb}cgmX}T0o^t5wy6H*^G>=SN?SmK=n1xvxwu=XYwZ@p zD)~jaozT$QzIE zM8IpoY2;D3N8}mVcRaMaVy&EJ%PmBi&iZRN+Qvm=p)!fQ2tpwZ(8IgsbOBSJp9ZzQ zFXuCg2Aw{nl84^!>PF~8n9F&=S{eY=tXS1}tTeIz?-!t|M0*ho6wwgr{cC^TGz`=A z<@U1YTCP#s9m(`HLK1)U_wXXbwsU!`$SG^NtC?l@jxTxJO#AMHs0pyB?0^T{Y; zKjPn_-%R30Fbom+sPri4KVA5lIQqx+N@DzB@+NNeMJV{(w{MTa1Vuh`)Efe_RCc#p z(@+#L^Ckn$kB4j;7Tzk~kL|wHMz1F$7GaR9+CWq)PyO>tci^~i-+zt?f_8AITXZyb z5^NgtK`|~=3JG5#4nS5$026TXbZ|mQQZEmJ^#a`7Ee>XH=f(0U(Eatt1_N&F``kGy zk@#dy8P@F_SBdbn$gmDufdnJ76jCvZg8H`DneNwMWIL!m3KbgLtY%rBg$AHky%p9r zt!AY>$_(dGEROEu`MF%vKTRI4W9GRYhg<+V>By~?4Gy~``jh)6*xKxB)4qtaa;ZzN z7!%%8r5IqxJ^HD{upC-7j)W;_w(45+gaXXtYtv?a68=j2ach&pXgn^XlwS9T6y=)= zB{w8PQx6+z@9|t*;i|O<_m$8#HF3Dn$SpaPResrLu_77s(OE9#9VFb)XuzJlKrUAL z89-AHezoR_2QhfJIX9J8@CD<0486#= zOwW39Nt!RPR&;aykzorge(NQ-`hCoGR-M5WDgABkb~xn*a9{}mlR6M}fA%&A+UJ7)O>S15v{5}f z3&12Y&w_B{8>a{j^Y^a!FP=`r*i2*K_;klViZZWPj)O9g;LgdT`+CvDlE3X()Z zhyR=T{IA7J@ONytD{zevkSXDaQGzPn9R6mc@aUftz0Cg#LXJa*#x^#(Y(fk8(oe~k zG2AlZydl2$_!|^F0BQLpk#-K!ay)%HG7wJO!IrxAH@-J!C!zOiERgzx0X7quF-61$ zk1@-?Qm=3wR1n2J8ZVCWb~uGf_>5fpI|2VP!x;@q@I?42@A&0j8C`cc%Q2Ay-DA^d zA9kwwY~>{U^P@sRty3x!D9E+Q(PHTt$hEK%y^!tj65mb)U5&9#Q_rg$m#K2ioZ`~^ z*^Xtd`#x+W)$1|;pk>6Nza2{^ZenpLW~MI)7#5Bt$u;#|<>D+g6i395#4!tNG?uOt z8TYBxtQ`ct?t@iDm1uNR(XTA;b?Z8CA|H-l?Hjw!EC8#5q3@EIjGr1)1?e+Hb`UnaJNp1JB#vpRXj zUz4xgaTP=xDiRVD9SYza-;4)|U|^&<3jn+NS?>(Q9;5NYr zqex|`ynNWO9HM->9-n*WV^s9|fL3R->sm19DRRkW)J@7ssg{cx>nhre*S(&^=nKNp z%(u(5dDDVXZablw6>bq z&Me;WalewfvEHlpa75SS zTnoAG_JvcX45O71?V#*d+>& zf0_WlvVJJqu#a}bs~GIi!2+C(al8C695qiez|PM6pP8W~MY|=gm<3_4QPsFm23XQ# zf3@K!m-rOk$`29kp#cWm=Nch85kqMGrh?AG(*2ndkB#AYN_Zgmbg+o->m z3L{eqO){AVUcWgU?-EPCYJURO!ZZr`gBw)nQ)!7qNf#G|(mE1J=amje^;!1git07z zBN;D^=;!bo0AsPm>Fj#HjZeFI0tF?iP}aLuzi&qc;pretQe@rXclR19N`5fa9T2(l zs#zQ3CBmm$sOfPVTdP&RYU4iu4hfNoTWp(u0m$ZWYEj(|&l)7nKsvyhY!H|ZH`C9G z#gdrw8I4G+1KSdHhufjqlH<@~P`@t#tA4B!jn6iCEBL%2Ol2F5XLA7(6_Fw_{bB!W zX<94zV^+}^1Dde03y6i$-{JGFTy)HxduU;R!9Bi04*d50=<)p3f*$NktW*$E(|%AaX}?Ze(PMtLF%zc*#SzeHVhDehM>>}}b&_LO^NnZ4;I7{Ulv$kf z#ap*&z*Pr1Ez6feN8_RO>7wJq3z*l?kH7Ox*iYaO#qR6`1XMB^uWJ9@EOa<}7Z-D3 zv)>;riyZre?)9Phe7iwPiZ>CnRXLi{knX&G84z#{1&?&Jc*TAfN9^wxz|a*N4rqW) zGd$}HQ6sB7Mlj4^VSbZS6|ZC&3@{%(kFlW;!(*DSvE!_W8La2{V_;@ye@QXbj_2)Zk|t41xy|V<}`^{#pHy(QvgODlXS%sWL_)==~Sp5@CE+vrrxROKhrjN4 z*YF(ko6ciZt(b0Y^IT53&R=|^dzq2lgD(B4eT_1-Tvx_v7bC9io$0Ak%{n;#)ahs! z9f2kCm#0tIj84sF+qxY<`YvlG(YhTICo3k7XVk@ohlj!vu&HXJx9u$E1j=Sv5#UaG znc|{_fS@2u3OiP9gE^IIjNwWdU7n9f*9lW$basb?Wo5H|#(qVc0&tRG$7-~-9!;&5 z^6rR}q*y$s6LtGz(mJnkWXB->O_C$$+bbe?)c^mlW3j?1LefCuc=S^Nz{;5{S5i}2 z+@2R11~|d)kUC@U0ANbE>6DRaM(xLAQz{F~NNRoOtku#q_r2k+*oAnebXsjdqn!~f za_t61R3`$X2onZ>0o7y=eO5i#*rPw|c72Lu{jI|uRBo8=M`8g)L^{8ZkD zcCD%W^DWf%u4@heHgAi-MkXUIZ#-|l0EirPQ;Q}Uj?BbcV)NzRIgTaSOEsu9A(1!< zqzUAAfw_Ny*YCIc=hGGIq*37IWC{}u8f@zun#!GJ)^$Eyhs z0}ORx>XELID3_v}KTjlVGH8H6@ii8zC$>t}4`1lI`SZ%=5(7q9-c3bzgmz2(UN2Ih zNKYeR(wKv@-!E1mF^Xo&Hn`5$ZQS{Nt`%h4(GQo1ZE#pl$16TIu*?T?>n1%#U6 z(o5ZjQlM?H>jykB5^3QwvTni!DnYT5s5ByLw~#YT$}=MKeIE*D2;2KL%E0@O-d%q( z&vF+{k?g5LV8+Eu>r-tsVmuVLCnlwbWkRCk{bv1q3xk64F4T@eQ%ZIo@(onwEztcg z5EupGo-W{uqg|`IJu;d<7@;8SVw$j&6dQD&@m4VY@S0mY$Qnrt(qg{@k$ zz%Hb%p&Af)R)~c5Hf%_+$)u6P5Rzfg&%Ivl*g44&@na~<%c-EWKqI2mRLxgbYS>TK znxUxg309yUZ67%dIs%@P=)ZoVgb8%}r!^V&7YL?k;Rd0N8D}dj+M}OZ3`3t}Bz!~m zO1X2c`PUSQp<12I_Vd=h82`|=5D=f8d>Hh%wWup+*s8Hjv zblYFvA2e-|GCym@=o+k)|03W6&(8(EO^fqG`!Wpw?6 zui4zdP{D%#>l5W@CJ(B$)3bwXDrGI(2J^<%Zk9J%ZnolIb z$hh>GL{)%zX`s#B-LR{X zPw>dE_-$=O<)O*5MM5yFV5-q}&o&rHc(igJeUEdkHpR+Jjz>U4GL6N2*t?++GFP^z zA09v29W0-hAIA4Q=z$#r9P~=tACXF>hRwlpBM!k}5DphnjmSVc=I-~)(RhWL!Uu$p z2<&TA>=gEoN5L|BEJz^r1{%z(%*%6cZS$c17uVI1H@f+j*w~K+dv;J`cX0`%-Wq3< zHMz{J8XB2=;)-$UQ$7y#pyiV@QhhmvA!I*Mgld%EbO1BL9pX&X+s)cFuVg@Ok7AYce^7d5b=_xft}5_Os?zb{`r&%c7HSb_ZzARmW}IYKJVw-SOmcV3|c&fqW-4?cbJBb zmp{&_Zw3RTm=)bSE1h zy_&29UhI?Sq0n=sR87zc`s{L)V9pwdrc(l#r$HuQ8sp=I(twNh-ut=aClW!quJ5Mn zBlz`pc$oALa~vXxC-nGVU)a8dr8-4nXgA9Jq?YKU_UJFbVadIK$3-19Blt4^2d)bk z4}%QxqJ8EoGGITp;v|_DryrZTOfng2wZA|7>|I`d1#W0!_knzQMSJbiVp&UnguRgd{Vw;TY6dBWxna$izm8&vXQ;UzYse7d|Us+(W}#tm_*^G3n&zd*8x%#U&F-Ub-Rq2c16Rr+zh z_yrOr(4zu`Ukt3c3oRftc-i(AxfzKZl$-rC3MA3XeYuSt>Mn}@+85=ztfqJdBZfBy zg_q`cExI1yli~lx`SGPcat2+&lbNC!VM0Ik3&qjeiWJEFYDN}E+3!c6=cTU|MaT~O z|8H(OGC)XSdLJw*^{2I4h-l z2;#cgjb$xXzu5q6vB=nrq!#n#DNH6_qv&;v`n??$njN+mZ4XYTi?I{Cz=~xjKeW48 zN0hz4Kav1;==nafF>D3#m@@=~K#b{FBt=^(1behnC=D{6&whFev2lCYiB21U&fua@ zS6(ku)h|T;bMShT0O~}|H%|O6VPXoir&1iF)A;3iti2rPC_F@XD&f0Xy8-_}sn!xV zQukicH-z9DoAKj0(D+^ye%U9Okv%=z*Tz<{!-nTOvg6gS7#wzk73zO=;jB$1z!>{8 z?W4AX`~*Ym%nQ;A7#20V0SO>S=jGP^2%6rjOG2_N2CVEOcM|49!le%@M&a2?kv|;z zESAfz(eSQTBA-LC=r1oo^<}lvkVbblnv%D#ckuo~Hf2ycZ#07T%Mf`!o50m=TIYCn zDnzNd7VnGJ)62!kO&=BtX#?5VMJUB=zu!OyFb++}_%{wU=Z{)00?~u}86JvfAYhX? zi*!y7ueB7=5_m0oV55(}&MIpB3|~B4VhYLt|Ne!0(Yz`(q6D>fJzreIIZR5Rn9Y(> z@~vTGw4?nhh{HW}pGrkaq{-dLTIr{&umzdGcAk-BllF3b!d*JwM-I?CNr^Sq*zWY} zxQ>CVmL)b4dGGW`0=ddmfuwa)&2=-@fx7g5b7wZ0KIoBaS>KZERVK&U9z=#XVGpql zKE~zqNCTWs={NoZ#cGIIMvL3hd$%wD6$S=p0`VLs{So5iO4w{zU$`GS3Aq=!=)Gph z9lZ?`C~m(FKz=^}{KN!!14b81pa~fpfOdEc4<+n5^$jGg4*1~Q%jJ7O%?IZ#j@Y$i zvVS^$+A07}A9j*?qq9taimuB{Tj=dA>;$=*at8=clxQ0}Z)>uHCpbq&`^4Z&l*GqC zP&rPeN}(K(5!8jD{cTP7)6cCpq?y3B+>Gh|k6I3wup?LMYAlGl*}9!UM`Lmj^ps;d zA+jt6_`+yAFlbuc6-j{yJLy18-{!WM01OZYJ>S7)H11&tJIV3a8cIbC{YKB*O-bwY zp|EbSf^*9D{4Yev_sGNad4RY|p}suAGUEF7 zD4K#)E1m6Pq?kQmlCC3}&?ke-x&40GqDmNjN36N%G4Qk*p+xtl%3(Lmcw*Bgg% z9(S2n8gO9aKoP#Z$8Vez3yinXp5NVRb|jYOerdOu>-G6U?2q_F5LOOdCf7&Q38J=L zOCXlkhQSa@t(I>UrtKox2uU)4w>(tyi!tfDUr$R8r|Djv)`X#ju(WLPeH8y{=@8yH zn(E

Qpto2P_-W(1NJ=F}SUJ7}}lBcl#y?DwQgKdt!)(EpdRyF!f(mQwjyKJUs7o znw;oXDEyZ=m04WB?!})9Z^r!fXvPQ(v{R+3Z#0C0y^(2_GL3Q3UN)$}3|qPxC)uic zM94>L=6t`zcytP{Xb^a#8?=09E+%C-Uar1zkm*iKycN|QxIn<=gy5)A7;$Q8!Sr{6 z?*p&IdyJ)lOQBu4REY|3#14F?Kc#a3EguGLNQ-{a>3LH(wSu3ttK3o|~CKj}2AMJ2g zYqqbm;VP;ygTKe$GMu)+O~52lhe2q6aNM5C#)gWhVS^oOM|iqga{V7V4_EerS|GzB z9Hi<^iiAJy-@k^R>sM{GSZgx#dE6wcM0*N_(MTdr13lt9%6WQhfdrLW=lJ=WhH{m8 z!qaq@QPR<<_j^gAIBv+Y`s%7no`N0c<2Jl&m?wrkfQ!eB279>ff|1ypsmkO0u2Zh9 z$pQ7#ZDb-$bSLU`maj9;KTF)N@GSTGQssG z4$?Tdw|7CuqB%n3C*W%$5e`!-yN^z&07bc)A5>JP`sb#>f9$$1fD;>zxSe}jI6=ppaF>t z<+g;=ku(l~!ZVGxCHjWv$l${(9BQ49CUG~Ba1;T3X9oc6I z;0mp0el1Ow%ze=IZjnt@{mXS>(?W^y-zeZGVrxTRsw2EK zrji*_f1S(@NkR6h;>D&{P3H*SVsFNX5zS57@wlCejvkDqJyefC8xP-VW^j&G@^&e! z){VvPtT-H@WdpA2N^;Wtk;Jo8T&u<$>y7rilLfZ+>mBbAUqGy$;*0nGEcv#bGgDxcq2Eq z&!?WvEE4;U3jXcHQ_S$W9RoZ9)T2nyhv=%N0^i530OyQFH)Zd7A3`J=`!G!V zqX0RTh}!vTDtX<@XZqQ=-*=mf3}lUPh%Jpkb?bdH_tGGl^y~2H!{s}%UYx6opZmod zkG=6&F6Os;Wxxgrhe_*kzht6XET`A$1Lpn<4%yL!2Jf#;1TOR~X0XCtfD^i-O1kL_~S`eGHw4nO=FCs~WO5!@4uzLmw>rvK>weRF#m$kz)70J)|+ZdscAw~>oOkP6lVhd6gCctWWGUUBOl0WiqmXdkx0ppQ>Ky-)t~ay?4m@>%Tyr| zdPD^y1Ds3n1_S2MbDvXk#MWkVRyA@2o@f5*?Q{90=Xn_ff>lVMk3qLMtGw(Whf4j~ zty|a?tYT#0eXE_1Xrx&AIu`}~<7tJ3)LAH&R?8HK9@_n#I(RnKV~w)`=9Y;HBqQkv z1%VN68r)a>G+S9sHKFYxnq00i4CR0a+!vA>Evl0)*KZFBkEZ)>cihXJ^A&N=RuIRl z_B@Pdb*5XZ`-w0ck!-00|8a31oJ|Tp58j_O?=RJiB>@gnq~>L-F&vJF+-^{b2FqGy z0$1mM;VG-n4-1q0MpJ-nMIPPb)i#^L3)taF08t13Cm?SYw%?b>4qfrn3)h{$c)%1r zV|;dx8&cx*2H>V1sa#0MTK7NkV()qqDWHyv<+l33xt41 z6$*^KJs+X_z1k;9C#+MW+XJU@|&smv20V<`vj(ba|yWM~zwYJz92Kh5` z6obL20oN;~Ga7fwH^Qj+$u9j5FUJ5tvzt3p42(w|dD`5|ju=&dt#qbUL~yJG(DjoR z{M)V{L+Ak^vGD&6vpLJMUs%?vEHxnIxHQ zMz;&4^E8=?GTPh=ssMU=+%m1UpNx&Ij#{pIwJA1}P6V2D=n#Quza_lGXTI3y5&F4m z&z3^9mHNBnj6Ba}R80?OeM0LWI8zT)PH2@pbMrtLAb$hy?V=wPP?>h@4O$;SlcBOC zXcWm1m=EyJm5#4b(spnU;Xo?oUI~8gRw$5ZMfc@#--WC~CN~-;ErckR2OZ8bK)pQf zgb_7vLEmH~1F~`0v>d^p0AtT#cGzro^<_qLDoU~e7(Z#K#buG zaDRtB9AvTSa5mnIC*Ppi?P&c4@#OOX#b(qG_e&iVfuR{x$)v=Ukeo#ms$KwqG`-$N zO>O-%I-ixtjos58SfzZ87IB=Rd%ja#4<@qGk;TFz2}EW#N27cR>Z@CTmarDz$OjP} ztszknQfe*}1WwkKsXR|knKrDxjHdW{Fas41!~Z>i_t;^};NheRd}shwf+?MWENn+S zdVJ|`m&Xw-c%hA+czjRrn6sbHRRF&6_r14G2v_Xw5J=txJZ{RDMpyeYP~Z~)gy@Bo z2UwtSU}FuGBp`SD=i9GLmWa3*f(p!Ri*IT%#I`jyIa0^{kt~QOonkd6dqse30f{I) zNoU>xug=mmsN;RQHVssl$$z!I%sGxU)|117r`rPJeRHnK;$m|XyYvB*fthJ`9ADgw z#AVroXI9Np%K=8ErDtIGHUsz{01*NSgAR#vrro3IxgBhI0^gVrlKPt@hLMlGe?Buf zbIhblh!>zXkKK~bxyhv{F*S(f^jn(Q0z7Lnu1hTq!OlBHS^1=qKKM~3I&2TCc>*G- zjGtdlMGt*gfth^V0Fo>!fI;}=;>_vqyrFz@w_&y&_6_BMJp%5zUax0ycAss-ba{zS zx`*q6(ko2kaOq|PaNlg)`tCEE#<*Hu4T6pbqvY!FxzI3mtZ~=nB{g=>C`Mg>iBI;W4%>AWmsshv1*Q?+-t?6iX%}|tM(Yq6iNBv6% zf?vRQ93uYz49q28KrnTl?_jvhg$^o3$wnj0Pk5y6f1xl)b*^A{dM%G9`G?N7(-69x z_$~Cz^xXR#^omgOkwo|~xaZcY3;r-Q78xAKgp#x`c6jS!K}AB^VueQG8x{8c~Sh@;(U>t~Ad9Odnuiy%54;s5^w>8UQ+*{W0No%D`j#IA8)^SiVvx$#O0;o5a-+ z>_*5alvfM2A-tgxE($yy!uGZ1M$bqRNl5Vr-DBnI=6pyn0bq4fEn$xMcv;BXEH0P) z6@Mw!8THNm*&pvzBRL{cBHRPv%=~=UZ8to_B5qo{Vq(5{|C`vrb!GQ{{@bZPn6<$z z6R10BfFKM9b_e+qRQYK7GW44TcRv|AA_1OG>7GhzOKA{@)41(B?)#a}N;8aC?oa4F z>wp0jGPkED5w^6;p=~BtkxF8>12GoEVGn#jb)x#O_mq)hzfdB>zIwklhArDGdF`Q( zAuHY$L$MuFj&FXt0)VFbRcUM+x9hj-;}s3mI}OMHfvn8#f?Te2wj;~SoIn%M-rj-p zu6R2DZ(9@GuQb~rFZ=-E@bom0pTg^yei*|rT$-N>SA>!{A~F( zrd|1`7i;BjA6AY0<^v{Wt?O+(iLRjWwe>_`D$OB~WI|LI%r6fGh)-><052zzPn{tV z3ZeIRY>{6Y?`VX}wNs-NU?6T9j?K8pDuaS658ZMD$Z*G=z@n_gozWT*0RQv{HSF^i zPT6kz$sf|vbsx>ms=W}RAMT*XGu%n1v($V}tdAN)aR+*NE-9s zgm^)o<4+4Z`y*mnUvNu!#aD{W&~lRCTQ3PCr5J zZQBEP{SSZ77vL(O(rwh?6F(Ho&hVSq1zD|a@qJS%e(6mWM0z~B+F{ACI@0`MwR9i` zV5$9nYhFstZ1(g=9&2f-W%0s!ny;{K$Fr1cBs4a6ZFhoclxUUJ@;{EQ_-f{f+_njDFd?(x(8%5^_B3pi zMk3oa2@1%7{%wi_BM34K6Lr^Hdp~a}K?NzTw|*_c=jQL! zvf&pBM}!@WB7r{nJYi2X(jjj^he6Y2U{HyZi&%`{Y= z%HRY|)W71g3Z(}F^0OK}+nGNZOwpcVQbe8%%D(+a2H_y^Z_13Cl@zZf&el|AKrRDl zb3YCJ!`kNMEUv_9e}b*3kSB$8tSPb;*Ra(<+|NH2)aDHY7Pi@c@wkcH=f+ouKs;}e z9f9;f`J2PQXdJ;y0UMDLi&8p~PQ{kO)1d!_z)S6Bg7VDbkNE0;=qct;8brHaG(aLQ zqsT8m5(>DghJDI%(+(yox4x>MLzE(r9qA4rNzb;xJ8cWq0YrKEVvaiTA;2*~r5rrE zQY}0_48X=k3{2_kw6rR}WM#R+NFy)+jHXC8Z4{!8DLL6N@c!?c?u zQgqGicl+f8*s9)UyE2@I)$gYz_a)&;+j#CvwK(h@q1k}!<(d*8Cinp-t5~jy*Y)S0 zHrDqFn;9)75b9br^cshOOxRkDRg>+UjiZ0F?iqA zM((O2XsDm}R@};unXR{Ik z;($4tKR8r+C@i9BKaHluF_&(9nH=%35ZN+rq+Sy@z$J(4c)VdSsO2)28osY+K(W7Q zFv|;d^IvWHeG7jcr3qiWJ=qLMw~klDNOa4;=w%;H3tK-^uA5|D{e-RdY7^lLhAVKQ zZBr5#EVpoCa{j|D(ZASYU*y185udn2`1Tc+l=c^Ud-7#brX4MB7K>yqZDAccU~+0V zRy}fval6|^+AqYbd8n%P2AphBUFr4;-RT=$qbb+e>XY1@j?-XC{L)Pe`C2YH&beQ_ z4>5T)+p;5n*I=HWR9fhU!eykc

7iv2Ji^PgWkOD;5q03uon0T}z#=sK$!kqm2*~ ze^~r$(9so|?BeJj*-0d2Sr;ewhWiT59?leF^0|}}VD2}&P*8@%$q_`O#Qx|WG$|?= zv~U@V%2H=}|FK*tkR18kKO4Ss`gr^en}NgbkQD4URO^jQuj|^=%}%)C0U`6D*Z#Ikka+wBX}K?9gC9i6v73 z11yE=cS_6EqwU+Ux(SuTVQJZ{j7Ks({{()Je*S4T|CPzx4;bU2Tr!&4Kgqeo- z9?gDKQmN6`BanYnEp_C1%#H%W#l!F6(Iz>=AMJiLHhp*@jv$#LC;dFWa;UM+xLh*9 z83lBmf(|G11QyiHHX@}AxNP5F9|#LB0(Q(qV}3@K`=6&M3P5q?xLjNE5av8;;oL}<0fdy+ zT?RlNkl>ViPbgCiMvtbT>uy5?Reum<;d7;?y|x_94!LJ>EEf^0en}COwe&$oumU#d z0p47?i#h(XDJVQAk7P-Z!=I+hQ$*o-2(Nd=tD%E6i#3!}$ErTPB&g=+BID8PGy`;A z+ra5}?3P3gpuP(VVTu4;fYyZ*B5nYkfa!1u*IMj==p`I&YWMHg@UDa`N0nYJH=ujV zAvX|ta@bZYH1sVW&RoMYi~WhIgJ(OIgxv8;GSzOGVxGRmOrFs{VVefP{xz~u_eP4S z-;clDR1OW;OfI&mcFqilO&^8)b~~YAg7OE*I2OOa-^Ob!Anwo&nFP21)m?N;+d78n z+IrjAPGgB2@$*iEsB4~x+weg1#U_>U1}{rRl>s`gT6wa_4iE`7edreTj)h_u^uJ!O z-+6Zp9#ViB?5jeN%%r$k`2JX(%*42LhZ${wQpq9-H%|(OVt*Mh2cT;&#`gIg zOKEzdGRCeqgGu`xo-2x8hRb4M*nEH%n};*AY>)Mf{h`2uIfvd8R4jth^72$J#Nd^RqXU%WlWVGrl^b9Idd0J?~k*A1#?l z#tNXD(rbm9^uvu>f!Z^`5bIz^k|eqG;$Qr40lJ>K&5P3z4Ivf`_R`=|$Y zLfId?KWW*&Nf_5q;8PYV(p*nB|Fqnq%j$W|NE?&R5_+4iJ5H0@qYBBkKX!voS9P}p z5@;4S2ZPiqQUw}TndW9$l6otFJSJ|Os>0OGq|BVvZ zi7e)eT|DQn={I-BGr$GeCXi?+2s!s%4~9kv%|^vDPL~Vb8TAA3M3g3>Fb9Kq?eY_u z9(Pv((@OZi>$0xOH1-sh>vMNw52GSR`L_UH*>+l4PN!M4V*KyAy`%Wfrr=B|fI(pU zv!77d{l!ItE~ARmshl07l5Y-Ju6c4XQ5YrVX;GB{1R3`Y+cvo%J)X`;+dnnD(m zYj2l6JZ8wXD<)Q{mi$435_E%wwmSo9;l*H7Co^jj z@gZ@Wok+P!@3{2+VOHl(xeP$m%CQ!_T#jFDKweARU84TW*O*x7n-y!>bV34FDL&P@ zQf$mk@iw<{Wvp3CV0?j2dTS7EhVq`IGs*|n9n|G}UFC3;FFrl`Yvni`8aRHRE7?)1 z$CGnLL(VHOiuKP)$PdX^p%#uh&y^hC#gKsv-98203p`+YuYN|S+J2S) zsgY(&A5bVuXtV{3NFL`5cojTT7>5s!dRP`*V0LA%KyAlAa z@Qu~ks%aW%N;Ydenl^l}QR2w|&Be@nzW$A*7Ly@)K!b!28qh1(9sKE>;fk=~S(K#q zAtF(;>*E;C{A*1Edlp;)2rQA#<#9*Dk8Da|D%u}Ab%oi19zm{heh2I*e;I#6)Vt@K zdY>wNbY6(b9lZw`iz!V)pv#`dJZuGf`BvK>01>yHs;BVDvF5xvv<<8J=cK{pRH`ym zd$ER@q4ZO#?>NX{*53=FAgQMgBp#dH*?6;ES1{#~@k_I>e5Bz+>)h&Gx!oLkQ;ykH z6zQ}}VeLK$KGCRAnh}`#my5@0a?zWtYLc7E=q}K{~xcncN$Fw;hos^P;4Vk3{w8?MU>~ zO$*DXm?~2yqw96*?<$FOs52n> z4)SnvsSwu#8d;GjDW$JSi~!=x1LFNvG5ovN3&0LWA)JqT`z$OP5uI_q_S>=(fc&Ng zF_IWz5ukJ}^ zu}~YmxjNAhMA^e_vf^7sx!&v|l_`%r2|Zqk&QvN@X8Ng^YV*qR9%NwhUWwyDn~O$sB!xCU~%m+iglC0gdjo?G_c-Qm+e3G2#}0a1bgcJ z0EC7D)4%fM7w|U?Irg^uyi&K&e4Z0HGTk8 z3?s>#Uw<}LyW;)FG}}CWKDlePUeow?rf8lRO1%%vGoG=xZGCnxR~5WgSWWyw0UC)D z>{k>*2SNikr*o~2m}P;$^r49_m;JeKL%;K|-irA}qilCk8G&_UAcWe=FQtm(Bzf-z zTJ_6w8!PzcA4}C<&2K{#sG$3^?5s%k&+JZ8P0+!JGqa{KofqhrCMQOL}4vnq!oW`pn4*(?f8Tp!?~{ltmu!6quQm#LUQc@ zAw?gTQP|V;=6OrT*n20~8>Inzg%(EjljOAw`O-1YUOa>dG8WWmJ1%MlS$)w*uCng$p29&Mn^3kP$B zvYG$1GOEi0seC-(ZuqUwrK8o~)zQquC1Bgnq!k< zUwr0HYD7K7ew0hup&923*#fhfQwWnm8Ot$^x_Emolo0RRBK&rjaSl!_PNkXrK@N?z zVtEB}-t3aq6(=>1hYZM~k8vC=3WXWzhx4#J)=i0sBP(V>AW~^P3?a+*f-a=HYCjAS zi9m_JLer!@0s=a**c}ldKh~NcHFD?KJ>8*@ zQ~M9n&q?#bF-O!##SV`WY&t2z(HI`2s-~HfYl+m5Xzq# z6Uk9`5!I_tjNRLZP(VtGh2vrN9_~*6kWu0*lo1$}%4o`;EUxB#97k-?ppUf{bQFag zKet<+2bX;0TKnA)w?DE7fe-{zPd8~T+(Pq zQz}k3ky^c!3OTZH!x|n;8tc$h=42a=bn6r!hK27|vqxP^F<_;YWo=d+Kf= za2s{4rZe<#*ZbGuh&JK#mb(txxQOwF*z}NOu`_J9FHzD?@Z1A=icL(f3)|CEc;;tk z4X7Es0K2+EOh-m6CL|1UzErkU;KyVXz6F7MwQJ3O${Ju$+%sl}G|RoG2djnKi9r5r z>D-E}Jrrwb^>|4d3ca0YYaq?_GMUXE$MOMv``zMb9)RG!pwslgOE z^tFfWm*p!N7KxOIn*r43ZQnIjzGB;))p@zYc)eEL#~Y1OX=~_V-WpMNPj5M|p_BC@ za9~meQkw_c_tzTeWbv*uUSAE|&4#1ZMO}-^-{5W0Qi_A7h^A(B+uj|>Ld{se>YTOOC=ap#d~qoM`(BOGPf_^j8cxSsvC*Oa8JORI zM8q0`mI@udv1u%)|A(lvY|CnE+qQso2?Ej}Al=>FogyLKAe~YY(%s!DCDPs9-5}lF z{f@Q0_gc>n;1k!JbByymj(xYdaNEXon>`*VkAX@|q>8Q8VQK$zx}-j4J}fP&8Nx|> zq*u*mkr!o^NoGL>x!BGU`Jt0M;yQUc-4oea(gQRy2b7^QjgZ+a%&e#0x1JDn0|-CD zn@SezwA#0IT{xrMG81<*CGKQCkHB8CLZ@TZ>gd<&TtW<+)SN*RV0I(^j?K{5u<8x} zY0_AoNS~0Bdnd8s@n(2O_*R5e#CMQ9@*1VkF>n9T{RJizmT20srDM8S*;6dk!jYwV%Z$`uBXFq`wa-!yOG&6$#rEt<6_(Jk@7@^5^$TnW&b0iD5}c0X?naU zWq~7i(qP+_qc0L!?NANyZ5zp}rJ6Gu&5nT=+po_LmY4Yi);>!TYRa_nuUakFOE$PN zn>y!cMETNOe!9Jp>fhz*S2J4ISKYUV{&E@6<`?Vgy3^l*6t^!YBz?qEn=T=DpD;Yf zR6%iw0*u?GMMx(R434I{u<-B_OyZf>X}7%pGssY9xOOJ<;wYu~N_j&1Lis^_Jr=5?qSLjwy8PMdky4VDZKX!8XebAj&WxxH& z&P0av=d}YClX0wP*F_F!_0Jk01zY?7@qDsl`MohfkxSd? zqm*kP`DZET=VF5ZEXrQY@{qXlTlyam-9#CMs_&86wE1_S_@eumNNv-(ac{sDx9%ib zg4LCf+sKO?1%-%TJ6jl<%oFgQ+;5KDM%d=^WD@EBsgAzN{1}FHE!6Aqb&6r;D=m9P z{&y+#s~w@P@GWdu?P(iFqyq9#!hR)!QfEOV|7-^jt8EJg2I_7P-`{vzp)vj#TH z>gF6(su2dYk_2qTs6PPhlhgkBCTv(hO4}*E?pZxwdiar8FBF{kC9^&wfv?>jlZTAr~7FOKWrtAbmjjuwxhZs_|HomQuYxH4+ExR4k zZPT9*UjP)m{ReKnH&lv(!YlJ{N8j|UHaC=yOA>3gd0j0N#kK9eRPNuJ=b{@iV!XgcXytWJ!P=c&pDu!^zlGLcz47^Pa%_GfC4U58}4_?gVRO*Y%LpzcS zzAqHmnn<8gkC8v<`T>E~2g~#P$dl`%{I1$FPfQjo3AxwcuE?BCm=;?QK#$H9frsoP zFptltf#uwr#g=NNhR2hpiC4eUD6-?%Ka{{Tuss;hqEoKhmVp{}0pEncmHS_=H^+K~ zY!(LfP3ck+A=JRz%TJyUdpoUoNY6(L+b;?oR4EGl6KRpVko%l}g?J474XDtl=WXXr zvGwu$nD|b{EGwum-Xq%{sN0_9W=wukAdD<#_cj@^@3ji-mdF(kPJZHcJkx1dX>B3L zSXOXfo`ex^=)jaa&u ze}`WS2Q@IEUk;0fiVq72IG4J72Q!-%QgWodW>AHaBKhv8ts|@WAz#Kl4>B9+7#dO6 ziz;|Dp0l$-t9F_)gt)PFt%}}ufoAGF=`xWh{EWI%<38KHu zMbNJqqnAHTLr6nkKt^h4ljXx*FWy5ikb^NT%QI(7eV~jIEyaz-s8$wtSIDG=#8diK zS}72pHG+>r&Znlh%IW^#|f5&}s;WWEzifMn=>`Yxn=Xnl2w$OnoNL#)k z%?&T9XvJN49SW9z9HgnRmU-P`96dt8Vd{dZpkCK~L<=%o{2vN3^5=5Z_BLqy z>7*P-!8SpMoM!;9#(&k#L~z_Hw^Zt^dVlY?sA|oD@N^VyvUg6FholA*Cbtc}rZQ8ls* z8qv}3<>{qKn&&|NQ84_UZvPVWFSdvpccy5rsx>Thn5#a!&1pB07}Sr_E=as)CR7o=hx;7)k;m2lW)t4Jb_OJm?+u0ACusnDGJSP0(`_akCNy8iZ0W>iso=8qzGI{8ffy9`HzJyBQj7*=*3e%1m-x)wwLSBE#Q!Sc3WUR z)dKDiWR$0wOkm9Lu69`ZHnFQjAs4fRR^}D6x4L2|QD-uecMj4FhBBd81w7zmRCxto zvLda}E~r}nyYZvgR$DM%iuVk4xYwSDyAi)8n%qo9ro+UG2r5<6yc~!5wws^=@^ES) zxsQjF=%?|hclX*qQak*v$u>H*(Mj1qmyScL*zsDMxk^gIm}c5#_!Jq-^t9t0QUT&x zA}98Iuc93kX{s{x!2>n=-(a6B+7?91iwX<%WUDIeP{NxoFld)Lj-hZ zItK$;)?XtDnDEc=(^w>0_{n8s%+7E!A_k@H z(L9rm^WiKV$h_#bdOX=g@q0daJwM=hBXe!S^B4!kjzdR%7xdy`kIvw_#K`CG)uYp7 z4Oj_A2C)E|kjt%ec_>06$y*rY>Ws59eUS5-Z_x_fJD5vk$=Bl8eJf91#w%mUnKB5qq zVhivOsFFFJq+w4VpCXf^X&`-__ zwAx=tn!UYI{eX%UdVn-F+ylYP3j_>mgAu($KA;}3Ja3|kA&24Q&hBB;gHIGHWFHtD z`ZOAow$_UT1|6d17*KY}r&phCT@11D>pDhfW}-oW8P4cWJ%?Rs!=*%-G~Rki2?I%l zw8<=miQfeK6phaD?743B@5QcGz z<1Yq9eyVs>%I?_fL*rUD>rym7YqiRp`_`TUxzvyk3=yN=H*IfHQ`jso{s3?a9=p}u zW~9KX_v`auJk8~(A1c3@2l3YMe|#5MD`^QYz2WnZBEy@pu(f&(_JnrEFM5Z>FHAei z7G?Z;Qy*xPME&2s6~P*r$_u^_b2>63=R!n@$yLnWQ{g}{8HqvmoKa(XT^@iMT3x(a z+VFuj(4k#vbOM1G<17bcLMuX%ffzyp!x4UB_CZ3AkN z0E|9q6CO%sOJ$cXn4jp=rN!~bl$n?`MuV_x<^nF(reP1WWd|xrU`|Qcph7dS{9FIw zx@dfAVwfL-f57xqCp`Q!zeh;^7p7n%34UJI$S&kY=dwxsMg2I*OdT(X?&j1FI#GYF z7Xp7G7&ITx$e2>9h|}y6d^6eV7yM}=NXN2#Zfj>+MkJu~@#C!ThS&47{}JK@&iPR= zDipKc4;a&GgfUK!Rb$lXCf3J#V_ z#YkYb&D!w9rVGVTvXo7f_t8XoZUc_ek0JqJFUST?u#pQMv1Tur)k=76pbEsbn-b9*%%|P>p!Ce0ov~3`Klbps`VtP=C*K$nTd4 z>Ju~HC{D8}ak**8@Le;*rP@y#RC>GXfi2sB;_#J{Wd4YY(+s94&if^r1&(EcWr1H$ zQF$mLKkGfk0kGcYwT|*}D8W8l4${a=Kn*6NO#aqK8ub4>2=~TOzZYUGeB;=5s6XuS z)TOt#kn?cX95VBKJ%UHoGgo4$YeVlmxJBUjXsOVK>r1OP^pMn1?lRA*8CkK0%K7oP zrH5_f?yJIL#fFT1vRa$Ou1^+|oKS?U;_R&;110PagUVjlAyTa4e%uzpsP9!|HbK@w z#gEUO_uD&Qb~yP{>ai3JvKg0QUrHZVEJeu`$?=c&>o^*h$wX}~$fldqxvyX~k0q@b zj3Pn!N&K=%eXN0_Fjdz(-Xt`|GvGZ;Sl0uXd55U5XuqBZ(ywN+Sx(vT$f%EFWU{~m<+SS_}Od;O6;m2>wWZWFI@nqQdwT%XP;JNMf5$)SH1z<7R#R5RF4be`@)&DT80+0(SShjv_SWZl}>B%fz zYHz5-iQ-_1?V|oUA|9<1*36gFNeLPi18`h$1(D24ERDPD4< z=fU-re@}8AdWuA)iT{d(uk$I>kHtdx#k__4EhF0_)=qKHO z&BDd7NY;Tc^jhqDtsQnh7Un=6eQKx5#2nYC{f%e7ZW|fR*VwLyYh_yOP$5CrHOE-; zAjaB^?}I$h^7i#Ni$OcrEMsN|#rj=)_fhg6u&2aAQ~I3E)S14y{iy$b!UgmxTt{n} zWaxx5fwuPJe~e=oArQOEK20uzWhM^sZ{tvHduMVv<*RqIWH1JK#RRx4G0f=dx@9GU zaZ(XnMik8PRbr6YzCAX&6X6RWk7flLnV0E5vbZL~&GsV&*w=!An=JTem(Q;JTdK}% z5!@6?{gAj58(9MuS{4f~&O=%j<8-m@!PQ4%s}<_g_WNBK!blv$R`VaW_Oiikmk}F? z)N0IApOim@weP08Y}nARdawjA?-rCEMTWWGY*Py!3j1@eRu*Aqqol*w3ih zf6LNwl_gGk&JEigQ?ExLfxVuuEo&9-3mzQLemIlLkx%b_iUZ+dSlxjb6UFxYM2jkM zp3S~P!Yb3-)u@@#@~`&g4Rubxy9T(_+R4N3D%8h#`Pr^cUu~x2H!;vikz8;$P`_o^ z#aMT`YSsV#j=$kO&&UONBys{;XHPl2m%Hkg{@`%@h@Whn>3+i1{Upb+vX#7Q(*>$4 zgK;<;ni@bXJu{rl5{Luw`r+S|CG~ncL?q=&)tG$p{Wp%|C5g4{LCDyAIlMA=j)awq zcb&r0(Gmfb$m_8RDGa2QR>_c`L4TI=C^zx}KE}v5q?g-8wuS#X&IH$uo#CrRYb^Id zy%HiTzM`D-A_MBodwG~TiyGx=FBza=IW0Vw+(A~pzVilY5i{B z4?CO?sR{yyi`I$vj*=(KXvXXUi;XoXt)`vozIW92h5jFhWoK5V-~bz4k( z9k(Y*unCVpn@>~P?NsRs6h_HY?Tp4N9M5XWeT&>-b=LXowX*(TJj8vgVm2e)A#Dxv zaq_ZA-*3|m7PM+^CM4_&7%%4Q4qvZSl3$QkB98p9w8h)Meto!_h{pyY_cb52FjbP< zens2+Z9)w~x;vGbU%{xp*M~Kfe&?|!B2~*(5{;kqP6RbqX4DU@n2Zz3bok7sMP$dz zsMRJRFg2TMrBeeVDn-b=nT4&6Flfk$q^Eh^1PgC;SKEw3jda?#n1SHal;n6zRk$$A z>v?}xZY6eCa=Ps3b?z_P*(lFNww@xGQQIY%C?poD@~vD=6%5?QMP*Sm)m;3nY%!7B zbtZg$x>VSo%n!w&vM1{-9X;RdlS!aWX0x1C_@*HOe0Ld9QMLeHpIRX@YWDAJN%~8b zc&h_X+sgsLT)ON#RNl^96S`X04S;P2N}xm_)%XxaA_o(jQkbQ{y8n1;Iht*&-(z$! zy$oX0uX)U-5#90GJ`{43Oz4Ms1^6;lpUW{?mjSWLxrkUR)9Y-ADN_V>vWmRAZ7yOwARfdE5r?qhsZw$ z7KiY=*x>q7*J2@#Yax4gueR9p_B8UlO%(_RcSq~r%-q?u9m_5yctll%MQso9h|K4%w8#+ssX$j7_{YgU~67T(k zW&G-IxJT`Jp%2ERN5h5h;>Y+^N~NP#t_^(+))R_Dt45i>()BZzzr)5mw$uT3_@D0e zo)y-hbf0i}u1h3P4gosSm&U3+@!%JY1djUESP4d zGa2@NF4Mf;pDGj&$MwhuB)I_nWB67vdyEMS8&o zvFC0>C*BuQ$-x3IX02hVYhJN*KPQfG1^_nlB9v5{=Cf+bp-P+NaRg8G#(5{AQ}oN> zR~5{mMEAEpbMy_EOSNi3{y4cw+BQ1L#01%Gic^8*(OCwf0v7!h;&h!LB}o7dH*HuA zj9jY4>SSz#L;eV_P~8Wrjb&(Lpd)p%Vf)43gC$neBtF;e+230B&!P<6a-i_)p23HiltI#s7?cQw~?MO^^RM4)B+97UQz>&?Qe~zrC|H8QQwgiOOsy5p*L0^4FQA4dH zrO75|Ae{3~Bp^kn0q-R9+4WioQHJ(NhNRZFe*3ki??XzT}$sL1~v&_4Z>wAOcK3{r9Ccb=nP z$bz^H6md6PTIiBf3P>^=7?bcH?T-iip8n}+9=`N%*yDz7eQXr^M42dEW>n0cBL_; z<3=~@YLG_iq8dk0n<@tFxQ|E;E{Ho*Thq)+nzM~&2Iqqw#!u+yN^_N;>y8I`1};|1 za8Jt%rbB3oO|@GPP$<%O0K@LEr%>`49rH#Jj;DW45``ER(4h;%poQy{NJmO|H2XV$ zYNlHw5+!5?nW~&D$JA8Yc4u6NswxH`c|GEC>J3ZGV^io>Oa7TP%~*~lm*c&`2*R_- z>{y#Tn1*Hu4@3)J`x5+3XdunI)qzG=p~y01dpC0=(K-MnT#j+Bc=H&F8`|*@%Xrfd z3U)fird4C)#Tz1}Z@M^S%yijMuz<(*6bUW>k%~CLA)$f=a-N_M2I<04_Aw zV`6HElF?RZv@9_d#^KYZQ={B9@3#BNKydqn(GRj&GHHbZ6ff0kXTJADNhsK`H&3Ri z?B*mGmHrJs)-l=M&r5Bbwqe$|cR)|R(FQyG0Vw;BL=E!TM4cF32f^rv(jBL>r%S@A z)Q{&vp`Ckmg+U^iOClBKh8g6{Fs!;)vhV)>&Gcs7jkKx~#LW8go19O`NPIC0A33t< z4ECG&si03Jc6P9?e2-wIQSdAQ231Vb_b45J&vL_0+aB6}dEAVoy!G0SAGJd_yH}c{ zkT4#^fVa2oiADW#0}nrXZxH~t^23HugCBMIaZX4jQhd;XIY+r(;`)GFe=NhkR54G9 zskzAM@H<6}$1Z^bmAk5I_m`3%(N_V8o8cU+$EVnV#T%dz^QU(r_j*eEvfA8Y9R?iy zdA4zcZ~(%fcNjL?!E|I@D}xl9O*$et33wndP1ioKSaUn8BK`Cn>UBR=YiZ9GdBE(0 zw4#pqgYbt5BGR5{m*=NOfovANjUX3Z1H3#UoD#xdru{ZXR!7xKm{Au@4+2x#0$;4@tXAH-*$tsyvb?kY-U?V|`>^fY#4|H#uHsQa&+#@9Ng-6!q zN?ZqRmrsn%*JA;QuXzlK2C4$GN@2?EF9Na_Q+Z~ED2Rw(sKKcWt+u06qnS1)i!52s z?l5M=o6n}5biYM$IK~ZUj}(s=zxT!F%hWV4vk1LOuuPzxsN3KWL?*dBX_R4p(*Trg zIk(3NmYMwLr4R+#xGJF>t9valgy8)mpZ?pst(@%S$7c+ysRHgQ&zz;qjULSR`at7k z7#P5eIL($H$CNuOFR^i^?}lG*Z}F};xK~^(k=FcWCevhO+I6`>0Et=+A+ELCR`~fc z(t0feElem&uY=4o9xRnCu@tHJzPs}Hntu)2%@Ol6`H@>sX?yDm4RAe1?y6DaC-YGt zxD)(F#B70}fXC&Rb6EVmYLUpTGRhV1t$$hSw^*3jLtHLK+i?xS%L!=ftk~(oVUGfN8Xyn_lX#rVZ64R=O_?);tG8e@8gBajyI` z0R^1b86+8)>Kl*r`f{!OBnGh+tDZK$AC;U;z%=J6(>I9HJfS)5W~3U0ETOaoMIFw{ zb!_bo(`juzaP8thBSIpy$>KD;;Z1!f;#0{WqADG)Y~ExjLg=k6gpGH!j?!9 zXm*DY9eOaSTZnBlB;h&RUUlf!S`#R!(?0q3E{){9CLcJbFHYUdAz(;dCx-{&b<1eOmghA`N%QVibfr8cTWq#J<1Pd8Ph zGgJcZtNKY)MI2) z8n7{fJRj}EPpwym4MT5^F}v-Kk~Hy;WM&3 z9~EJ6fl3BN9N+Co05ZZAV^}UUVp{&yghXQ~ssO9*!`X2i0#*>lmiLU>B0Mwa^bo*d zdr2H4b38qEBJNaDNNz9IY?A~x8WG0>3LO$=z!bS0tFf?_#j3W9E4XGysnZa{c^L_G znM_+zSC)9atYUkCS$}P ze@+zuLlQkyE(FwVb>GbCTE*Wb?FOU%#Z6bzj@YD7-KJTOm zf>Vq`;CM>-sTu-DqpqBn)0qMi*?bVgjcG7`YR>&Ofy5p>*uRLO{BLK}DeOKnl`CUJ zXCY$H{R%r*5~6LmSIACfQ1p)Ih6DjufXCCc;FVAJ~Hs#KFE=S2)J$q2JPlsS( zLQmxwdMVLaSt8C=(stHJOHNS2z-~43VwGBLMyLs|9z9m=BtXU^zic!e%Noi+CYQ4( zw^vAC{$8Ro2}tU~KmE=gPk)t8E6M?rXL|%6!!bWDZno*7bDsJcS=`NAlD$t}6X~ev z7IQZ`u+`?V0YQHSOnt;s88V%V*!7A4o*|gxv`L|ia`xwP-C71E6*3^nD^_3LZBD#b z`&=Aj)XI(CZ_~ZxH22BUjc!eh{S6cw?DF;5dZV30>x>T+CK_^;siiVO4Zit7q-KA* z7Qe3l9>`$Y^GkmAmJix;E^*XTb&*KW0OR5N-44Hz9@1v*Dsi+OusF3_;!ljoaPcPr zKTmhJJN=qWV7XMFHydw9lD88~mFR$(Q$Jo5TM!#VHq0{hf&eATeoK>{+zGoQCZ5wa zn^^{6eVyVt>qPuzCt)F|KuHoZU0FM-*BwMQAmqpBW2fN~Hqoj$Uks z)^EQWMnV~GzNl>tthNj$?O^73#bAss$$6?~=DR{R%5X(Ge8P^V6cFq{~ z6FCP$V*;m0?p{xJa>R2*+1?QZZkzKqI!L@-`lc* zaN6!Vn6^>#xlsKVnQ6z*4};$8$=%t;GE$(mOK#2UVr?VPQ_*&?Zv2)F`)rhLu1LST zo5*{Q_eBNVYB_xr_mqP=(Zx759Ct)|bZXp_I`ir9uMXA2e3$41w@OVVLw z``4-pQ}Xdr5Nc{I6YrVf+MWvvQlI49lo1x&x_b7roGg)Diq@uj*1K?(DCAX9LAE~j zZ2IvB#CO_WR@iq$U`L>!Z_I=ZGj=U#Sfaxx`|`nF`QHn_MV5gW;E&2Abf2E~(RPuA zS6A?}iykj3L-W(nS18x(0mKjNIR0KV#(`cHuqmI z6*LBldF5XM@Y0$(^c!HbW#^mStO}fi1OQf@lS}X~jt19k>3K%>@e;>CjH~zF--Naw zC^Bs#7x^-YqRBRkWO!F46~l?nia%JBI6=8UV7KAN)3QU2VuQDLa`Pu?$=58cC!y`{ z+z1T>G}$YDsN%9ldb?8!&pR#P>&_U8Eg2o(Qqi2V@HNayB&JNKtbGO0%Q3&uYLPpo zvzQ{KZsooX#W8)Y)28_8@pw$}@(w3JJFmu6jYN2{nkkZw^BAx?2}91k$BB^_%}idS z+`IO>)M>G36<+|2m~_V>-!7*<44c(Zt?K!(!|jwWor1ih)}z6idJ^R+4xZ0<*0@k6 zk!8{NIHF z&a5qsA3sw4=Ou(niVQ>n>*2lKJNt=99MV9Jf;I|~z=QRzwn(&D=k{*RdDG_ysA~0X|qk=|?Y^%O_okOFg;W85A_hJ=%i;_JRzhIO= zM3O>rWW7Do9ZE2HxtYjqDZA%&LsvPJFy4`6>E5iFlkE|nYdvixD-YZmX^9QjZ~8!w zZ;U?nUK3-m*>a97cnWD}EKyPP3>aa^h}50>2vTTn%zey;JnmWdj{_{bd<9$;M=q8f z{Kz-KwmTJhtux3`sLw$ijl z6?p+FSU=xeOtA1Pj!HgUj@_Q!6Y|qOHyZ}tqdT9dBE2GW>|u@aDA1_5Dl-;vL9VQ1 zDVQ0G55tWWIE+RwC4TOH7QbMdnx=}9Ad)-zWiqN*Rp5pnrQgNtK@w)aR|0ZxJb6~j zMYb>@i#eKX`DIM5XB}h;T?+h4(J)t|Dt6$O+K0uP6oMJLu=a4$gn*);Cc;{`(+1rI z1`0I(ZsToj_oD+p7Cm-wdTu8W6<1hKGx&_xOEnyR)m$|?Szzx^nhVXA)%Di?iYV!^ z2q8UTCL`ng-xree7+@6C98g@b>&pU*mK`Fox);CkhklY_HFez#S5lt1I>>iqdnwiY zls?7=-a-m(+qN+DqRz=UREoC>^%sY6pisO879=Im2`_5gW1FRdV-c?8{Dr1x|Z~qqNdt!BZeH+ zQr7z2aK^QWa0zu?+djhd8p=AsTd2~Ya!ex>ESFK5_@08hYm>-bwwyJj$X1_)238=2 z?=iRyy1>!A?5u7oTO_WGyU3V-DnImoQa+O(HwPI!PU|Oo?-#R4v-USaa}_MTAIp4) z>d^%{wHmElqi^s_5Zm=?|(RD-M0m``OV8Q3ua|9jK6o9|xF z@nIc0A8g4A;m1Qj8D-VeT>cdjE6}eO{Tk)mM-WWax(pyo3-MsEU~GHZGV0b~JQOD| z;IOhu1%*d2^n>C&OK2kYq*o%9ov>k01wNjJCowkb%9m5<9UVif8DU@^+)o6z?hI|O z29jRyXEpRiWOQzFnoLct--7QadLLc^n#&3$Y3J#o_M0+sM)Awt7kp4_SfL=An#k2O zJ0`4fJ{p%J;4*0S?+Ro)%0g|BG;(WnB;?T}CHK6DAI@ahj-}J;P9o<3PWK9I;x?t1 zCx7pH`*%@TVXoj;wibgUlSn?0KPKjUSl}ipuF2zeDZZ9AhVnCkB9bMX#wKTpuWAqi zJ;y@L+}*_)ei2XYtQQY=zJZ-J)s(lV-N(n#{P70&>v8B4xEAM~FCQRIfN2r>{77o* zX*crmL5z&SA%U((HYK_tJQ688U+3VHDezz3n;o5etWMj`0J&x|{xu1r8Eibp4(din zP!^icalcKfEBB|!3>)EcwaDt-M|=6zq$kuc;Cm{)IgmhyyUZvbhC!Auo!o$@UVgRu z<~q)9FKUB$uMEi=iRV1u92*2Jcmpgs$+q(T^#V?z+*ITtXlix zogINZPUL!#)~9gnk9CdivyfHxS7x8msdcogC~v6H5UofvMm|3s6oXlS9GA&pUQZy^ zpIHuc@I7agfAz#t0NF_jG?{7Fo#CBI)GIHmZBoNI#FOQ#KT&21V1&G1GTV^U1SUnqaYLFfYBt`!d?(Zpu%op zChGwFQk~_GZDkzc22I2JO0jtA$@PwgQ-0{mTvr0c)U<;@qTxi8@_OM_sXqR1)go7J zv!xc)&!T%~rll?k*M=8+eDq zjCoFwH9CiTxBB?_G9$I#(U6gG{jXa4x4Mh8n*gfUkO4U0L|`NHBYB+no~7fPUBaCi z^?hYMnp{_F4!3@9^l>BjLq~0 z#Ml-Q!i&eFD#KCJ^P?(+vxPrmed3VbbzOTKp)IkKT>y+SLZzunFN}*fX*N!ruLdG< zlpi-7nGCrUWQo^*eV*yOmRvf8Htm2cySJI{=ShMbr@%hf-b!~#A#u1e8{s15DXWes z`XCV_@BOZv@<2YFmzT4s82wZ8`_ybz9RFfm()`yy#ug^c&G#nHxszyhFGfRHc27^w zF2PKeTrhR96p;>Md;+Fq6&h_ik?4=qV6~X6~ z2d_e4xcfi`zoe*@Y;jlq)n6>rigEF%KNsJ9Ru*#1;lwI9cMNqh?N;gi+o9wu5f(?e zKP7R#LY%$kDw3J^XH-C!92OEtUTfCHWK+r0AhG|1iTY{h@sv_=g6GEPr+AMfsI*)B z-%ECohEG;DBSmPZ;^kh#tq{=pbv5IB;aPmQIuUE8-+R4ilzcgyj&=$?-aF+N zyfJj?O{`_SKRe`ePpNYYNj>Y2_Da~^-$-+a@kcOJZGfs>u_XoB&A1+xa#;JF>9pcP6{AsDIBWQX^&yAY3TWq>HUibIGP<6^?5_}c-%2yhgh{I_5j$JjS;;^u0m{vh3an5^UEYjAP z)2=HgLzp?AH@tWcWUgrp8dc(JsQJb+r*=PfAx)i2y*8qKu$}$ISj~t{Ny3*~;nseD zJsdvxfD<$Ry;KcBh=kHK5686++3rW1@DqV*I;6kEj>@_j4y{(UO#R_@Iqkyjr2OQj z3TBDrZyz^Pcl^z+O4+DQuf2wHNsYEO$XhbC-Qy?rX)Egs&&Hy5go}E>)O;Rp6!;+t+w24@ir3n<<^X+-jNA)I!r_C z&t?9W;(x+-o5WD}O$MK-$dQz|+06m^;tO#mzR!jd=tK-@C(^O#LPCY|jC_o_j+PiU zBmzISh+steadb-~iw<7|kDzKR(;=+<{)cPz;ss)v97>2S|8=Q>qzOYQRYAqmAX&1s z=&`Z)WPFC?B8q(xqY(dijZz?{dH6zUc6o1{Ae6FQmE_)0rIM057s%S5E&KyS{#IOi zwV$7hRF5s~K8W!XQ*;GCF0$eFc$Yrvq*we63Z?%Lz08Kg)<39z>8sndxot57On8)) zzE(6pJZTs;^PeAiA4|)pMj{BPX)I%sp`>TvoS1a%8G0S=@9dy;6$!ZP-)b_>w0g#P zN#KEVT1Gl&7DV@Lj|!A@2J^Z8;pZ9X?Z|9l-K;M_%c6gARIaWd^cD%acUk0@@uf-l zE)rEWta#Fv1W)Tlh&a21aClUdis1j^e)0@Op0fI|^HMV70Vp&~q|S7)zW-Z7CLn^@+Q9KYet-nK;RK0?iAus%RlW6Qi+=y{2RV-I5CZeP#1n zC|Jj*8TErX@uWAH1Wq}t9lM#9B#Rk;q5KH<4}UyvsE4sa2>nF}{g4O)peP)p3a&fj zCkrY=_;2(FDh2wjN-Zo4Duw(+aq!cCn+-KATfj(CG`|m3sTrdc4JH!HNgMA|CR>Rc zuW1DP>gEY92m2a)=U{v=O|KSM9qP99Z1jXId9OpeadUbDj*+-Q(t$M(LR#<1>HXKUmF3xOrK@z>?z_RK2+p%5YGOMwKokNa=P! zsr()K0S$A@R^R2MbjSgq5A7v27&RAlBk+siJfPw%A_+C4(DP#L^?ApSmnPV(uvziP zAi_tyBly^C2R;RV6n1tc)bHi}ZXhGc?cV6f%<^!n?!f)k62@@*xGvtnuLIfLuONfu zrdI^jTo&%1XY*e>gzfirrcE98uwwuCeJB%805dho2FTL@y^_y99tVAqL%d~L>QgZ@ zzXsxvGLWrby~NzvEw(CY=B2i)#xO9`7&5UI7H@6&!?T(~FlFfAL*A+GW>^y9v3|ql zOYs{c6X53PMj;tzK?GTSDLlX&l|b>(RFZWY{Sl!jg#l9VDvYFErEg7sP+L!lx4xkt zV2L&*Q+(8pH~fXbbr3D-Cn+4$TYwpN%Te#*gK1A zV%FH@_L7X6=%z%R1vxoQswha2xg6s%>3Kak(n$%%F69muOZQnI{^d;=OlK5IO@Njf z(D%`<_%gw}+N@!p=H=bgyN7%5FABpOkIIixbIFGoBTVcs}`AYz^&Fn zY4o;JPqkF1Y$6Ldl7%rC9vW+tR3xda8^pTAray6g z{74b}zja8Oj;jYZdm@Z#`ItY5^DXWUXvX!ww;U&y@+C&|t7s{J4xf*hDLM4EDo$z_ z+zLKvXu24H>VoV7B9}PNKK+|?=aW_~c3q1%ml!N_@(uPf0bpfa{3b!32uMN-M<)I1Y<&=x57E{ z)XE#kH*Wl^Ob@y7SkK_T=fG|cn-gkHmn3e*&Oi5O|5YrzQTw?3HCKG665y>K;Q9Sp zH-z*sQy?}k!8{1PL&>1oF|BU|9G#jPBk&4q59al!V}U|hLbJ6Q6y;~s;}gkZ)I*0N zW=yvNlxs}e-7cgWs_q5QuTTaDQ~HgUYZ+oTlFf8W<>9raPHQa8gYnBIGRTS1dmG_H z&o^@=F2y!>Qu#FMw;Yt9=dJ=Du^6;M}Gt*wy4(gxE^CCtZfVOS zc;;MFg#`9%bHnxM z`#2gwH22H?cJds=WXn$VMsOoJo`uNfw`Ze1rWhNmE;OpWU+h;8;I|GO`t5oyW=hNV zQ=_R?8|oze44GOzf^wg({tk-{V*ua$dm2fZlE|w^j(L;^B`gope#8WigNan=4^Ri1 zDr?Ug`7xGGG6BvHN?%G?icWs1#oieyX@>zUIxyg1P`>*F<9=_S9?qieW}Jm{nlIzT z7s*S~aWr0{AW)`_c`|D@UYhIxuZ5pg4yF$q2*zRr|CIQNf?u9TG}~A8t*S4~E?BqF z3~g-KEK?Ar$mLm|$$uh1+Xs#RXdv@b*NG+?e27oVA~92c(K^Y*avdB_D~`!)r|Jr2 zn7z2uZrHjF+mg;;lTpA4$eM0`NQbOYlhKhZzf92DSlb$VFD_3w@_98ODr!pXzmFvL zA6_qfy)8HS(w57JQV-HXjsnzPR+9uCp2VKPcm$^QcO9C-VtDXrF2|F3a%Ub8Fud0^ zs+>-C!9*U!4!(C5K}p56uBa-#;Ar4W>P{b=UZ1u`~3aLY zpmhdArb9BTGfP5sd@Ll3Gq~mNhCzh=(;Bh6>=o|(&sgvf$BVU1^4Bz zP#HUiGCHkR!K7h(ArtS*U9iAXmS7ITX&8>vrqJw9xpZoQxR3D-0l(DJ&*7RyDZf8t zyxfUc(`NdI3eDFm!9SVZ3nlE~ox!=UL(?T!GUS-g(guIXh+h6uuU|dmbeQ)wTomu+ zY?%7=0-qC0Lwa>_Pc4(FkpWZh5K;I zuCGFu6u&)~z7zD_in){(F{IK&?s7i1#obu2urs)z8pUE(Q}Nqw&D^v%fmX#>QuZt% z{sE$o#A&T*wuo;6{c$D4R{7TuY|Z8`PT|Yp)ody0^j|SBjt9g(B$wnKX8|4R-blQJ zy*TmW#JwME$!YHRIOfg3y-rJ>zxfP?O)C3@3yN0FAWpjV*_Z(Cv)O%+zD(CVIFBCZ zfm7G)46M)6dgl?NBF_ORj*syALb$9A$4aOLyd~h*9`pxMb@Qd!rxJ>%n$L9buB`WY zQm;Br@fYPhcMq0)Y$SGnf0#5=-4NU9hy+SgEG>17rc<*@+=;Y#4PyL-ABs%5}0a*ZR9;?x1!!D{Cf|tJ5NVJJ40A?^2_;<-vhVd2=I07BzOTBH4ya;6!f@?& zv5bkLVSYUKLAp#66?<-k#&&j=-7f%`%n~o_hED@mPOmT0^~dtKf#gi~Zy|l(2JfNn z2D2_T82o$+MtN7Ql$f|Agv%7f#U5LCIU%8J_VkY1zp`8y+KtfVXgm}9gtEos-XMuU zti|Ix-pxudb$3KQ9iw40;JoT9j~HQty2(AGVZfBR?}osS0-tyjUKg5q}-q zwacs`C7sVnLhM1s_gtctkh2NG8cmNx3F*IbtYRCR%i8P3m20xq*tlU|2>kbIC7nm+ zB_Pn#+#bAk5k_yMAUl$itf&5{FDTp@{kbfrR2uNpxRh@Y$otb>#Fy#d%bVz>-WaL& zMkWT5aJ^@P&}dZE%yBf|-j;7VYZeF}4PB^;C0h`tS>y<_^~09z(C+&Pb2!Vz!u%zR z58oUTtt-Q_mb7Cx+O4RD+bL$4R==jnc&Xm*;&wr(_MVIYn_pX{FS>T>bgGYQ4mpkS zZ*^_Q-h@&fWXf+3w;HXuY$gmOyqnjfbm)4Fnb%&1l}Q2;I5^3W>Bu;YsHl^uccQ{V znz%yyFhaOuO2Scb@7_g=3r30O-%kazn>!6Cw#)p(DRL_q1qaZH?)ca_#?9~Qqi54UbjyVB^LN@Pf1ufRo=7R z!GB^pJAW?Me71+h)^3)R>7c1NOK`tde%$CIT9^ni|3Zu}Ya99hc=`tJJfm&v*tXf& zW@9wAoixdt290eyjjg6(W81bG+qU^V=YHqjUy$*Ro&D@J=bD(l!ZY)GAIScGXR*bp9pwVv_3m6+ z_$rU1c&LE3vR1`tu9*{WoYd|33^iCxBsaLAc=fogEuCS5rILM)VBFYS-xy0=9O0ws zWR`dW^*ScY#z9_Q`({{wP7ZI6Bq0vaq2_vV=I2!EajOiqyIqWU$zs6Yi@0Pw6UT+4 zuBJYTy_eA8h2Q^LKFXU9K4Au*p)3P$2V-qlKJRnPV&TFl?2f(vR(3#v0EGp^kc)8a*9tipA_+K*|XYw0`odXk=kT%0{#U(R1 zh3fhd^Y;6xg(c|fbtW?Ee=htTBJAJKuNc=^d#^Qx&NX(=>U`(UWo;Z_nIV{_QHBPJ zfi^oBjF7P1E~ZnpxA#*!daLZILffE7RwSd!&~JV{DrBk-nj!pLmz}UV61S?~QU7B7jBL2s*jkm>&vri`xN+?ze>2ejSgGx^TYA{kY4i#V4ZfX zYUf%b_4-G~>}Lr0MCNN%TD1*+3_&N+S=UF#>%*k^VUFN77aXaVAQSmY@@D^(u;noS zcfUw1$8W~9ODH7J&OA9K&0@4BVg2sDqLwY!yjO@hV9ki-m}Kovhegl|%{v8{$YPkcfrr6h_}oU&c0=bKfRyxm+U{iZs{I*4;aosN zs-^PyI3#YQ3$H{otu9B6u6>BZa<{$2^fTmBZ<#+|7=w%8fd$KoWlCUop9J^MV6oY# z{$1vPakM(eb$&%s@RXw%>aZ?=0NFRM#>XR?XMl0klx# z*30An!KM!78*h&bBCW@}03Ip&zZ{l$KXUl${;nB_hs}QfMH!~B@+{znckl1#^XZcg zB8wKWpp7)BIp1h4Bw&$EExPA$wP~zy=_8#&Gcr_>OSvk_5!%0gdp;A;W0-CCXz%$V z!+Vkhgx}MEaC)YCigO*OmI-)6QPt1Vf?#UeY!mfgOyAsfzmE6p3BOBF23B==zKJ2@ zk;PRwUrx%oeEd6IPRuz+$&*HEJ1mfXOIOpUN5C!O`tx08`AIsiHvf&|1aU#P|S)vg<+Ark4ucQoKzbjlXL{#^qO z7l--J47n%-HQCV&WmeSNGXx|ODs5^TJAuMpfdUu-wk?Ev==ag@n7A+7VftAn=($2) zd7L(UQXN9s%!J?(beB3_Sxm1Fb4>c036#t1pMSgkeEHhCnU2IXO{i_mci7;$(X)dQ zg<5B3yXTM1`l4&U8`{cYb1+NA?6-~^x!6pj!!G5lSE`@RV0>G0G(VzL3&VkSF4g_K zRO5^Y@hcn6UEAC5N_1E_nANA1R5)pWtdtyD_+yxf{V@0++Bln8+3Oyf*+E&bZvX|8 zks--yt#JU29{ENVH8N??V4Yn*oFSy0_ksKgXGsqVvG+m1=MLhD#<$bHFstwC-^qpO zJsdCiRxO~AqJ@0apZOhr6R@(#JG%3V82&!4HQ&u?tn!RpZ(V*(fU~~_5v>uxtS(gC zNHQEz9x>lF{0l13WJ38CjcKFD>70A&=GPv{>`z!~oLBV{@Yx9l@l#QD$znY_hsEAqPH(=R<&lEgqiolN1=Sg=nXDba?5F68Fbswn2;2t{jb0 zk)!~ltJ9iL&Qktpbn{QrVn}MSc#1QSKA0zhR;}3(2b}0;t)$DgN_U)Z6pph&v@)|% z(K(AG0=-}P_wr*_N)*PWY4mMu?fe-DsQ>-ULObgQLftIMXY=bX4@LBa*xViIS5Bng z@>(yf6~0;AHL{vO@NBM~Id3=BdAjhAh0M?_;QnIJ9x-{om`%QGu~_B)aR%quayRgL z=`~7wu`b6E%u=L)Xn&L=Z!PyzmbQVZ{d&KVykEy+JlJ^%|hu4@HgI1MeAHL7wV$Jgq=`$k4 zdf}P;&dSvxO2gf>>@TJ1LU$l(=4JrwXhmavIfp$&Sf&w07O&~)9|z%|E0MnYHc~6g zNqb$o5jf~4+CDtzV+?~YzMt6^SmTV~p7zsZhW@leQC#R!8MZq}925amFL&akh0F#J z_ZtOaf)9X1EbG{y)&AG+i_^ZTVNi`3T^FRB8G5Xs&*(vIMJ*j@JwpMDGE@-R&Gq6> zHe8&}ov{vSr8athgSE5Tk7<7xp%`lV|GlM}#^9E1MyY~)ek0Y28GLF7emSfrV#>bYln|vflF95F)-symH!M$6E8pruEgu*ASp$!$T}n8R-u0dmIES0e z@Y(c2F)LEHit{hXvr0WeMR>3mt4jOP!iUY_cWNxXVU{odbT`Gu7iknFJ`oUPAJU%x zlB0a;WN}kVI=#j`+C>yDzS$)i8Ft=zHZf)%_l(e7k;?MJDPY+#pQjZfw4UE$a~2Z9 z89m>VA%L^@FJdhxhe4|WF}z`ZjFJmTX?Hheiob(1kFdf_^`LO*JjIBJox`)A`+(|2wPwp0AGMe10+#I{h13>GLT_LANSr zh|O{stxU5k&+?kLVP#lsV5I@+XAQ#e?$Gn;a)&@Jb_8afz%+HPuk6@l4B^dJ6q1Z?dt0)fa}pM!lOJD3;b^@;*83W#AXJ?N;AjheG59c>nB1p!rmct_GzVEFx!|i%JD11EnExp21DGE9KV00lv@f3=Aec}xq zNHI_{$6$9#*E`!0bqLI-_Op)izBq`u3c zRh1A*B6A>CO_9%*Rg-g<2qQG#s7Mc785Mr6%H1Nj8^3{Tc5krCUz!{u4wnTQSif^FS zd~v!8marnb9S-o+bK|bn#u&Mb?<0Y*s3}#!=z=d-9I4z)xiC+{B-Q9zdsDbajDjRC zH^LLQf&ZOobgpNl-(0ltcw%2M0{?0~6RMTXZ{+3qz+(!PsRVU7QRLTfSTESioD_Y- z&9$Ra1u4Yt|nvl59g@_tUHHvL7_tGeHXZI@5qfty6LeO4o!-~w9hDbND zJ`Wre@J`E=G;Jff<@a=MdUe;<&UB;9-ys9#^9N7Z?MfZIz(nCX<<2#N+Ix40veJBB z9WxiJqVAV!a)#o;iy9LGHv*XScoB*GvHJT)f0pubG^^2`q_J6%E2RC}Y4rBkNLt>B zpowE;5cv=-mgMxfac|@a;ecbV@^Fd^g89={<@nMUT7#J@7+-9>FRO$u%JJj^Xu%h7 z!HN}UQVyv-i4yQAFi%cHa0M;GyFPYuH(Mx`CZh3raK@4uusY6=>=cmrIPOoDdA>E- zwJTba2Pp@nKV1*q;Oz}>!!ubetGd{B$1xsI+Ijq=e@2kVCQS6&XtxocAr5f(5VYiB zM#YUr^iQhLjCpVH_V{96jVSH=)H6~CPsyaoIQXPq$!G)*{OTnTo9T4p{mbcxcsd0f zEFXT z^IFpGpBNyKoNvf>6$sd zXmJebV0HW>h@HfAN;N+d*L*q{V>MEy$0HBD$E=@MDE|gGnROhWE#NxMB2L#HC-p5O ziGPjENa%Cc?&iC$M+#G7F>{M&^6qV-(i371A4eCi>O;00s5dGrHzIs@5E+F7*3c*U zK}depUoVn&%&BLi`t03oVw*Ct$Y0;o2Xmw#De;r3K_DZCV_-7h!jp_BM zcxE~PH~5)FZQ$Zz-f?&;or?oW#?swof{KLoN7;Gyiq{EMN=!vk2SDL`aBZHkWC7@cQb*kiE@+mnn3BqdFm)1 z+ReYn;g4eBh|}Yde1nK)Z8@#PAQS7-yHi%1@JSNrFmah=5~g|Ykqo|68WqO@|GNBX zinnk1|HTQ^Yh6?3K=y>7wn-)sb|44L9-5n8+S*zsD$rC{J5g(o?%U8LxpyijGOXX> zh*A1fN|Z7O_m4Aw{wU`4s=jcBOF&|oh7Og4kFr{YM$lYhe$3^{H$T_C_@PUuA8iBfV5Db=0o#kBLX7d>)&C<=Z7bq(Nvn4ETrNZU-I`p;W0& zn_Rn}umY;)CT5UI0f6-8gj{W46o~kG8OcF@+wbv!#W0elHiOQQ)8&V-FjcDJN*iMrL z69HO`8R7xl;Of&gXVdm-zIzmI@xI+8k&=2im~g62tzZy@FS>NGqT&D}8`cbpsAzr( ze=ts;rRfp1!f2;B&sRNGh3Vq$BjSP?3F`j^1%XdYD&4Z*t`8>CIV{(j9Y|^UyHVcC zP1#-^R`sdGx6RDsBw16~{W9nwHaf;S!V$3F7Wo}V_D0t1D>WxHHUd5wwQbFq2xsEa z@!5wvLn&_dZFEX!Iij-O7K0joE>_+wfzhM)qRPHb5~nv+83{MZPylg|G5<*U5)ej* z)5DI5C}CWp2yu5l-j98ZeSV3=>5xi5v{x>X)Ibek4pQO807!4_z0=17kpg?CJ75jk z1=2Th)gL6*KssRTjzyaOY-atYA3yUxL&@z}rk)e*nnt{xM(@2Vh0qR~aeo&R zBmFANXK8V3fgs6&7PBCKZ;?0UFaf-%sX})8&pUadYcX!_rs790qu(~`XeJPP-L?wi zKxJqlFw?SVZ%_P4x@*0&g*L6FYR^g*8QcvXY|-UoXW@dJ$Z!IFRu8nTM5_y2D z#4TF6@|0Fg!dBECe= z5O#XsB9m$YAt=7X^Y9E>>{eoXDcE! z8L4P#jKxXblwu1UBQ~Y2+FzPBwB(#~29$$a4=+;iTLEkes=OuH{IS~P$NrZ`^@_6A zvyA12s7i3{6B8YsJTO1aRK|EmHn3_}?`z46mWXqf7`c}RWZlbuQyBJ6#!(zBJ-oaeLFiexmWTo(?0*JBufKp%>kHds(du+;44en}t2lsH#SU3DYN$y+h_{ELDbI zwH`8b>PmFg3U??wzM6^(jsL+5TEfh@OM zF)p@D@MusfI6^}pUih?_y(o{T^N}#&!0I=EvHl_0EBL0KdTTf(rpO7hM4=tCU_h4w z_A_`U9M=8rsMcE~ks3*PC@#-d1KLu84~FV$dsFn`Oz|i5bdi4IJ(@B^$A4U_FLCfIL zGD~&a*wif=V*Jt)3@Bi`0;I|GVe&Em0A?al_DZYPO0b*Lxp94DnwZ?mqwY$njInEQF!=x4}%&EE3fY|ViF~wgW1h$zh*doZC#ufF*9O(?l zTJmz2|420W?|RqSS~@kEL0V05p}fA1M)u3Pd@r15ncGi~HL z%?^GVt`&Tx7Fz5w*IgJ=VgO?+?L()e-P`aOsv}Ni&Yq*1$Wdte-e;pyg4Q7Ycu{H5^YOmMp_Gv{ zi7S^niktm>#=(UzQ6Od5bC^h@HrfgvgDK!zvX0|;c)<02>_8(z1f0G}1pLLw_`B~F zxY2TTz?7eZjro;v?k5%)F3Zg^Q~;CrC3#S?*V%N>;gn7?z2j9IR2OLa3XGD*Oo~8c zqQmJ^=rHMdb!Ha?8$Hgm`6orLgfocaO-3D3QMhZ= z9gT1JEQ`&`zUh>@=`7!#esUvzl{bDNt0B#qe@SyqFO%<80eMqi%?}QZNsM~qM&xK&< z@Y}QHV`}2gEWTZbS>JQ6Oar4~)Uf1q>gYU=iXPkpUFWe>HBUOP*G3WC1}n-qV8EBT zo~tJR8xUwZa75={`olMr_H07|`qWp>_EZzWV!Ih7{i~<*@ZV4WDF?McLsoNyWYr>h ztgHnFLDy)Ev6CC0U6^~1wdQ#Pgx#UJPq@ex8*XTKF#g4rX8V9X5~k1HxV8HV!|bL| z_@lfXfLzy?&&^r4Wa>TaMist7ow&Qabn$Qx%3MJRue4D5ZN00g(X+JbEck_+ay5O$HL&7aW;2a;3@gp|e{I zV|=T3tv^Vx7*K9y;LeSYCd=Q14JfU*)(;gbjJXbSdW1@Tc#}JRe{rds1?5ow_mzrA z^`!>N#)cpm?Ywb6>R^SlsATP@rc>C=n)~6quLkZ8fOCvEr~B}>)|^{7H(lA@=5J5!ZTn+?^U z{gBMSVYdwajiCK}0Jqc^*={Y5zVGL+1|zV+3ULbfRAZ1RKD`NXU?{RxDx3RFupLBW z$|)r5Q^7$|z3g(WW2HfdY$=_X?$vpXnbS)WU7t><-k@5IrIKPzA`PAN1Rc%6#O-*M z@B0#6p0OwaTyHOs>&*JuCMx$*rgC$?$oXkvfX+fP)QG{0>C$~eCy9`RzJ2hbjz z^ea$k&p=O(R=|Zpn|hSLkyPv+#DG>2ZFxx~ZgD<2nBB(rP+P_wy~aN`My*NK)QmpW zzsfXY81T9r1_-*6XnXvZ?4hzLh-Sz?5~-0rMxefH^ag+GF3y#R#8cdP0YhfF*3&gj zuCnLz1Wv4srDCt!XQzBR%Crxgsq)g6j>9R=en&W9QeIZe^M5a@ z4Esebu=B8Vc3T1t#`%&Sv*CGG3s7HJTJA_%^1)f0+l9OA`|{02o3k6P0|GJsbP3dX z24ni?x8NExE1#v-WJpRgsa)hhJ>Pqc$fc)i4Qt8M1tRz9!G)yy3f&ei@ugZP8cXT9 zB2Lbyoe7=}2yuY;h_RUc;_<^`00BkPdP9NZ*Na%kW~ag{1W98I0UI${P5?`nd_cxm zflrPhkbJtS8XOqUMhgd%kvm5#_9cs+=7*Z`Ryr8Cjo#DNrbIUX?1!nvfxJ+XYSEvM zpP?qFV%pN69#-!ORO&1Tt>;KD( z(YCk3RS8iOIOI4@U=qbO&9iAAkVb>rFtPemt)HJ|fU~okp4HXn6T5e<&Ve%ZQbdIq zg0ZLuYEgpdm#eJ((A}|NC&|AuhaKKJb3`|NNgY_xVnt_R9OLot6QiX~cEn2L=;UwZ zg1+PN#%NnIbmg~i(4vAzVsgv13PE!r?AMAFdTm8El9dA|tm zmReV0EEdNhg==?YM6Q#gAYKOVaNSVm!B$+5E9EF70ZI@#h^I>ZmiFNHg^D}n?yXW4 zaUV@UHV!7uSy9jJ=*mu`4NSrfn7{ldlQ?TI$2#OgB3+{y1H<3@>_BHzBwhz+KyOPD~$1 zMpL1fBsz7m7OJ?}@5|_w-R%y5t}{sKI&39Efx>O108ebdIyN5xn)qy^dG72FM? zGyA;I3bHEZj`DW~EHT{CYFFDE3g30x} zz$O&$n6l=m$6ej=aH0O~syhOd>Y*{v!PgSoC$z? zj7Qz;xj(&W*5h$0?#0!X9gMb0RDmZAxwlTHe^{01!T*imCBsPay!va%+HUM9=cKjnyK^`i}-J_6c^MZ7+g2}CoudR-FrL=4ixBCSSP{!^8miU~vJ+R(Su+(Wyc7-v6 zHgF;Dbi&z3puPt1iekL=yxZ&cfsQXw)DtJ9Tt zUx5tG=iJ-r{~X?bq+CyN$!);{yG(7ud#{|^{iSM#0pZ%5Z4o7#4N)I43j=G7wri;H z$&UmJo7#oj(yem1RcpK3V?9CobBlk6xWM-iG*^v$M>GNl$76}>d(SpmlprnEcw40W zc9FSC8ua<71?MD)w9n|rq{mrqA$WW|f2iwGQHwmL?{@pWC+n$(Dt5X=(Zi9NKB-To zi_=*b`T5!L3cHgjK|;n+3x0=^jB>O#=!d5DJpgMZrmT>~uDT+Ht5Yf1s{!uu+#^Zg z9MSdN>m`;hof=F+i!yj*ZwBH1g@N5^#|Qs<`4zUQlGhkcm2ya-T&dP-Q|jsfkKL6_ zh-Iy~C7=B@MME$?+~mdjK3f`l2=gh7%js;d>DbFXw+0?t_(JYl#E% z8P74=OB z=}udnuN}_^_eK+kie`O5J(dIzF1u3vzv75w@=L%1uvl`mmbiJn)9O}R{W@J3E{Q$I z^{KajJdOz{cv{{LzgUPr;;>37qW*(J48LpvrorZ7yK`LQ!hV8SK=py}nf;2!T^=al z)0A=+U#U0r3xUmUfg>99->$xTSjAH8^uJ=(Rwg0T?-+%Tb>%=s)zhsve)FpbmEm^a zn`jQMA^}+_@4Ob{#zqK@#oHh`e-SgTYl(V_NxJ;atJ!~~TT z*Ip}}vnsH`Frx3}A(L>3hk$dZ`VFO4Fdm9MPQY1|aA5r5&0QPc1MU|5mw>&0 z>>DmUtDgb?%U3r>{oycd5~DOVyvopmxtIHgV{9mF`f8b&Nl(qSb{V5$ewY6&;{2d( zA)Z*+t!DqQe6roAG8^a;;ejwkzHt0V8Y;zr1#-HpaYnLN2XS%zfP5}pnK9g7A=(F~ z4M4OUz#oj^=EDEtS0>Q-%TBPpVwPEUkH zyj#g9(Db@C#o|i*hv1^8+ss&393)@)6$nupu0LO*%H(-#{2tQBF-{PVejt%JRlKSe z&d=uqYOgM`)$$nXZd8O&iRIe-rK8a5u=b&!MiUuXjCdA!x1g&+xk7Mg)XFTr4o2&r zT@&C|fF;bzmCrT$fW#rhz3^N7FTdBYiOh8KtrwSAaVHVqAQ&4Zr$8y9U5g1dE-zPI z5s?;0-&v2PK!^Lw+du8z>DP=$&Ex6ERlyrZby6RRz;~a!fTj4)#X9~Q1`VJjqBb_& ziTLp_Jp=l<2Lva6@j$gp2T+8@yVT|9XHD68PFfF7me4agwbU2jZoi@1d+5rr3jGS#xUBx~B1_Tea<0LcK&<`=gJSd4xQZq=@>q zNk>T;j(uM7itJ+X04uKMHJGwBFSpksEK(;lq9+H%bNI9{80xRR5i5skh|F$u(!eZTItDFOxAS!d zBc3{2!lvtqE+7nq#l~2N`u|Wt8nya zpW%d%4cMbVlCMki3vehsd7{p7?7k=@Uv~y;ZJ!_s082Fi1QawvNxssPLpoQ~&4xY{ zcvmRiZ?nN^_b>V?lew1a;Vr+0_C|8v2*OYt>_WLCh?xiR6h9#V8CU@twSX>$Q;QsK zF7w@yfD?s02O{q54>YX1aY67@rrkPRyUOqVn2#8T?EWYNDFMg zr)O3gPAo#O%M+7$Kd~8_(bOGfmmQy2{VFiOY`riN@vKn<(kLB`FLwz)R#mstYDE43 zUxAFe`GnJEGEu>>rwY-mI109M<$ys;iNFNdY$!HhoP2(p;3(2v?4JTfC%KUFvx&PI1q^L{Dbm%{|(UodDfcC zDeZfJe!>|GX0Q2^Xsx|+Sfos89RBr+BW8FzhB?cd5yl1_5Q@+%uHy=x7Lysty>K0$rh;Bj3!Y~y9XQ= zmT*cg?S3ELS}vB*q~2Tm=uQ_zKD0JW1WyPi`Dxq=6UfiU#j_;=7Nl$xdxdDMm%-#k zYBcHb;9ZReBXF!U;~Ma6jdCeTLw0yVSsX{3Jv^JN{%n#6LZj2iM>;Bi-e|q`nXx{? zBwDHa7pvuHH0NMU!Sa}vc8b(33jkRDhuaz1I+X6`F?}~NjMpyJkYi#Cc`TNfnewpo zeT|WcBd4pe;gUraWLfJ{8kzZv+k|d9uv2SuWsHOWu^3cX#s!`xcd}TF(~Iy=(3s4? z8B0V$t*&U1d9%YS$wZ0`u;z{j+0#c?oFz zI*D9wYe_D{T0=lwt{dz1h4=<2oJ*GS12JeGWC@DxADK7p??6{gn~qa;KQxpE)cn!m zW)K}NsEjyo;s@RXktJM)B2C3~)*gnq zpgculuB`#wV#RC1?2fnJLU;jBCcWZhayZoH{l>1(<2|=0K%{R?vP1+3y1F6+J>NLE z{b9vvla4^a_`ke21tz1!l>mKrK#jn6=rMGs+9T;Wcip0Br6w709PwYs+6brwdpcQP zyVlxAN*3+bo7bXAbLAq@DbM7P-vzo~YPDEAi0Jd$rj@nZGMkRc2>)}MkRv7=%Y(hR zf4_sP*RU;{4K>2A1_X1=78|sGvo#AB51-O9yml8gd$;u-lP0YxxbE0iRaC9^;J}PZ z1ERpx!^iGk?yctSuapABy8HX#f+m^1n*Ol^guU_RV<5tTAyclZG;De;S9XoG zo`&V3RE|2|ud7f~CX~Jiq$ug@`9X69_b)DXKQnq>hvF<-6K4ybX|1QbZHH0sxN{!d zso|tC7~JQ>)L+e+;ls7VZkUe<`m#(4JzaFcqibMIvV=MWxq~bb_k1ES)~1HsbA+;8 zY2QdUWAibX2nIA(8;NGyTt|fAai`ZWJ80s1T3wPB4(xsE`=;~jJI#l?1-OD1Fui6V zVLj8OX%uc&azC%cbrHrJA%F4JEjGb@d}P{EVW9EP{fW?ITFRCrqR9g=zRD2M_~Jp? zU**#OL?}-i$x;IL(qdK;b=Xh_|EH#dPTl%p>$YYOr-NR!EWr_UyW!|ep5t&k|IWz_ z4VMuVN@4*|^ZBsYkPO*OP3p)#VUuH6CeB-%0>LIr1GY5-Xc-$-&!>NRA6yeWcqBa{;#@nrx zOy|6-Z7C&o2WZnDheN){vz&7xw)~LG(I{N(#Pr603T5}rF-w(u2Gbn3{N>+bXVMt) zE5JN%lzo-bx>;XYasD`OjbQ3>OvJ+D8RKP9hFUebY)zwF?LRbB+&IfNP|HlO)%ky|6hLYJG)iF_{Vx#@)XpVHYE^Vtz%+b z5iyV=j$LBpSD0&gG9N7%-Rz>B1i|oB)wxrtSgEg{C!Q-3ux0sS1T1SL=(#B=OL{qA?w`UnetoQN03# z`a6UFT?}><;np@{4oPTgPj84|4C$tvg}5x;>M$xPyNPr?C~1Fikf2|@#+1`8GU@&o z+5rY+K#eO??oW4^oe?V(w(7uQQs&kDH9Cz^TfwWrn06oiz7{`>`GU=B+4a_kXW}x= z`X=Dl|fCIYl1dew9w3yyFkx_Scz)7)r}G#f!=w|S5O zC0wdgH;ZA=TwOeDWNh5KV>z6{(rL_!5~}vaf5>L1pZ_^m>Ob;zL||!=?tDf&_G+R6 z(yRM%r2KJ5;DxTeU>twQfI)(2%BVA2xSO)&N8^+Ok>Ri*XhG1o!s+8#IbW=RC^=Y4 z3#VCsFs;ucVoM@4{;qAd2gn&UPUSGsMH0h(d;uP*c8`#?Z9xyQeVg3)Olz}Csjp`= z`39?_>d*Hfv9;l2>*#fNb#|L8Fw~*!ln|)#_svVnX6@S;^~A+&N5o zQHaljXjoL*bItN!#RvfV+l5Q)dGn=#!Pm{+8ch)|-Q|Q;k_w7&kTpjx^c7zBGKQ!9 z_bDZo{O|Gf4hcF>K;lW@14#6EWa~jUG%gE_8+1})VJPI6h$E)Pt`+oZQYkR)jv;&j_7pYaL^`gj7@kJ=G>c9TvZ-0iI7Rcsogehe@=7N%8~2>_R_xqS=k* zP_kTGai6IVT96+gc?1o(GCtY=yMrHwVu=3tw}q%DAlYHJWMAUpKrXd;qfBScH>Sab z0T&;i14gy<$!Pp~w}-=$-5b{t`cx8*h7s1*?c_JFMp;QRS$5Aie+*WNsTwTB1PKyr zir6BB4o>o<1QT@7=0@VG-=WH{lP#cTwVMvsfD;Rhtu^Wm^u$k+V!XqGtDIDT&np^6r_Pg}%-F-Ao%bAi zp%^GmdY)=3_Gjn`9>AMSPt?2nZ6gczeQYofk4NO|i-xD>%j2P9>GC6xSYVe%h~fNb z$Ip`YNd8wsWQd{4y;uBV-7M%8f+?N7kkebFdr8+_z~y&w8Xr7WH>oLSBmxA=R?Tz` zWiGaOC@Y?TnN&vBhIisF!sm9nnY)xo|BmxKt!rz%yDFVK__P`xhOFUWxY@hsinIjY z=kZ)peDjkOITg)>R)|XQ2rc^?kKNgRsY(-bA}-iksjbvYk;1Wt$)3M65C@dWh}4`G z0J-mwwBG}%`+l=;wz)mTCXMn5oEIc&Sb_9@P48*dT>bYqix8G(T%^mDhRD(t(rL)ru%0j-)+hu^6TRqIT|7a zsUQ(){02+rPIfYm-F`ZMJx_=B z_DtiZL#{xc9?Z0RWkNu0I(UaL#qF=$pSfOqveppQ%4s6z>#}6v`g(76)=DV!LM!4m z`fz^7YDZO?D8rFEYcQCLrpp=Rq1?g&}fB9 z5XA!bAz&ZPF|jy!art2Zy7#;X3E-5zI$TEKlu}vQtKlK-tk_Fi&0cvX*_wEVm=^Ye zdYm+5ib)-|RuifBk9z<3!%3@ctx6t1fM2LfWfZowqV|%lH=pBva`uZ$NYY( zmzvsMPe>#oGoW3 zK>W~$=m@wsxp9QX6)V3@;K!I0=5h&Umlf~CZRZIQ*c^}sMU{;#NY(YNFCqYS(Lzo7_>k-!->+m<#{AZxhT(JtU+N&DOTyGVD@8F;;436Dz(UHH!_A$?D2o8tU}TYf@x8Z>OaNHJ=TQ%mf0JT^P{YzGQL?+$vj z$P{$l?BBj@|7jjhpnA^BV8CL8V(r{HtvV)F zE=KW^HaXMIbPmPac8A)Yq6`B}%V{#oXllZCOWhR*Hp_pE21)&xx#Oza>fveuMR#0kjfRIggm$ z9t-PLI8ZX;QSKiRWMrZ*^K|q6xTY|(`h_3{IIaIUv_$@p&wBp*d#Ew(waU#rQ|;ax z2}O`+E?31l_Ox879x=wt!v~1ep%Hn@pUHxE1_}TfU?+p7M7Z$x?j$<#pb(C<&gnNi zUDGaTYiAWEeaw9M%!7ZE(+|C3u-LHJwv|FL&l{~=sCj(k2EoPMRb8szqKLJK#4Sj9 zyUn0Mm%I*tIL?jyJZ8TJ$D>m=KZOqW6cWgMfF+eRs{=o$66cYsACTHRtNM5Lk}_*| z`_)1hpg-;t`9=8+=*y)iC?ccRz(?rp&T3I85V+6?s-LaNtfNqwse`XI#nB^nSXGL} z1(>8vAQP5xL0=bud04n7{XeeWGOWrq+}fr=8tDd+?w0P5?(Xi8?(RuSOM`Sb(v5UU zcXtbu{+@O0wcfpt@1MV&57&Lg80SDZnEY9UyVbTwW=A4WkQK7l7bw147$1$5FAs?p z`ue=@GrrY6?oP@chIl>IV3DFMt+W`;4gZA7tfSo&ZL(CFgEx~G!-~tYM5ng(veFPS z5vMR*l~G~6)oZmUGcbT90%P@Q6^~vn6pPjj2YH+mgu?y%@RaJ0$KS5`-MQp##Qh%WXN!(s-SkvDu5~eQQlt8qn?&{r5Ws!QO54>Jbz0 zgw_hmW@nD|UUuy&rY%>v@5@jbc>h&r77~*mfb@csP^%`wR*3p2huP#_)!A=vcJqAM zh;G09NztCiC$(#bQdY)L&nhWWp`j9T+VjAdD1D@l(f3Tt4bAt?YRCK9>vs- zOw40>1$?CyD9-JhG*fi|4(?g16Fb1-{}#$B6+VI`{MiU=J0_3ZxhWkBI8t0>@5u1F z6>tQH0&Xe-47=k$W3sPwzOS4Qnll;#-lZf5+Xx)-V{$Ol?yHU4 zv0~BPFZGI-w!Kl9jr7{k-~hlE!fL>;n8bhA)OHZIm7;l8$WL}M`_q(9oFk2C<~Yw( z%6k}ZnKb|8desIeD_!*nii5&mH{dzewAIb_EsEKa*UGc-4z7n(l!cI$4^^#lL{Nem z9PJZ8m6zsoZ)Vf~@`$gBbN?wID3KwfB(pff=K-u56X3RMza5Syn5Vm$FLt9=I79Q_ z3>{mpUIqh-Hbh6(sxanZ^JLLfsL&i+th?zcU@;WbU|$dy1m>ih0!PE>lcSksTxd8J zk=+K93q74+A`nJ`idM2I0x&>3+Ax%JBmx!+74ncO-L^>_EXI?JF(?q}NPJCKK{XDD zK!TDXFsbhE%2I7mKU#cD9l5zUK?;*l+>w z{Co?Z^0Y$uE{7{Blicz!&dV!z+TR7NYfo6l1X|3o5s5y@>sZ1LQQKyB`c41SZt+|~ zvN!U<{0fQW;YCAsRftT~`l~rb9#&QXlw$es)i@DoE;jU#?{I*{U)Sv6;)O9VSim#E z854bPFy=PqDq^}~dUdtg>(Mz77*0EfN^y69j{z2|;OY_7th1+%;#6($5U zI31!g!bVf0de5bopl*EtU0c`=dr`fBO`SsETmu5n6q7=8Ft$~Iin!rDR#Jk-3tLEe zW+8t^oTHQOED7^nvak+NssDomh~%g@+a3~3b>6x$w+YV|Yts$;nSKRtP#+p|6AX*r zSQdq7^fgGrES_ZEO^ejDj?FGzE{h~Xn3C5FyxI2M6fO;Z2y~6_Q})4dXE;rL7(y)z z{V*YTLB)mCU)m3Lf{N=Kd4B$PiD*v*YldL#5AgSA`8h#J465O9w2-N7l7C*O>#Z@d zF><&hMfmh2Pv&p%viPWXhhiD-l%kI3*zXv7_U|=skAjyR8wMS79T!7)zlicgTLfW=LzD0hFq}dpwR*c*DE8cONCK#~*?ypC zmI&OMk1Y`clPpdY+;~nl1`M7wA-A`AcgueJWvS=&IqDX{K+F3pcZ5dUxBBFDO~Y#g z&>pOkMs&>RXo`UX3L?1CWbh1AHyr7Rfn%)Bv{7U0p;4K_TEyqwZv}Q542#GD{Yjh| z71^mFVE}di2_B`sW#CU`84hY=y({f2?DW`FRtEc{YFNt9X-z{43n|6q;t(Yu3}Lgg zUH}Q&c8Nyo1;f+wu9(9q#U6Bn{*{w`3rq(Q|3Dh}PR;BGHok0i4v57t)i_&{GW6Py z*d2~%HW-J6@o&auLiT^UJ6@_YHT3)Y$Mbr}{CAT1be@Q(gn#tGa*#P?s&~OWi^krc z^17Rhu^Ut45+~!_w+hj9k*~ojKV3hYnE^h^>WjDy4F698-b;4#0HxR23VgdOY*#=c zG|8yZpVG4h=vr4|K;*Ql-fLFZ1@@@y-L97k%G98EII-~QMl+(}D6#%fu&-~E6Z}$_ zz+SGrUdKoTo*BtqQhk2(YA=Pt=f?i`y1NMEaDpr@`E|)Sn6CE?!Onsd0?zamG6uVK z8J}3IjZOc;uek4npyS{0kaf|j2qeZFL9^i|;pxqP+&4;KQ#;wXD~gcyzXl zzizCQ0z0O14HteinqL|aP*KTk;hk<8cF_RrI30ADv9!6%p7GsbB1Y5-xR)jM>a(wO z7+qT`toc1-%wt5q)XSax0Ytnb4kkJZLX+dBme3eU4p;y`{guyA;~3wMH_=by}jiXfKCvnc%CHqRW3wKySs9 z{|qss1w>Z8-73-vL(T`g;R(lnmK#yQg0PuJS3{>;i1d!^go3rwheCf(xPU_DVQ?24 zLlc^==$1gTkkTAUi(iPyV7Jz`T1yw4YNc4iHKLvo zq-fap=tmOomVAnEMSg} zoyKsS!Y~b?Z^YHwgD0*Q^-`|Tg_^{N9B>H{q6n;ASZU1{uJ5KNFEFN)Dxkk*}m-%Fgm7% ze5aO@Rw*b`1-IQpj$-#T4OlB!G>K&KKKfRqHH0Z?VDVOi5wTHWOzxV{Z(l zL3p?xUbE2b`Gzk#vm`rE#LZuwFLtGP(dH5FKa;_}DjN(uH%2rDS-p>hTvyoqK?Yu7 z1iy{HzHUL*Y~rn|7GF)lcE9v-eDk_-qKPAxP0O%EeJTa)8D|g&%xdOFFJOxGD*Hhe z@o#{Kn>5jwL^Bxvt;6eu34seitx?F#eSh@q;Q4um6bAzloJ3qTGJrN7YVB@3s z?AIIYy5B=F$aO5YP}w008SdTgext?WT%c-|1o>8OB0;SfIvq^k`yi@FrFaoVk1v=t zk>-}|@^&$J1SlfSgvE?U`Oh@f}%Xr{*?5xiW(V^=Dp?Tj(= z#FGf6mSBu#@!YxeHo(#ma7R{itnL(N4_ADlQjOR&>X(@SG_y0)^ER(v8_7K zfmg`h@g|5-s~l&uF#F}ka1;w`vee6~xYx_Z?n1SgJ*_|ONUu4H%ZY&)8ap%Zb}EDM zr=v~Y+e77)h8!2^p0Bn+x%Du zsJz+`Kgpcwo4TPABPgG6&-9ckpM-mbA$F8=+2au>FdLdV2Ju2iMM^qB7bRDTJ6lW; zaAh*%UIUz-4?sw??^*XFmA_@%X50hySJ87~ityKFm(4DY0fY#Q1U3M5ZwwO;+pk9n zK4V|86|c&e_|fKJ@AeTmSJy!l)c0%#%;~OnB*s`~^7Q6IllqAZT?vULt%oK?pe>W( zb^1Md>OIAi{6rXL2$>(w>PzSfF!cV5%Q(vTWVa0d)w@tdR8im=4Pk#l_1*CG=}ZZ> zqcm9)(90fR5XS-1RG~yXSp^q^yuy9YOyYc&VqW5Q6MSY#{jG@wLFu_j#oW^Q-(*>hQEF-iFt$iqiJz3|S)S)g^9Z z50K1I2MyRf&a z_}wj*STeK5JqYk}{YQss9pJ?-=7rR$r;8-Lphlisoy!ixEZ;KN&!9l#U%!jKJ(2=S zeN@!Gy7y7+wjF3CF={V z>d(!b(S=9_iu4Qt1N zD+~P;yT%gm;t^k>PnLg>B4Y&k4Z5A0*}dZ$E`7OoTpOW%zZuhO6NN|AM)jL5lo}EG zaWp$fWk;B6_ZexRV6$fNbghlZs4J;XjMjM1=x>MFhs8C#*j6rMlR&v|?xAq(mZMJL z07lU5rVnW?=K0O%SL?2eWGteWDi*ZLn%?m`E<9?j$6A9Oz5t*2z`*XXTA$UB$A&RF zOwR4J1@I{HI3j<1=@Av!d30186D!=ti-nWmcBLVn&p)jMCSm36o%K#XK2yY}zlAAI zJrIut8Cg8ER@j2?S*u`xUq@UhfE?ApRoYzDTLmZtDP$4B?L{%<-^Kad~-; zC-ZHKzc^n*>*{+=P?4l6$?6(|?|VK%BDIqG8)-3X_-GZHW_&xr5{RwQZ=mHV_6pDQ z7y@k@5NWV`-F|y^zTTOx!j+0YpkWKl3QP#p)2rQDks|fGo0VlAj3wl@U8syD;N%zmmJ+`KVGW<{!kujEPSbVr9&^`NmL*#y@3h*tiQAmvjgbno%KK~SkB*1l& z%3zzRS{#YHpHoauQyNrGh`~MfaU?{^hd@F0I)>x7W?lc~Y77#%qt02i!oRyrrX8;} zYMv`dyao$+Co4V+`hD4~(AcLSjz2n{GryiR9sWY%l-QhTaFhn|3CpfGa?pG#lTs18 z>ph2J;A9w*mR?V@r=rIDajHgpxA`C#(EgnW>mFip8|}jdP-AGlQSu?ct$@%fa}XXK#%~)|a&pQMmE8N|mv|^hsjW8_b4} zr}4AN)+Iai&#cd-bIN85^DbdN`c)yHDV)o?-!o&HgO;8Bs$`l)DFVZf$?V;Wh4uEG zaE_o_Q+OXteTb$&iH~=m_kJo1twE0PP_Q(q(?8*rNMCalEr~02`97{RTC3KX3|h?; z7`vW>hjkw=*4rl?r(0nfrb=I^*Ya73lU`M^dW^P3Gluh`el-ThDzjJ#RYhjiW^)jIJ_u3ke@K)F?@|8P>HNPv4A#3qhe@X4L*)&dl%N^ zgCbr<26VtiwLXoW7X?25+8S8a^kmr~9%N?Ko z!wQ+r6uMOIytnr8xLCE+>+m(0n~sI17RxU`gUu{&tpP0EX%G0XCh(OPZNn35MjGCh zs{XT12r$&(Q3lMBiVFO?l{o|!wG6%GRA+Uc|Iev@@1K#y^>|hUq+X`7pYRo(-|ObH zBna=POiI$>yHcZ-atBGOaA1jI+l`nIFlkrB?eckC7Uvjt=Zw`4# z9pqpy3}{J<7;xE$$8XZ9TQLK@t*!x&%Qssn+l8X9ZN0%Mh;Q*JCYc<*#P87$!Y@XT zP!oaOgVb9tWI}@Az+BMOa0@_4KvAg-ygqM*)BCV6-0pt8;uO|8S)tkH_plk|-*b+J z-}houXWH5vBm7OXjF%|;HQ+orA}BFoiVizQbB+av+6yszR;HeB_>sfrn&;-R7Ih5UUp{-AAr&}%5>*JyPPSwOTE z9abwdL+DAN_nqIZvkQ#cq7n+rVARE{FfnU&`rw~#^T$LJy@ zbaOkCkgEuGV&sp!F`joNJ=@XN^G$EN@6V+%vXHggW z(_$onyfcA78M`u?OlB(g(EVt;{|*a)K2?|3>Al_So{-Yye*KQu29bhP7TCn;e^UqL zu$C@#gYUqPBtnPC0fAHaJIVPP@ezv}HBC?JOBeXlgV@dCp}!8m%qi~~g^=w` zWo(OGXrhPagGbpZ_jvKV=o!x*!~XNI>4JnMJC)5>786HmsldQsSyvR9bt0d?{~MD_ z|NX5)YR$h)Wo>IPNwaOG$+m1_GHcr%bA?*9*d2)R>fYB6Sk|+HQrZ0H+cBGpPb>`E*R#*7b^~%czB%hsy%TWK4JpEy?Ducf~&-A?Q7D&;4Ug z=qWN4Hv~;6+5ayd$pSwD>J~1_Vn`SJpYu9+%;}d{)U8F#TLE1z9o=d3^u?-ze`fU_ zD{;QnVC87mc!P%ECK$LPnv2pItG<6pwPb7=0zO<=nq#Sq63YSfCUM8jH)qAE-}9G`EaI$tSY)4_ywG28nN`fU z*;p_@RU<#R%lIW|njp&ii4f|)QQ8viWafX2opo)pS$14y(jU!MhaN}jwWv=if>7~djKWg&0r$|tYNpjZ#Q?4y|UUW5oiN5k~3X9Q>0NhTX%ML~G#QHK}w zmZ|!FgX>vtV6Zy8S-7elWG4z?4Df#(tu>zQvVb$?bI=oPl<*b;N%D7w;ru{_y`I-=7QqlaE;n`YlTGSXh$-|gGQ5Gg4XDImJ6y@D#woGH?w+2)p@r{; zW}>|>Dm@J}+H61ADhOh!SpFM2hvrHYUG_#2X;q8i7X}R9Ypv&~r0c2PvEci2=PNYP zYJjIrqNCu0;WRe4gOjrV0dmV2S+)OTn0Adu%|XHK7<1cGE?XF1HM*J>QNSGrw!~_) zp3Fjp)N9}$ehn6_853uao6sGJ2D?`8FzEMt-Z0=I{?!A8;7FsFPN<4aKN~<85Qk>H z7#ECEVO$w{g>5?gt;F`;j%mjka{B!Tw`$S(rXmJ-5Lb^Ghe7%k;#$ZArkmH@Zfa*~ zJPZkUXCUf3ubYkGJyo~kv{sNSuJ-iBrsccIRmXc*CPAkzcbV8|@^F=P5ezimB=&t&o1=+6SphSyrM{2szHYnrbWEsRN;tkoPOR8RP=-?>=x5B7PU4h z$*gHi%B8}qTUdqbM4MecEy(V*P?WS#pOBrp(e0E`q&?PFQs}efMFoJ`N^Sj9hNBv2 z;Ot|zemI^z*a^L7#f^4laaOt>_X(3k%F&F^mjSd##tdfCL$)DkD!#j%+Wm=aS@No* zZTXPl!ONb}b2bIQBK1+|ODsVx5UyMHmwvql<4BCAagL{3H`;!y7aNJ+%a}0GFuf8~^_f8QV zh~6FDsIgdo)L+fQgt6ktRQea37RjNI%?rz#`$;1D#$E4?n%4LBVB)%&d&9HP<8lL7 z6%066Xt=BY;8f0uKx^ZM^>e#tAcn~sCWEMD3B%HE2GQ$C`vDK!a|GJq&PO(YD?$L9 z$$f~U5lg^xiUCVcHd`@`$bwGq$Ll5$OQz{D3PYr;d{yh}vTR)stqp z@;P)En@ScZXMeg6O2@GuuGts3LVb@S%?)}*_iz2S+8WsIv5Z34Bgg<)K$FW_jg4T zFQU)N+(kpQfVRyJj#YojMAc(pQhA?WH3h?u2xJDI-hfo#NvJFnC}L)iL`gmdS3+eav_ zqXfwWF_oa#X0=jKMqQhqbOb_HK;11+P^b{K9nF7sQ4Jpt1Mump_9cYtVfyRY<>Fkg_XO~N&sp@E$lXO zWSO-4v!TK{*3Y0RsR+7B3iN90IX204Aa+Uzf{??=c6TWQgJMbh6K4pa6Xo&T9GUq~ zz$Gvt-AkQYEAVi>YZOVmib-E*9OC-<17712fO{YJi6-x~!Cu!5mCj)wemjLj&I{+r zdX!BzqLPJ1cDya>$5P1BA}|?mw2=r&gLXS9rA2l>FQ6Q(i9jHM>h!J~RXm*JkWeor zqY%m2{1gBg7?DCbk@#7i4(^8$uMuKlqV2*SG_dpyW&WRy6vRJJh8h!0IRDK&XDUO% zGLG7;u)Z4IMcGs_jLy4{XtmK{I^Z{-i)b+|L;$XDQCvrU+>=C^(_O9-wn3WkbbzpJ zyI6|7J7}s0qy)^!6X-Y(B0knMlS=!SLO{IVeH9l`1MbpoO@4fXPQYl}6N>5#_i?{4 zeyWDWuL{KH>PbHrHGX;1W^FeLW#9S}Zp9hb`i@&u{>Sd3iu z=r_OMI@1j9fqg8%Ms{wU9L?c*DS%%e6k;++V~7$15gz-e9Z6`=lhwoF!~ht6FA;>R zEl0&GzE^SZ`lMFFW7DtraDRbN2g%kC{oJmeNk2d)_eA?lFUbi&FUMG6zO7^mkgFMe z#$|T6CBHp%=>p+XP`o>C?76cRr}veqawy{Qpe|P3%4m_X=s7wC_I6vKOi(U72IFs! zm2CqRe7EWun#;sWVlw?J z58%iQfS(+s3f$zj%JKpy@EvMhT&@mto~F>REpj?0bzj4&K8OX2&gyl^9dDFy3 z1xe~Y1U)|-ODAzNr!Xc9>D2f>27LXekCDdQSH||f+lq`P(f>#K`3e1hq%(nly{HEu zfCJ?p467o327^kf04wPHY5fhQ_E*?Vw`XFK-KhpIg0LNkSe70l5R1b-{dKmMd{Af} z;f_&bNYd(|FHB9wv0EM=**I!zqdpUwQi{?c?mga)A z5_zI2%sm)?`StGuK%x+hpPtoj7&WEmcKp`xx}VlI>|pWgeexBV5hD>*J&V0$Y8oxg z=u5s=RWie|y3oxe@kW_6OrQqa9m~ZGPtGP~LI4m>NVm3(1RnCB81bhupf_Ow1 z!*LDr2J^k$wD-`?&!}FvyVGY1J5|^T@?uN}jOeX7G9$(Q=bDrUP_Mv@T-(J2VMENh z0h7WeO3e%&805<1gdqu^gkE~Mg>PaBC^3^zNaUshBAvLORGm(7ViEA!ruzd971|2B zoGG|t^EvYTPyZCU)-ldoTJ%Eka_zc2-S6L*kqe4E-;?|?8`~Y0bFm_Xd*6wAcZYQ{rIU^=DXP;3B1`fiE9M)F?4urb5FcEPz zLf(7t&)4+1pAS7whfV?DTyZPAFZ|of_Zg<`zAPR)R`PDvdDeBO9|c9``J!A3M1Z2l zg`DYlN8(XtwOIib<9vm6o`~BVtAmI&xQz=t_k~jS3nUt8YRQ)#bDC5rSmeL0&eq`m z!9w$CGVmv4BbUT(sd#WC%i-=zO`U0kJPWLacN~$g94xHYlQK}w`Tk!y_ZkMi@3cQO z9FxMJSp5DkFH3c8?Q!N6kXTr$Z!x%Y%l@le4xgiyPT~a%P??qcs?R@;_o=4u)OAvAB+Jvfrps^!|D9Y|aFU1|QPfl=j-#H0n`r~9mE5+{0@`y<$!`=mum zSp50jw$Ox}67Wv0r^(BSLqPcFVucgJAH@zWCuDAeATOYx85BtnjRsQ$Sb%jxdZ)?` zMxN?;`{rVeDsqc;|2zbq=+K~;gd+f|?niK7w~%wl$E6i*PoY_l=rxMfNN10j2+nsX z%6&OyeygHEG}?dI^qOc51MFQQ>>d19*yi)+L)`vcOzct z?UN;?H$6(gV{HurNO`d1TfJPrSCPqzoQ;)ol#~vL!Bx5;hJNZKA=(YCXYN$GT-r?= z$f;*#DqikNuPPm_@*8eWZ~T5Vc`eROR#}bKZQL8(LfI!1v}pa=D1=KnU4R|5{=5%1 zobtH}iiV?{88ZG2P{TV=XqNAN<$Jgy@8=a)h6~)@4J0*Mx7B;=y3JmsK3Tg!+9eN@*^Spclj)dWN5ju_JKX0r_NZ2>xdC5%jF-rk$=0Jt{*B_cU zW5wYRNY&f_(Z+c8GjAy&Uk`d{f~3}D*E3T~W^ANk^ASrJ7e(V3iS zokSyn;0&_-Z;t-`(k3(@h5V;Jz(Zcc{YW;Z>+NM9IQG zTwIgb{<(QM1+>C#BxVyQzuA_GKD5+l1HnM}ao1Pme6S{3iC+&VXMoUOhaWHZ`Q~rF zzl>xZX1>1DYDn{E6d^lS*5br-*xaQvp;9GM(8gD z5`Lp*Aw$l4RFa~^Nj=4UMbhwFJc&;mzH`N3iPxtWdP9`w-T1Q@@hC8toXWT>C~MKM zPYD0LmW4B5*b~t`N7)~#qg6`z z37TS}VL+>g^Kf^JpPMVxy>_5qAA0i-d3=#yhJw%-G0CJU@m!AsnrQf2fD0TBFvJ72fg(7l(3Kn4)0*X0(d#_Ul7ueQT4A zM7)Qz!(ExO|E3=lY9h!~>IzIez=i#Q^n0a)hwlhmHL<%;>NssXE6@2*ffp&=mg&tyt0ito zl^;F1Wan(z_w2JAjUp$3eCxkaCev0N1l^GnkGTOBd6$5f>i&s<)1>lS5R{xYymcsd zAPQltal1RC2SHWJI0}{g&Ov@YH2FQ9MiF%YuuYvESo}~J(w9R2a=+HrW;H~;@ zsrNO)B_v0{-kop4$Qsql^rweoiSNO~B|CH<_!>*1rb{MFwd2d+{b8=^82;c@E{~E` znF>GyfG4euAAjyA^ZG_8;&by^-Q?loM$P!Ijhm@zt!cy}D$fdxi8=(OwXWPGG6##9 zPXTw-z2hZ%)_u8Hx?03nmcd6B#Il1O4H`d2xNj+jAQ#`|9~F-;TYW&;(~` zVHSzeYKY&<>b0W3 z5$Q_7rODnm%swX|Q)PKjI9uqKo8S+vjnjJB0`nzC&$lMIgs(?(zlkC4OfO48mqUZ!8=iLEnY<1I?j$lxG5e+sh|C<7{4j z1d0^;23059JU<_jT?0^Zs8|G>m0q9^_b+HuQd;`OJ!kKTjok6@%U{1 zB;~%(DH3g9)8FK>kP>oi=~?|5{cboX6HoG{3%&XLoB9Ua4NwPMJ<1KT@wvGil9_=_ z#|R!WP~T5rUFiGol@$20V-3j^Qkf4?y#U{e-h=s=$~(23v_7@Uz8JOT?;YCG9D(-O z;Y-V0u;jmR`t3K}ug@8_Tb&O}2udQ4H_8axeR*M55~v-o?pP{(z-F!!DsODM zq*=4eDp4~Pj7?v9<#%3P`221E+b9|MW-N!b*1Jinl7w$4eWJuNz`i@9_d~exvs+FOnG? zjsZSygnyT_1b|urxAM*7!pw|sU^^Jr*L;J26dNG~091boV(a!!!GJu7Gw^jZS%Z;~%!t=`*THoyU0L9BzI@PWt-_OTEXrV^&FP;wB&v6wTl{KBx zaUetMMKT0Hwh4$Hid}9KI3>zwD&fD~eecw5VkUzK4(@AYCXQR{lK)Gi^7Oc~z-Uk# zd4a=2Z12)1;5TY-d{=y{XcbF9(j9_HU3vl=PvSK$fQV=G_51AU-fsNs9#Wv)P=Z*u zUMra)29coLGU(b`{^kc?KV`1* z5cS5{AcutD^6Mm!i5;v40nA41jl}MdKb=Uh%c0c(tEAuof~0hnj%!A5rQK@k2SGNA zB3h}UN2mVdIb>w*CYhX-o5#bokMD~VCT7SnvmTqyqguVH98#zRP#gsE;(7n02mhy9 zTfRNTL?6X4(^Pz-)0?S(+>n)0&7n=#ZSv?s9?!>;8Oy zGat0k*=go`wnPFgQ!HmA592Bz$nN2A%pl<1m}xkjYS6jlA!$e`JhAilVqKu@avfSA zUX~MADV^s#;Q^GM``uCUL<-$+rAJ6;Un&`={#3@hs6ea;I}(7gl=wDF2^YOsDsq}$ z8Xk!su}#-=I#>MLG%TAhBU<#ggVk8RSfly)59;rJ;xR++wi{WAs7>#*H;efpszW05 zvZ>QfdFd8d1l*}^!f#b_8GV*{Jdy`HgIfbp`*j(>QEXha!4_!mg#Q~Lt$-1xKq zZC7Z-AHrFyjZNMA@kZ_=oXsDVPObd*JjxzLA!iSya=1S0Rjy*pkfI<&MzxXevwG9z z*kR@XQi?&iGc=4|vo*u|Gg2sm< zNYEh6Qh?&74W$H-E?q-B`VS`Tw&76BQV~PO(s)YiEn5`Tx5m$wllKqMDz)c!Hw~KT zB53Xc2BZ10cX*8Q8d*j14q5kDszT>+jZUJhB4-M%6OT7HcUS8z(fImstx&otpOCNW zW(wJDgvIv5weqM*3$oL#3-#T1x4%+RZ zaob344o+m|zlBvgX!S@`{#b}*}*>4ud+c)ts-see2vdz>BmviCkZ>m4m6?>FhYY*hariO#Uh~>{B@_&GZf7| zB(xPFfZ{y(T;UJ+tG`2UQm!`74CgBl|M(Ry;H|Vt&_<^Zh2hXl8H+FWjtji09H&M$ zkws5d9JfpEiXm`~0l*?KBpAaMLhyC|6w7X@=jcNtb@J_U1IHX#r`u?f4j%>E|22g~ z08FFjJ{*@t>~+J!EtSbpi9pk%j{g-M7ECSo>1Smp^x>qlJ6|{HCaU^N&GwP!O({X_P=?*|kvxj|-|OLdi0fTd8IkI#>@ir|sE;-v z0W)@up6QQTuZlTxmnOcV(OA8OlE1kjN`o^w%f=<@{hV&8I_U`-@noWWQs{(9tB?HTtD*Y7yC_x-N}yb64q@e6h#ykCaEX_LFmP7%HU+{6il2gD+XV!=j7w={>L$h7iur?o&%g26< zIznos4mB~Fueto~*lms3PLg-J=^bM-n}sU8eP^u*8#E1wX}S>}9Nd`jc#_2Wnz?>3 z0%zzR!bw1dh-|G#NTZz;g3rxni$k%xJBTE);wv&&+%d_df8=1aCpe(FRk%>~y(IWM zwe=!;-DmX2nZmK8P>l`$)uBHxE1bWu0o(m-`ueZy%(=|ym%kSi_@8?~J)b{%aR7nR z2HD)qd!%p1Pp;l~dR+{Pufb@QYF~kTR)2vM7l?(QG=uYHL{kp+3R`6~YuV!WPN9`{VVL$>T1AdEQ{@2+e2NqX%5g- za6S$BPY_%f4@HTUnd+kX4k5RxqLhUwxD#u_j0U z8yzn;VY&VVn%(%wm#D;eDIt%r*SSJMj%#a+tw?$yJlES1q--2wwf2OJwxfQ3&k29M z+B7yZhlD|p{$uCyCjp)o9zW9m9(%v%=HKCpu^LnnR%atQ{aAT1EUkvfe|&`^_q&fhMfFS zWBjsn_@kc^o01@-uF9hQ=EZLk$66n5$_kO|oqO|hSTMTnMsJgC+i!dk;7qCc*qm|S zpC%QL*Mxd*38V&|Q6yeDUg({e6`pm798RwF46i1y#pc5j+e{*pQpb(IJb+mlzf7(k z%oM__%uXQ>iDj@6#V$yruW7C{uK9SB;#dQY9k-jw?3+eFme5fvjX~#L3h?h+*X>JP zxq-8w;xhoKZDix$b}o~F5frAURJ`~)1Bk$Tbz9gn41Xutd=Un^@KYdr9E2;KoAUsE zdwzidxdTi#WN)eKd-%(a-7=_FS6X}4=-YtX1Fj9qu2%09`64w4Wg6vRw2VVk{$L|Bh5gQP@@3L zZaJH10Io1yD*7shw0N=Jn3Pw=0w_Db?IU_sAOW3P^EEj%oF`Y$jCr#uz>fa)fOIhV z_pC?AQ`jeCyFb37uc+NE<~yaOLbQ!sKb1UQTi|jL)*~i^mT(D#E+98gPbgMA?0kPL z;m7W{mZVt|Tc|1=3u)WPhtm1z=L)Xn_hSO@qOAl1TGE_fW|sy&6ci*<*E_K3YAS^@ zU;fV=0*{E52a0$ZNeCKKMUX9J6Jz#!<4OBF?FJSylZ+)$6Vd83(MGmc?Pz7Fy-dTT z2G^ah-rkxH7SwzZ$1qz3D7;NiSwSlt&GdX8&DY6X=|Z`NB|w~diy1|x@8i)kv4}8a zDq{uJZ37f>4lU;MqDG1co|tggRdD$e6orExDt6>M;D~JjrQ#;j?GN)OQzA`#-R^sP zJ-Zl9IsQ{~)sN=NXuY=dJ|PO&AYrYH>(XMl#Wz2Vlx5JCR+J7VEuo5P$ zaM?-%YA(e8)?6@D!6zM#YKSmua3#xmx~~VlE&|zA}0<25!5HIuLeCTa;VQy{PSR2`UR~`tQ$%S80Z$ zyOGc>8Jra*Y6f2ba8h=EyGL3HYR4_A-%Y@)dJX{q%|$>>q=k5IIrxLdIGsVOdgCwg z>p5QNe#tzOv*AND7xXb-*%k31$cae65 zA43{V#XAj96Qq1x@(_RCexuac;YXY%Qjou&O`QD6Q3gZ>jHnt{JW-f)r1`qs-o3(0 zyWU-ol5Z8vEMnOW{3d>(H8>c&fSxAvaop&|2#YoYiP&msI^G$Pdq+@pmmS70_7F&- z`aL%tysFosMM4O~pkiP=W2a* z<|qN5qfrOD7bd+U>>*N!A6%^R1fdg$xnr6@+z3p@?kb?38E#Id$3^ryP7;eaLQ?AL zsFbv}I8^XA9gOym-q@a!z!YiOT_6!E#_gf6slCQ!EckUh21HB&aHy?-_ub%|l4^Ee>`0$seID#J5B2SNE*vVHElATAxQFH3T0AsO$$aIf)cn{eT9z z>;E*sxa^kSVwhbl9KMOxbv$3BcwQsI!`jOwA3-L=832e+oU4ZQnP7#ZrNrP42Ys2y zqOY{Syzh+AgPIgp_kOEr3TN;wqPf7~n)-gZ>sF4LL{!Uidv7xm`7_A7)9Ra%Il+Y> z!~z6^5PEg{16f=FZ(rFXN`)RyYm$lJHvNWU|1m@pXXWbsnN-3Yj$qrG5I0LdOee=7^H`1zZH)%z=IM%UaDu3I@HTdZb^ zRQ)QoxU}gefVuobSTEfE%bemJup`|pdFZ|Dp5qhV6JKi@Q&k~JdhSQF{!(g~YmE?t zvwyBu+H;4mthQYdo3lZ4D3H#br3hk9H6*coN} zgV_rRdL}d3jH=VYB)da?e^9MUjZa&sR_xjAT-aCbaz%dx6-*XzIR%9=x2P+X|5F|HnynTxUI6T&fRE$7~9TMl%Q1J&`4OBXo(>*;Ib=HS0; zd@^3a^Q>W|)Tzs}0Lwyc^cy+c#|f!JCzVZR4|{?HVLv{pwpEy~7u)mF%JAcAo@fYh zC~woxw-T^sAZ9-jISn*AO+IzvDP)AV$H~tD6Hd&`k9+}C6vq4 zFa>`5?-y$|C5t6es@jQ&^=zO#o`BCv3Ja?@lybuM=2v&b+aYeJ*WchaM~0GYCh|Uz ziOY$Ti=sE8Cx)S6??VOPIA*nkqY6Gxk_EiwZng_*R)az5Pn#-U`NTsWy&M|L58WDd zeM2M~^E1R+18EdcBu?FGHFCwSlhYBg=Gt=sMZ?}ay<5aFY;S7FB%U4zStbxnAianK z(H;-ky@*8(A^Ku$R=ojcKl=((h0EV06AAxy}w%}!vp>-NmkvBZ~To+6O?W>O0|2D{t8i{dPc6bo(ZQH$QUXU#C}J|@s?F~B|DvqHTL6Ue@M zw5zpr{nDo}-`i}^BsTw*od!T}ZiCuhwLek64B+}I&R6^D7Ap=92E}^zsBWG-oLEU! z1<$7l3F;l=TpzC6=`c(-!Gxe1(3JDW{{n&Cik!}~4Pq-M5--OvAi;S12K}@rQFT9? zpZtbbVT(3PfbS`v)PPL|st8zRL1(qvzwR|~?8n{Z$bB*S)kws?oi?lQ^P!bb^CcoU zSSaA2LJb6_DFlsSNO~xCaG5sIF48%%C;2^8UkoWeZ4hxkrnKocC~6}2Wq%5RC{YcY zCASnu?j*1kmv>Zm#%dw`8Wxw4P3RNkG6$eZ5ZYlrPeNX(zcOth;)>2#51uR}kUseYi<}z&dXmR4edVwxYTlxN zj3biIcNpKxIxsExg<8=RHxPwjm+@sr_d4xb=rO*VS@Z1z_7@rtq`Tg)gISs8u<}1T zLkRA&xhnk3f3cbQay@|Ei8f@2ORcW#g>^%Iwe3;WXg7^7iB5Rf43^8jpvog{$9WK2 zIPK+p(}_?Wb7Z3rg<0&A#4orcOa`MT|1^<1#D z@i2&+2cRGEz*h4)pN z0B5Q|nqG}>lR%g^p4Wrz-IZ3c&K8X#OO0Ng_4F88G||rdSVSV{2d;GP6t6>D?WW1n zY7>~C^@w$AU0ui#{U$b44cUH?FeG2$=Tb$IeQsJ)8zW>Cz3Ab~J#8{bwGL}p2#Zl= zLlY6r%F#S%hnCL0sWP0GK}~gLy}`ZhjwYAONY+Wz(M&mLskzQ_Zg0m^LrM2k3#zuQ z!jz@(2E#~t4Y(1&8kKpRH8|&B1KU(w5d!KE^ZW54-LtR1Fud!P-T>cg_`kn@tz5#k zey!zi1J8B$Pq@RkPv=7zG$|p$;jx5u8f^pI7%H=sLmTkup1#il!WV0zvV$WTAzBs2 zjVF(HwS?2(`YiuS@au4HkRwx7MvgIr`dnedX>>7wmq!~#vN%)}Plxq_2!&D&^KJid zo}eAIPS_A)YbF#Cg;&2Zeq#3QkJHqmty-Wn@*KJ_anLJwvdcCLbk5w*597GfY_*c0 zrf(WWhgylWvh4O~(Z}qh21>$XEl_|9jMRNVEy-pn^uer4w?UNy*;PeOKtM*MB{))c zNmYmAS}Jmogf{nU=L9APtix75H@kk+e6@rONAt!;`Y>AOO{I%P+xtcqsh^y7q-`ZK zSg}fvQ@=jiGVF@@l5;#B&I>Jbu<)~FWpA4l!owCKBhkOY=6FlH3wAX!90pRy$n1zfC+Q3GB2Oo}TIWqrVTjsQ1mWiT z2PVH1l>M~VR?(S`4hxPsZCI)WdSdt^brr=k;6Wz=bG`y(FzShXQdHSnNfawJ>5OD9 z*b=q%Vscxgc)kiZCew4OSy^ame2cvhDY|?fbQ0cBNcoy%;RTsW!;Nr55X5R~_-8&Bxg!LoYJ< zFH7)-({Yx{(*){+HQgLVA}w=Tb9a2Mz7(5}cL8j6N%?yU15DQIk&Fuol;^|w)?oge zZr0vEy@jJ%uarj9x<|Y0#86`ix}_gLEh?L~(>#T3Iw6Mx>r26&O* zW!2v)EXM=2xrW!UUHVXcZYEv-#Phx5ftMhhDxSi{5@8%3Ki^6rwLpT7Zn)gDdirZx z3;XX^@B3Nc?x{$@r;P~UK34nU0t9`o!NL=~;(IZ|=N4XX?S|`2rA95QU}keR!#GHh zBH{z~8yPa;HeV`r5h}4cgd3IKBH^VVQ~(dTCqSOR|0uZxTgqo1=%6Rkwtv4XIT!XD4@t7 znQPBBR{975-xoJj7E_S4Obr<9DvedT+)oRjHpqbV7opmcJ zk-!S1<~Zf;H;eu-Wb7kYq$-v+oRVMV+NIxm_@KlDWnQ_zhI#XBvnm9<1+}(b+&Z;1 zP8;^0aF532m~kvYW7?Q-HYrPB6Lgun(L2FVgY$r>Mt@U#xgz@$QXFYUi z!|x&%KR!F8M)jT|2ru+Il{}bkf^x2~ziQNJ)bAn)oP|;>n;vclML8rP>uvdCRwg}J znI0kL=fcdGz3k_Mq|t^9gC15@a!_7s#q(iTZ0oF6to8Vq}c)k1#oSRJ}LY= zW5j^&$cs&oxx_cDdH85hySX{`G+S3xRtiO`SU)I zF7U_x+NML1iPV^$E}Rhqk@aD4W|HjpV5|Q&S)cc7YKziDWr`4#yuNMVsl#9oe<(K$qeenxLZ6~ zExv!6l6qCW)TE&WOUq5gxyHVeV$c|al4NhT%!edVLT98l_alTWjLiSEnoi_S+)J}k zk#)7Y@KUWrIfxCqvRFy!2ddj=mfTvpwV&i_HRfhSpg}zZAvDie4WB1I%Jt7X9k0_M zSmblVGh_P%QXzR{wC~q5j6@m1IKFEoD(8)UK6?u>qQN#Uw=VrwR3*=8j$25}9OO>3 z-;*j+=UdW9aXD?OxDy$n$C@$#ic+>w1!ED{f?**4AlO&+5N8x<N4v<3N^SS^l4?dPZ((cI3iism+t@rm2wR9q7h{CWn3KWXOU?qYJQ^<8R zx~D_P5CaeaI$-&;a4=Hq__Q@tW55yx4o`&xDGHF3jQg%wa4z?kU-9a<89B5rcZnzQ zhj*Dv8r%HtylXAvLV`)D74ESWxNUG(uP5a?2fiF3A(gpw=3TVi^tURO1|0Pur2t%R&Q{F>DiqiCG&xOdypHJgKihJ z(m{{AZw>^Ynck?LuPZJ)3%@A9AHIinzG);@H-6p;pH*&!akuJ66Nf{toy0hGeY7k| zC&i|eRdpUrHyOMRZ7E{VKn+a8Wkj!ZAouf(C43s77?g`;%R|>Xp^-d&{fAS9^6P@; ziyYS=?2w4KWrbnE(|aF`+f(R%(5v#90(u##Olv2LMySP5R8tb*72w{c+9BPlKH`K+ zt#=(7*C;@e&DGGDOi-*)D;NtjRne8}4e4Dj|J>6-U-sPlqALu`{h@vI@E$}}XUcPs z0orT>H4`8E7dhGzCfchvw?3Uv_G}yOV1)5g3i#H7gM(v+jH$J2R9LIk5wW4Xm&?7)g#&-l>{g}#DGMS9&kyC%hOm?ZqEPN%OVDn+ zkcqFYrUqXJtaXJUJN@}3lgW2Qd9sh${yYeS5e)1@SC1oW-%z^vEyz;J zV`HidT()*UkZ*5n4%B{0)g$)4F<1Ku>2Z|fpTV8tFTO68E!3jOoy7ARjbkB=9YD}L zn4m>aUH~~7OY*;`!wuwh;^X0tpvzp1V5ppN+k+s0jo0xWw;CrMPf*t80Uq4WNB{Qz zK``Bpwj7tkaHv;%q|zgAO9}nS@1Tek7U=MT>IeX> zUh_QQ`}_iutvNY4%x$+~ZI|eF3oz&;gCV*NmhY-YG(HYFav`RbewZ))O4^G^&0J*U z85Gxbgq%U%TnBKigE?KJf5N#}3;b1tf4-{sS-lYgRM(>Z0{!gb3-sNe44UZXJmvfZZqZUO+YU4zS_rO)^Fi)`V&pWt=M*t4gy{qzhVVps_eWUd0lAZ^w?~Y zUlJjeGj=0^RA4nnz!sW@DG@A=GRo&BrvC&V{hpidDVD6by|>v7c$N25758-;HmxAO z@^n5%e$IXzOIFFZHD`rGhYR_;OI=fP~>W7b&58Fi9u-!Q$iP7O#2f`UG2DyK}RnDEqtG4lY#y{Ud z!}Y6$peIcdS2=s1{ z!AUJ%%lGe=TIITl7iO4K--RLnOs`@BrchiA(dA|obykoJNR|^}xPwg~3ZwSg3Sl`N^S90_~l?V-|6Qk3Wsw@*AxnN^5%CM?qS^#O(~XKMu1IPhuf1ToISCj zyg(&eLV*Ic%NHsCjU_w~)EmqF_Ndheg1Y=7B0fJ^NoF$yk5ZeBNikXXt+wYY-&V~f z$?h_Ld}O#Z#Df2&C7f-3Mv(%t{c?H}+_%kZLkQh|gjf6OOv&l*X3zHPi6HJxbRl49ehg ze=G45OtrT9YZRPR<=rBSq{lJ5vyE>}pgv9h%bT)WI!lhR|36RlSI8dnaPebq2m42@ zZx}NF?;EZ_=~V8x(uI7fn^*hsjpGs8)hunz4h9*)?m6yu1O|Th9Lta`HDxj@K1!%; zmHL8Z4s>H#BXiEV9Syd*1?v9!ZO`eXU7v6V)H)005*=sujdP($P(>F@FtN7p{-hYB zwh9}9QVjn_!*kQIB5t@qJM`c&p^fj(iGLbagZbTz30lBx6oKEpV38|!A~0`1h<5dT zb-~h)Y(XD)ptrSplTDXh)w=GjwffxUbv@o4igq4UF7`F=jE+3w*>@z$q^pl$?4>lj zb+aQ2nwQMIfaIf=eU^u1cCD4(JT8OQwUzu*OWF-SeFz>Yb!E%zqqiziNI27^*+Q99 z80e~Ct#cm}78i2E`P^_KW4OQqAxy(wZ|XVbyNJyB`V9z-l2*S_d=;WRou9eafh z23s|gJQ9=!yms|+{G8HnZZ`fynf&J*(TNN+at@>d{Z0&TDT6;#mO4Da5s0qm*ZJWv z|H`S*kR#>4xTITFayVS`6y-{u?r`FJU<3qPCrFPj&sd<~2v3`mjb)vK6=@FY^X zVs!Im{n%>J-`p(J34|;5Cwt3 z^AB>of(Uxz-@tpLK`2AIo%V}AJkJV zP+p=gq|Ig@hfYHHp(Os1hTY?&n)v=RB}j7`*eAF!>;n)5N&n4JLa{kHWp4h8Pu%Oy z!)XY~*iFq`=Ceb%5(QcfiAjTY#X7hrbL3{6eQrZw`@-tMV9pvoSg9^lVgLmoTHpJm zA;fpP(Ro+)XLs7XGq|wLD|F^{GlxY&O&qs}@IL(bbC;8oD9Uw-h}6t$jjcsKl0Hz7 z1gP7TDM_VjX*N@+4GwB75maWB_yVaE6nXmM_`GgWOr%rA7x+(E^hqhmh;ZVw-_PfQ zfctvoIS88g+ig3u|Kn#=S8)BRBWXt0v;NEvTh|A81*1O`f66>i6~@!C0#J-t->ZNIIJ>?w!Ik|NGOLT-<=4_ zpXPER(P>kr7!BredVfsHVPk$`^qDc^+oKmm6yFEu{unZ)trowZKu_HLV>)1p-4TjN zJdk%v(Lw$W8NX1Fq(r5=m=$xXSf0SEoW+Hj!6p?NBk!%mr|Qs90)ZLOI+=zIEMNay zItbz?y+P3MP%#2@Mgbk(?EIE)lm<@^&1Yo=_ce8FpnA)yzZwmbi$1gye zwQJ|@oJy9CcH7cG8nFS1qcrS&m*dNKwTNVL77Mhgy?N(Ho;r_$vs+d{10>vnWuspR z3)F08#t0w31WXWIS{=-sh51^s;#Whp;GGZ3P&aGcpVQ}Ln^+owyPqEa;Gp6aQ1rHwCzDLi+;MSCrcIN zq*Q3ehM4Xn$R_Q64TmE7+BR20f_$Ive_$;C^WBiwV9_M^9S1=P`{|G(1Lcyz^Foo? zmE80<@bK}X;Z(LW)xjk9ONQ|}9uxQIZVk%wq%e`Fl_S%*KtSShGS~*((-k&WW|lXy(k3l-2QujA28P=V&pfSs71J zXXC;n==3j01Lg2|ZsR8ln^Y`{{mR$6gM|jI8urG{5?I3`B{Kh8JOgmZs=%X4vc_07Iuyd~mBu6Ko z{X_vym+QBJA;T5Z1&H0B#dNXO3C;mUx(cKmIAYg+l>Q&1yw^Hxw$XZ9)pAse=L7>S z1RsVqhH@aQJVcU)nDeQ>*hOh`Yll^tv=BA$HS1 zmN3pP@S(>~R7#W;u6H6|{i9`q@Dq*=M0~z-MLpoMuEqrVVHo!&magSSNKkZ775m9% z(kQ(apd)-^`E*ab1De?$2WaF;B071U-?+Sn=@>{5!fFzq#$l4bvZ;L;PIKLbNF}jM zKAitOjD`=vl&~_EidjUA+BR4FvCC(H!;28tv4**g7FEB_#)mf-jHSPFGE{hu8V=qr z;AHb_Q9pEqilL_;SPI~MXvFyX=A!^Ei10kf9nSqNuz>jwn*D!*11c@|%Mh#=r?~=} z7^08{0V9`MIdXUpYZe9~iS8$(Atd~bPS&v5wg}I<4ZFw?RuKoKAJT-N{5d5HSS>Md zK5GK12_o_dGk~s3E`{V7~nv*ZfKQjeRhmu_AiFf7Od>rgcaZP*Rp0UR z5@+I`%E&xEEXgPj&ob?F1_W!R?i9a=lCf^8{FM@w!zTtUd`FeC#FQH$^H5%q4m`Jm zdr;Z_J1RNsa&JC$jIzmP$jb=m2uG=qJImlFf%<0yzu3;;(jP$s1#f@c>evu&%HWfH&+z!f1v}jKbises_ZIc$P6wtwyPsFK|RKj8}>r^#UiiV^IuP(|G=_rsH zb~b2YE1XSYIG1R*T^VM4cX~;eX|D7Y!Rz<0g*uch?u$t|YvQYFv+3@Egel$IDWyFk zvH?(Z-D*Hd*W9(%nHaXcA9!=320v5MnYog|ownWa;lncX!OR&nGz&3=^f)f#<`1X^ zMn7*aVx4fbE89(KIcn(oRZp-%AY`_AR0^O`;-e^}gUW2UyIYg(q>c!2kL6Z|RSZe; zBtHqr_nq%!NHP*^dQrT|QaeB07XSLFx3$^lqgsIAR;y^)se|Z;&9nu_=YIL7Uc`k_ zpZMGwA&LGDMVJ*dtJDjaZC@WqJ%9-<2mZ%%q%o2jiz!00?V2$j(f!$!;(w57e+Qx{ z@2pDPUt&o%V!yM4!S+p^9A0z4!{E6c?4anIkt}|#B>CX|->t#PQgQAJ@AT@TAiI^P z$AcPE$Km*4;Orj*Uh>nc3)N_FnI9hF`&BhwU3vbcE zVfDH~4w#lG4CnT~e=s7uQxJqGjdN$WTu7{kHqv}pgD!IRB^8xoAYh%T*my*>>rw~K zs(-Aj7CD)Tgb$;K^W96^qmhvZ%%BHV zx`za+d~`7wuYksnP#7ZXCIW$GL$r^^eb>%V0q3DfP%PdN=*45f(!_?y&jVT-j|h2Y za-#;H$64R1R}e1MF`%Ckcc^n(>mM)6?U1+65JZ1v(o2A7v3(1G90_?1Nuc5Mf~gfZyR{-6+V^nlOQZepXXC3)ZW zfm$F!y$Y4Xa%PypWPUt1x8_4&g)V{gS4w#C#N2T)BHj~}P1z>rPLJb$HTGMa;13Q{ zl37UPM}PVnJU#;#3L;t@SxT{{`DlT&BWM;3s%*bb3n4j5;0FH-BjT%mlmKXW*)3s@ z?_)<>xQxE(6vT7&F#-4txRl!C8I99`fp*O{?FO?hgtP{_=3fJruT!Dya5Tj7LoZRS z8Uj`HXIu3_Ac^>sp%Q^){8D3QG+fY~aVRW`Il{>&ye%ukrJqvmD4!=xmU!IbF|k4i zvN%e!r%^mkCU?k2EES#`%#a1&CN>w0!J-nD^dc{r#3wToD$I?$Naz2ZYW@A2YMTxE z{Mi{aOJKj_*smnsLFF>WFiug3TBZf@<$FfPHU z%jS}if$yA>W8j-c#AbeJyAqDn{SvS)rv2Lg!n{mYcN|tz3jrPk2qx%txndJQ*0u@q zUR$OTAG0wIDwQp)>7a8=*e6Nv_EHVk4}?-AnF?G-}efOIP<5{brIGROa> zZprcD^v@+}_~{|{n*ypz@tZo;Kt4wGNci#O?eg1iS}sFFTqh9Uf&S5S5P9=Hp<5I= zEpw8B25MBx!TiOauS8s>SZVB?W!vNiKQxX`Vbs(1#Y}~~B#U{p01k(hST;ht_A6v; z<%_&Zy`gAJ%cxTT97Lkm1)vap)IiOO0vF)9WwYHJCNPhzHCq!YI=&bJHEmD*U(<>T zkC&|?g3WuSBWst}R0}O%oW(nXiH{)sDmd00+9y1NRE#(ca|2wqHyvNq7uYRY(naPt zf3)vtwh$S1re4{OtjZmYvNMgMb1h+H;b9=Wd0v2t%3rT2W ztNuifGrH$EVY%YJb0At=Rs=|=D{Lrzgr4WVX%e(8e-#t<1%^l6PiBKG;}EK*XU1i0 z2DP>_pTZfzEf#Co9yWt}iW)S!olm3MEuNbPykrt(jVo@eLaoaImhaai^DF@)`G`uW z2sDvSLj6_H7Xt#3==%QiLUOB1O+r(AU@*#o#N7I;?3PhyJaW8+SG<#w3_PG+I@WMj zOz%qsuYq4{oopJ<>)o!Tq72#+huo{mv~9O}0)F*|S(2Z6<&cntA4O_N_>R}bsS#Lw zG81Vr1#D9V0B!#i`fjC#JcMy1rMK>+KQoo2NY2wlPu7& zIQZW9o_|zY4dru#8fZfs$)=7G0PQPuG?1Ie3w0FCUchf<&DeEv9f@h%4XnT9%DGTd z$gcT521$;6X4nv+eo@%v-#v~9;cLD?VTmIwtPn#1%F=@tD~evbqC%vXdZVK!wI2e$ zD;bkdFNzl-KK^5=+Qka1SB=HZ`}^^CyGvdd!Q6JnC6N^|wmXXVfpatGC3=e**fP^V z@!*`58BFx$0Rh3lf9Vc<9%vFm^&sZDeI#;!iM_A!?S8sy)zZA9Fdsf3jRiLl*NXk8PP-mFC*U( zeI&=EO)kveDs26Lh?5o2?MihK&A(&*m*^5rEVK9L6>T$!gZ62D|B#ys0{{W1Rauf64s$XKX*$e*;c$#%6ZgTM!H^O|pcUUj}kyum*Wu6x^iS zs?EfY>Ot&lD)*yj1otWmXd&JF9SO5){H+!gZ;>}txOJqd7H)38L}Iczo1Pjzn8w4S z!L;Ag!%}>w5QjsnfCxgPeCIE`E3}83;xXwm zb(C(WwPg=G6k1TrfXnQu508+xfMV_LRP3tJN$< z=$s>o-d|o9EyR2<4fbdLxp2TDw#}>&RUd~*i4TM6=12g`;$HsOYH0W6otOas&O|6g z@2>3Ex!y6eO=+%)&4KevZKpf7jMveebj=6pESLEn8O+`hTZ+598~)Q1T_ZvX{+y2gR2lyd7sdZM&Bi80B!TGnbA?D@t(ABW zg5Y5|h4}8Z?-r6?8(<{zm%zayvwcoA93z#~Uj0dv3{E)i2Bk#8ga0O{p-dtaQ(zV<;ecnm537~7dK{P!jYOxi^vM27DE*6QN% zS;j9$KKb6=S^*mL$L=K7%RmaK_NQbtSh#VNY=8PV%Iv;4tA{F$uEhqIJ2VaGo(yW# z7&@T*P66xM@=kUQrf--o;O%R@K8u8CFl1DN_kR(@@T;~;zdp=6L~+Ryj{1i2b%SD($TPC-Iv#}5mSzmbI|q}93&(n* z9D0!4#)MT~dwcz#4}yq%l2j-(*-(c*5uup zDK}CMWFbprJou=%T7RT{{6+MaW_drOEFed!b&jS{Dv4%rO>>p1!tRWXwF zSPQl)Vx?l{8W>~9H;Tp(c7g%LhBTZQGO}w87dwEOEP62|*UHVXR+g)Wy8AN^n`cD97eL&{G*R;;ocqK64Ghpq{ z%y3pI_@&z})WzN5=d=O$tNh-U)WY@`m?IY1 zte+x?wD15rX*h?jOah8SZl>H7syQHg0!#9)o6{!sO;_p%%~;}Gi2)sC$3?FDH6AV8 zNF>+8erzJRiyip()8K3Y1TfLZ`|obzB)-vGc2mv#=hsz#qsj6LX|t?Z;7!i^)GGHDxuC-^!f7@lgJ_->wjX(B7AOC*O4pD;ZL~`dO)4) zbRgVVcDDDNj`nzvOv3IL3?~uoJNm6aQm2i13eU&Xv?JBRKP#Ty;pOr0nEYOBa$Djj z+M;-s`iyb;*!Fo4-}Ow$Z$MkzX9_1{H+R<)rceBQfyqva2myPq^p=2KnRj^j>HzyU zzRFBFE-cuM0P?VY0{Z&CNQ0B9M*XgXm1uApC#=H6H{fs501^(%j? zMNR7L5aq|GoA{LHTr)W@Rxt0akThERwf zqEdOri5Cu7gbmRKDhZp>!$Xu-E-kMHz)OAFF3zEZ<4r$EF#uNe@ffSA1>1+QEQP7= z9MN-*^Ps>!PyOn5SvtVfh=z<0R}T~s-*}tZ$?Kag*47n2wi^APBr&Nl)7RgV`N)OYB)A_!BUp#ngR z>g~3ImrnH?VGKe?d(L?% zyz*2WKJ(R`@M!&7uhRg{sw_iLH!D4jJpyS}`p61dQb-c5m+P28kyz7mshM-w&S#ftYl|Ibs3YIMMa4VFb|r0VSeD5)%cS-#`>20z|gadIQC*M4i#( zKRr#$DU=bjlQYRZp9*(e>a0=RxS)A2C#25ttJ^JANXvEmI(&4qA00vUWb-aM>02dK z$CEH5r;Q1Sl=}snGUO2GZqT!z`o0Rw*T$YZZzqW=<;hvXfj{|>gNxp8#rDqZf|ZH&xiD$q2J8n z1^*N-;};`lAn?|-5?s<1oU8^6sp)dr8HY+(x;&WZn-2GvqegXF9=;!x-f_Lh?29Fd zzU|;lC143OSyABq$lR7w-0{Q2mwfHmkvy;;@Q=N0VQbg`;E-r(b3k58npO46aW+ymkNl`tX_I>bq^JR@~4k7ER;B6Y!p60{N!Gl1EY8 znMiTZGkLZ`P7q@OWiuCQ7M;!}=3`(BSe%(wp>|#R^&WS~r*ZDDQ56%y>(MQk^i7A< zD`ZJx$FkY`s22!K#}vOQz)Tc;^m~H+5I3*ya?b%xrCMn0)M)+NlDvbAUWSU|)e&@FD}n5N{`2NNfnfR_8k0eh4bYV3dl6YE9Wx|jAwbEu z++q-?4FoA$-kS6@NUiEXqL>fo+^GG(`AVbIe~s(*f!B)Z>ZJTtZVVw8c0s0t@j*td zZ7YTlSFace6G}wsX?rG50rB`8e_!jcGMzx^>nwq&C}dwOD`iUV1!_)p6(63)YA0YV z(%7GqAOM0$%yj97Oz1IO?bzYG`ZCBL8j3@uNuZgIf!Oedqs5l&L+gDS``$i!&IJ*7 zQAM#V&T(DdDm;p^-x@5K<*0&Fz&W|QZHDU?wPH40a@loiB*Q*5^KzJY7fze-mP_420UOtAmDy_uop)5$AdW6ziZKlVAzs5 zcNfFoWov^;TR)&&DU%QLr5>1rgiPSBSo)JkzF{wI^nIu%>Ktxzxi~0)r>xv@((WSh zUELL0`8l4fSD%52&g)$HR!5vz45?YBVCNIR2R`0-4rJy&gL;lVwlUFbVsE-&&$FI2 zzlY5qkQ^FIjo6;N&g1k!`hhwwqYvZXQsmWUD~Lw8$$i{2#y?iJRgWE9qc~x~o{sXf z`BNAOY2+B=ULMlL*){p5^_Ewqc((YY==N#XcvtTtg2v`BeBIhp;nHrB68q@iv-%0e zxm!;+g;@^2quelHBWDnmc7`fu3p0}T1}TFn@3I4XZnA{|E}teh=D^FD$?^Rk_JlXN z*Uz^mNaw9STkYY@g5I8VbL}tNLIL-e!}D-Ph!s#*2h<%t&%X1;Q^i9Hz&U37y5UR~ z|E9Yek6Q%-kBMa()PA~0{kaP^`uP3Fwi?UD@y~Vb$$)t_!s*kr28SUnnA9)$9ZXWT zjljH`Vb&SECK>bof{i7e`4@NKFtDWINwevo~gd+!<#9LS|fz zsY?D}MKr!BYm4P)0aW~w-DmG{MQ&8(Qy$N88pXd z`HaNsJ7}_bj$+~9?6D>>Z5Jh3aT#z69}X(j@Ig~;)JG=K#i+or7^0?1G{^aw%@=<6 zcZ_(J;9-Qo53PlrZ&~fJOtrQ8@ybBgN`gLW={M`)pq?cli?=4-;m^YfFE+o&-`e4h zphu=?0>}l(7?X_QE@q4uz2>TqQP`iKDRXqW!;^2J5cO5eGp6%_}Fa`HGUHb zGIZ30{i&b#5Xn0}=+G`ftS53aXHo*Du71x8z&vC}ipwB?Fw2j8GGVmm1Li??7T1!P zh{uWi$L138QdRZQQPaU+oflI|`$-%6z)X`L1^x1n4WN{_peu?yfi-2M>*3l?k?(T5 zH|9Jk5<;!$12670M@U<50!83bC;;(}z=Q)I8V3V@o5a-t|It1=;V-LiRn|BOoPW}= ze$TaK`lG^u0ixHh+{Ylv{2%`?xtKbw7aeSQHRsw^u$W2nFAW0pvhMRNRlNP;NaP~i z*>A;qQw0WmD;L``pKy*P=t5@eE68xTje^HQ3D>(4Xx<8>Q9!f5 zO$EkKtGBPkjGnLXB3hZ-KY|k6HOgL*l19g%5WA(uwM_oK)7Q~#oj2`OQ`~=JY#+{h@SeYocpR7~u#gc84rVrg#1g!F zw7WavKGq5m3k#n8j_O4hS}3=7%z)1o{kbETDli8KXQh{k<$D&Rr?M#U&w#TWVCgfY z2~>Hk(ANl*LFmGl*4IaiO;_pcG;VnJHbb~~%?9L$VGPcDlfw=vf<)2@j{vZM;%hEs7$dqzjyvJUm z^Eteug?Sj~5GuJ~08WE?W#b1=PLlgQ;5n`CW>~$19BXK`S%S&|8x{d47YPX%NK_RN z*H`L3g`<4lAQ?`V(A)1VhZvZxrL%+oOny`@BHVuYMIp9z`RDxF-Gz%>yBbaLzGb77 zG^S--wOJF9K}EVeIee3)hC&8+1k?OOM-UrJo4;Q(#N!oSt3df1={5E#-8X8@wb`@~ z(%P(nz~vZo7qCOJQVDIhILU-%<$5xDi){8)DgB-9ZxDv!cx$*I`KidijZyjVhsgta zWmUBwe_!wURy0nRw2;>qW@C&$K7MHpGv5oXB%P4&xA2m$dEDi*Br)%AEPkVe$fxDS zGs@?C>Hl+K0%)l9wjb;5xFJ z-$@sNHgT+3kxsK{27yBO>$Ag~mkVS#{T5IEGUZ=VUoW3kZ`rAL zhKvX9eyu+2s%t+_Huu;I^aZy|JhtP6-)~o$%G8fBR4R9h-EEK?2)TE*`kdRDs}>j8 zNv~&m;O8EFSq&&og3S3WA>bZM%teKw@ArG?{sgxIRxR;87x} zxqc$>slSo8;BkL+-5YJnw0~$gu8+;?90tC~mhf1wCUJEVbIR&BB!GTySwcVS6LwO` zL7GU~6%#PFE>7MY+lV9=`hIUUGM3@nvD)Ce{#bU68)NQB8ie1H1Uad8Ye*MN{`V+w zz@+3Zj&7?A7RGVW zUykMZR1pYuV3GEV^_ot zV4FGqU(N0-UYpA!>xty(7B!@Z$F@JQ$untz&=j%x%5{(hpA4##DWLuaSO-1v2oaW1 zg&aI7*ZSq_zeRo^7m2z1gpe!l-2oyl;PB}pq7XxY^x!w0akx5^rC7*^QlPWa&3O%0 z$8W3s9u<(n-PWMhZ;OIu#?tE(G;5T%4uO(POrrDQvOt8dQ`I>URT<)S+eauOmzE%d z{+PnncS2h6C3a(V7~*>csT+CkX@cAn|p0ZE``$3!RJV!93(+pi(-hO5>de_B*vQWlmvJifOmP`89?^Y~Ke*w<+}b9M;Dc zTZh&*M&J$E)MyrB=}qrmlhQeEoZDY3&sNCpVb%X!A9D3;+O*0P&4N=Iarrj?*Wn>y4ZdfDGZ8*Y6^YKKS|O@ z0Di5I0*4;8N&zdm(4qVB`bx3GVr%{5+~CnGLZjnDss;xj+KAvZeHkPE!we57+!k02 zznV%rZ48T8EoQQBn-c0Hy&i;TzLi?z$ArjJ>|?x4ep!kIOnsTCs$%dTHUF|aST-4n zAxBWv=uKC!cj_3cQLtpJr{<-Kt`L=&L0%b`C1?<%8SMUi>VIMMR*Zs`Mdvt4t3p8a z;t$4^r6ahluFw1#AA$5&_Wmws8m^(F5tohEp|BR|5Uc`{v6KJeMgjCRML7c&OX*^7 z102_6^2}cC1DW9m5F?-8s7QQ;NyH`feqsI_zknAkgV}inxlkv8_N%`D`*8>%(U&Z? zj8Pf)4a_3zM0yeTzP}yZ)kKnv+N>>z*9%M%NJtuBq#M*I%-u2X zeXK_V$?5QR8x*@)`@y6i07-ANR7uB~D#W-#$19LU|Hr*F2LrshFCoA|#uNU$Jep}u z)r^udvWqgQOA$!gJf~>AFxlT0R`}MM);r|ZEqc-%t_L`5FJ@^ceE&^2oU)~ReeZ(} z;$6WFR-vK^>>EAbKSkjxaYX&wPKs!66Y+1Xw_d|Azg$6gmxaP#MsLFZ%O3sUS4+~K zzwxp)^Awy(9QP^d<~qUKI{Jp~c}JflN}w~pLdeKdySoFMwjWkjcR znVa||BaPs~L-N^mueOGU|I;Lcfu&b$55_gX| zKaYdV6KzS1CuewCkHyMzIY1z4rSo(+s<&c?2jj!J1}&)bkY5{@no2#oE&>Z7n*9db3j>=M@!LDj zCHNa3jiR;69YNOdFc2o{ADC(;z^NO2++Q{Sk77&I8{yzjPq< z_4A19=LH|Kkk=$b{44y51gcCVCTT!0M|H+n>QNKL0y8UH5lB$|I~c(6*2yl720efV z+EZ^=cHJc6KN?NAUW@bmV~jGbU3 z^7g(Bpx0)v4;IP&rA&o94K!T)2F(Nq2G(*TufUh{U&Q6b0y)6Rn0=MrT zN;KuwtF2vW+}8W*^!gFz@j%p7RZ;NQBo=9nNL1$y%z#hK@5iHv29D0{v12PVSG0d= z6w9S>MDBA%)H3{;S)JmC_34=z<-2sE1$+~ zuitdB*F41kg}%OscmZ-!?e!V_YIGphRDoL1FWrZdOq5ldS3+!^$GTY**qK^iIxR{r zsqIXauRRPMEN*a2c1ctYZ>wlz6R*VPPMmil)hc!rXqH`iKY^r+V=gb5+uPflo6~AH zpTF0btu{i(CcC^o+beBke1QgmJY#uEDkI2Gv0&chz?O`^IlA%|QY0U)1@L|+M_-?pk&lEBaogfP(F`nY_y>R*44XN$$yu&?jJYU zIM+owul2?S@$uy+bVxs`rZ8^PcgyzmxY)M&fj3j3!&(2WT045eYv{QHW}b=Vz#T_E z=<+nBgQCyMO99tVgjv>RX2>&QL*Xm_9yB%1~pjQXW{xGh0 z;3Xm9e|;Lyuf)Z(Zk~8-2s!P=B2LJ!d(G2mA8Ezlwu-tX@p(Q2BF+a$}Z9Mi{vVVKp>_?#vP2o{c8hWqk{NZLeA3OHE&I|(4@Vg zsOnOAL|k{H#Ms#3MMbHmY)JNVonw>uO~+kbhAIjHxBw%&x!0@f_PCA7mOctDW13Yc zQ6@KPJD^-y>8c`vZEcFN>99K#+B>kj_k|(rL{y+4_u7cC859e32<2HRd3_bP0N#Gt z`R`sUqdX;gL61u&oXj$VL%G?AHQd_Ti}Z%$`Yl9TJ9G2#lf>hVn=0!!DeUD>iJ^;a zYhH|6{W&W4)y7+epI~_2*XC1&SN8SFnB@%(R|=X@d+|huh5{4#6fx3Aw1j~gTTZXhL>#|HgO%`~G|CO8E7m!x9o<8O=<7$~Go(0Mg zS|@I6V2h&+<<9H~n5g?XL{(8l=aB)@_k3l|m2);(#k)QX*&YH8gQrOM=?=W))ty3s z0$IL1c@}Dh-QO!0>`g7z_%KfE)r0XaT4~->s@ck+#C4;#;r(^3LS^!WKiA<5;L9wu zyzx1A`Yj39>Dw5YJbOpX`N1dk!3bbgEoe@yw+i@QUv5HE($>KW%@UZvm793A;{GNS_M9V^%S^)6f_ zaXdMs+lTZQjqL$jE#FIpJbDTIW@Td|EQtM* zpu*Pq;I`dT^2d;37b*-W)iC`zJ;L>QQ*FrUVK3)2d4cSC7%28iy_WjIQf+&Vb9ixW zYr^Gi)arW2<2&EdLTL>-;0;6jV>rn)iA-#q#-aRlQ%+aY)u1tI0qZJ~z}X?bnp?AF z9Sf{t5l}gDzdF}_bu3lMY_Tmi<{nhqB5d;JCxMmvyxCbu5S}1tr`YOXJWbE1rx|y9 z0j$GJ;K_6+yXTcx)M(L&w2S1bM}|Pck`fu++2vUd_Ws3kbMj z_-rncPB&2ft$7Qoe{*NmuN$xeTXToQ^D5mo&-je7zrXuN>fSrw1nA5jlE;IM?H-m& z*7FKd{$n{GjJW_&ZE!!Zw*X$YOKZSa9S}qBk|%g=T&hn47syXh-@#h_JJB#8<{vg= zrI_A(Ru4MfyQ>tAOtf5aAuVQ#+;@N9V&5~t{EsBbGR^biQ9{Q8~Tp9{9`_oK;56H_}t8D zr;)|RaR?Y_EGSSl7rKH)ib7y8`-yB+Wu^Y%;UwIG#3{Bf$ppsFATMP8@1%JgASN*= zqX+u>ETDJBEMM7%L7{|%;kQ_8Q?#fMOOI6OL|UZfQ8mRBKNC`i4ydyh5^+VZ9)hnJ z&|d2-sr=CBM1_-3VkPc#`BJuUAoj!wXy%=SXv()w7hhpV-JEG;jVur2AGnG6wdg95 z%vK-yZUU>!04q={X~pwk$oVE2-G46&0>%8iXWp#{d;GL|e6jG&tNT3eS&aR*aYQ?X z=(=MlH7DlORMA?h{bK9j^qcU|{H5uVzOR^=*xVMY1Us6BNduj>voQ+(g?x5lT*1j$ zewUpye|Fn^@+FK-H%B|73B~!XG)CV9U|WOeYi z*B)PS>*UGW+LuAhvgz-KRhl;LVbMw7G9$5m)DxoZT-zSc=$I92aG zoNsi-Z^D4l~F+PgEA65yuiR7UVU@zvG?<% z;QY4q(v!gZ(I6B!t*vb&Tkmfn(>XqT$0e8oY=i1Fv5u5qKvH{jr&RFzt@ru*Qda)) z(pWSHa+UraAD(P?zJgNEr`ptnxbaYSQ4lZb^$67o@6!h~IB#gn`!W9!Y~QPH+2Ltj z+S+9k3STt}c%c7_ovEW!I>5nJxThmK2#=B>9TC^^xCFjZ6zPE=Mt z*452DPmY1oL3gVc_!I=ekOBB z?D`Rux=vEUj`DTsG#`&7DIl0|@+Ap*`lLQtPs{MH(?b4frpo{4jMV5J5q3_BAT6Budlde>4~|VWCP{Y z*7fSGSo>cl3Zs4Zp?iUje&CnIjF0{RhdF;QP3?P8t5rsA`p1)5kIU58Q!n@tNzu#g zo)WQS`R@McOe*!X0_Sx(ht{e;fAq$ow-=NbXS%i2Eu7@5#d>v&K1jfHg_E|;Y_S#h z1gfhiEtt3gcQI`2>F%|GHNxluaNXTadB+#qlR$!VEd;vuSV-{5%J-Fz4AyA;mqxo4 z2U(Jsxr-y360B_|6!c?`7&3tuNsPEdrReY98x|&o=4ZYPGGL=?gS*iDwotuQN#TNo z;i^M&G5@Llb2c*(vb;L7lkG60U$ZqLky>3J;(6v8zbpqc-KSK1XHo^hAEaB;`_029 zFlTNrE}i~izhEYjy%_~Xt_~BV*lG70K8}hE?ogVXQpxtx%WK$Ui6Et0;Vq5A$yUM8 zyQ^d8<-#9*Y~i~4$5B{EIi8O9zBAid`NK>ay)d3qx$j#YX6OStvN5HNF4=5DgSQ+)AYor%QGPqtdl@&4E?hxM+m*4rJt0q$egPr>L4_VX}f6u0ql#Bt6z z^SH~n{qNp_+_coN8Qr{xCsjrx4JrT7f!+#Du;}zw7xKf*SxF?M`eu@7SS(I4My6lM zIR0d1$AWgKvHG3R&+fBm@i;~jIyf5=PdVPMYi6y^tB|-><<=$bFN_4dM;^~aKCA(gt|rw# zQ;I<(!JYO=nQHs3BQGc>$4cCJSC5&^O@!?m$}@fGA72}rqcK%BS{*=BRo9i$IJ|=+n6A0r(4mk zZ1vcJy`OnOCLeY{R`$Lb@WGncj)%Uui1B zzT+&AFzkOXQ$FdQoUQB=f?Ku^SucY~6)IG68ys_fv|^$orp}9mO9I=juwgFUK=Pm z|7kRjBYX0i-2nE?uOE!q#_fizvLO+u(gGh%-(SDvwum4a3sMavuOMEwINeZh2AGy* zda0t#oRmoVTZpFJRN+c~HUmycnmGXhVv|lCV1_uK*Z&;8yN^8oOIQ)UwWo8>!>ki? zNuZp)en1+|*|)jy4N)7=^Qe~O)ivri%y}7tKC?BUu+-slY_+9as}nSyEI%2FW10l? zC><$#ASVc;Ns-Jv zTy{16g`PkeI~n+3w6pE>uTSrGcfvQC^Bx+eC`(ggg1$FZrp|~k-`|r3<3>Es%7WvD zQuotqYa4p5{+XnqF#Y21S3OeHP2jh2lFWu!p;JGlrja?^DiG0>D3B5H3<6(0@#f1u zD8V>X_rVX=F{}HMAp(C=&}9oF`@g(HD2a30m`HkEC2-4=Y#K8ra2OvZlFe;Y%t$-S*1A%(F`7}Tn+F>y|*f;g#a|iD~ z?@Gj$LH%+-(vAF&8p*G~I^`dC=A(-J7re;0Ub!8q*C8V~P}&Bau}L-@wWvn%cMAk5{v>DAA~gke2dSKyTA3nxSgiRKBUNgeAkL&J6FQyM?mMJ6d8sId%W~QT z^zKifw-0{_OfXa$ratWqkWgrIF`a$QMXNK zVpW-ugoo!dy>iqItE+3QD6CMo_}h8*tE=o(Q__w1EnjPl;pt7zYpB&GQBXhVX{hC3 z=l+Wbf{k7&IIP1B^U^?9*U9nrGL>_!DSHn3*V_81V=@==O^4&)jf69=^z886{@vY` zhLYynw+QO2{BHmX^i|I-64@h7s#Y)ZR1KC->LpMw!Jd#TaX4HyC&?fe9d%x7_cP@c z%uSG?{BwD9i;t(H<6tw{U@H}s^#a6{zh{b9ep3EHeqpXwM4?n9dN5Zaew5)WY{PN? zAv(%a`$r*QDG%m9dUT9aZZUFL1$l<{pT6JuJG{>3?n}X%qeo|f>T6?NI_;De;f>b?FLJt&Rq$nMJ98)0bC`T=2mAm z_iVlIB6@pejQ2ibh^U28=X~`QyvTYpr`gvXlG*NiBv~m_;ATs~^4Y%+cIEh+C*g|K z`|NtZT(aXxudWxCpT87l8Z{*1rMWeZ3c>&PT$tQ?&fu*g>A25OXSctZ!QiOFoM{H`yvMn3)|Y@+wA(ZT4mkRAN(KF zDZrlKTDU&Qk>WG4>9ZLMmF}iO1AF%ZQfOw>kBj&0LHdgA*b%tMG zotrEEyuW<03sq_N>T&iN&qO!{n!fjf@QtCNI#vByA8G|n87F|h3-Xd30BHzJ~j+moj}0* zV495EFxV<2Y8VTj$ZK7W7@vw+B%HY%4oPNPW5U=${c67Q>#0uFDglz~7a@3&I50TI zYtp9_(XFJn?CQEjVbbTJ4&^d?R3r0yp4tKH=@oiKHoNB0F8M)}^IpoM@~cV1<{19P%PbKF7^=$nIJ;av*>Y{&(mRc*(iKH#Hm;O@oYu zd2+nD5&!U6DQCRL`E0vu1X|0X+u3uh@de5vDk{>OE7A*DurGPjW8@_4w(5URMYSS( zD;Z?F`-3x9jM9>iPee}l`V_&FMZNB_)q75)<|$68Ss)Vtj0!Ma&(8W_c5ML@L%E&e zweq_^H#(U}H0w(Ro{|kd*x0(%S%zGn;dy-Ljkx|%QX7ZQJ~~ERs_J(?x^&+gj@T@o2`YVgC z98M*SIgM;ezo(};3oT!{)ao?)-#Mn`zDaB*)if>OPqI|2ZP;+p$QD3>X#P7NqX-LQ znh5?|}jKkGVJKzs;Xof=Mp zk5qr0D?99V_N8F*h|c#BAg5E);~v2K<2Ue79he4{CwC2!)1#I1G|GzZhyLpMyR(1h>jAJ<=8N{8B5)l z<KCANeq9{%9uWR!TH{voj zKA_4U+%{?-Ww<)X(p91*=8m9$?&?4%|IraSaPZ&55FGcc+FPB^kzyi&j#TI~3eJWe zifq*KyNb>6jrWJY>RhtQhsBR3Z!Y5vo(*2y0e^0hMqj}JGiDmcvCJV9KRx}3nU5g( zG1ly%K zhm|r^AV=19EmyzjEdR(H~z?^fKKqo?GGMS&b zoB#M+g;+Q_fN99b;*-QsxL_Iw_Xpf4FJQi{cwjYa-yn92d6nA$mZgI}x|E=MHI ztU=Fiq-i%g>i?u@bL?i{?YXvQ8w6CZh*j8z0O5=2pULAngd><0+IQ~dnxfVU3oRn1 z8>yV(^8pflTN8*st2IQoDlUzUzT}`6-dh-lu(cXV<@!vNKk^mfyH1klSj ziU5gJ6Jt7Dtbg+-VG<3@MzxA0{K^RS>qvs5i6BxoL{S7A8=*#*mp;tE4?W!+reo&?`vHTf7;@h9Eivz)pj)AM`oPa> zKa`e0BtSw8Ha{iE(Eb+6SfG>oQi4@j*d<=BRZVOnCncS41I^afA+ZQX56KPu&v@%_ zeTrMBKIDBG2fXIdTDZp(Ln~h4Gg{TW&HDSB$$b}*=4i0-sEsrKO9b^Huk9r-px=BN zgFXe4!Se*LcjnnHHuU;_d6}!)s=?5nQ!Jap-kNTXjC>D(X$J?y>??;H_l@C>v$zt^ z%Q4d0${0x|6qNh-OeWgdp*ej0UUDC{!Mg!`1RUzVm&P+L78=6k-t!Q>e6iWTUi0>- z`B9a=vrSn*!2Ok!Sco}UYT6OuX$tmz36+lzMO>`^CG1MCE!~Aj^X01JvUq!pv{?VZ z`jD>$pfgP)X<}_pyE{GmCg=3hxD4xQ-)^xI^;sH`uOHl2-HNfvG#3YbkK#&Bg>i5E~?@#PDOSn z*x!#a9b_>^a$iLIBk*d7OnUj(*YLpyFt0dqngkMYy%YslUak?vdk*H;pAJi(B{4fo zS}uuF%&p$})J6&j9OA2RDodoWhtIi%R2RYY+06QNd8&}*tp6oFJe6KM?)~xA`^R2nv*)8m;# zMzqiq;ooz#+6^`*n`A>3xsU5?bq+l9<*e0OOGG>Ulb93WaNQXE7NlPtImS63WUhI( z_g6(u@?)?AI1Ua>dFgVWC#L=E9l}m<=-;in^;|~S@#~RhjA)}*YjmbDByfo zb832i-d`N6dC^3l>oSteR{I-IDWgC7MVN>=21E)#%KwXOAXG=Et1@)yp(R6Xb2n#e z)(GIK5BF^>cC+v+w`aB^4T5u^3(8xn0_T2ZW6If5rir)0NP)qHe z*%Mya7L)|yEX`dyzhHOo7xogsq<#MXO9(Oi>$$5#{hQAba$4Nb(lQ2X7$n9G$& zv(J|I4Qg3rjN1>F1A-rg&wPIWi_4*vX3MIw3ZBt_c?5zrS8i5q_J0%6S3SmD{kZw% zo$nb)R}n73BBpj9>W_)uuKnt0oDbE9-8Ne#N;=9~B17W;#Yy?0+$_LToQe9;D2K); z(!&wN0^Ffoo9%!`70xAQTG>>h+M!C-o@d+;@fVmfY@JUF zgoUUxIa&=PRB>puUkk!dG3yFW>_Sd{kV18#5W(FtxIRY8iT<%gCFk-3pB)k9 z=I*c_QIcbxa#k1yYbf@ey~D^yQ05;L2Zs_3u{YdxA-Tx^9t_{x!F>~a*!nVd{kwOF zLOnIAMhEf|6h?=?Qz5oYOzV*p3&X&KVJxpiX-yE#W;P~_d*{7XIl}@Dk=^q zIou2bGtl3CRU7WlzxlsPbH_Zq*eX=9V`wWmWYwVGSrD!*FCknY`V&ohlDY*VH1}o| zrb{BDjXNSz8Qw{Q!ZAEQoRkU6=chAhg4yEYgL=*8N-gN}$u@zhyV5x4MoI*PsIUM< z%z`;+{%kOtZ14j}G)u$Mh&^PdW}YtL>V)FB9BJgxO0Mi^WRtobnkZ|&^6Gxr-HS9@ zUwq}?LYC~~b@Z6&G=#nx6W?|he(Ie(>&cPKM7yE1G62XrU1cBWYzW`!S1k`u6BnBRTVHp8JctUR? z_6!Ys&pRZ)?n6yXkLO+eNJs>^OxZp7o0h)HF}u17WU{=?e9*!|A|e^iQ|^waC+w`V zY;`_Bgr$)%ebmTCO9U9$*qemTs}n?XR{mHzui)AXepTad$)P>1u1vR&A8)Pqy70UI z8QcMdN>D%6eBdYCC9|H3kDy}LVPW-?^4+zwd%|K?@0*dAGPCngdNsP&*!!x#k;> zj3scTzfKjP>$LSpM2|U!2mfxMAvRKx35t%v_J~?)Ics7EvoGD~#R;vHYRLj=*0c7YqC`O@ZCYpW#=PED>H zeScRpX{Jp)DWTNx@AMj-g%)QFU`Ra@1#5JeDh$(B(T<=BLTuW(sYD;;PR)`bv-y9UXI$Xu6z3A$C_ViZ+fNzq?^_ zo8OHaNQW$%%Q1X)@9BO9o&?l@pcF5uoafSO6FDcI)b(WZAIc98sRDjXj_!M`Kfag+ zm7dfVyy4tZj5ylAOXCM+Nbyv@9XK-~Uq5bU;9)j00{5D&OX zQ9KxH*E2Rf05huBtnh4RbudnIQHFTAI_>`!*~k!K5L@8UfYczGwDDZ`mKs==FiR8$ zaMQgnb~;ExihDjePdN3_dIcbMXE^Ksssd7?j>U+>QVdMyZXyRR=>{TBz0Jo+)J{|+ zKG)Uh#&pO5XbL)8f|7o#}V2jONeUFe|p7nMyOuPXF^8oGPPjB`eZL@?2oZG9}aaeMz*z|||ZwGnx$I`>~9`Twxj3=$1+PGqawZ!1=1M{o4 z^%$AyBh7|Pmy!Oyblb= zE#u>!Ijl(5HhpdPE2zLzrUlT!MDKUi%5o>S4UPQ2A4Cnv$?q+Y^16TKp)e3+WnFR2 ze4%3SSf@3!ySj$mL{1j;mAA}Pcx6t)Haw{V@9zRKxYoW?In+?`KLyq$3C?tD!SZWC zCJ(|NhV+?YsW~aK*ymde3MuV7@d^<4bpnw+^dq4lO04XzkIX;Yv%vm#&ZLl zyiEnL02lB3`weH#&nk!rd;g%}ZukQbf9Z>FV54v5RLX~9h3rcjV zN8_m${#F~Y@D(f0H=S5!t5P{6*8}aYC&6%gb6iY_Orq z-aQopOq|j)=;wZS-?4yxFl`H2U%|4C64;e2hUK)iO?4_qv&WRA^LM9~N^oRvG~*N% zn=|Ksh3|71AJa0y6pGjkn$hGXhq8^XPs6`ef7ihp`gM7<#-8C(heyoz z_PE;wg|oQkhhXW90PkPkXQsGL_w#_Khdaoi_^cvexZTfCqY55`A{anbkei{jxCjgX*SK#69iCL$c=K7pnfIw;#+Cg` zvo)D)yT6kLq6<`J2E&>Pc^n*oC2-Ftk-lKKU3ia8o z-~gNTH0;3S&;-Mbq3rT1@tfxDkup-2umUMx*anfFK8%RIKwV-bt_6@jNpm=Z(Ual^ zGH5}wm`f2*W9+g}#zje4O?@yMTOj<^jyRxv*!zOuTLLglLG;i~jmq6l8q4Ph-U;qZ zpFH#U<}SU6xkf1yFK84-z>&O75y#HtD&695^k<4J1c8PrbuY!-(qQYtf#nSX-Qdc7 zkfM{#@Haef+gA6sW-3+;)-3xl+mT1^o|LYOA48$g&&*ookDih=H#fTi|Hpv)Tj>bs z&P>JZNnws5ZHUBwxEYj5EGJeEPY7YHQb;rP)(G;z)l&7MW>e$pKk6VO)X_`f^K#Je zw&>-hb9+$nmP~LA@VTmZ8wm}U_Dtit1K$IO;t<11lo7?R1m>~*cj+oT{#=toFCp@0 zu0(zihM-fRS>r!1=|A~Qyty!i3p6OLhL?8r8ZZA=ek#w;nysAvzDQHvqwki=xHNvP zP#ldfEf!CjhTl-V?bxK1TWFbTu)VFwQ+a`1Cz6_axWPWPhzeavVWQy$&<#X6^K$;h zhy8h%GJ4I_4K;?0(JEMdi)SY*<^FI$}HuQEC;^fLHNQT_3= zgimbw?1$ITd>_UQ)@vEoR6uieb&TK&k*C*d)g5)uQ_cIZdlde$T@-UGq4HZ0@|_#> z)#gx775C4oNMGngK&-Ek{+B=(N~0Dh%6r{0Y58sBR8hZm4XozoL+MIoa)YSg}!B4NFzvAlV*5m*5?>jTIL~uNIXDUW2 z;)wozB|>AcW4}np_q2M62#75l7r*Jry5+Xqw64cLJ%baZe0ZqTgP%9J+gopc9}NAG z?AW^_=N|OBZP!+#DlQ*xLy=BFX1Urg%s&n7vXE>SThe@^nB zt>Ann^ zotsA61=}09sRG&0DEG1v5p+gNpKE+DH66+z(-!t1=+r#VYX7S%lcn$A&h#z7?m``- zD+FCG(aN@`=%5KzcE7&Plxrze-sTq+6ciP?rLZH#3H<*vP|GQ+1QngB0uK15-?qsCv2-~}Q>zf<@NH)^V)hSGev~nh0V{XR8gg_q42$j3Z1QcG=s*&7jR0nj)=K| zNf~CFw=~6Xy4PCFfcW0_Yh3f>OS7zmGk2po@g8a{T;;dg<(0k7ovpl@Qc{ zs{vlgc1iIMi|rftwXVL&tOzQ;>?D)i0~J66I1Z8Z{XvU;bsGL8Fo%*u<0w}^Lt6D& z6U)v*MrdWC&(6)IQ&2e0*;@!`_eP;m30$LvrDOVm7-z-QQowS#{N67EcA3y`>Vx`l zu8ZZ|nqdF?hwRs(&EWw5&WtP9j^+9(iQ=eT|G{vT+5!>&~)fTj3 zh9muF*7j}n?7C=xJ}*?6aJz(#Gs!rB#g^lno#d28@Z4sJaWvv#R%|nY&Gd4KX!If zyI-Lq-4YN`TWNP>%B~EMQdFcW{qX41$&K-`1;y&O8>2rebWDB7G^>WIAlu~z-x}wT zhm_>xD+@wZqL0&bCJ~wW7Abh4+;Nf98SU`v`64=BXWFGW{I9xb(2t+aGj8hP17$fZ#e(A(=G|*b>{@?_=Q6zj*$}?%%m# zr{kgd-8tY!Jyo49I$;9ohrjC$G>S0qmmd6!6&RR3m)h2x@2z=lwc7>n+h}NM(IU8a z5^FR<2Ub)_l$F(s6-lDYWF`v`7ulw%ZhPJQOnP5G*2(eO%AoRD4EOpC3xU%O=mxLx zQBZbz(3SPQJj3<@&&DNKDxKlszzBQhzUa|BSXKON)8ke~!=@Nb%et)pAxGcZ21k_zXr%!f-yo4jvs2v1_cE^{*8PE-YY;!v5}5A zJdPsnm^nS)rmE7TNybZt3o^(i>@No#ou0E1)-~G0$yJxy$x`n3dom|4wDM7#7MH%I zoTw@!hwXFbs~gqkpRR}NYHd%2%p(H>78=%JF&PdHWji%%SGNrcb!XDno}OU5ukP-? zZPMRh|MkE9s3Kjen^G!CPF7iH$?2I#cG}k-ODAlo7X=<|G7?#)sCJiY3C$XTjqbgy zR%&psL>7Guy{~eVVi6Vqb|53)80z7m<9}y0O@ELzq2-Ol<2W7*)Z$J>`4v`mPN!B< z9l;+P-l5<`d#!xXy$kib>OQjH8u#_ft>|s{qYggdKR#K@QQVmlnS38hky$$RQhuo= ziQ$Xt>n1Lu|ghMSDPi@}r@UUq6$dJgf~QWM>zzS(UQrC2%xqCd50Usfz!n=Ts3A zqDG5jUl6`dIWXOu-C`9_W~I{C_xXfFNfi@p{(6$BbLfrT8<7%a>5mtarP@kZ97|0c zvU<#=0-!F9ow2ccHmFeU490`;x^U{ra{p5>gi)c)b}47{S3#gavCqoZ2SZL5h<}Ld za5(JnJU-w2b>@Ax8iP+RB=-$~vm*C3;vsNX>-JT9#Gq0RpCiG10Vp8G_*x0tIbtra z1E14*s?Ugc^=g)7@EyHiDwM^c2&Kk;gtN)cwll2&^ayN_f7g21n-eJ+ki+17rt2n6 zChHsbp~c0w3JSJh1Y8x6dk=ypUw%UV)XV2;HJY^ulEs0216l+=)4iHnn^0&Bc*k-h zV+vn#VQYFL{Xh1;GboDfeRB{I1p$!(lq@JwK#^+j< zm+#s1xX4%=8{gsHyV&SR5?-oQ+e4#O#2!ty`tzzZ#B=&iq%U?5$MTb|I*Vm|Rwxw3 zD8hpLyZRGJD%qWbXq@22^2$Bg5p^A%i8n(4K^C(y*W?cd<4Hlue;D9Ews-y67suf| z4u>0vi_iYyxOhuUrvq7Ro7_ATAm=}bN`Rqszn?P3m>w9V_`O%g=W=xV$r3I!JU@QJzT!JME zbvD$Ur=aF6#%j&sV{mv}hCIq_eKge7bzrV3A{fs((c>&;t&c|QOLjbM+;}NbxoZ94 z21oge%~54ejyWuxgJ{%R**j)6hmJDe)7kCdII!;WjRESk?bSxk1Hi6p=WE0V8vmsIk#b;FFR z6VsDlwnq${9vG=RUBYyDP(*@v9JGr;^i zP!Ut2a9p`l-p8ig$fExB+hZ-^3Y2|xXrF{I9HdYBAU_uORHeyJw?-?U ztZ-mWsqdZ+0Omas`=a!~bF!LA{?na)#kn@ZB#$Q;mXnN2ouo$%xT;a0wMVc=kpjO1`j+uPE?pe zkzXpUrYiEqzN*2}0Ym9ew(k}jSCr2QzrAp}jByOl##%Lkf83z#qjhXeHD4q0GC_hp z@Z@N7iEKoxxZ;YLQnipOv@BXkaOA_q5w#f}qt*IEtPdB?t(CG*o6$@PHnwvblUMb5 z3+=K-&NwzUVRnm3lp6+G(l@ciL99*<$LWbyo>fb~8OkMAD4KmwDJOt+Ngo1e1goI9 z6lC<{qYU>T?AHwq~L1Q?p&?FZtay3@h5TH2l={q=Q^N z{4@5QBcP2I$)H%JoN|bwm;Y=IhYPtbT3Yq6maqPZZOjLNs-;SA45?k^TR8JHSAf)a z%rreXxbVBBBMb_|vfIbGx@d)8!?`IJyWA{>?n!u-qGMBaF@=g{31+fLS?TGNtEMr3 zCm!3MR;j)>g))+BOyzt+JARAy$4A1_l%cOOBL%+Jr;k9}oe;qHOUcVe=-0ngUc~~^ zm{M=E6z!u*UwMy8<92jkpZCGh2k0c92g=0M`1k|Wh)LdBH6|+i<{kwLML#yZdGU!l zkx(5mh8Ls-=I`Iz04i@-xqdFPwl`2)GN5%7TB61|Z(-2egMiT zBgD6=D3~;=Y6``FQ~7@RV=*N)32$ev$c?e_z|6}%bglxeQk^ibN=o*R_77%Sg{o2( zBVl&z5Z73v7QPp*yYKxmqjF#B=~YHItc}b`HHQ{I<;8EEMcxV!9>|d6e+U}vAsb2A z0yf(5JXR6A(hEOq{oN(sFfpsq2s&S~%5a(Cmm}e$VQ()DYUbr0UEH;vS^oaDJ-`P? zEh3(035ntLFY>Bxc6QeNWOu0}y0fWC!eSor?J@A}1sqmrhUp{>MX-J+bZCJfsRGXJ z`;9yNQ)l#1VBPQw6TeALPW1`sf5ZD};pZ+n&ek~yd;B3B=8^k;2Lm9b(GZzB;xm*3@YWt(AmQT-moLtJ~p}(Q|!L!4YKK^T7-X zHj3WgU$;2nF&$k4NFtq2nqmf+{jDgNrLSHh=qV~g!7k@R)1MOLLWztNC7x`GwrZO*TuM{aJLbZPDD zKHp{xElN2XnEl-P_=US9M);Ua{q-7Ca}0Cu3C-z1|mz@ucY^?9=-$i*z`fIh~RAq9Zf zoC3U>&D9!*oDzEm0+izkrzRcpxL)4<3J>b}P$dfzSWoO-E^sQ%#6~L_C>=`eZ;exq zc#5qC#sAIYI#Ru!UCC=*Ar$a&o{?EwGDwzy+HQEYm0;TZO$QQw-e0-Y9n^3Y(FiW` zPou%iN%8>CEQe@m4Urlw+~a28Z)iyOXT^}P&hyCjCI_hxY;W&>D!}sOVDRWd%E-Z_^|JZ6i%1Kchgk8{IPkJL*6_L04e`9dI5p+N~S(D z{Yp+`TO`At5@FHjLtWqy01I*bRW})aZni`CwM2gq;G3z1}1iec%G>|ela=MtW0Gn#aw_u<;iKZV4N!C zm0?3LnMUDqco)!O94|+&9)YaqB^ruJ%GTvL4z0Rw>OMH)uJ*QFoBB1In83+-5Z_FMf-8RQZEwt zPnzlwkp|tpp}alutqW4k{;{MZeTS<)4Of@xiphMMLq&83)UNxposxE+^c~voUe*kr zm~`FKWA1JXF!pSrc_-p&Q^ukvP^$}SsoiM~E~m$q_4Iq|;P#1f!Wzi_0ixL-)X|meJEE&wT6~R* zkN3GMokQapy5i_G=0eljl0E65jv(%~3}D>8+?QEDr30XWWSe5sgx$3nkq%qMP-^r% zkkimuJr(s$FuKgsLR6@p2CaPmhIo2q!=;SkA;|s0cmiR%|0l4oo9c|6e2o01M%5MC zxU603aw=-PfczqJ7|T9+-Y}iiTAwCuI>c;s_Qd5$Ia{Vkv5RfN?W~(+(u7nsh4SR^ zSy6Zg6clHy>Jj0GCVorSjq^%^&7$AvFeg%0LY)=t$n8ZYd65{z000H+; z%8M7uZaYx2Xoe8IbJztk6gemd8Hzj6#;p~LZ{a&F7&N{T{{)lU1a5nNEKO$J^Ezn2 zE5YNJtn>5xtU+@nCyZRaHNBNY?0 z_4Zk1f(G^tF7b5T8e*b(5;ns-u(Q{jxFG#uIz&N+gTApqZ&IvE>A|LGe@>*sX~`%R z9`Fo>-0WHdflVRf;rrCo81ZO9*!2qJ5Qb0NiHdNLxN>r}Ha0jO@{JcoS=UHW2%$&wrI_Jx&*z7|tBMvVAQq;$LIV zPeED9u|3-WGeU+?PylL2^Mi(1_IWR8&q!=M=45R*;c0b z^)*c<)IBpcE)pUG_Y<0H*3(7DdAP++4<8&_lEIj-pNK~h>~B&cSlP~5*>q=}9@#N` z&XBA8_9)Kn$i)SDda~F_dct@&S$K!t>X%wk6;dR2I#m)O8V1li0~wWSt$gDm7q6b0 zF6v^6;`|ZBqIsPfzdo47?`}EunPr$+ZPswkdGp0FeEW*S(D1xp$h|F+GK#qc1E|r$ zAPx22x^go8P%LJsi&C>n-aUeseFc>MYlE4#mWxS3uxt#;-B4<&bUhI9m)-cq_$*l{ z9*y<0pHK%TBq<0~xDn%fmJ`i~<|P*GQwQxI@9Un_!HGsP2a-iO?j_EloaeAx{DN>t z`Z`og8|oT*LeT3ejk-m&=xPdz=ELUauLaeaFWY~D47pl1NF8Rf1y(WxzK<;i4#}bg z7I7VwkjpE%mQn9;GX988_avARF-^-Kj34B^kvNXhYG$R%BYgaLUi8U1lj}!`s86XN zR^;f~m@rarX!U1!Y~!%lj{7l~-#jbK^Cx4{xTw{&L_ywG5x|m<&Ws_+B3Q{Fc|5Ds z+WdY39Uo^~zp&nQQ1aX5U&v5Cud{j3D&DUOBvo%OPKre{!>p4hJ3qf;k#v6Bod|0; z9PLRoBEIB+`VSWB>*%~7H?(FiV@Sd#s9?QYV+;UJP~x572v80rh4Kfp&EGSu8H{t zvMWi5qHAlKRfAi~ySp`%0!w+@05B~MKqz-MI+!I-sBrKLMhY-mu&;=QcauA{9&RBB z^HO&N{xZrTyg+Y(_5fZBPr&hae(~O{gkPt(dZ=-uYs2}@J)pY9Z z09-=M<4AhR7bD5i+2#Q1nNcNAZbg%3)Oek0RIyf*QaB+J3py14$p*eY6>ooC8F8xS zFp42Pw@vpqWL*?6Md!b)wgxZ!+AM)*_~BKKeFI>=ca&0v`x1y#H}qMmuDT3_iY*%bmDC4J^cFmGpzc}0Dx&zgC-P0vc{M~eE zl*wA(Y6kSKqn0puB&o!pxT_nXnEZSo@3fU5=dEUeRm)L)gpk`0y(4noW%t4Dxk*Vz z4zlaYYKp#PF1BpeAk7v0-EpmgKLTcISmT<2m96A0IMTGN{)LU*+{sC!?7J$$yeJo!Y>*=oAfl3Y>$m2nft=tQ|RcDin%zOAA8SOn%424)4f zQX|QYs&t2q4pvBXj5YL4|5svOynvs>`7n2{U2`%B z)18036^Qg55v1MwN?SUq{FXr5bXji@-A#rcw-VUCkeyv@zBrT$4*b+>AR#PF@oQo{ zP(6;~S11+h^R2zT1!fPNP9_>nF1&y!7-{{*8O7IwtzP-OTavOmW$(8_$XYbFX7-3Q z^JaA=>O2P`9wj8DV7YdGRj(`+2hUyKs~nX{q_@8P=o2a-t8TLPwg5BRI$Ixm(Td9B zav<8XVBi2M8^22&pJJz{jWo|U##=ltSINZd=$4pxfG54H_#>zWw1d11S{-kGqqm~o8QOo%*{PGSZ`nQr*#LU_wbiG_8LK+Oub3Atuf#! zry^p`1!!UC%>d)5*IfaG7!NX<*#B0#fXLK0cux?3b_4m{_Dl0)yG&&1H=lm(U%$ez zU4!SCXA6fl^Fl z9?FY@_*{WXzF2Kgki+WTk(mLl{#aqdcR$P78L++r*+K$nWj{6Oxrr7A2)Bogd0GSG zrLeS#)xiWKmrLE#OTB8Ehi0|4lMczXlfXgxaM_cX5E#gCN~j#B_{ikP?IK^L97eT( zLWYnK-NwO;1>XFZ;cj`^X){4FB+k?j>7suhySr!G-toI2Y$+WC0zP@O&|`q`mtVQ! zu*>oar$bZ-4%M)Hn__XeLwU(Vd5o#X5_1Vr5 zyEgQl)A|+w{8mWb87l{TR03}*fc}Aa@2@F|wWcd{x7_-V6&e{+{IvB7a4m%NV;)m1 ztp3`)cR(#1fO+Wz5;h_?v9XKD(ui4Ho;kecerp$tgX8fbhY2YgOlE70bAWOFA(d3r z`x*tkvaZ7soAt>thr9Dnpb%AXx&ORfNeOi9ING$8@N4p~{ha3FOta_gre$12wFO=7P{_{J|T(SaE&rY76#pw7S(t4qO0BHmjV_R6*4VlmOx-& zQY8(L4PGcDzx2MAP}m+9sgpD)HIjjgd~3hF{b_ICP+Qy1CnT1g$PRK2Z5fWij%QSU zH(>=xaz2Nx9SuH{ZULUx_FLLPRcFiU+y(ytWSt&kva+NdrRqVLNd7De$1KOkHgwzS zxi0lEoPj{%g|kc0O2cj2fa`1ZGJqU?49`>~?Rc$oN-EDQmwv64|+^Z_s7{Eny;-rA~X6i?QO9wBf#3 z_H+BT2;bI9my6Hkz>hWXhOuCHaD#MFs*<;CMGT1|2joB2fV%!Ybi{{S*m}^={tFKP z?*cS(-!cY!U`6i5PpaPh%xnEj*Wvid(N!$NwRCd^Jpn4UtK*$*4_PoMJ(Qgnv-3Lj z)933d=(SE|)!w8C08qbHboWmEgY3vihq-G6eszv4ns3)uwp{|{Uk{HOhM<02hXFKCwE_WMBU@mz}XK9Lpk;_ z$N)`MIkAoLb8oZWo-}dBWqO!npekmuS&+I{)Qx}AERge!ckj}HI!~h0)->#33VCIl zSNeuHlvq*OiW96f=*Q1L27KuS346^0768&Uo|>v^iDXhr7)-^YPDy<&7ZOlXQo-gh z#u?%(j3hy+RaDs>IPOxMZ&B|Zun_o|S@%+M9j?zs@Ouale442h^3Q`FnYK6P^8`ZY zHpwl=w<`#KC)f^APPQ@V4&v1Y%+-z@I#`7ZT{M@M0!$_~dqjrQw^bl)n@d zd8|Yc_TnRTFY!TtsDrff{BpNZ+`Cjj?0$Go#K6~>V~|`-)d6G}JCHc+AT@=*HBq_{ zzDMV{eA^7W%$hWJyY=L3?qs2m+LK*UzoR%}*zUJj6BF`ZNx*IEw0mxA8U zYkv^zd~PTgHm=qEc~UAdDMJ{yY7&H+^-?-)88}h zk=EF~rXrmh*09jz@esiFZ_gLI{*XpQ#OkI!8o!stcAKW0HjX#c|2=32bQZ0aU9Y~T zt$ohUIvBG#gre0JWd(7E1n0xID^R#M{D!67~%I%U#0TW!jV z`YWF+iV&T$hRMetD_-i{rH0(X{qvlpzf@45&;7?+B zQWpWf9jHu#imO`Yi#TSDJU-(ewr!-20f=eJ`f8V9+FkP(S z1&|>)>J_o~>-BFei)BZwRPb0SDHPt5@Gf~E7!4+A2}d>>V7i z8q`+1;(!K2Xy{3ne0-V5*`a^{z{vgV9~k%waH%2@X4}sHW-n5DhN4->TR+Zqob0di zSI2P&p=dkz!Wiz7l7^`G5yX04LUo|#3km$yeP4-NPXM$_S{3DVTx$b3-(B_qXQJ8dXWvrONvb?N}WG#XVv1>B^-ExAb2!C7i-=O(U4YkNa za&jxCsSMom`Yh>8YXhne7vrV(Ob>#{akg^Rl!3@Mo0N zsvKju6V7O5WbP>@CPEWrMYmbraIdz_w;%*tl!1&SU7T>@#FdB(jRrs(1WN99p8R8(5J?KAh=5Go<&;ij>PiMMb#Yg#eJG48*)q=2V5ZA^>$ zYjJn!_zetG{X2qaKWFgwGYc^EtWg#cg=F5P{^M;OMFFO6X_ zMyvlUGwGTV2^pCzZ+lr;89>JZ#`1*3i*yVm!=Dlot{*dC5)uS5`fiW7BhKqYIVX_Da;yCveEO)5X9cDwHVt8nD5rH=O+kSAI{gu464QSBUhl> z9V+1H5?z+1$lfFW;1uc=5~AQ@fRX=L>pLI?1mr`IWl%iRzxeq z)@Zm71xV-x0ZRPc7XHA7a|cHRNfTgSs)MQ@SP|8~zGBT6WzDyp!;q6=&9~OpjwE^f zk|qgrJBT7~Fn`9MfR;0Bbhuyn*>X$_Vfaab9xbOqmD*=s#b?WD&n2HNTTTSFRl7PS z5sHR%l;772L) zSazTma4he?GX2qg27(z=ZeFYH^J_piGBlpo+C@bIB$dY7n#J~+ya2d+Fw}gu-uwPj z)2>+d89Yg5{Mo`kih~fETh(r@#W}rkbllcG#K%zlV2XCz5c=pK04Pe4Y>1%P2Jqv4 zO+ci4E#&&FU-MH;%zoXK5TLqf#c}Ff9*HD(L_5OA+S(Y;$F@mR+9rG1X*rR*&z>!7 z7VauV*_n8*+#$I8Knlb|0d4N54pbs4Azh$!L&&n!2HFP_#>GBnB4&O_YtQ^NM>VLe zTGTtBt=h?wFwS|s?Lum?O;?HmT)0Y=XUjKkzywn$;&gQEvpo1YffM#@*`U@&;=<+m zvJ5@AyNy2B1e_*qN-@HZz3To=DtVRCZ?*^ ze;|UL)WLedN}h1DZvcmq`&a$P`zobxV2KYNMupuWi~}0(HL%6D$p*1!%ljUbB5btw zr#!sYB;l0>R?kd?&BFq^0CmWF6O2aOH=qqBM?x59*70zui-~p*(Ec=T@^e}b$v#`g zysGsO4ufDgz+OxAD(;x@DyC}oU z%Ug6Q7fCMF;>0?wE#Xo{QIRkXa1EwV477W=q_nj5baaGqpvgF^ z7A@`G&O+sdFGZa5=40BuDo1`dTB&8=JB#4*b1FtYf3^(r&&HkY;fO>5Ac;T`ceH+= zFb-sCX!k&XHXz8)DdO@349E`5?@+28FDE;b%>}xPbEZo+X`^3EUI3Y(k}YC6&IN{5 z`eumpbq7@Z5y7mr&!5@tR<#e_u3O~u$fx+KV#8C^<0}0tS_d$BXxZXq- z<@!fb%V4QYrk7fl{|u%Wkoy_Y3+VzYiimDVm;F*;Ko_8lg(KF6Rk9RlIjK3``5Q;k z?X?6+n$#Nmo0v1w?g2JMBZ8mP*@-0l1m!$1QW(&sdi?+@YGY$l>waRl)UgE8W;`+x zzP`ROF&h5(l+6P527fdxA)?=xmRcJ2c9$rImpfa-ZR$KJV5$iTB6Sq!ayhF0=5YCr zcwTk_tb1(0_W;PJ%vaAn3Hdp*zQw%L0WUV1Aze(6%qK6w%ahFQ-!HE;o-ISAJHz=C zF|kJNOcWlJ1Cyf!Mzbo03*MquAmF&Hws8KMn>A6uCPU^kH}G5z-& z7TP@nB#EfIqyPzcAQ*tJ5Y2DD3;=zh)FQP2`?w$95y{XC9)Ne2qbJGD;vC8pgz2Wwl(CY!S~w0kIL zq2kvpvHbSo)FR^ji2D$lM}I1)knOG2v0{KL9xgWPZ5Dt)(xv|Z#vzwN#;qYk0|Te3 z3)ikeL^=P^lOeNPOTT_;*SaJ0^z^`Nu5mpW$Wko4M|cPF9}yP>Sr`@;2Bx`5*Qfse zer1b@hjeswtgQJQ#y zXlwrFfB*Kz=1kp8r9HYDv1i&5m7|fbjZ4aQ`{vC%XAlSt*1sbI+K=0c|2nV#kGzX! z)gb`^(Q`@h#~3NF`Yk0YQLMo0j1mY4G2`9#->if{&p2=gICb;H?ss7R^Fhk(B@DF` z>4(_A@6G9JS}aJ1P0@|lj0FFD;Kdn*t>jG`PVqZ-Uy1zyg)la?kVSog{qq4v$6x>F zncZ&_nrc7~{>^RDw@QAykiS3pzxe~U3vc1!4Gj%#{LBH~{|1|G1&#G&3H-nJujyka z0$0H=i2L^de~;suF7YF)b5yIq!>;@r8mO`Q|F13hfo@SxGv~)mZd)Ryz(t&x7|JQ~7>#~VSiod7WM$=$zTkmdf-xGGP0JIs_Lj9U?fVY~S{;Hk} zXha9ByWc;0#`Tj!AWZkzu0ihL>C!@I$P|->i63B}^MeKjbRiV{oED?s#){1bzXOAv zBIcv3tGlQt=(Nt~e*CQ(T$@4Zaxgu?Rxd*Ed+;qmq**WG?%usiJN#(1Cs7c@WF@on z^PF#fX8%v$e20Zg#%11jN{U1x$16N9P9MxoPE9Q}{rq#nIy@lY{@3OO1yrB^ja@G& zs7CdD>DDLxEjINIr!^i6DfmERw8ynkh!S6mP!tO8itpMdeU1xSCP4{8I?js$o zV$<$gk262oo!+2K*zDc#h#ctc`)s&0;Ac8k2&darAf?N~u1WW^=~wfC%w<^Eogy|F z&_5*H&8D)V;v*S1^8o91uWGHy)^yE8eZ3b67|_Z!N)i%3+VBC!SZrNdui5XAUrIMb z{njuUXD=U&iGz!&^X(N-lfl!zn%~+|Bp)d>5P6t@LZRG0ost}vGZ}oZsi|4LHdW(x z1O`6PqCFiz8=eYI_D=3PI9a&(eaO3iPxjAzqmcyckH5G7zx)5M1LXgB67=nYRye;m zu#Ww28MD8S0*5{5fO-x763}i6`GEDnU1+k%a5qLEH?f%n>p-v0`h!bNKx|OVz^%5% zWYUBC=i@|0avO?DLfEdd50SV2K1sdE!$2scrLE4$2q#qC=)nA%>4DxGoe;`MgWx6` zyhsRPGeQ!kxv`X}QAom0RumNDiDWpiS330pz3zT*my+RGkSNS~<0dsD<5E1rpU#qQ zHhHR$d8UpmQpa_wB8Fd)N&^0T3HX11zkY^p0O}ihR0kV}m4ObBgo58T)#;KkJivFz3Oe$Z(_8$JmkA}@C` z+Q`9kEMWU`WO#;gT0y3{tgXlU@W*MwpQA}WXF)u%`Z@&F@zrLCFB-zJw*ny-NB0tW zE^A3VMH3C1ezI(F_u!s8;qT`$_JA%}zqi>fQWO+otv;P&mvUNQjvrzo;o#W|d8XtR zzCw#Qa8?_?n>+Z=ML6zk<|CZq2ejXpUuq);x4ieQQ9sKVHR#-&eyY*B zwP-Q%1Zpa~B1kS91AUN``JVXCmOu~2zqU(OaQ*qDL--#n-fO4ZS7;Qu_xA_0iUG7( zG$Tx(qZ+JdSdfzLWUFxqWUkXv~eR1=Xqx1MSv`N0y}ylJyryz;&!=c@E_ zy4QVwrT?;jH|XOQyRfY1`SIMw2CJRbTy5?NiQGO^K%!{(t-7%NU#IoTHs6ruV63vY zvEe(7O__~Rc$si&u(oy4B^69YeD9u%Fz0Z)S8Ob4;+K~vKn|7vucJiORCICb*VzrN zt*?61ArBXHJDgcvyQPf{c{4^0&-@Ovzh~c_=*3UhM!^qHnwseO43t9GPJb5l zvy5~UZmN5_l;$io*iIbmH;WZX^-tyNls_wpUB7sm54n5x)Y<7J*?#HStvw$jA*!D` z7zx2X_QQg`<2`&^e9b>f(Mzo!>_Su~XC`@5O_F5_g6vb@zSYv;2T}7cld{xlEIs}E zb_dAr%3`dKR}M}(v|NzaR12S@(MjD~Voo#U{O;`N?b7a5H*Qq2-eD_=W4ZM-V@SxO zbV!805pvmzfI&{AN_sjmS)luF{QQGU(2z_c)-4$|vpc!KgQhMoMhwi&5B9_+JC=G( zH*HF?pT&9MYpe|3I{MYItt za6`YtqBt#iI)-)rr09Wvn$+dpD-|5kbD3M+t3QlZb)*8X9u@YKyh6egM+r4|USM?b z+t>8xoXJ0?<`Fr|UaFMJ?-j9f7Bj(c)kBQWZ000j-Lq-(=))_|(A-QEFk?-+?!~Keg{->5{vHK~$phIQ(xSQGg2Hy-6exL-# zWtd3JwNI$_?2BDv$^$kV`wt76z15m_2v>GGkEA&5`( z7~P#r^F(hI3YsBT*0FMn%}!E^&E)ghttwrN1E(&;%3(kBkVU;e*v`j_o^y!&=R@+a zW(?Ieeve;+%l%8u+J{4u5xcjWG1_*y$Bk=`NcGrJjmmB{#fKW28&itRWJ1!5ayek zPvdD#=6>l|upqurs^e_Q;Og3X_`*?8-Em=eX`dd{bCqkM3wiJ(eVo}PO3GDBmQ`b&RUK?A-0jku{mQ8$(u?j;$~#icNv=5c zDo@uG_3~_g<_zD8ts+UlGIu!@+Z!a%(9$a{`F>X_o8QC(KCC`sh`)KNp@9y)*T1k1 z$1PICwCiI3FQX#^zrgpQ@;e0Fxg#aF?nKTiCrO5v8i}T3jv$LfUbwIQTGi~dJvA*f z_Vb(kniVq2l$wk1!|7Ndyn=!m?`aHVZJO4ojV~HumgF5a-QQBO+@t zh0<}f=7EgI(?A29z3Zwk-4{o@nmDC0B@Jv3zCR*>q*%Q`$# z1=yuiPd7RNRahFoh2W)r>pW9z<*8v+Yo>pix+Zlw;LjbRi_BwDRhRWFrM&v-obKbqN9BCg!yBQ z#4 zUUqRSVkDH5yfImRx$((9c;V?r@21rv?XD%pGGk#;tYN`6yVnJcsa;xQtVEl(=yI zS}f+s(huQZ5dJaXu?`RA$eNN$wxdRL7&kM88Zu1zC)kj?H(IW=k2ERN+;`vY_97}g zqc~cDFHdg-=#WN|CVosV71_?~uFcB-m{h{$GU?u%My9hF0$Ut#?XiBOLj)|$I-5s+iEKjKu0|BAl}f0?YJJ%i|g6{0v@J1A$)&0){q+ zKk;o#e*9F0q$YZlkZ6x;z~mOju#F5@g!Wuc+0q8$iP+A?exURhk)Rv>A`Yj?9JPr=!G>A zw_No(D#21m1@qpDl$!O-!;n_)BVqlLy%ZOI=^qr7lp-Fd57|Ws7}!N9>kjbrw|RwilP{3VWvn{QK|lPK=T=yAmlQ2X zg=@LC`dbhLmJZaTD^>cR+^)_kNZ0s}db&NG>@Tv=wIgb4EA7wr z^K?iC3z9!Emt%c<8gJreGXHw;7AZk+-K$jlX_vgA+I}g5jl0%Fto#(jSp`MEXG7Il zh`^4+e!H2mLft+4am%jzp-frS2x?2H%a_85p@ZUlD!(kqBz7E%pvZ-LaWP(ur0^`R z?w3bbntz;*<{)Vzf$-L=^XjQfv-~4r%h$*0ElI82`_$?)?q-V(ZuzG10pan$J`TX4W<9cOu&vLnBFA|S23!*R2W?GDl93_mD zR)zfS(1_lBSv!?IJk2n9jO^#$XxDgjgKAy4b+VORsrg1YZhYCYOL)&ji4^5fl2Jy@ zan)gnROykhcIlK-HRD4~yHR%b&Q%CPixAy8QBz%g`}Xah&V+B@t~qZ__tzyQB?TH^ z2BgbjIOsWq2 z*S$5oE`IsDQ4TY53rYU_&bx0Bpk-QBt{y4b#?Og|`W!J_1X4`9SHEo6gHUs%M?%b@ zy;dk;;hF8r{s?D+ z=KAjisy-)bo_NNR#N?&SkQ^+0V7GstS5>o@lv?DB()zL9S9ZOEtHG}eRrcjKl5NOM zHieJhW4Bxd(nF>~D;$L$euk8&zq!`uz?%i}qjs?3UP}S%dkYViP1h)+xh)*NgdFgz z9_Z1Xaps8_9*Qa(I^BHUP3CD%yHpPveExpi3}k8$5VdxUidbd{oA&raksRv&II%4<*D&2%m$n8`O; zF4<4dAI-u*-!Jt+$409{dKqG2##K7&0k?j4DuqCheIzv-tRE9foQ3C}ct*TF`Ql%4 zwr=NfDK>fTk9+gB`|4#+XQx!2f7+1W#YpUCrJP%{A(#}C?yp87ho6_1uUe9_6StX`rcKHq^5e@7yWH zHc{=i&z$C0&u6pq6eGCB)OtxvZ=NWK>Fla3Rd_JV#H?)IVD3;c(8C-0lO z7cRXp-r*q&vIO4TSN#YpTeyrN+z|t=N(FajgCnU{+mI1jtM)7(yW(NRc~?KG8c?`+ zGs)J+mli(dS-)II@dekMYl`*YFx_lC};0cFr^%2wcd|Kg-Qu$=D2AgLxjfqV13I){H9`o1M)kMP{Cu1LboAx zaLe`NS8o4@sV@qiw9K&F)^*EBJN#KZ-b6sUmdfktTUl{H;C!0kv7n&ZIZUaCI*6it zp4HUY*o-eTj;OCv8f+QAxXp+Aq+8qVz|yjbH0^-3MXvSv*-Se*HXhl-;imqt)p`=- zyjBT7OW=ZKI5Ht51V54I_a3&q3WPbznJFphoeIP<=99eLrRR43gncY`go8|ksolAC zfuo7X5VsEPt<@2$vHllFvn6ZRBc72Yo)Pp_zPD|5tPu^xlf#1f%RhGZQdc%X;clO@ zd1WkG(jY1Ba^H=5@rt``OYV5VK5T};_4=vD?ftVmD`&!eXuXu)cu4XHhA>ra($S`Y z?&50E8QOUv#rn(#7JRLa?7HU|MAkMEQK> z*Z3|5oPT~WOM9FYCwyGhy5m8xfSnd9;70wH!l_pOlVpBMle)(X=32gKYp+VTD{m)TeNgffF}F2q$FCL3tSk0*JSf_Dxi`d(( z*XzSo_~E8Za8C|6`~h6v6K-!MNivHj+z1jXOt3m#)s5`s2^Q9~INlL&I?}+Ke)$uD z$gD{`I$?`=>#=HRylQK|3TIi>B44#deIwm?r|%$OTBcYn_5wt7gmll3&(4Bw3UZ-68Fosi7m`q3QKhp|gm?6=N_Zg39zg29}d$2UbEF0I+d%NLLtzaGNf*Guw{enIF*cre| z_6w`O(pZ1do9FKz2jqs9X`oVj?n7ANez^;0+25K$?k={2LJ2AMBYtdbY{}8W0Q83s zA8xgr{66qSQPBDMiRz_*i9SI1r-(dYQi0&|{Bj<*tXn$BnkXNUF+@LtXY9`-2jKbk z6S-Y4v)J)fp1$4KRB$C7amUwLWs*md3!EFiLci4?>Yg6@Wb4xISHX3?511mWa>lkJ z%hBEmLvJ%Wx0k*mkDIRbygyCGIViq~=Wu)5$=#x^V|8*}P@|ZF)ofZo=wi7YKEj$g z8n0L;DBOOy^1f5*hk*dBr~l3OmZZ6P%T(eKsF$M)&TM;IWN+;;){)S$O<%uRq@wUX z&)ZpR?UUAqK#>>BXGt67s~_b>iqSQpuq~@ot{+g*1MU%7_V24TdvAj7e~7K!16XY?a$gZW_n7tVH4}Qj$k5L8n_xz?@U>> zp%#oEX5ENTrCZg1y6P#nDn`C)=(Y++Jt^1VwTubi4UoxGfv~AEpLH=4e*c!xLFeK* z7AtTywm!ia5)|x#W>>5_{5in9>~#I_wB0!q-9diI5o|=?DR=%^XP^ZBo1;nPvW*Vx z-sun93K7eXr}e%Kw8_ewXm>?4eGum z6D`}Njlk#Zt-q29ty4GxgIBSLuR3tUQ^D*|R&BmwZdLsB z+ojupBCjZ5K~bu&zKTebBE2aB(nS!YM(Hi|9v~__Gpv|p-r!Fv{ z@b8M1bV{;ZJ1+XvoI9b-V`0H#em~Pz%M$z$2Yx0cc86c0pL32;)DrT~F!P6y^Joor zFC%G5uepHlqYWuysBD*=v2bFT0LQe2eOGm|e|g#b_>(5QRuk4XbWD6rla$`@r*nF! z!g7sPn>dnE{bpYEaFr8n(e72bERqmgEWFFPJ8peR#JI5h^nbBJxs~|(dlOJ2C_aj< z#-p1<B$5Jg@sq49=rdUxH{HTl6 z>=Nd=LJ7b@2-_4oFMgQvGw083_)*KuZ^nH!q;X^w-*5IQYm46ErZXMj=5)u^@E(HPlqp)vDJh0W)qRGEZUdGk< zwM53~`VYtVM6Ba~K1kF7>*{dVq1Ft%9Gr0u^gb=UK6i|Qeqv?~ z$7pt6qGgS~Ti-kY7pbzgQ+o;y!<_49?)Hln<<)?tNfM4&CI7KeZV7%~K%8s}B=cM% zUD3>8&ewjp0DA`yd55W<7IgYSC{b(CkBCq^w*&D?T4w%sBkWMklR@Do921vDr34e( zj|DlhC#4@W8`Q3m$twW!?Os9t?kAMHpCG^KU&PYDe8p|o;q@E(7ZU-EKJZ!jtuN`D zN3Ny0VLPW+J?19|2g;(7{gm3E5Sn}gZehf3iClu`=k@Y)`L zJq7z!cHg02*oK5c(73PzCII^kA4&_|kK)mdD)+hk+)bhDpFIECdT^{b2B`SNln|D^-g^t-#Tjl0N{ zhlGk7?`|zwuJm}8-R|>YhRH+n(vr~iwcpD8R*!FPnJXVUr+ZtEY4CCDS&0*}-GhuO z9>(_@03ZqeZ>l}Uc|Wjl3n_3ZH&7gmHBjKy?=cJUPWxaZeaSOLQTs%tXkD9N-Oyr1 z-rq)TXAy0JAv|ubt|Wa6VeQ2E_A`kUjC+sF^EFE@R%T-slYK%!z|&b^=RpDFTN>c4nP|D4eY;B*CB{=(-Q3A=h4%oYC- z>xb@Df(l1EoX6IvTe2J}yV1H(jiMGc81%~V$Fs~g3tPXbM7#(k43!8D%}NYCqzy39 zj;w5VL~G`Z=dMD3>2>~Tl($9BL>;0J1@^7p9Q(7Kk>};{RvckC1Rr8j89&rGSfPRk zD~^0S5O7lIi)r(tR*cdK)s=nNH(7yL4~?(GeyyyBH~&QKDQD$|nr9i| zB?wyf)w)cNrbxO+ZaNxYbqeq3#p>$bV!63}eJJC?hk&aIhj6nGd|!3?>xjAhF#oL- z6_to}GS4@3TjG(J8W}R}BsM+|5}LBCY4GCmeB_DxQGG}C`xvj4x8fTkv9s> zzj@V_UrkkqF_#|o;=^f`BBJ07Z@k7{wb~;owvT~y9o`msmb+b1CZJ03(6k9^ZU6i) z2+Kxq;EN=NkmiQq@wc=4`^wFmXzP8La!EIXJ;DonfU>=5e$4Q;nm+QaqHSBK!W%Lv z0=EdaECFJx)*^Iw`6BVWP;Q*^v47nDML8n|Nr1?m3ms!5)l`kvxC;=$VN{C!+ECX( zSUlx3cMxWBck> zs>OUvKxt=!bRfL3qUuE8K;-j>j;8#=E4prgIw;l2_PHQ)|us|vb6Ie(GL)r$C{ zNjyKjyOlfJIG*JQ^_nO~+TCRPFa0E@l$u$y?=(KYT6Y7QGGS59fqBxTU2>f)b;+gb z0%KT1L?ix%efmk(=-&kuYe^F;rdLIre-F!>yu7^gOVlycsZ#d3_AmlLU+b15JxLEJ zZO6N)pZ`bX%Snt>yVj=6y{$j)0$`K=0*QnNtXu$kH91E>_&M(j^E}DcDLONI?cSE; z`x^^fk?7>X6x;-C>G`27iKTTxpFzZ}JKv&suV{cwdCIMCx|!{|f58Gh(< zbW`HlVbALEVhaB^wP%XwZrvO6^Jtuxr!hDwhnORVvp|L9RAWc&iP2IDToD3J6^5=D z2Yfdk)zNxddc`cqoNynq=U5z_cyxsDFy45QK-qW0PwpPv-aKA|X3DmMfjv%(v0wsAZ2V0V}v{ zUcGs9e1{C9my?X6)!0IlS(XKIS+1Dc@YrhNo(%bRH~O$c0&r7fEBh{!pavZcf}!A+ z&w8XpEHuJmbY`w;QGm4CST%~el_Mfz@$`csHfcxk^;Q25YdntRNJ)k0{8;dTqtFS!v~c`Lh`29Nzy%vWw-I#Vnt{%`xN&UQD-Tz_YZW zDd|hD<+;oQ-KOOM>8IaYfE>8Ran3#FOE861r(XQ)+zY@ERdOBf-I~GD{A!Cdu|kg@ zYw^Be5X91TYi2oh;Xm?&x(bUrl1muW{_61K@}S=(E_ey*T7uaPK@EoZvv1Dz=G@N1DPVvb-H*9)v>*C^6M9~tr z9T%U|vY@5cVD-JMonJmNiJz6AQ0RHGCTX*M|2~Q`-_1x;kDksK`f)!Ib_#ZSw`MMv zabLhKm0{K1%P=-Q2HtrEU${vWNT7zQ5<<$BkAn3Jv(Lml z1$yyMw@pA1HG1-*q?-w`Eg{^Lv#70y|4|62JUwC35MLUus}l5;z4Xelxk%)@1kj4F zTyHkKn$*Va+bDuZEIlrzEkYCy*;)Q?F7SXrFnMb5$@A(Fx;tD#=Z;>G|JctL=f!uIzg)q2dy|k$0#P0f`kf2-$ zD~a{()x9_ML{Dk=K0_au*d|h)DDwp#{P-=+`8GF@-(hBmIEkS6loGTlyE4eBxo`Gz!&W&4o`F&*0&%3H z)oH1d^`eSk+@?Q2^{A`2E%d}6f;~YvlBIOFDNN9N06}CbMRgdS5CwChR`8Twk|#Zz zGfOnN*NsoH@e?bvOe0>4;hCjkSQ$iwR1a5o1x9OGgv5n-*dZp&t1IE^Ll{GKLM2z)QYw~rh4wI zp^h)G!r>!J{0=EBKs^zNn@RpDDxqkX<|Nyq1g~#<08v^xtx=rww1`~yQ-e(K@( zFE=g5*i{Ba9l#Cg9drNgcX1Qii$5AK{5aG7^(14f&Hh1w2$DN?&d#f&9eL!D_b&A| zz`YG$eV+>cw|PW;cBOjpAxfbhK__<&>dRSCjV-!&XRATS?&k%@8E(u;)lP{_HS)Gc zj-yRemJAUFnveSH#eU|-Gf=ytgD_UfDt=JGQuMb<>uq$E4TIVVR1^L4cSR(k(WUue z>P7P>t{X6gF^!gqKLw zAt&c?MwxKskQVMH2Xp*QPqxF>vU!ig(Me^y z>y=AuQ_Y%u6?Vr>Wd5a9xjaPa`iRO?q4laSHRV6Aw5-}U)MwN~j(L3aD_jH;R2%bo z=jQ|fN@Q;-D+QCiPCwbmdJ4)K9m*PwIQ;AT?v4_D6tfzeH)^g%f=4X<6m(Vz$AnYs zj#r__*tu7wlwt~sLseBsS(z%%18qt;T$NhGx9ODNWikuJ0nzsIwh@mai~?&#9S zo#^LcKmlxy`i(0W9_wE|j?9e43opyPm}%p8kb zcAwCFW7m3m8ziLKN}Oj)K_1YmT@j+5+qkY9?t$B=sT(&zINwU83?`NsAD|^GO(ss8 zqMe-Sb*KUK)IvceJkHfkt}KBZ*DVX>p(Lf5C#Q{mNRv&fA4%OE{m3zzmN3RX=EeQJ zFuL-G)aEHkV?8iKXYG-)z1*kyJg+?GcRmSbu{EPZU6uvl#n~LGOCG6`uwQW?pa-ES z1zVmh|KNYrkpp0pl0FNt4~Rdz>@lhLrs8H%WL@WiM~x`vo5nu3E!G0|7$~kEPdK&v z?%~sS+Kkg z+}yd2i%l!1PJ;5%|3-C2oKlqvC)4lT9iNi;N8Xf;E%i|2XT-_qkW+8N|N1L@fqUyv z`(3&D29RCN(I;*8u6Qrnv~J2Bmk30#P9DbD9;}C~Am`pR)Z|gtL?qORyt@m8=SEn` zTUIiZAtcoG=;HnZ;WqO1jX~K|(zn!A3Ko?U#UjiNBA;gw-t$rJtVvwxA zXCbU~f}>MQnLGc<#mKrD1CZIc`Lmw}AYDw2gp|sVook>Vd8GK|NNIiNE3Fhf&o10+5dEX;nB9oo!#ngLL@&oJ?XAHWoivhuYc$Pi zB-L!>qwH8xJ@&&6>Gf6FzbpwV!8VjADEprrwJ)7+0$RFfMjVixlSTH1n%8(XU{J%T zromL{G45ZearqEJNmSn)AzdJbdi&(blLP;itSp*Bf(qKPTM73t6FvsJ2PrjX0@(=D zhK(7}uOiUZEm_0Vy8a(+Y3l-Blas^&w25=&kgk>R_2YCX6PIf`!jx8#8tve9_nz|- zHKa2~v~j*;sPAAFB2&V5S0t^i(Bb}mq)P=D9RUQ{d(p_PO#uOcrlzL3&O~mK@#ALr z+cN;SGH?Hp^KOQWAUc@N)WXt!YjX%#8ym#-h?RO zX&Mw**2)a>a2pe^_Mo2r+VhxeV6+uA%GY+aJg8!#s3C+T%XZ8vhO-FxeEiM6pX-nW zC{&@ZIYO6-2i-K^60aU3WqH@K;LShUWq^X5&~#_bv|w~N%)0L2%Epk|UJLBeW0z;o zA1yCMCdI;AjGDsL4%SH3+_|0L;7s&}^4yH$!Q}S52<0L?Jh5dLf4I|`R;pI7N-gQE zFD00x>7uB`86W38?$TrMI=f0E0uEs6b}^QLFhYz?5Sn@~aMiE14EqwP!XY0(q>MoF zOd490`JQ8rlx3cyj|>Z`qPO4!S>GMn<~7{|(mYn`Rv#V3V@I<j>iJOm`E*%amhweY{^ zE+fxck)5Fr78ZRTqn*v0{Or|Tdne$nU zj4%M3SElwx7Kg_VGglq}<=<^j`g-o?2$0xsBXbX9wOe2P^lk&fjd!)zI_bj{$szaN zuuy$YbxXf0RvfF!iKg5eZiBUBr{ir4@DZ;)83%q_sp(>}mSdR^>wr~4M^6Gx$=f}- zXGs(OYB3_I0~yWX&+ZXUjo#g)y;;nGNZw2^0KHqB`LaDR!9+-m2+atF-Lrtv$t;{0 z5wB)&FpDx>z?)WxDZzWCkE1i8?T`d=k45^*rrlWaQjG-qQ~3TqAAac!d2);xf~2g_ zPDsGkLKh7ZNw%tI)}|);qr*`6rPyK6oI&`%a2?2In;eANRq#%qW#qE1KRF}@5T^i0 z*F*_eM_>@}%@!XeLvbrq_sGt>sHno4l>-LRkE=LY6$olaiRlz`7c8K{Cf#rKP#cuU>Bh?~qfx!Ecv8`Abi zCY9B#M@%h0So-kO<<2>is!ZK3ug1prr%xckKp;jef&| zZfHOAIKU_!M^`<|OGJo8PQ7I3>`V{)V$%DxbdNpf3AQ8s-bj|juIB$TL5{zhZtQbg z_eifj?hh3Cj?Ma5xAi=iJ5u|ki?B13)Pnm5MW{-p|7h*^ks)2MfrvXl?t%bAZe|bt zTtxBH67v`3f1pRg3V3+8^wy)}H`r*n^d+xzyxmMS&3wWO?-Y4}9C%9-cHQ_mmWuNQAFES}t;z7M>&YnNR|B{YpRD2cHd|7r$dB6>OiINqP*v*{8UYE)WM4Ar zTQp(VmPPcKt9cc=910(ZCu+z>a9A^Nus#vuQ_l!J+av3Zzx{Vvb(WrvM@GM_gwsu{ z_dd8!Q19H369-G!DsVXUetO~TtSx94mo4hN51ryXs3(%PkGq!g_(HZ`L=P(=v9`Q? zgmE;rK5XAHeOM$4y0bApw^l%z?@vVTco%k7DM_S*!(|6oXI}dmr4vINmddbV5_$W9 z5>sC6hyJD9DjXgoGA!zVkJ-k)(mxT>M0F(Wo9jumSbEG=Z@i+*lyjRHs`0|M%KBqU zFD5j3j5qGD=P2cZRe<6^L_sNwi^t1@7g;;;0D1u?TwPI{zBOVTVpKl->eNbY8v>4U z$MDmXAOWr|$7Wb|bDW{vzZLokLO2~>YqP6}mxoJ*Yq$lTE+4)B6>s(rb7uW?6;oyA z)~}aj-pvXiJ3g{m)w3aO1~UOvb@-}I6iKg;=XIRh;&5FejBPOk6So3#UT z&3^*_rznpT!|RDPVC1OQRkljLGI^ahm|Zxh*Flc0O%`|bpy$M?v*$$q z2&-XnW0h8NFMggpFs~3o0Q1HJr-#vYN8D|WJ@r&dsd@7i6_=N0?FqqmWo1k5W*w)R zFAU@y7eBTJgTaJH#)|FaEh*!W_xg^7-6rp5BR9S<5Y5JhtiO96E@+yXU3?6*tbCXT zT1(DUfY(&2w6mvmjaCqO_p5Zmi1I`r#l~NJzg}gHxc<4tWlBMMn1M7IFmIy> z#&=k%jFYyU)*Txz8lm-78DVW=K}d7(A~xOi8%1s(ZNaz*$7#vqW0Fy*HgJY<>;`csT={i+|FgdHPToNdMi3*9@3vY zloAh9;rN&lmcPa|_a3lq=Rt5GF}Gi4NY?_rUx7U|G2|%1eEM^6Mic# z23Pg-`pRVFR4#t1z@7O1aWxl^K+dvQm13|vYj1dcsY*V6Fq1F($l8!Br#q9k{HhZy zbb~OKKI-+B_I@%MDdnV+W<{YbiKhD!w{3YoB>8?akVIRbhG#QBPHY=(IQM@3(#!B2 z*4NIU>qbns(SOD41YCFsL`*-wzyef>ZZhmv?t~#U28uxjZICUCJ4g58vaRsYz<>kE z`DDiJhI}9RDx&L$zhN)YAq>2XSZ zZN{A@(uXL8lMw_e`DlI6jFTqclIwA_wh?7?!%&6bgAbqHL=uS^Z!!C7J*1U5icv`z zRAv*ek+b2-2p(s=Rg$=(h#FCtxuX`x2i{Q#n<6_AH@MUr9vU!xN#TV8ax{cUXxTL< zgV7;+$(5KyK`&c$#O5J_bVLWns=rqwf)92w>=%WA$}2n zX|8m?P%w_^UAZeEA+ca@n)}%oBz8LusBKj4zwdZ`j07P2H$RdtTqy*V*MsySe2jM= z`^{?(8F5#_ei>uy!FA>~G_H)!Bp8`u4jyXIo&yLiDnMvakKe(?HPDm1)?RePQP5-ue-J+=k*>ud!Q;{3i=2p_WfU1P z{jT?%YQp|r-X$x+m2Ja;ZD+%si302EMtRCUfr0htQ0nAFjdow}uHfCVVZ0N#^F(+pluSbh zNhEv;?^lR>>3$-?CJ(l{Iy-EhZiO?F4=HThv|8#sy381!+iaYjt^0hf^U!Vq`!#Iw zk9#!fWEuo#>^YGdRs-2SE8R8f8vaKU8_h@pcPh(&icqiKqwL7G-nn1?S)*>ZC_?KHAMT*Xd) zZseuUty6v_aNL;p+xw{#+HM}z@E5xkB?xHWncUI-2(h5n%HDqH0=K1`(K!D3&qc{t zSufpBY_1&I5C}xGmb=nj$mt*qwKGiGqQSYNb3&VG>seQw!5--Sz{##sD5ZHlV6We~ zAx9N1d+cpBcjTLa-PW`THo~xVoOfA2X@Zopit>-5hbWwa^pIDF{eD(GUE4q@5G^R6QIVfSn_m z#)Vp9fFj6b0^*5Sbdx{hT}=MoU?J4fT{4$u{~DV6gTh8*n1042vb99G&^89w*R87Y z*e5NjTJbf0pGLddmv^m<*|^#Ttohb zL69sx!~2;Jor7yO2v+U8N*`qcMIpY($pR(kTV|XV&kWBqqQ$;$1Y1jPJ}}M~`RL20 zZu@U<;D?UGcw~=wO^+H)H`iF(k2=sZ80xy)Azd?;n^Z8HWN(Ijcw1PfDlu;fPLQx4 zJwHJ*>?H)7^~?77QYUkRdaDnc0vFQoVv~)4-}WB`wyl-iyyHux8DJZko}_~2V(rHI zlu|X7d!cl)DL@Z#Q_VO;w}|x*vpRfQY~bsGq?Dri(d31P*GoaNUWD3+BNTgzHRmYQ z(RTNZ=A|WjgMOZ~lL*fri}AcGku2^F>=w0!3%yhEi)-b|FM@97#~~y2AakE z%(~&p&jDvSM!+JFy3B8UjCq_ljGJBdE%51&c9-& z+7c){p&p&*YRFNE9=r}s0n-IyCpbL?9{a?n4%Vd?auNg`*QB;0dpwccPq9|yXVL@S z2410SQ+J;Lo}CNIEcvCSL2Jv#SUL?DcAA@6KVDlgu?%bsAZ-=v0gGG|eCPjaXV`bH z#sLdF+TUL~J%0XLl`zQed*^fbN^KwQ4hELxxJB}qQ~914fKkPX(H}MN-I)5G_<6y6 z!r#_8M;%IZ&W)(ql!|i1+v6Ev3+57#1HRu{yngPxol9#rvT6bF>Jz86?iXfh?oQo7 z5vz+f$x^q16v=n11;AZ_`d8C^iUssY_k5ShOhFEQOht-Tcz98ys_zWD*)?U(0U$N6hP-7xRX=|<>>9nC83oHBGbZr1OAUVMP*df&wav!{O=Xh_isfDQQlDDm&)T&q_A zs|cDAZGFp5GOu`sbUCkfS)yd2@3d(bpNP+2+B5+fvXd|6EuHlSE9WrMYZ*-E7PMUR z8FvqR#CJZUn^)X6{J4MPEAnLyT|kNEjv-*jgWK=oO26oBaDfUacGxN#A*0+{1faP9 z+f#s0j5urr_Ko1`+=11OvcT2W-(;d67fDT6Xi3zE;C^ zjwE*)wHfNkb+^&t_p;ewI7d6De41h~vU!DEUFw;G4AWHB{(tBD$R(9FW_f#FU43DG zVjOm6jyKEd6B$;-l^t1Nk3yW2Njeoddd<~g(c`iMJ=chc2qdfXvV zqiu?V8br7P@ittG{rN4YRHUj-7`ga)R`NOBwc5x&CYkvf;0U({d~E%RbaOUa4WhmPYnia2lS7Wm-+jb8q2l9@rcA30zdL>y(iW@WIzjd2{R1_b_q6q z@IH%~06-z`Ait%4rtZmGIop_ANVHp0`#n6FUbKc}1{84W=U#nT$be4XJj zvyn~P7jAX1R>$!Acn=tIJiUJUbn@VjtIq6y`+OO7!#5b4uCBj?y5rut{`0tT>qwur zA)(eEXqZ(S)=4hUae{5jSgM^CNdPM}*KmZI9d&#qcHi%QzkSUM(m3N;vsBAC{04b$ zrfbP08f6h*xbSJ1E#F~r*SZpvo0ginACR1O=g*k<<@T1wNp~BsJeqs_bCPIPlksT$ z!ee*k?%2Tco*c%r#=1f3{%C&3VAbEV@@cJ#P1U_*1O%`1;bD)iQ-sc!*jm%BKhs*% za^-c*8_Gs%kHRgt&JfpO8{yzv1kr%Jz;h=Ld?5tCJK6KF3Q&=8Q_%2}DKq~<>BSMh zj4!NFKioU?&L1Hp_p5??f-&^pyd2Rw1n2WQUyST4{uFi)mu11F*5sG|{`M>A7hI`f jMD_pq;UN97l`tls_mgiLo=E@v^P!HW;lrv2&tLr?7~M6* literal 0 HcmV?d00001 diff --git a/Sans titre2.png b/Sans titre2.png new file mode 100644 index 0000000000000000000000000000000000000000..10e6cce6f80d5ff0c7f1f3eb4f3f276cc0375709 GIT binary patch literal 464014 zcmeFZbyQUE_clBrAs{8vB@I#n(k0R@poBC?H%PaFgoL!@NJxty-QC^I(A_md%{<5W zKEKcB`@Da=f4=Ko&smE#9G!E{eeZkkeO>$7_aW@1iYzuJ872q>!j_klQU`%hH9??z zp!>+czdY9~N&r5PT-0S>fJ%lac7PKU3khWj5U4B~>(&?*ILC05({TZTaN2+UAay(B zzXgF1-{hqvUU?Yor(-lIPZD8&p;NhuE2s}#hoY@ zG{9q)vE}JCED}8|5_bY`-YYqa+G}d%G1qP$zFw#w7V}=Z*>CjQ+jog_SulD^@&N5a z>+g?thL-a@aMQyM_Q8`ibL4;g&xe)R$3fu;t<}UXCD4Dq{_83|+Mt&w2!(~Qj%P^w zVz);Qiq%tJ8g_S1SPfHtUiSy5hBz#FFGI2qt^Pja&j*I&eL}>K4tC{G45PcI_TeZ4 zO%v@7)ApnWepCJF*Yh{u=P&xh55R0Q&rEOp_&@&{-=AxzsZTqQpzmz&XRaa=YQACc zAyJ6B70+#(NndmNSoW;a?77u8AyJ5U*|xk7-m9C0OxCZI(S_(6{&NH+4tn1i1Gx6w z7bjipGsVvQ4QhHXFxw7U8dd#bww7h9sb`y(F1UZ&#*vgO+tr|Pa(Q)7!bX2MV9(if zak(0v8iD=G5;eDu#1N7Z4KhYez!X8B!~|0u-YbI)l?+qMZ}xo}H|<36`hDT| z6m$2lcH!)XVx`>HMSEty4ZOnrVg{bjS}STAlnnZ{6prc7iJQLs=Y}q^Mnly5Vz^F< zYsnzDyDPu-txod^f1{y1+{4?emBAEs$q)`OBL}^`CT$_1F5Jcw9t>c?#pQ&A7IR{#kU#T0GXR z!~>Y;n?c8D6$rSy{B_axF%6e0wY4nPq>4ohMNLIFXoAAQMa&4Tpfn*SCq)-3M$qwiEc5hV z8#>cG?^UG>?LhaqCOxM_q3m`*7Vu@HU)ZTI{qWbS-`e%LO;G+x7sY8eS*f7aoZHOMN`c=Irk8sE3yw*kw~+nc5c6OJb!N09 zHm^-(PNxW5T$5|9p%T;lWQfE0TATGBis+TLqieX+{eS)7*Dasf;W8Wtu8lJW;N?=M zVmzi_&@o~J{SJhoD7+_d!!X?xJOa>{Dl7M0zPQ-xlrQCH11EdKFgTmkte$IwOs!Y}e+{tWh3CMlqn zP+sA&iuCw~i;h&kWc34ZPg8$3ksU;w-x_i(c5rTn&gbL8Trya1+t3Tw9)E?+nzMM>05%X5pp`{As_h{K)#KY{dId8b~4qJhk~@^)shrP)nIpFUdUcJ2L*0DcfCaFzZ+z*u=$QQZ_4frIR)hjvwvX`%{&mFJ7y$P%`RC!R zADRqO`qxo{#YGSh_Rpi&l?KS(T>m_3IXaX;jQ={OgF8%-NnW)JMrN_o;;_S;m=T{Y z;)OW$hI+nrwS2L-N18r#eQRdqsDdQ-%>?C>E{Dl?<$pbyqq@TZIrP(sfgZtg5&2FL z?-d=eJ0@}2)W4p?n4~*^^4YOAw36?iBjT!Ea8_Xi4Kr=W+m32Ah#kM{2~xCe5E2^9 zVs8@Xk@d?~GaVsS8bwz6bUPSmU$+xW@VP^NfcNjaAR_fEd#x8O(xkVv3TFJ1sezW2y&_-w>ls-G7SE7Htd-d;?BuZ14Ezu`V8m#gCK* zf%~hPtUGU{f{-%;DKSTdQU7Hzr4o)2jRKO)Eb_rk#M zg?0az#F^OCRx1=Lzere9{&8@B96~b+NFy zs>OdArK4j#h1lZ9@0j@;3m^AD|HUlo0{$kBzwuDR;fTW+AnJX&KUX;~T4Pe`abhy< z%D2Bz>vFa^n9652_tUJuM894S@+n9$1$KEbFYnX-5&JeaX3sk+v?$YUf2PT={kn2* zDkG%Wu-UIWiqigt1?|e+KLYM!|A(Ly(B=N@&2Ua=6W!Lqj3?LC!DV`V;`iB~mYum9 zHr0nSo?@55K`#gM^O@g&e^Y6Fb-JOL#Gzkig4!Gt6XP^G?b61eOfjUYPTyoZ%T4h% zkdBsiRpeoGQKn|en_7>Ptk9m$m>7J;L@BR_we+;FXhms`O|sbZDvUPz2!Rp(1(3f9 z;Tw&_?@2!ZQ;Z&0I~l(FGUC48pkEKIVd4PU@X5GRmu*i=V8JOWi~D=b{3Ena_m)u) z(1y~REWeY}l8qC6yhfq(E0phDSyxPC(`oj*JAG}FJESk<^`_%}DB<4Jcf&@ni}Rgv ze*1-OG*NfGu@3j6CFMR~N(?6q{aVrKR9Da(X&0jUu;DLUYkCB~=JEYatv>=zCyPTZ z?l(Z)QUFrP5b>l9SmTI7b$k}!kGO;0|LF}aNhtbPy3;}*vPTZs#-XS$^{X%Qk1&`u z+uubyV0uT*ck`kcBia%webIDJB23Ulig$7o?>>Ir195DucY|tkVnXuyWZYtbMyP5X_o-D|oeb8As-p zd@@VTBewJOo58!)I3`ttX1_*q8l=$5%pS|h-PeG-0e;s#mCsJj7rUI1Z>P4$U;JUo zVYbffppLiR?O@@j*;z_uk^BCPid>t+JW-|7+O?>+n~U{iVS@b|3tG6}Y@O>~j(nU9 z7%NvfbyJ4#AAH+$h3)sE!$qCczTwvM?mxSjUSa**rEj5mUFtpTznKOlKpH11xv|sk z_!6v^O)M3e*6a#fU~e~fz&S=l`sUhii<(JB%iGL92;V-3W-XZ}`9Rzy?jX4}T&9vD zuUro1D)I60<2Kn4b^Q~8<5L`qHCtevJu!r@HAKD$p4@m+RKg>Kom}qLo>-ufXTQ`i z8yRQRq2$vZ^`WS0KegE$8qCz>ywMlh)5FD+=rif5Fnq$=eC^UjE*|0cZ6}l?I}uJP z*Kk%^Yr}8*kBBk1S9=~;^Jp`8~ z1c!3LvxzZaXFLz$4)MhmgDsn4v@g0t^nbpU=XZWzW;LEWlrB7+%+oEpR1d9&_+`sZ zG@5ot0TDl(A*ze}n|}WepOuvES$8BhgQk_EuurLXf(4!sX?8Rzze%gHmNKkO>5@fX z19GG(hovRoSL>xZmdfr80IS;TsH#dRKs4N?I`CV%DZko7tu1LEA$)`RWMzb{bXIh_eX z80g)mFQvo7LbaQ{XNn^aLO8vf4`8l)QPF>LxAJ+YosMqmh?Lu={YQI}?~MKJ^~D}w_InAgrd^+4%Ak37 zTXDzZ=K%V^b&*^Qt)TOI&B{k|`}%{bg;C&K`r`xAiF8)2l6V%4-C0b+CpBFE z@Y6Zz{oetPlUf7I27laMnTu3wz69UxfL-9m zt7ZfVSC-9mNoP3W&1pX;BC1Oix}fpHK-3j_1Zj3$X*2XWK|RDEVEiwGvoV4!X>Jky zQ3MbxE|2|lhMuowXQ}TpVD=$8u0jLw;yYLdVn7oyH;CqU(Y@Z3y~*Um*%E*e^TVJ2 zI;j<(5)lRSo^zh&zppm$?t48Szj;R|wo|v6li<@l%&IKwci9~gxVEVZ7V`zd(S87>MX}*dT+z@@ zC~MW?Lrfmo19i{S@j$cPiyw>DZCZ=wV4Kxv@Y}01z{w#FJoc~!W&Az&A2alt0hMYu zJy~bRJv)loXiEC?E~~pg>W0X8UDetMq9G_Cu(c3IZKxf4*!DlNX73U*bAaK7n~CfdIO4wViab*!BJP@`n!C z?aS%ak;d0OX!GRS1|wp^PB_!8zYL7vy8Fbz15d8Nc=6yX@|ZP8GQ?t3`#+>zIYTyDlnj2G}+B(T^>QGe`{rnH=3&6_3I?kL9fA^-0lSj_(Q8DZ+P{hMO}=kq~0r+r3TObBu+%_ zbcNwZ=_uVAv&(S1Pt%9CqDD)Su3l9;;tpe3k#w83Bm#B^Oq987Z+p%%!})6W>5_DGT&hq$Pz$0H#SwPAf~28| zom{s&lKDaWJXtq$1w#3eW1-&R$Em-Gei>sxy0AOIK#~*Lv`X~0hSK?^v)}f{e%Gzm zgaSwrPRv!m&{U05#rV!s6d8XFJJ&C4#>Dp>Qm~zW!#%kz>(!5~Vuc|X%VUTh9 z#Kv>lJMuk7j1Ha5#v0ehpTSa@;Za=)lG|`=^vf<#XwB7aa zY^mqX;i9*u!%UUYRaY=8AG=oa)7lK?QAy?wjBy`$K4?IHv2 zwUHUn5eE_`QKPx|t2~SOz%wS!IRWRxkK)~Ih}`~lUYjYUlxG-J+rJrs&(s(@mZtQe zPSpl7fnk;HY%GJKj8f!n-QIwo#uPvW^naZ6*GGo4Y5Xv3hvdDZ!sqh1PJx7QUKMOj zOcrUydAxcRPtIciFs)^31%KEv%_8E*Eutr;U2)nD(FASK_r9bQdRKar-}4jvz-rD{ zW+Ffk{TaIQ`FE}d#DaIHc{>*A@y*EyF@z@{dY@2E!w~qROeJ-5Usnp%ar#%5VHkzc3Dlh{n+>*y?-2f=5ck8`Y2%qy7A$@g z1Gu}<*!#+8UxDRxO;fFs==Zk-!LbH_-!dpBJ|KDe)%WHSSLC>b3G6c_Ocsnu=(UyZ zKCuY+FET3T_AEY~%>M~ZrM}%I2JKr-^FCjxN)|~jTz-&RBg3-B-yVGeQQtkQ7;hof zt!9Wv+~Y!e5cQIvh1zubcEVo`aiX~3BB9-Awbd6{pXIhs%4Isq3h9y^Ud>F|oBjdd z%XK&}xiC)3V#C({p=shpYD3{!C_^JtG0bje^~igGgx}`s@<133mudmv=`M3cxF(EZ zfUlOF@xys+7K52oV5B_eY`V&;{NU z$N47^5%a_9Q|DZBGtgxUNiNAz{W*??ARw6m|NSK z9)cCO2Mr6U*iO0j1(acFmO$!^*JP029WEqy%vaf^ezrgYxJ-}Rr$%oaDv_@MJ4Xb5 zKwom;U#a~8_pF@lNouA%F^Tgp^x@sl6lzp#n)lv)KMBO({;b(w5%!Pn8IG5S(b5jo z6|yRkx4CEZyhsxW*W2ZjPekmx&EEVCCuzTO6+rgWyGnMRTEDJeVQr$WC^n9krhb=p zWj`-}kC8pS%;Vs^a}Qm~V6moqbtqe_X~ySv91?K{VCt`YB|eG5s##3JV?J=Y(GO?< z_i;mDC-vroDPaUmZh$%f)cG%^ERAn25BzUWx>2!+_UBwba?$$fee75%Ggt-cU_b(y z+#byaYTmg#Rcg)?u-~=SXqNN|6V(q4BWNOfs@u`*#wp?+I-HF1>H<7IZ9muK*B|Ao zTlHhU!FMq?-$I=F)q3P%qYP)z?a@-?{z8@A9^sA9^AsBZxHkF{_Qt+pea~ao`I(bq z3Sz%HZpYo5MQKv~hk8_E4am=>Hq(c#Yn$SCqlVOXd{@ELxnko!&W(^dr5Qq z`KEU4cO2Rc&Mxyb_|4IJqs7n$a0pw`w3*-c%W??ZZV14Mrcv|VJ$9zX8I#-b$Zk={ zyEY!>uGet;Q>?-6$kg(_NDA^HYh=)TwF6k(9}bjj7N}26yCQ&^R9Z&nMJnRiivq~~|XJq12y85TCt9F2h!J){2Ryxx}iPL}% z_un3A4Q8#HxVGBQN=Us}LoD?pmTUy;ddL@>5jJG&h8y9$ND-96mmhG&JT4}+0OD*= zqF4K7vz>t#Ib%~(UhW-a#&;GZl@X?02EENQ3U}XS1zW{QUEVB_c3;ws)NAy&h@;E9_4 z^^Kyb)}VW-lco|clt3Mel{Um1IlqEzvDEmU{TQ&~^S~5@fZ;WILxBnkt80lPU^H8{ z9+0pV(*^7lt?8Qp;l@v1lOQ@Y^zn)PVqHv)m_3M5>C19gL?FNx-%2n5e9RqooM|Tv zt=JYUvZ^MfK!YK~HV{2f(OhEB?3;S==(*F}8cGEo$Q z8J?S@uKboGj{$+v3m8w;e_@<8a)9m&Ucj_`{%{|U3E0V+Yy`=ue@hG6pm6iaVrjJ> z$%%2CxEFK>3WfMblkr-Q<;Vjo^zjq0M9zRhdEy|YMJ4Rj*M|Ehl7d&_&>X?zJfPM5 z0RHvhi%_#t(X6@G#T1W$o#@&|;&>5Upwju1Jm)jYc^GuGd^7wzl7VuoNhNZJByWO< zWKXs2?29SPzTOo;JIdeO1<4^LE&*IDL)3e9*}WwI$#DmEK&JHq$Xo2R$}sU>_{Fp# z07DE;LJTX|gm%a?l~&_j>Gf`hGnLhABdF2-&y3m@CU3ID;i}9E9kW$;=7gTv-aB=^ zQ}zo#U8bY3xR9P!95zCi0F6~sg#@5onhhRKztk8&&;l|5HaXt_pdwTQ++e8)$#O}{ zz>@)1{68V8H!skRQtGm$Lc$pD-TEFC$TuXyZfvib0U=hu-tDf^H$(_r?RPdl^?mO4 zw42($B^wQ!?3qbNC;;Dp)WgKh?F?vEj)mI2OfBH@Us%TFe)3gq++rwA&}p?J1`s1j zxpUgVzD?GPH*4VQ#)~@$;>NzC2omYB7ve8w19hK2q{~wVi}}NEzbPiY@T#_7^iml} zth1f3Qf8@eHdjV*8=R#ScC(!+HJ<%x2FPPM;top<0AyA;K&UVy$*o207X&c(8QmF6 z208%#+VB+QWd|fiduItiUe+wpD+4so{QU2G{IVBh1Xrik?X3J{*QUdy<#f|~cm6O$ z7yCR~M6?HVOO0?BD(kn+Ww)6%X^pI1=3JXPl^hC`XMzp@fRwvP{L;XBFwod*0iHXU zs_O3?E0cXOp}ffQ_E_g1%&W@jBL+wvg%^nXNaub)r)y&ZYG*OW<>yyXUeM;ccL_H$ zz^Vg$j~RuE3^zGsyhOXq1PFkq9Q>IxAopPV?|QY|w6w7uc|h&yckA(xhNZ@7ctXUyeAAL8*@Jnjmhqgy-5>vd2B_GLn@Z14+=UDeHQNktjD^dkP)DNA6tB(!DkU{ zt~tr+n<&z)why9*0JNs#bvi4%liv-XE;o9+dt5}2^2muy9gqaM>r2ekxw3{G%r&}9 zmr%~T@9WjM?X?l660t!9{Aar=Q?rn7!4D6j=9)}LPcO>praXRH-)%0|yUR%1>6AK( zNxQ~jy(pd~{nLZ{mE=~$rPz*;1I{EQGS6+MiUW;hWMnwBON|Z}Y8|I%%Pr1?fv~+# zRYBy2sT?fRC2c7Q;$=7nw4bp2-q@5TaR&v^2po_chf{bzvC-1fE;j<;_rbU;&JR#a z`RRF|=k><#ZY#UW@m|E*ofm1XEq^|BRH&ZShy_{>fa?V@+dpwy##Fi;7DrHs`FIrT zf}R&+OUn+V@w#l4q+ioMUtey$C$}sea08VU$NE|Y>La8DsE%?vpDW;PfDiqrkNKy` zYZZFu8bI~<0N}a-pJdW8JQyilRVn7-Ye;HxaoeSuBy6vUhzg)um( zLkheb9G8cSZxz%7c0bpn<4l4gnkL2-BzzFp*Nf-#z-@!T*sJ8pC|B06WYl}b4wOg)8t_lE2KbhN1B~4%y zfDbBBukG2@&QE9L<4h#ALuh~ZNBn8gmOS}_u{_rSJj=lQpmM3vd(D2Tc(&BIeWDpC znq;FW!gjLlJMZC&lmhLLzZ+QoMDaA{0E#1a7SN*MY`#5h3&y%A1u!4zzkB058?{eQ*4)Qi;)+F~9~J zFcF((v39a0kby~tkD3wiNzhb@eo?E*wa35mfnFSNO7rMn`OfAca2oXQ?yE9z`tjwL zefFr-? z9>8J&dFI4v_&2^g9{$f-X>kJ;^)K2EG-~=2*%gzyzX8_Ny1z-udrS+$y1}} z*)owpL?K~?ccVD2_r$yi#>7VhR{R)33zr}VNFf!~&@3R`6b=J7k?jFU>h?-Y;5|V$ z-KzbQwQfNXw|(uMv2Q1&qFxnfzk_u}4{(fMp5S;8h~o=LKR}_KB;t80eAGbTdk%#B zVJ%7N!T3j3qF=$__yo`n8tyLVS=4j#4H|`7ZRyG3x*g({K(Q3*f6OfEb#A#kQGiAG zBqszQ;q)!P!U+$UD>^uZ*QT!fcdVw-{dKewE`ZI_0H)550J4bJ*&sjGBj$jcU}A$2 zZv~oPPc1^eI@^lwM;ZBHD30csr;?t+@8GvYC%B?n9@LP~VgxF~nFBiAd5TGg9bp8A zP7fBG``Ll2*9|u-hDP$EQZjcf`hP!DM{=?rJrt0@IOezCDwhW@i*@n+`@ z1?*CPgkRT^B(7*q2$gnjdt2M;?7;7Bev%@;9YpIBAkaO*Tx90Bh2I>J?WbL~7m(0>Wdzr5O!8ypZgvQCYMA)lM8frjs(Ih}mNNg{bt^i;8P-ELPMN2((O1*}!ic93 zyv8e2|Hj}2>t)J2thJyQQx$KVz&hJ6@Bc&$Rx*GwDPERu{Wx9n4hbis9G;a5YubXA z)T2!oRx;5?FcCgs6Ki%((bFq1gdj#`xwDr1A&A3zKN+p>Z{Ylp^XAJG#J8kvCq$g; zwPMm`65Eddv4npN?Mp92x_e)M5_rk~Y%oIJ|8yOG?C4&6I{!UY_zNKy(9o>1GyOT3 zAu3GZ9Egl+J(1s9F%U6m&Fg(>i)_1469WR=XyTZvFNrf60kqH;O@AltA=F>laMhX% z>80EkJEaA`n}cl`$q*cd0l|a7X2wj_$hL#UHOmF>qejc*LkSSE*-b_3XU8-VjP{e^ zv>j@J5lGc{MEUS7;sy-J9l@I4ly+3(d%$eT;%rKm;z3XR0`2j++4h6hC=}AKVRqG5 zE?bunw|UL(WDkh%eBrB;=IcVoTIdo%3bd0L?$Auw|DyQxVp`U>32nCA{r;ux0!(`> zC(?Q2y8TQ(K0kBKr!banRx3mN#qtBvH>+SS)1sThJur_2(?fcngE{i|9}0Y6E0^^0 zP4tczyNZ%3`bA?E1&CA!OAADj;k7to0rEBQokF8mTjS1GA=g_at#_J(DZoihlHsM+ z_uV`Ku=fz+eB5vQ>8l1kLH}fKxGdEPG3#dYkr>y*Mb{*83l;y%{kC2n^K*z-k+|I( z|CDF&iGsTV^(&2>&nxltVd73Eq;K$C(H^wRFuWDem&yc1*hwo9v;b8|vaQ4iH0*|> z+ej+WxvjHBU+7{@wY}K`;e;oz$26!WP)g1EiJ&vT7|TbOKp^L3))Z2s0N(u^Xc1({ zs6KeS;=TNX%VU_S2yJKa7}(R}3S?K8^`5}+Fhu=PQ;}~YpwE#zG~k14mJbS_k_=%8 zyI&KtpGK3c98JiFQt#skY2<{8YcSHt-L^p#l881D$L(#aj}bcM*I>^sNLH}_zPA6# z>Wj(uf|G)MEE^s#n{woXQJ&y-gh+0adJ?iRD?RkW*a`}5x=7R>r1CvKK)QEp+6A*1 zP8_^HUv+iVBs^iA8``@k22dLHUnsC(+UyV1+Q8wi*2v>jK;0b+QmJ8`Y#9oy^Q#m54Z+C`QL3EjdeoGvVrxx{r=|4A0{Cu z{I1bh62Sz9iQm4okDe~v@V|4V*_tf80{a^XRrq)&eHK6e{Ek^Ug(>e0=D$ z;~T2O16TA{X;C9onff23MRy(}2Yq(iIG|}PwsH=C8Z;3vN<*oP>971mfHJaZR8aAd ze~H=sqTK9kYml|FW(`MtQSluzibaYejY;?;?ux^Pvz^bG&ah+SI<#wlXXn_m2*Ra4gjVtW&}T(^pX!h(CBpaZ z;bT+Bo3)dlKjVSg6Ie-r)YcS(4!Wvn-NHxEJW}PQc&o zd?5<@+-|#*q*oiX@bILheh5#*Wh=3qUhXOKIBy57Syr5f9(1xXb$1l|5L2x0l4d2S zc?B)ZZ|{5TW7J%R-U>%!E7iiY5lO%N!|Z4U)T?h%um%5S007MHt38>inTkPv$r(E- z_ANzWzgMkDiSDIQ8^K8+dWXo#?U_l{S7QLb+_#shpUG|NcCp7jrHgFx*khkncrK+L zs)J9s`(g^kw8`vk7a5zT>JycYjlrR#Uh(?T-B!j~Gc3yz!JK>4$dtl*Uf^Vk zaEDy^!*%ROTzA)xmKGtokuU%v@g9z0U3(w3Mt5- z?QHBjGxR>-^;1lEk|5x;3e3{_1B&>4yq`sFjtq}8v_^0#1dc~#sR4${UXckXn?Q%d zSv4)p#W(D(K*LY{eP7$s%CXS8(Zw`}0_w_YsH{^jd93B|JaZ?a!$%Ud1n1 z0MS*Z-KzK1LRE}K3(v>n%$#58Dani;%ZPZJ3p+~W`uIbtCaGQ~ifBa^j=9`hu;K@2 zuLW)C0y-8vB~sg$w2tsNidAX>*A^!})b$##hghwdRcIG9l^{-0A|f{m_s3ZtFB00@ zqXmWzE38yo@~t@X9WM91DJ-lrM0B0E3K;LrthLW8?( z`@=RBm$_G9h099&q&%OmSLXFQwjhEg?7gYWQH7Jeu&Jc?qh#@s=Cvm>nb4f)LQl6A zY8g(vj}kl|yf7#MFn&1VReA0{ve8mD>&~{Je?s?S=J>nA;}w&pw`~*HsCbLw@Xx)4 z#*&`-8R7AqoZdpq!>_0r!Hkg+6n)P<+uC=&nns=d7AbXbK#zVTX)EgR9dIT(@Dd_PE6Zw-lhoc*f6a?8rtnA}R61Brvycf$~9z^dn| z_y(P#W&-LefIfhf+o4}+{hDzdU_#q0c=-5%xWqNyw!hP};O`1hkDU>8&R!uOiekGS z$^SB4HCJVk-}l;oBvtLTF`cSd*pR4ze%)+-X?`@G^SRus`O?yhsPc`?RMpJ5nEP|& z3Qx(NVuJJ1v+3Gc72+K+1a~=ii4+9q1j&wNsl$*%9xgQ0Zr6OKt<)74wxMmm#F$ zS2?^H%wP{+JKbyLXM_2m90_t~ z_AQVr!(H#L;o^w%;bci^`*##IzW&`3(>`q)l4{T67#Gp+pjSWN4v8?jY-Y>H?mMO# zT9!A~W91_&E;k_?+LY3$_L2QzjJ?9!CT@rS$8btI#$3-l=me!|Y%>cK8jYIuYLB%yOi$!QI*uCF(CL2;lFHs=Kc6W0MrypHQyy*{GaDiQ^%cube3BuN z?g~0}Ps2n-L9>}+a*Wr-Lq0L5tom&{lP`M(vXNJPosKsxOi=yH#tLA@pQdB>t0kfHvq=@J+TF7wHF;NvB z@p9Uu4bw%30&l$yPYiCq9>L*kq#vYu81uG(Zj{uUg4Xj)0Ugz%L&tAtZ@ss3lkmPL zt<~7n^%IGy_-9r*pTR!d>12}y8r}1gka~9qpNzM5SVnC@7!*xPd+3h46D%B#K8zZw ze^NHq@04Bm6e-`0P*Nq+A#*I#mIi4NXYj^jEQcu*vwDH{fw*#teiXrqfXiX+mfX%* zR)l5=+qLCj%Flx;1JT*wPuH+T_beI2bF`#6JWHH?Ep!CqJ>g@uIL2OVe@vnocg(?=O#xG|m-T@|^HrWw zOtIuhZsfw0WVsSpta;d7!*PvX;T^Z<>1H)#2|Z;Z^Ik*=jJWe80Al8eBq?H3*hu7evrkkkGfP^+8IZ`ye><+O@ zV9|KpU63MjwN+=@EQPURUi#>xa+A-C2?SKU7IUtOLDu-g%kCf%C!ghjg)78~ELV%f zOB%VC>14bem>^Xo3?ss_rL3?Gw3HkUYhL212w=R~&82li3-qTf6U^`^yxX&Z44G;Oydl;XM2 zE^$zj)}^#(P*ZHQ+HH!*LA4=D)!XI@SaD7FQ0Z3pZ zGC=A*=^)^4mf$u{eNxk(lvIC>GE#pc6<8C?`5jv;q><;RQN#V-)h<~F6P~h{Pt8u< zA?&I6+m*YMW)SqoUdx@i*AKorZqAmQc`f{uZrX9wq<_2c-eL9=`y1q)=Rvvr^yLACdhddyaIH!H|JdO7Qgb2V-BvE|kIi04l(;3rf-^*DGT=Cndhh%zh{^$yvzqE|b*T%>mr@iATMB#4&4!{p^ z5yY-UuW_lL@qEKW%6MF_6vrU^<=M{1<6}V<^$3@=sH5iQANs;-onBC)jY?D5Q4^p# zFd&3)Bsm-2-9b0R=u=E8t+Pb4h1%7_iNzZm#cedzPDf&SWhW$FDe*r0s+-N0RlhYP z`dGJ0hDH6ponjg+SIaN~8*54Iz57yNmcT~8|9Dg5i1V`@_oW!SVdx?gCIdYtd$R&z zt=3d__o#@c0zOHH7rO0<$t+XEn`pA@Zt8fN=C$>U6lNW6kN9{VUA|G_PlO+c2Zxf5 z$^jWCPcA0Qq?2DE2`*~bgkd#quMoR_tjw?Ml%`7UvHSrj-eN%ZXde+|fKD`y1Oi^8 zI~Prgz+NoF6}Dcy24Wfl@i}{(|Co-?k?AaSt=KKCH)@>KYRnDd&v}#@Q2j&ODdjt* z5It0Fx+DRr(SqoXj1%tFqkB-uXZLmg;E5K}K)52vy5luyadqqi zT`LV~*D-ZTyzn933oNYn*i@snzRH`&h7tlny;tXZ4Q@>O9RZ>mP z@>y$%dvNdp4%Ymhz>Pf3vZPQD%{pnpPJ-gq2hm~uhw3lze_~ZcANzwotd zdara4zy0D`OWr9UB4W>XH`*jMCeiVrPdQ=!A*{l+?;o1m7*zeMVB zd{*b$nIY`gK*DI!nZj#wX67~BOK~!m6ZYk^4h}OuJi=}4t1rjox53^|y(`?(`xJ4pYSrQw17KZ!yGNcV7W5 ze`=p&i8r}G%N63X^LsbFBhnwKDj37)%v`G;GnRlwgGxi1h_}Q@qPEenz6udcd*KlN3>1`FvW|{0*qXDr zpy%ngl@->Nr3c=j)k`}YZ;XPT;v|HwwmY5%Ns0)5ONzj${qo`+^7F>~!)C7S*d}y} z#2&Cog0FyOSEQvXu+9&mkjoJ9&XS^Bed4M2A`*uER>IBV zvubQs%4o14KTRu-;wqK(o+l&7?%=CY9;$y|E_O+)BS8$G7LF2PGt}=4+_Z%Y(9oI- zO?TG%%X;(HA6p}DSwNjHTfZv@eyCy)@>K{KOTCVV_jC5g-5*TtM@N;3Jmu75zRA&+ zUxmDg1vcHh+p*Vayza=6H*v~Wm)_6FP?NVI(-7$V@-|-s#3;|G^rX|nbgo!a**3S) zE9_wT*qA>_yUZp@B=K~Bhg+-?zk$N(rE-_L(R!#a3iZeBJ7|62q!^$N>e(obN{82! zJ*(?0AFjjk3euz{X^yXw!jKQ-Fe)>e{8}*)oU7YxK=rBSNK7Ye87Ayjv+;XN(Mr~D z*<6qP2>JLK`)j4wBi~+@zVsih$na4YK=Y#Uxrb`A{Ji$Hm@#tN)>^9l^~Keew3Afa z2ajyo!te+8M(2;1T?#|jo|8(WN_l?}YrM)Wg^KyEhXuSYQfWTeFYZYw^687`d@(cf zvX__;Z;{Jki7;xsP$eCk*Jj8Ae$~X;_-vyQTICDNY*_rN&MX*EXC z_u069O^NxLUIF)N^!deEJXKaQ|VbjLIm$Wxdtx(_SGwEAN>hj;`+CkmK^AOV@YR%UI3RB`}Lo$smuFB=*t~jG}VNn&s z@qWFwl6M(y!Dg5_=ZEBSH!q#=a_1#SkNhxFNB zbEBls$1#bka9IXbLlV7rloTv{TZ2|R zFc90L4?oq}BwtO^uE>aN;@-=vEO>nHhZ1R-(^FfLHxo(BgDJf>CW7n8C;4JAUzlC%{QU;DreWwqBSaDIaJYb;N%T#j^5U?}c8TqY zR-Q`R+rn2dH*$CnD|Tt6*TtR)aTPv&MlMQ%Eub$nI{*0*iyRRmeLM7esp2Fz)3@C zX=M!ogV1bIlI5**xD>r|3Y*Q89%nO~wDp)2Uyu!l(L}zQJzwD63Y}~?#&V2o&J?Z~ z^CSD7&)Q3}Mm048k)<$r@K9A zRs=1rGyC&IBhFzFI@N-a9X&=pWsG=SvCsW@bM2EzlR=y@KTmx)WH4K3iZMK4#1FYpK=1`tu%)Zk-tBQ8#N$Y{})}W9v4& z*sd@Y8mdf&=$HE>@Fc08(4nk6JPHN29fcsWQIXoUt9hvlES&k@n!O9`ti?*3r$ZhfZUNNYg|KFS%cj<$N@5C4GY zXPv~$%I;4qA4>?Nfnte!x!cB3XU~t8=ob6wjKAOp#!dj%KwZZz=>1&R}aM7MZLp z?OR|)Yii$hKsK7jd8B6G#+(M`uvvVA<9-m!Z&Uj7vtlaWX$ki4@{EJ%H?N&ELB6lX z;ZVE5T=*~}KZ9abE_Dicfp(E{tM=x|Ffs#rJ`QN9;?C3hl|bjC^V5-Hf`-Sh^?_{;}26_Yrw)+EbP<{B--^}Y2aN8$Y zi~(BpzJa&~!CyeTlLU?8&tdv%jYKC`Xu?BvJfED{H2lQn{wl_t#GtqeTXG7w zn<;f)c~N^IrAE$sy49D!5A4ZWA}^G5ysZ%-8>uPVuI!CdTzmP$?{1w2xm{ZJSy*EY zEi{dk-OHb3)VtQ}D!&or_hM@`G=bkazatEUV)~M6KT|Z+-Q~+ulmIfbp2wPKT^Q$K z{hwL42l+R?k$AOouPemk9V(EZ@rdPM$kJ*W6;mBMOCj4g8vA+C`F?J0IHT2O?)qM> zUU{*yLeBgEmF}rDP;_zGy&ZfK!Ah@SyP85CKjj4%nndA_w2Bsx3?-yc^L>wdPb^kW z$)E5vOV*M#CG=DS|KJf}p?trFhIuBiJ$a1dmE2|A)(|`6i|>qQG{%;?2PSo4Im;E# zg2TnchuM-CBZKI%-b+ub1w{zFO&e-kY7n(o!g}+q-kMQiAUpN58{lTpAaybG%iTMw!xAND3!?u*M_rMGyBLy&9kX2|({VPs(npAX z6~xcINqVIqg)#87J?!+aID=?WK*6tN5+Ff&hdJ;#t36$B}b_Y&;m9E zyzQH=NZt`Y=_w7-Rd?$B{Wzhc0&gLYTedn;T6=Mo=)Ne4?%HSWX@m zsg}{0+Gx~$L2|ZdbPUEpEyo3vX5+QNhO6pB3$pNltS@ekAyvD>RvB} zkNy0%AD*WwA6FIL{A!Ec0MLjLu4$3U-0AmyluoogU}3;(26PzXH`&oDE@|e`Vs!;? z`epok}kIUv#}yRFzvB_f1PlEV^0b0_l)Oy1P51K`BAHySsDIND3m|A>D{{cS<+! zz4so^!8gA5J>r~kuQ{*zkKbih9PIZ@D@!X+_r>{&9vh)IY~<=?Qv9MR;NzvGhvw(; z?9GMmTYPOr1ONJ+>Ho9$VHz;o8S|yk5Y;r%i{H+nvP8m_zK3(EtF1LNHGNE^chG5b zABrV=^Lh~_D1i#=f9k2fQmUMW39D5`$xnfR#9ZZIyzyk!e{=Ft&i~2pzL*e>++Bn> z?$A3oUm`Sw?B+gJ@Ue2aMY@woQ|@%0AxO+^JI%QOSWM#m1b`&Qhr8WnVlR;f&C*tTTZX(fec%rnUi7S^=DJ7_CfHtkd*feI8_U#|9+ zrW=TU_&qmhJhk6$o6ctQ?Fo!0!Z;*n8NMYBC(i7W{%kdN@p_f?i8w4(1ljI4?&){W z2Cv_aD^>}&8AYCx0t)yrD;Wif0r)EvxNLCHazU^NhrO&EpTegN zNkKnSbmkNtcsm$1bv2+BHD-Wj;AxxDvV}o35dZFugj%s)n4XW*F3oVu!&2=d?Nt0z zE)lK9CWH7B_C&IZnMCa*@{hLE;A6_U089in>5u_6I!qhy4a5a1jDrxh0WKl;f|YJp zMYNfpwjogcp%BvM?ICP?@3ZzENxvu6j%%1Ip|7K_XPwT{K7&{u*JK`|Dzc({pJni! zP{0|j5OU6GtGuC06@~uAkv+x$1)E6fCit^g3XDCs>`pSPFDBotJk85kzhtw_RVZf) zXdChW`Id6b(tNE|&Tvu)KOr9@ei)0{Q#4x?(H5-SUG&h01M;s3<@0;?^q39NscEM( z&uRj6FQ=uSDP0QJ@qYY)3y(pVMVX7jj?Qmo`45AFqUjXkH%{<^AXkz{znu@CZ!K6y z)7jOEI$u+Ny=`KF0ERJABp%?#_mvGJa#%zj!6RX&qNH-iO6*R!3H>`^^3wm41dFTy z$VWU+nyqU6Xxs$F^-^z}#oDwHirO%HJEj9^TKb*5uV=r5`q8+o5eN@zztJT_?tScaW){O#gwys-!frucGl#~8C+Fnfu)4?9q^UwNn!CyiNc-0&$7FSEN*W!7DYjf| z6JH_e@X{8cjZfzrk|3Ear@S-XhJ2P;BAirvgF9c1R*{^6yuqp<&^xxSAd<=|A#6mR<=3LT= zWgRD~yXPoasMI68)aXGh=h$8p>aia-4xtsdt`yUkA6d)_I=Jbm! z0;e+%GL`yifew?Rqg!Y%P0i}M6TjTXK+f6Rq3dz zNr~2|OLruY&;KgM3qooR`AgHquVN~B@AY7#ilw@bLoXaEl?9pFZ#_+HM9IhfdRQdb z=CavGyVUsM{zal5{@_V>Yb)m54Nr#cw2 z%v9B9{W%qv-#=_HY2{`qeIA$?)JsNFDku?Uat;1qFR#xiTfCEqAtoXHHI&yGte?@P zw5}|SJ$}Auci|4$v==gm;+V2{Dk82~fAjo?39#C|?AX7XN2CiHc}QM4v=rKE-apOt za0*LXhm!%eiw{8(eyB_$%`bSj#5j&wc!g^ne{SIFWdbe2v$yWxhX%Caeb5VB`5w;m z>EnY6AxnYFLGWCcJP{JjxVwpo^xi3`Xk9{(r<0$9yNDhfmL}b{SuWE1gHUd-jmjhT z;ktPHkdCE6>sFVx=_@z`3GJ=S@1Z1zzxM;~ME%Ut`_^jIPBihA9IrvK_1x#WSo1J0 z;GXDA>abBmK*rf|0j@&4!J5uU?4O@>(^NS@$s2aK%;+)Vc!bQOEu(C_>9&M4M#J4= zxH{~Yj)^qqei_VBcwZc9twtd?*weo_1+$%6>6wmk8NSH%%hO2k_V*!5PNc|_ulSwv zE$sItOLh;kI2eIftMrC$Py-K=aQilK`*P&~ne|Vg*H!$R9Kv(J^#Es_rn028V4;_5 zD;Kmq)jfG?_I5Kh+UNX{_JAD|XH!CnBJF56c7Y+(zunHB07KGM{1YF7Xi{ekgZUrm967v z`t+p8LpGA5Z@;2lE(R8W-q0#N(J|KC#`;6WccMaZ88p8w#BwqUJ|U-w70zjU+py$P z`-)mArpSFFD&q6&poy}&IWC|Q$GzMmFzoy&IW<4!5+o`zH?bcA(Y zCWg2UCm5JhrBPcn!*K7e6R*|O^K@ucj!m#r3B}v=*PP^JSpHfOcUrs7D#masB_ZXuFZ@fF+#P45qqdfM)Satlf<7!j ziV`uH-SGyA4-@)_f97z-VIuFsuKm2ItBHtY6eam>82&UGskjoY+|^lCqmnD>HbMj? z4P1Tut1r)j2(^k&IWFS)u6OWvx5pEXvLEQY5dD0`Z6@sdezN411Mw5-6SUp0mfD#) z9_5yb-@Q1@l1#b+>1u>(sDUMP`7(k{rcgLLH zsT*ym&lrvu)U}F*y!w8~QGMAP4zl4{p+RigKzd-Gk!F&aB7FZzM@OgShs|rgEuaJm zup*%oPL`<_lJYs%nlC%{!jJx;x!6wnsQ%AGC9EB)Qkq%Yg)B<=|7 zX9^j@`YkSJ*?b?3t*0eiR0jD%pr{czBS$drv`CSx?C0dX^CvUYq{{?F(fsyuW){EU zheC|XC*>lFW2D&h&@FNzyEeY;B<|BFv2_3GG~O4|^u5+xAR-9_T<(DvW4|GmXka91 zNU!!-hc$h~b-&uzAust;E83I9@HzZc9~#(}0KS8w_bPvoeZy{frE&^ z{CuiqJs+K%K{M|XUy<`gg4b*5b7}A7F1s_uI&TcAv`o%~8%`SL+rfsKDgtDY6it&m z1pX zQ9cd7o}nT1aHc2QVxX|w$=c3tv%6ppO6VCLgdH2C^CaaKFR?wmnU=`rXF0O#Npycwwzie4w>xsZ%Ws?&#|O=fLrsUrQ#FYuYAw-*4kSWZZr&Zd?UX zXuRX1z51YeP1&+CB$-S(dxU_hZ_b-qA#waK) zb+$_glYM-_D=850ZB2_?+VHf>SSE^Tg`VaxKBhH$oyd&O9+}5q?o4(((R)C_`pScK zyDrK@6CRoPsD0MS%IaA(mgg?^^B|Uj)mXVLx4Wy5fbtOC@MQQhbw3U{*u8~}Y?Em7 z3pvP-D%--EebmH&Tow%lrv`#^v;5s2m6!QD9r;WWm4|&boNKmO_c&G2E^T;FRMZiW z`X6jb+-lq5UE^2cY04#_4HbFWv7mr`p)l@;7ZU#E)Y3zkvYHh2VhaNtSc&&4??!Ot zOe1lz&6ZzZ={nelmc^Q5gDCyN}RcP6B_% z^Vhv8G89F4woOpk6)S|aUA;RHIPH;si$5`tD~c*IY^y6r5dH9UU1;d$dVIRvoG^Ge z?>)7A7b6*Dt;Q}1AD{ozwwAsg@_FP+*u7Svd8u*aE6hs$?~<5Lw>s^5KQW8sxY;Em znI$|f$GVuXM1b~Y#w*Zj4$bnoYu=*~yc7qZAL6TsY;M(UEAdiv(YK1Q|LT>3{~dpW z2>x|t-|&jCL(o%{eC~YCMfrkf4sTy!yvaXiuorrdby%yKUR(PH2PABkH_{%>Mp(SQ z{@rp8qcDt&X4Fn~gYCQ2WOiZIyv9e*Me<20!UMg zD}`~xWMJzrNNfU-d1_u4mj(@@sIv7btl;=aZ)5@9wUWToG0{n z%&NHjLpFE(ZsQG@@WB+$<)}0-_2jhO^PZY&*#uogV;hKs<`x`SC$Vb!FVAN3=$TIqfU`Dg%+p05( zEai>_kIk*P`~(8|S*L{3I}Jo&fS27tx$#E7_uf4gu34`yzy(TvM);oFa~w`d*c9oDod3fTu2$pcP5(86+#x&iKD5<400w$BU+vVy) zK9=-QXHHel z>-$r63N*?c5R2h7gBnUwf!)^=o`~^+naTyewyEF$9!G-zJC6JtD^L-qLQV@13&f!E z8yR$C2lO((qMdpR;ddrjg<0DuuUbXnH{K(J4)=K7&*83ms~Z^;;CS7lPBH6iUC9uB zTEBdPQd04g+E7i}C?iU=&zzJ%(hyN)WSWG+AXdrUkMF_zEBfvP$u*K_3m=pXYy+tD zJ6{go?3OAMyt*DK(JR#%b%dWvtf$fSe7M84&qN+eG-ec&=;5-V!iOCPuH18vMS8;I zU=v6}mHx<>cU@3Y=Tn{FE&u~r{-ZsYvA?)J`GJr+MwV>NM|<^&$3~5bRS^d0K(}s$ zK0e%}e69dYvntW<(++(jQXn;T(Ol`!aeoPTh{VDM9e0KW!P|lFUx(;lpyJBh4y*s) zu9I>O{|=pJM?RZVyN=g-S3sQbgZ1JM8=xhx10Y5f9|nI}bl?4*u6;0cIq61=|8vh~ zxQi0zLPh;1HW)&n_G*H11BMZ*cB{V+VJhF(4J8WTD>{>juK>y>7NhH-S?tqSur}Oc z9yW9m$Z`AEu|cK>In$!m!bY;=+|R)>j+uJoXXiaMxn7TNNUc71{q-@yyqnxtCI|c~ z@?SQdmL}Wz!k~iwC|xmc>*}U)DsXOh_hzJXd58i7C+HZ*&Q$D4ya%DR2C@O?eXZ#c zd>AXxhvj`#^{d{JS;^`j+{I}dR&b^62Xsv1b0EH?-4|J|-k;w!`!Fs4k^A5I>c1Gg zB%Qxio+}>R4{t(5bc7V86S&F5B?kf?jXZTus}@z5PkHCXawta-ErrweQrRu3N<)3# z33yBy+`tfTvM%^fKQ-Si5M&CsFY{q)wNVZg3KN8#fQtd_)NYkn*AHtMAwf{R=4>H4yb zQe*<`2yNy}`HS!MgR^_G%5b7x+?wOO0s+ zcItP-DLV)L@NfFUbO3Gi1`hRRT;Sp(qg)n4l2;)i6us={f8l&cc ziI~q_?RH4P<3`xkRD?vt&wKAy@T)o3i8{l7w+ z;%1xU`Fc0dEbFs{0{~8l2c`d)Hk?nyck2Wf)G-<5DHq#iS^qwdTm8o#f!ToW_;muF zO&~OzN4~wuXrMES1xWPo>oU1_E~Xr8owdTWo(dQ)E1Eea%9R4(UIGzU-p!+VD2a`n z%ilL!&XML9Y@GlXxzmJDHT}GXBcXB|(v%MS^Mv?#s}wBs5kOav#?AAKRIdB}^5Hr^ znV>#YPH3`(CXdP+T#pj+j)h5I7o?(0;l_^w{%?`GYv$lU(C zh}(g#sN0CL=Ijc#*#^N(GDJGEY4bo@-Ih9adXL$th#v|>3`pJQ^n@;Hx|>T5E84dk z%6-xlDf4HXC-EGYpIg7yd9Ry%&Eb$7?duI4(zqGrOq{Q3lw+2Ok=wA;qQtH-Srq2| z@s&NKKC^thw>y{Dnn>;ZX$y3yv;j!?cx-<^eaSYP`_`|tb}j0UL1xYX1eJNys-7P$ zWLqBXGg5&(x{^eZ9T+mVx`WI-QS6 zcYQ>^h?fgkp*;3Xtg&hh==Xe zQCnAT*?fz_Wg|eiG&KDexj23b1+JKCC{nnro{ngFnh+T3 zRKECWP?Yh-w83DS?rl}$GG87Wy53U;iQRl^R0#Oj-DtY%Kz$l@KV5Cfx<_dEgWYdp z9U*MnzJ^|K10@Vb4zm*_&3Ii;&((fmU0lQtW$y66PFy?(b2iP;kok~QIU+riLNsrS z1(SKN`gtqNAeSPsUzJ{+G!siS34I#lLFY@0--Y@7%)eJR-v6%d^!Fz}dJsC>w=g!q z*6;hHT0Qk&o}4)|>fKgompRf&tBp=N7%@3uPUwec%Rh>Cyc&y{3ptFn!*qC} zePG%zj|2LxB}zFhST1{Y{?*XHA25bPY+XJb&JQnaLcno60z8oPB^|vq-ZU;ETcf`n zVlBP1_(bXGD^+=#V=BRJPo#QhcV*HYCJ)nHb-=kwIAq}I&X_VSx+BTw0Ci8!h9xzK z)>$!_7xEl@k3S)OB*X6VLCmr8RYu88YgsHkT>wrAAs2UY?DepI-l^mb8J&zZtX?nm z67pxXLdyY@Pgo*h!34RcUD+a>R0Yb zhov_7`l`5l#t7ZFu|0Z`Ic@WV>ynPD8qIY$zz)m%_CM9wHdM$47_m{h^zt>mE@atl zrsO>Dtz#K8C1r3tgjaQaoxCvKZpqe}v%Q}1GHNcueJ}0uj8H|iy#gvKl1K1%;2L=I z_x6(_YIj#NyvC+zKOG3v5!GqG(8V}zhaWlod&gWrn><@xHZ9!{`YZN1U6 zyg9ZnSE+U0O`g5N@;IPnS9>}Sg3MTtnj8MCB*EsdLYLsSoDRrP_cs9vI2Q@B#SN#k z=6RpXHb~8?ZoLU4s;uA*$84gNP;lIHoA;usE!$r+^D4|rmHi_l|RN=$&gldIV z9WQ!=f)>2K20vBN$ruG>7zk-p8jO-v>q-vF82JBM<)Os*-RP=bLDRU1v!U8GA_r#T zqi(uk{xATffs9wB14G0(zhP#|)KuKNquJrEwAhF3C9E6SZ?axd7C83*cVPV!eFihH^gpR zLi8VC>R=W+bnyiCY=K6ua$>|b7i1Cl7D6MJ+ZE^V_%f@y?~I;BnGcO{cPJgfVw zZ96J{I4u0gL1sC2s9-UdNKf(zgw=Mx$-SVT2S(3ivWeOG2jl2p1~%?di9F)q*Xe$d z!7fse(&>OcD)L%EZIQoh8M-yk$jiW7L;Zksu(-@GdBHzqRCh@PGZ=+RE65mRy&0S% z2E#OY?1i01LhLYjtSmcL=E7I;q#TWGLZ^$gc><=J)7n=-yJHs4W`B|}V*8^ke$t4R z2qdC1h$~Dbnh!aL#_iRl5%#N05Z2M#{cbLnlf8AimXsVCQL+Ba-79n%T}f9-oxHu9 zv0TBkBWeRmuwCD=Xz`6W)6aUvWj zTs)QPai{GMTuT+lkVt+P=Ts+CGUkWL>WP^iU|l3%fZo3)qACSkcH?Be{_z|!-Evi^ zSR%G7RB*Ch;4Ha_-z_xepa5f&+lAoWrm-6-ROE~=e^hd`Kj)0@NVEPyBJ}Gt=1N<(1=ctv3|PoQ$swl zKMO=%N|;_$9q5WjTXEyr)RMrhCFZkoc?*K<{B?vH&>4X^Ba{IBmoBGV{+&0L17slr z1_cxPn^X#DaCPrxkv|K+&cOa~f0~}n-Qz<=L83_Hb!MU|By|4cgwH#!CDazK=(O5% zt|BcXO9(-ABH9l~JJD&~h1*17;{n}1F@2T!zcam2Wbpy(Il564 z-UCwZ>jQrByh)JWwsZ$tCy(6`I4`Np7Vb%b1N|qi6o~5j@GplrObS7`t%@W>k^IL& zk|VuyeNVE(?C@oG-oH?BdFOtVCr28TF>#(8)r`<|1xI5#mCICUDQvCLD+z{*YrX4v zGjoTCw*2hW`Mmqk7Xn1Wi6?Rm$z{!|{=qQyHoX0ZP2%L50i%H?QP{GBzc3e3oy1+S zJRu4VcF(5=v-zbnDv(&9!JVnvV*3cCzq|CGKTKKHGee>s+{Coc*w33v9*n}{FQ;LhjAC}C9kd5C`?bbc2_Fc)SB z&~2u$TV1dp6w4>K*A4e`_S5{Hz*;D*ieTXY+Pig?!{IEpg z{=x3Av|BchGV0~D{AuHZfD0BLj>qF?2FDTwt2Q;&?-o&?UZjolKCE5CmMRThq8YXh z%WnaWP9;oH4WhVxhwdub`p{dRXrQ-|XOf2%L6omRq%#Jf0W6Wcs19Z(x;j5C6ne@? z19kALwAF=@5~F(e9#b};Q~|L6c6pV69UwqXJQN_b0+Gr>02u)k1pzimo)6Jk+Efs3 z3bxFAjV?9qyeUOo@a*hm#6e9WW6C+|c+VHYrR&2XO>wIP?#}2TptQwf${mD+^1XD1 z6QKh^)Zn8>57?p*k1r&Mz2v1RsI;RCZUQKxOKjvz71dyKGq^s{7f5QN@VWYKUgr3! z8zNE)?a^!Ol z;O3SRm|?mE02Mt9aAhQKzF<^f*3;g9!^Cj)62rxNx_>K-$7E`%pGdco!237A>-4@% z=esrz{i<>!fW(-PrXbt&tkjU*Oe9PCy4k0nNc$Ken~qp!Z>XEw)MVtNNoVR4FcgfU z_O10SRhoP}5*FV4r6?x@L5Jv{EQRBLpdAB4Iv5wSxdN3f6&$Gd?J{+v6J-mK=D3Pe z-}ksH!~`G%dUSmqo~}HeY~M7n$KvW$>|OGu$+5NC9HHrWgK*W;g<;1TeXlQ%J2~DV zXi+3m+pxA0s5`^JmpTx0QD8F&LeCc8S*4MzghSkx9S6#Zy3q9khJud;Z9nbk4}LhX z0$j>6`)$eY-!%lUIP?-Z#hG((XSlNl=g>@C4xO3nA8IQ>awWB_zFyZL;b?eashI=j z2G$O&ShutGI?Wg0`Sx}RVa=Ob68Ndvh~UZ<^gZp*j^{Xkh(R!R?|z-r{@9%VkWBhE zk#TzvJXiW7?!#&78{o_KID!tJG29Iu}w+k^WMdD-6l&ObnD&46GT1T3;XqBQCPO~_Ch?A4mCXD{Q^SxbnnEZ zXnM+`l=je3%BSul=s?-YJme5U#QaZ9*95ZJcj;SCqA|SkOw6_>OPwU^)5saQ+)+W_ zL#BLS2Zy>i;n3GVv-f0!Q9fw~+Q@iH+k8D=h@$GI-FToy+m$5)U8z>-ebf)$Ol729 zdkZ@%XfVs5KJ3V>rxC5i`@_WG3`kp$yO&T}HeVgAvIv2<$SkWgkQ=P@j{uwK`>=5qMzN6T`pK7n?4A4&JL|8Y30sM8hV)_fmP@G%(s ziTg&o;GFhyCg>Cw6W=AL6q`xgWNTKKV|$$PWjrIFFIaK7Vv<6SEf>G^374~4;>e|1v19vtorGx1u~=ULNY@EM?pKZ z1^S^M!4{{yJBD5{@loEorG?>YFE6C4a8;DmYBU}bHD5bH^7&yCqBYvydU4)cP~TIm z8K&Q?M$RIsEzU!$OY2+~gvA#bLvn%HDJEZ7Mq0q_30Qom!)m)7J|TKrch}m@VR=*` zB$VlmDo!rkLK0WIiHtR89Y_4hEy*k=`0yTQLJLz};Klc!#e(vA3dz2nv1GnOAnB?` zfzd3?+^?j$22cY*`G0WZ-h=JF8MHOwQYw?P+oF@uWx@S)z)a@wx5{<;q9JPvp@IDPA4;+{(t96a0xL%Vp9}!bmc}M^@Hp|O9 z0y;pAM9=*Ci(>O8G%3;u4h5SG{V7xeQz?M`=HX~M>jz(q)SjBZSV*v9v9jOr-lKri zW{9cjD^mI^gjcpe;t^;Ej5ny%kc;n2=;)ZQ_g>ek_qD%OdY~Ce5t|2$*m7xdn+!%x z-#pglEpz3}9{_K(w44dt5T7Q~6}45y9pE*b)mnjc8GinI2S;x@4kgA{4rYV8*>i1joduKiY6aPuyk513ABn07Df8e?#h9kxAtn%>8PRZP4Y7y+s z4yVNF)G{+ASk5k$L+##HXxCH&X?K91s|IjHSdBXX0BpYo_y3>sNT4Hw7_H_&d?@SnESck|B(G8b3SyZZfiD*i7!M zU9o6*&m-|ZD!L!D-^z~wk8fG1Z~If7%5t?~Kb1;H+aEF&*$w%9otif12Uq`=DA49& z)Ax!SDEDR@|6FV1@nx8v)!5-`VNl7%lhz#NCMw<_^BLxFOpZiru@l$sLly>&}= zu`D-t=HFZ|iDsJ9EQd(ni0Se;boczsBJp}iEJfNgZoK0diw*>23yDePvU#bk&EgHF z0M&`WPNl25?9xA4@n$vnL4|JEju1%OMD|gx&FcEv3%n_m=Qq8lkM}(I z95VSL&$4*HPoG^e8Dzk^xB@N(LH5YlwZPop#91#Za>fz*i!zzB?yQY?b%@j5`BDTL z9oKR!tU7xmAq2egd&G*-{@bx0XM3lH?-Pc9{h>>TYj{06*E{yQizJ zzYecVu%u`wgQFIc-gf4DMlD>Ns&2<>on~j+Q2Fe=%^?EI3_xez{t?CMj4SWJbPBptMWh$|Xrb za6Cb_OqN{o9VZj|Fm3{ktZd#HZny7?Ze)?JNQ&&|-%K9*0S}arsN~>yPnpfKq9;&d zBmon|TVGj~v8>};6*8l9v-7m|!?!@&xuPztPX+N}W0@Bj;u<1iK+<})MVZ251ov~e z*24hF^s#k?b?OfoBAdGHg3jD{VOr=Exkn!mP6<&f?O@0~Q|&L>kxzSw!m~TzRV4R1 zUO#D+=YbMwSNt4tT4hq-MSE@mi(tN-3aAFoRf;GAK}D%RHAH1d)-CLbjv@>mqXzKF zUng)z>C~AIu?^aXqiiPz1c-j0nlDwtlaKjHPb$tV#|XYg#V+VW&nJOxa{^Uh{r$NV ztmNp#zV3BHy3RZC=&eX*^?mCJ?G2sC;jI0pi=F?ugF@yNj9F;H>$t!RI#DQ}l3Sib z1-<~~gPPFUIVlY!VX`+~{riK8QkBD~I!ao8Q!a{sveTJkcFxoig%Z-w3U@GTV4t4l zL;sQPVji0Y+elKZ49g)sa|)v`|Zq(iMrd|NbDrB4ztbr(b7QvY9OPcNF&U9D~8% zD3K9CYY8@j$pBIgyxoptJnttTc6MT)WlMQOcZjNl$F`=IBjlEPdpiS zN3o-rgTf?a0-D+Hd{~?|W*HVj`do&O$JAP#3IT;J8*f7BmXvWU9GeQ2ATDA!$* zu3k)h0Nmf@e0u0Kc0RyZg1xw1b8aPBIqk)iOtW43t;mQ_6r>b-%4-=dNQ3!~#Zb>a z)F0qT?M5g`*?P(ccR^wyjubvFdb$$u@N2&BZf~YCe#C!kS^2sYkVs1p^dfJ>I){|Mw5wvgWEIhG8IK29I#cm)xxvLufY&L9>vp(1%ztQZuoHf2!DRfiNDVUTf zVu%m?X_j*=A)qqgzFmFyMPP7oziyXS|O zrZ!Nq{mSI?s{(Y?d|T|g-V#q-b|SZ~fzfv~llG_Ug+&RO@bWbm;if3CX$=(@vQCar zYduA!H9cSOR=dG&e%BFT&3Pink_%-5|33ih*$l8UHwymCoEp;kyBI?S2`O^C+R!-)^nL`qn9}Gbgs?RbAr~W6Hc{R9iNWI; z>)A=*2kpfUlY)CUoas2kT*a68Z#% zC-ygfnwz-{BaBCm3Brt3E8hM}G;(U_Hl+9xOSZGxu_{CFpLtBcf*S(bxn6O5?q0eA zEQmDz>-Km}u|y6sC{HGwbC1(E#9Yt^kF)l?NAK2|BGI#B5dKf!2bbjWoPVeV0O31{ zo;98C@=-D>mdW_V`sO%!Po+SDbIntpTt}o~rEy}c44C!G(Bgz{{#fPt+yHAiwt!6s z1M|isKSMtDZ?~fWJ4Dp<>r3{V)JtSK^Qr7)+kVf8Bl}Zn;dB9%;%{12at~#!Kt{q6 z01!JCjsc|7?zc_{uskA5CEeY?8-c=R1F+&7rSBcziAAm5OR>JwPCAZRGb%`KZ@V*?;hm`b;}sH>n)m)3B4-E`>K@bS7H;xhIF zi&WBq(_pzdYG>qD2)cizTW|gW&encs*w;s+(@eS?+w;UMr4O^iM-)>;1_;CMJd(^{~FIfORqDV#CY`i z&pKOC#6H$rVEh;JVbLKRIK}W_{+v&Jb7Y06@xv}KB%v}uh@!_mtm(tkq^sQ?QkaHY zt#a)?UND>1b-}q(j-pcbFSo~P1ZXUOum<5PI|=FEOtB!37jO>)_l|X~yVyXcd`}2Q zB=@tsbF@4c8E7`KLfO$DK`vT{zPAV9p4Kt24WjLi@&zokO1%wa|Jj&LG@YVzc`e95 zj>CY%>T`8i@o~)DGPGU%rSncK6P)(a{gO;qPg;$GX~Ji!*L9mUAbS!bTF2_qeyVxsMIBCfN+ zl^yciP@QhiVK{!@r#k?7Q|~P;CAH~swXd2tpt*w$H=w;`dFjHn!on3?W1Z_t$=SVS(0*&jbW~z5h>)V>Als5m@nSlDDoPD%?^T?s(@c(ws71CqyvxK zQG!1nMZru^5$HtU70#r0-w?xjZ3L~Psi#BQD$U5^JsDr>3@a1WVWc<`yAWK%L)~+u zNX@_y^-xWl<}D`WWa~~PUf3yEoIUGXIl^gSBd^^FR6g8K%Ag1vx-*xo%U&AS71CY_EL4a z$f5C5^VbV=-C=5KH(n+8|Cb|>)8(KIe4}6f*=hl8I#htc(xYv${^SS+dbW1_VXjBR zKGD^NA(DVsrt)!+@#UOU@IFV_(E5XuYLHIF`cl1Rv&{fPBsTGT(#I@^Z8j<~5R<-^ z7OUf7az!?Due@4T3ZP-&9QOsLa66C-9H5etQ{(Rh3>BJf_!kOaMlYw*m*X=-o_4#K zfAw@eO~3s->h*)X0H^_ebP|C(kTJ}E&;wbMB(E+}`ol?EI872??zO674TttfUz6~p zP8Y1I5>A8dtgZfTo}QxUSjUm8EdaJ+y?Is5F|?e*BlrRTOZGzS%#c$ez-Ys1p;OJ| zN(gb7~QT}iOtjv^? z-?AE{oSP3bV|d?BSuPp`2Zj^5rxZApoUlFh+{^w(t9+UXgDhe=Ia^~ccn1XhGks3< zh}`*Ge4jOaiL{4b`6}j2&nKOl%vPu4?7eT}yA|x#^BJyi1A}0I>^B|bwWu}wgpbkY zcQR5Zj=V2;HKVTy$CzzI;66?r7Cl8ANN&U!jwgOY)>Q8MD&BPdw$(WKCeqU;aeLvT z@JLM-`w=@^{s9O%JR!w(TN6<~E^8r{ay0`T|E?4_K`1f-rL(C;5*oOPHUBD;=>%(9 zI+H*wZZgiZ!S>Y1q=dKH6GJooX$~}YcnO3*k>{ogPt6N-n$?VUhrRWyvx|l_MCz^{ z1hQi$fvG5Zv#d}`D>vBocRT4KKJzpbt-DP1BL`(S!24Ft+Vv!^egip? zPB1x;o)HQA8|u_x%P~mdOQ^Z+sPiYHF9P%4JFBO6-g4Y~`(}x#Y_xdrl*{JpieD%C zNSd(}n%>!^PX?`gy-~Zl{_t{h9bUhJJW_9e;QzkUV!4RKKH?ybqT!>>{yH?6>TxQB zbA>de*?fhJU^yru9s`xz`>Td0GXB8@`rP=(iax^@4MDU162+b}XabubZP$kSK$(ISj~Ow45V;}8Di9)o5YAGm#WFJK*gze&4tVo~(OEnL6`Ned6y@leMkst&<7oa~YywDQ*L>^az9?D(noP z;fFlG7U9Uv{^HSgFZnGy_Cfhu-SzRLJ@n8ZD`30kUsMEY1BQj!a_2I#mkabEM3ylY4pMsGXB?JP2`OStCGa5fKaKctepZ zjXEDRd2mIo?I}ZGoDV={zUUg7WDjLQr02M(V+L6(VCI{Yn!8Q0j!A0->q&qBO|<^?)CpBT30%lXYyRz#`B>!6v-#yjvsVO1Ves~dG$(znHWbhH;`n@8^b7QQBh0=K!J4wZv%c@i; z>J8trJ$H#@vv+RlC$`yPQ_aI^QK?+%YYz*}VM*wzn%8A3fm|=&IN`LYyjJ^+`WOQM z(4kMFS=i$J)!XZ*khmQ;I4I+ZS`4)u^NCfbQZ48M*g&n1r&2^58bFC#H3CF?71Z_m z@=n<{83IPkpBH@Q=1^0>b0KXJWBYoNn1crS^<_64QQ}Aj*4j^QkYO3~1CwS~H-nt~ z+5QoFwSvYs8WMhMQ=hEF_YCc?J!qTdUPk9r82zF#`@*hA?#TEB=kkPA!hs-VJA{^r z6J0zw@AH6g0uEo4w(rhy6K;ZiA4DRR_8*zHQsLRXSz=XY*5wep=#A9gXdt*J50+^+;?6C;!7; zt>3O$R7<0X*8?wB4-5Xo!E*J2agO;Ta)%#8sR*f9feZqH9ZI=OJW^Mu?88{*i6IDY zcLUx$J>EuH8Tdy)^`JA}_r*u>#WafU9RG)^cVO+qTWdXl&cIZQHhOr?G9c zN!p;Xlg8F_eSi1Nf981!naStcd#`n##{nN#nW0SN#rzWR)rS!j=SGTvRd@w)QKiAi zYS3g>;s|6Zp)TI83eULVRV(to2EOV=KgfF8Z7Ip=q!{G8d_9|E=_knJ0z8$Xxgs(4 z=eQ_KI)M4cWh31Vvd|=>vwrdJ6wt*UfAe`bV1OfDH}3aq$w!t?jvy0Wsc~t|ry|o{ z)pQ{(qk@lAEHo(KD@Pm|xr+>+GAZ5WB=J`R)d7b-l*?|>5YFE?;5K*cUFxG(t4c~c z&bH)z^NR+vgcLN~JDU5-`6mC5Ss9XJa) zDhyNC>I@&ykw>(nu=uIZ@SPRW;fr3fijA>opdiunQ6$W*cT`kij9i8yYdjm@9mHue zyiS@lPLb2V>Dy}B0&NdGmM4YnIiw}w!pWfuW!Zcxury&hkb=`QVYN5lUG4EZZP8-o7N zaRq2>5(lqJo89TphTa4XFLl}z(wP`%cxAB9{s76U#EvGq{0IGDKF?_Z@bSAQfNaT>8N;*N_k{;UKf%) zjC+{`V)l*pxBGA6t98S^z-`%bHtQZXk%-+q28HhEDexR*+7ma=8KU5bx<@U9}c72w9;mKux5o0eB4Pu$cRI7K=qy zD;Orzs=)-gw(j>kw&Aj$ngR#v=F;K?*V|_v?pgdg52S>abAd$HP@9+9ZY*;dB@hQo z5l%;itH@!64@@9HyNS`?U+Pv;qT%@f!zovbX9Kqxg7JIO=aJQKt40L_kUP3VCs#@Z zSYTBy5uzg`2rQe=5OJIh^$<&~$7ItX3gMBy8=xL9e)~=k<0B9g(z%?rToTEd?K1D) z&KX4aulF@rXT$B%5A8#u^9H=6%usSsmc!vEL**+YC<`+rW)s3D|3umlZ^{f1tOMM` zu4h<~aE;Cyotc%J{rgiXYEL7t3tM9}3wA;NujY`6o9TkaVgo^DMZ!v##|v3)hpZ88&j>_(EP&+?jF6^IPaMYrOC2{^ z-`9S(N&f|fpsWbQVXUKN)Gg3}5(y#--vgesB}Ob>IQV~^Vz6GM&hmI1o`b=mm)8KB z)Y=FrIFyqXU~fuY;(PY}e`|pt@j}+ew=0*P5HExovnjDwpBwS6x8=sd3q*eRX~aAy zz~^Bz{{F%y^LC%im@S_Z#d^M?Y5oQhV=|xDa-jkl;ChJWkI-HN^i6$&Vnn=5P(6ph zSkv@K39=s#WM%>Ds&G0SCn!H4*m_RHVI3BDbX6XRRJ8rLa0LUyX#o8%AUh8Mf-jk? zJRY(>VHU3d_?$#wiv3t5Dy*xh=#Xr2Vr3sMOyG^aS!%qW(RYa>6GO>n!r@BHna~Bk z*=t|U!~JHfK{ypw0Pt?ahc7jByN8*FuEdkxo|gPm9UEVVjhiKu)bZ{vQ|sz+GtQ2GAFt4E|;*a-am6>`N8)>nxXX9U}Io z6)X?;wGYB{m7*`or_DM4h=>f#<*=4)!QplSgcB_k(zoAiJ>t@$W&hM@2mtae9ztsI z9*;_5mXCjYQ;>pn_+%o3!(w9XTX95}8rm~ZffWnki}M`ny?#2nBA15xXKwT(u3FXR0HXJ)g77GSB_vP#IlH7tV%Ev zFLpOLR5@Nqzi|Yd7%`iL2Nh?TZi3*rXrV(RU1%OEfG@xZk$rUG+jl_)G zRe$?VQFcI(0-vdJy4=EJyF$k*F%kllJ_q`yDF=Q#ck|9eSF5Q1?$InreA|OJmY4hF z+GL@UPU*foCJuRDYh=Dda0P5u@x@rm!E4R;=WEEG+x`CL9aHX{*; zu8H7Hmvc9!cNQKSmM{@Z*amPMS486p=WY3zcI#Q&(XYeqQFESH)+&i@VtjY zzJ`;v@PH$g@VN-%(^sWjr#4XwT_yYh6NO08f5bzo-DhR6nWGbxBvm4|kxFqY zE`?;Ri}y{vW*;z8xa5gqgzh=ZAd+!yzgO%toc^+203hh5`mpf6xn=;oB3#uF3~)fo zzq4Bw$WIg-TFg)(lQU?MRGRE!_!T+>3hBGj!s!SQ4%V8V`}K|KLs-4bG2(`DmPX!gRP31&i)K(t1rCfSZ&fSP7QEnBe-`If75Yc0ybH zRR?4~rM*VU=GV_=4Aps^GFL|S7ZIa2grS0=$V~0|+CPf$?#4-@=`aE%?faUQsOed| zH?VHmowzIpV($w*VWgLNC`)Hvk!F{eBX@D?Ol5h;WK1uK@_Rh)-FD4bXo{R8&ZJeK zu{yR=cn2-NWW(arPQV)E9lzf|1Xhq_#M!KvvD&Z3nYT%ni2cN6nboYLo$dC2ZBp=0 zr<}3MAgZ9Evd7BY4x~N+o6t6_oS)~kjrtvD9k^Pj4Oo^Pf&Ior0^vi?4QZ6EuPaLi zqizP9xr_?@H_+dYM_SGSZHCS#NyHjnSAEN;ancz&Dn@f~L_~juA6|gNS`y&r$O4XU zK%m@nH(T!sEKJIN0w#1M|Gx8v9^lsJO4LmQ2Xp~iPPl9+?(y>@>0$CKO~hZMSkAU* zvn{=s?}nYPi|ml{xfK6ND5ZE@ntfSsb>9ktwW+El0Het_Tn=na#5FKFtg{K=qS%AK z7#Q#-@4*pA%-mu2%|6AGSP$m*c!AiZJdfMC#QW~Z|9(qkDU08mZB4`!E++^i!WR5L zHwHT>$ZxP=zZf62ma?cE=4@9WUlPT1CzvYO4UhhBDpe#dJ5Bw`|Af@L;`PVIK`}F6 zt#I1+{g=F@SBG0gYYBOg>{hf|E*pzfCWBT>cnXjQ@sGx^^}{)}z&!O5y(6t;)kxiK z{FHE^c@!doN;CKCob$F4?h^M2ZopJgk1W+^q$tuCk5tb5? zP7zJxmrhA$k;dV!{PmndA#Gd;JkeIE0V+oSS0;@zrCOv)xtT4EEIF?(Kz_J!T(!fW z14GT{m|~QcgK$Zv#A0zdm6;<1#6Q~3r~c1@p-_9G%5RV9KFM_{vvz;VK$Wq%@x8uw zFe6v%$8;b-i$X!_3SL!i_a_eXC7uDR(-AU3lI22!Sm4q_oNze`ve1P}lu_|Co`E)( zwTxL&QGy6n+BA14Zc1%VuU&tw>jG$ma(XyVk4@H)jIuS6#4E9j~ zN?;eS%Rv%qZqjIb4`&(GUVe8KS|O}3Gm}nk49oD+3hEU@`7rv>kX;3#7*Bg!X3Oj` zRa#PuHBacfqLM|0f5sRvYsxN+4u8RlfZYhYKH+m49v&}~S}L|#QAKD1Rs_8BsvVmy z@Tmi23=9`QE{1R33|shpBUb=m2bBR&n;elQ*ufuMzCf<*xAo<^%M?qs;71!j^XcWX zA_=e<^7#0CyM>@6*Cs~DW)nYx)Av-v+2B>mPDOP~Clc7iU_#DdGC!EC_yBx1wvcx? zGU9()TpFuHp_jZrQzt-{#5)`_Tb4{hp=W-^0Yc&&eIU}{; zpXJJ!d;!WS+!QRe7@$bR8I;9V$~xQn6`^|%7p*2i&)1^fZt|`Z#Oej& z3fpDnr0TNd*l-o%<@^xj{O9r?uO?K`05-`6V&|Y+AmBtPx;7d`maqVVbwO3o5OF~$ z2~rS!WW@Ghs`cN?@fftmDfd^2JEa1D6jmwr?J+YB7S_MJ_!8z5!dpN@NnFUxpkCu! zb(=)ma|{%fb*xwP)}9{zQ;#azXCcoAETeeu=>Q)%v-{U($* zz-Wr!haF0DxvnJ#hF=QUZ{>PtH7L?J~bJR_~PHh3ma3v1OuJ9N<@cax8Ze2S{Z z(lxCnugFu)rqzmC5XX3>DR2QEJwLVXRt%K5>dSOxJFz+sR^o;B<-xs%LXeX?(Ik5Z z@u(V%u*odtQ$cuLvI^amst34!-!G=hD$jFRCqUJ8RNfxkP))Im@r97x$ijC0>-=rX z2xaLWwYLa@SKuJBJazsv+>w3Ar94UhZ||+Fql=gAy`(5A+OEvn$-x*zNtZ9Elb+ZT zN1vH<61hBTmXkt6H%`& z==ga3xZ(Ie0Sb^QfdGyfz2lAC4hPJcfPCIzM(s~J^_2RHzvKbOa2&+r>Oj{t>Zd2r zZ)b=+0$9>+Z3!xuo)Xna`h7&&m0326v7e%K28^C~MVp*9lXw$KC2&=s910shO2{1k z>_zmV0Wa8IdYfA_Z;du@*RJqT6)|gV#0LSwzw7Z;SjVIR=)(0nuPGMP>NRTcrUBRF zpr8nv|5<2OtiXbZ*=}epC6xS)hF`O}HrXv;pd;WU#HX|?WII1<8>eGIvhK6FfYlyk zaa1}zbPBv*1mYp=w3zH*XAY<9hbd$*sSZ%Y{00eu8ELkAumi087zEAcs(b$NiZ-uu z0{k*HV>-*`(IM?4`!+7A&VG}i2h6~db28q*&r>%oCG92PeSHl<9#@k~@o?F(7lG_5 zC8o0DIS9fUU@OK5;*E;74DI-4x&fRsdHytvHKgF-sg?M}Hp*l@L_hQ)aw zioBT<5nc=-go2g9ru$+i241x|S#u16F> z3(hKB_IRX~;3S-2t#-azEn*zLIkxv!YtTrImlDd=%<{^O1q^rEEm4;PM&D0Qj=>61 zEe029!-@|uQbutxufM{2LH2GZ|7)leuDv`%XID zbtD+keAZdgPXNm%=(CERqB4Wgrzp`@9I>k@311S4_bC!4*82;Gx?sS^XY2T-R$MNe zMZkBuAm8srAyb~v0B2P88+U$dOv1_x?Xg-fd?tj2Buh?6*Zn--p${w%ej-F=BA?gn zwJdSD3?-I2fbFen=QJ!|Oe>rs?m$9z`E{I18x(P4!fKR-*j6=EQXTF!PCi6CD#ytG zt~8zYH_s0Hh_Yw?8bDKq{#E#(B!F)AGC%lm4_!X&;$saMgnW*E>xV z1#j&gjU^7|{G?2os6Y`4-hb7j(Td7y`WITFZ;xB>!NCDuj?t>4qIUP;V8G|t=5H?# z(gK8&zk_3cXPe>B9{iVCR~U8RQ$9m`S)u~iOIapPo=>oEXmG-91o0+kV1PGAi=8%C zJJ8qQdX{GW9;{ht^YDK#v;bDew7hCkJC>pLVS1YpL{sHfV4%g2o zq2?MTkTi)53yr`AhqP>wa5FOTF-BDh1<3mb_A(E9E_3mBsvto2%whNYx;)cBrhxyY z9(ZBfuX8+!am?clIz9ZCqKl^j(nSv#FxqxmTo3e~AoJkJV%0uZ0z6^WY}P-lNDEVq z1)Y5gs zyt5UT7M^zFFg))hK1Se8=q)fb7FadcNj#I(VDCvM%)Zft5VWk40Y$N^Tw`esQ}+Whq%59u3R6_v_xZ+3>!vIA|BsL9( zA|Wd}!ejCEP$Yt{PsXbXi%r;wEcB2nqJU0-OhTf>F_(n|Z1P=fx>IpjL2hsFYX7Zx zPY{u@!JZA=KN$Njl;}T@yh=bq?JHc?$rwjucEJoIFBWSYU*AW{yI1rGD_@bR+DY7Z z9A+*@qmSp>B|tz-%O9xR^J{mtRo|5HVieTo!WObFsEB*P5P>=+QSD}LTy=`dkwT2j z9Smw;#Y9QM?7;4d<}eYF;@C_53yu)j<-YX~OJX^uuLP1ns98w*qvCd}4f?Txzyi!U zG7BUGc;P!H#H8fj0b_hqQBJbeKiaLEt=LgWgk^!oV<2;9|9ZqNje2Rzf#T^Ya|8D! zHz5eGX)W>$D|wiTz z`gBXidPYNF%0FQK^zpeCHvIv5FhUR;9kI)$T<^O{GzoGO7!e%V`91FFfk*z+71K<2 z0R{Y)G?{of#_ps{l%&l3wA6ke#Q7)M6fmW(0(tEmdsP0ED%0Ees{NU`Lia#R&$>2@`_wyODaQ-=M%#0y~O zD>x!KNQa7`94k%786lUD;$p?Af!sCFqS5IRLPym)AGkCTR-|4##Y zm^RFfzYrp(!kZKB(n%p)Xf0Yjr>QV=4Z9Po~VkichbA$2I0QgR@po zQZ3aG>8eL@)s|zK*Ig|8<;C)kUDS`zALA|k_PI0^HvmtXQ#w_U7;E+7C>J{{k{Do8 zH11zKzI>JsJ+zp3jD7bQLc1*p&(fT(kk17g18r2}sW_A}X*)5$f$@Mgc;`e!Ey4di z%xyS8fz+W@wv3%tuuM7{V)T^fo*2(e3}g>Lo%ViV@w$`OCLefH_)7pUpU)w^$Ch0p zGM7s&2a8p#iv*33Vn-)33d+c<$aMn!q6Eg<8q2x;y&UCM#>j(o z$VB2`-B`)nqGE)S8quUX4Y}G``I;kC-ej|Au$F!(@??r z)Y;nWkGFL}yF5%0+LtVf0O_F-aDQXKWy`x6dIAa&#K0bMZ!{VxT2)8hWPvoqU(PvA z_WK`}kJUBZGoRzl__$p%vqd0ds~?9Bc4UC~sQqav!8=Va$v!)`a4S}3lzLN`n=V)f z-Vs*JbBH(zcu}m@0@lto*0XC3#aLy@L10P1WuQPL#ISclEBh?JT6iy zRg~!lgqIlkW3nIWvZ@PD+d}@-@}e0uySyl?)KtdxG)-LOlB5scEns4DQ3IU<* z(qSejAdrw6Q`*y_o>ey?Nw23QJ~8IE@myul#x-?~3=IIGC9@p4cUbtzJm~8~@eJ&t z@0dv26Ep|^)Cyb$zD5{pw1iosK81kx^7CU4Aey#(1x}%94=*Xh)Kx$e06M);G$2?G zPY4s(EJ*Ix4CsH`Jol9|`!3plpAZRt=NL;b_M0K!qPa?}YJPm6b4?Gts zARqf)c;}-OS`Dr!!51kWBQ>$~<8RQtPX?6=bTIDOS%P8jy{UlOkZNqDgP3Fv(2(Pf zJH}d)IR-VRJ>=f#oREeetU;?IlY6_*SUv@Ga=6WUXC6!z2d(L zhQ71+jc|>2Q+ErS{xGY3=k`D+2$Kcb$==76nY3L(PY_}eYbO&#t^mfgAPE9SK@}NQ zUM#l0plo0N?U;<(zklCs`e8B+p3mp=MU`vo7rAKqw6ty%YIaM<* zpGV!ovF%bxxGzB??BIxcN1ykbhxZ8UK`Lc>bb|<_ca!rt!qWvMm>71sNFgEwK>v$9 zU2kW5*RppHJ$QXsmPe3XLC@lMms?JMxs3*&6GPUH>;KSrY;UGnt0u43cOwvFDEz70 zCdCm93V!g2Tz`LBSpuix;-5_P3RO!n0#M+(qJUp@J^Bd_iy=p<$K}BayOn>dW$bI_ zHQzQ(#=%BU2mjIaFuV(LMD5i)-$%t?5!x3X-7R^`QStLgLATKqF84fP0#Yn~7NJSSouz>9ewfQ?X_cfH*HB+Of!S zQ;Z_Btb9IXzLoRx1E-Dyv#54*i!GdtM`HT$-Y>DIqN+OLKbmul1n8jE-;L?kAM5nk_jGK zk<@CG$zfry#2>t0t(TZ-d8Sm<&=^!D5Cj~1NsR^Hl`@tATy%FWJxw$KsN&CFSJqYo zEm@pz9AJuoT?Z}7Z1OTxHu6&at`nM3r!Gq*CN?n~xvErTv{FxB8lIz4YFUu{7XS+m zr5c{a3Xyl|ayc(zsG;YFsuDnbo&A~3KD_>XD-Z2WuJ|A#8v@-!T^8$Q*h5tz*K#r- zu+dlJpnZQ>gD*wOi7F5eSpaY)?SrJbkS1`M5>X57)awog=a9b3N3+O(X??<)4>$v) z(p)joqB+A+6nUePU~!F(84sjZvP649OU+@Jq(f@sm=Zz~_BVfYQtQz~<30B-lcg0F zm>jq&vxBNAa9-TbsLkp*i|(MZgPn{Wic=&*sL>UR;IomlVh;)9@Mp7e$|vs$RQMdZ zV#$L+OkeznTku4KwW0AAB7;;Y(ECe*VhfHYfWsO+2dIld#G~N{fKKpAPv47B@kb26 zp+eR_oNn0%DI%m*j4*8#W|2ON#|p|2As%WtmAQ1zAeA7DjDw4a6!fkXO-RpICwhp6 z%%Kzv-ZtADFhoGSJD$nMNo(E?NY&&Fd~dGXsq;x|6$WKBZcQWS<{nK|g&@)TS>e)A zp-8;MaWscMmjuC#oWU3>A`1$bFWTf|BFBe$XTYW(d;vm&~V#* zT15}+6zG2|zELp*?c)8v-w_BSbi1fGNgK-NLR>VEl+9z**FpFlj~_dQJGlF^GSg@x z0oFEz#D1NEK9x=y9(&r}^5~>omXakXL8K-`=g2hepyvfnpf@* zMg%63T0NcXYkV-H?xZMkG<6PcbQLlhf8t1zGd<+8R$2^(5of2iBx?L{V?#w+yy!Da zEobE7L#9CrO%;6I1Or_Yp@#Nyq>(K~7^d?Glr@Sy$Ajbm1^H&jHdAej1stWI%Yj?J z!6ZsJ+E8SS7XVvZRp=IjYalNZvZ}wAB{WzR5IpRw#&)*kqC24b0gS2%@BiJ4e@@GQCDoFh(e7(AUa*0GX=;9Mc&}x%jntuLQ%}gxmVVe z4t#Mr9hG%f-4g*a{%NhU*tG26bsCJ;9C#Vs=W}6zX1a$UkC0c*roM-sN0!ePo5Tw9 zSxjO&iGpV(F-1j@5X1mSvF&Do?mz*SGr1McG$MAgN1`n=I+mr) z<&mD=4z+ele( zMS=36dmV)+E76-;+Qr;%b!zU}bSjKQ7lROyack6T9okXqV3D1q>-BXXy5B;(CDty= zqSu{rotto&E*)I^5+)UOBcZmbprRNQJEHYlZ>eI%#;TQqN8HdQ0z9$87D&AFyc0YH z0&mVHr^DEp5P_A9!0{yD<5tfe%m(gAtJy&C4=}&z>2KtEUZ9j8{ttTbjjD~hFzpTf zXJwBiGcwQ!=x$M`e@Z%xXur+(9Mx|wLD9S-mpLK2*U#bjS5xCDs3qoxv=mR*Js{VU zBK{ajEG9jZqkcp%4^)b@4Wb)cS$EZ&Ntx)kDhp#c%K)rP?ajWp@$b&1z>_518hYrr zC)vyX7l~KYK1xdk<=-{xsrdMHM{0%ivFnF(^lA8PFp!@W^83q^DU|U114ct3z(Q`TI>zq*CTH#c z>GjH~g5F>B3BwK5P*$O$DBCK1J$W|z`;=}T&c#ue?EmJ4@SIBoVH=?6vcaP{yB=ft zf&x$6r!J5|6NGc4p;}!{ByCjfRFZCrF@{-!daHG{6cad!KjK*@pmxL}^CAtc?B=@E$lMj1TgDDR7JEJ1gjcFIQ#mx0Y)+7^(_!y#m6i(&k~El zN-xhe&&3Sq#55Oi7ZYjFq1@Pj@s_=xDgRX{qCzB-kjn{V9I6>A-98#r!~;|%1CKXj zrCy??{s4FG`fxT|kf=PHFT8L_WMYCzbVaERl_q{~v*xF7@1=@6(jjUdo7|c6%2F8u z3rwojDKiJOAkv4Eq=doU!dsyJ!7U|;0Vp5y!1EaNa+FL0zxcEdXr-H3@x zTQ{~vZdL8?45`@NgL7yd9^WrzvASe{zC3Q2aL}qsjDyhmCX+SzLlnQR3!cCsz!vdm zpZL&2dDe+Ai9JElo#pdN$rGL(Et6y&r=q|brwqYD!H-0ju>EKsq&rw?$Omj<2K}Vs z%gV)((y2rVk)c2qty00O;46A`1twEuZ(8=ln)gUL-?g{)xo+$ZY!okrqpQDnB#Ffb zOR>T*&D5{+eP8i<8VgqqBUc9kNuSE^C7cbSgQ%~%Z;<&Xm@0%ToBh08Z6yuMPpZB~ z=WIDG=~Kc6u?j5wtatsE% z+R8YNS6Xg1#UX*$Jv#ej--ckkQFf-c|00awu?YV{IPyLcfD4bgE$poT83Pdy5nNVW z0CNk1CPJA;{OcvkAXdjs^rt~jI|79_o#|g*`3#PJ9L+eUsW7t>6xslcXh`q`vjbU6 zTI)qiK=JqH4F69cc@6NEYPhUZ_UEKRX(%^y}(uGY^60U+!qkm7ULHch`W0*JX1#K+DN| zJm7t3z#BdO$tZQp3KmLA`d_fQ8g}R9*qly{ot>Rrm0~t5yv)a)XC`kF!|%EX;;vxB z63gO9z(MILHr1lfG0 z3}p5q4YZ}tIFun6NXOu#xOr&Yj_^vd#EdeRR7w#KecuK8&VPAhEh>i8!c~Ib@6RX; ze562DQ(hmoEOB9`ZsV4NLer0yB+Ch&;^URgNuWyk~|<% z`>V}T(fas@y?6%|zy1Pg`j~uaabRjfKzT|+QP*MvM^J=vWH)L%r&oc2l+VvQvHB_W zkFDD*w7msV^Tps~VN%s9n5_fz7-U+O@!rwuDBcjtSB4x_2CAUnaCJip+ud=GU&s^% zn|%gR>Yp1Xkud)CnU-?Jc?Qa-dhU@J1vzA_wqjT8riDLgUau$~cRg`OZ3T|tm^=vd zzH@L^a+~2l(uUiADD z<|YFH(fkMmNWxclW?f{4AsK9H}Jrny)g`A)WeQJ@~u={veEgG20g8W%za?; z6!$jNCn3ZJ%Mym8*4-i1xcRqF{G&=uI>Y@}&6=Snm$iXS9zQKInopVkJV7&C91dyU zVqcFPjn#?_mc~Z`NBYP1ml$M?(swt6w4@No!y03L0BLWabdPt=rYaBu%8J) zstojr?#Uos6bYY$cxGTDXD5A*35+o*M&By^NyQZ)5# zX<)bH`V(FZg8mWQ{8Ei9%?Qa446vh-qM#4utWqV5&QslSSy2|W zI?xm0Oa5VO(I3Wb=u;fNw-%ax8r6xqBXn9-T9TnE2>s%^li+)aX?V-tIzfoNUb?aQ zb(D#se)5lon)*DBeNP)Jj^G=EMI>H&@9lJ_SdDEX;>`hpkCl`;16YeDuxuRX2nu1gc#$sq@V z1}z1y`LK6>UPe*^MH+PP>arU!_%;nSmyMNwa>H`JY$+3K8vM8{{=%30beUzy9zj1Q z%=zlhI}ur9@BG|vnRzt!<|sX%8yf8J53Wm9=gURyXI9@ zLwQU6h@%5d?0ZQMBvxmM;Q;tJkuRRIXQAN!0*~crz#lM$-;8;lRv#7LmbUE!KsZlJ z?Lmta_a7|kPpje|83$6nw!aFz_M+R@419B}D{yV=nk@>vk1l^~Tn)o-Z<=R%wI|7& z#=nprQg$w6{q^T6Xm<4y8)ot8Iy7O@Fcjb~Y0oJfJwDEYnHk9ok#&u+EEMR?&-aM& z5B6Ii?k_6@PbV1SNK#S8EE=g^yr9Yzlb^Y`#j@#x6d+$JsS`Beo5u`|laZJ|GG}*PcJYJ=52;iMo2QyakZwjp&`2(j191xRy^gYX zTo>ZMJ&akp!lT?ylJE0Chr31U?3G)uLtbMd!cadhK1Iief0Yqrga@=kjpH) zergBZN4|oGAOSR#e8wQ8_Me$<@H=Ix!*$1kymIEQkPAj2+=sb#nR;l7(a9t%9lygv z*k>1gP(cQznwnm^0-Bm<*_0!;A_-nd3EX}g*Xu`YIK-+(joBRALQ1_2OR*FQcWcKo zV*L)CR+Y&lfdgD?E>s|cLKEFRBbH!Qr@MM?%D;xaF~N6Ius&`x4yyiDd1jBN9EK+( zO<4F~Q8REC`kaaykVr-J4BtEB=X%kNf$c}#!CB7ROMiVhUTj&(yOW2E!ZYFY9H}Z2ZZHk&sJFl?L`Y!i zb4Y*=$Iq0J12{d@%@V&i1!HG6wlG}>*!(K5Vb~=|0atig=c0A+;!)Pv8sBm z1SG?l->ZuMv`Iw!&l_;6DY>3DZ&W}i@hf0e7`FURw>%TcImvR$uwIb)Q4C_m3aDf= zf6C>edZvmoh4Rvy)~{xoS99V~Njt`@Xk*Ii)W45e8)vV22vqWPFF~5hM^;aO5p#vT zO|uB7dMT*Rr;(3!>(&SRrB~nA$`5k@s6YyKJ1(n(r%) zd4HSe?zca_y(`tBqARn&w4%*UQl!Swu(NIJt6Opgb_=lb@UxEz3SsjrB}k1twR z5}pO9fsi;fi*xV|K`P`4+jW8 zUbNl>OvrPM$=dH7lqSF_v5*h@vJ6p!7O{-ohEmz_J+sgvRMWgJitdN^%QDAj&J4!? zerR9Y>$``gj-%21ZFtgsJ}eqEzvr|fpE3D|f~i@Iq+NA|5fgOafr@CJcC}iz$*#Iw z1YuZ?$GpvMIog=;_NP$?6uVUi(S3;=?7F(1c{=L%p5o-QEK>=H%QZc8p|t%A^F;;x z#@<`lu!*YyVtf={9sBlcd#~^J){}n2q@p2>1A=;l4NSAAlSzW^Sb{{>2<2Zl~*(_1u@02ciJ#@Qpo5a4qHJV42XkYO> zmT=_yscbi-(~5d9mk|RwZv`&VwS~ue^+R6Z^$yDrb1%wOLHgIbuGg*+&&fgRhI_-jZe*`0=a-4v->(JX|gHrg7F%WXDTuwm-jZg7M%fCsVb;Uw56=EP;8#?a}oP zf+_2pz3qguo>oM&2NMPIs|~TUbe-MC7}nvBVlw=^6rvjBKNv8bO z{lJXP9IXRz2aqO&=zvHm909k5{76}eq%z8hk60|UVLk0jtzmcJH7 zJ;t8x&~00D)&L3~!O$wljZY9n=((w!o~m%R<#}y;KaO7sjnr=*t@>n^Md{^ zs{J_12?nJLxXX1`+wmNTm9?%Qtjr>7!U|r9TSlj%Bw#0{W^cE{7}Uyzo7s)U*U6AO zVw~c?XtE;cuSpn-VX7vBwu1pfv|JD%zx#NS6uXf5*Q$6PAG#T)K=qiW`XgYaqMP7$ zviD!N7mreo5w3y7OB&YKeI+ALGfte5+n8+8!R%-r8XzJ=F&csdf0zR97pxp!((zQN zqh$RFP@t75DA*Mlk1u2qc366BVIPmNx070J79oqtk`eFY3L7UK1M$`TSG_0V@OT_F zBfk=gNt=}fNri4koof2I({i=dYz(X-N{({q^^UIsg$k}o&i!T>$&FQ*dRZ(EmSy+v zpkF-5D9ezV%?DqKpxfSWm6z4$U(XvmJk(Q8sT0GytZHNzvrK6-@|Xzc**fb7tvb^v zYy`f*v)N@Z|Cs6;_FeFH>FzE$68N>``S)%6(H9qNvmaCZFc08hvSF^Yk4_x7pECjT zT)052O_3ETVQ5mmk+k|sJ>tTPA3}5G`1(U{Sz|cxj%WTZ_mrB``R{${*9N}An-ClR z67la{i^PaWId)f7R{QOKbRMM2hB54I=NZPt>KfDT?ucf61m+!_z;~|PE7Z8F`T7B@ z1WqaOq;PGI^z3P8b1HU)Ear7hoyEgULx;8joX^uAnuhV0fIk9p!xm$1?Po%k&slPS zPDT$@F2dK3U^+#9)JEs;RfQi61*XI^U;-BB2h>7vhb z^lX9%pN3>u=s52gval$>()pM2jZFTIQ0Qa(S^}|Ql-hBj5T5arbvk^qC$9C2$a-Y` zs#AY8*8=~|9xn|mZ4*8Rv9p+)+rKVQRvjo&5YM~0eQXE|nSE8RFEJ2?)1{qCX|qrcv% z3&<$@}&bR%5e7)-w7vd zHV@&OlaZzzAqt{0y8w5r@zfZ&^(w|s5@swdLVKOc3?}>!L20*8LRk6JV~6-F%Hr#J zLaOw*0A3Bmf-U&Z&d^PeK101Kck(XptkgTYi_n+f%#!h_WkJ_NkLUNEHje{S5eqOm zEdB_B1bhb^L@G0z?+O`m8T%=Z-|L9JFV(e5*#3#4GZL(=>vcIW^tG4D&CIKrTqxpV zHFh8{av%F!bzg2SDF|UWsvZJ+6+0Va4r;%bvdAq25>?=BK|@^$mFm>7rL*##T*q_E zDh$2I{8Euqee_uR9jD1gf&=Clq6DtY2r8s2-R0IZvttu&zg(U106Xq>>!G$Grna&G z&zViry6>T+eTF&lA6wikBT;Pdc0@q{@8CnMs2*jk_h0W3q1J%9$np$0&v>ECLaU?3 zSsqIY1mk4!Va=j!d8fn{1qt_)XBHG0mR&Xbk@xPo^>e*XHY zYJseW!AWQSSiosccc)O-@$EIkxA!$Ud@6>x>viHlv3gslwV77w_?O2=8RxmGC={q;A?f$PN+0y2sERR{%H6qv9x069dkL)QJIDtziQRE3lNv4VZ zZe52&1#Zj7uMhaZZNV{S>IFYhaJmX<%Pe)qN_jbW&j z1y&Xw?Qb;q*rY#BOXR=y8;oG*q1w}m^6}J*DJRg{76g6muo$|`K>CUZ4eSQ|FRac1 zztzYt&v9PUdtTo52h-my@SDIdU$bTVPpbw6GCwTA?P%YRhr#Xojs#r4o#3OxT``^P zqr*Rz;Mj48ngcPaA<3hZu9b1pz&F+^sZ9?ol+tfcyuTf(*NCGTnU_XzmVb)k2K8_u z>)Cza-Q3P*v8!hxNq!X)dz1pp=Vr_a(<`nk1vA&7`#P4XpZhP-(&Vnm>+W-%WFnKj<810A zS}xD<4`2|1{H3jOlwQ9O`6%>ZeSsA9nCj5SdBLpPNG@iKTgud9SCrpyms|~k0K35L z(ZKfeRR!(43?dl**uA>e!)$U8?oT=N$~~?qGE#%|D;u46zi<_ueO`58lZTakNH2%r zwp!Sck5@#(!1nWnPk*7QP+f1bls`K zm1)99QPC%U(pg@m^fxxX!jKt#jY5f1>{-K$e#`wYo{7J-Bf0*9hgt1-+5ziFL1J`4eKHpv`yAMo}-~N1MTF_Igh8Y%4L*}2~9QoFt zfR-`GL*|%ujb<}FEi%>y!(L<4INlP+tT|JdFJ=ABRlM>s4q5rHo>pZm#$l#EU* zu#dQJ9UJ-)RY46bw(&!?1?EC?*GR%UpteRAQ2ygvFD zIc`<`?%dq4sq+7;d!WUC!sC?H_hIgSp&vA)=&!#o zT5H%y(juj{rEu~o7~OywQd&%V6X%@wd7GuKX$q_Lp8Gh7#?7tKslB8~u05CNHs55@$w@a;l@|x6BsebQ8 z5{^_4c@#0x<7h9$`PJY4~> z^~8B_dBFsLEv<_JzwaT`<{pNt199FU)h9qX+XZp54SzT_s=yuUc$BgNPm`mLfzMN~ zj+P?y;WZk6*-qX?1`_q5w9KM~x8<5c=Hr`Ym0BFv1S2?5p8I$msra=?OFgegQPU`E zcb6@$TJbdi(_7ksM-CYMZaU9QNZN`NZW2b*{7;Ai5u`kFRmm2?BXu&xQF1`6OU zOb|y=`Fxj8{>`*J7t6f1SIFZF1Mi6pRpdKz$dpXS>*Z+ks7gTkzv>&i1g_lg`e`XN zIZaf=su(C#`k7{~C0_|s397MU%|eJrOAT9mv`e3IqA!vyJY}C|yDx$RUEZyop6Ikz zW?wYR=bS1j-zQWmjt33{wWez~zAcMUWt1sZ-ppP9>Xi0gW9zM7r?Sb@xwhve&Wz@2 zj+|0qZED|~lREHP#j%ZjpRw53b21A-%EMZR$V%1lLF$TQ9kx+dkLBJ}SGdRJ0yZX? zTjdMsdb%qZ0zGDuPFY{K`+fLBtybAkmA+u;!BqvpR)cm?|F~eNKU}u&_0$id0c$s2 zeg8Rr4yvhM=&H*(G)+l#{g5Jx6k!c{1aPG+(ODkg_cXlp3se-Z2OUPww*9X29Q@j_ zlSE7^itk83dRY|RN>IWV?4ALU_Izy#&-BC_E%@R|6<0ezF3ie%&PHFBc0^B5Vx#;^q?z@^|uZ zqFFuZ_X4%>AyDp3Q)%hD3gB@5-#9O>5fQP5Cs*H!@v4JP<5<`N1DRYw2V!=nnQrr= zN)4fBWCI;Xahnndw+(Ome&ixjHi_#vSG~gfO1tvPDOKZEs~pzA|A{O)?;t-g;7y|+ z!9xK15sH9s5inh& zWII2#Mc?RTn}U#xAC|}~XVTf*R>%UxqmDD_EgIJm#KMQUV36?BOUZH*@vm%>707Zw z!_|pI4=-he@(cf|`Fbi!S;ie+naj&s*k}OD^qMWGmgQuymt88f+7}z8=gTWB1LSL4 z7EB|EsuwOD9RgkS$le|qgKBHvSd8O!AqDTGR40B>-P8ABB;~w*m9+V`e0LW5&+A@O z7|J34mnX&MVl~%L1`UsAir)Z1Yf%>$L%t<^ppt@z!~E+SrP88Z5bI=zD%6 zfWXjx`qz+4aO z>I2$8OdgNqD!#0@U9l9`Un7dgcuul9#&K`z?YUxIy^iw95GbbhIZJ5rP~={Y6#&E7UXEN%Ev{pnwsu)7HzvbpWZsndPc0 z_-hd6$9&(**~o6b^Ds`q?G!#K#{3>O{WKqaTBixRA`ZS-TC*FIW6N!l+XAI+gI@rH z`S{EcK^TduREiQB_h?ym*oq!un;&{_R<1j6&`d{#XwjgGo&oHGwt|R!aIV_lOyd!8A}YHF`JV(V`S`=Tl13ei-*3bi zhBcY{;u$S|ET|@q8ZJ7v>4Q;_Gl4Cn%$`lMlM{>7Hb|buj_jMfYkMCQ_CIA2&nH{l zFSNL46(_H_|LtR}zaJom?ypE)8XGYFu8+#UYKFpXs1VZ$Z$=&~88FP7RaqJMaB^pO z;JHR?^6;hiu+)>ium6y1Xl;>2|ZDSa*_mR(V=`*F<)PY;g=&`J`- zin<=Bgeu&!dPyjcvK@ypa4MoKR6~}-Dj4QI#LmEWtGr4JcYy`z}Op)e& z5?tT+II+`mDhiRzpl+dOd5;De?lh0lFB+uYN}&Xm&r6brEu`o^L$OVmTzt>6Y>O0B zE2gOPV+uFslt9)odhoY=^m)|oD*9F%`WS1u}6mKXn`c~!QDTUE` zxhjPrp7%SSVHx~hP;Wl5qt1Nj?=Dx;o~_nfAHI?A%4=Bnmec&@W-iN;a zFZ+F_2z}C}+H}J|OG8brDHTw0<{3oNEiy6xIgfzBst@WMu(Rg#AD|}fAVVT3Xeo+5 zUVUn)3pPBi)xEzRH8ibDq6j^2ieioFA5S zrgVKn#S}8++i%k?Uv%5gT5S2U-Ve1Em#-RyPacl^T7)f?b3j5Lj;L?=zR^6a; z!RE&llhM)Yw`=-BhFjoBJU2KE48V-Kera1+^HOT7#E(CnkRRfX?GbpcuV~XyW@ip4 z@-wml`b;8Qs)|-tT~d5*HmIg^+|sHXdk}8)E!PuyO77RgAUZ289_cA<`CwTj2U-sP z54JJo$5HZPEJ88^2o^|}we(Rz!jIrbN*6bf&yH;!6xTwwjG^~IkeT}9mhfhL!l-f2 zvx!}bav~T`@F{Rlcl>_ZOi-W_;A#fA56`T8T1hEF&RuGXeCC?Y(@%>$-quYP~}#acW^w9-swymrvxaxbLI-)D4-KV*}rxs@|Q{1&92*;!G?vbdMnyWzCS z=sI4{{Z?U=6`lR{h#`Cd6#R9&Z%t+Xtg%1U?d8X>)zQ(91u; zaD{@yV%EC4xnW!PjBM!5XtWcGU6!kPCv$Hp3TT6^S)U8!_O04of1WmdYZibTDEHA?v45@lBfD?D{6^x7Oy6!zr}%ycJIm$Z~dQ|i2~*a)q}9E@Rh9OYD$ zv;5?b6S6~hOG{0_2j~WtTYogZGwRE=nFHm)Se*JfZIYz|7x^P-jyGsx#b ztAVJ}=hd4GyzSc0xfU<(wPSt3@sVkAnYFb~v09;}8sh9WzR}rqE ztiH3JtBoRplthz|U+`uSr$Rn~xr;-~fN*STnqy(GefFX)o}#e-ZW7&`A_aSj$j@p2 zPMCx2n}Gc(_VA2wpxO5ym&^LxMS8sRVJPNPYcFRoTxSuk72kNJBWw-we3?%B-Ps>z z#Z;j1v(l2|goQ9Nh;?^g_Avr4oBu#JSZ(>Ss~KaI0L9!mS;q5DJ;Gxh9Q$vq2%%2X zRt&`T)eVweYY8?v#$g%lIpPkPL)v)~bFFL^e;UQrRIo@jdU7n>%RA_#lR%kinW7eB zE|HaI<)OdRQyeZ0Vn^E`CYJC5zwf*xBnE~HH!J1C*p?F#MNUckHwvjw$E_!2j@Ak{ zZ3_ENCqA~XWq=Oj*475RztpT* z*{Q1|aO{0%R-T4=A9Y7DehMW-mbVqeG-cGhU@H z$JWR2kU?HV{q+0x%Yi8Q?v9ng^7Dh)!(G4Osz(f4@4BV(<;t_?4i=$n`v)uh&C#4x zQ|DO>=dzZV7f?<9ejOf6vR+7JebFNIvLo0#WcGe;xq|^0^iMj+arw(U$?Fe9&a?cdeQkXcEP*Zd#Zoe;fNAOPi z>{`^TH2%+_12bZI66KGBQl$~kaUS-P(%FsU@Ap8#U#0`})|zd03A)63fa8G8XjF zKVWWG-Qcl)5Kyo=%7q%kOYTn)>lWZr?n5B9htil%ykKJ^mo;nh9w^fcI@yQB%%{hh z%C#P)d`&c#EMa)B&+IKf?);JOi(Y#-M`VI0C0CGg7xXe!nY6K(?B8dl5y=iVzj4tp zaLcoyUq#WAJqlfQ1?e7_mdGpS>G1xtyL;V2aSS;s0b|5XF*(ta##w}?7iS$WWV%2d zYldG8eA`<&8@q@Z!j3n|+OR6-S%M{1AhSR3v=vawFpayGb5qc<2PBeetXfH-sl!#0 z!j^?bI#}pYVb3*>e;LZ+q+#1uH#o58fe%YOQ{~)#%(vvoND?>~a1mZrk)zEkBb0FJKvmrI-NmX-#DNPybqv{SQ*o5>`&3}q#>w?1g z#F@UhcY!N4!6>>y+BGX0uMjT!nSvF-R7kXB^16E+p6G<5yRpRCTy)2dVQmos;xMj@*{p2P1Db~nI9Qbq9PCy90kAY(Wpo+FDvwl?$S66Be6MFUnZ==;p zo$5K9BCzSxDTRU8N}I-y_wWWxy9bl#Ayeb@LA83Z=CW&Wn4d_&+oEi-pC3=om0lwgt#3MKhSUPBhPi}feF9oVfn@Z-#Jxgda(H?F@d}=G@LT%0FdQNpButQ39PePhY@M#ZDmn+W;H~sCnu&f~xCb;+6qr`?%oF-1!Yw0F8?+$8$J0M%ruVyi@WkF{iN#$K zXMCj2*MY@%h;kiRXk$F~WYvFbG7m5-DM_cJL@ps}US zZ{2z42SxXdq*}0XIKlk5alsDiiveKxl8A#x{4j!?K$e4NY*8~(T07==mlp^;*a;tK zXP;6u&L%jkg#{TjAM>?obw$aZ%Z6WC-1Eh8_s(N%Rt(BR{ z?lX<$gf*Qxm171;oVV}-yNVqny!QAr{45({dWHu5LN%av0ZgFqZeS{Yri5cd}9d;VecFC*I9Q>`p$Im9d_>Ad6976XI8d zE8wt*iAoY}9{lw%W1IdN9wVQl$}(=kF4Z)Rm-hAtW`NKCa?$@{=TH-$Ip4Z0^Oo|{ zG~OKT&l#m@T*vIZ+!fH-+Dl}aQ(k$x(=g2U(vM(>@mcrVAqG|tFSnrCFaH?5koc2l zF(aO=6J1IPLm#GH(*Vv2RoRr*q)P>MJf4sDaUNxof)CLQZ-s#*OeT=)w`<^rHr z{!T@QiUx>?Wy#h*LJw+oWTS3Xx6AF4Hki8uC0nI2KbLRmd;9RdtNxXt9-8lbyYez#;iwOVQ zrZhM&WlB)m4)bo}cX2r|84F@C{(`mntH-VZwMC`r>l!-f8n-S|m@r9up3--T3@0WB zF>(90wSdd3D9IJhf5j)*k0%w=f=5j_)n{-g~&t64D(6VWS$M6v7EW*p75E=vq3 zZ5^Wura5=?QNzuQjsmBnmUQP8q1$hesVn^mOSdb>20cqB8VZ|gv`tL&;GAZjAKPQBV+9hFbWS$ z<}4^VzDt`m9y)S76Avp^r95u>vcBDtS%s~;(2xqBoG+>{3hG$QhgK}AG-*@u8akwi z%}_Q?^PYsty;7Ff^a1R$`Qsq5R>1&yyS%plWvA=Er8#UxjWPo}wUe1J)eMz~*VPGj zAI0Z{(PDlFj3?3PaO~DwUFY`O-EhZ%yU)tgZjQrJsL;|gr13E(<8!IHUo9Fw>6^xc=@t=i%n^{LUfkN<9Fg;@Q!{P#j3;N&2{O2q2E_D!n{${{K0rStvK3%PgkdqWWx!H0V9t)kWZLAn&HNH zub9tY*qimC7qTV~hFjuynlS4YD~0K|yYO0%h;e z zPWK%GF4SmVT~oqjFIG2ul}6ZNAR-+bymgarl6$wHouU(3nmV80FoQ6>;6Q=577@cZ zkevnsQvQzj=nEptlUIqC(6WYICBxE~bMvQcPv zNnCdi0l!WbQ8}_d2&hBOpliO-@+|&f19A%SG2JL^<-@n`8vZg9`!r^T_jaQ}uCEv5 zV4EKQMn}3R7rK`;f+NU`)kzMrY{Q5v(o_fLHsbgtUv29IO~yIM{w(|`pe?5xZXCiY zlyBbjsqx|;D}h{_Nmmr)lnnNw)+pH7^0ut53WhX23Kf%YqY2bWGUKB$9zfFltq-~i zI;1c61$-4@IfYwCMLyb;9AbIEx1~uyU{0sxw1@*SR!Q)o^ZIKGt-jroZ%D!0_6AsU zRF~YA`Y&iQacVQLlC2zHk66MxPT*pu%lxs?)}+**VUDvKBM`J4Ge~o!Uw$?4*}q)! zWtP8^3$PK0iIh`6VqEsSecK#FM@h|ZQieYgJfOlvZb*Kp06Le>tp=^Ze^8Bdua?i) zCM&*(dmO2)f9C@K-MQNa2?;H*)OO_yzy+pSkL&CPRF=9amKW@7UlR8%GfA1rbLLW_ ztN=ki97V+MFmsRbj2QycezAoPy*&uOxC$L%QrBpCJ32@>@?yhnK}5;PZ8!mrIx6>2}yaKN*zg>Q zxh~tb4p7ClLfbU@rX&=~Rrn^=SNZNHCw{W)kxb76vx>mk8}YX8T3Cg^6tP#+HvH8F zkO{$^09ilo&u(-$K6G8_w+#98?Z0&aOE0Mbg-@H&SFo3ja(0%<1Q_%C#2=`RsMTC= zRRQaa9|lkPqHm9FtY7G-YQE`2x^=U>qXT^fI+Vf*x1k7_NSTgl*RrKf%4FP4F_eaB zUFVIP$|4XL)FK)RT z3QWpasptE&ct1*^#fR{e@W+d@DIln#@$elheS?aB-%c92kB z6Zm*$Iat#?WDbPGN9s%Xg@*hGY*_%Q;qu;PH`4e$*TrYBtpn-ibqgi~E}5fen(ym~ zEXx@Pz0NU^pRC!hm=yT9VG*Fy?I#$YR!G?y*mXIZiJBlMi{H$JyPhe1xWZ;CmLtI) z(89_zgd6(*?m`B;jZ6W>mFF&_L7yd3WX|w9$*T=;n2u&~ntc#h8&}E~3Rz-cLFhM` zil6Lf^6XlFivuN*w{BS#OYfgu^66NY!rt;SAuyo&f=8BhYMH0@T|uJ6R8S=C47l5H zLy4N?CGak>tZbTlPDLCQm6sXC@(u5xgxWyu~B0BvP3-{ z9`=QakxW(L%HPLDtlu=e1OxAL%&LL5<}9>&{ztA8lu|iHx7UFOP)PV0I?Ha>j6{jKb8Hlz+>4 zcqNkZw?jFFfOWP^sir2lzSHOR7xLX+GE`MUujkGu8Kw}ZAj0|QCCvc`_Cr)XV@8t0 zmmJrAW%dopdx?S<76krMbgtz6jROKU3LymQG<1TrnbA8Yrfv=hBLpos{~^qpw{*jg zt(icgOYl2n*1{d7K)!jgD z=~gcM$;+aDT}`1fmGTALi$pIM68U&X2~|?e&r+3aRajGVTO_NkJEj-tz!}QU{E-596?_}TGfe53+qnPA1V|kkOC3k z$>_5x2^346_Q>-x{%cUN_3R!o5Gp)K53!c zIo4^T(aB;r=VcO?sI6@!cT`)?bHj^rq=M}ss@Qlag4L*x->^C1d4L^s_Q`gAu-8g! zn>{$Ebo{GUhdoB7TnNI$yTtfg4x_#(xSFG6{-E4o0Kn|^Cr=8~fvD&gfgOyK> z#mulr8{rE)PbYUCu7B;UK0mGiRl`EPo5ntFG5vl!5*x_La6`{Y|IYSlaj6ls+ihDV}V~iDU^!(k!fE<%G zhzoZ?6rKC;?8fGLHG&8Gy07_lAD5s&@XtW7a9i*Kv@ z_1-?7YLdFCr}1Zygmlur)a%7YBi~I#=wPiVvB^v#Fy1J-GPG@N>QD?Jxc(1$wQ8-0yW1K!l=`GubB}hlJ#s@_xBbh!COl9!+yNf4|t$JnbS{Fhy69q~f zo*&_>7Pgpas+-|mua^n3JWcPHHZAS4-k%h0@Etl{{r2PtNe+RR269R;r($W5%^|`IF7?e&6m=1T;$XNeCPxun)j1#(BO9|Q|c%T z0=%s_w`%2gN#Bp93UO=kAF`yH&N)VUPAgeEWC(iHkjs$HPN%qwwZ_!wH7#CxRus}B z_kqAr0MGbVmQ7{iZL+#2M?!1P4lp3R3ac}@KQ9~>ye{5QwOMt>M{fpwolL2!pU=_MO0hHF?_LZZ-dUC&9HMTlw~vkC64M$YfX?wdJxC zs3wDz9I#ce4o70Rnh%UiDV7^8%VG0?u*|xkbOL|p^7(wf))F}l!ylG(&CT;;dxZ63 zb88$Sx(LBM1&m|yNIpUi8Y0bWLBQyxp!IDRoUaSOtb%G?KKX&r?+wINQOV~@q;z~v z!1N4~`$3-m>!g?9)55cJ{N5s%faUUfzM#Xh#vwVORA1?Na5CakZ^aAgIzwoFe|h}9 z@bxlUBHNc>R~IbZ@vF^G1h-A^xgIAS)d>c4W{nbQ!Fl0N-0``u@wQpkqI6MEfjZ=U zes>bKAkK9Z2_Oa6mc*I!icPgvGB9gf7aPYTQ2U+sm%i7I)*~6`~CCi7oh0sM-&W0Qf%Rx-q=M4f0FKp18@=Ks%AEC@DX6?2dE24wYP zF2}CXOL`hK%G`&&tJKF1I2y*>cfvcfAt=y~z*N@-o=34h-mNP#^vpH_npz2buk!YO z4lD<^Xw5($IEI9_{)U&F%i8f1cAOQChORG;eHXN1Q`;fB=Ep+s1l1ggq<9yx0}s0x zM^L9W_{f*O_UU16~r9EY7EUjD4 zw785uX`;|_&K(pBw$njAzF!75asWubawq;tuAL{MMx8GwO5}MZmZUx&DHmsQ5ECjx zi8{|pWiEg9O^Kkc#li+9Lsq``DP`2O!l$c@yUh&rwc1F1r;t>KqoQ?LL4say_jm2at%6 zgXUU)(LpGRoeAaLgMKHtM z1^m}2kLB9Vy*kwnnxsg3zz-|HjcV@sW&fqL&0 z0Twyy=v2lqXyCM5>ix(pQ}(MO7mfX8$z3x8k*k8V=4zGUC!ajWaf-6h2;o4USk(He z+Fa>^QhX@{+X`7&)?`G5@I`YF3dqL{OxVzb(ba8O;+*YTExMs(esJL2zNdAAy!**u z@XoDqPEzpg@N?65kC*)b=lQGDV0z3Mg%hSzRKtdb16Eey7{|lLiKQ@tifeg0Dmvrc z4UkkwW!15KDsn>5mgDRrJ5dG(N9WA>J&L8dFqV`->VG}#+H5T~t0x1b& z5HL~IUiR>(c#PB5R2?{G11UHwm^jg1og#UQZ_Ikt{!g)O6p|s$>srxfk(4?p zruV>CbO-G?ZY3uQi1_`rWCoZQ6Z1oR3EwculJztl?}H53vt<5}h&h~KY<-UW_iRBh zu+MuL@ozvp4e3t-P1K$^PC122qD#qNL*X!HYIIw!Pbm`b%Z_5_`A$`i>96BQNud0j*$si;9M)j6uThw02CzlQ99GufZG;7NlFMN}(Hm=M6y( zZ?7Cc(YXqnVg9Dy-HJ3*NoU5Lts(wRlZ{A{(8!!rxQfMny0(RQHI$Tjo~z;}l3@(JJh>no4a@fo73#{M0;tCP{l_lvhxfY^~Y#}hCq{&iHI#d}X z0x^hIfNA&B1g$i*-{zb65L?afmnE~}iKnS;1;PAqQW(GGY;~Lo`9zk4wg))B_j}Izx0t22=f2yU|HWwp6WGCA39!Yxw@j&SirqsU-9kdII{6I|7^4uB0 zsAWl`s?sJ5*J8zK0I59Nf$xNH{0uiA6)=LNGnCj7gMXn_)e#xM3Kr1U*?C(CAmY)R z5!Fb_PS z6Yv~NCuqwH_U~5~!*`hbAOBEKR$TWNtEfE5bN(=s% zHf2V-;5X(ruq?-?qv*XhOlioU)@)?mvSiZT5L_Cnlq0MxOso)Gk=#0YSsjD#vCkBS zOu!>w7CexWBtxym2Z?e*^p7~zA^A+bku#?|+R=5K<#*Oad&+3i04)@dlbpPjzz(JS zde4UNLumqq^#OiV9FYE4NY7WzlC_}cVa17D<+p(B{N`}qD+tRs&{@|o%8zVX%E~`BFS$dg38}N6zlk>_#L|l;Y|8Q>H-OQsdG?8 zOgk0Qu)q|iTUw|`EgvT~U{u%F4w1Eg-ohZ;`NMp3H|{zxZov_X?P%Wc*x{MWpxl`U z9wzhJ(Be~dFTtktH9Ri%9A?sX9>1zQD@n#65C#XJ2mbz0#bfGCeT8*f*4`PeXXo7r zE1n8LL4J~aJ60aa2sNThwU#`7-l9X?Mfqprp8;E-FN0dH_Dq<=Q^KNfwu zP=unds^qgR(=td!++{+x2T#^r+w@T1S`Oo_Qy0HZR`FAg)tVGg*3?SIRBg&(&8D~o zB$u(UXw0*yikeuylDUHXVDrLN(+L0;h6Wtmu2b|dbV6D>PA;i`aP*P0=*{qR%_f+x zubg$$$CloCC$xqdvMdZ5wt`|~KFDHi+AV74UxAAsCMKWypP3n{+Ad*$b@x-!tK?&t)ba1Xb z$xn(q0@_-nI*vm+Uxt@i3p|$M=8cVg0B$5FVv$s_#zOS);qOSZ4Y*~1v1ZfR_qGAz zU{zmt!Z_J{!NZBkibQE9P@MU$tWfLqy3_&2k-C&;+ba!wlY>TGlSx`Wrfn!sBc{XA zl1i@&$?9?K!>Ro zWiPjFA=4P!tHCtt$f3iu<5m%R#*`m~Kua*Zfad+5hEQD=C1G&CW5#uSY>@mc2jAQM zuE4JFrB9L@&*v!jnY9ZxIZg5b`+nD6cA-(r`J{Bf{ur4PFlG$@sfb(^oeg0jOl>(! zo!QLyeiEkn6~}%c)&P|Ue;*{N^8H*gIoAp*9rB#|)5TA6uqd{_&`8?HZL3JGg-x=u znD27~i>#6T3dx%9rfZZCBXab~JovzN-+)+$)Q@?fjYCH{V9Q?&j-x=E`?nF!C1m?a zx#NXU!QISfe!X_HA+=`c6UCT)1n3aK_}M+Jn^w!JaD@z)Z?_jum_zW{=*vD{iM)MM zX7g}=w61aJY}kFSXPCupFXFNu`#Ks?aldU1CNi8mz^$nbmQigLkT#`WsjaP1+1FCq zE#~C2PeAbAkjSn39fwDRUlpt@MQmURB4P)j*H1j%p|e3NJP%Ug=1n} z3tR?}5><~YtNOR8;CxR%Kj`EkBv6lIxpjCeCxQh*KlS!>AfcJNG4SU_Rnv4nN|K>7 z8a|k6x?F5~gRH~id@peWz^teXO>&4_#+7h$4nLsOM(MQWI-M*a7S|mOOk;zT%;y=G z&wb8XWPgNHrdJCi!)x@Z$gIdSW>S3z^cL;!+3@MNnH5rvxL@}*NP4BIiA{K?*_He< z%0;j@ZR?bwe!SeyHH?IPc(Yvl4j`EpQ*@VpkA7R6=$)h8X{oNuc8DTZO0<+Y0w}a& zMV!zM9yF5&KLn=knK7#9vS+g&x;mVk`vT9~E32fvSTy-!39n~bSLQLxD7`z8)J3c7 z$p3-uW;x96sJm-DF$Se-=!~_z+BiCG`af;BaMcCMZJQ=@T3C5*Ea?dR+=sbif5s|f zi%hyRL`1ClAf$!DD3b{h1#Mwv+hd8f+NEhzxB zy71siULY1mK+BJaD)FosorjJ^J2<<|$wuZmMPJ8p7N4~lz^_&gZx74wOMz#4{imqb zo2vLFOnA*Cx=;KP=}-F?5rvE>FG3&)bh~02k5tpT>EmTb*xkEf#X*(pHvetF`n(|@ zNYqx9=iDAxm&ab<46tTX35KIE#q&}v7vf{>W@CVSfR?E=?BIa=;^mODgS2Stb%B;r%mRpCw?h`zSbp(>{p1~hHeB5YPyZ7R%a^%9T)g8thJ8@7e299|;~x}> zzMINfWHWe3Ftg%Q=%vp5*++y+9y|AMjCw@xyvx<> zkeTxt32zds#I-5N!o^V+xr}lp65#rH1dnoH^@0!7HAAl@bD2YHdwg;}o<~@}0#Uh5k&H8y3S*@rS?N)=!fv*Fx!>azTanE^j%)FRvc#0Aob*_!$ zc)zG+b!jLhNi!>9=3T`yV5^YEfa+tvDx4`r8kJqi0 zRt+r?V8dL^B*hMgfcfX#-Ap(*c2>aaKV#58A>H3cd0*d-i1)fd7RP?&xe&@)8D1{ z4$f?pI|MA>jMEomuZaLr1yfu;jv#y;7Z<%u& z^%=#D$3;6y+HdQrfO>2UB&ZjM@MRp8-Rab+lul09YzH(;=slxwXXK>>hA?)HM3nZD zWE_P-GScp2lnrU?UtOpi0?b+T%iJdU77I6(|4T(R-+};BG}0=_yOe%mlBfQ`3Up{} zN_ry@+BYej88Z)>r=NY2P4p0ZXtiq}NPq>v+0wfL%?FEY?brr5DtuzqBlnP6W;pe8 zk~M-lu_eWQJz@;c>2=g#qd(OduLH!LEpsthAnDu^)iEIL(8h*<2qZXDA{N(reJX7p z_ap;3F|n)smnbytf@z&HO30a~aap15$*RcRd2K=bl+j0h*^(W3R7vkl64}gZbMZK@ z?LHdl;ey{p9T-4pVnv>-7VeXi6*FXh{&k#wM2UUhijnv^#qu-*ds*k} zY*Lg^g^u^iB&k;2ql^G-71&=(FyO zZJo<;0t7#|85xxW8%ksxifU_X3yF_P2NJDU>JzAY_r=wIoFxB~)WkxpL%2b3bsUPS zbhL10R#WL|*8qI^2}bOwB?#=~@Ipcxx0f~B2D}QBibGGzc;Oz--W5W#;e5YFcRJy} zA&;Dtg=yLoRiP6Q?EKo*`xHmnB;F?zqxsSM#FYy#CBIg(JBw*eaZ}tbUsB;}{#MSo z9R8kzMuN{a&24{Jt6kRC=c0%mgOPm=hFbIDI8arA_gmpYc_ZAm^l)EH!u5-=00_UwdUci)udo5Q9xq|k^Ku-13O(~x2`?rW9AOqgSOW7 zj8E5_i+C6nUO{zlfEG1tWtH{H0!dxF$-beRid{7@Vh)qu z&7V2>v+>}iL|{{%#-82;;CDZ0yx}F{k&^7c90`lzuNe>g1NhHf=b=gV z5mPg`@_&xR!IZw6lKhuAu0V;9@Wp9oJ3s?ho)S+mz22LrhkCkgxKDndt3QZr^@yRb z-ZU?SITp);^eO6DY@$iq4g+tZHDpSlLJox6#UU-OgJB?SImiS-`_8XoWaKV~`636!%4aT^VxZQo85?{oegye_pKlUMl*aD27lbQ+DAash23tt?AwtdHs% zaE^ntUBFnka+u(uR_36>n^xxAwn3IGY#k)?&mNlyV>X>R`1T^(0fiPgjw=6cY5>P^ z#ccr$2ONa~qqaUCApE}V<$4a2-`vf_!_2W1&&F~O5A0BI>3A7RpMTM8T_Gd;q?m?Z z=(-th*qVgg&fR`9?Ruj@_}F}cnCSzPhV-3aCN|G-N9-DdLoZE(fG4hJHXE8dD@=%j-0NBqy%7{<_{5Vx< zXA7jL#;xE(E#|)nvhkn)iJr$ljMEY?`EeCEBlHSn2j~xo5}g5mPSgXySuyDfOL0vcSv`4w{(MqbZzp! z|9j53=blfFp`T#5_gcR-=X_?oq({n4Ilb^!iH4dS7iW3F$x;Lsz8KIT{pqF3U(M9YsQa~k#e`sp(Bm>9v9)b z@dVVE6HEjzw6feE@ZYR~pw8jkc|&N6^O_|qbDMk0C05$q|K49e@zE4Wsd?Wo4cM`D z!~hZu6>bp1JBcSn&2o6~)aAlEcm{yk&GsY1&pV4_yykcS?ZIc0H)PVilE2(W2MIe4 zRB(*!g#wh1h#~5pAZ945<3l4I7UZuZGUT>U3;~thMC{5Y1P{v6AJRGpclL<+_fz^G z%hJE1WcpDs5Ma^l_KGr^f204VgUI11ko-v!XhMJvs`JKHpl+arG#^>Hs<83|Awk^r zbB+O3;=wPtrh;xP@0zxL#pI{e86%hNH@jAGtv_}hKhTR7rQK2whYsLL2pjU0^~j?S zM?T$9wqPovFn;@Xk;nTb^*hfzv8r`I!|2Q`X{mDWB=wHdHQnFUqS;PK3Yvf%i8>SK zac`CgLbC`ZjVv9D({k>=3+6@U+#k;?Jv=|@#ops-TOjnFVBX@*4(w6M9eGf1Ijc>` zf4}-&M~)s-(IuK-ob|ZvN>2WHH4auGZO;eBCthaxVU1=TcqP0%=#|5zg8rj%>?b$p zGBm*7DK`4|uhZFPk7o#f?0)}Z*361|6^7TWUhW{U&z6$^)v&FsOUh2!{`5a~oHe?3 zS|?WNovlW8ujTH0^7)3X(QUVd`%yu+itJcgIXp|| z6GOFdTVC`z+H#yrA8zaamb!gG%Bsw0J(qgfh9T+_K)S_PU?A7FSzmQ27eCrP6GR7A zP|aSn*x)(N>H+knWm(%yd*Yms-L!2ATl|xPNJ(V2sqU29W3;55ip*>?rq;ZBeA23V z0ViSn7%|U_xZpmL*3*izAvTJxTZP5(7FiC_F#-5L@Q3BuYL?JG$`jPmz(b8G-6M0$ zC4*jIz@}d#_bN3@<~WDo=cbeFU!MheV;q0u5EY7iO%Vh2^hGWPuAlTe4H)z_xcWDV z%p+cL>EI)+5<2Xq?ia~^TZ#1JToTmoXR8gI@s9&)$4QWO9=s||&;KWkJTO8~VIW*b z>@e|9Qvm`{FAB2X$6Ix2p=h=bqkv_sprn9d4(R>k?Nq&*1F)Wt(lSHoI7+11^d=qx z7wZ&F=Jj=n+R$G8P0Ufrws`Us7Ne&5oKL@Wb_;9xEG^vX33m&uk zY&^1by#N{`R;-x;IZ&|91PS~ z7VdlOi1}OqI*Bj#^mfIv#g^xB@(1GkX9zsw_cYMW*Z?f+73hN>?)Uun>S{>wufQIF zNG_kte*%CLS)D}8t^H(Z#;gQhuW-qAEw9Gu2V^HW8x9hbNK;3c{m^;6z!UmpUq|GN zI1^g|qHxqF(~P{%?+Ry91=F1(BMko4sLHv#8RL_mlqHmum^D4Qb+ye5)i;l9(@92$ zK1D?+OG{0Z$mI@}@+G&QF{Mpnm2hu#6~QT+wSdOXeSa11c_FLZ;n`s0O1t0Q2i)>_ z)x?VOeMz=Wk;ORt$@Xg|2bYZ<_T{s>&;Rp|D{dW)#N*&w@stva!^w)4kXTi$v8^7^t`y~8?K~O$YSwE_Ax{l%3)pa zq9`;P_eVQP!JPS9a1-&#vi3mT!XLnZb#hi4`jHn|-E8#+Q>9>J_KhmG_{Y19-upTI zaarYAm*oC6_{dwI(0lajh#ENv82~`yB;EcZv1xzWs|7uFh`l_9I@YQ$y-YB9-!3SQ zM8>fs-5;r^QJF9RPNsoS=0pX2W0z#nsH7~UEI%*l$e?HEN%SYC3i!P+bJLXgRUoi0 z&7z4fa9XB;k+GCS$apI@xb7mIC|Uosw;P)e?4tM#tl$xf_p|^9BIg$wsl12WkElnY zyoztvlH=QaVZHL)lZQRkEqXRF2h5*WO`-v&T9GAULdi|41{qcX?o=7g$N|6ztf%hJ zRiXkJn-=jUNJ9@LCy%;ICjwAS58{EjrC=@a7&LbVUDnwD9)Nc3v_=GG*L#uVPw-zA zzPbo);duTh077xxZHa+gBQlR?-slrAT9NBzg?q80hujM6S<=o%2^!{Zc+hm&Y#Zx# z1TTHpLW?`)_fm%p!~l5t~3z)`wl>e_aHP5r|Qmo^|V;!DQyh?_4mg~<|ha+Hb%z}FNedg#S;79xOS&S!@0A4}z)jz~Pbd78SLTx!345RG<# zzA?Bgr>nl|g(4ZMbQ3Et!gQ)ko8R`%D8fnws%P+1Y_fkxuC~3I2ak}n6J@Xynj+jb zo9=@nMUP_eqpuHBwRwTDr$(yU`duPrN{)R9i{Snj+At-)v?67$nayvR$wJKqW=Jf_ zRK2yINwP6%W#wJ{Y|beSB2-SC70ISTwoJO9@2}-t?`;n2VM2Y7X38oo5aws*k*T5JS(d%$%s`bw}-Ec9^2%H~BBxk)dB2Iih?tJRh`_k0_~vZ&?jy5r}p z%6Q+9yE#io#Q&*f%VR%!MgWsik&jlyur&L9z2#EZ_eBp5y*HpQP{DW`Ak3~6JM+pc zz|pXpupwxMr?Ob!#X$;!O?LPVEtvI-eO|A5B+M3WKBFn;EpO)f{ z^8T!DPVv4%n3c+N>MGSGZoi_NiOXT9+{%~ z)F)vOdAe}9w7{X`e|RoM{{^C+=!S(bzBxHuQkUXERoP)R2^?YW#!bP`_`Ppgh0I!e zBG>t1_vi3gf0PF8OY;WXYg)4Uryi388Kc@3AAP|A?*MM{nhqj2i`_(p!^ohX>*y;K zjZ>d^VvGazX8?awa0UcJe0^QRDasZ^GyF*N9oQiJtJq`}ocxH?H_m?c*PTW(E_*5O zOtKqKbS{pYu~+-oY2whDEK`cTXQ7zOe0L7gQ!s41yB>k3N@jDRj9+38C5}p6Ng$#6 z@dWtELDKpmaYKuHGPqc+dq^ht=d7_=5Qx9a%k;I{@0X<=2oVcu-^CG!`g)8ci~Q*{ zbYn_1Wr5cNge-A5WJ+|hs(LgY{O({}qE%|_p$QaVml6bgH;%)aIT5Fg4{O%ys`nQE zG9dvfNnVyKL!e?3$}E|9B-gfS9*2o|ii_9G=-%Y^h@O*7tGg@Pt7Qq|A(p$d#qBnv zC*80$pNCn`vnmaRd&W^l8FJrny@jz^EnwDE;6g! zo07z;*gP!BYPtr%hY?IQJ(P-HUqP68S-Ys1BeS%_7018+&IChb;c<|qEI6*3ihYq~ z!mCBqa)P_42<}?9V-?|6c*l&J#8iy(S!R}ju#5uO8+?p|iJE?33$BmJCMmD`r9U60 zWi6{z@62!;z!rLj!S}e~@ewbBlc=mqhlhrH#a4P4Mh-=Vt@U@hqTR8o9!`TgVo)GTgTuvi?IRW4mlCb&WvL z`THIpJ}|sq|LT%j$&IrPWT}2quy4m+1rPqq8ZOO2lE7oukGTon1Cz*rf0nvVyuDnw z8++oa__6lk&vsuljv;=FWG23>sYuQg|DF)ElHtW7*97x%m(}wm_6u%EusCIT!)x>{ zS#1&Ke}Cji>kQ%Xrr4(u_7Q9h5Ge-8vH&Zz`vI_WPg-y0MHb&yGXh=(@@}8Z!LVF+ zy+20RXd0%!0i3VJ>*|sIOYbPhaupXnN;4!xkaWjP6>?**p_bb+2_c;%OBtNg@7j}+ z$dR_nYHY~Pgm9P>2Wp_)glK9otjG7KKRM@NQhmd$kIDq}OHYNDbFaU*r!gXmdG02i z4o~iE0%LxdQx?7!q*Ez|MquwjYFzENLr=tlvvvbbo=WrXe*D}bupj|S4a!KAN#@u* z>1RFBzVjqmaYPJYhfEOr4TLt`5JZY!DRMsJk=|`MOWi+np>~~+73!plw@DVkTICvs z#91wC?kChcyFAHxu_Bcs-Hx3O%)xp_xYxKVSj_{2ZUhMN=Jbg*^;oonk21lMXVga{ zv0S0mZATeSzD*)^E@sdLzAkxOXylN zIeDU2!k^k-c&vy0GP=QKYFp}BBg;ltE|k$&m|i8h-*&`$w>r`B(-4(UflKrK1*lEs zG}-A@7w5TwEGWU4aH>RSAag`V9?seJb*IokE71sCtv`Z|uFLG(wyI1iH-FXx3BD`n zvlhhzM29+_^SWj4m0V;*sr<>-{Sc3k;W&JRGrBFaAWbu4_`u<0G*@5=<6^#9t@Yn- z9WUK<+hA2V%O&f+>Sr0f&zk!TvYlWogbf2f?f2a&;_Ai4;=QSbM$&UG7BIn0$+cj#mJ0!DkB%ka}=YqWhWM=SiNxpP;}_G z>U4@t#`Ra(eo_$e3x{se5GrX28KwIj)M^5s%fkQeWB^8?zxWWQBBA1bX2*&lALJL(Rr{W& z`)(QpMAx);QBf+@gp2mdCRbeqjH1Apsu!*TY#EP=N* zC($w^^ciS1Io&HXq2iMC`znKi*+`!#9MrKN^9NgI`=Th3%>4IQf2OAIJx#eXyYyI_ zOfHP6d^GQrZkh{U^cs2z9{~98H1s$vzg|1wJr@5I^1Cs<_k^REEVdE*MkRJJL2=p{ zx%V8fFgL91HqJ>BIObt%+thaf5TX2F?1U|>e$c#l6v{m~V{iaSIN|RH9w?e5B4p*( z6wNf_kjp;;nc%!}MFI~-HbhzVl<_R*;ahHZdAc7mVCnwf42_<*rBRyxBOx26It4xi zl-6H-o9lg$YV{e<@~_HH{Wx1UG`o&fq}`jamXg8GcTeOk+f<#qvKzs`$;vE`Iv@Ty&x2!cgZ4B!ejZHCNX1ByIQ}M>T&}T3Zxe zD>Pgs1LkSB5!+9YbF3qSIyC!FD?O5(6e^e+Nc-uBgeR!nK~w5_YbgEJ^@PqNoujK} znJn*QB8;TVz(Pp=9yC<7cPwE;E5X_j7Zx|0b(lmYoCNc;cPQG@|B8(BYE}$Vm7{r9 zv|2b|Vr73W$6HdU)aYs_>~Zj4*GDw;APfvg^TXO4zrm(W!{4)l$bxNP21s}RYd$^2 z|NXEA{|Vov&mZ!mqT&_~bBbz+a506g<7$DQ7u45%;`zgu6Ajiq}#)wh+f zD0P^~;98ksi%ys=rwI|O#8Gpe-JmNsstlSfdU2zt8;IQF0ZNDO3aET^C4H%S5yP7e zCREi5O)0glI6!>I13@WFSxL`IY-h4!;$!3lwd>W%AUDkukS^-V$v#1QJ)ekhh`sco zNqVUTF|1LhgvDOo=v4(&*2WmMY!fSnk7l9sJlZd78fRx(REjnrmGbUg0^WZm*c-C> z8!kqSF5@#Dyq|}q*|!&YDe2}h%L#TJjCvw0KW}T|gAAr~G=K2)l+FUq@sR%t@z(ZY z_W}pbNtOizNsj3{q-qITe|XlUk5}{ax#qXFPsX}JFlE7j<+3=j`!+kQk+W$xqpX}URL^-#PKJB)_yzp~^@;$EbiAx#<|?ly+0Oos4??2!0&fVuV2%1K@To2{eR2Z8){NtZg&E~?tRA0(1&3(W3!H%z0HaZ;3Ld;4l zLQ24+}aptJt01|JdFcU~U>ba3O-?ewPu zgn4J4ur+caOz#2V~M%iacpi)BSk-T($ZyEP9mFwbM~wBFkc=JBmxFGqx9`fmQv z1WA!4%$%_JAc>dfKI>~J70Olp0o>))th+(ik`UE&ni`Op@!|a^4>FC1A0GqD)I&gx z!^1}5yDU`?`-%v2sSNA#%(%_OWqiZbyi-QtByBqOX>WjI`N6?b|KNa~bBitZ6N*L; z6xu-2sA-h!-o%8iE}BVWE;d_f_ZZltr}%0&om|6@eU6Um2XHA8{&>5LpNTq1{XR6n zWLjnuAJ%%&Ms0(BI}yl=AR~G>AN*P6jwWwD#=$!MD0jZY8ffy;JlR?UDitt6NNAgXna5Q1G`4Ls-APHqz%-M%^qREdFmwcd)YJ-`7 z?QcKwfQ-jw*Yb(QU%)K01VCljP321zM819x;*_#Q`#@h+)1oySxw|$;=%ws9%D_d) zR-E;b9TGsAOVwslDMJ4B8^Z}nO^?^?V-Ry6d&1u229RZ>8Dd zY5{I%A;8F3=4nh)OkbVeeqXMz#&h|fha-I*Y+WDRwbl)Q@V%X9Y(~IjcydPyM|Z%0 z+Vpj&_h+EsV+1imm*KAR^;w!_%OVX;JiJ<#N&w$Z7(dc2sWf0F*gtPgFnn_K5}p*y z@`nWTyGar{KtVjA+T6H8=vu&&9l`miDNYLl@R$Mo==>kbUa!|ARTaV|m`8M;8K&?2 z%Nn&u69~dj-;i~Rb;miTmqk3(CXM+F?}NxgetKraV(~b5%8-NQ2N^>861a5bP2{nE z-=H0sH{`8c-C{6WZp^9v6Pdc<2LU@qJ_&mn1xX||$&hC$ z&{Q(v(Y&I8!di8OSb)Q4obA6R?Y&}w7=^>i=}U&|STHBy*4C1G%fUC8zwfk1ikS>2 zK8|f8e@PUuQ*K`Q3klk056E=5&Ejn#LcuN zT`ChheerpT&y}nI1U8*VKd_jPv9RO9>M#?57o+J5f8b$RGX90%{fF3lRPv8@`jVYO zM+Kv4W2bcyaVhMd3hsjXF*WOK$Ss^kjI?9RV=Y^3<|&$chWH?EMn&!917dcm0ax;6 za_c$<8?xeuh8xX#s$fZ)-A8=O7DkL=X_1`=(t#3*hd&lw1xq-Aplf>+j-URXcZ+HAd&1ar7BtjY=gF_C!TQ-gH`>(MclDMfymWpPEDLfin-3wCp46uo=MDSjSDwN~ z0gbE)8-E#`ia5on;4IWg?Xi)6)pUQnd2CEULaPGTQm1y9O_-L5Lv?#z6^euYrg**6 z?(~bB>PgXc+eb(wpQ}FqHdq`K&?M3#Cy^8G7D#xDJP)%$q_a8n!=k#$XeVr)>p1H= zlV@Q>eZ%{5nQIm>-{NzTVMKgX2jOLY49S{x&DKdwOif(EBCW-LDc~xJSPlKrD7D~5A<-6=!2 z^QUTUIoVVI|6vmL#>2mt1AJ?k?h^G-<($D}6IPRM8(xPe{m4UADD!G89!yPtVx3K+ zNL*vGXQ3By!)&vjniBJUE44lcR&57WA!%i$YSUDrud!d1JB(btF51$@0hqQhoL)su z!K#Yv&i59$zh#r1w~`rZih`Uq{RTs%1u49k8=Q%zR^Q1bw4_d4da~%mqB^a#!o3!i z>I;x;8>XbdQ@bM+6LNokF$f3ZF-rx}le1CVwwZz+8kTFBm^-R`36N=J5QjBD3ZfFr zC{4G=a#I6np_y#!Hgm{F4SaeYhKu7;g3|6T$yEnQ%EL=8CJmj-I^)<#r4{VkQH!Zk zPLFiCaG<@eB<=kHr}&~&GGF}XF&VIk-Pu}KE-&xHv&)L?_kEXZqRkyaw^Y@en2E;1 z1iN{g{2YBJq?YWMh%XaNNajJ|-m6e%s6QdNsGZl=2)`g(5_T{rd)<3ILrZ*TrP%l` zkrq3=259&Verv{;oAy>7i#;F6(Zk;Nll^9K29}kSaTXteM^5nx2$&|HD0|@uML?;#{e5*tK;s2U(>0PW zqWu&-@0|Gcdj|U0v22-yYX$pJMOt4l&L`vdyM=3)wX)j==ED35X0(=XW3DUFTEQ3X z^m#fyVZ>fEN!z}@C3cR=Gk_5&evBHFXz)4ZvX8;O<6jST+71b(T%AVYb-#}DRMWQK zOV{l*Ka_5(K@?%~O>9HmJcMiCxpQR^=XC6vMd2vNa5#0$SL+4ZzvvIL9hXsBmvGY` ztR}o*R;nQnYw1^;lugdfa3RKDK;#Kc#NHdM@00UEHkU1u#sqVU#q>?f=)n9VmY-=p zEq3xSsXIUug}d<-r|~n;QlRq*%(2`lPxh|w zGRHIDSuWM{;akLO8KV}TT-YhQC@YJt7?CO*#9+dx#GeNMYiZ)@UMls2?V7~Kh)#bn zmp8!90?;)i8_2r%*`$-sw+EJmb7rxzy<6dFUg`(CTkyv)LCgEM>d!$P2MKCkrP-3t ztxSO&{VZ3_mscMKVm)AaQo^3k6a(x;_5GsE&3b|8@az@9PGaglY2Qo@Xq=-m7(Dp^ z`x=(xyS0=xlKHQ(L^&r}RiIRBO}Mp9k;Jv(@L&)HL9lb#7wAWj(}90TN+Q>X8cnA2 zH$N#RU!auJO5cI^Duy^1OBnu}#>n3<`#nX?J(3Y>mx6{R(wH@3LzA}KzHMbJp^S7nco-4D$&+`KPb&J%2s zsuGzJ3Qzya{P%$j4W;VhAt7!nghr9>R#4CTvj^f8dx@&LEm#uVCtG0GVar1qSdV9J z^ESt^r+lQBFo@Mef`ElB>EPPwLyj|~NoGu!CR#+(SX{a-Z{aSQ z>eKBZ@fS8EaKKz7MooL_2=U8Q#q;qfY@jZuX2aAnn|#?I*b@=19#ED=o_e7nXSp|K zp~xB5WH1zu>?bGzb;GOkX^-VR7g_VlruJ$^cL(84U5mEPJ6?iJKMoE%xjt?6XA0&8 z1lxdNkS7$G;GgzMwt#82FEp{)%v~Hw3%<}eKq-O%?+UVW^|NhD(@o+IR&nxQ_f6OR zm0*`ltMlpdSK#8Nn+6n@(XqHRO!e2@rY`Gw59Tlj3f17_(=byI21l7{eKQw=n>j`r z8?XB^j!^x$!QM+&nv=}3-)Q2Os>9}z20UH#d{{BQA1&PQWjhW_lRyc)oIi2uWM6c$ zQw@n$B>vF!>0Yzi?P<#}rhavvf%QsAmnHQAJ#MOjMFHOn8o`b3uS5l;DdB7J$xFMA zp*8kQNtkR-`d2;B+h3@|7o7IdQJ;$Py(#7CG*g3`TV*K@^6ZN^O&0gz%A)d?ei<6! z+LUlE8vn{{DH7D(y^%i|3f?iU0PlmqsYE+=H;>H>@(B8i1o;hVU5z9i3br39Fw$;LHf8IRs z$s4m|%SqM*gZUd}>=;B8d9oofRbAoNzrN@7+S2K~F`5j{pLj?`WFh-+&wEy1u~2!A zX>1ymdfSxc5}Z`hdg0Q#Mqdw^#h~-Bu$Ld%ia>XT4yJ$^N2eH(Dy-%kPg1r?!l>mZ z79IL(NKvwXt;Unna0KGN6ov4-Z^sP^{ZqB#mc8GRL~xEIuy)e~YZ?>?5lg;xS?d^5 zw*7zrI)3-X#Amxc2T0xO%jd%3X>}WfBS_Mnd0uuIFJ?^xa4=ob&QJi#4D&S?)Sb?m zbtB=6EH|k}^Feg=x3F;a)i-oV!2A}CftK<9_E=a-1{HfG>GUXvpJ{FhLsmS{I?(0Y zdYi#-FFJwrM!W}eGfx!lV=wSUsXiss>D%Z=N!I*MX+DSTa;B@fV>up@Gu?y7LHt$G zVWxgMHtt6^HTm){n+u`zHnUUpv*)qb3)hYYE!(&Da-xPBS)|Vie~LveHScXYxf6U~ zE_@p#`+yq`YwyOxdds{Pf$A@_QZ6D`mk>^To_Q3}9>03-&D!m_0OGk>mLfRTms^H?3h$$CIxbG3;PJ36)>mjytM}V#0*4$Hr!UO4S^KS)FB z99*f#!r{k1lezr%bFaDthx0I=aTn#)G3ie%JsGgG5wMrwI z`1TA>vfbfetPGbm2QB~tTVtY9qW=%(E5%F{Rsm_`=?TZA6AYWgRY@RnR{xi6B4}YU zPxhAyl^$d8dYZ=#0qXS!e>4z(ob3Tk5Ma8WKpjY**;Uo&lvk)?!65=PgS9w?%g)BE z8;Xadtf-XmeB8$A*Q%TolV8c{)t1K1po==--2US!J|?`TRtQC?6!AeQ({q&L%a}M#1;W>y#cS*Q!b+&sWOM z_{;JTh8=2tC@sy`x_pr?`k>f}uCIJ4<7G}sfmmv2*+g3*yXicp=CRnv^Tptf5kynt z9xw1b+>v^T8f#WZQr&lv#qE&@zmP!e{Mdl?L>e>ocUK=i&abxZ8_PMtc9=f4MQEQ4 zJ!|Ky^yI-2NhA^ip2K0fH8P?be<1q=Eu~4*A0JlXflrY`m1K&BnGfsl&j$@(MG*Ia z9t@KsU4+}TkxtmbTpNSER5on5fK6n;nblVZ_2crfCl*SDQJnSug5q=uzXf-F!A zaah~QMtraD<7h+E+YQ)P9kadd#BV--d!1}302j$Jqwa3nNusLWm&rRpjcD722Xs_) zz7EC%?$XBxMIm0crSBs${r~{IezTT|GEE23!?v!mA|+unTmf6VDp^wJlkedrJ#uyP z+Q$^@$U~xhvv%S2tx+!T@fpyFfCZT1S#5JtqZlZvS*aL9L7b-Up_ z(?rJ|t~|0`=pgP9_t??{`{O6NV!{x6=JVTJ?A~E8U=ixdB<10591HDnjiGc;Gucqc3bv8$o4P3#Q%O%#t4aJ}nsdAt@TW$z_ z9Fyqv`l2duUe_+w;AaC|F%C)@n9RlB!|x|2tFKJhlLGClY)v*>}~NE%yk}v=VYpK_D@kgHtf<9-0%W4VF3kj`QCx9 zo2A=F&(rv|dFN&~(00`(Gi+1?{3K)`Bj+{+o_tqCN75>v!D#+Gu+)ZY0f%x)`SS%t zXabkpCTEDv&ODsLmj#Xw(jR2G{rPQ2R)W<)Z;TyNhLWUp7Tu7C=+Pm-7~dvJeYV-R zshdV>Ib2)?;G|E#*|S>???QyD6uyIF)#7o^ES7jPmQhw(gr#yPk0tG~6_3eZ1~tCFSE8jFNKm4*njUobhe$b?59 z_4~dc-EUVMW7)k|=okUdGqqfyHuBHsej}3|-GiZm7j}_)N4df%Yt=21Pepa6y$KBx z3KGrW24=8%7W#TT#%CQCw}W^{4dC&zz~$R)GHh6xEN3it@w6|cV@@gw@9+)dw)L_b zU6i1yGK4%DrPBs#Eol zc>dTl#L)>tx-x1>wIp}=tIlZ7dXxDvaa|WFANEn|Wcoflkzx4w9K>7Xc0iqMkO%5v z7PVVoza0w)ysu_FaNZ>522q?^qj7R%VWBjNk< zJ~Dp3a`~nDF!DK+_`3)F!y#Z8ai8K`(XlEouBgZWf?j$A@4`VwHpIs7T{D!aL1lm@ zc{YVBf8jVXL>0Vi9qk7wvJc;GWPf^J5_!W|ssdZqc;?>)1!NM%JcX~XH0jG?3L{v` zgQ!L+p|8AaF0R9A1od!;-F7||3%F%Ja=STncMOXg+eVFyfl~Nc0mf9)= z&aWF;&TueLjBY@Zc>t#H?E!f~vsC|`Ew1A;h_dHx`W%W5{S*ItAxZE@d~Td!cN?vB zEm8C>;-9x)pOAtQ4LTO`j6H@+2Fyl)r<&j+4UCsea%^9zm0y$~h~v-jnu;KSO-E7; zzBoMZw#EBm&m1n0U@s*4d0hbEu;=>>gRzB^{nw zu_nNAv$f<0+Mb6Zjy18^&v)P+$^8e0OQ5x(;#plaS{2Z3FG23W6W2mOQ+4M45+vLG zgHAlx=C^yr_v)vKU-iS!Vyc33wcESUa5_AFFrfX9FKpygbK(m=-!pIQyIghNUbe}@ zD8mhJgxUPZ*l2mV<|S}!ZS@$IUPmCAGD>&|=XdlCCqiOHLxDTV2c@Oxgzy(@!2NXtn;-wix~qs6t2ONxA&qS?f4Pv>@)(D>uPnX2`A~H68W7U zDM?$8G3BefrxVimF_RSdWgTBvn~ch0e_DmaOi&RsJd#bTVO1}nsUOClPL1wsjT|te`2Kk|| zgBUHkY+H1LtX_krxY5L&`ThOi5+_AR#PP6k5kCcQgk(9M+$~5U3t$hg_PTHJ8aY8^ z_awr5;(OjsNmJ`Od`kjaiyUyvWSIwN@ms`y0c@3YGwS=4m$q`}5jIndMGGu}&;Did z5mSoW)Ve;7^qm}z0AQI!1;fvr-$_NT{bt;M;x5nxzo~LK5_r|##hGwLOTX+{Jx0pP z+)fi@-g9pg>ZPRcie4;qsy3DLU0VQwD{bL{*VUPRM>>E6f>QU&x6`pLSXi;8X^{^f zmd^=I!m^{}H)PlGCbZcDK$+GobOi1f+25?6LdKP(hCn3eOF=*9x|@8*Y2(o(8P|aE z3}-hS4nVlB`5^kDQfC^@YU+{W_{jl*+_$*ro4}VZnDYbU+pi_XlE?!bw!dX8!aK@3 z`=yAMo|6W2oF!gLz8q)wS5XSS*!=Bt(RY-n^5mYN8vvzBv7d+>Wg-AKC;PJhx;a_d zK>A}E49~Lfq0mf>Vv8}irh(F_nmymaVS2b5Tt?j!$A57jQEGZI9Gp&ay!%a#J1$x_ z=KF2p5StfF4Hwe)VWgM0RS`!SeMi3XlhU4%YPP!S$_)?V4%WOPOJ9uYeW>He zTV+Xx!zkVxc#{1?LSHM>=jLfkvyd`E#NMIcNwmcB#QF+ zb}6H)MclRMlzj#zbdr{4DNJh~AU&u<(v6ko@cAHz-?4FTa_AvRL+#r32*0WT{{zLM ziU4qXe$3JGWxOIsEaQ}@kEo#SR)o0m) zEd#-9sI-NIUtef+W=2xd>0ImA6&Tg^T8YZA-ff_H zqke?A!xmYjQFuv3d5n<50&wiuwT+TR0*QZWl@^0CYD0;;&lw00+b5Dr4 zHuD(-(LgO+RGq>73@9dsbO-2X|6Ai<$IeaUA#QpcGYMX(rY*5JY=yBRLU-9&$AUt# z5kj2c0DuAl%ggaW!>(3VjkF`<+#=JHK&9S6j;~uI>G@1bV&20ve<(Ez(@v z`}WW>hj3U1`@OMz1b`iA^@jZ!gisx}ut?QiuG;ty$@~Dli@EbEPICVl(1#d_pua>r z&gS*)$M9b?F6fCX5HYrFSlTuK#IQ>sqwBH#vh@f!(%sGmcmD#l-;QtZkC06|$bpCJ z&iw!}sTigk+gy|Mu6K2z9J@7;5CgdvH{5GQHy`H9SkJ>6t2GSJB2Hry^|uT-0eIlI zA^wcg^V5e2(6Tm2kl9;>21(w(J=*JP*>|;)qcpsffI|5==>8iwg0Brxz@tHLwUd0qkgh*22o`>F;{R&$`l__NkKr$lzM>#TW z;)8akP%;YVHqawnd*~AL%>dSyDmc=`a+9$^t`R7{Hhf5|Y2Ax}{={PdjOqZ=!c{1b z<7{_vukk#u&#fzZ-ece~MZbBzSm7<fV?u<9m*BJ3h<5DpB{fq58{RJ|xRG+KlJf&IoBxd=-(ZkWQI zhQqRSv?v%TajeB4_B81v>!V*#DoF4H?%RIB0SsJ3|2l6QR9#5|ENvoa3po8Uc=3&+ zN~;v#2fQz7c?W`kwccbj&WxJ;FCf*|-+IGyZ+vz=-0<_B_*|@i{dO6u2AC*|_82?w zewvWA7dUH?ErH%K@mZ>41+f)B#R&0beJ-U)?YW))dd#&x*p0?pn$1)?;G*o&*;78+U;Ih+n#@;|L;Q9R?_6_v%FN`9YLH{mTFAmx(e0;P@&B!@+!{_}&FIULj z{DqTvt#k%dd0K4t{E;!#zq`Y9*2sY{|FZ~Vo_gXSPu8Drq*=CN0b+Fr`>W}9Yb2Qd zcZU74<)5+=;@^v>vOX#+zGAH6yBiiKXA$!rCZ(1~hRRAT4m>{yimsi@u?CAbZ8(8| z77Kk&e0$J7LF~f`dsL%!?dFXz#uKVMRramD2m7GHjvR{HeNkdT8q_NzVv`Bfd5MAJ zB2Yv$u!xJL6IwW&{4+qqblwqiX<0FW?NC3J<4-f_?qn`meHi!F68iX8P;X9-j5W5j zcIo{}tS@CFP(k1)r8PRQx`|)b!~Y);COFWg7(!CiH~fxhVjsZ{=`e0&$>$s>Ok^B7 zdI(BkM4@wiIq0NVS@|+H_CrBxresXK#nkVb*ENCr-h6n~l3=2WUf7x8vbkSynMkm* zf60x#`Or8uK~^C?-(-AOdu5`P1c&Iow1UEfd&9J0dW~*B?duP0H!Gs$%E!@h3&sU6 zm2AUFgLO(NMhf%v3!RD<$4s?r3;c4N8nk?qhY(>KFrRyB^Tv5OSv0$~!r5bq)+W7C z@OsdkC~bNwhjo#y19^2(xPk)%xbWC!V-V7!G$YyhX3Ws)M)=1tfLua2%jC#l^tWwZ zHLI#02K3WttV(-GhMw0OCq25an;#6F$A?uvb9z?7Af8RV$4J#U;wo#9&ewfzaepIh z{M9*hg;-9~;Tb0|{E9xw=3q#GDZh)tPzEq~J?I-)|$M6gyY+vv08cnAOauHS_XZ(Jx2@Rj7A z6DRMk@0k%IPXRiog?aaM0F;jPf=+Bmt?$3Qe6hkvQNYHk*qN%!rB}XR@g)!eY#<5A z*mEse1W>jZ{J%BLO)!Vb0>rML3c7z6>v<#k_G3YX-@d&9{Xr>+3rj=%TG#h0`k>3M zNBrpF*V`G;w(nzgAoe?`E-)tiKKYR&2cLuWwJXfAQ4^COH28OmJX|q$KrmVqLXOFhN29o-O~r zBtR+i5vT4caym*!XKso&0)PGjJZ20YtSX13V4C8JkT7R?8Gry z2+;^m#mlM+LkNZeXlT!e)mf4DwCyKJAD)Ui+%*e_(Q>)&*nwAUDZBbS4=U#KwD3a4T{<=Zu{wzKyA z9~(2iW?k3Qkbio?S$3z5(dmidcxD#a52KnT)lI*P>dh7q8j~HhnAJ3d)Qaseyl0AW zLW;MHJ(a7XHLJbq&o@!EX9!V2f7UBFCMb?9FP(O{$<0dHb|4<_}zWY-m$O?%scq40;&GU1hpMx}<%J zVB5TkJnkh%N_Jl>=Zx5NkA)kWDR9?ldss6(NY(G=Y*fj{;|0nqEP6~yKU$B_&ewr~ zY~+iSlPnHo&c3v4@uhI+OEU&|T>vo%)s~y_YF@2UaBUUjcBc1v@?cJxJU)+jZ=E zwklFKCq&=$=Tf)|xrw)|gC6bl{W z{ts1e6;)>!HR)o3U;%^^_SLk^Z|(%)mFR?mP&}FoXylg~=IZ#bCep2V&}>|B9lcXa-zZ3mi9jpk3BX z=w>24C9>!lasgt?86Jl%m;YxKwzLWXb_U=cC;=oOcqAlE_ zt>${)y1QDQb57`UDpa7Q4w#HdiQ%K;etth`Gz39hNk@gH%y44sn@!BG#YPsI+rsGQ zT2=(8u&D>^*#lCLRG%;4Gq0)8$kbzXw^_H?Z~h6ID#3u7i5X5^_r9OwumdiFo8hdY z3i8WS&ovcYOg~nNWa#1rD~>Ecr9q{j*qBQzI*GTZVtKe+43_0Gfj6O&>8bR47PgZ8 zodRBVEAat11N#JJKRlQ-?Rrv2#)32~%T1R{L66^d`7qfS2 zCC@8|N3nr5K8poUQl2T(GcH2P2%e5)P+xx@`%2hCj#si0w^_B= z#S%ogv7O4C?8#+OJ^Kbbw^;L+>qRBGF}+S~bJraRpbcyVQ`dd>zXsdJX>J%idw-*y z9-qVH+CfauliygF3vSa~^+YrL{FD2pSwpyiO-w^*0nz;y8OlDF?M#XZ1kK@PO2=8Y zI1Ccy6YPaz1h79TkIXqauk`4WM>UlB2M`K=rmM6V!q-psPkaY&*d=$~4Jq0InkX&W zxq<72?ik-#Xy|SYJ~}=LG?>){I`qq@LL@oLX7O}Rv8ER!{1#`DuQ9Rj4_O%U{uEaU z)JkVzQu-AU>y=8}#}hIaOA+75@`%6#5>koxdDk6qK4e(T=mX8=b;`($hH{AeMWw4I(+ov8(hKTyV5e6Q?ezTa_;>ipn zT{ohvw^4e(G{e6TfA9X94Le!FV=2QxhMMQ|`1Oj;h;9jy@h7{O0d;+hL+|?!@)>d3 ziIpts4D9b^Q88A3zU(J985y=a8?NF^`9-JI!ljA$s=OCf)J(Wa22II(zg2jaRcu#R zxK*5Ts5E=1_!zz2JpG2k@&nctlZ*qxJD_O-m1c7lMEi2RUZ+ewrnY9iUR;3o2$0oy zZXlt%7MIw3cY5}nU509*L4d( zB<(fmelYxDSz8;bFM5C3S#9^#trX#}gGW7CgqcLZ$&$sN>pPERX}B>N)I?GVR4RP5 z!Ahw^CAP3o@p z-J;vN4?GxPNAl?Zh(=QA^?j!YCb;EhoSzTMqXUCFz8<8$w@H0ZWSO62#&dyN5t)QL zDCrLDoWzAD`9{UeA#J=#XEpGz*~_#+9NBJUA|~-v$SF?$3U*nl8YFp}%xeh z?oG#uEx*tA{n*YrE}y$84#4YWit3kWj3wj=A1K-10;v4|* zrD2iyYr`4Lu`do@vxUep*y%+sLSZ2aKuNI@4!d7YnNk@9pP>=C-k!)F}G%G z%mWQKbpGCupXo-LH#10nSd<&0`DFa>fqh)?@U6PO?I}S}t9`Ves9GN=VoQCCA%m-ba2N)<(W+dvoQ z0%y;^c6uuB&p68FuvoXqO%GC(qs)z2i7vmXp}A3i&c5ICTnT&(|RW4*Xf0V3U^bkC^~K)9yDe1@!C-19YTId3{{jV8RqZz)S;ohR@etcw7W5QY1CDIy2TkmLbN<&`f-Q*kXR zAU&~zDAMqhzKrk9*wJKuQ7O~uh(Ro+J8nFFGamlOrDoLNkaC}vFeO5M8bqxv`s5H= zZrkmt+1N!Wb=6iKRW&qEZ3^40GjuDpUNLbymZ32-hMw-`j9uE+T^njc+=&JEfc!Y+= z9alZbq2O=tS4C$7-{2{CS+ao@o6n0h`vk26Ac=n)o8h8>=Gk@^hCz7t>h;}V1@x+) zk9aY|Yx^-z>>+6n*GYMO2|Kc^bA|7(SBpz7dPViqe_;4WRAxh(3qsybEs2kERDl(` zco3vaMh*lxKH&A~9_6tQk#{kv>L&jn(oz1b&(p&a-Fs3vOcXcG`nV1rbr z5b(iXkhiNIYAUQ-CBrHvqedO=*grfvh?c4TCZp?2VhVCQ_ zc}e-`+kdjU6WdNQ&+}jRulLXU3GJ61T3MGrAKQ*kN(by^ICPB3Ga$IRuDaaw6LD`s z5E#{{Yyb+IcQDZ3Xvhh;Q;bX(Zj?f2_Sx$*@hI}TLP{;EQW@Bfod4y#@nTp)?Vthw z(P16eVeD!;Xj>$Y(;YB&^}~mLpuP6Lj%+&rT5=s=-ai(|-F1Gu8L0)>$H4Hr%>tUr z&UJ+IVQT@47k7yu+cS9vJbw(qt>8(3uzpVN#N}+xdwLv_51h_szhiz0fKxBG2F1(AI;m(G2VK+g06{n9`5+}yuZK31GG3K z#6K?p4njhj-rc;JYY*Hm8%M()1z-2_S=Wt_c=N*)ExXJn6f=7K<`y;mHa%_B3nLo- z6d)>FP6?QMf1lAN{UmSI=%rP%tB5&ED_+PImr8!qbu3r(BvtQz z=Pu2r0+o#~wsV*;PMJ5Jf1#+P*`dpmqWmrCO5H&sUBQZ2mDQmQh?flr7+X{Pel+CH z`%>^>gS`4oHsQ?HM}Q4OnMD1&u_@+Sa!7%?277T~$N74B>^N=H&EG#VuS><3T3~+9 z1BAdxJGZ=SZ@B>hwA}&vrcrc;Y39lM?UB!2++InRZ3nP#r_sZsBt0c(WNm+cL^f^R z3haHT{!iPA65W>|t~7}3c1rV}WP*`n8ah>Jb}w?UDFSB-*m_lY=u?#X$zZ`ml-Ku^}Fo>aljD5U@ z$;c|mylB~lw9{8iKoL^0V%ITFHhxJmT=AIZA}mgwe+J-?W;nTaJu-K&vv4$3i~yMj$VBrP zd+mmd?!p6GlOHjnD>kj&h`m*-Kv$}_F~H=xN#_HVKxmX-0w!b>(j;-05%`DYEYA?TluG$&2o5(=0{ z5S0M>vwHHI%RfjU?*Ww01LuY3vW6L*78nqQzbcuk9RbpTIY2mGB#z7FW!xGZEd5~x ziOBnQtgjd#mf}*&o5>xgleqpvVR@OC3NVPa+n9ML@a25en6vXm72MzU5>r+Rr-QbR zes*36X;<^9tnS|oqQp4_FD5x0O%7_32FOv*9GoO&LYD2on!#Z(ltYzf1Dqh*YmC8K z+t}Z4C`3^=vuyZl(zbii18Zk6__z_-oifB*GHbrepmRzF&SLDFA~~vz$96@9S*2w` zMMp;k!I(F~P}az6<*A#FPLkP?eQ(m!olp@|@d>=G7H=J&kM7mR(|P@fF8~p3pGz;S z&{gIfiIrJ<-k;epM`*jB{{sLjFU;Qbi~sUYQ1UC>iJjOpc}eGOTq_Yk)Yb_Z<3xcV zt|8Qvtes;I6m;Ua?32tja}1}MAT}ho-HnRpc&?y$Klcd}@@HPM@bkWFltGQoyx!4$ z_1N}c!XN;)(nE3r3>{^_umKoMsyqg#)}3Zdmq&q++T7P&V7ro{6n>YGX3xE2K0!CY zQ-HzM6bALiD^Bg`xf^oh8IqxRv-26toSdx%2D)ZE{s-BfHuUkiyG{8E8;%3T1~gV= z_h*R!-dn%7y;WV^!`EinF%57-OEqlje|0 z9k)4}HZnTfQ$1vGFngKPlbXwUm^!trL9{4lAlwSVh~V{yjxr5d&gF{YHDcr(kkfX8 z2j*D9JZ2D?RN^t>O(#?M>l zAmF00Hp;B2#5{!GX{;V;Q+PD&-e2etz!CbPra=; z1+0S2tN(4q+RkcjyuJ2ggiYc5#DSbQLG>9K6Ml8KD}va!FSd1p=6sm29JSBXTkfOF zT07>TEgufCe=z_?rna&&>M3hSzhf_wM*6I^w|ndJeMkPH_xXp)oAxyC-T8ja0SAVS z(`Qr5vL;i_t*Lpzy}%|pn#`)z7*v{y_K3Iz2IW(&J6vn@Us3bt7 zR?F16{m|20alB2>O-FwfDB84gl&8=m7QO~*(jal6zacD4?vKryXPE4zSh)A$m2RcA z&+r9U+9!kMA08w@YM((tqmh&5PnE%9>a#{SmG_&G(Ge&j;ljz3}-A+py~5TUD``X5UmD zxq%<_E|_-_1Ldd)Dr|tFjkM-{_gZn<@B6+zZ=|*YFo`KtT%?L_Fipx(^4W2Y`;K5K zHWMEa;65C_O0PAqv}7xg>15jX3uwd!LQ#mC>N4-QLmH0fx)-wjsDXU(yz6uW@VT$| zn)&n2{0|Lb5{11x-ExV!ByQE-H_Hn#$zsPK-g8Hcq zLnYt6{Mk>@o{*4rk~st&hlY)Ct3scobls5qzklj?3~~+(iv|Fog$|>wUPY#`FqbWi z)h$pw(yU?vN0VP@(LvWZ-Oesq|Ndwd;xT`y&QGVx6z6do z+H6XCnvI*r+1Y0!v!o&G<04_UAFPoN8lluEVO8OLAi}t~v2;`=TsncdE#t;tIuYAf zkWiUncye^yZb^roiXe)BK+uP6p_11miI7C7HCm7qGfmL$@P`iuXd(KcA})32z7Hvh z-gj9FQdURiNizNZlk9IhFbx_Ab;b?X(Jh)(U<6B0=ry>zzzNa&x^>k;ka3h@Mo`yq z-Y_A#MJNNOi6e zHUvcYDIJ}xY?tLMe{w<)&N}e@2{x_mINi|%$P+e|r|AyE9yo)HE0xv5*+9v`N~NWr zXv$dwF#dK|*9p;DsHU9|FzTz{@$fJ`-i&+#`R`3lm1Dp6GyeCNl`tyrL6q`VwMOYY zzAHJd!+QOWIV@fvh)U5}6RDg+8_CuS^3@nV4h|qXk~JU`x!sey;aA$hb4(_MPWYQ2 z5h{om3Rvzwibk&QVuGkj5p;-cFrH2_%nVhodyF9(_GmVr353X8(vl!EY1fDU_`=@EuP#7pu zvB>}`rzVDR?Lf`7bW}e-p0zBp!Ay7}YR$2aXOK2>H}i{PBV%t}qJjQ0yzM~PaSj-e z3t;{AB4f?wi^ves#_8t07T~mdV^yOv9zY}sKmjK;mlhJ42M(^T<>qOI+kz z45A1THw?utjGTPQqjmk?=KVgkq*E<0F+7J~9!oY6WU2o-Iy#Pxxld^BFu(-%5+Ooc zcVg*I8>iu{!7Pxa26OEk8vkMsMO=4&hDw&W=Vm$1iQK5WubGH>_vty49@h=*SwZ;U zjZtWYx4oRA*q%`0({@V%g$caK;=M3Itld}LZk6S4u^p!te|{%vcq|>3rC+D&pryhR z&&&OQ+$ls0Qtuav4Sxe-0N-!#(A~O?bw-RK!rfWI>=Kx+BWYUfDZ4og#aFDB7N-2J zaC@_len)RqT5eWww^p=RmvrL9;E&+leP+tS+TLIA+(Dt9tEl|-D6Girsk}i>tJ*-OjxM8Ih{>WayZ@R2 zgf|bW!w^>Yt;!r7dvt(p@{H* z=34>nUEHqSgcDC2#!!9i;Ua=m_=x`POs`(siobN^{KF@;q) zf9fUtsj0c={SCYK*K5U9G0g|zP(UcNR_S{?sL=Z zPt#?D9Gba|Xs43(zOoPg&Wo`1XQ4#DgxtO)&vb*;N?ev4lK_UE6*OFz8Pr&`Yf zLZiu1ag=pP8c_TO1&~F6B~G8RlFZf;+i)0x6FTm;k0cJvY ziz2f;M1IFm>^8)B93>5xUrKj7M<(*;X~MSE;+pbIM9z+|7`G^UwieJ|`3- zXLm43oVADv(CAcMUgJGnSYtVe;uM6ZBWX?Uz2}f)Fm}H%qVTT zq-8zVajKpf$QlY=cB?pS`u!Rg;)eIx-e0Ulw?R^FGA*-JE8y9#w?eaW&i%tm&kOjt zEq}Zp+w&czi^Z@^d&LZQPgU;JR5;+ooKR%j2YtM!l~>eMtan%FW;@S+z8-PJl~s(r z-eX&ZVjlsj8ZPT73`COg0QAIM*wk$V#q%Oh7+AjIRUmvzpyD$fOIUQdatV_nQ0EYe z^v9p1UJ97_t);NcKhgbK}>u&0w;lWO%FSYR^h~RJMRj4&! zb-TpDMmVi%^nB*X2krth$x-pMPkrToz(d3pVf@z$)z%bQ>Q^~>%wmjLRJmYH=d{-E zI|@1w*XB90ybfKM9j6t$`9SvI3`Iu4*8tIVX3_LNm!Q|yx42NR+8V{g1u9<}&{)mm zsxp0CSF(xywh7s`QOyRnygg6qI0Wco1fIgA+_w9q^!h>hcc*W zH%{J!H5*8;=o5|-R#=6c9kK+Dza?rMZ+nnFjsjMB zgV(fRja)-$bpM!SexuN3O#yskO@I~am8Ne6G#nWhq?;rSCCg!>Ot@9^Ak2MPeK$pm>hI^J>>8)oqZoSH?tzTgll}%^4#E7)*dt&%-A!LNJq!=*{Nqi<=LN`;a7~m zS*Dpwr5Q&|PQ=BV#!0HBL~=@pX>gFxZ#8r73_CSyqGEuD*YB=~H}qT2>%E6eaCTh2hI?vF4qe*x?y zb0(sIn#jMxJlau+?B+J#xh{LWe$^SO#ouJ@1aAyXD7MMsjMc81kDONm{!3!@8YrP@ zRweP=YdR&_HO78b1?*{{NT?AUsyIA>)Cows?daohv*xb7U5DLB;?GQFe{+j5I&?Zk z5Y%gCV-6gZKwA7wA}LBfT83Kmkf?<kH1$3h6$1Jh@4Pb}x+8qXAe0lYzW5U)M+#onEY716*eLq>U_G#RKI^E^ZIsUB!P2D8P^6a-?oD-J@F2m6Ax}dAQDk&>g#WZ#l`V<)XvK~VJURW!+7+pb`ba*@JwKx zS~NQGxgr4uQ+yOX+)6>r<2H}BO4GU}32zqrUXBuT z$RbsqxcpJBSIa#Sg&*%Pkwv!8xB8X`DK%i6v8WWO{}Z&&l;CxGJy5iu?HD4a%R*A` zy6)H`&x--kv-mDvP01qCEv+V`ZeAE%VUE+i`qM z^R8N?#rG$v+GHaqpgSY`@Uf%;<&oH^zFTnpIj-372re87{;-xx&lJ* zK)~P-9#r3!U~!x?Kx(=&R^AH8On|8*+q!WIg9~7Kr3=<)*8#8VeJ&^-E+BaKc!BFD z-#g8HthgV|(nI-vVK;%@T5$=)@BjdYR!L=LrQHrwn%1Rn3tAO?F$&Tz4`EXyIc^Jc zwUt>Nw|7*347G(vdkKIZFre$LAeJDne|r@7IALn*xDBB`1gMp-AsmLW2l?J-+q{kh z>7D^Ez&d1P?;dmvnLr0-1mG|z0nzv1i3(?i17C+IC?>WTb?^>= zRhDB*)E954CWn9sm1tFgTvI6PnB!z7MRXjchy5D0~8Vo)J3rC0S!j75Ec*O zE#75)weGJMePU7^dZ=|+x2Xk)!>U&6Tz8X{`5IAfyCEcWN*-sQn@(D|h|Akmjl4CQXh1{S#xOrj1dUCyAv&{J7oLMLQFXQEO=Ag+e*-TBS8woRkxNVtO9w_|76 zn9?0VFKZ@szZbBJ9M2sML{?N<^`ood?NR>?-jl&zuB|XL%eoNxrW*MR=^irfX@}oC zkoG*>$-fJ6Am9+_IUPtwS_e@MvTN)aQ%icY&EFb3zMMb~$t<_+x9F}hx&fUv&CxkE zlO@t(E=d5+oI3N8`$nX#5s0X7ZAXqTV|$qo`sp+1;jJpGzn}mOXe?|G&w6_(9r|Bg zRT66`wmkZDx{R-nHgNpS_L(ZG9ko?>{)p`#ThmE(FizY2Xx+l7N6sP&Wo3xIJ}DJ* z`J#>vUT`f9vK9>Va8T(>t*j4E@LJ1|B{%D-^AAwgU7}5Yp8RTw$t&Y3nb_k)c(HQj zh>~f)A`tD9BqP*H6q;(9>mjbTVx{t6s)BgAaBMSfVR*));$oqav)%hS73eC%_6d8H zE4u#*WV@RVQ>!uGZ-wvOHc>9*zvVhjFLy$h81;alYg@PZU!VL0ANYI>rF8gm?4=a> z_hUG$+Yfcqy>Ef(;3+#3MeNa|`=QW5!82DfipB43-#qEz=lW*;8d-7ZxqEWjPIaNhEqN>qiVv=zH87mnT^rj=% z?Rr)D1{zK)=Ds2RSL;2=ZShN~!d~2*gzyUY3q{gMczCglWZikQ5jQ97SGc6{7ctvmu-dNg#FV&*p&=aCCt>^uG{C|rKmafvBV8+e@FBupvFKKydW{?FIShS0&~I2X zIpUO|YeM#Mu$@<=LAb)czeoCYg$%#h@X$^%&~Qw$oMm@}{7b^Tf_?+>uIXIS@$zgy zeAna%Ol^oc=NwJnJQyrPUJ8Q3-53W~^TqqXVN&|%ZF-L5x~hgr@I-od8ypY%#4XND zqJ7=KF+&q|pAN8W`U)6n)fRCiacJ)9Gr`MKg4 zRomP15HxU^jKU)_r%POv>hZ9IBKaE{ZC2+)eED6-4vz>&iMF}ahdz1GWhEp^RM~PD zYz%vPcPrKT)Z@NN+Ah-N*{DI~qQrb+&?C$FSet+_(urV;Btx9ygJ;J=BZ7H?)}Ptt zJ+3BT)ffRBBqhy%V=KQ(LDKm;@MPc0GjPtQ?b}g5yRT6YsX#L zAPrn?T#oE5EaTVF#8@uT0MCdvW<7XEYh@*K)H45JeWGb1w_kD0I z(o|50fn0}SkF1n4?Z-{{qR)IiCC#e}r-7`d6`Y@`F)eIPh*Giddkui27(B`Bl?E3; z(C_K>x$6GRa#^kfEZGv36`AgPho*V&28p=)tP8Ud>E6{fHCxb#IMiZ1%EWzu^yjC% zw6CKhd?=rP+kYe&vQ8QGwb_{Wwa(^n*Q{Y8Hia+cb+Z)k+|l&sf}hLKtr%f$?=uYY1>O*%}x@)mFXh zdJPT3aKByK6GRUQz>#+#PV76!|A8+gTe|9G0Gipi3jo|{TW!Rz?{Jedc*rDA%zqW= zVKel_U*)gb_J52(%oY_Tepe?i@spifkQ3Vir2M?yipoNgoSIf$gh&X#>mU^VTI4so z4hyuRjVRHNq#RN*9SD1XYyaKQ=nXU@Y{3oeSSW=l4vuTUWS9>wxhMkWHzA%jQA>Fx zZqGD%rb?gf=L0Df!AZ~&0JhYfYSI{TKiAq1d_h`{mPRtr)Zhj9!7 zGtM_tV8%dV4(l+j(QGtG#H)tvI`Oq)0lzCjOgLp={eld^sz>QYg{i&{F9H!-eMAM9 zi%KLysje2l4k1H>C~gcGCmcH}I&Yl=u{5Oh;+cIQE{sX!gUgs*=m2vycA*#@ZGpO~ zg#A>>`s!~}L#^rY(J#7qjDNR}dZAlL@pApdRJQU?9ERIX`~2xf@SnDP9$~u=kuWMO z6Dm9<1GA4rhB8beVXi=Z#5*bWu=J9~6SDYsH+%wz?^W%lXO5JB|vNzuhdX4X* zX-he|E~I9iRS-kIz%$@&5Q;X9{z%~e10|=rB)A{bI%HA0H4cOP1A>IcwROwTskmYo zXbx&;h1d9={?7(*y$nLLg4uAgjh zuxp_&w3#R2U!LN$+)azs0PAl6hS635{dC2joFrg(4=dq81ay%10{H`5?ouemFLnDs z21(jz03u_aiUd~dZUshDx->gD+`fHpg^us=i}hdfDiQRu6mUDzahYgBiUO{{gxVe2 z_Pgo&W`nf@x%=8)K5jNaRtce~S;-d8q&}Lo83@(-5kHWD8S8`#U`xa*`kmzm)H*Wt zy%n?av*`J1dtIm}8BbinR|xS2l8vn-1Y~V)@+~xIHo+KR(?cd(lzfHE`CXnsa^S1n z+Vj)lZ$Ld$0lmnfo#_84J62hT&^G{vOj^G0JCSL{Hw9s$;z$rl2M6H=56vs=jiC#G zU>t&dfBW*peHN?{#w{W3^sywf{^ETO+uD~Ee4Vn(cTy~VjA@eL)d%}}*yo#E19_(- z^kfVI=5HbBui(~w2#jTE5~=McCH1HYYJv(a8gLXPr}W*wC-uw=D38P)A)GL8AE2r_ zrS-#2Mq$ggxEv}gpjDSL*QjjCLm#jBb&76)ZZVD0HKU>%dzJSV5K>?Q%VDyd^3u#O z-knK|fD(0%#}QAK9E)!41j9MZYVf2#s-|6?pm#Kf4@wnd8X4-Qj|CaxT2p3%_sV{< zl92Mp)Olm8q~$D1Cif9#6V;%LC4IJKo+e;&8khgdfpZPiG%EOiCiqRKK}7?B$~V%? zPvwX!^=(mN+@Aed^@Bm4yUA!=eQ_ zq(k|lN^ic7sn2i7;*(5b(V7w+KO}An%cK}3KprPahSe$1{A;N^+2;gqN=+t)jXSA9 zba7ojfh7L8(_nQHFC7cz&bY&*6xW2R5xMA+h#UPOK8x6TjQ5`}L!vSIPmUNgAzpw# z0pF)uE}q|84CU45b>oJSOXWEI=%-C4bVk&?H94LV2#%%Yq4M$&Sf)8J@CdOk52G=( zYM;SUY}$CX!JI#^?LPl9o}zkp~8T#X=ELmiCV{?1u`38`Ud3cz9p*Hp?=&+?oia zec5_~ShavQ^u&}G1S6eA^FJ%kBZ2VB>ux5N(s8T~G zwRy7n+I5`6==F4ki<0MMd*N!r=)v3o!;|9`8g}Inabsv8q-hD0F5V>}Zp}8x0`JSk z=IF95A7CBZp9tNL^o^1~5-N~>OXsTAUBpMvqVqyBbO`gR`z!We4Qb029VsbM6fZ2w zEF}i+`p#s%m-$3_gBZ4P0S)u4KSDHR6mtCpFTYSdxp;M4?7Yzsec)Q{t>T|nIDZvv z?S`#TrHp5XVE_7l@wdo=6ri7!8y3Y#`agBo#{NLO9%6X(t#O}XbLlupBm={=D5%%0 zdWG!vev9inbN%G~*SSNtmOP~69HO#}8AJLRifbvuapoJbfF3q)@eJ4!brP35KIH%> zcIl<_-+ZrEfdS6w0i%9kgW`Y{jD3OumPP+$BtYofhVZmzmL@T!V^f}N&Aaw$S^2Py zX!HbFMZctLVrbOP`1Pm_I57XY%>!F;S&&f)mkaEmB=oXQX~z}?<$6_QBegqJuIO%b zHdabV7fE>JdJsgU=97!D`;`CoEW_*F{wf67ZcP6OuUFPkz(p`<5qKaNPbpcFBS~`W z3b%=lG*~Z)urx5+H^IQLGr-ZB2@X*5j8D40ASe7do}DGjnO@+@k;s{bMy2pATmbpy zOgHDmHht6sLt zT|)JH2I&i(RS}cPVNvYq`~AL4Ee#?6jyIc9!Y}f0Ga zqBLx`_Z`O`qv&djfzb9n{|e!v*Kz9>Afdp?zY`%ye9XT~hB)lpm%R#Y{5gWgQ0n+XkH><}FrUIGh1{|qtKxSz)$L{*u#vD+FnV>Q>&`j~?;+~VvIr+iVT?nzm8Sj8Kn#$_^BFzL&XAHC6`*`ykyJGy0GxwrrXYYf9Tx|L)28fsR&*thZ6l6-}TM~;7y)> z)fN{1l&@dbw36Ua(`haN{)V(X<~3()EVf~MO6hEOu~Mh$#=M^((2SqEx%q9^9iM<2 zE9Cb3XCo!UjaVW3&}rt%`x@2;4t@zRhV`qZT6(ytRv-I?qico{pbL$0Q{&RalJ( z)+_x`Tpv`*zr@-O%{$c{&lC%*_Y32< zAV!ic2;@J5C7(we55k87NVS_<%J(;MYMlL+EDQcxKm{fB+dr{5PCBB3@1YRi81(GN z{9qg@V!=(*q=KTE7iJ{t)lq! zV6g@`VIC8ALp|BX0SnBgqGCg^j9@lCm-XI*TQQ;-+mRtB3N)XCCS!xD;&a_k`0 z-0tt3>2jI6o?m;J5vVIC&ZdMoo}Q(5v)9)NGwz~3QD48ChT(s_=Unl29c3O*@!o;9 z7)XCIvff8=9d~WmKZ~1BLCj>I8oI*%V-b6pjr2PZ;(VKS zxzPecsQsk3ZbQYS7nEwjOMkA{=DO~8&hQquuS9ExJN@y76gEA?=HCt$RCJrSo?q_f zvnJF&ZcQ=5Xq{DhqZW=L-1TzmQZYM&N2uVKI0OExq=-IddwRwM!bsuO!IBxKF)Zt? zdUJ>7q38$GaGTRhu~CwxyZY_Ut5a(6p3>ZQP(5ER@D-m$? zn_HFm$~NB^`{2S6S9I0lnP?!aJ>C`t@;5ye^JsjvEpxE%$#0rCLu(kQD8?58NAWdo zBLflYl&W|V2s~r$a0A_6esKQysW+n2DDJ(3ihpF;pVYb~WqmiUuh-yd>+X2(s+jL4 zD<`>*sZl9vn0dR#S#s-pR8Mwz@1zNEUerpR=J1@l{DKg--zUv_$`>@67eIHJR@;4_ zJ;y&?^njbgYVgh35KKo5Z;khEu|&uIj|+t?Z`@I5rBjINmlr?|(u}?Io8DPD;RTHE z-C4h!r%{x0MuVAk1T`RND8pLmT?0wAGpTperXm$@D`TSQD@xv~bYiMpZidddxK=GI zD>Q7|bA@5gTePl>z>k1tycHxyCJw3riN8$0?2yuHnU}b@x9kTxg6HC6!j@ht^&UuB z%e}KyljsbT=33g%>%~&;Ucj2pV!11xV1i$-^x#V;xQ-WviJZ{*d7t$&aEv5I*@$t` zi}&uP)bPI;8B$c}=D%Y4aAtA7AB4S_3KEQ?M9PrA@RuQ>a-vVh)2$4- zZag%3u3L!sZMm>5%Wm~*Iv30}lFz}rkMNw@{3?1H5XDvb$@lMWeh0XuoBICmCEa&3 zqGma$4IDQbqV*FmXKF&D+T-fqc&eVnlP->8AkH26h+v96w5$~hpu?;6WIB7H!PDm-@H|!(Xad`VmRl z(ECV>$YAysyH)c{4mNlOaBsgR;+1xUJZ=R0HKut!*pTE}wmZge)w?;VFYEFOj6|iS z^P88D^fRSVMf=-3dh^00_R+rz7-FXXfj*39uA|ZRU=9=lUClKwwk; zINXj@`k{bNM|E6}(9q@wm0e$i9>)%)_|_d*ML-C#Ab~nIPkK8_i%>yTOAg1^XXmH2 zK`z4{@lN9Wb<@v}ZX8AIe%Xo}d?$}E4lFTg@Ti!zgSn<}A{O7j^OBm(Uy8mw-q!Lj za{&ji(S5L>%&t}=>h!$org>jzY@32OqQ;FVAoR-Aw8aa^}s&h8KwnXkR* ziP}C5vebQS7|F$99*ItLlt(!?Gbv4X=|e#zV{V#_>cji0`t=(3D3v*f$aN7u}Yj1pXx0dSnrsX*t*z$ zkacDZ9d!6x*e0E=8B8cU!e?;EK=tZ1yMgu z!6d-NKOSXO>Tj$nv{x_q!;GbYfF_JR{egHm4#=AdKB~u9BxXZMQ{l&Tj zq5J**33tC1Ao0pW0Vq+#rWM_xKiZT@HI9CIL;%wT{pulT4#=r0e*H7e*Qv(!ZT~u* z(HCAH586Pq7<0=+^Hqo!!a15B#cG-u7z@ zO|7Uof2T$IAzpxMDy8RMqzYDG_P8PqUQk(l*sc=mG_ z$pz;CB54;2L@Y!dp7eY)<6V+=g#F`w6FSr(>7?O#?~rPgB84o6CDsShVl>igqRCS3>Y9bs* zg6{9WNo{*c&qz`y7~Ug;pN0;gGpS)%;0D*vK$if-$btXEFvN7gj9{FxI6Ak z@wzd;+a%8o{+p39`w@ILDwMJE(#LJZ`XUHr8L2RQ)d@3K?(91zht>*;U}wCM>j78;W`-~epPfj*WxVDGSZ9y^a4pg_e%9#{>mT!6GKsCq%n`D5gi|~!_R$_( z*L`A5zhW%00^T?*KOaVk2DAQ6OjEp1(BZE7+L@dH)14x@45Jk7uCanJa=`wOViAuV zA|GfhHy#BjKBI>m`pP4+mYeq2JIJ9Eu(Mh7I^vECcxUL?^~{XJ`F1^j;CZ%0 zTV_>REvaCMw*7W=Yc+4g)dFR=J_6EmL5=onE=!(~pL4Si>EOCv^_YPr>9j(tgFIvcm zLuwmkBVaxsTgQ3RbXqPqZ=(M}Iw~7#5sleHdf0t9L;v2*RADM~(0OLZ!u}^F25S%1 zcHKXZ^g(%N$GNG&ean3C3wQ{)SgvF|l=3aT$_Z{N3k{A#u)pHfb6y|w*8&}wdW74h z;9GX>zoA-w$M7(RVEn`xO&ti1XbhtgT!f-;FD}G{&)NC4IyT%NBWX12K0s4j07yD^#TG2KT8dn}4VpfkhRFZfGm)53Y-e z3AP&x6~S|}wGvC`F$(t41llX0J@o{X_4Ho4io~K9w!Pild1?dY#d+yR4To&fR+?^y zdiG?j)ogq1Rd&P#%w{Z#&Bflzmz+?aLmx@{AA2@bTSXXRKZwI*e5Fu^fD!W~eInNk zP8ZUu^xr%MrS0LeiL@588 z%AZFp%8Cg$IU6hdJnP$F`Lms#)pz>^uGa!%#WZqDCv=#n_fe|Vj#G9_IZ$!3JHR^; z)4|HOMKoU7mUr6SskggzwXxZ4nN$SPi=SHiPz19H3AM=uvE=NsWjo)O2;ITK|Lf2^ zv<%W^>bS^^H-R3ReX1As{8}~v`3z?=SxvGMZ=88JKKFCdm(MUSb-h*uSsVj7&hKOB ztZ?wk$dR^0mYV*zhAqiqw#g1{iGxcRMqYYgH)XwKRcU>rs_5#7P3g%YAReJ!SkZ=B zhe}hH%6=TJ=lyP2!z&}?fXQcskTUup{dngwGl|8&C|=F&!!u8ZgA<(U4CT)wr%P7S zw2}*@s-0z!co7uDmh_QwPz9N9d6efTZq-9~lnQwu57|zPlI_@X@$a>KaIKT(rYYKkPWI7A6%Y zd(Iy1*Gh1ZwmYhg<-9)_b*#WjwaOUr&d!5EW+;B?744l?zAxv$2sv- zP8Gx^@J~ezo5SdbLSA?vEn7V(JyOIX7_exkF}jZB`0;O$4BogsHO1L!Q@1<0Ay37Osxgd!T;{xEX(882Kh zo>JMO4Fp*`^K7*_p~~7gw-tRGndfa>Q*YjA17mW&{j*;5Sa+F(6K`fCLBszSu@x$AGSepQ}Vb*9N_U5%iS=r_|-I0x2ezQ-LTu`q;N#bl<| zf6e#b->5NR$gLzzjw98rw|a{zSYSm%x1QF-F>bM$B`y zBNwBs2S0J4shClh!aa_IQ7@{s_f3t1-JV*uA1-P&EFy9D2>K8OL#A(sL;iTct+?N@ z9b9dck4VYK_J#Fz_7Zk%EM0zVE;LQM+Ci17B=R4VbCsZscRSJe;#YrHHRg7UFQ3aQ zAYc%?f(~f~%+=M(_54pXx=C>CimmN$lQU9BzCxYW>AdR@xoroeF-uRg z-im72g;I>h{o$0?ws->jDbL8a_h^fY_}yLZol} z8ut!nS+>3biaIhi;*BUJt5A4-Q>X-~PvXiH&j34{k_>A}#xW&2JB-kVr;gALTRlZW zt@E+kK;X+_T(HB!eYb?3Z_XXp@&fHsJM9G>O)HM;#Dx-bXDtk_tjWuAZ@T`Z{$!Sr zoL_lx#N^WFk5;KESXhV zRzq@Ul)dkhOvFGa%QEcvd94(6>AZhcTIs)%{f2KG7zJ$-$Gm_ zimKhOSn!uZwxP)0z0hHOw8^@haexkxU%>bXZ@HT+%EyhFvO^R zrn16*xRx2X?t^3*;?0Ne-v$`_Ubb{p2+QHfDd!tHlcT{wFu{m(2QtFyEX;cpu_dT4 zGK{C>>fcwg=a`ziUct>ndK*={mzT8l5Rx|NGvqFA|J3lU092%VJoJ z+CLNAr?b}k8S;e>eqzv3UN~#LVB5tW>qB<0*D+enJMe&W-*9XtAh2Q1AfvbQkeXQId~D_{PR*MwUfmihrZ)Nz}6b(<9Rotf2`9B-vmtQgxX;h@4!Tw;DLt z*_hTf(^oB>a%l*^Tkn=Wx4`4TmOkt5nk0! zEvvh}1g!=am=~4_5s@KJjf1^y2%U5{P(YzIA4{#(j6-ZoZWCz}YH*bOWWAFzpEa#O z8s7qet8$+yA*C`6w?&FfMLVq}Dbz8YggsNQ3xGIR>e>uh^FIvH4k zwzqrVS+=6xg+68Oj7cCT!Y>W9a1O=hoe{A!e%?$5>)&}{l+E@#X27b%U`UPh9}CYv zZQt(!+GV-XpAD^I zGAKl9T4D5lyn&`ykt*IC>Ilp>cx5Vl*~A#rpwOa{tNJbO7X8>2KAlOloM)Q*KBPhH zGb*v)dc3Km!%_OIuM=lMT~)^SfwHpQZk_G)mknD3b)4hx$+T3V@)&AHM;VKSWRK2J z8LR3EYHbcLf>@@M@7(_Bn6Pf*i2s^bwj6wtw@m+N?PZbx$?V|r)pt~LN;_<66i>KU z1ufS2-lq#v{ziXd;TPT2t!t2Oet&=HmR}!tsmN82=E;*y1M&q=sMrqwqVZRrFLNMV z<=jlpcfzM8(0*1ncBhE|YrKPW=wG-3h*yDF8S3pRCLCJsl#ZCr)T^N(HIs5=t@ZSa zK<~8nuKN@Tn9Q5B&_pbi+CM24>tEa41V|1LgLYVg=tyKBKCzJ!^Bw_)qXW6Qz+s%` zs2nH#=x5;FNuiGci=~zs^xjb=Mwm)>247BXwky|r8IHtw!yVSlz1{m(7dFIKpAky( z{wrTL&)05ozNp>hAyi9a;w9~@KB`Xw4X1`8zS4HCPp5aSh9uJUo8o`fneUrWJ8)A1 z^|AYR%gbov!2Ohwm#||PH@ucU<%_NlcnekYv%rhruX7xTO@NwEvrHqR zSAT;@N_&P?P}%vYt@Oak18SVWja+xCSq0}sq0}j)Q)3pZX^$nb>S0$z%mcFkAn4Kf z^R|KDyzlz$K4SR}GWa2GOM3OdduN01aOEUxx~ryJYXz+W2p?*y8$|%JN8W#}TIF;D zF3JMWB|YQ2YMryriynI@0}3ln;5K# z7&xq-+tf#{Tuob^u|`%>*fMpiv|Ij=xYM-#Exm$HE6Hzc$ZYjpHh;7>7o;wBfU~Cj zgtDv}kWC;~WBd2_W@YGj@ptG{KzJ?e-C*vciB<7i`;s@+-889wvGyw^Gbb?qI`Uf> zUT@n^>I|2TUxd_ixOlFhe-+|G3S{dL*I#gl$xkXVd6FqsTt|KBYCTO0zGN76D1#G0 z7==nH$5!Tx&dpkRCkPLlt%6ZdFVg?4Jw+DN(LkUdWl`C>WLXu|mVKrB4l>{z_jy8D zDxN89at`}{_)J#_RS9?+6Q)glzoKoZDTe)jdl zFMl#FeX;+@@D#y~f`df=otRi@{NbAydJ#~6NdB%_zgYN_f(WL7TO{rN`{hVf7l)Zc z?^T@9+y4e7{^3G2z3-xB%nCkibhu9J15%97r=yn{SE8`v+Yc1bjS> z@*6rf8>tEh^TTPJJKI%mNxCRJmFE!iDY-lqp{0G-L`R~;MX70CX7lkCf)aUzH8l z3iDa48S-!a!#+Wfr)=H(_ETE4JKlYo>9MV7zP;gP=XvQ!_#svKh=$|O!kbwj$p*mY z0b*g_m;uDHp?BV7&|ImUJrDstC2;YYz1#)&0gLzb()i<9C&3J9=du{@%i8hl=|xbz z23ts*%#!O_vsPi8$ZL^gz-2%4T}gkrl7$2A)7VX=$t1V8nz<;SGpJ25w(<05cO=a{ zF{-XcM)Ic3jRx-?DXKRz8s8_>w~|F~SBt6bKmyjqb;!3G4rr6!pZV;QpieuMX&Qs* z58lW1S&e^%CZQ#GPu8j|R!w48g7KB%?Ve{B?HGy7c!;qal{cO*C}QK@Ea=c2E|UD= zIu1BT)haI3<1mQ(l5$D# ztf!~cd3HaBt|pLXwG=L7DsblLq;NS;?k626ctL_Ni{h|Gy-Vr z+g(jea^PN7+85v-dybaOG?yZlrEv~)XF*By6X0_7OBTnRD`aEY-8PNXqBXM-^qi)6 zhO_^vC$^LChucl+IKkxiLC{BtnR((y2nI1I;0RoNZ9p<>VtoS$jta3Q*Sh8(O;Kv2 zH&dtAXMwYbhn-zR^Lg?&hOu4fMH2<@niV?&+f|+SFr@9l=t1X3L$ZO=X_s$>8LXrv z*rmk^EN6=e|LcX@?*s|B7TVRF4uhfTyDby}g9bZTvFkQ))$%m(-de;Ub^BSn+X-*Q zJMm3Vgqd<9J*dt==!s@uKVKTiPE?yOu`jP~%=Ljn6PPg8Kr}+4oC@bRLop zdRf2Yg1mjjqQUSE@57i9a2{^X`e+eK=Uxe2rwcwt zdN+NkQb|j6m5Qr1t)Xn9B?B*osen8PeRjOofz7Hs0TT(AXXDp{t07xrEL-mzGIO(L zJ>L7?LVaMfP3oeJmJ4ORD5MJd+fegS9nvQ)Y^q?0CvS4)tJj;DzUMhK>ZFvuUqWR? zE7VOI_}S*{Gi9($X;MhXRIf5!2&l(!s-wG_nTH^zw`ErY_w>Na#4~5v({zC$*~b?iF`Gb;4$?un3lC_r;s>E@y|`cty^m~YAsLDw=DTsDXS*;f=qw} z8r~B6P2jVo2W*Mx+Su{sr6XNz+~DAY@bm9hat;*kx7Q0&R09z9^Jzr{+4-nf!>vwy zh!Wy4yPXW@&sF>oNRR$Cooox1lC4I{qRo{R`cjAOc>X0>B7B|tNmmDl$rqhf9R8Ey zoB>Xx8(m%RRRZSLjctv-ub~-gijnKd1uk~3xLIoR`Ru93;NN9Y?CC8$Ci;Am@e~#D zR*}+}HjIjs%TQGnXFA>0{}4+SID<*KAt5O)qO{(NM6;mvt@8+U23U->+P8ccrA+I) zL7lNNP$Zzo|-|$tSz-fHQuoNnHLilB&?b>m*-Z4FaHqTwzvtM;3c+hne zaBryV@>%W0W4av+jlFyvCifEl(#n-Cds2fwq%MX~k%sTo(T~I`I#;&stam*Vv!b5FTKz zrWc=Zrjql(C-EXZxme#W`x}RSaF~osUIK3Rxf_oe9ywH{(cD*jn>C#1z)=|>ZQMk@2pUJ1MWkJ7D}HdQ z?-{Dl0R`ZqIEl0IfPKawrfS?(WlAYWAf+Aus(7*+$q+9_q3-|39>inc$O#9A9VYik z#$yZX@^Ss*e-+bR$bCgM6|c;}d7ww(rK({hq)LiuIQv>E_W(R97Xt>kpFU526GaIT z{mpsNh3Cn?Ts*{Gt$Ob94xl@)wIe?hod1xQp~ZH=0t30*CaLQSFYM3uLxR-x*+cBV z`@i02X7YgjCGAjLff@>dqU)E)FnmcM>M2@K#vkGS=RHvSNm=^2)TBjBM$@Y3*&+lB35= z*$68tf|j1QR|7qUe(`;`Bhqs2B~B3Q887E805vRbisv=zyMDGX|13LqnEc%Kosnen zO!ID1zuaY#%~BUQGL$^mBEV;ZR^}`-&Q?Fl(&^_*BS zl=jAkISCO8o+jZZ#rtnpkGLO{k9MQ6KAul>g1pX}FWB**>_Zo18x|N0jeWq`pHxOm z>l>td3 zeGfE#uukTN{)9c1e1zQgEbm$uLq`$+0utuCo!Pnv1evE2qF>|GR0#wUiK>_TbGW|a z4j;D_dnhd%jr>M#a@~ApOOXDDCp}RQ4GC$=vSuC~G)qi3kzsD@~e}e%ELD5LH=a40e^Lw`gc z+RtC&Pcr6?&02K}Iz8&QJ2~66J7LbS7d|Q&CQ+FGT8)_koQ61etffe;eqd(t-ZaQUaC504xHVX7XRT`9R4(fT?{Qp++?_(a<@UdLFmT7J^j8zEx6eLyazbo>zlO#od z5Y_}7W`W^?(GMCYPExpEH{@v2jE8ms{+PON-E=~cqo<3YWV)f@E|KX*tF)==1gp=sUrt3a&a zH@D)(Hchv_6ZZ>2MRLXXeo1|O3LL)qYHBq1)L~S8)H+3CI~o`M7Gqt&j$DtI$52W^ z0LuoG6qOAUEJEUW-@59$@g)(X{52CoabV-4`c#+r_d7`~cwQ(e?p!lfU{9MUk|O?Z z!29ywf;WdUP%&g`Kgt^Gye492CwNNvNG8YWxda+buz7yfrYz0L-}Is8hhZapL*aziGl@1%44?dR8zF^YtLc@O;x#vSuBGhdzv zSTj_*VIa)BcSGf(b9-LF)t?c?BTwt=Crq;}eYr|PCq*IfgS=FPXqWx_rDY=PA2VzU;U)h`ApFg-L@9|T7zdl-A`E>CX`iu#q zEX2nBak<;?^Ki?mUC|j1D`g_Xf)R8GUsPt=6NMF*~IrP($^!1eU0{r&!y81@I7xl*%U+_ylr0k zc6f7FHJW~5uFS-M_cZ0LO*T#+TI-2IZ4rfU&E-b(Nexw)-qNGPMWW!{BaYDYclD6Q zQ_p!q%?i2F#ud;-mXcNf^mZ|^dB7mjCUhyftf|B^mSS)|@)wC(Tu^@JFNHg>2_a%p ztI)wSfevIn6#`6LH1Ax+zW>c)q-W`# zx>NkiALpNcf|)jnJvGPM_kMW($We`4`@_$@O}>}ANZAXd`RfFw4hmVKt%My|Oan=j z=Z8Qh->|}y)-aBaW{u|34Ec}ym)EGF+3&Ac`5HFT0nCqz2O}%LkCzFxam+g)AND#mG%b$1`tLyrNnPjI4)C#?MA7UZJdI`a{8nzK zt>C>0Ro1(Fq+H@tp+RAy82+(7qf=8(R5VE+n0KeMW6ZT1ojI?>9QK|14p_7FjQRN; z6-iZCuYWJPIF|!(T(^cWOHr&_P(9>A7&XRsHzevQDXQQdW36%&V7GTmS0;0Wx!-K1 zQM>_%25%gVM4E7-e^y*22xnA`7w#~VnVKs`&|rkw{=DOK;}lM7+7Ig|@mDz?oKe4g z?*jboe6guRIgy<*odDgJ=q!FS=qj2OdWBkm^Y$ZMcTX|A`$5<+Fz{*^?`W}SI^g_V z`6#dH&pn5EIQy6H6?scDQ?{-7V1L>k`mkJub3su%ZvVixj8zN* z?+@I5+3B-rFn{AhJxix#`ooSws%`T-KGkudVFyV5Z6s`NG31Y1c~(Z=Q>+GX82f{? zO|*)#&Sy&ce%sxrwy-eh+n)q71H5+fH8onG<zPXIHI*MBElvmI{!Mw*d zIhzQu3>m-foob{{Ftx0R@aMf4KMp)E8!s6cRYzZyRz~pZOfn^mTi> zDAJGMX{t0M;PvRI`1G$y;Yo%_t<{+w{kIEsrj9rxlG6}rY2paE*_^Q6^l~E13bAyO z4q+68$g^7O(>9K85^4+Dz9i;eRVh{{tk9bPmpmt+x^ra!UJqY>NfIatS}es=u4PR{ z-pkdfaNO!V+#Tt%D?qY)W88K*cs-!0*;*=I0T7IW${o1^00+88F8<2MIWpuL&s^gi z)HzX!j4f`svm0seQTGg(itoOVTqDbe3xzqjTn&2)P$*d0n4*>HDi^T6<%W>D#4!0f z7e@JK-;bCQ5o3)wL&gr0PMWkrKs*eVHg@f#YJdzI-j%6R8q4#%f689HY}ad#Q~~=z>z=!SF4$fK2%IvRr;l zxsZLiKOlyOleo&6gd&s($7?nlBtEH>l`k#P2YMlld75A8p8Jl3b(9IjB9vn>zks;q zinnadljUa9C{RhhnfS?$^2QNCM{<9)bK9UEYj6-^RIL{-N;(EH%B4T^U%u z9{+O1Cq94oyT--`BK(01+D5=)?@g?=;QoJDzWV#w%j*nhc1{nOch|%|uj~fk1n%ZG zo2EJ$AMnuGSxOQ7J`YaG+nUcsq-AACL_hqOB3*yE{TC(stIu<$aFXwFA3-?D6io z8{Rs81H8dfu^cr>Ek=&FaUhk2+ZTql!qG}eDjLeJDrTZqFH^rmXTM@XUVjg+JSZZ` z7z94$?&O;KpAU5CmEON4Dm6z1&MQBf(?kd}UVVt_mN(p&_fbic4&!~?g~#Rym&H{( z?*2y>m&o(*aH-G!c1^ma6jJ`pE#)P?g?z``Rclj z6KH;N=4FslLpa!t;PwuOOQF%RB%Ue=^mVoO13Xf8sz&R@2N-HQp~xW5ADXD9YKM8P z(wz2eIeIRjHpMype+wCcP~WB7sxbW_{W_6=BlT1d8`& zvzx8U$D7oBeNb9O60RGBdLAId?8gk&7%f^pT!7jrr4SizywYKEuD~^!ZazD16N_~) zbyx85C_+;_8>&uRTrTfVe$!bg;x&9{zunM~lxIip=ugcMDv7qSs3%yAe-?Xs6ZOHU zqYE7+H9i7&*hkvL4YuT4imVrv26DnOzU%s3MGj7M;a@mIkhCIK(bYw!Tu+Z@&Oz&h z@xPI5T+p9+=UR+>i1#?>T@}Sp{{xy67%q@QG{c-Z-v>U=BYF4ryrieMYbi*HCWvJIZ^=a%>3)tSc_x9v=YZ*4#cdiC6G-W@ctt zy+s9RAU{+-3XS9GVeX~LwWWsK{vsif!f_R~mhi@U&lHRdbUe>Upl!NMFpa;4;&tu( znB6+^8)jJgLeRk>Hn-*XaLx-*Olik7&TR)b@D#f>#&vN>lFlS=HUM3Tz9{8pPlh!4 zB?L?5Uo+e%!Czi^&s@ulkWod7(A3MEGuU(KnEKgWn0)lq!a$DgUHvJ4)$)SW3WMxzVCQ7u zcB4Kp;5toM;Jt79!+yM#9--W(klG$y=-KDmH~6W>`Z1ez+8CuYFvpQT!#sWei)cjC z5i{UEqd850D_j5hzX@F1vNqSa^70j>Bd8=m*1IIMsjQ(`=CbHPMgUC z8bzCJUron`CQ#WA3cgK7uBxeBpX6QOeX2E8G5hB2Bnx?HXI7@FMbs zl$z}=*pmh^ToR`?S9CyY=X&xU0YI}H5fu^$cbQse_c1utfUogTzTM(gx#Hw?=&j-sY%q<5^VqCp zioz*a*zd>Bz-?0QMLPvt1EJamQF%jJq=Jc>`=r?&mZ9~~{K zr^1--D%OS9LAW1i(fq*)I@gfC6>JE6jym%Y-0m6YEgHzTxnup$O%?VJ(1C>tBcW53)#h8I1S$08DHnD8g*`rF%`P{ z?)ws2+v%i;!LQHWkGtKw1oD+cT4v&FU*B)048Vb)r}Ec!hzQyQfuGtbT6_;1?ANwt zte^SXg`jLP6M3st2BKHgetAUF`@es;ISi!brza?SWXR8y@<;l!3JPP`LifPT;|Zlaox z5psr+x4#2y;0{B1oPP1tM!IRqge(~-=C(l^cP65bVUdiEWj(yToZ%8)68&IXy0N= zp;Z`D#Ay#97e0nZ^gmBn8M(6bMP!TcJKKw9m@)U#HPXC+x3HFHf4BCceg(a4x4E0M0q;x4CX3LaZNI zg6Ac?rH2$5Rd*KzD6CEU=?lUB?`Y|^OW}Xw{C0}60`t}3hLJetuX<2gOMIE1>VxVU zmrBpO5H5yiB2fS`zPoiQz2G|Nj<1-8>EP&FGtk4C7<04Zhaf5&?$TH7`dtv-I7Tik zB(s8UYKyJncySw#+$o>9yik2N-GI1iRI-fkkdytC_DDsP@e?`yIh1JYKcrR z8v7q|h-}X#2U6OJ04Hu2Ae7ArP#uD>VMPeEbxmP49)WFoRiFS0nepsY*S*Yc9o9B#s|_K1j51)yv|oO@7i*>r|QJ;U-4l8=gIFF1PQFZ1Ud$FxIcyL zfukr)6QrA>7z&U;vIa-yp1qHc4`p^+z&!+FTSsi^e(Q}@Vlv<7OcqMZgxNtX>9$jk zud`ZM)Uo~2)CfX~&1a8U`+Fu76Te5nBGoP`oX`T`)M}xoLR`%y)==L#8E(s;wNeJ zlQf+EVk*@H74+SvU5!!JcixlAd@(QId8I`u%=r8XYDaFlo3Bqvp$(jtA0JQC;MG}l z7H%=l(C8}Ho@htSh{v@0+QrqNkL1hcUgjXz>+v!`_t0g$26nt=zN5^Nh;`eFEfQA8 z4%@5AI5J|#RZ9k~_{l@5af_WP8&Z1lT2hBh=N|Q_BJcG&U&Qp(GYLcNrLRq1RwGCb zO-gq-*LUB$LE}9iZ)I5XLpKs6)$2UcG~76@4}#`K;hBEtzEr!w{aKHf>*~GW3h0BW z%dSKAS}o(|uytI+H&A;BO3X7iW-K9s+;LcnlN{tZQ5DnYyKSYAXn?1C*BhrDs=`ZP^11^?PGl;#Ns zfMHW{Z?_d-#A`7fm-|)liCIPhU%A~Lw%$jIGQD+u^s;G>&le|__%OZYn5+?Pte}El z5Gks}zBbXN7h>>2*Vs}i2y_@)Tj%?5k4$%84Z93Gc%Hu*%a*P?ojx7UaH4J6JvS^` zAW5E0JGf%KhJSeXXjD}3XehHW<3=C`%n^E*IWR{ra?a8uRFd*}m!_9K3;vW1{R!n0 z8e&aIWzz$b!+Gq;ejut)E%Lf+*O;9*r6Q1b3d~uW8_8kQ!>o%lj~^Py{-`}_SrXD^@tDWLLA=@J_Vj9K>JM>|-4CwVooH7^Q3+5JEZRBb|+bNTS$ zXQM}8R~G3GJQL?QlSzO!p-J)YzWXr(>hQ|_VgB5o&+~hC>oTIeyLh_cEKEB~wJOib z{thd4=>0jW6z;xWS%iewZ1??zw|P})n3qXD(Co2|cjblRSf;MwN;f*UV<<`vv<$EphXohMhNXBJHYl+ffvLj;BeAM6R16D#|gD82rGKz5z@tDI{QV52{J;y zj+%M5f_y-9^JX*GOJjZE5`&uS@t^hS=qI46%hP)o=u>cHm8kD@+RP@)JnuZyPW7rk zRbYjqWpZ9}_^p=5{VVDaX!X8hm6l0P{QB+Yu6}tYn#0iB!>j`=2$$f)9T- z!S}~KQNrh9%4rDI+GEw2X40lVtiW)N`@h5aa$F@n%gDa2u^OnsVK6+f)SFz?sc&@1 z{qrYp&F_M#X#xlGlgWAeM8;QFsc9+L+dcg~%^~t&XNB0itm)fOvWWF0hCR$SBy-pM zs~AN-mb=*mZKn&)dhLO(U1wDv{h*m>#DocV%BsVPeZp_pN*%o1X77w8l{!<)YrwDd zvK=#>Xx-bFmm~^TPIQ8BB8-~xsG6T^C1LJ=7GsvjvDil?Q7GAbb5rD3j}LP))&~?r+51wcW@UV3jWN?ikIWppUtBU;EqjNg+_;o-gdaI?ChuxO{`w4ry@r~w zhm_0}k#XU`wh-P20eMgEgJzoFp63hRfoa?>qmR~k!W6-EHiq%*av;WwKZOoyMI^Op z04XhU+eHHLX%A0_)|{yvjwWAsdM4PV>tpoC8vv|wg#)grbv8|!P`0G{fVyRZnN9hu z%^wWf_8Qq=^2KW=r+`M6?4498I){s2D23t5WcJwqtgnM$b0(2K+Fw=T;L5o{qCy(f zC4cLEplF#dtZRt=i74r{IZs#QmTRAjXxR`l3b+t7_=TV~dRms17X(e}n+rFq!RZP` zuQ-o?9|?`kr|@xGl>C(*G)F9g4?gH=5l8O_l+P^S5|=KwjPdy;OS=Mfb=^W{H*44A zpJ_?P&tI6*skt}3?Mac+De`H2PBzgvtVVj5RCa%{oTAc_f-3y(9Y83qOwchU}%xV{z&pD%B0=p<(JAqY`ea2o#MyuZ~yRd#6&bru5BxL(bHKIeqKPX2ZhLI zri4zSZfbv=NAIEn^$P&`n2oL^Ofn4Vap0f0#onVuGwzn_`9L*ti|_OgSOv7&?EafR zM1eq{Aw4rDR)X3WxrM@2&*i=J0`Pi`8OI&3fEA<66TA*x6C3YZZ5FZ`MzF}?ELL&)fw=cKp~lu{ zi5$-v0LuPu{5M)aY)?z zWChZ@5)vFL&2*i}h;?^PNpZ;AA&niV)|F!AG(knW>j!2Ou>}5Yw2(+7(YvQcIvkEluHzm9{V@=2TC-$z*{O)xn!FO=@&;yM z3npH-I|Y`y<9_9%Khxhvc5fLAX9Ga~7eEY~T}2)>%kP=Iyr~WamTvn27KQJP3NAVi zyqDHfRQbW<{|2nTJ-*-f1bfC#b&9;draU8J5oh}x=5%;t{g8eqauKTovLV#pqOoY` zIlql77?H1&5D?7$z8WFC=s5k!P~X*<4SeWN%V_@ht;oPh%%$SSB)<=#aJ*$!8V6SR z)g{`LJlIVVrv!-3*6f41KAfmDSvF;$bjzZ(z`75jp<}@ya+B?Tw%PrCn3WG=v`HLU z(7mce;AS7yq)u+ys3HPTeBWPzAa&gMHOq*h_pI{Q(&;xuj^C?acS2u6o^6Nz6(r&N zI3!bNmbI2RcxKc&a#Z(G+U77-D!iyIa_-6QaceUGt}L9Squ;&FX(TMdyYZ-hIK!!> z=h7B_p;X1r#<1@P5L64E*3OX;OspjbfiD+eNh(q&4hC5cSJgnN031l~0Gk<_!)Bk=Y4O2Fh;oI|^>qD6{zF$M!s?&FCs-va4jrnh37GjL z<)}aU{Mi^sZJSI9yPr)AI3b{x+*<0Y%;Mzd!!OeK&-C=Wk+#VP}` zp&dGJT3-rff5KTLiV#6XOS%tV^LCi}0NMFJonHFGr|o|4o+jc?(N~S=uFaw@ZP%dT zZDvFJI(6hlz5dsh+syMIwB3)9b9iq;bge*Q>d=%w+zi>?-8I^%@CFD7o(KuYwZH0>d5UcMm%Q^Ze{QI4MxWSS)@esT_!CNsgV{7I{fy&qe zM&@JwH*604E&eD1Q~V5-*!`D22#;<(xbTL1H<-_bvo$Z=ey}j{rjLg_I`aTX#&9qu zQAHP}g;X_ZdyaSMbu+y^0lp=#7=W-!jTm#Y789FO#&oj^rEmW%vlg?hWPD?%NIvM) znI@tgRXL7@X}Tj35`Q(%e`p2b=}{X32wY1eK7z4A)cpv$ufT9!kBoF4dkMooSubmM z{`P1DZa=JcZ8~QOIL=l-1xgOe{0hLEc~jd0c?NjKU7m8Ej4fYHajBx@#>&w}LX+wU zGlh9w_qHP=0+-(ugGGNiK^{cXpuz>D<$QK|41qThup5tHUn$|RGp0^zR!)NW)y*n zNH+*+_GVGXd%c5Hz37AFtukNP21F3IkN{pPrOwv;Heo=lCr_X)ahNM?w9xtiw;CHq zjSNp;fhEjVw}$pK^(6a>Ml~H_+V7A#W+hNHNutF`De9%k@!foXp`4G)wh3kgHH6~R zPi!!^nLWsM{X_+qd#c3jydKtEe|>YyBEU8|c7E-4>*Po9%QE}j2DHxxuVr3stqqF>0ZI>D_0HN|Q zPL#X=0LDW&RUkwhim`FLx-?CLWC>p4vMUHU;0v8{{~xaYGOFvYjoO7NrKKeWk?wA! zJ4H%bq`SM36zOisKb->7-QC^Y-L=;>#{InSezpULU;M`St+md1&Uwt4i$V3T?9W2p zE9KKcqSv#`&3e#sNw%k!)yuqQU!R$TZi&yYJ3G+?E|X*T+nW+J@^2wmn3inWLb5sN z9i%{@;@B`Tv`o6tS6|UFyFXvum$~l&Zl~ML@-Yr&1-MC6w_SW&dvrY z71E4M_qIW4Y_~A{vp^=KAJ-5?o_M^wtZ^m>*H3*W!*bq^IthSxtRf9L?r zHSXZ>bcp=34_gOlMA<|g8%&qp}j)zx#gr`VbOV?XE%=+z?r!`*PuqG3wY?z3N@lAKuva$!Xy=LD-i- z$B27vKb!b?z8!q~d;k9zdejirDn-Nd4eKQRU1?o{;CFLiWtLH&GkS{+^ziNQyHGUm z3hUME=vN1*<4H??bc+bsRz8#4Ljg2F?Hl#-9hnbCKOQci>sti5=*A`B zC30XktrVN0gc1C~dC!Z~&2&!>V4O(#hxqbzQUpIg&bRIwRSv|d3LKmH>^rvH9+}ME zJ~fV-kRRNlqVmx0Ha`z;AIDNoH^W9#tL^UruY%wwG&8owpcHDzBi8UEZ~7%)I$y&r zZV}BbU;bMgkHtmZGk;vbD`sfEG=tR_gV_LXX43A%`r_{fbEIInR3zNmRfaXc2b>0* zmfuM8%pgD;uk%64%x6yc-kGECfzsGZ=QfgxK$Bqh-8S8Bpxhg1WisDF%ib5OdpPFQ zOPbD*XSk?_2dWpr5ZFZzf^h-24q4_PT6XDUW-8Tc!P-?kgL#{IS9H5n1wy0W>uYnR z=+L;nr6SDn$9O}5labG*uZR%?5Q=pSx%OyzweLgKhyJ7nRU)x4Q%axYE6p$7yU@}o zQ^;(irxKtB5bjv%Oi;M|N`HCUZPuk_z{jc_pmib`o%5z3&e%c|oqq?hZG%=#P%Ev~ z9A_2_Cf3}nvSjkm(BMbBtX+J+$kmjEkR)cUIl${?Z>MFFz9K)g567?h`Z+Nux!k}S znr^I#h8hiR6<{Zc^6agbVR#Lh3ymT_AG8!92zxWC{0Vln19@Gs%eX)EJnA#z_@YKc zBB5;R2;H!WI%M*Gs>Q3!% zYDnVhy;Jo^KUt@8w(BZYSeL3Wm$EcbkFeVr>F@YZnhflL}OCVfYZIJG`=mj zjbFVkGq0htqZHB_`%eMm%r66e84rm?OXb+@ znhUMb=Ww=mrNvz+TfW`yrjZGtt0eX_c`L=$E7@;`H$MQwSnvNajDbbgM}ybP%t5)= zHFzi5Barj08reV;2&(yf-i0LKeN*k;`Gvn7P1@;Zp*Z7`Z3YwapF^Al{{g;yk-TE`jk15FvZ|XnULj!r zlm5V=UmO(?wVx==GrgsPWo?CUz2|4JQCf-NmF9kimANN9p;@1X^7r}XGY{c~Xhc@P zovjBy-Dj%aoN(Y9&`mkRM!nkg-l6`Zgizw&6lv>{XiXMRXzmXRK($Er7?#_14z{|Y%~G*KAmswi=lTmhwg3&Zbv z7(K>=)nc=-xz;%kAXTccAk%Wq{TXzVvE@!W{HI-i@GFU}*XD!4ds=b#b4*$Hx!1(-npuEl%{AquKJ3))exnbk2Ji5Yzak&xnavu2$J%X=nXDX41ZaZCffrG7WkqwEqQP=XDZYy^pQqRh1UG@`j{ zrX?qxChLt76L^>!RCi2gN;G`U7`PKjM*X?DL5W9WB8f;j1_I=5I`#kT$Txu%6B#ovgPRn1#y@ zXu^gPv!qlQ)u1emW3$hr77mGh)l$Ps=Sul*E-@oWsTpGWf_U}Z8h9+TziNh>>Azq1 z`E}~g^ODcN$FL^JbPwhSGfgDUhZFJ71Du3E*P$Yg_%I*M9(W>`5A8_R%BuWQh<-lH z7gB}(g}g?D%0!XGvFym3xqTvta~%Hc(wsGnpZAuewi$IC<=?|*8HM|&OFEZuH%VhbpxQ16CWgt} z-^}H>?kJU(faC2DS-@9Ozw@$T-Vr9D@l?_<^1FFM>zgF{&fUkPc0?@lC$~qri}JHg zYyanR>*3a$`Q3Lch=&YrKO3Ib;J5Vw!th^mKI^h3Zp2Wfn@=FUSWjSOe|?B%vjJ^A zgk!dZG;SX?U$wwMFey6zz|nZ$QSH?6Zl#<<6$?d9-64Q&fiNW2E6? z8QX_zH~kDtwfi<$3mXJKR*Qez2^?y1Xij$Ixt9DSy)2R_8qs9D`o2!wCP>Hy1riC z17^;#`$p)s01#qVJ>Vy8LGZ;R^n0e4dz?Rh>MAC?Eyo8ZmFQ4rB_#RMh?cjX)}@#q zNM65bbz`nM9G3py_b~W?Gd7hoi>_!|b5_iYWkQWkk6!3>mC9q!(IFX{8Q;S>4orTf zA=z{x>Nsl{J>FBFkNW72{KVOTjo``G6uhlBe+C0gM(p>-Zjz;+b77(Coh*M`u+9AV zPD^CcoFwy?{Ez6$=~?CFc+e7O#Bmw6WE=>BAtksDB&?;hfyzy9U^qxe8c_zc({rkL z@}0=D(O8b&xA3!H9ZgYLac)~bFFEbLjx)167K{bp>G;3S?jNn}Hx*5~^^c7~$5K9{ zz~hYw$C%6%+OWpzp_m|o14ex^N|T6?B&)wyP}fEGy{_vzB39W$2kyY8{h~$r^1t-z zt(dws(fj?0eb3Eprq;iNQR@!3V`Jsm0ZBfOTAx)i+4pA@b}d9juOU!sGDMtt>ZBu9 zrf(*v>OwyN2sNeArBrEf&G{}w83yZLjF@vvEbn9qj_Gvw& zwt%{Q#;cc));Ebj+r#R#8X2Tw(eB~fUb=>f2-gbpn@83@O&qA?^@&<=np8AGBVlb& zfpjE045XC5CZ$l{pe!u3&K>eB_YzB*!OEU^R9R_6SW~0%8=5FSDO+0&Ha-#=!ntIy zVNle}U~20tFqs`fNhM;R%(p&RG|0hlvBr28rLV`YWs3smsqa_y zNq7$i-8Jje%pq_CE)TH@rnWU@4WBKp-mpEv?1J^jL#}i$t+wZRHw?rzHrYgXZ+=vl zj>|MbyQ)mPVkhMqCj$}7o9xr4EtgiU#tmTQE8%8(B8zQj9DDA30)CU^1%|q%uX+{$ z+BYE)FlGK8@MgIXEHj#lvuSRT_a>JL#bL@D2~dXBWze+a8!pEW`h{x2R@cbch%vFD zpR$`R8j-;7N1N@BdZUCwzYDZCwaF*7EI&B@%FyauH2-`{3AE&CMLYnJznIM?FelH7 z`iMJQ-pIu53s{A!|Ng+J>!{i-08o`f7E2r;qPR?Ie}v@GR#iz2GUc1*2CjW%#Bzx>oR`qF1f5zUUy&-Kh*;Nf!QLS5ED7`cpa!{=Dr8llCOVcyR&iO^*Ql=aJ9d^z40L- zXfR9AIAD9sM-LhhHew9-$=j84s2(;aotO%NH~({YebRU+e+MEIj;4FBh}_h|j0LV8Bf1Ww3qg^IrK%mk_!jdi8pw%dH0AF5Ho#B`6M%AAaoatr9&K51KfE3xq56`j)Hbc2XzYDIh2v>zE}>37s``|>CZ(n{;!~Ch`P%smGx?P* zsL+gh?ig}ZepGJeagF%raIo_D0NN0a{W{fu3{t4d=?U`##nCM0Z$|;_wGC|TI0nhf zCqZl%TKGY(x%kU`Av{j&KG*CWJAzM>*pje1n?nL4w4|#90y=tMIMT=__1{q3XhQ~? zhCB~TozS>~yjq_Rqy_Z1_z~`4u6P@UlF7~{Gu7zSsaaA1|E53D(a1We@nWFp9>AaN zcI)O3%k?lXjwaFO+B`eL+hFlf#YoRBC`BskW5q46yB1wmR~n7`pF!`0I|h_pf>4jt zJ*MClBKeGFF)`2gc#7{^G?IR-qqkIG+Q@jL-TV#+V~nSt|^_aOxmxY>rd%j~hv`^ZEJICzIW5Co2mV zz`1@R42^gy^5lh_wzhiCd#q|@g`F6in{Rw7>a(z3Q}ihsN`T^x>1rA)AT|68Pcf}! zrFvals)od6P1IZ0a(&u-TSj#TE<~B|D#udFKv=Yp_1P9Rv|zCh4XqnEI9sNH@3}Ht zd0y@?d#+;^Pe2p|Z5QM0r~~a{>)ji*-E?(0=u!!|0BpmBq0qzMKc&1gX0 zGlCoBdZP`*v*okDWCi9?`9_erTnkIY8PGS|DZ^$WiA z9F-p;4B85ZbKO9i(#mhzNb>Vu*e3!pso3A~uI%y;_H&+uFR+R#1!d{R<_bCC5;;p= z=I3i?XRD%I`+Q5!;AD^k9~|`Jr|9!-Z0#q> z(?<&L&K`G>vmUOSjWzyD4CvH2KQKenh7^o^uFIhP4Lt$IwK51QqQ%2{Nwqoe)oPnj zc2BN0eOt`-GFB2w`%)p@!zg3m^WgYjb`Hy~gnz0L%XEs#*im_puZqm({mo5&1JT>x zTh(5%h&;pzB7|p}nLXeP93~eO$8J;w8=j6|y{lMU8`$5Pzx}cbP2e%~k7dvnWv6{< z`U4>g{?Ac^cjM@JR;P2AS>C_Hk>neB|0T(d{ocU+s7IEkWR|aAuynN+cQ0=gm8H-u z-+d@;gzq!e86E;C-jpWAlQGE>=a%GLp6cO zTfFbl@4x-Yh`l5b8ra3`3lD;)t0@ud`*yD+w4(H*(7Lfy0Rn%f@mu%iQcA8_OhtI8 z?K2OKdfT0aOto#kukXUFR{2IOxE-k)emgYqeGQTN$o17u3(&FxeSdy?QxI2DgvdDa zoG9ilo990XunP$*g%~(3_rn($2bB}KV-2xg7aBhvO={*h}; zyW}UId^06=*k6VLfS#4%6QHJ83w^^?kRb=jnkQqBdl#?XjA+*D*V3-GKAi)w^>{p{ z8kN#?;hM5mZ;D-MM>p!ybJok@*+s&~6Rj0_)P6G0mLCbyGd?P_; z8O@Zjsp4b=Yq1K6@4TOc?X}?1Wh9t*AqOsuQS)FxloCL(u6H^bS9QMXILOPJl-8IN z(lh8#;(oyRi=JS!#z|B^+I-{Q6<+x`#4AwZqr0gdV!_pr!zf%Ct=!%v ztEY*X-zbxDy}fL+yO$)>MY9$wLLxA=f3&>6G__9z>OMSrKgeQ!aLci_ybV*>?KmO3 zBL0l8S-*JOm6e4R5-q(y=ViB+oIY}3j$*PGA}nYqo80C$MRbJBjU;YQ6JXL=*OW)e zXEvb+lrT*!7w;vznz&_Q!kOPsL4F8{duxXQH3RP;EJD3kFMt;`0l>E&8yqR^MY>uz1O;vej~zf{Q9 z&Z5v#VUN(MyLxjO{&f*P!9cl|c!FT2NrwA+HVHu4yCmw?3wUz)u0vHG3l8@vXk<12 zV8(20thD|6`Dt#hL6MBJFhlGp)2!H24(0sQGD!~SP<46S;tNqIY~w>=?@RK|0txJ+ z9w~ld_SBa7hZ>H1eINPP{i%xR8WCMm1vjWz4SBwe`=sh1)2iZLO5t~TM}mf?;qmpuTb* zlSs6*&u?XFx)aWI@=P>xFoy};aon?{M(cZcG+z5q$me=+O!?GqJMlRq^zmyhD- z8rJ(EWUWVyqNdI`ALV>QzEy!}k4asTKY&a;q^+M5e(-Jzq_IS!x)L_gT~?dl2U**JCLu>XwB**Ej!aq z*Sx;M;{AFCq3IQx?bj0*iXo7LY|oVyoiod`AME#phk>swIP0gEi!DQ7J5cuqnJtOH z|0O)O7<@sV;3QYq!)kskN$Te6%~1IEeHNi|%+Y87129{^q`o zazXl-$h4>QW%QClQQ>OUsmp!IHk3QdHqFIzXQlv%VONO8+M3 zMUF6QmA~-b+Tz-P6yyVVOS^SpaIMGABpW{{LoRO=cC)=}yAB=2FkekM5QC;JTafq} zZ4&LHh9Zoy-_RDcv$;iZ)3Bq{$=+n#PQhkJ`ZRUT7zzh+yGw_5!*#Je6U}N@<36S& z2KII0C;5FHYp}gljGvrBAR=>9sJBx3L*Soxy%k$*iNLo75QLVdd(PKn24jOvt=e;r z-yR#YdeOA3H5{Ow|G0S_YQ@usihEzC#&oqjAKTEu5y67@&=%ayx=YJsX$s6?iL%^7 z<8G?%mm#k;z#nR6(i~+SEKMJ|z%|h5>M3gF=SW*1&Zw*` ztZdDXcX;!By4EKyH{AE2R2dyEELeeRKTvcvtGHt4B{b<=~?-)<*{oTcZB%h?|XTX;+XHPLWdu!%5`x z)!4G{5QfPx#N0Fa)F-{}D|R!?H~!@zP}`~P&@R5h3_)UFFQk+okamw>2baV3RH}|} z_~Yqo-*T*DzdbuUqpIMk8}caUV)Y{2d8Sc$OU3pk&EaK5Leptl zB-x>EFp)PM*TF$l)IuS}v9xa&q{n`zU)GR-C59%hHPEOEX!>->e2GB8F%6$E@_c~d z!MVT@wY{vVs{9k|qVL z!-2n~0Tpacxx5)lP|j!V6lm|Jip&2ThLFiDDshhz+8PNPl4GEOcZRCd#vUgYPt!1{cm=k0#V z4m0;?DtX)-yV>;zoZm>q|8af+P!CY^+%zOI@t?Puii2QZ=0^uaZ3%~pWpwocw9&_UptqXUZ3qu`^>yWUdt7ByA*b-d#s2WRwZ0 zr;j~Zfm(EE8bd(-t!n?Jof#tjv=}C>)6@aGTM5OW7j$w3!sY;-1rB}LnXG)A@3%1_ z*?)O9FiatqkH;RYU*hr$WJ%-4{umAxvKC%cyfMzh4&Y9;QWM3qyO|ec<=1|F?aD!G z)Acx};C#riy$kJNY>cy9+ex)>`e~|Ahd@x}gvgDoPOHD7Z5Qi@%eelu#xABTAr z(`rscYitGvsg{c#IkXNcX(=+9Py&qUjVEu-{iB=Kr(A0vunD*z&pHnbk;y?k40)7u zimQ>&*O9Wa(hS%OEzgP-p)4_rQ{<?}dU2}N1K)PCOD)e3G%*HN3w$&+K9k)F9_ zht3O6@4&iFrn6(ROW!h|a$nw+xB2O!s`(z1Fu0H8_@BWxC!yt+Qf4jngzXS2cv|S4 z%?;_iVd)>2i4+KiMqDf3vh8y$v3D%7S-WnRl-YeBcc_IWW-0XG(};x(RB$O`vp(qa z%R0ggha9r#aSUi6eBhxu5g@XiG@q@ht8=CBMCTh|5GO#w#>)s9es?C;gJWsfYi!C- zQ#5UxbGKW5-H`oG5DMz`N?J@<1q1l1kE5WI;iK@_hX2|^lviPc^lOG#PdDoyzKcMJ^HZwKrLgxy{-ffNZ-Z}kzkqB&4H8Cl zX|waO71q;CoqINna`lFU(q-~!+!;6zE~pmKw0*peRb|s~zX@Cy68kKATu&b^<4-g& zBJ|vAx?qfyLp&v!&jOj^So@!rPDWKiuf$fFh=N}Q|4-lQ#e1kVI|{*bYM~3JWS>!w z0kW!7-_Gw<8d@Ju0O_`>)orJBHzOXV8}+}gn-ty0g@(-ZkBBD39fcRED=OB%dDQOf zM^)D+WDnaBC_`9;!H3xwQGIIu4=af|;`YZ(e<%DNW^06%HtUa(ebC$C-(ub+1hnUV zi6Al9h7dt?!;&Zt_ql98?;}j@>HV}o=^mu#T#8*|=J4>>l=%~FUXP3|WY!N+;~Q4A)yD@7ay z#C(ZdO!<^I6tHx6v6(8jJw(Ycx1)n)^~T50@xli(egD;dnC)fJn2dQ(5vXna{@_fV z3?Lfz2UgfD^B9tGt_`Csy)2!bK59&|B)$L@YMY>8T>tv==&>6~(uEWhbq4nPdBI?2 zyV3t7@`Juc1qXby_>o9A_aNu}s9femK`>e9yhf`i{})Vf73)6dr=T)u;xpyNP#(ROk7~e9gckPDBtHnd6WN(UKM&Kh&PvH@V7jJ;>9FZ9)F zI<}zGiMVswxj1*P9e$95J6^I<0SNm>I>hb;V$XY$hr?$SiS)sA^4V!i2;a}Z+mmao zYEZ2K8GtBRN9fmY7F`JQVUxID=7W`@-HiGXB%BI|C=L1Z63vfBo5&I5A@q_hAXwdts7MmIx4fiuVrL`NhIgGpPRcuqp zVbO=(5JfBX9iSfX$xpp`VNu6rkE@^2yjJAhG0Myt5`bg z)+i)*mvYjJdvVHN>-8cYascqcb16*C^Ed%4@+j~x1G6~I%g)z5aL4nAcK{J8$M?TU zTFC|)KwG`oLH*G|2IHESI4Q1a#UY%T-?0sg0L~IF%*)DFvww z+IwK>#bf<m+ahm#4;ymmO zK)|LLBd@S5+qqin|IvJ0^P3=Wmxqr2Le9d}TPEp)O)u=oF zk9&MT#EhO_FcmlRU5z{h&AQ9>ugMuuWn5AiBYwQ`3+ooY>A=lk=6|A!*LD?Lvh73# zxoD*qSl3-X3tj+sZk`i?YLtay*m=7nj`DHu=(T2DYR+}jo$>rK^Ol$M&!^aUQg(EM z!hXT0$k5nE#YcGBRGGu~LR0YwC=#6vzuz<0&jh&N6AO#x+-54EViCMkx!J^)emnTe z@Eav!lDoaK($0coiqAf!5T9p5Y9PpfJ={;RWOlQ|k2Dvq6m$=NuJHM?T?wI)3`ex; zW3RcuJ6t&lZZHIoo0kY>tdH-tpeu!A+qjL4Kg?6d*R4DhoY)~*eZ3iND}@eGL^3^T zu1hns(Db?{_+%3b0!5?lP|gxFSKUkr=F{{W^`bn>g!>PRaA0+ii54mz-|($L?nO zyg)u%Wz_F9tWM1N$vt$U;liKX-7F3++g>$oc|XR(vgZ7b7h7(KO>>=p+cjuhy|D$l zJZMeKL(Jq3!jecJjBl=XGgr0Jkr}D0fFRRLwc5D8FGV596{QxPWEbc;P^-ZxXa2Ob zd$0^An?u$Q;5aYW(#29k^e9%!S*w=SMSn+Wb~}*6Udw%SWM=5V=P z@g@2hJXQKs4%&ruDDlTp?6qT+AfFt$`c_JmMKfC&&x*6I(9s=_w|it6B77eR7QPUH zqT@!I4?b-CPdn1FJHSK$REndQ&^9E5jMt~e31kU2X5ug#w)U6Z%c$2CsaBeIUo**LY^W%H~0^TB!IAx5vJUhilLd9d%`xT_obNNJNYIbPM9mf0UPhO zAfy8zDj6%ZVc+*Ol&S5U2YSPpK|~ezNj_3Dr0o zuU#GSHuspYj*&-i_N?)dHA|EHpVgP zvGSZUwOAQiM-Yr%Qm(QtN^+p{5kP^CAp4_GlHE%9MQI6s1Okj3W?fWayKUNgdJByc^}H*reR!7T>>z z0~t%}<{Cy@N_H>&{(mYL+(6RZHah@vC#D>0Cq31;3?-uD{mbnkg%6~M71_XUhF>Hj z>>%~F4O$u@;W0~*x9g1Y?-#Ssv-42%Z0bP%->N}PzsY0@EotkCdo9t3#|r0sC#rIW zBEs}x)9ra#AP4(?wNBD41cD*Q&WrKGT#gCxWPQK7=4hoB6uGkomeekr40{CObcmWf zzzQQgD=U-qo7c5RaL^67Xy2!S>Vw^+%`rr*6F`MJ@mzhR-5t$@5!mH%LT>v*m2pP} z>FgZMblXvV|LuExR+g%9idp=;u@<D4_g=C2IL@l9XkYh)G zbgJ?iBh3d~+?Y!66n$AcycgaEEbL{Py;iGmoCYh;SzxEzNT<9)x zj)eZbFUc>X{MFfER&@;B`QKN+dLx|W?!E=p!zFtOm&>L(F?v^~yZ}TdZJ}shWA?Zn zr%bEacHq)lYzl`8sNe_JFSoP3MUGi%K+z(Q3i9(I@CL=>g}!&as{nXdU?EMY?^pQbV(+qkJgpPWpiP99636yr~G;8p`bmc=Hw@H5|y&Vn~ z)Q3o0GJn68l=@MMZcG}mT8#_PHidApb^Tc+`ohBCLd zt3F1QNv0QVEhkz0Bbd- zWs(a9EIWQiJ{zsG9+aDFM?i2+nRl~O`+wN@WAS8{0|5M|gR+KgLrQt$OOuNwRmZyf>%CFFIZ1 zH*^q^z>CPkcYRZLa5b#lU3foBT4}bSHE&+sh_MGOdz(8HV*MF zF8gEl3%Ni!=jxD6lD#s36nP-}FK?9}=G|LhNS0%4`FAp1RcWVB54GV6x0B-f8q-Oc2&KM-_3kASs|vP#;! zp&_GFFO^- z4ClW06d{s>YLlH{P^IctjV;Zv=eqYX{R@PbBS(e5?8`F-nU72H&I@J`9Chu=NsaPJ zx9?z`gdqcTdrj{`u}nONTEg{Y;nzhA?t>p!11 zT|7EA-ma(`Folj41Quwg-q#}Xa*zd12{nqB$0`){?x#s{@~3m}%tk+54A9NmAo-FO zqS=@~h;jEVMnoR-ci0AvL%h;_!e>2h*-KbAJ z^v}E#!=T>lW6H*$DkOb7BC%D;UWkE3okK2X?oZBwn{%1d^u`ZY=PG&}9{shqWZ&^U zF+ou|w7#s0sN*Y!t)If~_xS!wp8ES;svZlz^kgap&k91@w5k0ju5+=D#;hz7M_Avw ziJ*N)3-=af9;r^_;Z=t=o?)VH+krg{lN4G9InsYi_IYK19jYk5`*JwS9k*aBP5X*{dk*D_u04I+f+fJ~H{>nc zla@Rb;6OE$Wj|V#{ZjrC0U!dbX(@$7IPgi4V!-nH%waGI;n=Z*l03#sT`KqUu8M=_ z4Vr79dXKxCu?)Lv z`?1JAuO2!Up4Rl!*stHPs4$fl(blpCM!jn_vy>?{l~t&YeY)w)op(OvjD+t;k%E9! zm@K1)Wc>b*@G5iDz21fHP$iG8+c+1?ArtE->>&}~O?f!0mCWprw1ywzzidt) z8BZVS+`;2s55VG0-v&!Q_JAobP}lGV%UvQ3JJB^eKa8;`YaHG3cDXp`ubSIWR9b;b zIdaL?)0S(w3_ejefEdYrAtTujH8%&NVcM~fkopg*i!k<<+vbU(FkO{8k!(guoi1_B z#cj)QB6Xb_-FyBu--cC&9$3yK_whe*eAYU|?+ouMv(?nv8^#FZHO18b{#`n02EA@W zM~+;K>(L)PZA)kKQ{Tq|2!nJWq@_OdWg>Cr57AN&q0c$0jcey6$Z_)QBpF=#d#v1# zY{1GTyluJbW&(e4fvDYGo#7M$>?Vyh7vmBvtIs#Zl@Fxlh5ykz%wN$h|L9RPxlbnxk&Cv` zvi7^MQ7c=);&NTJJHY5(EjSERwN{t?fN!UftxG%2P5C54F8sDO10K*#yWr+LPJdC^ zv+;S$O7>;(%DX^PZFGMkH4(}GVjI($gxb-4`{35|fbo5OZ0uZAbhM|m{31(X7bksW zk~f`1Sz(32bAC|a)cB5%bWfsLi!a$}W|GYCwsj-n*fEGop{e0~UBm3717fy{=;c_U zv~au#5pO?i=9k+09qNoeTH9XwHW>Ear= zz1W5IVYInvMRjzipU;9zQxsW3hpNnSB1cd(zI$UR+LP zpbEQ!^)Cuf#R#v_J=+Oj=%FGzU-Vx$3lYJvHUl=l7Fya%>^q-3Q8QnRk%KM_YV?@0 z7_5QtocFyH346z)M%IBUyv8T=wRmI>T!~Fgf8=;J-~*{AZSg-9&}VH!47=%ROAq>D zfInhf>*F;(W0`zH*iYp-?}<6_`4=58NPAHz6EVTY)ofquy>0Krb*gnkXc&k*FE3!z zGmg^rRkkD*$DL$2esx+kFCMt0Azxk6uqbsOjIqCv*OLc%oaMOPjv<$v@PWHdpOY)FY?OH zkNV0ld9%O&4(x_DZ~V#&hC}?vP$kuEjD&6dVOZhWZFhQO0mVHO37mfXh083b;RpTz z$YOeCH4QAMM04Q=hRTr)RR`~+Gdzu$!;D!ci5;L@^9b( zu}2euhYlAD3tscsNvqE20kt_!TDPB1_v@(@_Wo_smK&$*6Mb7bFo~mb|5!%zf}(i!^x1E-S!HL{y8mYuLGRg7 z?-xu$<0Y2!9R(A~H(k8E&U8#b+*{d~bKha(!XsYEo74b9kK_9z#~10Nlh(VJ=%0iH zDRcXl;Ae7wXqtkXmfy_Rc<2+LZ<+{+vpBL zklcaUqK_%VTujnp%=u+K%gPSNNay6%XIejPSV>Lf+;3 z4A5NbCBYQ7eQ>$j$sTJ%k2CvvkkcH^U8Rd^q?zLP;C-|ju$Qy@GL_A7ooO6SjP;nT zh`h7mE=PoJ4ApD>f$%l9rQI0y?Uy`pqJlJnPql$B4*D5*5uZ<{jJaxb4;;vta1DHv zZKom(j?(;^A&*iUe!H*AopWi0rO35#@0YYDl_*GftW(3bWi4{D0-~=t7~58JsQ0`MV2Qyi(giZdb*n8qslZfl+p^I*A=CVA zFG`d)sDIIXMl%*T2qiyEKNcJ8U4g@Q{b|V|kuH(EHUE(-AyIE-(UmGw`&uH`uc=9b z>gqd!96CDY_WkZ`&c%}AdOKn!5AVTY2xK^!@WK2@H+5`}T0B(mQB&IWs1he8kUO!S z14kW!@^+>11|nQazwvYd^V)Rd(}~(Wxj!~`xtnsh?K8-P^}^uJUp86qzMscLiAN>C z&kvIGCPSd5jC&Hm!UETp0MKH=y79pJ0XTM+>Gp$F)k`s4=JUh=DJ913|GssFesr=y zzhi0_^OnAAK8>gGxgQ)HCUX6*;d8PTLN=g(rl^guIhYT>q2!8Tta%e(f|;j$;{x6y zP#eU#A+9YYkLu=4fL}_>)#gUMS^g)7H9BUpYAxabaCH&>c|x?`jbgvF|D(pY_l64z zI#nWxH09ogQ$^3b`l?`99+mQ)4A0MV6xMae1lh|~9#TCLfLN`V!hQ(UVGgqieOU%4 zrrMP3Us+kJsHj%pWn3`nrU1Ege^+viLm{Rz#}vxy2N3oXLdcMf+$>#lpt?om>ezK7 z!B2`c$Nh;a3`~0I_HlDU#~W_|>UTM^nDn|yx++?tJ%KcllOig`;k0IsLk=>XYKDV? z8KFr$;LnxPB2s$coIE}4Iz6@>q;_0Ey=1%v7RUik3EgV)&PX3^MN)+OVVjv8L@hhZ zJFwr_#BF;w6#MJ_x7(i|0)-Ir1R9ZRBVQ$tQ5Oqgh92pa&0l^is(j{*5H?s3;D(J? zM5=wh(d&KHj)@Lq{c@Sa%`kYCyEX-v`reNu)|h~5#1?g`tvAo_n{RI*T$s^ex#d3o zWgZQQXgnnc47a^Rq1iPo9KGrg!Qda7eqF(E`_?Dc0x)1R-p>&HhM0c1eE6%(nWg$8 zV_DV%Yyi0e>(Ml+YBD4{xC{PxPTWdP%dI)wCTX*-#_alNjRev$NX`2I?o_q2ZpLjhL$w>Jt9!s;Fe`R)XC)w*} z<(ri_U^?u=DGU07=!(BI2%4;%n2pvd&W8)0IF_Yw+Z}e}`n&?Zz|=nf(||g$&*O33 zA{wst*dxB6j3sKrc~87|te^Lkw!O3$c4(Uzm~SuC_`&N#aV4YX@ggzon-rNj=JB_^ zrEii#FM2Ok)+}eGdUqm)=VzUC>e+_y2* zEE*U-4(b)fq(w1*VuWB?_MXIf~*#Fs@-%`Q?pxdU#;ah{&oDnW~k0P246e80Q_sPiS@E+t|_?z zZR#{+bR!@se4+0NYeQNc({{a=bHwtJV@7hXW#tIBtpL9GCEQP zpKEzm19EH8OdcC0XfTg6mMh^m-9uu}z-v$26v7{DKn77xHqS=w>bnz(3u91o@v)QA zd*jtVY5p5|@~W!>alRs)q6NB_Nck%TVlc*6KjfoUlW}(*Oo2dtZS!lMuV#~~#k~pS zRg-BMu0PJv{MHwaec?peFF^znE2-(@!*sctP*g-*W^Q^m$S3ML=F!mPu@0qwFx9wZ z49c1=#<w(!daqU z^1aSefga zC;2-U<x-z|K${pDru<{pz@jQBIc02|;+jsHX})Cy(rkHDQhpT~q@wd3$L&9~ z_b4Xy2~F1fd55^3eJH=yxmq~KSq-AZ^!9I{gKNwZvP;4nc_02X?V-GJyL z^jRb(w&}~?$s#$Anddo!FoBW_<3}aQcyc>)T0({YhpTt~%JhB1w)4cvc6XC)O}5=+ z+nPApw(X{xT$AmZY}>Y<>+`PXS?jyrf1sbbuk$>QW8b%}C4KBS?Oa!LREQS)IuIjS zI)0PEj)&o2;H+i`r)sH$td&5oig>HA4CwZ%(SP}RwfLvo_ z(_OoEP*%n3gn$I0YuCfdj`zANrl#2Q)`pk0b$ay#dMu#cTQv6Yw&94u35CX@0`Klc z(C8Ti`$4*p;kCb4yIGl`Hc;_tG9H2B0%+;zJyq z1Ck6!EVDi}C2aM_CG05_M*q7k^|uFSI!cg|P{#-8b{!fp46#LdN=Kg?bp3S%B=YD zU}VD-ziM9{cKCh0OD2yEy*BlwM~mFw$TvM4p>=fk3x$y^TM{caGP zh3CDC1)*hTh@o~y1B}Y^9$ByfFVj>R7d=}nLas|lYW=wMQ@F zlW%W{l-Q2^P*?G>7|yuah?^**H^fA@&bbu|cVd<;Raf)X3uA|Xkgw$^@hi6O+-$g% z(6Sf2RYAo4LIrO4m!#cyO&f?YNqpQ=5ucSvPJlr>Lu6kEFwCX#mnmB;?XYGnD^fgl z2~f>vBeZ3`pZ94YMFY9v=KByOv^cyoZAT%RNBO-CnwE)_xebLs@C=0;Wc#O2xSDO4gX{^CU!?16e=UX&MD&xvIlnJhUpC6t{)yOyKqzSt*|n z(OGDS2q)CM<*zYqPg+Uf{c)nwsD@~$;By_x9&|r5wgRO0rA(tIAJ!}iqn|WigWi5D0~I1zlh(ZnJ2#R zD<%*B4RWVb`s&*!M6nwUX^@Bfy#YS1S<=lEE)Al(Fhpfi#5D$u?;&J`{k5ASi8_>y`kd15e2!JJ!SN1Cm?th%4Tt{S_H&=IJY5hRAJ*$;KMfd^u<~h<( z_3w^+!F=kr0R9-K@7uK+g@|5A1J-{Zx!IEXF^2nJHmtv7QNHUtNv(6$Wcx7%$jden zTP%rQEjA3|`JTHlobm4|7=5-~)Ly_sIlJbawSlI*KqQhHTF1Fd@`W2dF5yUXZ--0C zho6WKr~PF7dfT?I7*5Xu3>gaSx%5B|%Z1x=G=4Pq{A2%RkVwye?S$ywM*Q zmv|ZkkJ3aTdyXRx44 z2BFfj#jJ0qU9haQQXwLBv}l*9d|s8Tl;myUhYXVrcIMX&uh`*W1A+;4u1uje+Xal@tm!c{+huz`!kca#89Df{o1Fc z-ILiX(UZ)>9-z@?9}-p3gzihvMiBiT+*UGG<_M2^w+l4J3`#$69XHGYI#(oJ-LN*W zIR@b5zueu^x3?<}vLA_|+#l+Xy<dIr;Q>zyxiS^G~FRxJzo_4 zn%CuvKh4N%&&$j_O+^wPkTEd&|NSx@R9PNCv2@KCY1V&UT2=s*oqDG2_bor3i!R?5 zD4(#ZSV(Q>i3s{Rht()LO8*>%ohp9@D(=j;BN=_1t}*koPOoP$7@mJ%=o0tW=& z#oc_r@azjX0mDp3_;v^RElm<4+c>rgcD`}~8-A;M! z!Akh=w3fS<&8zRIKbZCHPE&ov)GPIcjpcH(tUHGc;+7|gY2tXsZAOs)o^D2}FlTZoPe!zO1Rl!w)aUNK!WQ2tSpw;imKzw8! zhYaj}YirnlMxpa8j?gY()n1?A>-UBj+CM+!099wQldG3hQBo>DP&DD%6L3s;zN`_6 zwmVIjog$-J?(|pJuHtZb)$g11?SyJFKT~LnEIZ8A=Nt_VPJto*E!cisGVs~+<@7cb z_*%;)YVkkyMEvMynof?k-GQGTIja|#JMQiILd@rJvzKtT3DKVG$^$G^?%u1K$etnB zAIxRbu1Er+IcN-l#2(NKe?&swH0MI++lxyG!g1Rqgz3md1Iv{5pD8o?pK%YOH-g~D zClD<7wX-A#U_0(-@{at6c7&f`^b|`7OAFf1>h7Px%rvmgzBfms-b&efs>Ful4Lbw7 z&&eZRCxc!>2BA4L&bT!=g>^^g2zr(t=~f5%H@CGKl|M17krHrr^>WoC@n3@byYoFZ zLp;95;n3dIU@GVATzZv427}v>QU?I-BK&8lUB_$AR;LWS^m6tWjDRC;QzCuA`n(^l zWKBf?86RJkz8SxaHc3&xw0ygTd!;Dv1kK)-|b*>ANnnn)9+;4JPtvWjjN%-nx0d{F^>aF!GHDqbN!T2mm(01==*yWiE z_8@aZF3q0JL{UIoDrUx3lb&rk#AGibJNCnP*YE8eF&Q^Yec9KhjlnuwrLy7RM21#Y zQ|0E{0v%BiF-SzfmwkI}l7{{NbKb{=YFRJAjkf`1gxc1kaCvIh!gbT?$)?9#O>@g+4EG`;01~_K zsnY_EO{DDC8ZiI2IJ3_CD!qwB=pkZ#A{vHCsuq7Eiy@$)YGTYZ4Ty8+YsUAm zC8Wm|&$i4mlNFReDGm{6ecE=%rY;jgyCcV3PDe?BmCJe(dJ5>WIE5kBnH{gYqRH{B zvQy^9h#x*DMp1bK=H4HNxk8z5QcS)zblLIRv_6=ioO^3Uk$vcXdB{2LPaqX8X(h{mTf;IwPHt(GdVHY9?}5?lXkVRNtP>{TJ_=^L{4r z3qdf7c~M6nm{aMPXSX%4H(j9eoob%ax7kqhxe@!^fn+}xj@LdLO68hL4sM#7le5nM zq;Rc=8H8U{2u9M~3`4X3j}8T<6WU?J!xjIjBy&{ubDvQSbhbq#&sQtUQQDj9XdFdH z>?h9sN!Tq?^J?{kUy?$+uYbGA0Hg!iGp5e!WF~h&2Ng|A1v*OJlmUOCeqmm5VtG{& z97=#~WH;{~#Fy(^SKZj2(}PK{anbg-9j14O;Hz5;IORgJ*D#Mvhrx$%oT5ZUb`T%>|=A@4htnfKNmZPna_|B0sn2u8E8;}tQ=pc$z_FS@e5*U za@*0d{wN02#s?n%ajVH@Qz?#>qvLI4<2)c|?=8DbBuC=sGp8V5LP&fl80-Ju&ycA8 zwa$_>>{+_ym=!u1-qPvpv%^tV{YuI*}szyjkhd z>s6--G1n95j6ULn(?9?%&f=h{*v^lY!3Er*cEz*Ly!oK-tL- z-!sK!Ccvi3&BnG`q2Hkz+lp}MT?%_bCJiiBeRnukZR#h!Kf*mDBY;P(dmW?)b;USl zayhc-+lS(7tU2A!uYY|0$rVn69-aX(-j^=GS&8?5V|>6_NwNt6)h^t5<#tl;ddblo zp{c;!?=+@HD=}cj3th>2J6du}uqFsW%{&A=QDuzk81HD>)H^e70tbQT_S>wbB2y9C zH_n43oG_KXcL$o27Gid9Ziwjwx|rQbOFowqLJ;KFR&?d+h6fPi(wpKb(cag4x&7fz zZz~E2?V&lY!R$ni!cunT^ldWw^LVBL3O>23#iKysRxAV~$pipP=XE9Dhhh~Sq|*uV zK%DLm1O~Q$vQ=rKY2AT_;Y}D+UI#2S5tmX`ioBpr_Ph5{KKt^8FTx`Sy=D0$ zv(SbQz~|~ZI4bnA8gT>1!=a5wYXAILnE{}9_O)fu9b1g}gYhTAaPwT^wUBAjnM|c= zdj;-UT=SdIDAd8jal3O&ueWf!OXJ$7OD2U@)RL2mj|5+|wwJPo#53I96u6*_(Q|Zw z{HR1HGc!FGo69G9Cjyu*KP0>HR)d8Nxm<-*zDH4D{nGgerUPPkrskKomSoA z=3LFaky%UNTmz`9enBfR+=zBHv88-5OA=9c6bW_jCx_i>)nZ#;CT~@SY;;SE3Q0|d zd-0W{2~?V=CKg^o)~}x(CP`f+rb8&aWZgQ?Kt53>)7EX`BvSjr>ExqzQOyW9`J>p& z**E-K#KsRG9ABzHHjD@-0_N=U_B14uuq23EzR#qB9?M8F2wa~s=Y$jJTGhktSopyHixCurARw!Tz=>Hw#q(oHsn z;ADH(-_uLqYG^=9`ulDDQaZ6nI3+tOR%tl5%bY9?k7$bD(aJ4;Gs-3WBiL}#UHn~7 zuwxpSa6lm(y#_PRVd%ZgI6cBjLQf+fY3`4+5|fN{J#Kh;Wq<0{`|Q(hE*`&G|Kp}a zAX)%gj#7#IpVzShd6pCGr`1Sbd0;22S*@KXzb~J~2z1)f$L}S`^yc}%f}X%Ra!AjZ z9sm9B3gii^8=xHzK?oPTWdNeF-)z9YWfzo=G>T^iT#F)VNrRLjrDgWh z-)I~o;B$d3kjfA!%&I% zZP2;L>#EnR!Yo;&>c-ex=doP!f?b`|`lhPy{rtBk209vhS|v89)aFeeb|_pfE~49y z*D(Nyw)TZMB38=3ap9ymM&acX0(gGl`l5+PAuv{k|A5}d?ySi1*91F%I;chKxdLN86rec1ZS$(Gi(o^cZ0vV zM9YczCF88x2H^U<+jc195dB%Tsvo~O)ilp`1v>Y~M?hS*K7+5a>8IKIkbpY89F4`S z+2e^k(+=qtTk4MjAHuvGFphRf#2?l|0pT+FN?H~jL249a;2%?=(n{_JRVap-OuU+{ z`|7bvL`pBoj2j3Ubh@Rz!xRZ`0jyXso?+dd!^e!EsSAJ*dHCF z6<$PDFhl1MMi&Foq0UAoxl7StodGx_GxG0=xf4p13CjXQvUs}Iv*Y^GGs&Am< zLK)bm+N>O}S>p%ZP6~7ZqveB4;%I}$`H%O;YRw&d-fXvHYn7@_&vo3|YAX8bl7KPB z>hEAqUKStEr#ytAj%hz}x}cf91~NfzLV&GJo;Rl=FFEw_BoEZ)1YlC5;KSdd^Z(q8 zpV)U#bG?^uff83APYUgRPLtzTzf6K09*X#TIA_yl%UI!tSC>LD@P*a^CvJ1a<4_tX z!Jgp%mg<>$Q}Ij>V1S1c63)YPDt0d^nSadf<)G@>+0eq?f2#4J80EHggpADzz))3@ z@xm*{lNFxCecX)lYsV;8gf}Xq(#x$7I zJut@!_ToS8n;r+{6Ibh(>IaMk-xBydc)hW&OhtMq|pps(@{~7_lM$)`;;Wq zpdMZ~ABjM)Ix8Z{V75z>N)RZWKz|BTn|Fd9OnVqrlT26A@8f9HGKRX_0p##$nHCkD zNFmom1yP;#6)8MUw5&ry?OYNrTAO2LiHlxD0mM&T36r*W2j{%tc-A>vP@r@T7kRf= zfWXA@0JnRWCaL1}S=)tD&z(SVL1FqcWdAZ(x5BNQqi+@dJ&n;WNX=8IQrRqTPw9zj z%sCAM`eA~3v9Wi!kd~GLwc|`HdLpr8ip|I}^OP_egdG=|oo*VmKN(dYW4oL0sFVr) z0n96w$&wQ(Qwyg#?-G2)arS|NfZIIkS%V6-Vf4l4YmTe>#Nx5C%siFB>-kv77+mgM z(b0tc9}iUi(X$VOHVR1&w3}TMuOVJ|{rlf!kaJ>uN)mT@po$9i@Pb0vAX2s6rK~zn zXrj2!h(Aty`^!Ho{|R(iVQ?7*H^5M<(9kN`Cu`yf^UO%md^x!t^x_SUM~U#RE40C9 z3o7yzxfOi|4Zbl}Z@V~3i4&Q!@eO+%s?A}1$}|DBE*~xfGV**jYP*0SAfm-WL@Ze! zo*xy63QU83@BKX&^qzBAZk3fPJI(gJPN=#mW}HW9J5#QPJZsdLR&-x$U};#U8WK%n z*7tqCDT4RV2VJF4sxHt=!u9~@JEt>ojZjY(lqWw(E7Hn;XfjD<(_k+;av@`3-29gw ziJZV~6!;wulSQ62%*xw)&Svst)8@XP*#eR{X*$o_31qp9yK0ni?!)R7ottj?!^OV7 zwxhNoBFv?$_Mc%M*`8J!{TJ2902~e;iZvqJzWIOWuC?~yu)lmhZtF77>&@4=6M-d$ zY1=ch;g`^Sx_ILk+=VP*2J_u$FMXneRj^NN^hqIj{iRL!HK;GZGG9o|+YoK8!3rMU zlnX66%~{gZ(iSTGHY*__Q?!Jo3Qj1AJ7+KvUr~}f7^uJKFUbckoj~j|zGfQyMKZuI zAdI%Q8qMH(LP-n8lSJFlMVg!Aftl6#{^Bh~1tqlqaJLa3^e(KtNESJVcmG%iUy|Of z#8@#hWR3Zqizhk$W^I8gehAQ|!DYL9x*uh&Zx{Rf092LFYKXhRj}x|CxGj`ALG@ zv>aZf_|G$g5E-)k8&%8{v^=(O4yr1rDAGpfctgTZEs9_it-zWG^!1Is(h-^#e-vc{T){ciL=+QPjx0XDY^TZz zc-lEgLrWZNKLO;iH0x1L3$7yo&Xpn0l^>>QkTAR>dk)-M5#P!RY2?^n5)s>d=*7l6Yu@H(XAWAX)-B^2ap4NTH^Oc^a78V#7uV!Xf+-jQ z>bq|G6cGgxtpCbTq3Pv|tCbbC;KW%ac-_@CmjiOuz*+cK2HR20PuD_PA|>JPt*LZL%_r1nJ8vvk;T~2aFBq% z)-CJk++PE3v`#%*GI0S-wgAXf(zYlbNQjg?2-Y!eFxef~0@(C!fc4osM_d+=Lls^T zXm6SYY)l~)mCDGgN(CP0)~Eke?NGL^{E?F$IeBp7Gcu*$}EReJ)D4Q-}g=0DmHGYzP?S55gFi*11Q`vrGNGa zr0C*i#$Wn@J(ONBqV3M?F@oqWQ{n$(BfMhy?d4J)WQmgd2V?&sSFG%YWWJ8FjCv{+ z(2enbmwVeD9=mAX?84S+-A~EzE400i1tn$`Vmc4~O6!J*mm|Df4^gi-ZZVm{!a^_R@O(rPuW%u2e zfeaS41_~|ZDU+CT8=S}VIz$c;hpciqr_U2~PzVW4fQO&oIi7XWsam2G^_0TQ*to98 zyc+GDl+Jz5qpE0F6i6W~aS|a>sMU_tp{Ydvmh6uyw3DuBSk4~xa0)a}c+TbDLcNjQ z1ZUd*B>&p4M<2Ga)3-Z2cVM>>rJO<2kfLaz9r>^GeE?W7RpvHvtah9D^GHmiC0%TF z^Hr}oAHjpZHzOnd9I5jQ*hg5VH**@5lsb=gnODzQNO0gw4gcn94P-X zeXPHQ7ur|ksS~3rR-g%tM$D+I{bAFRTS&+0);D5+Ar+YqRFK+baLmMEI!=Cja(+^-t8m z*WE_f+D049RVg_;sHts0loNgYd|2)EO;kG0Z*Z!zgU~{h{nFc<5E$v?G~62To++N1 zruy6@HnO%%^ObJfx{_Ocpb3-LtXR3)0*}3pRpMzTX=B42ynP$Xtn(3=XDEu~o##Gc z^$F%7RUJGOksJ@R^(vGi($^J0^LXi{Z@CLt;x+Igh(8?G8@jjvj)|Qq;O3y^o%P)jt}K9pIAHGF_KUfOrNNrq6hHf zf1}>9PPQRN?jgvmC=- z<5$$I_Aj-+E&5Ce?Yqrd(N&86$x!4eK`4JZyV{$E&M?_M2v4P&`g=#5S`GC4-F$Y? z=h-gX_lGmF7ZI`?gkv-DpdBf7jKVhxAv^q7_~AkTq=OYuaOQt80BK6I$Wo%G^nkXHATmLae+D9EG%Z_ABus75*>* zRqWIa74E^9qj4W68m<|rAj7!u-QnJCXvQ+m(&53cMJ3Uztye14Lqa4+hb1A@9BV{g zs<^b_o!cRQ6eQY7Xm!9`k9&&H%OfF^-RSHXekE6OAzbcm%x+}_Qd+AvNa`EDn}#E z>d?8EVaP-x`a-iSVvtf#oIaN4|4C9J`uRg)(#k+onFNwWjsa@inY)3|v{u=IPX#tn zz1*wS1h!%jQe2hSD%HtuMvrP|ALTe1GI?=W;iqoh3eWtTyrZjw~WCyEt@lFUneD% z@TfU1i7h7t?-+G6fm#8>xvnaW5|oF$^yggS!-W4JEn=-qWApS+g#-eS_QB_U0UsjL zzElsBloLe{X))#aU(stPba&K6vwpfN)@_RRZ}GjJMh7tF!rEOH@h0Adtn&kMcfy5F zfNoA<61N)Xeu~*P`9Zcz|5wD0QBU#v=#w9pD|<{;9LR_n7xypmg|uAG4AgW#dY;n3 zHXZ;KkbU{B5Rpky3J~%}*aW{S42i z?R|DJF-=%nhCpbVW6h4?!6S@sT*LH!eAj+T*MDHX8+-Gv^>_GZOW)4-f>W zSz56n;X69)$0MnxgDG$D zbcRQLJ*cg%>6>$R_-`m&b(Ay0h#nhHbW)6M>jH8~N*X>^ACtZdVG=}|?AI7qgzH_w z0^32q@n+aG8KohtZ$!y-f_?f+7dn^PCw+5_@oO0Iu&h$~wDa}BPPRc8$b-3zY6evr z7W$*|x1sjU6`>uN31R7ywsEe`VC^Gd6wS7Lt4apbG4%3B?fkf(zk9wQ=Glpzul7-E z3((epM6IloR$4)%XuF#!?&kaSTQ+OTMG51dUt$8UM87R#=5}D@@;SY#uzH_oK9kr`|;2I8ru)R<;H4ev}uB+3mC;9DiE@7 zryxi~TPiF4L{4_zPxY-yL{`E6wEb_{_<I^*+)r(F!%5L{{{`rsUYN8(TEk4Ox2| zj<5tGP0 zXHqRX}%=T%e6w z|FqaOnh89Kq;f9KC2k0~?WNCm5bL%LTF?z0{)D;q=wL&cIFJX9x-Pyymh!6^+qRfC zp0ut1oF600@v@U!yK_vFC-J0!LwQ)n2XGCj51UzCFRu=X-XZ9AJ$ zkrx1BwbjZ7sEuHj05*P+z*e#h6A8(r1?j{>#=MG}9*Uczp(JKm;Fu*kt&vFcB8Q)i z?d~z@xN9C6@jE*Kim~7G?tmr19o%k1RvgWn(OU0e16*klH-y$Eel)@g-r*oTvRK0^Ly@oy4)*De41 zTTAi#zq_7YW}%Me@G*!8yHa3~jtW6amrnBX1%BP%`VN?2hjGL;enHtKP>~o{x|r*# z;1)65VW8pDTKA$`ktHuMIqt15X^&*e;y8Tow-%{6he;lbS8+@4ngzJqoD=nsZ;8X- zHJK*)iq-n|WB9^mqW%Ed7q8`41)rHQr{b5J27qYnNz-vuKo-;3K#Q_x7iMWDULHlk zY%)0!FPt>b>9TS}{VbzT^L312)mklwVS~7#-bk$e)&AU-*ev=7hn*;-t8UWu$ z=ju++X+{2fn0^f`x2;4@2v!LEMLd6?$OscbG!D!>&ygA)RvIa9>mihvx5a^B=t{+K zWfGqMCcufz3M4uGW>BM)o#XAKo6mtm8VpXws+r}=#t1E)rEzTUw=$%iy-(`)T zR(_mD^7pu;RS<7U%(_wu`OSHK{g>M>1c%&T5l?To#3Q$Et5xK{BX7l0YxpAYeddA-#H~yaZT;g9W)73@pJ(L?R{0PXS9vr?D-eqrNdOz zZAo7v*hnL?5r2OuKNBQ1WeGoV?zl>WDiVyCgjYu`Xa|{2Vd@VtSp;J473xrjE>9X= z`1aiNvNk6OlD1BSF99LnJv2X#!a-Hv?oV34C3Vm!+&Q|LXe-9> zHx$RkFd?YB+dwgp3(TCa$*!djKo^qVc0wUCPF9~Jq55X3UD2jE*$NU?zXZLq#Vj1^ zD{rL+*ulp_^Fp3FQ!XjVc!SQ+A6Rr$6Z4<%S3ncu+jrn2DyHNQ5CR_QsYypi@Rrf6 zFmB$4?&^K-CLVBF7N(4Zs*aqAt?(QzjsR!Ci~LOC^;jZ>Zm_nziUR?a=s!!LgvZ>H zSFW!ljeGDf)dt$YVKQ_;@S~p+!5C?)`>(MLn%u~st?NE)%Gj5$OzpcdIlfY+B5j<> z4Bis^Ssa<0v6h5ooD9grjV(t}|9-Ly3|#JkQ@9wm?k(FwGKc6Od)`YBuY>#ylQrt% z0X*$}DplInvIPnF5 zW4?0d!wSz$FAzqQ1-ootu~Kud^V4#w2SEfLB#&no++6TTDbkdg7yv+rqj3615h-_J z3LAsk@X>q|9xb_0JGF$h9|zWd8+z3xvkaacmOKtm5-xkqtc8AUUdL>pyCzj1`9P3J ze}$(}p2~PxXr9lVdS?}IwoJaA)EA*8p@=#@wU$_>hf=rCNDnTYxcaRz|3XFr7Xs@t z%{5FWrXZP~Y?T-q4?h8gPGj~d(lDjsU)vKRm9bCkbg5F&n+(wx+t@L8Nfvl%gN z$H{|C)mme(i(Q(lcLVC1)nUT6&L>a166raj$k9BcjPRe8uh4j)3T@cxML2~Kf?P}z z`<#yTT%-{Ah>xAiCK*@K8Ulk8xG(oC4E2nbEW&Kd{r2&>)Q0}F{`=T>>+pGFHRvr$ zU^li4O{y%3Z7K|=m`%!=O))+q!i=p9Lpns7r35yflqJXl2!&v0j4)t-6pv7pUw8*SMdbNz22;O zK#FG}<(dDy;YP4_E~-32#l4h;XUOz5Hy|`s?`DV(>aai3dM7=L;$j+s#GuW%v#*}n z{-cfbS_yTNe5YrKxf}ml@0vjeFN90tH*nO^x=P3aVITn-l|vTo3fQyNO`i`A}svs9ccaT1`USZTsr z$%=&3X7B_dN7&6Q*?v9L2O=M?d7cWUMJ0qnjxzdc(yX{H3Ojv1Gr!g6>b?N-Ebxv2 zWoC7+SPgRjvz0xfmQl!f($XSQyI? zSe`%;*9mwt7TuX>{!k=u--|7fl=jJ0eNC`H+D+%>^Jw_N`t-B!PfO{Np~Mbz)fFAl z*d#}YV8Pg$V@yjo^PXGN>YotMp;2VAN6;a)%g}GQ*yN-%R$F6eCJC(3@oZh_D$utY z;h!v<9Sd6QJhiMZz&&qJUtg{jC0VFMxx7#|D$olj5*J)~AG~d*K|(iUZ@lE^n&Z6~ zk8ncV61I+FQ;hqK6g9IamUe0-9lMj@-yW{{NEogSyGwO!l?Cq4o^gh@KKIPG}IG!{!p2-(-`2eh;zV` z`GuiY6xF%zKPZjXEgmfY^>N67wJNZ1@4^0g?MS~wZ|3;%?E2!5jGc>?yawlmG?G21>Z9IHmGOG?mu6aqLQKD1kC#r|ApFB(SnhrNInmpsPUW ziD>(I0}^s2(&sYF<((gh2SqN<5^`d$O{K+iU(_p35>xAeav-m5s_Fw~N^8vlBlpp9XY@A;?f`Nm>e*xKJBa!pK zIn2alaD~Tl8}&|sKw!k^0YK+iny__9#>_Ai|QE!_-J?LbM=+8QM?(s9yc3FisB zow}T#e7a`gxanc`mr?+4NjQKTz6Xd@Au_z1UUrGAU!h%Yjunt$JeML3;^q5^Ip~)! zS}Wqvoc!;xyMFkC%7Lt6MVD}zWbKzao`S4xvNI-4tNh#NSK>zHpe8bIFN)1h3NS*z z;t@#LHY*QFo(*WV)kq8pAWf`YQFg8cG``+>xfC{kE}@yYeBl?<|qA?eNN=}W%0KI&dWB(KE~mnODU)xI{dX2 z87Rp565JRN`&c^nZmUTBUkVvO|`tG2An~azEnn9i= zmriqiK*N_U-L9qu>9UkU6dJ#9)$mQyw7*HgFQT7IdT@;(&|a2~R>RJJ?ps-w)0#h~ z#-ZUkifoErYYd&qjmL5w=%4a(VeFsPyT7P2@+u51CJr>5>UC{EXq#y7$0Gnwj_Z0+ zn+D_8Efa^yiY{IvO^Xa;K^Q*6>fhr&F1pFD_Lv|Em8jgywW}h`0Mb>|KNwfyBAf%1 z7-ey^H2W+Ede~+cqnxNMT}RsYz6EaP0&xRqOr8T`aHL;1BWhBl_0;;V^M1FcscIFv zK*7dUBY^4IL_w$BqCcb=zU20*^NL0DV={F_8!XYZ;VridIMryL{ zGnYs%o5y{^eKcwH#bcO#jLx|+i&8#b_apZ6Z}Z~VM8L^#XC!NbQ-nM>rCFdQ;{PoU$9mXIhk!4GTc;_RF6(gbRWa;9lftOpk8!3{C~F7W{+0kJ}}-$&yY zLT2cWW}%!DiNNa~eu#Vp_Hs!D0Q%Es%e-HXqa2$6ci z0fqZ$i#u8Mza^=#AhtR?!ueY_xl13nb$zA?h9Wez%D+bMwDZ3!7Q)&t_0XSJ7GWU2 zpNSDz>Rk5#MN}Ig12J6H^t%xSMpG_PZ9)IDlM!*U{V)7@z&NPZ>0=H)heK3=nheLP z;TpIGy9D@!K?AgasIvoAID#f4#^^fC7%!_RyhI@7)%G*2`9 zslf})9ZW3FA^8_s+*6Lg$@hE{j5Rgx#@quQ8Ma}ua@ie+$n#<3O5n?QJOYl8Jhp|| zQfojH@~t>CZ8Sxis&JHVmL$orA%9<5JMJ7$U34Y!V`$*H9GLdpU)cuF)69_+SsA;by+2=rTh5z0uRXaUws)47nOz6gKx%rhpFm4p z?R_UQGNI8VtLlI>G^v^tvowYAMwv_6Z*U)UZQPe_)w`zS5`V}WjR|d8oH*>zkE-^$ z&zrzzR=?cfxVej7Lu@{6YaH`;7`({=jMx?%4Fm^$X$r4O5)gbwF0mAqu9tz1 zVD$CqkaxP97Q3p?#U$#{^O_H9UEOQ45au_iH`M@bIP__m-j(DIKw!Bvub)Iinoh7= zTYxBTIa7hSigbh+YTWR-lnf;RInG&^y*=m(-&0vo-%IVP#O4dGE|E%9_pXyo3ICs; zV|M~e#yHRHc!$(R0#d+JjVb{uT}}7*jtxTR$#;#CcGSD=jgP~j%Mg>27G+Ha&yXdh zo7v1Zv7$%Ef3FZjGU&pcsR0DM}>%+Q36tIapQ1IeGASGO%Gmc{t)71E<~g zYx0NfP;3}lsBKodqH^wi5*2{9m4U(dnsu0jKNwAe;kj@Pg!eqv`^}!FLVw=`d>j_i zrN6x0BKzRmdvO(vAC{;=A;knl0a0QS$Q<$Q8iAMTo~n0b?>tYrE4Vj0poB=Wh3t#- zhQj>m*|F&p%=dZ*-&ii=vAQa4iB6sS;ZnZRnzrKby!FMJtosgI+s3bbJ0ycWnaF+1 zU^YQ0ynxMgOvns9!Y-6E-*p5b4v7`f!^547sW(5{3_9B^voV_kk!%cAHjf$C@WM#e zv~|twOB5m-sE3G7R_8+#-{PR7;Vb&zJgr|p`$Xne=>lnc<5xi4H6sxmX?WAVBL4_h z=w_O$N?O-9v_eUT>6w3OvluZAks0E4z}jlSF^sx`fV`dNc8gB;ue;33!4$% z4+t$lQ8P-Txvn|7dahWSN-6eonf5hrwAw7 z#qFl!PzJ1X1XxYzT?sZQP?eD5`F@^Z7T}*+32n*WokMx3*-~5*q%jTu2IIC5NMtsC6!mQz&6f?c8^N;O zyyd=EUgX#}>#l!cJ`%&m#QgxIJe;ToqFhw^kF7qRBP^N}>J;|ivMJLyz8_fKfE?BS zC>);)tkZwpyiId5?FP)ghl-K_+|u>tjn-F>rMaTM$j(~nyHAYk3CAAO~;_(OKf1_ zQh}jgs~?5(w1}Aye$39m+T!qe?6zLTAD$oj`z4vbN9g|A_G#+-hY5oLQ6R*R!r>W& ze=+>6F1!i+BU1rnq{itfx@K=23)0UV|aeI_UDv=$pyKL zTWV#8nGW{X!akilqHR637^C2G<7fVY zCxc#N#g<-rXLGZ<@sn7Nmjh?Pqhg6wQ^irty<{Gqq0`+Fg^1~pljf4F)JuDH5r+ZHJtf&~k%30_!m z3+_QfaF^f~+$}i4A!u-ScXzkou7$hT-QRnswR_tA4Nz;ZHRl+;?-t ziuQ(r_@bliz&AiMk=y`4!Pl>)!tmNqY-@%MMyC_=mFp_1C3O)vmF$*2qh=02%Aiqe zU`IvforQRwdyaZjcl}q5)pO|v3YxdAIr&K+Uef%!xK}SKfdZnf(?6VF3g-Xs*RG)^ z54d49B=YV@5n9|fMLAGxv962+lQ>GhhEEo=w6L~a^f--GSF391adv^O?;oqlXUBr= z@eE5nqsLc@oyNjiD0a$COE7vfd>?uP&w{MwMSiJrhpUn)K7CMXczfFOfB5scZrCWr zAiyA<+$+6KdIHV~Z(#2q(|;N%s@O%-mSOV&6iU?;;dTMr)r0_+yUMzilbdPA*Is zl{fEi;*SBFJOFKj^6PRK0w2~WeG3fZjPpOKqMO`e)J;p`bzeLYeo%8}|1$!Mqy}>d z$UY85Xbhtq_fzx#cE02Xd>mW)Yk{nbf=YfW%U|{_6up)raXt&=N2qB<$jD_ zfSyHdf6?UA68Tl`TuDG+I17XOFJ`A_fRhmk)^Jw@{Ir2gX(%HROUDm96UYPFF&VC8 zJgbqTh*yCOW9%IDy3kxJ%yu28aRaW)(Cpbxbyt>A{X^^hcDjqZ=p;w8t`wwuELOJ557t_>*tC(*(Ek+KaJq%<-)r z&makT%{OKYx(DhrsI9|ubv41yH34Je$@7*Ki`&_(iZd-{QO~idk1Q62B8)OBO0!`9 zaV(B^7F{>o8*Ofg@wB5Nb)tD~uh{iN#ëz@RY?;R7>5mhIm%nX#seB9dkep5~v zT+LU$Bm2Ynw4Zz(?)~?CFL_Zhww>|$^jnsirpvrX?-y4itL2|7Pnv%I*5Eze^AB#Y z-lPf(Z^93oAEYZIQzkJwPE70bfyntqQXg)X=CS&JeAC#CR*87TndzC`RN)Z??()K$ zW6u+1S^MGaJ|bjd=}bHBi%5$EU03F3b5hlU z05?$dx>@hIrKhpce?QBF|NADSP{PIk#6)*qf46-9*oHX9vcssd`_+94c)y-7C3kVx z?nm;R3*E00+eD9Mv}`uRG~r!s*i~oKN)1yu09B}Us>P~ z_cwoO$X#WXpSxrO`3~!DW#>{uL0Un5lqicDI@LqzfBj?hl~H0z2!BVoq)p>eD-z6b z*NTu#M7d|9Y<^+~|K&5BiorUl!$y++`zvX#mhZ}D(EE9E2%U|Ntp_nwGHZe8ty#%ReD1GnNBAi-)y6Ho5r zAmZwVJ@z+Z{XT_iLr2p%YB`in4*s*!`}%o}z<#&}tTv65z9thzTF$U*tVj}bxG005 z8A}kMzxY2`&loL9z6J#zbQI0dZgEL4M*vcKPv2Hfl?P$JTUBfhDU{gs!7lW(>!P%x zO@B&XsuPbg4FZ+F+w`<{u@-wYzrW)z_RAiaxGoplY zvw;09U$q8A>bO#AIHwQPxEcU9Wb&_SMeA9MYdb{uKbq%$rsvt?K^8R1&TEIZrZneD zA9}05)>I?q)3pYr%HZl>jg$|KMSa9TrS|-mW7FZ+B98V*ok^QqhV>%R~A!%PPfnJiYOmHoZ4lO{u z-=%6WoE|{`{9N01ns|Jxc=lL)ErGmIMp8PZ^ZW1g`>EdUOTx2FV}vpBcWYon^Wx|z zC=b}L{7tYL+=tN&0<>-W2s5;rK2m3T{AhnKf}@gJPiy5(px2bS6_M-s1@e*2*|D{*Jx66pKrj}c9jbeoGi{C2$T z4^$mJwxHPiMO~7~&*PCg2bed*o`CRqS{gR8IYs!;E9({YzL&d9A;9Xk^ownap_~H* zl_RG%grdKvu^I1pGtddV0cKS}QtS}`r%cAy;WGK>0SOoWZw*57#Xr0{h#Zt%aW~Ls zlFEcjAKwT=H)`=H?2EQ3C0v4pjk*Z;?|TQY9<04G3CGUc>Ve*ob3Y!mW2#ukI+9@1w^iBU2 z3ddP7>+FyQs7*yc1DzEePn+L-J%;b5t$Hws4!XBwEQIfysW#gw+({F*V0yA}+^{*p z(XqWpsB}cE=e3 zKCd|h_)5i0c+9eo7b)35CrO1L$vPXDribiLOam}7{j{a80N4%Z7I^Aw_95C<5@TJ} zjQ&7H`2eCieHYd15pa zss6TV2r_2CmtMucH8bXvPTm@Ert~rcQEhH9zqbIs>pJ?)eOi!<;Hj?LxIzA2uwGRv z8ppFA4acHNwys7m_;)lWGKYEG0?NCas-f$1|L=OXXgQUs4db87{%%nd+PRp@_NE|~ z%ax+{+A~_EChx*~VMU@&070@C#wfVVb!dUElloTd=*QcE+WGpLENg=y!k|3)CL*>h zC*hkZK2tUo^t9)~$bSGl*GFpO@Z*O9S{Dxk&yDAG*%Z^S7MnXc>^JfhXE535+CL+^ z)d0}Z0zv0P|IB_eFh10_sh=+e77%)s+>1I+uiFHjhjQOQU?7h?o80O9A5r^@{o5lv zf#3BPv_!f@Amy(5V;mAzaBQ4dhFK^(`jLzw4ey4y#05M`VebU$KN*dvmo} z^9U%QuT|Tu0R7kFK#{<$TqMJ2{I}BY`=0E+RJzkKU<~td3tWEa1`uvF=o&|nEOCz0 zy&PYC^;qgIbbKD;u(ZPj&*}b(6er@S$=?CqC?w`jl;Z&_Bk*?|lT7Haob8X}5>EdB zc64P&i!D-0^4a@}`NN;dO<#0vv&t30AbmiWVf4oa(Ums#dz0@=ZkoNO@2kJ!T-ciI zTl_y|eF9{ni($0)0PqpvGw>L<%hPjGKq>Rugs-0!7yoJeOfvKT{;DT^S-zFi=o&^} z7rgQ`Ic2(6?CiT|1Ba-u<8}*=qBqfMFQ&P@?~)7mpv=d{17$4mk^rCZ`%btNM=7r> zZP5hq3-^=TDnWbE3uE4yNA-!0qK@1lDF$pj$$YVL`j-&{LzoSwlPSm zU$L925ky)ph2m?dQr+@?94m@LEO5fL&tA42Bs%S}Q&xxnQESrEMUN_!0QA`qZ>;G7 zVA8&BER{}-!F~XY5w^M8ixrEpOTD;ag>Kh8&pqx;15zR+lC*wcX#=y4^3D5BeMg|G zX|NjF?sZpN&jw(FT0Tl-o#w(9+-024K>}zVFG3lu|CWX&WW8F0y*-N&AhPSI>pxev zfyXI)9>uWZ*P7UfeO)y3bhbm5&p39)JPIbMwDupckXC|?X>0?{Ot}fU|4k^M<1w5nG7vO#i={ zzmbxj)zYkp_(FOrw7$us+mv7r#0+e4IX^;4rHT%qStpa@3X~cw?KXbAGB5x#T-Mn5c#(xEuK?0_BXH4&)&%+1>A z0+-B|41ahH07DC!wjn<|Caq%|Pf#-Ivg*vP91>msIi!Qlt%v=B(EFYjy)gzxY%-+rJj%H93 znFPIVgn3W4UC}y%>coMPQ-HSm@q-XdJCj9>;Bm9VmslTs2KzRh_}SI|gU}nJnw|M8 zbfWc744>l7;H`P#6=ErP%cFI$jV6ZaUH?{a>84+qjNf1MrASL5;68L+|De?P=;!XB z1%CNN!+JGh2}MH)0HvqPD~ZqZG!__IkcQ?^%A84~L`wn;J5g1BI!ZOnl*(Dd$m!gC z7}{%d;I!YIJP_?u#YRs}8~%$KS|pcoCyoQD(3WHBLodB!^aB#REM`&yFZwUrzTQW2 z^{633&)8{K#WasjWG5uPUKwe>pT3)`>q?;`kh|ZDzU(F#^%D&@VmoaijzHgyMN|1T zvW+378DNN;N{6NXkApy8pzGr(9%h6ZkTM59W+zWa z?S)sp{uecN%sSKf{yx!VjAdj7ba>%?PTY2vsycNXP561tZ3wYT;HBHmh;X~O4rECP zgprRcGD65hoU>TaIpo`Q*`bJp!WpSu_H=jl-GMlpusIH@D0Kx;<1x0r*>;gjv~R3ea$5qPh3D_86kpwZGPNz#by+N1_AC==tCr`JqqN^ z@m>5DwV!!-;P1b+gq9;w(|4w@nb=}xSwWJnx4}%t*z&>Z2Rn|7Zr9_bmDZ<+xub7+ z1cgZ~T_Pzdt-0TWCdWj79}6EV$F%TPdMGh6R<_kxKQF&Auf!|z$-MUAD#_12P!VvM zQsabF8X_i=x-!8cA0-rX&dw?_`U9>Uy}7^SxXF3+tK*~kdY|urf(3lijMvhIA@4Zy z5{Z-b8ss#<#*8$DeJ`%!Igsgwe}n!NeEUja;;(1d`Ife>_)sXY$9&9#tI~gXJ$5}) z@#iB$c#9f{qg(T`VF_mUVTDl~&$Gy&Xn5jxeZg??Uhl%y5(9&11BNk651A9EmDntf z%Vm{LA-cwx2)xR+?$6={Hw->CwuL9i;#(mwO4Y7V8!RSuUEQP)E`N^DpOedI=@ZOw z)k9I@c#>3$<(C4K^3^!Rn#h@H)?FU75fj0^N6-^<7b|V~y&LsP2D+f`pd^5A9kL*p zWtMG7A{|V3Ifk$Op4>k)z%Lv?vN#vPmwKZs8RBw<7P1!Vvd4nv9H2k#E})?()!rB%{Zv2pQ+yl~Rs#!f(`0 zw^i59)^x1OuE`v1_>z>+S%wBuqI~3;C!b zUY9=K6z!0mNp^%-3O`r<0w}lKO#!`bAJJ+R9(q>MqWyrxT}?7Zl3OV053007UfQe+ zY)}^rqX)(vbaYP}l?l-}9-fzAIlf>M&J}X5DFussa%EICl@> znbII>5(!a~qCmg4FQC-rKW)%5c+j#iINZ{M^*=$T^J|)qkBvlHHKSsvk2D~|Cln4& z?RtRRZv`Wn2;shR+K2UjeVGI~jd7X_CF{`nBjr2wvFYzniYd9SZs{>x()(}mm*+VA z;6@B%C(EJK6#}kY--SJe{v^Q$Ehf98o8u2in5V`SkF3_!T*M~X1>+$uVmAOVhVL2! ziKkVFBBbUGYgl8*VyL+jZTt#GGX9Fco834}O&(%t;^5t`u;AHbS=>56(>s=bln$q}9z(~MVUb9(0d2TB5XZ^_E;Q}JkHboOZqQELF*G!j+~ddn z((jDVXWHApgQOFRZ;wmSt{WOL&a!YKE8gDjTh^G=bMJ`l+Ux?{JDIR{;CVm)G+QLK zN-&FF#+vE$JZnD4IDdioz8&Zf4!k>V8H|p4Emm^!Ts(b&zHKl}qj(Ggm;1~?f&DN# zK(73rE|%e6NhwcMu6!wVw?Ua=EbI;r9p6EMu^BO=ZWq9}{7Gu7N!bulH!^QSTxbZe zit$J#;wruJ8`3pRw}MAqt?HxY`HaeShzTU~A5z{|+T1L*SJOTvF zKE!wq4!nJKM9W@my_Zq?L72$@3`O{LVyh6VTA;HC@ox7m+-!6jyNuU6|CgVnRRM`k zv#JpE0JxJ=4-ZXzH!rf1&J5a~64024jGCQjhZU-i3me6s2I=1&%lm4P?pRXALSKl+!8O1z*AVO#dbrqo1N_8=XxIv7X|K9<=}BdG=iqZQz%C z6@`erl^zyY9|sXv`hJYj$+?7Oa#z$aC=tw>aTomgJ2w}Vn;|q;C`5IU(VKSQaU}3d zuU7H9ZoF@54Uy|!jjJ_jJdPef<;G*xgu=}v%)v77IEcT%euO@_TW5;mkQz;bmhJOi8;dWy;fN#~M%)O0JN^76xQ0MVWFh$j z-6Br5pFfB=;vmihq9Ym&ZcaFc&f*eJ63=ZIU2njxXK z6cL(!ml2R!=4w9>OpF}%`Y-$k1JrjH)84b3DJ?hb#+j}rX_YXQV8_c#TED2X+cL!Z zZ#^NS`ySRM0)f$=70vq|BdVE>i@L77YmTGLrlY`0C!SPwU|?YVuAwns{jrBY_Di4& zwX5;dh?J1ZjtXh}CBndn@FIA6e^h`yWM&ai+MQLWA!mHbDHK}^-Af?j2bAb&le`Bz zCV{=UYKs~B8y6uqrq8;r#|iW?seHGKmT+*1dUn%;LU%|C9F-pPLV>Byz7{Kl>r6cj z8;}l47~pzVN%T}`g0^KrDPsG|V}lJ>qv@$Ia|_<>4i@>Gs2UyTw41i`3Tznt>36LD z>qK-jzQ~32>M-up)SUrHD`L7}Tu8>Kfi%4?J(RZK$q9b}iQqj9cW$(03zA!Q(RbJ?Wv0D$wF)w~ zK>m9$5VInke4NO9Zi2f427PbId{GW#A;Z83)8W4tUb_|>cFko^!8sfoJ~RCxFnvJf zooY?%c-iaLr;&Z;`p(`1fI1B6fSjPg|KtRzxA0*)*>585JxxzuN5(Jp?vctJ-%2>P zW4uoibzMh|$!ZZfUV}ciwJ-9A%#sp|se-=gJyt#*bY?@=*Ic;wmXKfSlt(z~Rbl-P zyY10fb@quvN;mNo1spa-agB?4)DLh14&-`*^yd)hgu<+&f%imnBTz?OL8W3KL&M1y zzMVtmYKlh)dGipIsayaL%4Qfa7Zdv*QNg|(mo9#D0wpMpv-q3+CBYjM@iNbjf)vr) zX08Mx;b__7wI4-%oI!xXzx%{(*D;q^HE#*p!6x{g*YV1jxOYnru52E;mVo(-i_W}C zyrGHNQjaRS{(9Czo@e*|0RTnfv<}nF%SN5DqVU*>Mk;M;9pALu6AK!8K2x^(6bMQ6R-Ict>`ih8ip-C z?3rl^*lgDF37_2}#gc3Jr_MfPvwoG-E!=z5)51;%xq;>h76K^N+**l~$n@`UA>ebTD67Mb?#g~#0;-PR8EFUh}LLb3VNulRwK zP7Z4p$@eg)-u^=Q9c^C>KSszkp5@CXQa*k(HCy0mLb6nu<7aq%Tmrl4D3+19*NS?L z+hq?3&b$bIGAX`-;JJH$DovMdW8*1f50460gFACH7{p2a>md5nn)_7m7n(c6w0V*ZYSyaAO{^t>(I%e#!!YLE;8nUPZBs_0X1w z&*K6Z#&qUOc;CV?WQ0aS_4pbGfqinrh5LN45 zB7Q&PB}UDL|Mx%M(RY2Dda8YPpd7`Jeg+hXZU2xQ|s-)=rN50EATud5Hk6IOKPrvJ3J@X>Se{=h81#OW#=9sumnVNsoJz%p6`W z;a`@m7H!@=@;)NqhvPw451wo|nCHIuj8@;w+`cljs95I|ePde!FpH=YpBk4-jG_h1 zfTIovkv*KfqKeBU+(m8j7_Fg<6%Ic5`au^q=v#0ax{zI(2v|=KmMCP5lCyo?22xd{vMW}R8q>H z0In`#QIWz&R9bAJ6O(JXaNi*=rEg}m!g>OWTBEwRO`5$ODcxc?2?)O)8GX9`?seI6 zFl60vtiHz{t4sh54s>3`o-|W}J65)w6|qv6@lNq+*<`Q0ot8`*(te+GRGaPX{Z_EZ-w9dA zFiKs%qR8Merr0HvQ6|+w0I#bYUdGZ=^!ekP(is#HwsBPu zTaHHp5OpWNe17pl}m>!Kn*&&zbg{ye|~f?Tu$rfE&0u(YLSb zz1~C4w*7eF_lA`^WUVS)ThG#^nu;$n+$G=d0!E^o1D^*(fk1(?rswI8y~^j9AKVcW z?~DY%&Lr@mH|2Kfd>`|0J&%gi|8+OEZz3f2Tw(>CZ1gu_ns`UM&ww_kbn zHeEU8_#K8fhBQMeT2}rVod*5vVSfjl{!B=bFxM~301Oz~On0a_e#=H6nn^X^%%Czgtk%5Y|I!k=41?AC$K3SNg>;;O zkOmY>pVYThbtCR`NqqNQ8cJ!$+EZ>A2 z(t_4A3JEBK&Q|$4ul4Bu_m%SkHcm3#+`viEOIkbpEVg@XcVAyHBkx_2O~hQs z6mS%gVNT`9M)h;Jvh|FD3)OVJUB%EOazdKV4B3jAW4e^K;-W0y_)dNWy?mZ6AYVrR zrVL*W*mou>0p3GfVNXsiuX+Se1?*Uz64x9A-D1!uG(j1pebZ6sZ9CF3 zgO$@5noD&) zfo3*hKYq6GO>9?LUVB@z1WFCHj$)poe)ptW2smLKL{_2&zxEaC@j zzJ%eGc3|;et+5&;Plllp=Om$DmasbUFq?IJ8V2m3W`Ryk2g4_YAF~RKUx--_GWj3a z5I!hxuX`rL09b1Uz-HMAJunAKj#~F?t`|RHG7E-P!n}&C{#W!%0LK>A>lI?!L~LIN z#F|ShRzzPh>>?jvw$tG&g5(#Lg@D>+^N#Z|e| z^`vIh_8-LC=XlO)Kl7RFjbgnB!#@YrHnNGXkU<9-UBkM?fThpFKgh}wh+UG*e$em- z!Yh3Hg9ZXD_hM#l=#P4dbxTouNlI7V4W&j+YY z@J!UZ$Ok)dWf+oZBu+k!D)5H*JdQHXxVTW@&h_NdAhvfG@gvq~ zdK6PzrJ%FvJ`8Z54Z=o#B%>P&Mdav1&c~Sj6k3@<1iRhX;nLN|sSel6dFl*;W>b_r z+;{zACuhl?w4f*@H;Icf9HN~y*p~JDbesWx@hNu?$Gv{Cl-X$XTjwCPBp94}s+A&su ztL1Z(OFsVy8UfhMxpKDn;6kEcW2)NkjNkOWzYNO|&luB5ciazfC*cBR2MAg9cVb;B z$*Tk5N@F?+<7^oobRdDUQ_-5%iKb0`=iz(Oa(*K$r{)3Xl08(i@2&7ut90cy^bjOI z-?Rs(3p}#L@Wx*_jn~r(8RBhZRMv62L>-PFg%H16*B)ynqqKjowtGCl@Mptliv-SR z_5|I=r3Ry{qq$P>27xMeh3%)@SUn>G(v#Pb91wEy3(BnAYAx0x^(PeJ-Tsxvg@ODT zm>zh9zqK9U38F*K7^)yMx@*|~9HSBWb|Sa40lyy}jChL0z*Whghz=I2%r(y6mNnyV zkj`UN_FU*aG`u`Eut-CLaUy_Gb^S-FDB?TgA3!z?-KF_%xn=F5Wf8ABFGEpnCVY4+ z^d2Ei!%gok*%qbhAoEsRk!p|NEoo;ro^kGRHcM8TZJ09j{W`6roSJM^4zx9$DSprY ze|^WVHmdxp&3-qo#<2=#Ll#1|y4)z-D0)$d7$dDa9$A2~N}sRry8D4~{Pq>B)40pG z4MzPL7rBdi-TOo@CM9MFp_o{+JPn@f0(~uGy;@7-*h8OnWS*6N*+0Sdv zQ+)A8ED3ZZ*nK4KCTl#|1ExttWdYk3td=#X+lmTHU$m{+G+jxon^%7=`9izL%fv7I zPpIUIXY`hkg|KS2Shh1mvRESPW||oZRxYxzr&79XLA-D*l2(Fa!X?rn*B4)Spp}6~ z;ezqEBjz(*ff>Mlw>3x#jERG|@1aGz5e(3)OS81^w~i}X>!3a^7M~AW)C;-rZag+1 zE$*#n3xmQ!zQ;c1P_7d@#Z*TvWTQH%6GMu{X=HYotO5(5c0o9O7x@61k^R;OKD@|) zTTpSt(>_R88`TuiXqZz89@C60=j?T6Pu5iQi$mDYB$;>W{qo_&1L%Rau$9B@%)mRS zlwsJHkQKwQ6K;1`9pq6(wu~Jh34aRM4M#@*jT%82g)Y>?N!XEZn}GMt1T$tQr}3Xr z#GQNRmSZ;p0aMdvKx@pi_2wvW!D?=L^dXR>f5yODax>pM_ho(a6S%k%bCV3g-1aaj zDQH`&+g73KZXJXt>L zey~;tS*SNgIl7TidK%PmVxEUYy$<@m;Lu)D%+}p5EMh*4xJb6cPhh`0z=4zjd}8FMNV(r2Il_1On7P3x!6D zNBy@$Mb{I^dCYw=@%}y77I;iYgvB5U21<>sG?a9t+mGqs3k{ge*icdpqfMC;9-iqQ zz-BlTZ3YZ}NbBL!T!(+*K73cjH^Y*zWUMHf1-9HFwFkbprF?sub}hwl{ih9#LMRf} zi$IV?@&9w%$4Iz8Sn}<5v2tne zBm95U_p1LpeHRJ4#k>&=%07+ZRrr_Fv&yl@z*ylns^fIJ4s}|)1(Jj~YXJAO2Pgu4 zbY8PmEm&QKtZ}#;3tE-CEX@@Y-0esx8$Z&dtMA5Z79Xeyz63fj%*ZMd3m|2~VFLRA zQ7`!3*`iRfD-vnFAlz-Uo^;mTtcRGgt(wvGWDUywSU*&w!A;^Ic&tX=0^?|$HBQ)E z{?A5JAi0}Z8Q$ZSp**Gi{4edNEFyB~FtSwLdCAnt1rgHkoLG2a{13&=&}v78IMI^A?CTumG)JWglr zmR#sTYz2~RQ6ecAwNGkRAozO_idK`hLz#Tn%lOzy5Z69>VR!Nk2ynF^Ol3`{dbjnh zU&dB=>O(nTZ_lgP=GxcObh!uX_>mP*SWj++*lIdz%d(En;)!fB%OsAA`}(kNt@IgH z>0JzqPwW#cU@#FRJ&F$lm|Q5djcM7fq|17i@<(=d&-`YQLsVLN>Ve5eDjI&*zGyby zByCa=3E||0>-e@`$`M`W4mng)SSs%Ah^ljZt@oE951Dw)AbaFSEHaIY13re>esX)H zl-pZv=4~1OS(CBB!jc>B)F4`~~pCtn(Qo4Wxpr5E9 zE$h3e8>n0)F_5zQM!fN91jvAR$CO0&<@{uX1%=gJ&&(TWF{2+LCUgFVq#(c$4+RS;=eLlWlrUb57bAsN46L zkaEZ}P~2Nh#V@fHwARBFYMA`{vK?4{BodN|a~O&XkZW2nGU|!--s{4!7U=l6KVsMX zmL(tof;(D!$(?O|es_vFuo>3Ge$250=a@=u>joI0VKavK! z@BP}nC$jTteSgxdj(v9z5c0bPi}VA6BY^X*c$~Pq;sV^yRe*^mjGcp$V7*qeK(LcD z>F*yvd2y1O3X!{gm@ZHo<=_UII<#j$EiqrhVok^bq(f3Wi#YR`3qHw zy*!MgqXr^03-M0FTyP#^!^@V>cuMBociTyKdW&t8WZK%5ej=?rZJ{oZZ*Jyo1KMeJ zJS?ydK0=FeB!g;c_uKIHP9M0@duci8Ruj(z@;AGVgr3!OC6a9#%k9Gnlz|@Z(54GI zE~OkXqe3rM+s@yJBx2P`wzW{pD%pHWG29wX>;hV2a7gcX+XvVo$SVd2mZV%`RmLmVW@=pd*jFlK)uZtvV!=|kSKwZs8HB~azyJSufh02cRUziT) z8CV3x9H9Wu^uaA78$3?F4 zpy_RD(Ga@id-fDs!QTJ@HqDhk*Cs<+{KTHVFM$zt1lrF>gH=Nt8=;O$gV1w8U_RQvvG*wk4$I>31F=5|)NtPF|gHATI6H?}{ zBk{qEXU9>K<){3v4-T^lz~I!a1@I_JTwFwF!1XF;&kg7|XXh+w_f=RK+ca%;iAcnu zC!@ZxvnYZK`97#IqIGt`xekQ_bnlPl0_~1sP>oB=!i>8^DPfOj-hEBa(|RB<*2q*l z#@^DliNN~sN3BC2xPZCg9N}htdL7+Up@MnwdB!-i0t!AZ9y?Kc)N0WJH8e5{F2{xYX;y>g0y~nN_rA3<5OR<9 zNtZR+_VwgCBkAh8X$|XCk^^h+~{Fm;N>e90sHJ#l3CY zcz99{zi{SOUk7ph3rPG~lJ%CqZFC-=Q(i3%F+qS8;@Byc?8K@r+|mWF;AP*Fr&nCj z3bVU-P9>?^Fl{}?SH8WpoqJN%h85cjYnXPdFY(ns&!K|~nev(h>#C-}Bgx#MuOSr0 zj7j^$RG7`<7Unno-khAMk3!XL2jp*GOXY`we4AkG$C9&fjK^+Fe5DmhRyg2&4nF~q ztM$t)B`koarJxwa`RM4&ncOQ#rO?yzE3j3U{!o-z};&6_xA>P5(NKmkWNgj zHq01j#Hs;sXx@2z8<^Zf`6zeF<8mCO>$?5#UyMh4#DgFH&#GppiQ=PD=wnv$ego%6 zN|tUz>yrkcbub;%QT_TlQ}t&OtBthqm-dTMo0%l2?N{}#+Uid)y!~<)!Zd9>iAy4# z;OLqf06%T^oA(0(2H1Jk946l(bV<+WF}o+3Ct4bBh#n>MH&5@!e~!l%U#~6#dQE_l ztU#{6-_jlnB66nM7ny4ecHvs#gY=%#pia(tdT#5d=CG>k2|TeP7+55!q8_e>xcjpy zG}5!?!sALGmkcwi$|ES!6{gQu?7&Y7=;B!kRigll#$o;wo>X^5v8CYiiDPeR8T*42 z%rfp3@bJWgV`(z*omvb3x$u%j4+?FZY)jurv;*w9ZLQhE%d*{F|gg?+*vW zM)|#<4T?_Z_R|I<#gzcE1i)l3hBn$qwXp1nB}O|5RVSgu75z-%q`?dNK5npV$xzO6 z;xxt{)dilhbuC#$)B9RjA#Rn1#G38!hef^-FYbj}L1E4?h4=b<;8M3!%M@Z-J@(+e z$5*dIrpH#syE>mxmS4 z3bFf#Ml!T1A>=|C*g@7UeH`21fS61fmvOE{%4?>$tSD|W9Z@aam|@=#QAXeHnN9HMOx^YBm5WWp93^44unRm6U{QzF(K1mysOaZ(PAW zT+&Q57c31C>m3-er%`ku&l{Pd2uA>y%~lUCV7L~BM7xd(qFucl_+E{2FnwcpdUbpQ zHni0PAO2g&liwCeF#{=w|3Wi1)*E#-+u`t(K=R$Oa#!9zj1bu8dS{L|0loY}uRg#c zhb|ygDe4c%gA` zl`Q9f0T6*I&y0IKI(LB|FG$hR%orPQGbAxQHDJi z{6St9Ye!w-Mt(lf|A}JuvQ|bZxbie={Iq% ziVvc5mxGJm;RyIe%J0dR*0JcPDO3M9pND!EUqpy(q0Nl^%s@t66WSE7r_^EI{#$!&u^-TME%n9BYgW58E|Je4lWi9g}s1?@>CX)^?mhu7p44lh}WVt%E zs{to)nbwI8YmTTy7X8^49r?%r{2q&9N9d7ErMUMa`Mb?@R5}n@GbYv7QJpkt25h%~ zqi}I`)5MNV6W7WKXAFwXoP$+g;!_)xN#NbWKd(OwbmQ0$x21g*;Y;>>q)e(GX`dEJ zV;=)5-j!z%vI#2Y1g%i0!=g!jrlYK&I~F=o27l=Ef43HoYI+oaEIkmc<2dZ$77T2+ z6HY*cTPMH*4pixLyD9SkoRoG->7KSSf7!LsGE#DlqP=_>Z>(#7>!;M5wFG9NkF}*c zNLtD#zqtAlp4H7B*N=hp%%1*iypPX)K&=-pft#QCA~GtQQ! z`rsg2qo+a5_zfHb?1;5XY{3c1kHHcyE{iqw8kO=z{taG24}ok;QqjB*10Z{=MY%x3 znv>z5AEZGq!sKRo>0!MO%`q?t%SF^fU1QHe6bDO)_s(nQ&-!n~lI#C`7oQ?@?^pEB z$#okQ7Eh-;5$tt+iLF!?#AQw>Ib3w1{r(hH8$MO?^7cai}hI zjG&)i?%Wl39OjI(R%rbKPd*L#4IeWqp>dNs)${EI{)>9q&a5^Sq!0%B7wl!=%rQB3y#fNADi0#Tiah^mZPM}bMvc#j+5;vF8PgWuigZY?L-kAo zY1o#44zs&kX~Jg*Ucyw2aU4D}m$^+}^Q`C95tL~XFZ+!BEDOywo&;o>6Q+0%ctR=Z zA8OOIpzg*$rbuLN`ud|ZU%Pn~U=@@N*8kMnn@s#rv9r(;sCvB%lr8%%X^AfuoSO$a z#^c~|q2&3{^P5A$IP5YsthkXp9d4;?6N&C`54dx+@ilw*KG8iMo5&Ujzr(}U#v30f zJzFvf!;4B%w!kdcR;%v*1G9P=jt`xMoAW;I#-U$<30a&>kUmU2vzlH*qNbX9obJjuh5qiP$4sG^f~26_Jn}CEe|(5rfWKFmuIuyNQbh z3bf(D<)8dDM=b(lo_3HENPyOZd?K!Oc@yh#xf)8se%LX}qMqYUn!Dl`4G2lRJLA7S z_}sA11EY!K!|Mo43Z5yNFMB7~?h+1R($QZo!p07D@tdcqVg9Dtd6#-!k1#GCzW3=y zz{`JqoW!GJnTJN4EPWHlp;4A*f2sU}e^b>f`z1~a5w?$O@n*&BYczj_nYr+87WBvo z`U;Uie6d8#;+XhE`%6Nckm_WyvjdRnCFKOOh8ZdQJg-P3u^Jm9BO7zmfy8l5j-$-n zZbMn)4MmLKKTQ@ZYu#g4DXEAWFuxOYPMEO-b8N$e{6Wu{C-3GaOzQM+7YukLhwD|% z9=IGj>Ve0J40X;)U+lOOLU<=OI{sm-=Tj}L?HTdKU662BCbZ;Lp^L=Hs{t|rnI-u* zPXJqSv;pU~hUE?Ta>w;p$qAU;x=>mWrNA7pt06>+uH^4}ffrL^ood00`(EPx>yc7r zy@amnFhlPMdvK1NknRaq7(R_G;^6H%**k7H$WT&=J@-|0FHCjAN zE&HraKTqe&9vA1IuCKcveCJCU5__Ut=H)u_)bpc=J7ZN7?~*?O9d{3k!dzu6nnah8 zC0?PMIR4DCS0!Jqp6e?5YP%pH7wp)Co}1G=0XU#+eZNN2XLIpefq#(8udupA0fwj-{C!V(C}H zlXW%7zxt_dNqr4rR;K^D+Ry)I-vfe2Cbr6Xlz9p|s$)hPYgo|;W}I|oDVkW1rHL0W zrFI>dO{HF>9-9J=S-!h}J)IZ9{WLK|I37f%ov+6jA5s9HqK%(?Po>wPm`gH}{~6%j z6N^nvm#uMyBb>YI`Y7zl`+Tyj3^)*`KLPh<=Ck>41e07(&{=vq_hVJ7|N5cF-_Xz9 zl_a>L6MpvN1rH*%?U1@G`kiM2^vUi2p-=vIX)d!_)vnntR%MLB1aHqA4GNw;Rq&TC zw&pFiCQN$v;QHK-nODrZ5JX002%Wce0s$huHK0v*+`_s?-TueAW^FdhM-y7nJvlIN zj5oz|6^Zlp{GP#_BhvE0dF!KXr+2JpsC>M~nN29q18`^oi)a-oPB8GweN>Eh9C^$c z)9h{M3{wVCg;C-Ng0|t{hfH=n_D*fFLZXyLM?U0v=DM#zj<@7NJI7j5DR;B8AQ3-8 zup%iCis0M(x9PrW=)!xoDn+VZejz{}!-(qeUg0x4(TV#(; z&w}C&c$Hf0Te6+&9ks zErcXX@OdOcPmP+PAe9`o;2+0(DveyhFAPDC^OZoL;+I>AZ(b@S?u3rmb81$-go?ZBh8{Y*DP5O?9nyQLx!@ zIHB!$c-<@vx)=ZJ7AAyt#t08p=*^Nja{DKn z?Pg7&VixuK)4EKEbY+gjU`a$nd@2*n5=hMe3uWBkJeX7Y6_EjfedU z1t0<1xL0GS2bgIvt7SVM*YVxBuiAcngE6jj`K*a=DH>6m4E!V|?*##i$UAl1eaNiz zwhl53@;QjLb1H71e(inrI`Gy!*Q_DxjFM)gVH5EM^gR zX>hu3R+bAkf+c;}GBhMQmLxX4c@&OCr=JCQ#`6dBz$;i^Jd{ULmVHot@3Yv3`Io6qIOqAH55k-4S?*}v{sC-rbyOWOTjJzGiH2#O<5yg+OYttfbid$p{an{o!#9#mE z@gvsm;=H|jjmZ6asK#Xcwd<)T>$$V-$ng87mnt64gE!c`X$@Mwa#tIwvS%)a59J@< zb~V?vo)Dpe=S`8I_MmwE{psjz#gM#{^UFARfuDusS96d=V2Q#--q8SLaMcz1Gz!s+ zQ0fp}3u&(-7Y~X_&iIuWlt`KL(_XR`CI4_*iFPQprpi<#9LG;u^Ek|KNzE2>ve&P5 z((==k1j_rD+gDPQ}_0=I!{l1CAq)zZyud>90&Zt#1OxQ=m9dmp==;zwEZE56HTXQsxkkC$TX z(*j3njN4zA|2?a3j;6^)GlA{_V`dA}F-B4Wpyu2q{Sj0s9I)=xL>6Os>A>-?7w8_Y8-xar z9UpWM=J&HXYcEg0scG~hx2KeB)y;_Xbk=x31PZzqMkg%&A_8sB-DXpxl=%A_QKfq?K~2u3D=o8o=kJ{i5vnnye$)~Oo`T1VIDl~;y@@?4mdo#g6iPu+^pTKyfKcg*uhhz7?Z^{X zEE(urH*`v1Dtr6BP*a{N2PKu#uGiGLJ>n#Q^ihxT z#w%9%b}ZW@GY%-ev=5cpA#H06-he%!gr>`M2_(OdbY?^^J+04a8FX2xchkZtx3pXd zB{XX`=ixsuzfS|iKwz?4gJAzJV?|faz8;`sIC0W6)~`FmQo_wZsMWOn4pvhHB~wz4 zDKwdWV_D^?iT5?H4R$9l_PcO#3!%;Tt%j|gR#KQnjWa~otdaaAca zOl9UBjY1#z4}j%IexLX*3Wb_$jITGl3QbkT32**vqa@g5Qjm>FU~7<1o^|XcNr6Pg?1hTLl_CQo!an`*7KIkF-v@TK=d^l&&Qi<~Rp&F3F~l_FAADs_(4-K%jKPqssQK$) z#WJhUVq!`@nOcRl?x(t`1@ki?fX8R^-~EksWNa4ON5YCZ;knBn!oSnb`H+$XXAS{O zAM#f?*jyNrEzgHx0QYBhGRJ4JC3`FUL+7I<)OTR`ImFZE67r7@STOicu#c_juKs0Kw-#Ky76OSe{7i7_ zx6>iVAlOqh4v{XQ0#hu1Eq=7Y&JwjYGh5}4REK3A6V$`B_M@cujWs%qU zX3@7R36=jfy_WsM0)dxN5v^(}%#V(NKGHdi%~#*g2=a=Khn*I5Qxbw-?EekGCEW(! zluse_Mm%Xn%AS|_CLkcUBN~v+f`+jPkY!q-GX%%`B2){d26hgH`L~x{pO0mk#8LYI zHNqg2pj!~mNb*+-=U||Loe*|DUv?DjjXfR;SAw|TJ~lPm2HIAcXplS**j z4#Q*2Woh0%aWiu067awDp$UmeI~xgqR7L877Sp*} zWyb0)08SUE^9q%6zwCZpjBL&=+#Zui|B(5F8v(pq56{}JT9%?hkQGBR4uKe_PUK(* zzCc}lJ(&gBO^4{4nr!kxD21z1p(tsUAkHzOhWi|R*%~}Rb+(EBtb$LPpmY|4U>Zhh zm_FtRsqu+|pr#-K%1(O{f#YQ|%y$%Y`{g;uW_tEV;u<8%>Td&HRncMx^X9(H(>=lXT`mpcY=2f{Kj9^bkZO??&$*ciwsfHN zPXB4mPMZzeX17THKAO!i{7XgmHO@KFjx8uHnLshBA~kHE(BLNXO6YcyTRLq)w)yz(kko!wZ4+z0D%lVlY{S(er?5g1ZE93P?g) z-_+&-op5m}_hM<}*~+`>bY4D_@^PA>cU}v?hPv>$4JYpMD@EL7kCPt(xc_WNpK$b? zS7&*Oe&yB7t=ThiD60Uy|2PQC4L4g?-@gHSpJ)IOjPI#NvB{G|KnHC)JWAEFvo5e! zGNjDg1c>CwvVA7^3-I}2b(1p~=lqbnLbtrp0K%?YB=5g^bIcdAI#0>x>-aM-Xgb>? z0KIap#@f?K3Z3x$ep#cu+#SshJYc29|6kjizXjsS;TpbhGVj03WpjC*^DjwIWt=0O zil=b^>2W6v2|Jrha8oUk%1{kbA_D_H{A|*r0{(JT&1sS{wVSLfUZezaM?0sidC{c# z6!IgUj{NJDWnTp16KmUkcY;J5Ja`8^ZA6nOhf&=oyQJ-^*dw zqxZd;E5R&VW_poXax55`aDA&ZySphn!#bOt*=(HUalns%qvB(d#(18vtW@vj%_|j zF6p;~jKFJUFPgM%*i4jz zO8|8pNF|JeL?i#m-E4y4&->Kp61yMRK|xY(Rf1nlf4tgF1bTO<6a5wsCm0T8`2`F+ zF-zP+E!!~;S2)SDAeD+7j1N<&l6bADM5NL&!6uG`hlGc&J3C2(aEf=L!MT`9Qa2HZ z;SNZpM`o4-q8~lQXWdJ{f6vD2izv*i%96o~Tfk|1R(NP*;~0Dn}zs#|IC1frrp2cUmjWBhWQjfbR-yfq4;OnM^fG=bD@BeyFW85>d zBC8%(B1UqNFtdA-SCoOx>Z;T#+*LLxm9m#zUcx0LK$M~QoH`XLO6fG|(2 z863-TjFjea#$wc*A!enOqL`0x-gyRx14a-@a|%2K-C21Wt+|*{iP*1ZwZq00Rby8; zouRL%mUhV89Wa#)DEI+0($Icr(Bq%%>Df{0B>cKOLG5OtHjm1)DGJc0EvTGJ`j3;` z+FdvRT}Zq4EAmV*t1`hjc+%=)@eK7MPClQdQEPSJ=;aJvb(NccVP+R-`X8t-={HCf z7^b-6XjlK}lTC)@{`q?{czHZ)^UEmxcwDfy_#Cm*Ek2j~(~dOYm{05VJ${=L391x? z+D>r>VChd{o4zhhGK$lF_K1=^LoonDf4a-);vCEjK2c>WiHTVbovr{5BI3g5c>>us ze7y6mhbh3_>gYd0@6T9vzq4J{hxiE?fp|sa9k^LS%yAyy)_r=vRE!O@ zUI>u5vn>Gk%z^;DmhW}R|FfPFhmP9_&(;TWP@3}Vo2Kyo(%{J~_1Np5*XrtyqO)dv z6JRwGYa$V@>TBAInnBe`rSz$PMru$7_>~!}(m6u+S5k<}OlN?!08;8W9GWCC5enWXPFedWze^_Cw|0#|SNcxROCMW2`kCk} z7}Tg|BEROJfb82&-%(uH5yP>?dD*0R?7X>x-fP9;tOM@ZxK9a5c~xb8b{rVv5QxWQ z91`X!+n->k^#B45)YS=9PG&+=Wv)CviBs!K{&GMytnMb3agsF$r}G%N*j&>){Ao)z z-ineRgL>+y(F6+5+jGEbp%&K{U6e43+`JZqp}+yI_5}6nmJhf=nAaK4~?O<8%h|u z8Hjg9Axy?H4{1c3Q$;!D1@9%mx=cE)Vdr{oE-$Yu-IZ5tww^azi0;XTk8zj|{@GYC zf2xK$m0;dTwUK;4^%)~Gbt`L)nv=$_@~HvJaU}qtS^ENT7K9g0C>pBsP)KlSF~=bF z!q1|;Z9Xz)*bw9i4%9E|x~VZ$o*DXR()cd-va~Q0r8R#+Qk9W0>H7j&aU4kUJ*$GB z*0pK_X6a%QX)&gm6D&&(PfOc$Hs)U~Gn`RrZN*hZ+K$Jr010eGMT`$6DbwBVM~mfd zpL{75l#VIa$(PKuI_L4>a)?n}ZDu>E^Qp~dtz>ER>h^M(AVOLQ;)uo-9Njl#oXSeH z9Jt{5%ooRz&!_k4Ba!ggi?$rV*yoobD?j<~t4>(FUaRis!?SkI1sf{#1;`aGqppj< zQn}G{_OsRz(uFW*k-L27N+2wLZu+M*S;f3GnSU#yVv|n&wd_ps8HgpH_~pYtL#E6b zj_B2b*D&PfS`IwDq(^`igZqs}u5M)`Rvu#8rnmH1?0ALE-5y+?i)H*;<*@MZ`8$e|diTphX5|Uf z^TA0N{^G)QtV2pD5}T4*=vDxD_G(1baP)uQGL5#ug5Jmu*}It;)`Z`15}Pc(>6oYU z!Hoi`|BV#|nv$63-P=dNO^J3w8E>G;lx%_oHo)fn@cUS157HK!G(X(p zV!PU@lZzyUq?To+Ox*a9@RH*r78A}H9kL`XmsWE9_7|i#a1VwTWE(Wxa9axF_Z_8F zCHq*3V7uSj7QdT30nj65Xm`0;cAF(_*JY~j6ttFo8yEExz3c<~mV=ImKPMeeis6Ie z^28hI+LY5CdwK>xFP+ZQrzBY8UITSG5fra!;bNGxbiK<)8AIU!75^;Zr;n^cpj1-y51b4_HFrZTs2k zq?sOyX2LW~H4+P=yIU_^(32M?=@xjmQZPk9;Xuy^c)6hi~jzQ<@ zBO6N{W9-6<9_YRxqJ;uX*k6loWL~RtB7d^SrGaeXm36=!26KS)5A4JrIh(H# zZq4(5Tn#$zoSzHjWo@V{{#bRL+xcnS)Vy%yGDqeZl&6!MO{>+@QJI! z{>uN@hF4UX#S-JcpTAkU)?sxaBr;7qGW1CWy^wmDC$`C*`!Xu4U=!$cC}MmE6*_`v5d*iKr_5L~ z8qPv(MGdPtQ(o3~UwTc$#&9@40X|K2+Hpyd44;%jSx1;)R-YP6Z1XIAb)X{do!Q-x;4$`IG4(F?x3%XzKBKC1z91n-elNQDG1O*Jec z)}~040x$ChV!_Mbob6tKkpQZ>tIx@H$k{`Nc*Ml(rncV<@Vs3hxjr*85>VSe*J8=& z!Jy0~6nXvU-{N1F2!p=fZfby#Ou2A$<7sj*&Sb02Hw!0(W}5XM+@ATbj6EcV^Z#B{ zIom_l=2Qk`?-ssnc^uFYXvIb3TUn9(y3rh{PSFJKS{h=Zab{xozBSDDtZ5Tnhigg zwq%duu4}W}z{5Q>zc@zZe0Y$?;4#|p@>Evz<<4gMFVd5likijue^DQ1b!)@J-Scj_ z-oTlz7iN374T*5ZIQ?-;w*WTT+uq7CyMU=XISm(~9|+JFI2n@NaPSY6ks2mkJpGpR zYM?Z{oSpkSlM(qmgNR}#jSy^^kttBrU1iBJ#K1-Ug__)vt5GQB|^^*|o5A8cTN`o34CsK=L#Gu8W)^1}NQozw1V6j+sKHe~}@7 z`rd4g4{0l5G+*2JD#Xu4w4!`A&Ur_WWj>nLmW1PLKUS7b^;}HeTZ8< zVUxN-d|^*~CE|?uff7ag4V(*suBF%jcewWOrbOO9_=K`YhGD57+U}w+63yDKy=3rm zzy^*rW_4eh072S|X)qoeOrW@Ns6V0dRu0NPq&i8W%o})2iXiu*f!~hYs30(0yQv9-ebbGbnc(`*64fc-6WCp;eNThJH7I_3q2=xI=5c z5uk|0~=zGcaC%>VE(*-G}g&Ha^1kO^vC-P4)B2HFZ zeyN*Rhj!RaS(c&!q4kwsam4l7Bv?aCy1bAnkHXBs(1UPU9g>y5Nx8wqJ<&-e?v5Kf zk$*iypl*aG{hGS0H#cA0gcf3mN3VV#e}A952*Y{V>2c?MADs?V7WQx+&{Zk)XaiwL z#b3Hllr?uqcs5&kD9TVWFW;`0f`bmyYT{4B8WtC{J}HqAPA%h3u-d#7j|7iwsmSHi7<~Wl{+8AcvboIV*qoD#sPOH=gBxG@w}T&r>_@1P5P94# zYtQqPE;1C5oF5PaZ}TsbkWud!9uFUnmyQ3RC13vsT5^O30X<%?n7)_H+U0sx zB30SEC-Dx>RZMneiVuM9j7-r>L>M9rF)xP@XQWE#rW$>yRM!|rQjUZB=2jp81*t<1 zolS{eH_35tNI2c6=tP0w$!#$sjl6P!29Z++3ok~(bvUeG8*)~yDB$6_6Mm`Q;5P-aN%`JdE4ZzCuRs>Fxj#qix6C)tYyL!K_TRen5yX`3ErjWgtj-u?(E=HxdX_y1} zqyV1^leAA};#RK!Pw;!rs6rMki58*H6c@lkLhn2TfP=d*WY*wpp874}FSI1nc zByX;a!A+Br6X;_kQ-I+T+nLY$RH-Imh;7}*)LUdR(`uvqmbbh7lezNi$+BZ0K`Fr< zsza%Ql92$Ez2DA>y z@^B|9>b`O<==W2sx;-sU7oSh7fCy6SC$oOpd_)S#GLX6{x$n{0{*n|A{^ju#qH6id z{o|rTTcl?%ZfNeO!^B`0Oysys;A;LX(Y_)yg9z30xz9ck!2w*Ws)N0=7{k zJ3AvsV-4I_w!3AP1&COE2a%9jTzljw6ELrHA87lvM~34<=@{eJiby`aN`g_rFC2@@ z%S{FzFCh4&JMRFJPaU;jY@PM)Ww&Y4PaOtY8RQ|1PWvazbk%0aNc@*lp#rA` zsgqaX1M(=K$O;%(f{-6&uNKf-eS>nHY?c zov$0X?wzNaZVKBTT@{ou*s7Jrk>zgrlYk=ft@^Sdm!vjR`5+Mb6m1j$16;>Gqv00- zbU<7ygy`EhGMOv(4d?p>ZgFoPAp9qg_EczDnQl&YQ^Ti2Jcj(E^0?lRf__XbzNXBJ z>g@B0WA%?fI5Q!XJk%*FJt$QsSHt`yOQSG>)9+J#A1K_Db_6LIW%44gMj$<`FE@2r_sQ_}{MDb^FeJsXyjph%2!E#|N1we7 zke$LW4{IL%!@)DeipzS#);n1N^jX~t91{miJ=IRvT#XWzeUeDppN3|k_qDs#*(wtw zCVzvYjd0k5?-!XaB}w6aI>mh|_}Lf?n2`y^p;DAGerJadua|8w9L9lSd%qsrsQ${1 zW^wP)5?dP%gM^d*k=HcNNunz1=UDzjn2gr?YM&0D33v4(;NS?@J6Q7^T>=w2MD*<6 zf+ojkSxG`JbTXbWV=}$+%k*TiIRr`CzUzF#2pwPq)bnOF68+4?vNKf9J(z? zLa1ZnxE~^GP#QlN7$3rISY|2wvpW%fpx0`nD}XBN@8gF`91wm?fygX{#h!ddQ)q?+ za6`zQJ3yswH!41$b3Qt~(05Gn8#=a_6Aq75v!?dBN0!##TxW$a3>h8AKFAw*(b6j9 zWYfqshnfqYO9Pdo645FI>KaufiGN($egB*ABeelFs%Tm%6g?@(QCNV=E{sxfI{Fl4 znWW~}epB5VA;pQ(POM~vv6NLiW-}U2F}fI9)lRX0-l>)V`Gkqae*nP;f;#Fr1LVk$ z>02+0H!>>RPRS1cz!@y~fYAUKrSyFZ{HfR)lwbw}$`2Th5<1DWy14iL%aA_un}b+@0j*VSdUjad`C z{j*A)l?^wMkGW_RRrtCveTj>fx?GSzTKY$AvJ5@41`ewBrL|McM|DJ$Ai@OW+$4hvU;^NSC=@Ioy2JzbG4PxuysrL;Nvkr)>q*S4 z(>wyQ0Eq{?GtN`FoRZ_;fTW6Qorx(N6>5i3LpgxPh}N4!P^7RP#mlo1Bvk=gZnGVz zvTnx?;&02;9FO_M8=U@--2nQ)Xe-s=N>fy~P5nx2%S3TBM%45E&We#+0)Cf6FeelobUGy=@2!09j0Dt=~mk zvB^(D$=@;8@HJk_U1<@xX7|8+Wu+i`k-oka$5K@5m@S};|0Z<{{IMM^+MwUc7>+g# z?9?<06;Cuq6Ao%y0s5yy1b{i_X0W`KS1kuFD;CY-2-gc`fvDh=&zQnf!VZ;cFp6!cwAl z*TY$lPl-}n4)ixDrGX`%l%Lao)B=W>PEnsHS$ob)8bOm$vT%}SVKTF?k3DJ2T0-j> zSN6M*;y5IypZH^wx&?@6Jg{S;d-2>F>vCrT4r0rT7Xi2%rZr`G5CBeQ6rkOdWG3gr zzkMH-jmml0U)!OAAYgqHL8J9N%y6UH7ThXxl12bpw6S5UCU@)93dxL8dWsD z3jj&mXyVRbm94fn9M9zb5zD(+DecGF2*A4BGd)w~013hHezXzs=l`x)6aOFGT6Uf# zuxW|4VmuA>ck-CEBc<-=Ox=tMMTS`-Of+##uM5|%`RLVY(Dt6ahN^|o6<#)Eg2B~?C$Vw!H1v*oc- ztx@vfwPpuD1F`JT)7O$R+G|n1eK}fomI{)fxmDl1ua=M*>t|4y8?TaxY9R;6FXCxu z)lA+ncOfEb{eT4Y^0;}m+|@!#xzomfBkwgoVvz*f9LHiNEM_LAn=Ae(tw;YXF8wSO z;s~4zoA#tPlKWOfs!s87$ZLDNq74M}H;-g5pM~kEP8~5B&s)ug(vX=yyMT{GnfUNz zR9p6=)7v{AyPzk%ju!l?so@SkX@14bPc`=531hPBeNc8N{|%^-rSl+G^sRfF34dc|(5T0J37U^!rvfR7b()xi#G7eBIcsu{JFl=1 z{!0e%Tmxy2g-cwM0Y6PTjT=6#M(#0jMr0%lcVc^aw!scNs9_v=XmgF+K$6T zdj~+js$tNmRvw`fK3To!zG?jUWvWvk9)H#z4U9Lf>V~2a6@F_DRdNzzk5?9h_RdFU zmlb--h-e`9d%vq0HP;J`TZw4IWfhO#J~P!YxBMyJ13o^BCIZQyc8SvEZa*h%N>Crf z{B6Y`E(8yr_7n+>9X|g7FlZ?BE1IUa9Bo?^z2q_3$xc*N`YCgDkOjOs2pR2a1-bv= z@1Ooc_}T}Q1|I*dYifSa5a&K1Ma3Wfk5%>)8nqbn7DeBX2n9iJghwj`nD7;R+y;Pp zC;3b6VLcAId*{nS=pfJGf+&J_pLzK1|lN+$5N=M{)AB)_H&hIP3E%LIIiV2Q2)i(L5&iDx>v3;qI7d3ObJ! znKTENZ_kT?295hk#fHjM(gc>QJSEG7?|`@c1;=nVZy7?@q1#LBcD`gWFMZubwZ{c~ zk)*R$2domIR|puaa&$N;HKP^))0^}0sN7AN>Vhn`wow-?5H1(bVyph2Z!H9A=1`hu z{ZkD08e8$J>ajjBfwT4w->&GOPZW=jr%@)${jA- zYgju$z6`l=F!VBXblPc{SzjQbddWZYNf$zUnov?N2Y>}=2(%DwmCV=dnD~v#!K#Y+ zz(YrP`oXI&g$PI+C6Y!gKL*GcL76iwKmNIBOyp8Cm?B({ zL>mbqC}9h#4@n?vcA91`Ldo4U{kKp_Re6b74YO!tGrKz`{@$!JQxqr3*vFN*?b1O( z00S_?gkHWU4b#cVR&0S#C;iOHK{4{J-;w#T*6O%X2WmkSh2U(;Md1!pm>2v%U~B7D z|7DX-v_98FFm&HV{qA0In2uR&)VAKm{MA57`x=T@Jb6MCsaMA z=YFs=4c6s#d=C)3Et#2#a*~8wTy{-hjkh0w{S@3ka%6>10mON0(V4e_$Ed!GfjB?# zOWAbxGnd06#PBi&1YGc|{&MKPKgu{-G4Oa@{`#&!3~ICCZnTZMP32}^V)(u!jjwr7 zUh(a-WMPpc+)?u#(vE{O)Ll6AK z_A+70u!lY5x&ZCklE5#|XFP9yWRDHO7)n5e*{p~U{yEjT5+#C5Zcxstzm6>67A^x=nNRN*2zU-tp z-{9r|Y1$c@|PUrcJ_OEQDf7=UjNciJY03U4klaZGN3E*~vF#fzY^zn#4MhYn)K0HsPN0jhl!BD7mk$q6F@4s}D@11#6-LZwfJn7G%3pnrV1FoZo=4ww-$ zarC$TAFe@5@)t8NJP5-Wd|ct3aZm$x7#yA^^nv?Y|0TSo-o!$=nBXe3jF!DXeg#_% zS;Ee32%69ABjIXeb?BY1=)ZPpO)lng7u|dwb1@CTp>%KMXCgCh9x93-HQ9>?s;b_z zY_9<%`>p51F3c-#ml;0x`2$seDNOY*bydO9f>wpXli(pq&>&0(=F;(K2f*oDQ6qk@z`*?x6hYU#Nky z!v0pKXj%xm;Va7avRr9DEC+OZ9KJeu*hSI$7f*Z9fn>e{qS@+G~#8_@5rU@`1|2~i`2Rtxk-74?Y zTfPd>Qh0T_D*}?7GaWRdNzvPk%tV1VmKKzsB0!3I_AB_{C(}yN@$nb8V)M{Y2gK6AfiRc8J-Bq&*67p! zIWD_QSN+|Iq#9>+K}Tt%Vyf9^R|(WkI3G1n7z!$@ou4`yViG&VvEFrFJwb?xUHIhc z&5b7MxR%0jnPnD-?G_&$yiWr7Z_01y+DH3F$I6P36-eW5#V{OL(j(;<+5Bv{%c7y1 zH`_bI1ZYpHYgiFDw8Hm9vaY=EnL^OP>iC3r%8#R>u}={O9wn`{_o$L+%q2CRLqP^h z0KoL#Mob+RF*MN2gl!Xlnm%ClFSN)q5)_{(0T-jVKtD3P=IBqWKc>uv#Oar7TOtXd z>FUSjLOvt6g+QTN>7G247BcE`m-JO>h^>L9&6zQox6m!INv`?@LzEwE(tC`kjn0|Fo1$;#X1`sdXiT(%Q%e9!h859By7Rw_y80X9AjTT=H&Oq7PwbP z(8g&>r5Pw4U}Qk!uOtNO9tREmiH4Y>>}$D#=vtgFlz~CC=^w`$8J1by{$v4730rt` z=R_tMyTd;RjEt2azlvHzxk= z{a6?kg>nvf$ay*)AgdN6r_1?znGb>c>XKpcO@^sP$Wf9j94q&+)9SAQ5jeGGJ{5K> zqq=z&BH-hhCO+dgbC2&vWlOGs6Chu^PzM#Vc>&0U*;(Fh_B;SkXF>Tt!@E*F2x5@O zXwpqL<1=$EjGl?zp6D(n(C(RJJ?dL^79Az<+vMto3EBf43kGKptOE?+hksU=t8QCF zpE^u#r{H@k=nMxxd+cL*a*w<{q1OM%-=!~iq#n?*!ac6gOe2>>{F1W{zNUbhbDAe9 z1-Kv3zL6vy7Y^Ai0;s zOdwNI1o?JFHA)Rb#R1xq7HrY0p!TLjvYI%ye&jRj@pCq4K>D)@g%MUc3pVSKir^Uo z-d$?MXL&Hb&e16Yk~>X|&o=gb2<7#Cy82ntlTi>{Wif#|%VR4oedc3Ou`%{6QA}Ll zBl^@uioq@TsDC57P^zFnEiwZnbqX|D{LmEEPbU(iu7sp2H75L4U%)NBv3sBfG)}CK zEs-*?zhkWGV0jBFkAbOomc;_9!-T$3tfq6xd}T2z+hGY2^zc$=j4ch?1TXbf=efts zQ-Eux7)OOoZQf8Ol^wPi+ZSNjN#SN>o_I5=&M};^lN8IT96@Gyx@sJPl|_A60D^rM zo22Wj{Qjk9VG$;)?+zySxJc>`QQ^uliI2|M80 z7>Tvy3qzrTQR{Z<6xU}=P*E|frBm@f#vwUwMrC!jn?kKZGZvR=Y-&8W#7=c6Co~dR zY?ZO+1s!V_2wskVS5hR|HCC-P6eUDtPfS5Z7CnOWJu1J7_LQ%bzE`MEC zUbr&{t>Gh~?Bh5V22)b(DjMl_s1&DmTres?lXzQivl;^3B@TVn3nq&?etO3J}%}l3E`1i^nuLReiK{ zbN`=jBoZ%`O-j3?nOB5RoL8>j_)YnURqe)G=s!8E{_SD-5>1-G?u8O~&VZ`N#p({P z)A^28q-xg7uMc3i9+-g)Rn7Q0g)pi~!8NH<7y6cYa}b-q#frtm`4CleH>xAB7ciEQ zz(`3@Y1!&tE-!H~dU~mjf9}7Ej=l%GAkfM_8D3()m&k(L`_OrOG7B&sJlv5bArd{y&64=&hm5n~RpB+^)&3|jODT~JUBDs1XB+#60KeMxGW z+ezqn_yXsmIpukF)52#1p>(TUX;3E6VX7 zbXo`T0hKTRn5=RQZVT8GLwAaHtNyjy4oMb3=Er#ICcHdPFRh`@u^dXUG|nU4N9k+p zmR)3}b3@5i6jrtvDiiCyk^wr8vu-hG^aMSAuNf|al0Z=0IoFb+pdAF8fwqmZ)(U&Y zBDvoD=AWO|35L%QUj?V&mTgL+sD4=*g^_R1&;Kp`YzF#~8Zj13)(7zxLWfKHWaUnt zib(-Ba2$co$i(squ2=Th?IY}00ScFX1&DtZLZOeMdq~kN46ZE z-j*KW(U%({LYkNaC6eGN^%XmW-;qr|=yqN4aQa}a-5^RH44;f) za&bNw7N58=4*q7eUBf{seQtua!U72l;LD=&>oj+iEP4b0?>97lJaldt#~)!sGjpWL z4vi#-TJfM0@`0$(gv=ZB&Aj{(q@cXxUTFBkUqrW2xdMk2(7#c$GQNs9&q!aezNH+W-Hp^c*j6FvMq6_JbOv z6wtZ!e1tEfFlMgEuos)|f0*9n_MJb(%(ztq661G^oN%g7?SbF5$LiTTO_iBh0FdX( z!0qnwr-OJE*7Xv~VnQbrS#{JAbAm@0gLJKL1RV)2lb%Cs8}n5b;_~=0_FZ1FFB7XF1Xt=SOP^R zm__Y7wSW-A8$;?z3Y4HP*qn~+9%egUB5KgD@8=faFx3n^H*r4zZ-(Ef*ysBrQS_^* zHjLq$j4*ns&5!rXCG4aVyiAH_v+*h3v@0kJrlu*L$CI~}>1wU(WQ|oGi}8{=0DYo7 z8)EC)(Eu+EzRj;_8E$%X?}LE&F))+_xb1!xh_;1cF$;1Iern2z}< zmE0pOP;=nI^-7RsY;L5Cmx#>w)^*7^-du<+VSZ&Gw~?Rff4JZ){pPe8FuLpHXVtfBs`OVCiJKAtfA29f8elh%6q$=68NCT*$Sji#1pFE&{1W* z%uhR|kMorll-JQZIL~u&Ra|oZG3jb9w%5*Tn>7P9hKwEULk=22;Q(lw`U( z_)nIe_ULEgjZ2HYgyL=$eD>_lk$iov;k<7K54b4_ABltyRFfHf6r zd*Hk5EbF_!sh1E|esYX>vtDG%E;~+AjA}c^Ru4o7VOcH(*Yp!OR{(~4%pwGG6L>U$ zbmOT5L7?VayJoM6*?hPex(!jmR826*g>;VT=58bg^vxxZ#^Z(RgR^`E1P=gKv~u@D z)BT^|1PK`ToiLhnS7g-fdh3f2oo2N>H z)I6KvHA|1K!)%cxOWI|VsoabkPKr&tNQ>#J#rog21) zXDQ?i*WS;*v@fBWrz0+Bl%;PY)QLxoG^rV+mRYq-tF+pceoW-QfN2SI?jm4+S3GB+ zn2VycShgA6W{O*4A)wY)oEL|q3vDy&XT=^u{;+~yZW)fX{9;KhNk#BU&-0>0_4>vR~Bp)5f60* zO2@$cvPbTi%n?$^WOG6gzbQs5KLIcanHXOHLRZ`jfyC^?H6{+1ljJW~Ej=vF{{Rz# zkV=eHpi)qdk24wTqE|-^_o-ym=O|p0+g0@=P(M2x?42}BpuHkZ$;k_ z)Tks<`bEr8P8SxOzLmcZURbcZcBa?ivUZ+}$O3aCdiiKX-rC>Q?=Ai$@v_Uf5^t zHRl+;t3>_F(V_SbM8_%b%x?hosT~Bn#-c$_+R%aF&mvv-A2Je?n2IlA#N}WxLzIT$ zzZ;L~4!gI5K(9L}uqpqcA&UMtFxee(89*U!fW`j6Cwr`=bQ}&`q7QgaP#nxJV}@ygo;o zBCrSD+=E;U#hZ5?vN#PTZ57j%6dQgG{5C!NmQgi^Yknzf`+zpGFid846fZpCoMoIg zEVed)q*v2&Jzth>Zi(G(l6|X|*U$R#`%DwKylI_1TpGpE@cU}$n#tQQZOpoP#Kr1C z(8A02iL{gPt-38Gh0G`$C%3WiWXMGdcmbbP;=MsDb#!SaYj$TmLew#POCFsRBR_BE%`@6`#Ald7#9tpHY|$K0o@zuBp8KHoyW(jvO{t-2{&prp+3b?|2uAv90KVPBMAwg=fC?BFEI~@*p)K16 zaPUbOEZ4Gq^;>!TFi${qzz-L`)Md|NsgDJ(oajqg98Qgc6zEk4#FBJbS|nn#ki?0q zrNlj!jhckfZJp7{eb~gofY}(sIuPD(f-G|wv6Qd-$Z75gc3F>(SC(a0BT&{q=C) zFfqD6DCQgtUnWCzS%BA<}xltPJUkhj))^21Ofl7ZNCU01#b+-}&8 z_j}ES`-Z#o1E_<6ClDtidSw(5D)0(mB^nSsoR^{4U-KXHNW+KeD_j!1HdLT`F}T9M z7Q0P#MFK4vbgnLSXQ7~XuQru=EC?wdAdHKyn$lZ#gzdXdcc2_vcGHnUCBe}?aSe2O z^G^ImDIah|2w}pReG2kauJ41WD^L$mA69MTu-4l|laG0xfyL@CN$hn%7#<7gppmY} zE?UyTbR6{NNcpj7L&Av-lvQh{Nr7M?o$S|;l}88vH{rnE>gQc-dYG~Dl@}_%VZz{8 zk)K)W5vK6*n@U<)MG5wnlwu;HI;3_9!u-mI(J{OHmV^E6T{>rmP&@Bzr)`0}z1ppZ>A{@5cnv(V+_ zZYXA85092#0iN8-nNmb!0d z#lLkEC)$q0<3T3F=CNF`Nt%B^MotOVwC+0B189TsUV%%XLez_OQ}?`L4DkHEM=*q8 z);1Oy#{rmf@1X!y`qaX7Mw5!vnQsaYW@%-S=0l49TXBx}!Qu&UySpL+w?_=BNd0_-78iV@)|7BRgI(VUu5byH(Wv8d_z zi>#9DMk!%S;r8o%GJ%NM<}h`A;!C&?!xt%PGAKd0d&+Ned*~c6 z8ZVCN7x)Os7~e9Eq}RZ@;(ovtq|6JWcxwu3FtueHbSQddmi7 zV}?)X1!bQ={sv}ScD3QReCeaNaQ~Z5UbF%6{Lg_7(Jb_bKXRDLp(d^`C1{2$(`a`^ z7e;&NFTtIF^T^8)apwt_)3%njK>q7l52EAwHDTc4QTyfT`|u`EdHlY#P{TSpGz=`q zNbpF&`k>?i4HDL8Z{l#$udq~-lLRpsr|go(tTB-0?MK#J#UwPHBFOk2JvWL zt-ny>Az0yqDYcK4kq1E8=|Mck|5iwq9l^U{L84v@U?C+3+@N_?>3^I4sltBAk3tgp ztC7qQv1~;cwnNBAv0cZ^uQ|j%3|8w>FhO-&<*z-HO zunBp4k=S zJI_225r zQ~fNE1*J!*!XBgbON+&80on>JRjb0&R3Rxxdra`G_OEZ^=4w!c*h$qu`?GYR|j24zjp7Y@;- z&rvm<@3(~<%r3;5vl*OaJgXOjDt^2C`pm3V~gYDw2l=A84$TvvoRUt=4UkjMKrs|H9nRvfa zDDLiBrGT|ipwI?VKL(*HOWHP`?8HwK-Dl3?b(E`A~RLC>8Q>3LX4mfEU6T%AY;go5#?I>+>7#0>_)czB7%~Nuu4T67pe?42Wi+it5(p2!T`-@PS zGCs(0W8nKxIJN6{#8)h1>Yk`(_#<7vovFAI!jjJs$8|K!!}p+(GZwaLC9v#lcV4)k zGmw1Z`SQzeW3tHNq+YJq9odM$kCju5z{Pa_i$*8p?UhE>pWBz!9iG~`8f`wtU#&31 z%=~Ds9dEoMSTI;i)}U~4`r^aCOP8ga5qja`BeBbvg&d90I>wrUIFk8XaDs<$RNm!^(#J!<=wE!K2S$G^5sJJ-1&#QXDu znqE4#J}@e`DNWwvD*aZ>==Dge#4X1eE0&_@7a{%MRr))mT^hFWxBk!zczpeS2+W1g zFvsu8wNm2^ZQFV;E~wbI7NoGhD~fdD zfCH*6APr zRn!|a4*nVQ>HTAL#WEY@;B1h_k+mB(l zW&(ozLYH$lJrxF1qJl&K8S57c18y(%|-PA`Ud15xbaSUIS&iu6eXE+)o^rc^jv zUoC3558OCzenG?mdRr-8qme6X4XbxGu6BO4{SyYm!C^|AC09S17%)``5{&s@WrI)E{=`3i51A1Oh6or9>VG#rpCt%+JA`6 zMjH1(AUz|(>m`RQSzkCMJM1Yf>R_g?1JsYl(nsVD(0UgNPR+`;F8G$!Y{3h${t$ z)v-%G&U)^`2c1p+iphQz&)A>bfHND6lkVCKt?$S{yxx4;Tz1oX=z(xl^H-~48z#WM z_wJbBTpCj=A=oR7Q~bQe-rRq$t2=Ptcu@2y8kDEe>Em!>s_w?_X}x{FXkqRkrB2Dg zSC>jNkccW~(XGD!PD=anu#_Iod-|t-jjpnbJP4C&QW$|gF{)p+>ve&1@n%>nX{h_3 zvkaMCL8?s+TIeStDzNnjlwGgay43K zjLU7kA6jGS85&zBoIQcKEZWxw^M%V7P>cA&rQ`;+g6K#u#C=0&U472YWMPyQMp6lOcRE>|v&4?eQVUvW$vKDW)# zot&Xo96YDlztw_%kgU4Ao?Cz}GpE)s0gd=P@PazwbN6uwh|1~f0d?ng-|Of5QE@Wx zPHiAXchy;)u99VrAXrc>Du`E#k}=4HMS=R{a;Pd)B(Av!Q9yvv9L!+8^CoDL=b95>M(6vx==pt=H{{ zt1sJ$`9E*WwM&gEqSZJeEsb)LOydP${Bxh9w2qq^RGoVA}sL|>tME+ixrt`ouwrZo*dgnmH zp~SfLrY{jooy#Fy0vBUzl~t0-eFX*vx|b0bQU76@m{rEDfxPwE_a_x-09i$`-7RSr zemT|leTX^*3JeHYO;m^DHQyM%E*ywN3IAgX!W@e@VN7dB-AatIL~{CyM#a)~_P1JE zpZCM22*v8vVrhfNZ0r+&9e&Wj%U@hDEyFc_v5Hk*z4o#QnMhE;u|_gu*$e3;?lfG5 zoq~)AKT3TumWH>xUu@qFdLkvpTW3YS3qb8!kdho87@%07nb1uJ#j>FFg}EiQOLrNC z^OG}b|C9v@G+}jI##HmYWKMNHrq(cs-PFbFZMyjzc|6V@Nx4vkMw@cTIWl4o)lNu-Mu)zi(8^btlv>8=JY~sJhKj z^qPHua+dHAY0>^h-Enfl7g-giTo5}7H))IGq{$liaF}UvbKck@ft}D$sfbV&i$m7? zWEtnC>A4$b{rOua+n^rT`ms;#W?LF(oQK`@XLe>9QcO-k4HhC8ZjQy1%HSWZz0qIl ztojGa0?lX8`_w8-LJIK9_8p^eMCf`?$-mOUDJEHMxz2&Tbo4?zuo!fOiWP|1lC0;L#{n?-`ZIUmLv|%#X<3!7W8YT& z_HIJ_wgRYB3fa(Coqucr-veqT{xUTlZ&fXetwPUzhCla@umIQWXc>8ro#}Jflkp&`B&ML>2#Lb z-EPG$h#O^H{Z%X_f3Ezz#bBcufN1hA(Ea&hLF=&_=IZ21*E~H|kw`rP_OxzDs(>S&V}-(aU8NqEYPnMxn2`MA#KfC8J&N>HQ%cK2tFVx(|f$$84yoVZ!m+R z`QC+tJOGFkIfTI^E*VwdxiIUZd7_f4_AG?>giAW_i`|k(X3SByfVZ+x>?_}^Urktv znO3VPFQzv&ej4D(BNLlnxzs8(d7b!oLU^NOPm+gpp@rUewuK6Hxew(eXhPXonqvh_ zRO)?L=zc-Fiz%a2KXeJz_jRe2n3{0>K>{#v^HoiHGZ_`}78w%iG9jyQ00NZ==aOi5 z2Q8RDkh4iLU`N_xcoEOOYzn6J>Tu*84X823zo9L4xmcJlM!Reo3{Q?Tb=m% zqX}&SE~Iz$%hoH@vbhL8XgyQG7YFZvWj|_~W8JLir>erpONnoTZ|ehi!OFzVZ!SyY zeOI5*2W1OLGxE`8%2_K7kD0nt1r)ltiA0Kv6t(im+2&>A1V)qok&(d+Wj+N>TpP#T zNV9Ytj6F^r5R^%MuZR=PZmw(d=`a$Cq(Mk&-_#pN@4r!s{-r=4hX8Hl$PyF296QCuC za)~;q4PmaS-La@G(Ti~cH;Ow`(C&&n&>399hm`w!Kl1noG{x@{ril}bO;#UaOT&8J zPNO8H_1To}0$UMiX+UsT@gMe75F1r^Kbcp!OhaNgY(I6n#T74h0sGJU%T(|b29&0O zZ>=2R1(V*l@0!gC+KO6liVu;8d4Xf959Ct7!2ijwo(O)t6UGk8BKYf^V$L6Gt)xwjt#2$W-jls zCK&m3Y%Z_)>HThM%T0+GzvHmHqI`+a1L;^{3l+it3v(K(XpXz~C z2=+?lgJ<*9ya`bQk0nnh*Wc;qVcfK&;2;RvvDDGaW8VmO$hrhh^39i4KxHtmc9qFi zEU?m14|=Hv7}|Pz9ugqd@h=~0OctrwUB|93)F@I!gK;Er`Jf0$mzV~J-T{#$-F_-P z{>Np}ta_7n!$Jso+3mj~x5AP9B%y?GP@%fW#?r$9wUFSS#!a;djqM0GQ2t_7Pq$4e zwA}?tRREhzZE1t^s`CL`ZOZTQ3rhj!DdpW#IvDPf697H_^K0Mx4i%>Y)s&>{+`(T5 zE6#v}O8FPZ3|OF-f|Cpx{tn(d5I9JIj~r+_T3mYIm??#0R%yioQVZVmzm}Ya7jhv; zp*1Zn&(m}el;ER0CDQ%HNNZ0bNdH(q8>NsbCr_xstq8u1wyzn7JM?@2k9l_A`~+DK zIrm9XJFPI!S2@?b3p;p%t^1Nf%xvB)LSG;~2`!%$lbRu!EMSspoBbEN#u2K%O8Q&I zD`X$wxpLAwbwfv7y{21X9C-gXQg=c2Yt$S5`^DFB1v(t79xNr#7G==Z-)#)U61lVN zu?eG~dyM_Z094XaL@Ggw3A-;se7(Z(mBg6*y0V_NEd14ar?;8zSz0RPg7WO&hOWzt zP6R9R6d>xmL@MO5uVb3565ebEy27{|1G-X||4f9uR9ZQ=cV&UCXun+vwFV*c*Se;j zbM>msf@P%PrB;zpgaef52ah&%^pjZIgwUS*S+cp03IoO|vZ=&ZvJzCUH=$3J-z;pc zZ8&vFg*HGtX}5L|-HkCh9D1))wN(hIPE};+nb^;>i?FJ8sQMD1MS0=8W44h&QsQ$} zLye{ij#E<2w9`0ipP~~rqWfF(4wAzM4=@~^ZZkV`g}5ysk}SJSy$0y|Il>mI8d~3% z^b6ND{_vG?XtvRW?Fs~vDRhbo2m{+LTes}-mJc&edJ-@0`q9QlOCWUg@4;-b* z!hu2jMl!haiUM=cS6q;xe|#R(f`J+e3IyGk+PtQbY*hJ8w8jzq_#{MSOSUsafNMn; zOV|gHyZXSSyCcH(8xp0>>_^8Iq3z6J7TWSRmPbff3;nbK+Sg-Us6zOGK@^f(spKzn zae7aQ?Y znvuZ9TKPXt>gUB4y0v(*1Dwt;tkYd3Z_|{RKD3$(z z@#N$Iemk)7^JkZkV&*OD=6J+M=|@88!`$cA6#G>Cs}pr={n;nWQO;X+<7_kE<+I%H zWa>Wg9xWbiri9>dY+c@iquuc)bMaK55JH<_*xiZ|6u_jb!g5G?t88VIzo_o{&nT>& z+x+sC>d+F(_s^CmB#{kH&&|-mGpW~EDgVK4HQ&_wQRZ;vm9F;*y_glky3VF;2>1&R z3`xPk^Yifdk57!TnFVm$7I>tX2~U4E9r1HB#KB z6$6-1fp|Px&;lro-Rx9EkRR8~GHQ9P*?U zHG!ze;bUYHQD#_@t^Ya2P z@ycYu|FNNdd6Cku)Ax1%^-OLX@ToGqENG#q-u$2sA*B->%l}mWJ>sV0bs|@>&{>}n zapKth*>eXBGf7i*A2JzOv|FO%0foQpWNj0th1BUV(RNb)S83x_koj`psiKbCqvH_j2l>40UhTRlCU z96-UeSJbC(!#$g;6VkTekmhnmC16czZg0Gfd39WMJ}T z__X8Sx2E-%1CUEz1E9DTT5}rKPS<2ei=>ZK)n&*B`RE~3*)2S&;4#-&;w z1|gPDs*!Ix^z8Zoi&r%~45tg*S`n*&f`I=T4F8Whs8rdXLkE+5o$0>R2A9&8~%-y&*H@!om2 z$??ry&Sp2pi*IIad3kGi$Pe)QYClN{$Ts@E0oM;DABe9(AbV#7Zvyf>L$ge?(|`V= zKv7g8N0_uc!u+zmVlm~qZ~{oy?NC<4dAW;Z3caeJA@1Fi#V^avCCM%7d3llsU5}ue zV$5^{RjeaX53~S<{yk%|0G7)wkUj@p%Z6sW%~zeuo(gjpG>ho}pc$(yqJca0OZuE> zw;74g-|uZp8aY&L+iXw#KN}Q*agH|~rEUKsFa(|!p9462uUt0Pm`%#R9IeZWVT8W0 z3_6c5uvVa0%5$gc!)=SDVf`?UAGXTv6`wpJK0{4pwtkGdf<+AD;@TUjGIlP>lhzzoDo~()tEHd%Q#6%=5ROCPC!iD z{sIZ~pb-yq&hL!6)I zC8KIGp*JRV!C2&f*{f!z%W>1H*(6yN(PpnhPm+k^1H)gTq9hAZKy#Rhcapj9KF)Yn zKP#t_zTCR|2NRe4#28pG8i&fv`laW+EBuvT*;!8bc~$juk&RcP0xI(F9^(Gv{e)4j zi=x>oTQ#9OO=5;15_3=Iv0CNd&7bLJlgt$sZKzl*p8#)4OCaB0$;%$(ahqVuf~L8Y zMgs47reh-s+*AS}U1W={{Cgl!qNBlXDL+ukrrY#^{InZFQ5wk|j3$Y-N?*|muY63l zx8N~eP6U!GewO6+2--e$Aiug+AMRjD*LCQVom;&0hFI#N`a8Z zm{zy*Fd-fwJ=Mi}Kxb2cI>O8BBQ*W=zqbe$Hi&5j%!EG5TaMJr8o-Wkq;30qb(=Auj=Z z;@_6B_=^%T#wEIOFqul27SDyp?XI>0nBf6Z-6gH-9zetIWfTf$ZtW?cLkXpD+@xz3U)FL4n- zF##h&#oVZf79Wt1UjSGmD`uck)3hj-{q3(3lBr>#x*BenE`fk-IIDbLYh|_wkCtWQ z>(x?eE&5@399f{iFKglh>M7`aY{GK&`#8f=x#$6bWjdeNQ6e=d2kje>xXnm#h9(+c zW=*h$Mop+F8^;lYo`sWDccJ9LJ_@5XeVE-AtC=Q$w-PasNRr3H3#R zk-TfXCg@8DSuWG*lVq1ix{|dj9dwsnonGFgqpx!930DU`3G;rbzzD5d@7jqEaPm98 z#2A``&B++Qk#8=5h~9G9N1RLZ0foGwI1i|*w|qSfr0PY|+6ofsaDQF;Jd=BXnVVL0 zPd@2d*%Ds z##1P0^h6NEhWCk_#DA17Xw`HijFu!g1*zIZ65QP$Fr$PF+O;NFZ~2a+(co-4%Mrhk z$oY+;NEg=rIo%?BR?|sui@jmHMo<8U5B?8I^P2hED z%GRPj+x-3UbdGy(OW1T|=l+a@Cz!#_wkL8LlzLL3!=TuQS^#yyOhnT2x=`LoWxGJm z28k-s zEdD3Oh;vcJOXB8y*FU%DWq&6_!BF1VcU%|%cqC7^jaYgX>3)Y|W#{jWn1`C-Iz^!K z3$QEzU5w-|yVUjT>~r32gTQ6trftf168&iN%R|=2m7mrv{~qqoNuDE%s;r7%SOkAq zvF^RVceaD&oTGSwiq+RS1VGDL`r!UAo6Uo;+-g+- z2aUY-lEsjG0RF!vL76RJ`+=&y_NjbEre@qe16(~n64&uJS*|r0xPkC>{eJb!y&=VO zo?^h{@vug4UENm9dp5Sq6!{Q4kHmXpsowOFn!^a!cA@eu)LFGo52}vW!RcSOV#F3S zHbrTQsM`tlvvd=5B8&;)obZ(br~T0oTJNe_(NI}A1{Ife%im+>1H$W-@HC9Peh-Niv0eYPP*uDRp4{Ga=62Y6JnmF4(nF z{^GQHJ9Ma*#sZ+6`Ym?HH&qy)$+Hx~epvD=GU?CnhVLnmlJb_H!YqZ!!X0riT65eZ zO_~q#RYC{&=Dl{J)6Yoc78v)%gc6hJ6VgJz4&E)lmmB@dnFhf|z0o?h8{UnGYB;+E zBz`e}P^;6@WB78l+|D7b_Uoe8_BN-zH7JJ@=WvUKp+~lQnjkxbi51sY7e0pIHyRi` zdg-1lbvBZ9$HnP_*^t`o!+q(J3Wmp?s=#GyU??Ep=x?ZKXBm$(w@~%+&px0)LcX?5 zr$;MZu)_vnl;dXKA(06;%@Q=pu2Jq26P;%7J&r( zHnI9>h5qwZy++?pcea0psGr=?G)D{r2|`}~vHlINaC07TMa_os)=pz) zdutP_pmX1gu>Ih>^xRqu?JLM^HBSh1GS~urC&4o=O2yYW&jHHz^7h0P(;DXKbp%R+ zUID}W8-xuy_r)@)nEH7Jl96FOeDBw{hsHQ2MmQ@>?SEcZVGbjb9_y*w*sFS(*epZ9 zGg^M2^flS`H{`j^H01kUjZz!juP${rpS1%-(`n$PWf%L&Un=2tzLbdVD2E!r6DBxM z@)Ywzyzdc1mQ9F?8+DDC@RCIx2?Frr`YA!k@XyDVr7m=L$d9tpuZPWR))K9LJFr+Q zFQ)E0j&p}L`MPczi3v;H08LNUYjR5ELzndgE>-+WnLy-k5ND)=Ogth(lqZD;7=sF|su2%)9QqGW0 zShm;m_VN7N6#Q>%l{vckJ;LvY)fGaClNg>HS+`W8`Q0IdU%-)*e27w56t#4!v@u}8 zHkVQ)wEqL}TYf$DzlzP~;6q|9EdbOMA+)Pjnw$l9%sQ>iBh zlEK?5F9H;&)4u67d&5xlX-e6Y}LNZIH2ZydnrmjtsDA_o$h?w?@ym% zsNYWiQdp27#!`1&$k}o1^LAmQrA)O8n%eXY(9^_x+3UID6LZ~g^Y~X`{1u!s0*Vrj zOa__~7Fs5WJqR6WUa1RHAi#)2iKvK3pebXr(~;32AOs=&q32h#Wh!c zzA&&CddMkNbo;-)v>w`yHW6E6W4_76+p^iiunc}QLS%MamI_Z~fQC=iO8i;y@m-Mi z@XHAK`R4dHXL}Y$zb3`&KFc55=Jixen|Lc>NdF>ic0r7+n2ri|0<*wsal}Nr$#+!5 zHqQAGXo-G|Fs~vA=PQ1_mq}y~ex~p=cNM5X{I%VhD}$*Hk-csi#ESDSDMS4Iwp#zH zB`cb0>zQ(%J}3cIQHLC&OO(JSp&QfxU* z#O0}KXUEA*t1Wl`V`JzF&@t=?t&XkT#O-uwqUbE-vcY&lfGV>9F2zyjo%OkwfGk$j z#UHGnd(j5E6;rB|W2v$|Z+dp;+ABJR3&1~@68QP(*F&J($OhDX2x$Q{;_iw=4*~~} z;!py&G(+Kk**}$@p;ejG+PKX*n#Vv`>yA5*O4sN8HKpm)I(CgB*lN$*QF#xT8D8B` z7McHcem+QmFVmbSgk?52Pv`8c$q0h9hmC@0eg6s27(uZG9wj~mKa98y+MJ2i3*`Jy)8YN7?=BcB zNl>AsPFQG0*>+KJeccEmv=GyUk zif*Pl2yoEG4rg%)M@^-H#iQ}zCOXo=nL!PuVVjX9=uK`kRjYdBb5!Z8kR9uJheMUr z$QLf8Wl1x2^WqpH@R%`2FCRgOWs`Vs1d`^J*U%^*I8c>?1|CI1?+jr;XmKZO>uwYZ zJjz^X0V*4mqMDBV54h0+4%7Blez2qwyjMVnMyr)D4(Wiov!aoJN~k9`h=T1$;^60! zyB0_VQ~XUV7>DrNOKd?CS>t}}lMf9z_^3p?bZ-HNm2z?>qz-1DtP@*XTRapj-=nwI zqj&zPn*C{yC6`%Qu^+ylmW&SHnot9%^d7ajxRe5hiS8&SJX01m_%A%RlM_O+D%5?> zaLlwx^^O}QO9c$993z}KO-k$U?FGGHm zf;~9~bK?keEqfgu@H`CTny=5RnOi5%DqI1rQCmmxPo#cB9w>0_9iZCZj+ZrRCcx8D zew~aFKh|1;sA6@PB8(wgL7JDjW>nHEc=5(ry#d0oGc@xp1*y5K4Gn#69<$@BW3z3D z4gLtkUD*Mlv50=m8#LC7md={AZ%=}ro(vL4s;G#MAM&=&KBTrr{Le7%x&r#LA#NP= zh*5waBo2x!snx6OawnarNPBCOgrj)Bd8y12KAsEBR2N`qTreuMvr$lAJ7WEQ&XfK3 zX9LHrlt&y#GqRvO2xv1HxHhgd6VyRCdK{zwMX5*06@>=)q zKHu9(Wm}xCmy#jKbw*I}*Z1Qr$Wcj#uU23^x!>|l2d5774l(txjo4`-?0)FDZbWV* znrPoKCjoMe0rhe2vVY7wF7USYxfP-KdA;R4qRCbyUUaY%$R7W|vIq7ekyj7VKf21g&P3Uc|Z~e%k`P{ zX2=6naGBz#q`(wq6$O!Dnt`$@&R`y)M`aN>ndh>#-SDHgPIHpy3Q3{~9G(-|ti2m1 z1(=ehEq_oH5|wRv5?v(0Xxbl&et7u#aaiVMaXeO~Khp`fiBuEZ>~bgK-3s5zLTC%R z9w-xV_&(hhy{?Dw&ki1eoWo$X)v?dQXaTIa)(ve-7GloxT#;{Pnr5{cAG$(~`_P&H zenp24;mcvp-K0#i{qd5YO%pH zz^hYX7BeRv{V`ZyBv!)#A%v<~d@?$rD`6b?L(HA;_1JoHMDcmI4plKFCxBp5EG6c2 zR!%O$=aQAC<4T{|bwug`&;mgk(?<+-FKVX}05i;wXGgYe&FZ$2Axp*N-}zqVW-Rq~ zFX5U!sx+}S$PhnPeI{W^5)ZiR^71t&>xt^FWI&s%7b1*Y4oh(Q+ns4G63 zUZ5O0S35QaA;tc^W7_Psf4zQ_^j=T;=*Sk{{Ydln2=AP5>-d;Y_SHy z`EB%FIi2TooV2JpWX_NJhsq>RURHT&#wsMZ6W6Mfn zjNwgEWM*b0=JVYK#crelng;~7@z4i$<{SQXbr9~pj8~WI+vEAo4Ja27)Te576K=q# zl`nR?HO@#%0hzeOWNKnw!OwTQmXBjZgYP!OrwzL~is7dAgqFk?qhNIXA92sv^!QVrm z#>31h43;UWP?3=}6C)8}B;2x2(vi@Ni^qffb7Mm$*$0Kp7Dp5XbzHFUdy3R(`imC{ zmpP~tY0J%Ong|x`t(;^x?Rv!POs8}~G;h-%t8Oia!`58r1&m^1$0?TW%GUw9?3qQ1 z?P?{&gg1qt3g5DS9)LUpw;ku{10i74i_vGVT_EjNJM)P3vBe{acE2|j#(SKITNa6-*6 z*&nubtFSoN%O;3BF!$=MlxKbLND?c+3NcQ2?DZ@?ZzAamj%LcoTmT9%!^-aaz3p|;S7sZB}00xhC7}_F!(@7aY(>P6+uXxnDAY_9@=AV=% z0=(8Iq0nmO;lYJNpb)jjkysn+*)zCy5%s}#V8Iq1zlPyNtmmFl+omI z25p7n1Q#p&QM66;>^BXrC-0VAmr0&c7Pv^S%v`pUl;(_B!fMTBv2bZMWt#j7)VyY( ztycO$pzB8AUdWyj=D8ddNwGyn10#^-beC5du`lrWXCkS&@@WS}tG-`G{MBW$%xH{g zHW6vmN_T+x{g?fkfvQls1cWJiykNWfziiqK&fo>wwZsmOh)X z%4U189UPsEd&eukj_>GcZUnx^_8#!Vb7dUH#o8T5cA%0FBP)zV4Wm>c4^~;2INx3W z-@anV%?+$-aZR#P_b*W9BV_wFn3}IS*fRGh&{DVxkz!?Ez*_5mKwz=V8;ox7J<|!z zc%3iTcI?a2&BIWdM8&gQ?t;dhnWhP|pF>DoX7VLN;`A}SRzhQg!Y~uW>oR@)lyUT^ z@i4yrvkDTf=~iS*1%EFFsel@{OfQy@1+V>SxL=XyN_p>UX{W11K9har`@qT?fIkr zRocxBV#W+a9qi-Er5h?9KA&YE^kgpoi$vF^55WK10&riCs5(x087=kWObdg(c7M}S zFLS1M^ljBhBuMKc+s8Cu<)qeIf45&|ZM-V0-*Xt5jCHwlXR~ z4>RS#b2ku(+AHgHatt{$M$km~GZ8>bq`Aq)0(KLBTiejKBmHw=4!;4FlcP4eg#-ji zeco?^Q6MkdN};T!DXq_VQ3x+P8^S=FPsqlZ4;f_oa_y=>QbSc{jXa(}c{x)-+}{=u zdt->7M^dLjU;=uz|Nr6s5cleCihl_>OiCCWP__Kt)~vP!T>d>>n&R`EMzF#+e%mc@ z=|`oQXq=u+z!kxXa0}%UMw7+X_e8C5{-&6q20hHoA)2Hpf#+A6btKe7L|5T`mkmqI zYqcAd?2QYj0`qwjucb&Xm#ox?5{<<2y8mrVSy)(M4Rr;I@cpePI`Kgb1U%Fi0;bpf z*o!@oVHouNom-!r0voDC1o%Cya#%}d#I{CRj~ppLZ@+w;Nsb1;Qyhv zH<5gCu`}%4SQFkO9absb5eYMt-ahXaT7EY&YQHt901fn7ln}1IiCOw9Ae0%zk<+En_(Jms3dF;#yaF%_VrN%DVCHp_1$FkE3iwC`??VzLMrMR8f5NeiHvt+6dLgd4Y-}(>Q)@6G7 z_l2;UI{!BPu6CnqfUCd_?o=zgQ=e?lNy%s2ouPn^Qi>~7eF-vO<+;gDgzPI>EFlL# zGWEvzvfH=^m#!RYIaNp6;=Jkgu+q_hs(25egHR0Np~U{KazV#g^KduaE!bjh%qSbY z{A|ARt!W%=JYR*VZwT0~#a+SrM%N6yn<31R|x3R>5dQAbmlOi%Aq2~bVowMtZJ4lHJVN}}*EHellOW;QuD`T7;af64 z|1^VVHotApWBef1hBw5VW65_2zpHX!Yy#$SBK$6j$zKu}8Y6gXJSF}*N6;+m|8V6* zeP1R!UFz|>HX*KXSq(z`+H+4oeD0cPAUqviahDp#Kr%?BZ;V)KNdaltc*IYA^>d5e z%enj1AVGzLq;KJvN~v2{Rd7ky!@%o+L`GIBWIzWUa_T3n>m=-tuybqc>x$yGw&ajZ zS?5)9B+2BW!d|@xF?@FODmraxwN8uUJfL5 z%`;WO3R8y*Ms{C>9$fJbc*sgcu7=j-sWH8f^*Otgum!WZSlFKh?S4wa)LXb^e6b>bbwyb?v=B zn>@F)l;}%%__XM?X?P$_DdGmr1`&b0>Egyb`4k#W(<>}F;vH$oiS>h0!g^?WOea5j zJ^a_lty5A82*ro`4{W{JGvej5s>L%qj!)3m#nR>Gr&lPsgFyAto6V=RK%io$Mtm@``n`tR z|7P4`F^&FK2YKKyBbxY2uEW1}HlSv5u zfc<2%oaXtfZ@GO_opf!LxgK7(qpgOdiZXlzz#aV4QR@BrPvx<8(+QzH#1+vG)`y|< zfZ6S=sEB`UMj0^5$N|k)OYk5-CJc$QyleIfV6aP& z6O0PE=^`ow2$VyQ6y85Wrq0*=?r2s4nT+4gk8U%*ekS3nB4so7%Rl44eeqr%1NeLb zgAFrWFZrzh)}9lImnD?tvCZ1X(nBK5l)}|PVARN7SmZQqH{oCYQ9*H<%*M5Fl99hk z@W6I&Yg~Dq_FJ|Uy63P<{8=5qVGI$CA)cLwq$2Xr%kECc{an;dqb5&GV%??!r(n#> zZ!u4~2@#;z7z;JAuqBv<71V450*mC6`&C1{N1(pvmb*{EyK$GhWv!q3D(jy;s1?ir zKkzp8=4Opn=>v!OmZKA7h-F~kda8fCKM1IT;}F&P^sY2RG5gR-#O`I`SXFo}=?6#j zR7R;*aF-U@TzJm_d^=7B=!y-n`z~pwF?x*NU51o4bU_KGVmGI7W@>3T84dzcShN(> zFP+(%AYJd1Rl6N-y+F*wWwbE&wPFu)0eCqhN%{;sK@753x_+AP(O(LZH%Q}*Xhvm= zhM{`hA%2I+NE~MV4FhmF3nTaz{XsPe@H5KC>TdTl4;XP4u>^GQeCCKZNq|uT!4Sz= zzmbbH+;uD?dn*&#f8390qljzJay~^PX=e$(7%x^^Ut5@IKL*8?+H9?%ZMI4YHZixz z93E&Com;tK6fDL$Wmjzly)>;S9@c#x9_y9K8Gu0>_hjF+(p~P%Wo5-`3F!N-%^@Yf_UDU%gct&z7vOk-Ea5#eLC+pKOTkKfq|SO=B@{I zQPBo^#f~U)Xvo1>@NG8TVsX!0eUdx5mgEA1O3(l21+SMzv|?aZ?#ljk-x(597OzGE zAjWA{*-0^G4k`nn6+V!fEs)DibzE$EK*s)o6=OS@42XOuAm`CPSf%^~iKGWp!d>>z zLCsyA|1MY@_lpp0l{u%1_&4ayQ&B4P_I{vT+f?&zmvT1=w1bw1tT~iY$TLv{qnPY> zke79e{s2}pW-BGu3{M{Bh?HL zcvT5u7LX#*Zg10hFBv+{@}+lhYdx4kBhZOK6WDMoZD&$#YsFxkZ(3j=4`~jm>2f?Z z^K+57lmD8IYoHYgYlf8{k~EAap)UFo>+r|0u)F^K@!?*3#c2qm7g^)#GZ^f1zqks{ zj%g)F_rNfoiEibjyc9*1eq)ENz~_p%CU&%JTozvt0xxCfw&f=jSuEN$FjuX*WFwI) zrZg=9jrZ%&6rOOEFKq;txpK64`x#Tk;be`0{o61UqJ3_wJnah3nPJZZ*h~AWR$r*d z+7J}y6){Em6poqdqUIpvbK0Zrph}{lx>Ac|h5p?akJ=V-WgtFAPMk>74WtI=8o}TS z>BGxFiNz6RG=z{T%$Fd*)kbEwB8%;0yEAZC%;Hm%Zdd*U_E?1d)bXcI2ggiZUr=|}^(kSb(98sy|W>6Jg>7!M1QuGc) z-(brX+l5PmyYF*gyBVNGbXd7^6wYWUGCo>{)`wJ8Dn~= zf(-&$G62dDBn*!x%oc2$)0!$UkPW7md2gDFr)3V{KogLkqG$9tw5x3)titUk?i{5m zFK>I`O~xg&;5?BQ_Yb+pVUA^Wo4rn<3Mvf#n?S)!?_dz9f)P*>;dUdJz&n9|;sDDw z6)hh1KqPmHqC%Kj)ij7Qf)J1-66fJ}u1SBW;c-t3Xc}w6<5@51zHlSSiBFd97&n)B z!}_H+FZIsf=Bn_47VblJ6^jb~~M_&>-_e z;Fc;jJ}9qiFj|`R3;we5uM0LXTWI4)tXXn--M&wP?#Ay{GVMnx6Q9}`xWUJp)>-_} zkMzB6o!9IhDy?|K;Hd#&e55A{(0>>BYn#%T=rBHBmwLALco($7Rx1`jR!WsuQ>gz{ zWgo#&!J*0i63#U^b1$p&f3Sw+2u{xybY7S`rlpXzKv5(=pi-jIjdrlyZJ0_l zt1jIp@vz(kmcIh4*A8+~uBvkT0U+y(8?;boS(H?qryIKyS_N`b9_0#qhF8)%4BN?x zLdBy#`g6b)88->tP&bwbv3@JuZv)*n2DvZibLOKC0R6WJh1P_GRuxE6u9FCfmgNOC z+1fSYs^D>VAJXXQ&I0m5Z zVS8~b-lNfP{*7}V`(km60{}zJ-ep!M*!K#6O8ey17^a8LvQjl0bh1x$9Y?{9neX zFFNjEOw5{11OkDJX1Y%G3tlpipQUk~Q;;JS$77g<8#FWy&B$oK`r-jJ&7R#zF&;+8 z;s2rkcRwquR>b7okEY;#$S4)m+*wsZX>M9cvmh+xtCdPZdOo;9#)kptR1Hhkp_6@XEt7QYK}m} zJOw>}x{_ni?9PQoB7L`O0k!OaPYOt+!;iPoRJpgg=P*AHQ45T2QyE4yPLrdQ|Md7w zqk(PCt`LCWX#4H(HM;#0 zVU2ch@G^~s#{=C&%1z|-({eZY<*ftIgc?@bMVIinq80y zzgTlxlp2%Ogmv|(``7Q6U0vpZ-k#MRbyUh$yO>(-qnVrEUE3#s43GOg+~~(!nxlSE z)=&2h03=K-3XK9O47$cE@;p}Bfr3!+d02p5Lu`_F68gi%67?%#X|+E5e6|;x z=!?9NB1Y4pt$l4PLJxVb+de__%z8=#Fo~<=z(g$DIw@}a0hgL@*QJ?A)HX|LtC)>G zJbV1ir)l0rgina<{d*4$bokxsy4#T28o5AgQ22q5L44nLgBL-@6TY(fjS`Ak$3Py2 zqY@y;-`P$rOE({VQt19Kw`IwoIJgdYU(b~aLKSQU_v5`c#*IcmV}=#H!M>L+1L-bL(i{f{ z9LcPN>CZcklr4?~Z->3Nba~Jb?dB*%b0QEO+}+2oVeB!lMS6`3tbW)u>Q57M4=D!r zGar)I!q@V)w8f$&z*B`o!cVcstXosW#h_3CsXc5L`vY-Kk7Vj_E!T0m$E_nJU8z5a zEPwFo7j?L_yzscCMp-S3=b$vz>ChyG_S^$xgkVQFocCsNiixrMa2yc}TA`A;q~|1T z=c2ri>ALOqTdEsW^)sPpjhhFHTXn~Wh}3YBWR$s->;eS(m^nrz?(m~)r!}%l82TmR zlbR703eIc9Be^(VS+l{IM0xM0O`ZWn<7hna-Ad_%|MXN8^4eC3vwm4!lD%+SEPojd zH`=)U_oUuLzLei#(jojTO8vEp)l=~SSX~64v|T1ft4&8FM-Ks?>>hjD^Co@icl!_& z|JkHbq2t<50Lia0!Fe*Kp2EnQ*~XfpH&fLVQY5Q;n$BdUT)4eYUd1chHqDwG>FGVr z*ivqdRDxj-gRO=+DKG`Wd&FvFAIql{#MGw@p)&yCIHKKb4Oeg)lZRYUz63_yhAhgX zue+ul7c z&L0Izknvt%)AaVQ(G03-*L=6v2xCc%*QkxJUbk#0rzpbYv!Z&Ao5R7aGD-gyJ|`xH z<6<|C1blA>npWsLH(3UUu3k2-PTOx_%=RvFSEjG@{a)G~IvW?U_IOB7U)BFI1YYP) zIQ%?oFvA<*oN6vR$17S9v>kJ;k6mk5o)qrds#D8(Kd&o#-`dPnk^nFTqUwx~ZP^~x z%n4;c1+x2qlyd*{GSva1VVUkbM5g3NISI89&m$?2=C&~hjHaTx73M|2+GgPyT!;Ln z@jLPaUO6ltc$}lSUCEeeo3LoG);N>S24FSSIlzT&>^+g-)2D6jTeecLmrriUx8t|M z7!dgg0yk2AsP<6DjzBSXu_G3BEb(ZD$tlH)$PxyL6e&ZCTJ^&vcnIF52OpVurs_Av zP{y=11|C7;d3w)4<>A%U_Eq8DM6(1=d}VoqlL3(v7e@ye@F491QO#|2&6H3D*^r|s z?YL{AN%}$i7Xmp<3N#>=`S6R*T6qD2T(-2E!Cf8Dd-P_?+>9l{`qCR;T|Y@b+vlO{uW@p9ZZ|gEj&KKd*;gp+a_sdUeS-FiEo(0ee#L zVJj-S$#Aia*E3WD+qc87XTcKa1j{9MbrewjU#_gz+>njzwe=D4Uao64cEORATpF+Q zpI6N&p_D>eqA1ES3|;OK^!E#MvdEfuN-uz(pb%h915w!XSDolL9Vr(fj<-f}GGn?q z3%%b*8C;)LXW~qf!wdYLlS>k@{ffy4x<37aP^oYj$PtW8^$^%{*|JB58ox^wo0o56 z9ehkd+*s{&xC0lp(;`a=gh~e)hZ5zeKT+ycIG{n#dp73K4*h$-81-;h`QB;Nz-Rfj zpZlbH71k$9#`?S z4AA>kiYd_iW>%&#KN#-NRxXqWNK&#~%RRnq1MOS-g)nRxO}@IAIINlGw2y4p!1?s} zW`9~ip#tq@OfzGMW^X7S|0v6m*#mtZ&3`QDk&l)m2YGS3a91L7rR*O_%<# za9iCUm(FYO*)4)_}$p1t?xUm`Xz3LjbkD64UG4Bn2qGoxhG2KT2?C zYgUG`zTIt{*c+QF*m?jkSWmk(75}n$7K{X|Pke6-zO!#kWF2<-UWDt_Ewi%UT-*Hg zKQ&(=B^8X#;sj3_-2jFXdVTG(q}JOgqfHH=tuiW{!A%r9w8{ z!{9zEkdAo!{YzTJRAl^D3;gjjdT@;+_XWokQA=u=_?vpuv8~e(5l1WvRDuAObl)X6 z-V1yJS?MK6HE&b@uFXWm!xb?nEI{bE|8$;9U2y{_og2|2+5b>+g z+lsxh24xeN)9BbqZ-C~Ci?pOu`3gi=y$$|q^nb5|T=y{CNsqP=ZqG5hb9BD_O%|$I zUsJB6?Q=1jaM@CrLFCxI?cwGBP}vr1^4~8Mz!m@R7s`Y9zU04v!vrSn1m&Q62OyO# zq;-A$kh(-6M4}P&O~joi@PEKzIEmKv^~-@R`Jic*E7`MAdG}mAi1RX8P`Z} zpZr#vY7;)|o~bw4caC6d)rkzl8Ohlq zYSgi+d#BcquII$0J<(iUm)mP-vJ#oo0|gy5St=rW8nTSBB=m7OT2BO%;)l*8-sc$N>Rz4-y`Uyuo$af^q(jl^}({?nK;2F zc?&EU#`^zm8VqWM3$#KiYK5{Hy>LhiG&gl)qh8K(=I1ciR9xf2Mvy#XY9rXR+d9YT zQXncRG0dPO!rwHWcS+yD$3;2&SB^zkzRyC%QEG6?s4ph3J*R9Yd1s8SbJqrhCt>c$ zTBMiWsLh5T>C4}PZzDNGd+B{hBqG7jzcTLxT_d!bc>v~PoE)Ya87@pc$QEa^W_pMm~xcW*IuRDs% z3_89)n1u}Bvea^e^2OGGA{!yS#{I7MizwWEE@%_9`8{9?^nh8j%x+-SU=9^N|NlcWyK*Drx9%q|x-;(~ikKUf;SXA_Xk>jy3;H3^bF$q{|Dr-jQp*l%b^AFJjQ|ed zF`F}nR2pMfjUm_UzIMAzfYr z#8}{-SDlQNj&{G+h)yv><}}MEYcC&r=hcD1Lk(QeGG@JhBz{iWNxvM z5tb0XRY4jh0Rknfzhsn|%5~y^;x{>PPy%LvHnL4Tx#w>QC7Ed0+%meOM?#vi=0)-e ze>aV%qYLv6kJ}uh6zh&Pb`c{hc=Uk+8?;Wm9~n?+m@MEQrq0e8RGfSO{P|Q`-06#L z~BJ@HP~Z;#EIS(2`0=9prxuQzc^F@L)J*s?q}y945^TS2!O%BLeaD|Tf7jMk_l zaUK}aP+o>e4Xujx$iG!#Mcs}fFwQHvu)UG^%rBc^0FW7EVfT2{bcllWLDz|M+uO#! zDQH;D<2ejjhm#G~3pv@weUwW*m;$sewgjidE@^Yll(b2^+@m5Q%Md5%t|t!ObK7jl z>kHRj=9SPRVdT{>eoUm3jh(6TbzX7tE%BTiT+|^-Nr3@X5jTfp#1bc^Bupq@na5fjoEdARZ1&2*NzDDxPa) zW(rsvfsG0@3(lzY;BSI%;UK$)*u%wMNy4A)OK;nlIoIEi6mK`U;9d<)x;mEH&&mov zTo=^cB%Ou44mtjwM*jr6GY(&9&ag{_sO+4NoGidG4%Iwj43|MTtL#iHjNBM^w|=j1 z&J@phXAbxEx$=8^c>3!HbX$7sOwa&H$+JuRcYn`DM)$GKr_`+6&yLAYAd+#R$>$A4 z%_7whUX}YSv2mK+WU>w@aX%KvQHH;YZhn3c+!AgoPa(QS+5ZL_(mcNyZ3ESDu6%zR zR9}!_RHj5ko?RL#tss{4l8rloOw9<*<+QlXeEL&|zwy{<8@SCeUG8|eJ?5O|=Z(U~ z;R{cm<3Aq^g;fVAWu>kV3D~7-UlHUb+h;U^8_e`DMsquG0Sq!@@rFAOdRJ+*+Kq4c zU&z!NyDaV-hN4L!RgpcpM0}%y%-FvWLY#In1`# zY}MwNUCn=>DxpDA?FS)_c0RN}EEXg26)19jzAjbnU~A47Ir`ZDdAw|wBg>K<_2|-N zo55gxxbn5|>iq;MZ8TBvWlHq>@*7<=j=^Hl)Dhios8>!koc;s^o~HiC;)}s5v4~UF7C%ja2IJsbfN_ULse!S*Z@#6}Rqd!Q=DcgR=X<7mmPOe_oeCf# z@c#Cw(oA*DNd&wMOPw}@4dhJumL!&zN%%npaiV@gybH5;Z_Bb%U$qpPN*WdXqY=|& zha`h3wX-Kwp5h`;56OMEB|r^PD1vK6-aipin2*Y=j$?6FEbVjU*f7ktl;#QhuX5n{J>$f|;=a^w7 zkjH*P!M}Q{o1S-zm6EKS+ZA@BW<4|!LY6&u!yVD=>Pal16oPi7VF}-jMWwXq6`HFP z15IZ!PmJ37zX&k(!L>~{S+dT!V$$1*&#|J?DOkE-8+_G&Yu2zP6kjKk@N3`ubs%To zK3=VD`Ivhmo5LIt(o!8fy1cy6xv2n8q|No}eVZhF-%tC`;}`E`IRC6^Cm5oJ%XJa$ z0x9*En(oq%=OMmoQqS#VgR6VLwXSl(-H5vJIDfs&Pe3JSi{QYtSK~X*YpdA!`Lx>R zg4Srb5}lPBOOW}#(u%S{4~X5T`2E1_xU9S4zV>?cbNraQzBlPZJHa2Qz~oXH*?DRDpl*k3%#Tl9@D4gB~DX=s*Gm$FT9zfTG-Hbf>bp=2#` zy{ySrX?H*F+>s!4AoUT#ZN%t)zGdHTGWarPm>RhZC0;<@X2S{YHF=37L!ff(I){t4 z6&#XuE%44s(Hz-3LxqZaZVR}hrQ3!}HprZZHGS5d7KjBl+d;Pn<5h)ZhZ)z$=?1DP z<>3)y0_29fJ~z>o9_(sz3k^|`<6=4Ugk&&#Vhs-MW*5GXn@`sTh;&qN_~=1!7UJ-_ z8br|m`rW_;X!5BL}Ztfy>j4Jxh9{=$A>1)N~swSP3OZ6cOb8m0?zYUfo?w}}1 zk?&z%EtqAmuPNjU7`aBg8ue2UV&(Ur2aJp;qA0vY6j?N+AR}UQ_#!V%6wU;KFfks40U$8u zErg6JIR4@(+zes;ilCIHMm6SvhGypAby0)7-odF@b2#6n0dsLoov~XQX0UE;=GrF5 z?8w8(*@-y&r*s;JLs6T_(xJFum`0yX4jdjGNZ{1K^s)i{4C9rLUQ?A*g-|Cc8Vv8n z9dV-hzsWPX=!16TnHtQhxfbcVQbfkOfGuP*2ng(NL*vc#sBMJ%;&vK`sA!q+N8 zyvb{Q>NDQWmJE}hJ!*{ju`3S?3WDm{uBr;65y)Do2`hb&csSQeSrwddP#knJ1*&iH zQEz}mRi4&#u^K9wFty=*#+g6GxDJlGHSaEjWC^t__K1J_?Tlh6z+HsC!4wd(qTh zjIh^UMA^AuZBCVx$IWbRow9&TEezDKC18!ZK0AOC}uU$B$2b zp^v$FbL3yKg41W&*Zs8i97kDOB!umDzP`mHNe+O0`j^mD)!rVe=}*Axw{Vu-bY5pO zDfpDl;=5DVxmg@BDaP&VEHwN1(@)cal~$aR%a`^`AK>WK;fex3EVtPl5gUiRKc5B2 zz;yLIzgL3Vgi{aC@8@z;TbbnNEF`FyYWv0gV!yFcDAdBAH>e4+JCZbkPuh?4!S$-q zU8O=3scl_{y}F601w)k8?k5&w3@`mPIX&m4;jA{1;@gdgB3QA@Is<;X?x_7Wt>0*; znS+-b{4E&i>9-4Dq+74q6SceFBNIZABI^GKvTsF?X+0XGGYCxA} zLcYXbgIT@0g(4r;KC`!_R$=fI;m_Ui&(?(^xO*Q?4=N^!YuuTDS5ko(CkMn|o>~+>QV^zbf zzQ+c(z`+d&C!nnUX){>*oXqa2Ilt@bXJb9T4LrQNu2C~GI~4OEr(V2eKNONNe5fyL zKbQ_8t@y*KfUxm(s%o+6l$|f0mnt1?~eoY zO!(R2Wag!RfxJu$1TLA9Q0wc26x6F-XM|Sd?y_ESDL~up{7l!vGl>Ti5NzW%kpP!5 zK*_Sb+W?N=neIsmeX znmnsp>v5$t!-(54GN|X@k>EhzYKK|ZdxdPk5ktxO!ryAsv%0a@$$L6nDZQj#9t_0C zbS+b)ER9pj&yP_}hNNZt_E$o3YJY3yOw&^U=A^g#ymyx5f@0JbC**w%tI76|_V0U% zxxD7!xP198Lu%NXvNOrBe0j>H$BVeBI09vx!e!`|-u2z(lL;8fXoG+CXpxcPBMvIK zwgj1NHF$PdVym2bM+5kawKjc=jap+RheAxl$Ua#4=_@=duCdSOTd5l#`t%w{vOknL zRTpA??_JHbd&&?_$-Q^80vXJg^9Py-Z^TD$pGR;13m24+$G@nskKXMM-Y*y4jhc@Y z=WBS&{gaqu@=HQMDyo@W@eBILp`!!W9}QTpUi?#62FQfAaG$&6 zzPw}@Tuqh=Jv^lU0+Ekp*erq(_X7Qy-mZ#+p93t5t6#rlA4+sS@48X2Yh}hTBgSE} zkOPDq9&WSZ6b3L}+i10y<=)yMlkevj+}5;8eXb;!9qya0$Mi23uF!oXK1d%q@8|-> z3VB`|XE4pY8ME3;TOjk!uxV~6Yo5(^`wpkrRnykpBHBK&YrM2;a$rkyH##zI4C#N4 zKQG$`c;J|g*$8YuaBZN7o1+vGBhMMUd)BkhwhuW;OT$GOT|J#+iP-g{^O88z%G4;pzFPJFte^k^sMImS z61d)+)qkd^4zLm#254^CxsX&ix&lMj>M~ZfpAn@OyTn~Oz^kJfHws8aa>fC_v#Xg~tj;hDJo@BP*S?pwh7eOws# zac&_@=$xAGg!%wzJGgNGuS73+h>Bxfuf zh8tK|ZEeLwxezE)Turyt&)W7}DPBT>ji&a(E4%q#g-X7lkf+FNzZ*QX6yc8+2K-T$ znmF1~2&pR)73ek%`w(+)Bay|G8t;elLl3G(m{T{n+ajr6ORLa_}Y`n6nn7@ zKbIg`7c%&_9aP4MT~y+3H}ue+GehBH6_@e=n`5%T#T9XH*EPF^5cy;{2it2rhWIj6 z-uL@cKyMOnpO*G>W_K-2)!OGE!lIo5db-Pn_v67swQz!e&?s*XuG+6CvxZ$Y>Bee` zOZ#C(`S`w!9dIYg)pm9EK9!}uU9qSuNC<8H)-vV(g`8=ty7&Gv#dyb>|3XuR6|!1q zy-CNCR({p#k$p76HV(890tMfJzCIdF$x|Zi4|;M}VdJvqquA6W(EFTT!a?BT;3Zn- zD?-6s9^(;~)-CIYnYb!Rj)$f>Uh_W=`H&nH5|>+%l?Y(AsgTgEOh$Lj^TWf_4x4-~ zf<(<~@a2ApTM5J}9=>fEG8XGDKv$cnlG%-n6J^NIimAC3OzQvky7+`1E)u{Zq6~kU zHMsf*P+%t0J2!LRP~lFo?}cieHrLK#AG~wVg&|rRmfBmF-n9Qd&2?mKhB96IBRC3c zN}@m=5!&tcvUake1pGjK!T5YRGqgd!0TIPAp~d6&mY!kgxkj+N3^Tx_nsPRKd_x|T zvE!7=_5U#0uGO}QSPT-0PcXOi!elN8xCp9b1pEUmAj6+-PJDfEbWMeTEH_{&<@})n z@Y){HGHhE9j9SgAv@;7(Ur1J^*5nd@@bW z6I|-W5j;NUD(%I6`(OXf{LRc36Th{}Nz{%PIDbpNFj@+_lgNE+ok1o1}wBcftT08ba~Na=k&GYtjWXU zFI&uwGdofwywA3fY{)y+6Y6L{zh8#7Cnh$W3ux%(p`!BC0vEjpT?(uAfK?w3GNi#X zp?qXe8Z%iSK&#+W(@TuEO*fx>>F{nQ#0=;F%D_c9`-O;pIgXU3A`LmK-<;z2t-HCS z_>XbWJOu=N3{Ruorvv?M;ro@J2k?|HbHM{WiCRM6vBin^m=OZwppU_xkp$tV#=-z% zW5{`>;8;@Fokhi_x6Q-wPS;cCt4>d)p?=9B?|&jX1|T$1j7{<{S=Z5t9UbXK&~!b2 zV{R5WB}h?8e_;29y7pueei>0}I{6$PDF#|3ip$=nZ$15>97m`d$GRS>8u<}7Q53nI zoTNZV}*}Y`!Rt1Yj2kIClcawx21GK+L+_l(_e5;Lj&Cc`4i4wcRT1FW{_sP;2YUWk3 zac5iz1yv*r`v+5RRCVvhSpF)f(e#(J!z7~z2Pc)Jq6JTs_K!Vum9fZMe+g7RTXbu` zkZrlX;$8xPR|aK$G!dtq)@tL9S*xgacn*Hl$BI=%lGwW00MP*pZSU^-gN=@p zlL$Y?#?Q1&mumEuME0`f$2%XH_(7o`wKo0RbvVFLs^y57=PlGQ5$VnWGWEl6o0_~D znf&fXXybUE-;V3j=Wp>*Fh8Nn-4+<)3c!>OxzBTxm%^ZwQY1zr$SN9~bv$pAD(wWI zGQ)1vD;rypp_Cj&AY?1m9}d5!DG-P!J8_xCN;4*{=>)cbN65;&Ln`>q#Wwlo&CrTf zgyEU@3t&zcx$#A_x*SRYU3M_dPfy)vG}Gu;86rerHuv5h_ufPIq?iJ?JC@I=Iw`0j zzvte@!7Xr93_rmKqWB+|d+pde6jPYtvMo#|t*rwldG&)mD$Swvx$Wv(q}|(l5wNAu z+L5f?tkc4d<{U62U*`Rn%>sYp)w;e;8xpPG@c^6JIsYME+=1 zcXn_hwLVv!Pn==)-Db6D8|;dXcb5N@v*PQv=-t+1lMb9%B4xvbA!ZidEW>O7Lq2KOdluSB?5f)$ z{ZC-Zyhh@U!vlkcSl1ebWh0h}0)upBm`mvWhU}Z95XC&P5+9jJe1HtC*1D+U7VtS8 zE*o@NMwP0PvJV&~r@OJDToHrAc<8f~uAWvay@hu|65aO`xS-gp;KW%6k^#@t7!7b2 zNBOG-5f2KU1&C&i>6ZWRpw>X-zHFR%KXwK1_Q9>Jy##;{|HEPw8c-k7UcoUAXgffF zqGmg&v5)V~>e%HX}xC4 zZiI$04nbw>`COIt`$vt%Bx-j{FPiX2&-a36(eo zP~V3B+*zYwJ>t`&H|#-(F#2mrOT|)Ub6HqL+w{Uj2zLkKVJGtoJ~;0ULVVR=ec~7^Uha&wVi}xHt5I%IKLQ6^(2NxSfDLvsp^FQ?=+8eQIVE9}Z^>f<}G^4l^ z3nEtogXFdVLW;#rECRsX+Pk3Bq&O4RXnUc1xXcOAO8CNl-bBCuBK?CZZMgX9{tDzk z>mh?T%rjSS%$rRm`$Y%xId!)HP1LZFEus@HxQa>Av6xpKP)zJ&zw*Zwk`=08DEjB5 zaujub)wM^G#tP8_0X938x9woqDV*9!uI4QRo+xn^lF@7Y3CM~pP4pFTl7mSGp7En${i{e*2)!dQaFOv_4%s+&AWT0>1IA!(C1(=95{1ZC${ zj6A-y{M&f_!<^DzZIN-zs0O!*J146?0Ap7B+wpXSunLP^U8Yk@%i~ZbB~p1(uvrzQ zksa-jLgQthmeDPtgDsn0V*q8g37MO&?J!CMC!v;(2cAGzG#NUd2Oi*Ke&i>A zOIiM-5fr2yg6RxJC^ijXW&S;GV0Xnnu`TAk_u$j<9 zD;uD#uqE#8u(A(Z2b z`pM)k78}}nZz$VFn^cx3u+bpCw%s=yO| zmavpn45=QMf|T%a(49TP^1MJ6__l*v!2Poi-r;h!b( z!EypvW{^|BEKYl+BkF3Q*7#yNvR4{BeRraSNQZAN&l%U)9-uaQJD^}x zUN##x*0~VqJc8@yYP<~i=p5Kuby%l=MHv(ls~HC71Z=&!5h7p50pg@D2AND%ZIdv^ zk{J_Q=G9Lv%3v1u3+9AFMuhVlz!-@addQ6cG(u==+9Jc1sy6l4KtIQz-B=+gbH)>I(G zRKs^`ZSho^J2WP@=Ev1w%j_vekpj;yKi_ zlFI|tg-GAssA%qP#}F;<9Q^7NX?qMV-k(sZgjc`a+PMR+I@RL;RD0WRZARwBxESc) z6kT3Vf>9A#irLtQKi)Jq@7A_bSBYY%g+E`s8C83YpY3PJXUol1_a^QWj5=rtsP9>S zPXLfKs65tR71tdv6K)HmDRBv4*QQR?<<6N{tdZ<-ZqVswQMDXh008w>$NcnD(*ho> z9tVnZ3r-?dq+tP;GzirVk zd-?iazyCQAD=G0=BX-NoCg)}~&2nGMR=(qM8qFxj#d6&wnh!%at_k8Tn6YLP8&B(pmOL442>jj{7sU#nU~bCl<(Hk@jfW6}63WpVo9@zW)q-`FnR_0qu`C19>?5 z4S$R`@%3ItHD$jRB%}T;TfO|}b7J)EI7m3=|5{W2OGEMaL)9#3JV-AX*zPrP$r*+? zWqii)y;6jM7iySCNJFaht<0UVBnP ze!zfGW8f#J!;$hDLKZ)s+rv!)!x`GWjiJ50R)L`>5tI1+*s z=QnWgI%Cx*Ze!IC!*AU6*;qqa)AZ?F5=e%~dikvSyz}z_*wI~$Z(joDTbFdJm)d=N zL4zMx&;?r?{-!ndBps6o4VN?w0)^y&(d7fDD+4`*d5%_|lXp>$V=UgWng5cg5m^L<_{N5>kE|k*d7{!@RUj={lFmq{iqN^Grb0iQJ#W9Zs@y_Z!_pF&s zC*{|HS7Nnnhn&-I;j50;mp% z7h-%Mo|RY;Gj6HEtdQ+Lb~6HkZQL%cqrn>TsQOyw4O=rboK26d)f+gh6f_|EK~}kqz9Q}=0TXE#O%Z>E8n->@uP(@4tO;!FG;L^msdn`$ zbLn$+NTC~v@p1C3%lapUhCHw$P~&Bk7%>~n>1l=r_2Y99CQ&sfbO+-ca&Yi~NIWxw z`#ut~FARrvAV-9H8!nuDKt6W=2^UZyP*X*pL|y!H_*IU8OJ2$kU7U@0ME>9Bd)vem zx31p4vJ81H6mklt5|b%F3MT`wS(TKiWB*|SJO3|WC`%ZE=YHCogsHP;&!OEeyD$WK z&EC&TJ*M_Ttc^_17>}@B-<#nY4ynmUbGrkb1Zi(i`24{SxD$jH?zd2E4wKvNzHimN zYW$`3Pg(sCtb&L%KtmtnRpTa8<>r!3@;gv@3K!NJx1wlJmdC7RmI2e_0nNn055(TjcG;F9{i;m-;Hdd zP~9LPgce-_maTkEZ|M{y@-9J^i{GC7NDLLhHj1&IFv5(7mQCEW^-p-~y*D5PtZLD~ z=h~Rdd@)Ze5s7SxD)v?a9%SozQoIoIuq=h^6gTt-Sf9$N6cSJrL9}Ap(dbpJ=2pem z)+dORy6Z4zipcwbQnoV;+$r)|<#e6TQw4~KbWl2y~CjW&$_ z7#_-MmFwdisn3u2)&Qj!$7kIg_d835K^(ui`n_CFudF%r;djfJ$qA-{LUfa>X|Dw+NiKmJAH1*W6;p%~aM0~&FP@O|Of<4=0! z=YOMHvY%Cv1cLlwK!A?Hffddgh!k&{04!a_*c{*aHr52}0@d&^&hnIm4Z z)rM(koQ58ouwwO0TEw>D=9ocq-GsPZM%OYCC&8$?9jRGsK4Q;+8Ku7Yj zvZ(_aI}qFundF<>B%9shiHN^9I;2=2AC6-ZPs4k>j~QBztSN>na&m7-t4$yVNR;$L#F{fZ$>nmU%T~BTOu(q{$ z7Ygj-)>DGbJZi47ckfp$Ddv^yJ`N+WfUU}?-g(}Yi?5bmC5IR)l#H)Vb9pN(@B)wL z02L58;9&Y{E&Ptf%~WSu*C?{y$?yzbMhV1d#(p7BPw^D?_g=)Cb8r+OPLQv*(GVrY z8)ONvH3(ND{x`&z1CYA)3@&0TOM@({^w4*==E3<-JC*j!HnY3++5CsZ^}Mt1gaN)Y z=KW!KLb(Fa!`~E#5HVfNNf}s-oVRs|K&_p!d*k%S(v(yf1^M)Z63c>CjI_L*d~H3T zUzFy*LwOZ&C}(BpJ8=4d+x}C3y3zrnTx-5->NFU3YLcprJStix>n~RZ4&t0m=F;3} z-{BWNUvhJgAN+D*5%NVG4Ong%(ldhY=3DYc)@?FBu9)DvK$Z zl(ooY?t|%b$T>(eC=x~k;QU#`Y$r*~cr(XkCBa6u-_2c(Y;=l%3Mp2D7Lbrd{+a#$ z`mel(rs4OjW?jl(J~J+k-lWYCKr&{;PzA-s*+%mF5I>X}?`x#&6WAzgjvk9dOF~-# ze_gn+DQvjZ=r&m!x!Cfww%)B(c$xPN1b{+>Wv{B}a50A*U1-3n)X(5}yWpM5^~Dwx zsG|~NYAtf8^}j2`8gaKlAg(v50~!H7P81pGPs&TcLE(fNtEAF9SqK>Ufhiq7bDVCT z*w>Et8Q@h+nFiemV?O(^jT3sZ9v!0qEy^)T(w^T*k1Z~y1_^j+f7;PE3Bg26_>>}v z$z84Qqm+@_AbANWTcHLH1@R}mVtER>jOisk=-@itgE6Lb;r!;ZU?w3sw2B{@SV2ov zyoGyoq6Ng1kfAN#E6&zoz^&QPsBhx&!bEQ$nB1}yLMz5#CK*4SM~pt1dzCs3I^j88 zkIU`*1xlA*6=^4fa?p6+K27Y-J=GmaAmV0wE|O9eoHjXY)1Jf|kT*MipDA5qC(Ah5 z`dTBh48ZLmIS>$ZBP%>8x3+(sUu1UFf1;TdpQhcM|E93POZS!Nb+nu-KEPrzZxX9|VY zhT0q!0{-vP99#}1Z4o~#puh#HYvUCPvy3gRU1h%_OSQckTDzCHUCGKJw>iB z{4z*iB_UuOK=w&UPJjTaoEk?@r7FEv8xD8hsCiQdu7C>381G#SuJ{(O@p{gv9`jJA{qxc{H>YPciVEgB)^|Q$M}?J`rVUL z>9?&8%VM%@tLWb;1(~y7w4^3Xo+{zmvK)nE7-~dWSa>WFu!skdgk_O7vNOJ&ue+XM z_rnUQDC@cng9BgecR+vM#VWJo=Ub!8VA6JNoD|THd~f)z#JBZ;j-NHP=pL3tk0fU_ zD#;roEP@qT!oH*@K7)#ybLc^YX4EQIYLI{o|IibP#VMpJA`60te9N?U`gsU}9uozG zHL6&F?3SY`BBq=NWF>8^<%M=mI6kP0l@4=wAtKRIc0y;vn!DVC29!q}HF_9HBAw!| zONOHgAo5Wc@U_mtR;RmNDx%9hEo}}bM0eTsN5~Nr&RH>kw5_4xxFgni^rg~Y*5NR+-E*spImYYq z5xPwqk%cbrb66pVw4BD8m2x%%sqBpsxwx1Ng+9ZXPgE`mFJk7lLDYzBXQ@gzdKtp! zh3Zpx;%4gOs&<>vy?i8)I*M?|>M8(9h0EF#tX(qDbv_!Qpf~!K4mcmAZB^kzWJfQd zPy4ElCjvj7-HkMb9$R-6diMsbXfihXXYZF#rJ85uIBEIK7=HaopAo$VzIHmV2a?F& zZIfL0Y((Sq09y$S87k}0ZILUFj=5ICzNm?`ah2^4yD%~OJ~8f1z#P5dH-m&GkJ7hL zgn+CfWUfOovQ$EgUTe?y>$o3qUOCnPWf?!t%>z}x#lu{$e$eNke z%GCiG%2`Hlb^2b;j~pK`bw=RN+@q-v#-Ihi|Y2JzW{V$K?Rsa2c}ax=1~LsCnl?I zrNSA})){899#)iTOvC1-?)Ot1lglwaZW)0~yxLm>#4`v_&cu%T}wMKyMT6ESUe zRV~;k;}G{T9a#2gVSc$Lo=aj)4b`hcZ;~?Ze(Y7c)$L?yV~n;j4~->uJY{f_5CAlV#d^<3bTJwC;y2 z>8Y=pz){(NxwNd0(r6j{Mts@-qi1tcA=~CkB|tLFDvyB@1p%geMy@fCsi?GI24SKx z%0mDRnnETWS~Ev!_&3kx=xFzcs+SWXg7|o|FT#d|%FE6tgYmeW!@fKlf&0Nn{?P}c zn+WXTB=5HR{L^q-kZhIwNtWc(yV~<PlY-*=3lIHP!1a zQ_Z-%C63J25ZCEMq*pBSbP|<>O-(e{Ae9bBY?COoy zdyQoL58816c>Ry_d9AxwVd7wU8o<@2j%@)%$uG;Bjh(ksY5{vO<#J@};q?Hi6LC`W zdF8JS&&zB=3jGrsB4FhhNKjt7kmXo*>W`)-k5$d{H1L;JPL|+SK<8+9&0vT;B>D8x zSb33=zb#HJD`)>?4p6n=P;0*Q(fVTQwk(r`Zly$DKuOFC**@t8)`DK?R>m)ZvGWy= z>n^)$g`^)Sl?}x?X>i$VfJ8=n@GR$re)8Tiq3%>kCFqjn(qiDiaD9$QkJV<;>T~ms z;$0OsRB|H6&~E`Rw@;CW_4)u^(a|&b^tl1BjoBK;o%4l(e>LKNq8UfgEr!q2WuiIF zs4-%wI{!vT6nO7LjgyhDR3Gy%j8Y2*lkv)lj@hbI9=d?A0Z zqBMLDIMl@#a8j)DYUqti`DOViD` zA$I>ssTMw?zn*ytc-*>V?r=x4CxPndM7n%R_GJ$wtaSvgvMVx`2=Hm6j(**5yc@+a zj6f)yQ5Sj#;!V1!Y)B`LhcXDoi(cK=F?t-3v;r*$Dd-FL0LwVzy(Yuti9*w4@-%Rv}3!dglR$; z6`ZavR? z&K2IjF}SRV;OZ#+bPeL(Z+c#EGscb}X{ypf5=~-HpwSQ~QhelcSShKv*6za#D6CnV z?x*hBP?%q)yJex)4P zw$F2hKoUI(l_mZm^qQ<7uRT3#dHx)v?d#w>o%=nDoeJE_^+= zERUL;E^B`4erV)N4SYYlPuAR*Tk*Z*8wBn&jI%3ri*>bTJf9Dagmz<3Pb9C+sCS=> zrAkjP_K2xX<4ms`qe*#YScrarQwh3jlB=Aq-1jeSdij8z;|M?yF3_u7RI3 zT4P^Q;_&XnkOHmBL3B(M94Z>BUi>T$OlC{;Asc8`Mv1-(Jw@X4qKSZTTcgzjE!(@m zh7|Z4ZLb;ROCN!$UL@4g;ScfdRF&pv!uj_hwYAeKD)<*ka>LQ1r8hJ3AZ3AKZ&z){ zF-!PoGyBy=7UyS?#5S+OGg06&2)`V8xJ=-riPOa2X8YZcqIZ72OYZ16jro1t7N?M_ z^WBV;xh%&zFu>2ZL8ssUP&D>%IKgH$gf!Mw1mhn0blB$&3kN#bNYQXs>37M2O?5}P z#az2I!rz$PtYqxNJ9neWbtv?X2bq~1)3X0-l?}X(N!6XP(ZAYlJ$E*TvbGBon$iF5 z+Pd;chlQ7k{2pDd+iP^QFAho)16RHHqg+XCYHFCyVI8dk%c7hskh4{-RC$a!Y4}X@RP!GXAv|@h<;_RN^I9!p1Izrqi ztj4%-ZG?6(y@m8M4*guoi)|}CPclI@z!z+s8afOsoOw#z89$ z?xyz_^)&}9Ok=NW3}Hm}I+qWI2`@(nJ>I5+eQssz#%9w>B{Y`^JscGc2^_`@f_C^~ zA+6Jb1{P;BP*Q!kOeP(ySU^2{ZZPD!*}hb2_0RkPDEOIWoaqJZzX9y&dU7eBR8 zv<9L_S{Q3B<|cC%<^B&}2#8%3E|R_gQM_LN`vu#M$8~nnDLGbc$ZWn%UmC?1bK&)n zc731*;_He(u?4g9+#J~cD67n8Gg~A{)T$Vf^H6SBS*d|_;2JYS_)0X@XpWs_Z1}Ma zWhGu%3U1NOR)uLPCcrS4+gcOk6g9VqIhqi%`_lTc#cJ_5oj`AWCpwQEn8{GnLz-M_ z50r(Gq;_o7vG|Li_>cvcg8s~-QHsIY{pGVCZ`&(xb3!~~EFl2WDkt5bY$D?A0V&K3 zKd@cw4KhQZeBr}O-YtU3r7`L>O9--kDCTfNs{8SFC7}kf^S9F5Sb;3jk+R}yQ$TCB zx^)?_oqILRDTTm!?MBTRD9hh*E0my235{XoswmsspnM@yy3|YfQpW@gvzyAJt{$tW zITM%#Ec@KfYHm5OOeV)bnGkKO<1e@2y8@UJU*X*FtWm*#QH6l8I24v|rZ_P*zLu^<@c44*CNkG=YFd|sZ2jBk1ygm8txjTHp4qJT2U)RZo;8BHiPt@nYF!u( z3hx9_{G(9o^k~tUY;izoyC6|!FX6@JBv9oT=xbgMQpfvLM!-dNCa4dk!CYb>Ow2%( z?DsOoT^7i@g*9WL1)1OpzYmcxNDVu}Lb?U~s4~>bAwQL*lVwc?o7Bjt2C<7U;S*}_ z{Skw8j%y(Lo*D-s@DdH7f7}!!(wEiVq_c9No~IMdDi&EuH?;_@F-L`>+Q#yAt&?*< zTo@wVyE_hLzSUo>TkGD(@%-K(UafA= zz1s!rN<8%ogxS!+b__Ur$4L^82`8_Rd2mE5*$YccC+5xD2Wkh|X`1FSFea`Vczh!g z)dIGf+`Rk=^{Y1SV6J_hjmOCVg*L^Zvk}Fb3%0+x6KJtlo_TiFZ}tF>+{6s5Op14a zx>2rBIr$8%Ig03#FFRZ{zVKmnL^j?7$4toG3QQj*qQm#Sz2<2;CCR;TFewJlBiIZYA?-4@j=4Q()NZQ@1~}{v2nuHOIf~lcEu0zN|h_#@}I&! z6s4DT*!Mf1x5CZiB_r7Sduw^i_^hYF*uD!$NJJ(UD+yhlzsZO>v~Kp6)GcW()fQ8 zqyTdlD1=eORUi!o*f9SKxJ!6nT?o%zBeW~&13c1{P$3~0G9A`W`=f!#=m<_6?>A}J z>wvh@P&lVkoB?Q4JjzL6VzHd*-@VM2o?<&kQNgTOim}PO!K8yDt2Q8fkNt)~#dhzG z8~MJ2dRE&^cRk9;CHvFh?f~j{Mg5dWtd85@7ta|<+Yv`EaZXH9fZOMjm~+^W2q`+y zp$)I!6rnzlat&t$)mA`Z0%wH1P*7G@Qg8d?@uW|5<2QxCQubY&0J6+Tykc;^IlAz5 zRIr(wX@a<(m+=?t8WWq`>n&eL-k@|kQxAHY__7jsf0+;vd9k`V3}>>6oLS*0o%(0c zDJ$*kKV3YeGg)RNdy{Wg`S>G;S!o3HKnhVj>DRP6H6umB1mJbCp2`&vjU7~hC1j~l zL#Ggz64(g^pTQhx-&WWm++C~~oPYL5Xt6CErZVAPnum}TAb{ac0S1hyF6tL|dv>gN z_}0YHV0V174%O96J;m8#`<@X)3+>p`p(5i0N(+4U zjo|WM=p{7}nasFS@J-lINSQ76X;v5yG_w$?)WrL8(z@`r#Oen+btKfUk!tXA~jL|}%<#FR>`t5}oHBv1!Ahiv{1q0*3^Q&xt|e9P>N!N4SnCax<1^s*8&L zON&kYR$_K4If|;B&Y&-!&9zd5TXO+aT3zJa#AhhNf%o6P3Q@8kc8mfi0U+fiZE3J! zJvhp4Q?nIt|10c7Kh0Cz#FTj%wJ zf9spC&n7(Vd%WiMTi%s0n%(Zh?$Aou18`7{5|W_Ru-nZqwE^I?t74=)PunIKJp+ze zALTFIGLLm>8a|XMGYGESPx&HZaZq%WMo`u6D9WJQt4s^9ZmF$^j}|;363bTGamdM8x@NC6RWU+1^NU091dUn;C$I5hW0$Xf0AYrK=xF7Y{WjWx0sqg=D=NBTM@r0ryUBsn?yqpaT&sy)ZHrD1jLR0VjG+zui{cVAbRP}G)tu7|axK?SM$ z9#@qaNJX5m)n0STn6e@nCx3Trt%kViy3palyvGKAW!@cmgzd5ubkl3uNmQ>H0=P)MSBKsHPU~e*QM@7ovGobhbrJ?v}vjZlrR^SzNb+LPA`t? zeT_E15w;;$$`$H3V7!M7@OGUXr8`*Eg>8p@8N@-2tXDfv;y}Xvvk@1zGvu;toPr*C zshsuV&ea(b_}UDJ9JjKnF9Vu)l~D3lsE`={@<*;(<`ww8?cLLIO$P5B$8c*hKXGri zyqMq>B#$!@{KUz!{yvO+z7QpM{LU44bocT!-gcj{9w{)T-Wvy38rQ4JB%oRGU)^aAD9uUgFKnI zQvj!ThVd`v)s;pS+>FXD<+cs<^7`zrvVH-3U@>(1_$*u<{k5hw2Kivc&o2idf+J?_mhJJm4etDV zL5#3Rg89o2%988-eToN40m|+Kgmphx$r6BLLJGBf2OZ-3?@LptD>$lts4G>*VHx^` ziVL!tgifP^YB$P6R6?enkM+B$>wXLVkGT>$9e8%J%ePxp18gIDq^QZej)PPa#CQrx zjH-PpHp(38;F0Mz&4tAs_D;*7QCu}d_*ll&IAihTGOj5y8P6D!>3BTk;rs;f-jXcr z5Ia+Vai{NTX$?H<3< z`)!OLU)5%7=9D-&%*PqeoYn3OZT`#}e&oD`T&q4&>iXX#&4oiIB-EJM!GT+VSYeEV zSzO7Mmi2V@qRCtpc~tHBY6clk4iQvFgl|S%u6X8Je^=)RZ%E6+s6rfHx)R8;+w_KZh#v*PY?@VknojvNi!;^dOn={Rl`gBn~Rk zRWA5-wh@WQjh^_1{53M5nn@8JnS-@6cW{FKt#GFvZW6N|uI+3}HRRh&H{z2eM>gRF zF}9P-hKD@;kMGr7V?RkXXBRC}76#zrm%6)@81^MtCE_PZ_L+|%^P!G1>}QJ0b~5LN zUFsLRuEKUuzlx^eshnrKo(5sQ02Vqp!TK0Th^RXL6|o#;zyZzIV1*S9%%*RT-POU` z4l{D;PqS$@!Th2t6>xgK7YKr58=h$nyz9Gek+TCQON?SnV0= zhK5N9f_7Ad7$btKX66y|fBbn!aN!mk#JImWTySM#SS@laN#gUpbp83{e(kYOZ(Q|0 zDqwj6u4R}l{p|9q0c)X3L8x~?U+UgxNy@vj?&9+(uxjh9lWS`?suK4I@9#1%^2Ybh z$Eqcf8-xAj^=J_2TI43VP|KhVBZTM(Jv&JI=Du3%H^wtJ@yjv7a61b^}vt0V%@Ao0DW;^KE037Jg?s29AJAeVb zA_`$3cz`nk#Z&0o?63CO*I3P<2PfqfG8%hv!VN|KV%R{njFKeZDR`E+F=lJZ! z>mhsKp+Gb{hdM#wk*Xybw0siYJ-n)3od4m+eUhQ)4uL+xhY1)Fywt_5#;XV{1QrWb zOpeHo)?I-#N+TEHpoks+V)a7VBY=;&jk|TqHDPEqBg$5@GS}s*O6zJ^MiHpVmCzl; z%M5UAEhaWBIe_n_DoPqpO%-Y3<+5|>@R8at!IBTZ-$LN(VzA&Sb<;paS$K=#=M zU=~e#QQY>ER9&#{HNx*T*B@N_l=M@!nbhPhv&?~@>;H^861ajb9b4G|Mvn0G(AMn_<;tM$Aw4NMgP{zQpdhW=~>{L z^Z|HqZ7r-CCl|GRi!GgQ*=Z)J87$yE?Ne^@Z474lp>_p8*xATRi6;7x5EQGryWEnX zBJp^j367L&cYY23VX{_e$*e&&-cNB2Fuf zRqEv=7)|Z`-QqQYT(A?`CyD7)hu+#+KL(^U^*Zg@%(oE;p34r{t=nAuSNElq#I09@ zcY^w+Odh-T*Bh`KxCJ}zJ zizx%_os*IKQm+451S#FIPvP>&4jt3kM#Us}>gXX%lD!MS9cK{J$~Y0zmC!#H z8uV=lUeUkhv6f;1@F=STGm4%(_0aYq2ntI<8^cn;C1iOGOgH}JnurDVNieKeEp1^S ziYwjMlzs&-5nQ{${XOqtei%gLmY8_jb$7432QY|`m4@~kHTzp+9;81x#}_k{)48Xa zM4b&)s@t0DBp)hocfw~Cu+5u3Iu}4;a^ayk1+r`ojd*ADSwMJ@Tq#&Hl)bRYRQUeS z{nMJ!Me{P!*c6cASg1Y*SXrHt%CR908$Tfcf`L_4MXLo-xnBD~1Y=HXRo;oU=_Q3a zwPM=_?RoUqu%fb0R*_C|9nWvq{3&vNFTHc!P?%}F%XUWe?Cz?mV_bMrAYcw#i^bNWp1WK?;xq#8G?+cVdjsUWN016WO~ zTPG=zM8Q78q-f1fZ=j2TE9w>24312RU9=qZworOH z?k&BR<=%HQb@cp^2Ai&@!9EPATT1z!4ae>m+$g`)IJxRTf7Xth6x6Y5=B}1(yd0mv zH&ek3lO%CeB0p!y$nof~i6%gUnjL+m7)XED18Gatd(Skn1DFAZCjaA${?8f=@I?cN z{b`UMT(q*%gZE}KKlcdKw(UfMGarB#wvHX zFklr1N9f-UjwRefO8B2(Gb~ZuO?@6REhWK77)~mocUC<7X!8@Ph&NF0nh3g@CZICH z6jh_5JB#G}X%hT_Dy?WY3*Goc29x_1b=VMAhqY$Nc37{wX>bokEEk+)$*|BfWn9fD4 zlA+g)Qip}2tnS6lhcD|RqM=LUf4AV6&=2P#1o5`cf;W^c>L)?Ay?w&&)PAkVaBIs^ zqReazKPp1=(#~Oha~;OA7GP<%C)I?4wL%TYcM1~V-~PRbMych(0A3!4!RPtS>UxM4 zX+3<`D%l(n7P}o;SPZ|2tF$EOU9aE&v63@=D;qIxBa5{iVovJ{<^jQtVs^cfS}L=# z{;H32!u4|W=fXXac2guzBC6@oH19-mK&m@B<#EgKjjLEDR~b9=C!ofVo2AQJp>IeJ6pIph;rOQhu)$*J@6{KmeIFuahr@0LN>sLXxGx@MF1FxbuZ@CZDEf-$q;JPL(b0~po9Ek zkw->7^6DeJw&}9ruuwLgGz!85q(U+JfFHYPZ@}G+WW0D~?^w<)iDiNY4e4eAo#j?m zi3G-!6pwARSS^7-8tpxgVKFkCF(UDuWe;KVX$Tz=y+c(((PM;J%yunNUM4ndInrgr z zyv6JVki2c%?9^#g0v^{gzS{{OU4u2V({Q5~(z4l{oycp@&^+B%Tc8~RvSKY#B5Ff5 zr^mQsfO@p5tXkFExg{qW$C219<_kT85e%<(E`t9aL5OkN_agPoeJ)wLDeZnQeOW8s zT3Z*k8`I}2AVL;|a!2rqDooO{6AsJV@{9K8mV1c%5|PsoS=zS}YT7Z%=DoHmsJ5}q zCt~w#g9&JInw?Xqu_*R$V5N6H`5%s+x)STZyqRT6BGF6b3^Bm5aVG3RvKBE575>Oc8QB^i}@g`i)z!*+gtnhPWUImc7T>-iw$s7aqfyg@D7Yll26B(KYE zDZ0uKctL;u!0`y$i!Ik52{5mAa-Z#&igbD|z**piyTSN}A`^N%o|~%dtPZ$g!w-Ko z&M85TRU~65;r?F5oLb;&xf!E@ySwx|YV3a1x6jQuj6;!Hw3tXt##Z15{PH+7hz{-~>J*`Yt**H=eQ*eLNA3k5~(`TqQdKmi(> zlE0NO+?XuXN)k4HYr1nU*5^lVLkLP)yiM$GcF+8NRQ)|(W_krJ7%q&L()EYLlR5IQ+_VMH*m;$Pr z)3V}xYKRxWni>Cv;u~i-)Ztmcf8|1fcQLKEIUm8}*K`vK50{#5dGnXRprg>dz#CKp z8S>$;CNsAQG9sW=yZT<%3GB;NF$%qHzz}p6lJE=Yi9}yi)FVhI&jB=ZEd7VI>QEjf zQ<(4Z*-~ga5-MmWF`Utca0*Ot`+|MxSF(M8cB0f!<8RhWT#!h=|HGdm1WEhc#pbz2 zqe7gqnjqXEI3<6MUON>u@^v{+^tg>(PsQ}2ZtXBJC4#!WVklL!3+Z=of}D_Hp0MJj24FQOtD3y98-$0*#p1--L3a z18tkG%Fg(|G}r9rJbw)r`Ms{C{9=LlyB_cgUaJe7OXrh(>S|o}VnWRNkbwO%R`aZ4 zCOhWvh^Jx}o;gcZ2`)5|aupB-1DG>N8Ja?P65U986+CB}0MZ|BY*ck4rN~xltxw(?}jmyQOD-YsH z;L?AbV2UBnYDPn@i_O~?ZxW~-`0g{oC~(p4sH$n$$z@aNg%V=*eT8pK{XDb}aP+A! zuK-=A=#)wx^HzQD10QLl#c?dHub%$t4;Cbo876*jxqumd&9R#(>-{!g-YfdpW7C_{ zU~J#5QX`yjO5d|GhJNUIu{nB|r|o_bD>2j;d;Ep?+z*8Dk6k zBjJ3Gb60eWN@5J)z$)UV`1R+Ui?WlR+ia@wZ3-tozxrsU z7?FwLks<_W5wwq>s19o4p{cibecVfO@4JN_2W`lG#Ke7B)OBRxl)n$O_+Hvd#keva z7bxKMvmkoTMBLKeHG&2i&=|N>0$OT=xpDQMZ+-tHaTXM!R0PP*@U4o^zNnv4UUGfb zfhSt1;3mlTD+|=(1DQBk7AEyk?%%y?i1qXrx4Fa5E)dic|=!L zPicgo<+%yqggArTcQ!q`0HJ3tAdfxDcI^aElWbgEk`;1bV8$Rj&}(qL#{*EcT76j< zD<~2zlW@+6H#)EJIsFroo_2(3GHYF`aZ1`fqjC$#eZs#={)(rD=zN}}Qv8iUYEB@A z1_fEm#|C8=YXFgT_@qH~A=5U>0A!1Vm9o+f26&sF5#8*PF`-RiC#vvgHJOW48S-%i zH5jhy(vS`KkR{fFc*-=+lWf6qIiL%0mSAk!W$n|&9h-6QAY^re^=MO$S%_-ckX~?G zqIyUN&18{d#J~*9Q>d@~(&X>Tg#s$rT9pgpLr2}~| zDx)^_tllBZy07jMmNJCI=rZDwpEKiI|&l`;u%0YSs`Otj(kqb!~eW5)yB@b2(U{ zV8J4jM1ICs@@r(CHCLX=jMrsa)iy4cHBC0UKoy5HMXu^pdjA6X_r!w|>x)GI%-^bN z<9BWh{Xl=t<^cP$$*0(N1i@Q>ZpEMa`Ei96D&`w_?Jg_kRLDlt>)6P(Ns+b_k?eyz zKyK`e!Ct@l=KXRh={sP|f!wJ`d*gBssCHW zoLrk*hM`2;zY1;=fjg;bXFys70UE%21&E-Qw3mT_?m7My#R%R$^!;w;dv~oR*Q>c^GeA#s@ndyqEMn8Amf2mOtUeMKP4{o;a88Xj%+~KCTN`a;OQT zrb74ae}E=ufFn3~n(YaFx47{Tka)1E+G612RcqsayL!QtmfdVwu{iL(^fgq4GYhnj zS*7J+)Iy7uUF2#HHP3CGOQSaj8j>%8y#S+r75#op3;TULgg&`@8~XnE|4oH}9kiXD zQaW7^Hlo3v&%+bMu>D{;%D#~81qjccZ%cvt8-WH_!+;lXd*yExU6z-akx62V(8;gg zO&3jAN>E_@UB?BQpjG1tF`<_k(YL2lt#Zv4G0ZhHyXUAcs+7WpX-4o-ek&8s!&r5D zu_+|udGm7oeJ9agM>!!hi13m=3EsyLOeF?B))_L`G8!*3C=Ok%_%JHJbEXfftI%aywEM z_YDwj%*rW!$;+CF(6P8EX0EI_ShYRlg7+8dO2xhC@+AWYv6h#}X9J?RnO4WCbXn6e!(nL$u563)T>9;wc7HFy<`PIT4UAic`t>(yKoU!6wDU>_Yti z`j!aBK`yWI#-JF7w|iLjR(9zbKDJq7677)jUdpUF5w5W`bcK^9E=1#}UI7?jG8&h@ zUzH2e77q#<>Am>2$LW!KA&=lU~-i_RK|00}bG zSgg97sTMN!tk?YiF)KLWmkR|PX6rBIH7PGWDqn>5vBFH@|{ckE)hqqtc)e*VP) zNi{ag*2#7~IrT!DBWw0K4w;tQxn&32Q`94(VTCrF7hD1PG^DAY_lRxphM^WL#fI#Ry?z6?(?=2M|B9A6L0=<9WJ-y`H ziTX%_AW$A2=#;w8YnjbD>F{KDlPDLnUR5KuqDL=~f4rLCmO}F3 z6rU$i($qSL_Y5qpk`L0VcSa^v;MQ%*ZERZy^UwyrSsW!ji;pEKl^rg&8$DKeVugY1 zu>X{IJ+b&_@2?3vZ*xQWgkul}cv%O`NZ#Xqr!XGzlzdz%6!1J|6>>y@%MVvN%o6q2ZNUVlQLQgLz+~Cbm!a56 z;~8c?YkgXid%*TN>avRxW9e_cN>6Kbw|(!_QS?}~zPex&j~54};Fd(uA1eD5pu@3> z>!r0@eHV>ax^p3Rm2m3-#@#b)+!mg@k`G~+cA)DN?SU>zMzgX%N`p#F1vWdy?-+l_ zu=cst<>w^2Mp*|WuYf|wXeh0G#y>oy(rd0qk75pgxbKu!sUZHbol=C6Xro`ZuD#cJI^9~By4OQ6L*9Gv3sS*3A(fjn} zReTpLTS48ebw|ChS`X(E7udpN`OS7}d@1lIK1fjd3k0kBP^f^OG!_@fi10NIELSr3>Lh%$9?DH3rGw|Hg0-4jQWJU;l6_t3sS^DO=g+j(fgvoDv}g8Q#{ECf zv>#>qKn3uxL)#yVG3|i2J#_La*<#w~mnGCYR;V|0VR;yFO*{n7eTy4IzOLQ%lhWDZ^1-2ouOrC+k(96b#RiWQn{XWU=n!lqo21BvH$eO=ij)pjr1z)G$MZdw!vug&h273(g!J6fCt=>h zWJ@Y0JH-*}Bl%!~`>n>!s&MuC@kqZI&IpFnO14V~Y+x$8Gejs^po{43>DF1jZv=gc znr1(hBVK|3LsL-jfwU=r!fei@PFVh_{=xgVRq=&QD8LiK9%`%skj2z#$QK45GGBfw z1ZlRP&pzf37Xiw(Z|M+s88ajhqhduUK-ce*nfAwBV5*^o-7fGV!v7N5tn%@beQb5z zZp6(yFjvET=O%#Ns^eGyYU6yweO3Z{bG3w`*-ifNR5KIZL`^}2;ngxg{HK$Eh@rE- z^_E2z76gNW$VHrAk<`FVxarR_7TYN-DslQsj;AUFUguS0?uyvsIiZahCq(w>KQ6`S zpK)wDt*7Hyp;p@)jU>4+F|CN=zLJ?OCe-ZxOOB@LOcHA+eeo#B77}^x>H6?VTxXfSYhT4{BPenM zUK+Y~b&&tUQ#K=;^!R<>5HSSwt4B#!uHypfHGCCr@}p!C!j^-r?#M!gCtj1bHoZ0< zZ%0cu?vo<8(l|hAHo%b6kpVYp#GXFP2lN= zVKN7M`$X>6;pjmA!+#%yfcPGdGs8Z~Te+qP|+?>xVm|C*V6>xX1@ zwRz7u_r3SN_VX^}x6l|Zb1`cE1H)8bPnsa)6jTUsLl+Fc6`@&}3pV^ysBo z`LEYrj8)%gjF^~s{195vXi!N+o+~k-@qGeJh2uz~D)pC+3>-g?3Q%dAGD4drb(t(h zZ14Xj^1BnCQ)|TB#bwp9f$)2|b%|G!+*eeW0cuB_XR9YJ_tzZp&B+eQ(+mUI9*u5&9aO~bb@n82f2&?~5^;H-wVj{V?Y zpB*5PrhmvK(U1_pu#x$mEjWWykb|R(fsd9aW`zgyjk$h0j@#YHv zEuWVPv~PzcRj)w3aP_8PFtYx25Y9ONRXZY6^ERL<2yIY#o>iuZ4^p>Vv`YAO{}@Ba9Unq9VSjS18ED}N5bo<$kNKa?_Qng0O3cbNRS-)UJ+&9iMVT_!R z&o>gEq>Dhst8ArGdKwiJlRza&4R_E5YD0kma@9PRmd03wzAihrX8kc-_`^ozNB+M_ z;uIto7SsHaRxpq83(f^1B4gR>>3cK1^rSC-1x)hQ*0%PWmLq2*DScT`H#}rv5CBaX zwZdd!rEko9I9G~h$Pkh%;@rxYhRNy+#m88Yj^a8NR5oImr8){qiee|JZ|enaRcxW2-fkxozKQomj(1hQDb|c zjK@yX{m0bl0HRr88caoHpl=H= z0u65LX7WA)d%xJ^h#N7S`q38>F!MfO4I6_aug>jjXWQ6KTZf;@Yzl9{)dTO13%|x8 zR~ZGh<;ABVT(y);))*~9+fG0zHZ@vjm_9j6{CdA=WcU=|0{Thz-O1E_pH0yw;C*hB zK+FEL*H8LaM<2~i*46HAprYZeM=!wc=HHbAbSXD7;u5^+RzF422;Jml70^*UpC+6X zU}R~LmUVty^xP$+wz70aLJIsgvFOcZSHQO#FpqF5SPbEg`ckkjCG=fAV4`k4;IQ}i zj`bO?y%h#O&ozKQQ*yW$!=$Eqajj+u1bqCTK$?Y0_1jGNdy*0px5IYV(@Byl$E~-j^3Z z_pWqYqO{Q<7>1s52$Xln8mhm?H6n*6KBL62oTG;+FUfQFw$9T&9KHLdRx=dsZ0}>( zr_z`h;O0$)K_A1NV>X*uK!~43e1%e`4${rn3NVJiP^r|gpk()i93e|&mW_;68<1y% z-z|8i-xD|~1lJK^5Tnfv6EozHX-1n&EWI|H?6g3QXszA#OCg%Fe#aEx4eO)5*s|XW+4#(gQqoC%PsxmfunyY7)gd z(NvYI?O>_D91F|HtY)otMjSa|^M}&b?bbm$vcqKI$#(BM01|>O-pP?SFVz8W2Z)&G z7?6W0emR6N_jnGYjMUunvZm6f#S_!zFx0J*SxMSYKnmiH2vYzxTi|G`lTP4yMxfvi zfCV2{?dT1^LeEuxfQZITzhGA0PX$FL?xog2RN6kZbEB(Gj6z9>Ej@`j9xy5dt%=wX zIR>x2lkuK8Avv)Dm3;bOFiw+#?%RIf*n%PD`1>Wv7AMUrD{Ds$WA>lHUBprT8AdkL zbi5x(NWqsZn;MB_bXS=g;^p{x*>Yy^TuL$s90N+LZ|+J9?GC590}Z*v(sET>)%Dg# zRY5m(=KRfO#)SS(D{xJTcXLVOk-h!bZu{0w-&Z5`@jN7(t-NB~== z7=sTzu2@r{ppIw5fx6os9>}KsGj>v-uA&4XyONEmiCUAi7}pk0msXSE-=U@&%knfO zJWNi7$gxbw_c59|I`-BE3OxK!AlyTqp=`DND<2{x31-C~#CI>YtH-KV7#O1F;w2Ul zDsW+0gf%Ah;t*E3L)mQmMcPy>=ks1xpq4S5tVa;Wb4;gfu6b_y_7@GTg&3(~Ab)ES zw!{vZ16$xu+b+#SA#;vCxc6d#s ze$}?Ax8|bdXxjj?#!;~!m|5-c3}%$$%%U2RK7rtrIM4aNvH}2J3HTn^hnsMI-^z$yKjxHZ4u?W z7{)LQ7gA8$!ISAkLU`L|{u#-Vt&IWku?8Grz-y#SX(7vbbMvgD4K)02-m&S{v6|p(Bj4*!d_rx(pn#v{RB} zsBHo5?L*=!kRJhCx2YW_SA`P*7Kv7n`7MzK;#uULX3#t$JyEG zs9U+O9P|LSZisJysR2>{8bazRG7ik|CfXpci(43zqoek5)!Kwd^HZqd9Eh#bl8i)O zp)wBUEHRi)%`pNfD|@`zBR>o?Vhxy$9f#h>X7SzWl=eDjCk07GgYF{?&5b8|)mrs#}M>4ND^MBQu%g6fsYJeV<6Uc2|+l@}I-) zHmYfG3=ygBDt&h@eLwV@e_e(kl%s_`5*pKwWdtN~=4CLx(JOz0wb~SGaU-)DW}kdF zMw6zoj#KppUWSOWSl;4QfUt{|_h4OA(V*eGT!m;Z;1MNJ$*l7lE-aA86M$Z-?nmaT zF`A;Os7eP%N;X;tZ$16b*0H-Eo;&l_U8IKlOY?V@G+w{iw^$vEwrnL%-+ zSsT)fw|@gza$m0+CzxyMW7qE*x zca9GH50eYrHV}H06bMw|=HjsSOKBYyor>hu6tex}r-sV_Xuk^JtYttK503bY6Hbno zDXcy74v=rTG*!Dg=zTL(5*+<=Z4s*Q=(-b1<(#4p12R54?wpZ4K)t#68q)Pq=^$~c za1PK_zS-(~EgQK;i{dzyxnytBSw5q^h3Ttxd|W`1(Xo5MJB}vPNfA2siy<;{ObOfx zfL^AAue%{tU|dzlw9K;`dJ!0aR|e>bJ?G{ZAeLRfo>h~m{Tl81ua5eEE_J7y0jwCI zXVIIHnGg3Q8Ux@{^fu19WH2;z^)Ur{A9#ND1$}G@XE>DQvRTd&p%&FYs~DiA3%peE z9yWVdwNwFeShBf*iHX$fkuXTeu>+Jamiv12ZcDB7Nj2$r-0JM}o?KIN_2B(7v+kTb zcjoKs^B#3`bN1GyrrD!(J`Qi7COr&az~u-*i4Tq1@sl1xeDfGG1n%^Bgp+JnYq?cZ zMkIqW9~?gs6@#>oPIm^mZf%i2^dW)?ES$E{NRiSmKK8RkqOvo2z; zzzaC~{ExuiZVr zQ9q~-(R5xL%2ILGdY0O!{C$ZquFhz$yU_Q-x`?I0G7;wo8c=>DJ@Un*)7iC=ZfCs}XS~r_gl*nqR0Sd#<*xJ&QFcfZ z1Z{I2Q$hz*j+TbG+snFX6hAF8O!enGcd_O=j?zTPYPLw=dui7>$QsB;hR2IQJ5<~#KA3=`xrA9N+`&!_t z?^Ip?Qe4;deOL{g5YzdxW7=f!Q8pR=BHz5w3wizVL~@@N`TG) z;Lx^1Ey_**Lx>MvTHqTPe+L$QnB#xLA}VMGq7Qg;e6cVLMUYe~M76=AMxqM|ab2?M zJ*1bn@jDfPX}Ykb8CJAf2@W^X9{=mdpkfDAh_hBQwN*GAF#FS)H4RE&&fUk@BN3OY ze8;)BBnZlH`7R<=e?big90V#O=19zd*OF_+Gzq8USmK(9dUd2d`Hz4aKf~{~ zj{R?imt#p#;96=yzqT`Q+P8mYyS?54t5$RSj+?=?A__z%kEJYUrgII?6S*le=a&Np zvVVJPmjfzac1HC<>qndXma{@hH2wkOOP!5D;kP}gD4Vq~xt}hAf~wD^}Je_+#aMM%(Q;`6=> zOj;-|0hpOacAcIFTjX|4X<-Cciu?~9B?iE&CqI()IWHK6ZA|!eCQgy}Ao=5I3uFQ` zG#tbhs*VAF@W1YX^}lq^C0KtNbML$(Qa};7?gowsfxF)+p~vFXtQ$b|fU^`ZXeO($ zLapMX!^R8$JU^#yOKdYIWq1Tx(Hc7O=7btr02Tu-q&REpgnft0mLo9BJdIY&y1Q_W zc|9u{MGYRyfpAwT8NFOjvxb8sp1?jy6i5dQZKubwPmorgb-Hfu8V$5O{VxOZqQ$7s z9#q*F(_B61Fb7+iX{ba7FYUl*pS(2(>b$wbkc6#q3=-?<&H>v5#V^DP5LV&1)VIQ^ z@tZWKEEKQ8C<@f3lDBQxkeDlBxSw?K`mOAUQ)HCtRV~oi84o|FrfhMkFWCXJ?Q^5t z7dJ%*mVh;&XerjyM_wwOhA-~Y=^g=T0Y*IPKOt;p-EMmxe2ON9wlTw@s!87xPNi*< zufd6Rm`Is40{6D}MSPl5K^)H;QL!(MEogN{3MVK6;`m&-z7M6L6o^sAwzW<#?u=sZ zi_?Esg%los!V#w$ZQmnW5bv&)llANYL=sJ1G)9yVdz^{5p*HHb~%Bz zo{uf#oa!Mrv`KZXf<#Mr30M0w(C*){x9$CPtm+6v9U=(N`+8O%5cQ zkSozyfu#WYEXfVKi|!EyF-x7&nT}m7RKL$VnWkdac(dx*%5AjS0vHd_n_PI&tA9V* zw8ZBK1dU%p>&(Wc!?yuhruuQVVBuvGhtcxcw=n~K(dpY6em@3=q#~}@`fLNWsFk~@ zKviGK(Ih}zzwQFlo|(Y zPFmOdL7_|%2k0&rL^w(oP8hVK_rl(%^0Gt^ILrUA{TJobu4w|6*bN=4i?&a|`c*to z7EDCfBxW_?;_8Ci{w)s1&Qiyj>np&^3Kx;9_V&6yRp%^s?6*B-s@ zCWS%8jjN#dDFD=j1n~4(kK`sZBF=ivtKIwB@0f(2)=_G(3eMkvIk01zwv{O(pv22isc_5_ z>UcoB&f2R%c<8!TwoEs#S}jc54i+Ko!i|3Ap`!gt^2vd;Y4_9hdb&+7q(mKAbnpD( zGE?AXk}2VHkhb{)zC`Zy9FE8Q&bC4Joip`_2|EU|pHBo53a|)H$cf zPetiI28k+QNTu(w6B_-scDM`l*5#i2rJg(?1yW@*S)oa~tn?L_&PGfBHR?2ux(j(m z)R<%6s(gFTkCB$0xbs}n+2ZqHRAn5Z2vPklYbnd4QwE!1UvCP%+3>@~BAGH_gw7h#U-uWVTYK+ZmeJMX75#YjzQmap|y_hUc%Hv`PhQ)f>&xzc2o^P8yF1ZohPGn0|J!3k=ifIV~41q==sP?4DeY zSPn3e`E&i~GHQFd*r6{HNY0@fyOj&U>?!< zsu+AC6{wo1lRer2wnyYMO`nmWPoQaf0B1-z-v@ilC|n}R`!#arz3>!gO%#|0y{!D+S|wt8UO((DyJ}AxZR2 zq>729ae(|IGII3(6)=CI0xb}bHAu~Cb`l{pu94~+wL8Yq3$W)7W=8dOQ^fU7RHHd~ z>kE|{u|xF;2MyIk7D1QzI0zvn;4t5;TfkLr(VEbj@CS$1qnH8vq7dmW<=seX8|ZVc zQCCEVE7DHhia1dEOEj6J5nR_Um_yzls8FB~lBe>oZR6k05Y$&g!|!(f&pQX+)M8&% zfr71!S^(S@frY~M9b>mX{&E>Ssj7LG)FZ+2nR?i?g=$WFyL5TlRaVe4{Swz`!}aXQ zR zDRP{a`@T;@t7F&l)2?aFj=u@;zA4(Jcwe?iz1IAL7N!R|0egQ#wXm^cbP)#fGxshX zoeR1WHLhk&m+MT0DFbYc9eBwLGJhUpGYWzl&r7Bq-xG>oBkE^l=mi1KdRB!ofu=M zj8JTPu3iaotr>9GFCYeel^JLygYY1?ZVIh;>qJN^Jvut}U^wkcTU=?(t{F^d$0!Gn zb-#!5P&5KRyg^uD9-jPs%I{GJDv-{{Bh)+ML@vsq{?BcjoYJtWDdTL-iezE%*jJNO?q$Q^F{ZY2z|sh?9HOyxY*>@Oc`SSz1ICNss`s_74;^kZ_h=+D zfPWmb%`(Rb?CzrgKWN8FzB1>(=iMUD@stEJ@eR!cQ9nhkS}JoVn=p#n0O~_UOt)`= zg`T9bg=wZyVE*wUd-j^+;*RObrd8*7FJGn`>L!4SssdF4qW$&d!hl+%m3;DS3E)je zZ!-3W;hRa(J$d=tE)MK{WIS<;M!VSe;VoLO{<)%NTMr!SS(R3Cv49%W0OVo@mPOnG z7kd(H>Zl1^5`u^|0T>p&GldWj?We{acJSWJcd}~SATrKXUNVgDYrbYty-jtL-y(gQ zR-)Rv(^t4e3EM7GyI(}zKf(t%2QJV>G`#kk^aIq{#RJduEdEujAIcbnp*5cS(d7J? zf?}lVXdXyC^5qRlB8B?Vh;kb7)n{I%K}w=my!&@J5l=&Cd{&Yzmyxu7YUj(L*RKMc zqaS0KYry&;Tv8>{c-}0RyR!x&Y2W~AV3NRAZSKM&izeVDUl-|R>QRdhsOd$xSNAo{ z@jTV>5cxqu(B=<>ypA9A1)tX4|Lv1UuX750p7~XZ+zov`02E17=W$kvFLQruL{_c8 z_>yr-0r{5fvmdi+t@zNbmFbh(z8`0G~#a$sDp(u_UV};RohoFi%70>%stP0mfV;-SsbRg9wK@%o;b3SuqZGOSs*5!CHdHez6zX`5SZYc|(!JDg6-4`JGKeu#NBpd90cb$PKc?32 zBEl!VN^}aypvBP+(T1*G*R*0rneC}R5^`naB#kd0E zWwe{*xj#IBJMgvwo&-nW<3!27SoCpBPX9I$@XL+>k7R#4AS>SXe~mg82bK1|*OStvGJq8?PP~eaBQb@C`jA~AO6i! zW@NbO*|m6faT`LT8)<-qMw#dxnGyd!(7n7Y$k-@RTS-ER63OcDE>=NZOSqwcgr%bH zf(CNHSWW}lxYabMQqS<6xrG(K`Qla6CsQ)y-EbI2-9ulop)nLfE75};)7g7pIs+)` zB>!njb+DQpR@Xnrnj^{owaWKv_TaOBuAWuPh|XC z&uia)ssK>o)|~N3GdC4b(hUTAu_-E)a$IQLq zg2{FC4omD|C~}&{3@n%507-BVXmtB;jq~tV3D_cba+e-|L70}6=Z-(YeqkB_9NqB~ z-ARKZT)IhvtcG<2<_;4MB0{MyHmS}PwWHm5EdO#e;(ru#8bz5Qk0YbHXoi=0IJGNM z%MQ;-3406?H8l6u^&&h-jKVFYnm8zC0fJeK`-ZC=1Wv8=1|JsfEU6tS4VQ>s{4dzN zZ8E6M;$QohGQZHZmqfnrV|SUTQ^2fxwB@XX4zh?_-tULzSz}IrAs{bsiTu_Cf-t;5 zQZd6ZZe_?JUh$9NaMKB*hj@$(RAaE*vTKw!TCzB|j&$CNl3EcLI>$N9l);f(g)YaCZWrV9ka(FX6`NjdjD zOYLT;-U(|rH*G}EevH~iI|x?T$I;>t^f)E!S-ROsrqkH72sf^B3?$K z{8&9Er47r%dG29&6+W5zDn_7q7b;E7zZ{M#)V!HHszb0^TV_Jv|97@WRcg>^7z^Rn@R zDL_c#1HCU~J6&~9S&b&If*vx5tiV{y2k|!NT{KyFW#5?ObMQ^|aATeBCM2YQJ&PAH zV^1D@AR^O`;oGq#v2Mcv4|&0zkpuEAhtjkrmVO00JTFr8e<_hCLzPXNt7i}Twkrbl z!!JWaLq#M{>&{cl%gg2Z4`p(|zgP_CqQ~l7&f~ecuy?lW;>(4-KffVSivR!AnE+3S zyc9^(3j4*#?|==2q;f5xZQ#;Is?i{tsyE-3uV;Hi=~Kte^uE#k$$+RLF0ak-4Diux z`|`XcvjFJ8BEEs*w9h6aS?T^!%UQi$aXzPU9plJZgt&lkse0v1(hzABOHxslH6Wbj z5f(JTh$h>#R+T=|gI$OWMUE}|mC}m0+q#qj9S7oehh-T4pKne)vEB@G`#+8uO@3Y0 zJo3VwG({QFMBDg38uf?-Xft~3QS*mZ=cb8U=`$ygGTk{GC(KHoqhCyBn8}i-%!lvM z`2mAun!pk7l$OU1o$#AhNAj6PC7?V|sj9`^YST#(YZ*M#Q1a!qjk=Tln)|TdJQ0FO zw;N%;e?R2z!dn*xnD%L1S-?ZfKt2wBfJ}?rxGKh4asU??lLx(@Hi}FEnnA&wfb<** zilyN*twvzkoFW5%|GCVZPAxHio;iZpuO(OOV6a8&hVm-yO2Tv3gsG2Gd@`pL7udAD z!=kO9X_YkivqHQ{=X2oS9LMfbG&^f=wO>-v$z%_I0D<=irv?5Odmob*+Ys1o-gnBt zuu-r@i5p{JyWVl!s7B-VK~s&-xKC$(4RMo zH29bf(!@OCP?h}BouY!#2-gK+N=sC=MlhNLPXQd#Sl!s!0MkeK&WDD(7}CgXpyl%w z)sjFYGU3IC;8VPEoo~A)ILYc0o>_e9u%iZ}V6P*aMs9@Zwe0iC5vZt^IEvyGj_ewt zcD1V^<}9QfRbIl^o_w@oEmzlylgv0u>5h87O_OT^0&=T9=O>0&B8Y@1tbh2ctD21k z(@7PQ_^&F6vlq`@=@fNS$1D8Xw4`QWrv<=60i5Wb2dEoS-vRWvw)8o7_F?6-{@Y)9 zjr$6@V{^fIg31jwA}F@KDM&96PA2$*f5)e1~*wIgo|R0n8ND9`Q18<)>c=JT9Hj;FoNhux|HA((o~eAsCS% zz`3LGRJ75cW^v&I>P4CNnOiMh1V+l9$LUJuLGqzV{`e;v5Pe-1r7HTvQek@R)WpV{Kdc5;%!RW|RY0hXzgDUU&=RQ*1M>uh+Scvix(sFEg=quMM4VfYb7t1Y{)XrQ`=#Nj|px8~QQ$ zfe6FLxr|b)O;L&l&;s5uICyE`bL0KD#3(1{s%B`r2@CT0S099j%l`YyXoWDuve#K9 zox{sPnt}hvgTebQj{j5J7BYQt>bu82kh*{B`Ix_bUDEuV(D2GtF{*lpTmgy!R-Mc= ziGwDMzw_BHnEk>7CM2tjLL#Rdz#FPvxyIwa2L;v2#Vab3#@Ots<@eHiGaQfK_kOoj zFh)aW_dw9E)<_mVs!W;!}!WmiF1YpYzeVCwQArSPot=#Sd$fa!4A|& zNt)$xS-v$)4tmQW*So?n1&o-8mrY__M3C^;dJPb&5%nt9gPE^5=&OaEl6V;D9N!;p z!=T!`>)iY@ktW-|wr`iOI%sc_@schFPWk;bd$<$A6w2QaS61`CFA{MHSjF)ecN6|& z(smEHc8k`sEk{tE&CvFJ&{l{kP@fw$cER#;Tltyy>!JB(u;Kpek5Lh0a(eLD(lQG3 z97t3`+#Y@7c9T3*vxH;? zCu;Yx$*=Zlm<~6~LqHSWwLt4awMcGSrS=a~Y&Q|`Anp3mir+(Ad*_xg$gr8$r%}=o z`;>F}^oqD59Q>XYNI!B!uS>|_cCEy{dPw+w?#7oDeA|WmvITA2_S5+F2G9?+ zuxre6vRq|}!QX*_q7~5L$wu3NHs?pBKwui!1RfIw?~QZYFo@-^y2V|yg9u~P&$0kvMyD%yo?h5?Y;LU%#t3menuO1W;s_0V+C4R0 zRX6E>V0Zg}Eb+q2!4va^DrLBMR6jwzGoSm%D2HHTP@(~4vOmFQLx*+kTD+L@TGq01 zr-a&2O2v7ZsgmM3O0jGRpD}Cxp-UUFD*bbr?K{ak=r70CGZ528Ii)>jWBj58E$ao# zK}J^KvQHnp!Kh4b>yGj391$Y#tbYP6Hmzom zp-?Nu0_zw}Z})qcIpLf;^gGKVZ=3Y5Bsw-P5WhOugOo^a-+X||gRw`it;^tAwQBb( zYkgesyLBomwcZ# z+()R=j$N1DgAGc6y(RhGB>z>v{c&ZR-N7Fjx2q0!AO$!JS2x8A@LXoKHV;R2lS>?O zkn_{|m&Q3MNjX_LBHyga)oTl|M1T_#9OHO5W>x_Kyhc1UY47098KDsSc9459L4Q;N zwuz@m`R&S}!TW*}H@cViM!M}c5$*=iF^l%RuxhPYE^>$bG5Qvxh@DQ~4-n$73Bh9% zFMCPE3rMm|A&okw33PN^l98yUam}DJ)6ri^oepU`pl)^$|}3>&$Zr~iE^t6Nuh zxc9+MD`8=n_ghzQs1spA{G<45=E6qes`fOld6}c?ptsy)XK1cakLQ&fxq|!WNT4LP zrF^yqgRUVQ&bOOJ41tfF07bsCR)C{Q3nvXoGy?yF4-VkDK-}W(N$BS+f(9lwkaN}Z z9c2O7;TvR^njUFK5XFAuGPsFIDJg>iaXz1-!xfHg=gl>lsHvUp!miTC9Au^hZ;0&+xF7{^NN8n!XR8%vSiBGU+=;{t* zbnJblvBC|awqh6$u?Z0N!472+AJwgW&6fes!KE|*j?T;xK&eeO5=W{~wqq~F%2#zP zN#er*``r}^>T%xq?JwKwqBcY0OT;Ho2i-^DJ@v!xb_=A>q6;(Z#>NyJ1UPRJqHeo) zpZCUsF~Wi7QW+`M1~iSAK9Td^7{U@a7X44>oqY8<YuR35a*4=<+T3a4B2V$^%hcnEQoO?zWkz3N!Y!W`ZEWJ^* zf@5FRcMlmb6b#5_eKnk0Z!^ z20!nqOCzh{lVV#-Grp3bAe)-i&q!wT_clx75>H7J~=vYx_e z(p=IvqN=vox7~KJS`jg|EyXprtQ0-xZf3t;;o}m{iJe>i(T7A#I3=YnivdTJix*#2 z==`6Zci&Ne5gqifNIV@>ZqUh9y((U(8aq^2Wpoz)8a9@$FX(M!r}noBpAh+vWY6*~ z*5u4$u}+DiC4eK3s{YX1g}edgtm24B(KDB$fuq;9NpuZB0IVBM%YKfnJ9)}6C@g<2 z`Mbs)t$PdL;~t8HP-lA>%dk;>$zY8k9PFe%*mwVkdK%`^Tz%!*x)!~As574$p@xET zj&8*JJ8J12Cn(!aJDm*e7x~B@ADxSAD{sM*D|{3v{gqRL1?Vvu_EFBIP5zYVGP5Em z9mF0whI|#cpDvq)`J^rY%l(1xtAmdVWfN1Ir$)?MN61t&E%ht;O%{=jfG$rSL&rFK zr%SQ%BI7-!y23!76c-|W9N^M2VikGon@ekv9jI&k)+|aD7;HG^crOuNn3C*`UW;S| zTHEk4fHIpB2};%k0X|Wa>4VgA=6M$Id5aOsP3YQ?E$<8U_lJQfsTl!5UzuYyzFsx( zNujn(I_j6dhCh=e2C3v`RUY<}&PI~avr!fthFf93#>_Nu4d7Q9{4;;GTunnGd7Tay z;<~#kk`mZOM=eP+(zg0rq+zCdm2*4R4{R-!T3>lSx)KNDzy>WjVo1R6lcH6=o?_r! zcU_0NQap*()kgaeh4nX}=&szbtiqByQt3_Cnfw1V-mR=zY(~DAn1TsbLW0pm0Wn`s z1@|nOPw;uLJjV^-Y+chSd5!>Hfoz|k9zLepVb9C0$Vg{b4k)>J0)zJcY_He3F~ffd zHZTO#ekR@fW$guUgB<$qdN?fB#?mgHJ?mXs2;5}ke@c-!$cDdO?|)CX)J0h5+GpoxA zsUUX+q?G?zdFqo+#zhalanLsYD(=X)jAkq|nXTt~&T^jAavGsBpUUYtNY%OQc-jQa zCUsvg0h`E@{w-*}M2M4>HP8%jMFWj!zKeS9dQbo>0rWznKb~CwwE4hRl0uFe?y=hc z;=K)Njo!4;XnObq^9T437wZxceAPyEES$?Qohy)j3JnmB2(5kQy-dJrG#Dy@-Q4$nM8hu10U7eLD zbZCI`6mtPeWbysi`ElAo#Olr5v6|7i_yQ@Lsk~{h?)PN*lYP`D%tGM zK0H7QPyUbnG;S^bqbJ-tOsr4qa0x=z-y-|HY1mu1aiE=}s`acYg&W?rNzWZ<^bl;j z4;shoSIDA(^$%;3IZMAAdOhS04_p!gBu?DSN6eWvQPBt)TxF-8z0ggDmIcWN)|!joYN#F3DMY2VC_m~>pPjveF!0#XXxc2PZ-SF=i^`|raMPMXGH z(V`_g4st20>fi9}>a%0e3qviCM2ShR^8jx@;jd=`zFkQ*YGR>H6l$mM2P;s9GyBWE z!RLgDO}^67-tyqw{S|!&X=%R?D|<2@h`s0E*v$GDG36sBYeeH{$dI8TGwDJ5sXDUk z3XDKIQf4j)athY@o|F@O?^H48AKyj&@xs;EEo%g9} zZyw?^R^3oBMc#*NlJaEcWkr@7ae&c3hkpjNkdMgRj&=y`ywRfoxU2parMA8tW~wS^ zTURzv)6m!hz^N)BMNoC&4Ml(>zQUdq*vEa=(frh4t54VSz^jGCyzi`xUJ_-MLoi~W z?lHKVoM|oS)0KjoM*m3y+i}Y8Km8Ot3#o6reG!1n9nE zVlul+0W-S4f%8Nah4MBg0G0HOPoyu8NA)nciK;zbhbtyujKEqq%Y3!VpBCJx(R1JM zYI_4-ON20<>y8^Vxkl*`D()T6KX&zhY9O=ZdW!Yb9_~R)gX50GSj1-Z!v40Br;|U- zL^T)Dh24wl#uJ8MPvYKCBf4Yu@ERb1>$p@fL6CP^hH+7%T@XU+3m2dZIcz;^y{#Eq z#Pkv^zFoCWJ1t~vs@S?kU$*}z`r&dd3aei3i8t_r4<+ivWohF)COG z7yT!K%qejDUI&x3_hZOawBL?~6S*x%4E(2hH0^{DFm>F|$}zRqGiu zu6dHUXbylD9oy;@dMC8|gX@+0o3S+qOf9piCv2NF^uozJO%uOO&T8B2D9PN%ZRZ`P-M@_&{k9#e=mHJs_G#--2X z*Ri4Q8?tLx@To&}4FaU`RFXafY6&Em3G8*DcJ_wDzvZZLNi&;juc09aB@oC>`awJQ zqpKT2h#l&d@@b*a$t35#t+y)n37BJs6AD&dui3gU0Rl*6Nv=Mu1_N8MC|s0|-wV=j z?`8EroRHAl*)FL?@XSA~IDS=!2!{dTD5I2KEpv56EKh912vw!Zv_rMuIa{BNoA?f( zQYOP$!M+D0C#Tro8Ki=6l?ETDZN^&^C0X%uOrExWxWjx=Ps=D)^F^Vx0hGOd_t!Sa z9X*9~!vY*Nxf8VX6Zcpmw1N2>YHn>B+*U#6i@Y%S3{WSfB4*MV^+7JsaouR^@C5J* zw2?%IE^vPkKb_1J(le|=pgiBexWQ!9%73?UqoI(hLpcTBFKFU`4zWnLEwqS!_OAKi zkt-2uKat8LTE+5)Q$o#4i|N^z?6H|rMzW-KPrFR|^1bYP-5a`i|H@2Qxe0Qi6saJ- zi|XqO-|~zc-vv2O{=EeVh--g99R%M;)c>%y3F0JFVjP)1dmO)xjErIHoWByew;LrX zM12hgOt0L)_TC^}@NHKDo7d-Nz@LxTa|n3wniI^QwgFS9Z&>hBhC-Bz;Jl-1*1ku9A4i2BnK1LH;zmTu7gi9WA$Sfzdajka|P$VR&QIFv#VCZ-X4 z;1)sV0RUT&zJ$-cINLr@9&n3&1qT*01v8o{R6>X8uUF-?XhIq+di!N6hPuBwI7xjf z{y6P6Nm7)>oo?QyzA}~5gO6uC76R2)nyBKzK_ZIZgg&iuv(hs{T4X9~WwA;#1VY5^ zlMENOh!M$%yew>mg~)SnpSrH%Dd?u`aD7e95=u$gN1Zq}=%>wfDAeoT-nJN~#&W?K za*#2p6`GI@YYF;Rh$r`0pr5B{bYas~59vx=x7?NVgKUbc`-DMF@>V)v@Mx^ z&ZeEJk25x%yXD2uH^FDa>9HYz%fr(0@O(tja-@E>Bl+M_pqx)uA+1}H=khKNEViJ7 zLS7kV58Qb*P2WbNX)v1R2$F0k9VfUif>3??z72QS+0&6|Mg7Bpn&K`)_DI)CoiF)ETR6;5Ye!7Xr{@)rFb|lU*V_?P!y)g z(aifxvAlSlF(TCT@&^ou-aaxh`@2aysSLD(^umYR7-J~!bvMF@ArQc5#lk`o#eHIj zX9oIgC<;x7WX{CdO%c=kOPd4H{{}eL$dUqQFwRtldi6)i$aEO4AMEwy0CwiyXyUDw zyFiHKUuGdB1n7*vDmL_$5k^2lo&JbS`u?w>|7;3`F=lcbDs#(z6%aO$_q3_Rc`qw> zd&;Su)+Vd&EQb+;A(wCSe;tk}Th-_R9&GgO0VKb*l;H|%Rr>d}Bk^~yPlA1W2UdNa za}kff1#HT$sMtN+O;tC9#ihP3{h=2ogXlKbmCi%-2L6fp5wOaw@FnVe^fT6L#X32$4VkCGg(J+`rVd4LkL2HF!AiZV3bZ3Kc8T`2w>uZca| z+Jq5lCj{uFVi0cZeG)Woa>5h$@cn?jr*}%%JlhooD39R;3_PAqn{l{XjzdJAs)oSw zeam@DaLK^m_aIzgpDc|}c<&yhi!Tg;TQbAp2Q{q(^a7I9x9YTfF?iF4CayR+NOP|Y zV&Z02b$q|s=$JCBgMGokXCP-8`ziQ-)D<1Fe*L1(DqxhL zo|FW_Md}oK*Dx}NyD>eL?sZ{xB7YZui*SYK{sjMZtcgPRY-FJTZjOu2EQDaw$RoUC zO-|c?ZS!lI!DuZ(YEdM<3;+pn;t3`fR4e(_YO8}Ij!y1mo$QA~hHcIfJX0gkS^Zc0{ z2L2*9DRk%$dB}X!8~#_-&GMJwWu5kA%^!=!Dr>~n0LT@S#-DbRmPXVq@Otj^hT7F*Y8@Vt72 z{4@PX9xbxz)b+Lz@4YP?#vG1{(-fg;;EOU295hiu_4>ahKq%;^Z4ukxH@M1CPGp&1 zY6U7$I&@g&sJYv8bpe#Y(Qn$e?+(ht*sf!AZAnvtO$Y@o&9sIqJ4$QuBn;!|N0Ic> z)gpruX0^qnsDh@4(J~0=#o#`RrJ`lmm8*wE_NuiVrkB9>QsuH1cQI+=fvCqRm}sXYPAp+5Jgr0rz4I_hJ(gDbSngB^i&iwSMQuhSHr^{1?H#M*nqo z)#SG;oH3fr=k(6jV*N?CIE={e>oUP0{Q^GfW35b5mZ0Ca^A2v(Of0_*hh z>dx1jtfjURAmV>_-G}ObZbH)byc-QTgp^j@w|s}tdqCy?-;ED1g*OSDOKlzi;;091 z?54`ywK9<*of$A=|LjQCJJ2P(w=?a3@%KJhHfe;y<3BZs%laJ5{;NkkFWfaZW z$|Hayhyw+wKxH4i@Ix!i{aSVPo57`@~LT z+h}atXw1g8(b#F6G`8(z&3EVj)>`}7dXC)l(irD>v;5I$xtuK5FbhKTF7x)C6M2kY zc%a_@L9q{T^{9oKGbW$M^-~XCd(=hDp2@=gO1Z)`B=6N}qNE{Fq9Vru#&fDBTcYFBddr@ak+G6C!2{%v{IGOuP zcXce^Wtt;;ZTdKrI{&0my!Bjz_=8R_5d5YQ{rp7T&gY!zm%z^uZ$)4LH;HKQfntf`~=myX_BX)7# zto#a?t21Dx{6;UCx{cKC;EBO7P|y86sNQ*0zdQUDYrKDe3z~kbcC4SgdM~%c*l9Do z?ezOl0LP=@J{%lu>f4*bN3t8m1($JsSozwf2h_t-wD<8JqG=4^sK7Sbn(uGZhFgP(1JeHCD1Q;{F9w#G+Z>HJ;Um8=;_^u4y|~_R90)1}8P}!R)|*P> zJlWq2(-&eCsG=8Y{kI{_8_jFMq?zv5bcfo%a0qfm;t{UeU_=W!5KnXHNMXK_)1qSQ zL7EB|x)j{Lem*pG-{qzJ?6}mc*8Rek<6-7=su-}X>2uF#_k4h;QXM7sg@ywk;vfVy z^Grl-WQ53;!++0)p)NS)x&x@zFYn=ia#|WyeDf?8sOsMH`10E~k~q)32=wcgOn~@t zlltqwE9^vJW24M%vtL?yS)%_aqO}es@JzFYj`fQFH`2RohwKmk$K}mkcl)6`nENEb zi^<3eY13QP;^uzshtdPrd-a=bnq2eIi$MYu-tjSrId0}$4#2Np?ASpTMlQ1~WUOW) zHOu*`VI>9Yh`O27P@@G6rwr>rw4K`e9XX?r(;e&gOw~5K%4{}*(7h=Av-04$V#6%p znpr*uNZ_Dvz5_`S()ervm`V08Lope93VZXq5HolHs4R(=JGLcg@=M@mg{P+**6 zg5%V`kB675XLtn~?0sW|+WSRa+}=^d3J%Ur2>j?Mzsmah5Q|+dPpiF5nISfs0J%Q2 zas^+fNwHq|2<67I*BOH)>5!cTKz<(I9#(b4XAfV0(Z3Xu@$WXrGo;UKi^2EOi`a?M z=aB#F-mG*Qoy>A`YT5m*0IcO@xL83;nN5x=lPg%2nUKt&Rh(csd`s;Z z8bbRTwJaBJAXn4dHxeN!SzI~P_E+W>SOO}6*Yph1to|l&8Q%eGZmg$h=|L-AF zHoNotZ9%4dC&Ky{box|Y5jyGax*67aJLM#?e%VPh6()nBoU)m;M6hk_1tgGnT>k4a z8h&#$Ol} zOpi=YHCknd1G;Nj3<;mN>&tDrUH9{`uRnW3=HZOgv@aGZ!>kS>nRDv*( zay;P?5W<;5IXLskS##|B_dT2<5=?Is?KgxR5k&}6K7lu67P}U-^R!4AME|(fyox-+ z1X~Lj*yo+BgsAGVi~OheBqYl3rGCscXNH?qlYd|nk#E;=rWStJQQAA{e&q*D&OS3V z&OA6~J2bZ=wDDJ)Pf}q-vT3^N4R|k@oYy7v3s}k}us15&W(W~%k@adN=L@7G&3w-y z3?htL{NM5Q8Gosyb=Ksk#RT^hA6}UjY6mJFxK0w0K-bf5neivH#czMpDxIusCi z0yyaJ0eqj5q&U|bbUiEocJQyI}B@^)) z&*dSl+VgYL6V)V=j8m%8wBscGgvW=g7*7^0(R6FTBK|`G5fpZ?Rk31DzlOeiM}jLuf2lH z6(3Q-nz-3Xw*XTnFoS2x-s3y#rcHx#&wG=-MXICG&;Xo6wjK%|pxFQRkh(?pp5FL9Z@ET&LOU%vc(@kxNqyfQWydVZL`ks< zBOIcPfM1_fdZX2+ zQ77t_9Z}!b8BN>u0R@-R8eNOn8r}-s)x1-BWR_*#8NQ9K5Q3Wx58;N;^b}IC_(6X- zlsFhT2-CjYllW^GgwTew9#-Ojc`Fz5VFD6<$SD6+FQ2K$tcd<|dBvhAdx50vSu&*j z$9^ik-Sanes`!a@AeCs_`MiSfKDyFFshd#qk=X4wIz{NdK_?2o%|F{sQgTVN zIeR*6Kna?1s2Ku^?diAcSa6?oLBC)!@ErYKUf7Va9c@&y7qN`ccZdTa7bZgAfFW7e z4-l)-cjK9~HFWC65H$BsVaAGFuiKZ^XdC2A3S%PiGM)*@jcCLPh-b=gUE;gEB zb&H-68;!g7g8!k*4LJ3BIo?RM9xwm)9YKq2e$-BsWQMzn|NJk$=T%b;_KLQ(YtPpS zJ=hwGpC7j!y6B`LX1FZm&B1a1fC;yJX8>1u@^8QN!jVf#>!f#myxiY`9{`j%s0QkWj%ZT^Z6!Kq$YqLI{*8L0 z1mra=0)QN{$%~gY<14lkfcka|7$TE^IyMBM%Dto<)qUV5=3G`R z#DVAS`IH2{0p3VH7t6nx7Ym70hE>3NX#M}K!4$_H(-m>d>&=0F)e-*N(d;KD{|(6P zeq=ya(E9y8())>qnpuF(Ouxp1NI3aRWU+hCIJm}EN)1C)!30sg!Wja8DMjc6bxvk2 z20IG|0ytDU2PzLoX|}qsOY|8K7*7{^+|Tp%DrzE7?dO6f@vT+KUkNy{wo$5VRf`*` zg8oAx?yRe;9|=&T0?i-_3k95=UuHVIzp$o=5bdNvY!=M|Nv5|u+O)$yCR^}Bgv;Ky zopRa_pj?ma!W-flCl*#v5}5q#@Kobug|&+mLppJ`c1)TErj%JPu=Y zwnYB>VG{kJKr&-3Bb_-Vfe7}AQEH78TK(R;>o|8~&ccU&TsO}`z4ye=|jT>&RQ9^)+SPQzSyE72Z^3;s{=g0H(ZHYJr@sEYo{cWt~8js1&|D(vjwQshdn(~-9X5 z?lHQil~#v150E*hg9Yt;-E{$tSN-*{N}HvK>*=;ThNHR^TGa`j=giB))?VM%Att8t zT;uzLJF)YG0yP!Nuk_X!M@sg6?@O;HnkZ%=^RnU(fNB4Ov3{hFh8-#Znfe;uBQ)%b z_R~+!p&0omvRw}OM>;_A5!ETd zf}4DrdXaRlpK5yLn9^CUL!wHX#ES-(Qikqz;7f>^%9f*42j17Ajy1!8LivGQ`W-I+dz z0>3?z_78d(2+*;2?L@LI_-HfbRHIMld7U^$R!5Z>$h*5BC4^6H>u;F7n|^Eg7# z1de6heYO!dz#Vt&I;v<~^ZkY$vR(Ol!U&-XJNA2r(SS7B&4Z_zFsoNnm!BbLGYqXFou^_)i18rSS3#1=pNE8B;iX(*Jk2nO= zmSpp=x9FF8eQ#mEP$&L6(&hY4@PJyWX-{}rfO(Yb6mtGfi!}a+6Z1~G&Vkk-QLdN; zqaa$u`kP@<0o07VHNPl$-*V&UI(oCbDBxuKT18uGRoQ7|%d{d1N-u{@ zOdtM|s*+}n|F8Jl6tJ5w9lGMBK!CCOCGc2l4P*nHR?-m|#z8VMxe|$y`VQzU7`hke z9<+lIJ*)tRm*^-qFp^0V3Fr;LQzG9Lwb2$@MDt8RqBTdbWLx%<+Ty~!Cs=Yj&3rJ( ze=}mIczw&=vl5d7uMNQqCn}QiyUrcXffO4&Q&tSE&eES9tOon=jQ;t%p7M(Z7>)34 zMs=D%#U;k;({P2x;@AF}95pWTB5ca@>JA)aPx_-&vt3}_F(-?Y(B7Ysdv&U>k&pU( zL;T({*>E$a#wk&VUdWcGTwWsnWZQCHl82a)mh(zN!!k|a3rm)Vo#*lbXXeVHAu{xs zC)L5n5#F%PSzNd-p{+(Q2n#ro2EKMybnA|kwH_5@mMC$oQ~63{B;mk$fRdh$B5Q6$TsHmA0+{-@(sjZ09v`_qCf_MRVWK8g^NfJZ% z(|LoLE*l=hO>LMDd-8K_pTkr?=Tb8D=*q}6pLU30njO~19#71C*Ec|gvdfVP$k?Rj zfWbie9YlrrlJn@&m%sJgIA88?GwMoaHLlQ5#R_k%v2m;KH=7JnLnp2&jt;{OA|xLj~>N?88i;LZAuMu&UjJ+iMVgfZl;z zguHl@sIW1C;r_m1@yP5@SuOA`h~d~z>5n%buqYbUr1+{v<@;h}v2r?Tq&BDY5fw0r z6bdl-Umk?OMGk5*X$$`N`=QgZv@jiI2wrlZ@q@Mu4!5f4$KAF*8f-Y-FpHfv35cbO zVbJ3+MVvG}nnfU5qqD$9xMqCpMuL%?l#D>T{b{HCpQrV{%g9w!FY8cg_=1vPDE=xBPsYjjW}u*G8(>182Iy>{;*=;V)6hFiG{AnFJJ%W z|D+X$tHx16H(&CF2SFk+ZpUyppEwr70xSgu&>0^-U~3frJ{#XkvGdR$JC;wX1pJOJ zi-&r$W3klnKL!~@W=Ob0h}zX9A>B5+_^Td7tZg}-%Q|6@H<_%cX=L1W?ZlQyqX`qW z$k;2w@P^nV>4qb#c;Bw*F!>X6ecav`Nbqk+nJ4O;Xh`>wVC|+d^`7InzvqDh_RP<8 z#;eP`k0(}G7Xkm9^rT$B2t7qS<`dv+3DEg#m%h~pbhCNXS&F8iX5jN`8VfE*&-1w# zPvd}Y+6$MKz^#}jIvmOcly)cxG;e`cnFPh%)oe=iQPB}v!~cr0yR>G4>OG({mQm}9 zi=NGe8d8Jg8E`sz>1M!)mF@eTZvP;_La73Rt9yE`h{M|sc zDcTDd+ZtPC@^OIa@HhRP3|$OCfT902r$kXX@7Q6jKAhzNk8J-yrs66deLAn)n|DYC z7o=F-h>YsJwN$|Iee}ozVBkNZ!lVIA5pHt4olh=2qOQNno0?`B zFH7(TPm%QPYipf%tEOo;)WtfAcS!b9;vbw*js&G%DgP%kjV@yLDbr({RyepalOUag z6<&V7S_T$(OLc30Q(0_WHfuNI8XP;-arCs&j{F^!x9_sJ+`Dw!e89;Kh6SYlIYE`P+S@=TMLf0cep8L0uN@)?*~ViP z`(dl5i#AL>^XKU7w>r3OZd(?vsYECmIQ|H;&A=E3FkyR=2%&C353p)4liN*+Y6eK? z@Ima(^#bUWZj@2qi?Al*47E!FwqW4m2TUqXE)Ym`!&yI7 z=}`LstTTN{wifVvWm2`Q>CD`A@zhZET=ip+)-)(9A@Qnv>j1BY#(jO((u<7p=IS$? z@{8}Z*MBXt>O7gVzP*3r>=%Wp#eFuhOv&7mfW?G(B#8x5LlDObDdOsI%RBr4NleY< zS(c*|HV}HPK1ee*SgVm8b@hCzZ%uybV=wtC@rR6LI0Q)0`P)$m1Zz#<=V_%l>h;GFU^G+76hEG^JP?%A>H@0?EmZAvaSeh%F<&X6!k<*Qv{ zb8I&VI%TiszCTHWT5tszoBZJANG^^;O=f7a`ytcN9yEsxl{_D`* z@RjdM`Z_%iE*1IgwR#mL>BfoFyaO7>{D-2TC_$HR`8tF=bptG;t<}A&ZIl7@IrWC4 zIww@LWIn=#V=s}i#NJM%FN7hS6O5}Pp-sIkqx8gAgYw3Ml^wUWg^*f*S!UyFaHomB zSbm%wq%v}_gLEtZy*nHaFkQ*$kGZ@Rhk;Bs*IAa2c11IzailOv;;|oZXE5{SV1Cd0 z_X`5aaHP6V0D`It9U!tDSo^PIbNI&uQ3lZ`uptu&7uEU9Mz!M_vU!TExDud%;qR>3 zUuvrb{F)@QZ3trJ|4_)O4u#hz-$#=$>y{n>GH$X3I!UYAmkkhBis9HiHw`i%0>~P$ z15)|{@kB)m9n>vUgRN>rnqF`8PaW_41&vFVtgbUX4k?qBlmsoGZ-smdg>ls$WU)UH z@HvS5=RMuM_{-W^Nc&+Qry)EGJnO zi4D%s=+X!MH3dJvapeXdBX95j|5O1IA^)C~St5`+Q|~d?w6s{|^M3E{^Vkt$?m8vd z!mhDi0wmHgAe)CE=D5>lko=rV>iB_4Shxik)-+v4oNzZnIf(c*Kfog6e+CT|F7Q0+5q#+|S0jCC(t#{R%*;2lwPP2I*4C_|K#h zVE?%hr5ij}@_A@Lw5TV6AEZ@^KYWG|s!BnkHE9J?&!U88Z;~?M+WC0ZkVdSE@O{{5 zd5MItYf469)aZ3O#78D$%}48>A*%qLvplW;G`95GE{bBV)-|WK9dGHX5|@_~Fwkb( zq$v-u;vlN&s%e4oF&P_`Q@4vUYmocCSPGTu-(JbnM7a8q&&L7Jh~>6cmGgwg`GX@@ ztFMKd7Z_cI-V5IVE#hP}s))llO{fKmhjS!`AdtUm%_ zaz5Ya_ROhd5M3gAXVV3si7Bk&X*m>ald|FG{)Ehw8|FY~3O8<(PrQLUrXC216WWpW zz71Pdae?MPdvIO^c25Z_YRuP~B=wP{9z^KZbZ<&NpW)U?jOes@fLWW#&9V@F4qTSkd2mqkBDJwV!)=Wpz4^jiNM#r^=2iW7Aq6V{0;L3`xRE6s zK6?}ktkMedx$)J~gFAlU`N^e20Esy!gn^qkdRxLy%o_SZo&#^i0um+$ZPtkf(nKNq z#t)nnk2nSZ5N}}afo;p$NjPg=B{LORG{BK803pPgZ0eQe^sH6AN4=eU;o_+R+#riR zAgI)Pf=|u+W^fq!p+3!3#y?^fxrm5zf!G-&NH$4*j@7@P_YVMNj_BQHPR*g`Bmng6 z*w7(hH{f^n@0-7+c<1vZCxUB2(w+wbCaGG#He$@s4BtTj&q(K1Lem-&#t?(c=%R88 zVRekm)UaSR61`oY#n_ZW_stden=NCT=vv)eT@`dKCI@Rs*{YK*T;AItb!sU56<{zQ z#y~b6$u}CKa3+FLhZG!J>gn!qCT$2Ir`!Pr%YcEWlykA*OxX%EH2tj#>H|95jcQ!H z?rX2`Ktzp$5mdrpt;4G_f&TyNEyg zEoPo)qXH08vB($xC$q3}+K$W(VFJ?E)u}BTCQq#GpY`ymcdrJ<8yvORUC&@|8>aY7 z7kppW+UKFG&oISD(zge2a$JK&r6($VY!uCQT;f>_`*B@%b-Eo^S3OB=@dVr^i-q5r6k564_LjAzhl?jXjI++ znzh3CpF_egN@altMZo$ga=TwvK-h}Ix__CBy%<~LEVUAKHivi4O}nAh=ZK!}j?|>j z+>$_)o?8UyUv-Dg1qyFmlxo!i0RcuPbk#Tg=Wo|_-(%|EZZ@VxbDhQ<2;3LUna!+z z0T!kvOWTq62m0r)FJaqp2d-NFal6NZ_z=$GomU}}_=iZMP9{$hkb-elH!#mBHt|fz zt2zWF`Z@5JaQ{NddK=4sA+XnF!oS!!|2ssbc*9jJ4*~P(d--7}RJ+x0Y;jm*ljq{n zh)wjc1^JwCC6s4B9U&z$Z%pD<vD)He<+7*LfKtG@sLIVJ774|=_!V1hy zk+Oey1|df>0-+bxh=2p;#HGO^BM@;>Yn)#lM9sEAygh;`WM?xmS{9v>^lK5_--Wjo zWaOxdzH7#ZW6_6sTf}U6Yci;fm$rv7HKsip=R6c5yFELQ>m>7NK!8k2*eOZb)6~2V z($UA9o{I~v=P=gAs<+&~Q1j8hFE6LdauAdKFM8C7)uf_I{Z4ax7h(_}IY9p^FmZi< zLgexMAoYhE*HRvW2OrXoO*}#l(jZFW8YTp{E!0$l>cR}+lIu5k+eLh)8(0@m)8t>Y zZ4t6dPYpHr!c5%_&Dj*DDvh-|kpT4-Aoq`r1XL4*S{;%{k~vB=8;|ojfI@G_?4`vk zsm1S%yS!@<7ec*IEISNZR5wW^l@1*W!-O6cRE${;>MM?7bh{oL%pMSi>-2THApwZX zjLr}Kuu{)Fo_cd@0NAX8=bR((hxb+$=fJP)XIb~hj*^bIxT2cQu1(WrkNaR2 zl5%CpGV4O^f9D-eMu33tbcECWung)CLRDxObK1T_Zv&S$9A#R0APdV z+Ics(&2dpq&331Nar-CO8L*x2>)&`L%=({mFRheIo0UHi(lBr3xx`M;BieRVX4=kh zC6+MzUfXR43+#8N2`~oxijpRKjBR;yz6C-e$9W%d_~lKwC10SUF+b^i;I~c}M!Tq< z8<*JK3xW78cp9moL91O$q#8+Lxw0MJFC+d{IdC3*k_5aimWkYoe;7lg;`JV!g;4^q zC`*ZsF!?RciyEoo3(=!lXif858$#PCY$$kBE{KxlQxVaMOQM*WrdWV7Y8fHgn4q%? zC~-E<6CHGMwNqv~oU&=1l|nZSg4opf`0RiUW=$f%LgxIIek!?2lcWxx}4zvmw%ck>GChm~(fuJR}0l38ZC1_6@Bk zi4k8<m8boA@^ou`MTuO|EaA;d@{)h=UFYkItoV0BQN8f79#Ivplwx*RIPo zWFO*K1Jy5((pv~1$(}B=mFc>ZY6G#q+-N~zF06ETxOHmbwlPSgu%choFWlM|LF;Dm zElMJ8+AJe`F9+&KLYopS@wz5beT7hirwvvjVs2r-%Lx8@W>8cFct|-qv(2CJD@3CY zhpj={4{H-gCf?kU#eLA0I*JpGtSF5*7mNI=tgEfZG`LgV*CkzSJSynH|KQ)s0&L!X zr$Dx{y6>9($o5d*)>YqDW1qok-xf(wUwP2Cnk>Orvnsbhm%Ri|@)oGjYjQs%Q5b?! z$99eXQ!w`aZCo+C|51N&o%>$dS#asw67To=W1|g-ok+E5+P?fv>>#51Vx*DAnKbZ6 zG%so`qu3-%XYq`+gS^OuE_f5^3q>}e4kfdZIcl;YU}SXa{a_UnsI~X=qM6h+-4^LY z*rm&IRX11c({Y|lL7wblK^sq~!?+jRLBB_jDYAdVm}6_VA(Reyd)cWO9o)Q0O{B}( z2dGZXb+VMIRA4pXzu)ja(AYe;7)o$O%-}+V=$`?WD9w6D?q_G_OzjI*_zzzwM0`@N zjqXdIuW{viB|$u()w|ccQLI&dhMh2kG4~63s>6FvTKk-7k&gFn9qe$ z++}Z#H@`M@@Ct5z12V77Y%1+Z{YB<1m)G-sBuDROK@Tww+p)DApKvpoe@mlq7X1R< zoY@K$+d_kCR!G-N@3acXcX1JFv2n44NTEGXlGqY(sT89Q)Y+~h7lguOW@nDKGOR=QAUsKh?XPTHsae|=T2H4GfBmTwa!bfG%mC{#UOwkW}P z)If0b{a%1t8L@u9Fesj?fT;3iR9D^h6lR5lgTrV<_0J(vE~GUx{?6O&=>gPGpbJFNl3Fg3P3c4{>#S0}Cq_?h`UFVw{OBLF#Z z*WeV__F1Ict?`$ywWig{#bKK-h7nhPDcxz-S!g9b(8C*PDMSwDG_PFN9shU(sSS{N zM0n8sgqhgAT4V>DFVy8^Y`6<>ms3h8TGo-jOPoi@ijx`%XsV#pVa9mEc>GJtU5iXK zzJ|a~Q*TQG6!yo`e)>v>r9)x;tf~VbSuUN%aLsm{3^0|RAVNHGPa$ML6v45}7?0it z^kDW)v_&3o9v#!PFga3+sME>OO0RYnq#XA)+zdsE7pOG}mcY}T9y!@j0k|H%wT+R+ z_H8m1QzMx0gk!o2LBZjsXs zBxNFQ;4^wM-6}P?anv89InAePr-2P|;QyqJDoMYzD^K;zR3u4B-Yvq+sex!50kG`~ zme5?rWizE^-iM#1*(ch-hV0bJEbIw6t8|i!K4|i;{j`a#;OJLf-ysD_Sz1=iA5lZ} zd+65VUw4265!*ywTRQal5A#K(WhDirq8zvg+nRUTZro+`*I#{XU$cGOq#@Z9N3Mp0 z4L0A*kFCv&K7YQ;Q4t2Tt?av+I<}zHqR6%ls4uygY{i$0(6uoIGn zB8EMpj9)80_nDW@3c{Fu>t0Lz-nG)dV(L<_Ggja@)oy*N=~3V?73lz&Yj2?9C|i8l`k=d z^;3MV7(mJ;jVpJ-ZjdH@9;T^x`^OWYq>01I{RfOto8=K*|WETlO;)NW>B($zj zNZA~tycQfC)J|ydaJ2eJ9Y_vV7JXmUDqfviHcmRsEP~{d*WnZutig#C3iWWNZ7kZ|gCr4@KNA3<-vt77d2J#Bas4!+bGMt5_$$T#7>n zF;T9k3fCbZ>U&+J0n6VgJ+)0L_Kx*-u;k?F&06xdYy%zl*E1D_ZLf4@hzJx*hM(&e z3|>Lsx5!NgQwHW~#*XgQLY2OX^GOZtC7a*RBU&H`lET!G3PIM7FqeJ}k;2(0MFIEz z+zT|*7lW6PR3f(xF&K$wX+__f|GCNzD0bo|nwJZjBa=(vnLYtmbl^i8>Ss85Nyr^a z8vM;9Ql!Vh)7G}aCqauLK`_Jk9dLt|S)JPa(fP8lQLszv9tIfJY z+2X(mf5W;ILI8N}5MBYmTlb40&)AA_+^XwxCWKJS`rJKGg|*}VUt{i=ANUOcbTKTk zDwF)cWv#e5UMx>Rbd1Hi4`hT}ceL9IU{kUy!)K%mQXz=?3zQYeGJ6yu zQyPd2_P4h`-4g0%Xum>U@MuKpjaew=LDde9AOvWln z`=!%68mf7B*<>Z~ug3^`5ikDj^D134?|!Lf*sy$S5YyTeym@Hngq9~g)n-XIihW7v z)G!P?hti@_!+AJ>(Q}e>1D35fuZp(ez+Oatv{f zn`2%XCZp{B8kyI&MkL7)E@JKS$dE5RcA(9@=H!PxIEY{U6CwlWt{$^>R;44(z>J(F zp<}u@NXTbRb%=lrr;zFb0#2$m28mBarH3dpbaa6m8;ytaMhZXr-G;DqJ^Tk6woKYy zU}WfJRN95+{+JpNfCa%3;lR}X+rnaKzpQ;;-u1cj>5t^ZmFXaGbg%##(-YT^XII@# zw;#l6YNb+vqL=?13Y)pp*MHxwD**Vb5UC4pjmRfh^NsBH4Y!J;qhkeTURQX7^oWsd z?0Rn>k;Sp2Vu0^wX=Joxi0ZZMe32uM{{aKQvb7Y;SacYPRh#6-@-OFH$fWCKUt)V%hsP3o8e*9jl?oF* zXbODz@^#mU6yDUAgS(HHQE5Ee9Y=_ty?=S&DV@1x(7T~KG*8gVvOYfoUv1eWX*IWG z-3GxVC&aeZuqDum=m}3fxJMLK(~$mb+8kBEQ+cxgpWQKgZkgm#5rs$2%U`2@0&Shr z-tZ}6_F!J#SsgFiB|xNXDLVIr-pdnH0(cI}j@O+}Z_yrWmKDw>>#5qJGRRwc_z7ah z2?Bnt>P~QCbvdj+GctL0j|0>>OvLL-b8H%bAZ!YTm(HV%KvT!}de(nf%x}W1 z(yK&$&u4&zg5xfiA@f(ZCMo=G!U8q(jUDMkmOAAfCX-Enl;(`vgMpO*;;K65p>Zy{ z_h#-pe~&0jSw|M`NTlEA>%e4PEry}QR3{G86KFKlk^pSB7mnkz47E>@;wz12!qxy; zj=KLVy>xEzc0!&K&uQft?KgVUvHMlK4zU{{_kV58GzYRTk@&5gTs>;FEB{{q?Kp1* zY~*TdL06cKCBEa-tcoU?bJo>|k9odd$8oOn|5KVKAYu&?Gx}BBlB^wLfkk|tl@hl3 z300n9iGse>SUdxU+&gnHK@tt^U^k8ap=OYWg_MSwogV~cHaq5HL0lSm5i<&x@du$q zcn~T6>Cf~HD8Rd1C2xP&X_3+V_ldUtMTYBp1Cl1oThG%s zO=E7|3hXm*`0MQpGEJ9BA**gH;rn>)>2aUr)TjTZ!BvKI_yuK62+yu%Bhr5;nX%gY zzRgdx)PB#hf`MCWJ9ojQrL{ir@9YunA#ySj0zScEf4SiE=%0Bp7ENYvL*2x`_uHr% z3%cgBWr(nbSJ)b=3%Y63WMEVQ%~1qwz|3IIP_NuZFP1cnOg05GwL-bZwdR7Sdt(BQ zIoN(U59dtH+v(IzxXINlrk^+@ZI?-^u>&lKMbr2E_d;Rgxd@S$ZB#Q&=8Y=G7EQv} z>1-?AyDCO*5D|OBwOX?>p+2S3PK_`zAh}~zjzskewv8msd=qvHqs2Lb2x@A_Wx8DB_+b2ZAPe4 z?klF_nRd0JVQBz{r5E}=t>>@Y`J6f7GRA{Q*5$+DMe7|t8NAalanwZDr5SGO;1?FM zwqaw%?Uh6Wv|2$sKXHlyvdepTo52E>(DCuG2|OcSly-n7wLkX4CIDr@#VM2bHX^0MtND8IgFHdvJ}H-BjbRM=M_!Z;F7b0XFjsqEoOS6be`yS(R;T^t zh2TR9KZ?B?^|)NVqreN~>UMSi9)n%bwGIzxI~|7)vL}%)x@<(NBXm}#-IWRej{I~x zT#_;6C;?ixsVti=^Ec77)>OoM4UUhb5 z%w_Sq&kw+XwVhrI+Up)+{ho!+7XV(`jHS4ktBdu0%)W^2H0rFe9Vp znpT}KQdVt*pG46+@2i?x@3KflhEiKRN613@4)>XvJ%6cV3XygL3EQtLT#JEgjE!4Q zPJE163xmSHxL}c6Zl_L#I_7cF;DtQ!nkN_GUev0%%yUBvUN)uEg*7|SK|w(4o%yOd z)z?VN09Q1wsy^U;qX1wY-kK}>6hP}jX$C?L#R9~l>fV}m9oCt)T;2`sg8UGO{963f6>7)S#I!cI=Tq!vB_me z;I`uVM12Tmf`eV^ON5H8#w@#54<}fF`jEjj0i1bhHlK#*_)UBBha3P%H_;y}gX(eG z(&P!i3f={=<@B+BXeC9nkwl(R)m$zd+XrCQtm}uq%_&`#mF2E8PW(0wX(JPQKSs%= zWcviz25p@zNX|h8;I`zqVE}sj6d>*n8n6K0%Lcw!_R`-%s4{5mgK8WW>)J$bRkmxOJX|vrwzf&S`|6Apj~t=sT=kTW2_IJ!*!%ik-3G zKJ5m!xf0k!hWR3)a>u3blJLju_0miGl3G$n8h3xqf3n%;MC!9`$Vz)E`X$M}601Zg z0-q8P-syrPLtc`@JNZOBv&*ngcc|27?;PD&b`ReHT~>E_L#UioX#)_I+>l;Kx^Bk$w->gQs@ z7abv@IJjJDA%TVe-m}90-m~0#GLW;%bdAW&KvMkGG3s|5YsXd~fS zq!!i^cRbW||E~8HkUQz(_bYiCv>dSvX;{lo3@%Lv&6U&S{Cb#{suUTuY~z+~YXCD- z`}o3!q{I3EHVKHd#siLI`-i^c)1<=G@1y!Uz~lEYipUQfTkEJ8FCq6?0`UanD}3*F zQzuu5`$Kafk|qptDtYo;WjhCY5v2 z)3C7VchEG?_K1WQ!1$(8+v<%4&DzFj#os5q4Sz3>Ol&r={LH1G*T{SSmmq;VW77f+ zV;S-xlnpu8LG00Rd_43s-S*LJP)(f{o|O_$eT)lr1*1iimWjEZh~o|D{+)(fR?Pl| zX=wRCi7XJQ%|l5Uc?qzBBSX$`FWheo`VPa)ljEXA%g5mF{JU!VK~znV&UxCtje7re zO4?z~;ObXLl5SRw;56D0WR=D}tJdRoLlDW`wR_ly0_2YOyMcooD!ZUW*PYD^a)y6t zUn9b-Dcu*US3{`HFkfrGna~y-r?(##*(J@GB_T6+8IR*`UVfMN;{j-}xdD6eq%~_C z1T&Yh43|}Re^jOz2zU^kWI#H09&atfUtEQG{*2v)4&@u@Ya-x&H00{)u7|bmTfgbQ z84=sgrXkKF_eMtwvoCV@Xk}^WHh~}sU*0b_?;m?K9tTiPzmT^KmfJNdWm^ou|0;cd zRB_7?Oa$0j)gi#7^g5>)D{IEV=zZaA)X$9!6LdQ*43MoquC~KSKDr;fE;V{y7UEAW z#xz!@d3FV!>&F*+dUBk;4G+tDABlfwe8+}wM3!=OKKM)BC81mrBLxX^{(L`FD%rw7 z6xY3)W)E}|ZS%gvIHZRZB@KhZh|xQUo!0Y8aedlnMpOuZ8o$-4+|4n9)YYk1PSDT%`{#Q-ChV1-~J}QcI#CiEvYZjMi2A50h6tl%{*~fRFa3! z=%_#5qYo=$8?N!|3V+q+^cm6xFAe~#;91-p^p!L3fuvMdU<&&H2GRQzMYB<$Trt&n zWGsm>bM~uA@^jAPUz9#xym&niXLen{`6~ZYS<*&2ly|(82hQf>tz;UvTajDjqYjVt z8x*K$aA7+@U>E=ELxQw=^(dDE2GDwv;{kJZ@BilN)jcy@oOY|4j_L`K?}0?VF!QfX zH4D>Ft*4Sfb{-tSp~fd}wh3iaRYvUF)Fh(5W*zd(bN<7yU;8Zpz9$y3_mpcdjA-u%bx+SySFAzKW~mFTOvqB})5$2EjxqgTqw> za?n`bLjP1V4Pt8-`E6M#{9Z=YZ^UYF90e~BC_vi_e(3jBXk0xJ=zA6P)va6FiqBT3 ziV+q$4mAe>>oqaWr5{WxVbuHf*ElY#VthLy7~Y2**D(vl%u|b)kdGXv&={qV(vu94?!GFcML_{=uf_(@h5iV=HD&${sW9 zwiu_Ge^t}d(cCw#N2K-q?q)eB1^nvD_7=$vQ$og_zansJg)oF64^Sw<$tAA{wL`s$ zb<+wROCDMrjnUvl2@jj1Yi}L!ct3VXj`EhQIZrbVqp;d}*xi?KFQmp&-%XgS&s5`f z3Pv=D^@gLbZDTB8PUkeb0nn8xQA|(XO%#%(m~lMH+Wq>bEkX=DU6gq@S{Zz{y!B>N z>-WQeH;Qx-DUk1`!N|&&-?lRY8Xm3O{~eui>~g-bYt+6zQG6njT>PRsA9cfTmIfnT zFS!UPt5_*LuAv?4mKmGB2%eD$Z6=%Nz+7Ha(b}iA0t;gq6+BC)bThIbatlRL&KdB! z>f@|F^#N|hL$2FcJX`WRKQ=wnEM6Gx%X(!UBsF$8x>9wUFF-Kke?r(BM(lEa8r2CN zX7yi*etbLvcJQEz6DQ2F_6lshx1ElQ*23=ojn8-I(1?xXS_~NK^G;_$1(W+&zVaM) zDop}#^d-BFb1pojFK>W=DG4CX=>rmv4d2&u;=;Dkd(%Kv->ZB+vsS>Uot|FvI&+q+ zYqU)S-TX%_&p8d__9dA5?H0fRbDyC~jC>@TMB>QfbkbG#E8R6THHUbQNo=|L`k zB&vD)Z!C@23i#j_|H1_=BL-OHSb$hFkXY_835W5WCed)r+gLES#J`T{oLOf9nsT4s zSTf}F%Gk61{4h8DlAp^1-v;0}LQb`WIA$LLU>C)X@cJg0PB94H5&%nI=VRA~3qf9j zP0ATEUtAk2$7qBh_40zw@W{lPW9FHyClJO~QDZXpG1D%Y_^_Pm)y)U^IbqV zHwx$gw)gyh$ErqIG~a%BQ%PVEQV{i#h7J9N1*mh~QC>P<28N8@-wxGcJw~J-iIQt;C} zn^o(`YX^~)p`Q!+<*_lv4$`Za52ESg>b5H)0yvA+g`~icSmx#N z5^FoOMSqstwdk&xHN2kNBVuCyR%1pI=fW0)Nf%TRhtcH6;j4pJz2^9VhNY6j;MX##J7lJeuOd@{Arj1$N*1V|yA)sEfL2-Eq56qalE zQ`W?AcQEd4hiCF`0#Q$d%Rpgs%C(%#rva!9i?U&8`+v|!+!`k!E%Wi0rvOnD)l^tj zMcat9Q7*zlB%KYcV5u~*3A#J7oLAf>5fZ!%Y;T|iBrm0Vxfm6g%{*`!C=@7HCx}sy zKe5j;*anHcF9+pMI{U1aMM z+Omm@OQg639g0J2nLlA4S?r+~it!KNoFhB?3;ccq6AeQHKu`1^_dSN87S5HC!t-(H z4yl*hJtCp@`|*8U9RmXflm$(WoHvv<>^!xsN@)*m=H!Q3v}bP@BBlZ#_GnB&^cQWt zr6WR#hH84sTYR&oF_CmEt?ENYvl#;I8b^-zy%E!dipa`3Z-uYfR+<7SF2QVZ!TZ&e zbwQ$khOWlpXUT1CUJcXb75ED1SMXUyYwW1Z#0=S`;k^*z^pugk*gFeQZ%3da#7&e5 ziC^Y!(!Wf7t^_XOe4y{!r?`2KT#eqUrQN3A;8RnQAXT9T)Q53)%^5+!Kdcu2&Kirz z%W>|5fV)XodODJnQ1|px;+!wj*%ZKg4rp=zzC6{9SG6-(8^Z|DqN406dA|!DA`l zc@k^<^D2_aVBIpmbLdvC>A#(IXO*F{&mgjfh2T&cu!!`(8Y6b>cE>7N(qj1x9Y>dH zBw_aP!wrxMXEN5hGk4|!;B3&DJ`DzEk!9LkW?|qHz+niwBA9s}e0yjLe>y7q2b{J` zO*1D#uvW#i3}b4ni_?+4WnG(BJi*#rBh>Q5_rF|lQULsz?_R=`HnpvClSR%Rl@&Yr zs>cTVpdeD^Vi^1$(x0ioC#Xy@NZg$9z62NERlZ{7F{<>G2XYP4fN{S9HdO!9*CXk4 zpHdp(4%5clnR|)+FGtvGQUq9et5SzO$|3Vq7&M{q2)#^;9vfI+(@l)a-m2NST$C+j zpRM--$v73t2zxEf1lCNii8Pw{Hl!M7Z=KUhOIGiG+J>uqV+m5tlT>kdtq1-S`4A^O zz6lXQbXIqJi17etR%%z3RRckYAhBt11>_zNMz zQJ!f@^EOwC64j>Ii#>5p2M&#o=L@(w5EIj&P}CSXJZ{iX_vE*G+Z`^hObg zP;h?`9sMB;Z2-{iV39l*F!wn{4(*r0<&p;EWyd`5=bb{AyMw_@p*WaUpB;kSX6N2l zz#-Q3DOhWAZu2FR7F{4Y6zria7G}rNM6iw53kyU>MZx#0+3X+4*u6b^ke82+MRNve zd8v&{Q^ye_jmGSFV3KWYhgk=Wao1Fbzl$QTb>8iR%9;< znvaO&pNtbo5^YYmSS6uvK@GxW=wS!t!Zq}R#>EFMydtQ04BoW2@nG1(8iMx--8N-P zSY_5jM`R8#pZ%D)<_N)_1h*Aa5U@9A?WU6V?|&c4nf)86Zg(SBC@7)6W8w-K7yzi= z>qg+NRy+CM>h*u1*u^pc&@&aJygNq05OEo};QO%Vo=D=MovOblCLMqZ*(dmokV0x~ zI>By|>C}93n)|e^QQIa6%%cL135w4qTRv&|0C{WyPFvjG zB}yPkBi3^>4%9{aC>}ES`x2rQAH`HjaP|FL;a{yaW5*?QtJv@{y5wyYnbkTV8!ck(7s`P_VC9( zn@)o~ae5)+#ZS_J zmffKryV^EK=wn6lVH@ZZ4|MV9tNot?{WWh^scRiEs-V@NQpM|H~ zerCW+$oGR_qxzq19mUOrY!mj21A^DlOR_42p_^^AOwFZkgXLL&Wy3iAGg$59Au4x( z#B$Gu`SV!kw(K4hu z(^rIu1eK6o%(K2b*|+?QAQGyt@5k=iJI_Xw%zD|&9#qD8wx=7OEP$L#jj{D$Qcm!3 zQ}<3=YMZEr-U+ff;8ah)?*B95Rrvev@YM|DWY?nc6>&Cygi7Dr94|DUyOO=B?fqdZ za^wO8VEtSyVKR~z6{{RCW50ArFxwu>8J;jESLMSGZJuAc7+OEkG&InPoM!*se7{*^ z3Dhy0(vBnX#n`as?FioIuWeHNYTk#;@CJy;XH<5S7`xs4MT1oKbqj$kUP`0Xl>8JK z617NhsrqW*=RonU%ziv%Uq3re@b@U-@juf52Ya=Uz6`|&1juwmNpthdr1J|wBgl~v zP)Dhzni{4M=tI)MB};GQL5=7Ng4jG}ba8z{65gic{Y9|{k)tOZc=N9da@yU^zSu`0ZNP z8lo7Kj}A07NKVe|+Btax_W6T1w0AA#b{Efw!mf@Ci1NRgH1*nBp+vbg`5&tMgY4|w z57W#UfFH*@=;Q{}cqSf1Ji4fdjH}+7@|PZ67R}mRCkz3QJ9WPiart6l5K>^Z5nKVh zsE{K3m1tANx^_*pBB|bzu^ma>E{E9K1R{ztG&Rj@-P|l?BKHE+1@lYUUg+vm3Q4D6hxVCw z4}+%}9Tna?IK=rR(B&PZXhk0cLui9l)W9zMezp?>Fib{h_LyPOsm%xb7j`N6@#V%NefSqE|ekdtg-VMTgdvJ zx2zbk;y&y5NelbDj*r_8#^3_`+xQy*hz|?KDj(#OK)fy@o*{m4R;APQK|W?^-*PLl zb@ueIVF-ND(DNwQTre=wCvf!d__JxUWQeU6Rjl;)z;y+1(1IT+heaR^91Xl-m*TF{Z3sy!r{4_uKr_W7JmGIxk7Qy>BRS5SjC8tKLtS zO%v+Dyd1Jgj#jTZ0>(|dn?7`hlKx0!9H(zn5>~`)ZwD56%iwSJ@B%u|JE2u{PjQlp zC<~^MpZ>SimhQc=*AYB!?0}m#+|5AwXLJ1Z}I0zxNW>>UZ-$4xxhY$+Q?2_ZxaUh!46$uTVnaDxD+%7B-} zh{AbiIuM!i%T?~&)WKPHzMYBg^m;tGAE!ybEywzVBOI(Ie8thMD9fRr%t}NYLzAX7P=w4l zsE|igr*RZK|?OQBjHEoAq0r|=m&_W$DO>@QQLJ&k^m+q^Yw zG|h%^&-5KsmRvORE7(bv4z`AFO|uaaYxv4*e3wS;-!XvjL{Y!!rO(TQ^8PhRjHEHj z#qPYSHGQ9QN?N6tA=JtY zQAsZn;2RC!UB?cJJFP8O%BAO4M$|=EsT5B|Muk38*z!H*&~cA(tup$WZ?mGG<)2_K z^dKxvc_`yl%Bl~x!1~9CVbmgR1(cJEWvy!`auk-z(f|iN}DitqWy#3(&?D1z+S*< zwa<2KB~A=JHLqX8fx^y3ZBBOH^OPlX>#E7SA(S9+ z?}iDDoXPXoYsZUXEpaadbsYg7QNFm}{na`xgF5HCrJk=wS9bva&=a_m4(B8%2NDG6 zlnJbx5x6k>ES5_>$}FQRHLxL|w6CDWf)Ts0(Ou_;gc z96tfa$9K}?M;@3BY5nug1e4dcoH0W7Vr?9wctByd5T{8XPHfVxDA+&?ZzrdHvGYui zjZPbC$10Eef;NUcZ?J+8F>P*x7n|Y!6N5mipL_B>xvc#Sh5e^jO$qSTHwtK5mBt znpoW*t~1A0`?%}P2*~2rT88=pWQgE+i!giLNi_fEpK2+_@H27b$~E>l+PNzdy7fG_ z_#rIFekvK(yh~(8G;K7H2jx=JWuur2{lnW@#F*I~A@KZrNBDmab<2hr8!#?TX9HRT z08GA#aw*W^Hr!`0JVu%VMxroM$#7wXU(f2&BuTXoHxHn#Li33 z8V!Bv0vYnY`ReTi9M0KwTHl+q8nLF76YlK~WH-&wPbwgJsB|6`HL8vQGQI%2%-uEH zx|vH$ecT;@hb_g)JO#9R6RR3dAY0*{&@zVd!JL(Ys7*nKU&vutvF)7@|HCU12JIXx zT@oLTnq_%Wj38qmDH!S`H!h>~{RS~fI*pOtlYPNor;vJqP>5e@4kCpH7(B_I^75O1 zIst!MYLkWk`OE3)>BN56Ve{7=a2ymEJ>flcS^<^#CqTp&$@E2d!NO>V=kM=>u}A)g z)fce+qv9&}!csu|+OsS=fWA_gzh{t4g2xy5(6n&wl(jiMxuSE}cm$PUfp7~xB=V?! zD^*045U37Y?HFNu2j3a@3LqWRJXF;UU)T955H|f8Y{@MODI!^jIArtWhs7b*$h^~_ z&NN=rvZ3*ij?&rUiV5e;^ja&ITjO7iF!}bl7u7+Tc7vq#Ragu7R#1=FY2R;R`ghLtu zC)p_J`i?{q(@L&8tS-ZN)(@+tjmToK5VlI2ft&uYbM4tQ&w=8NhQ=2?RR5DqHey_4 zLh%BiQ01DFk6!^JT=!8TPr?7cKkMW9(9?8fD`3Kib#-yb=NQBi$OmZX-Db--pGR8s z0BY(GMdCO+GJ0`8Ag8~$DGb~7cV9BP8pXavE!;SNg4<I!ee@J%0zBfW+dH?CtT}6Qz;2ZoDm#H9Splvtsb}o0t;as5h&GKi6Jl1Phod4)qGv&?`M2au%96-QI7LTy^%2J=`OqS*= zlLasRDla!OaSL$)evs1*u!VfN!Kbl z+4fZ600z^Be<}J7@n(M+0C@%_sLg{o@~S?u0^!TwGcIE~aL_^+g8)=}=W@qY3x6oDjKk+}jj7=sxf`8<8Vsov ztKbjJ!jb%LzJ!U5EmXm8vNGi(@_Zf!E~m2=2ak^v&`@8rzduw$yumwtzJ6M>YTpBL zHIFI`&tPPLd?1(nGYP2tGXKbX{5_C;3|tCW1*5|=k=kA_s9d)dGPtij4;7nodesyw zW_b>5{>`NS-UpuYz=uWchfA6}l-MF|lXzoD|E+FZNVZKYGqf%`fyhw%-+omR_yYH zY=vD3tPHDp9YZ_+VRgl;lnTD;`%a(rf%eY4=rJ2#!)kA<=sbbok1u`jkAx(*j!$v2 zy#J4826}Fo)Jy^8FVh+$IEsW2L+etX8(YRQ`|@0VJoUw`;iEsXhnbSQ$^WYBfu!N< z=9j|fV6&mz4OU0V|Oz6$G!$j;=#+5AFjZ%$$}}#@QYq4e&#i}-tIxqRmZ{8+fC5?GWFG}7@t*&~@ykgm z{tW9~8hyT5+tz_XOmL98#t3U7q=;LsTqRg0;^#{5MV{!X*HwQh6{o%GHC2lH>?JIn z>7;lvAOOLKUQHegav7RaDLjsh9(Q4&h-Gap+U!Z?2)yzJL&xXqn{eP^c3}JQz-szf zh`QvP^#t_V*;cZM2$-B9l96IoMZDK!7Xk7lvBf|R=@uQI^nXM+%bQ}7bN>H8k>CC| z?p9m(K1BHZzTEq&zxDflzs!OIpyVNNd#o1rOpoEVr%S#9D)z0j?`ReW-Ip~q?|#%h zQ9#v6@@&Dgw+ZU3`R%7%%r>aD%iuc#MWcr|?v!r5-g8NcmdzXh_teEer#piFvS06g zTBD`#wCQ8(|CKD5#FWDSSkAm#U1jg>^)HT+2C%8F&CgV^I9WFA4LA$xvqlJnwC}RV zs*izQn1GgNAiI4d*0CeAyeNu2!GrzWscxDew?SqTF};ZI6)W<=K+@SCLI#&%RlyR^ z0(fvs3|Q1-hdXowkQmVruSO|OazeP9^Em_s@=J#AHis(k(Kz}kdLH+oByZ}r3ctrj zVtOB1wkEwe`}~79lzdJ+=q4}a&%wEZ#jZ%M`iw$F*o?rxEsMGAYgytkl8eV zpyhn=%%26Y=D>Y&%ITX#ZL_MDbbS!b4$Y43eP8>d;0TjJ=`4nsmc76>*lbhHOWtFv zB>*l4-`)B&L_CLS;|zT;(VinFKDSY`e-?mX9{xZL+b&_XPIhk}kmgD{HoI`;QZ|as z^K}5>L1;VoXjP^xUIkmbhm__1fI+wDH-4~d5dCx&bK;RV{AoR$0Z&bRvCH#Tlw{l& z*k(l{uei-#6dbhHzi4APjtIBNo`c;HBtpQPscB!0S!SLME59ga*zhP@g1+~|W`p>m zPXdQxhaGM|raZ?&hx-TSJ2FL|~uQ4~=8jd0YnU zZ9@SAL3FB?!E^l}O4sv6FNW7~X*vo_sHO1h+N_rp&D6&$P9VjBKA3g3JwmeF*@e^m zmB?2Mmz!TYO`VtMf-mztNHBVvmjQ;k8N8&zGPeb=_MB{Ne7J9Z<5Vo3x4@72Z5v75 z`+lCF=Rplh8VX?L#OI&tY!A@VF4WUWe_prsyo{O`>15Dj^yYG%p3J>oPn{TBwBF^4)Ld#SY%U9}FFWKk(EPrBW7bxg2&gs5DZi5rU;HjGfw2<;;M zEr17lRiIzMA>D$&s`(ItD62*GZ3ZtH@(nN7ZvCNs(?pUW2{&LDkt;189a@TbC(?W^U5-xYg!Mm_+i^ z*uu?H1*nlv7>B7M;5IhGn7CZ+yEJfqC;4G1kK(#U)D+ zq>x6+td$_y!Vhp&2&Lp!`4OuS%JPb1(|C*!W zTj5XdMiM5(E%zDgFyuc&yw$gv>xXW=4s@)OId%Xlg z&1(h^-S>L1yRk4QT?3} zt1au(h>=tCm7N2BGf%%>Bxz5l6RWlZtJkm*>pwjh|CYPSiUcDt?-z2AjSVY_1F3C_ zoN0;1QYlZ%r2HK1)-Djj{E9a9kcZmLtcHm4BZwO$l3fhZ5O0$Dqd&@kkU5z4)#RvY zmf5uY9?0>l?Why`+Esueg{z+y-~S!JqO?R~d>Lt9joHju9@~L)Y|&Vw_DrGfFYKXS zs%7D0i*wltcJHifFRDdpO$Fl{FgC|bVFko^6$)QCV^W$Cwl_J_4c2#Y1licws4fEo zLCkp19vfTkujgA>=w#*L(a{1hq1n{b4gyYf}nHkSj}&oP>6 zTT)Dg7TGrMTbHtD$x6&G4}UJrSs37fiqr|O;=ksg|D`|YhxONSGpX$4_G-(GuiR0m>DUGrOcAUL5PHN84p0{YR znW?uc1Nx!P$O+IG0~U5&_Fu;=!${X~rBYlA;FU)HL6Xq^E03cAf8sn7ZIapX zzpP3$K&Lfyk@3eDug6sp#AAiN3z}kOR1Og@BrUNCpterepZM1SpjHCqEnX(Zb9UY0 z>ZH^?h{}Ed?I`c$;oHo?Ptk9-xb&2@v8N-yIGXo5r+Mn=XxUN4ya|8&BLS*kGv?J@cq;6VcT085xoAHR zO9Yn2r%yLsCwV3yL&DRv-vPYUGhJYr#FL)^_>n%uBJfFEWQ@kjfbSXgR82&7iS&r3{kM(l|!%z zcr&bx>8pg=(Oxt*Rp;b5sg_G~pd1qe+;Y{*M!`3IPG6`)p#D0T7RH)Nwj~nw@FaL8 zemzmJaP_P;#^+tfgYL#SOn4uYp3v+}aB(cbA{o84HDq}AyRW)G!f<_zu);>>GBLk+ z>SBw7rmM8;oqdTl{PWZQfMb|mxW|`d!8p>ri%Qt!C*n!x=?R4=qBIzedi82Es~<*r zfC41Q$Z5^!Dl$^&PSGU`-HB%=>;ATX2dLe*=^cgTS(6IR(^8f@g|mVK5HO{a*Vw#w zaa3I_T5wqIcc9TWSmTHQbV2S*uUO4)oa&>Jnr#dUq1F~^@IQ|4few+YXM5wt559h< z{dt@Gl1l5U8d)*uI}0e8hKXe=amy4djY8x<9ALZ7J7%L+!Mg z$O@GW{1ajl#9!n>gP1tU#Rt;G#JQ=JAA#h&Y+ufmbyzzia%Ky_4T|o(nYh=*CrG4$ zd`=9+be^&#xx#E~D${KkmLO9=I57D>P_lkyQ9_YSh=dliNF(Frn-hV{#~CE5!QF*x zXS3!yi_gh_%rTFS%u;DQhlHrVY4TkyiZX)q96*&djFAVb0%L+6s#zDuF8jlUAB6G0 zekwixXE!tJYkAI@;LJx*8 zPQT&{2;1gTHSsIPH-6`mHX0?WvO`@ICXSmYu0~m$oEr3^bTTL*qD92XcRp*5-eXsiz&k42H59RQ$p?+dArpdh=rn37CT*HlS9$QP(3cjA z&{HIC`{mv&uNw>!7w3EKH^S`{`*$%7CCUq{yJnuMIXK)dEe1x%^F1zPQm3zasntwY z3=(c|Ue`E0;p1j{63hmKiu-_Fl1-7Wx>>v19^nS{dsi&kd4y55L5&@zU=`uljm3?dHTWb!#+Sh%ey z$Bvj9Vx2JXU8-V6eEu6Xa{T%5zi@V$+m^d|+bU%J=f_sncbQsK&FB5($;z*v&-c$F zNRX~BPrK%yxL_j@#XH;p^z$a=WVqO8`|5KfO{dI2?w=x{Ei(U}-O>Ggz|L1KCe-=Y zI8tncpPscLEc?AJu zh!Rut2VpRPuVzt+pXnY%J1EOOk#tam=NS2w-KYY=3r8^xQR?D~K(I4AiRautjiYBw zV62;3o59cSq);D11Nqw}Z}c{J|F^hcP3(6pQJ0YGEBSc(1*nLbB<&(ZntGc`n8DuZ zUZ)4UUu5rXqdel-TNkw_}$)G3|B z0p1!+eI9~}nUO}^IBiZZN-)EJ11LX+9(nJEh5(|$y<9OrT%pRxA;UQqYH6%bxqDY*nhx)@f8rQZ1z}yq7H>w@$IlzoFyUODk%4 zRx};UcT53uFL}$?dF&=9x$J`5RM)I|B60dHr@=}CCsD~Q2uclk!cV`67#LV{XfuXd z?Ezjcl%8O~E9Yf0U_;~oG-%F9IjD0Aq&?4${l5W0k@7b|Sa31ffowYOfTzK%>Uxh= z&dUxgnWCz-rn)wo!;hLEegD&+avo-xz6RsY!nYW6V0OJ%;WIGMMre}+)V;fVKWVTu z_M6P1Mp~G*#@zSSfOOm1rtu8a ze!T48?e`gi#|3|@Br16vPs4LE%;FveTks#%ea%Cghs4y^J6 zeC99PO)FGbm^W<=yXrsVt#Upb|JS-YNY*w7&+`)BdH;`T7#+Smq~@&C)MH}T_S-j; zNY}AjjJ~c((LXh)!T2_eb3xZO72dhYwdUhx#YgJuIx&459lwDjX@Pq~-E(9_A9ePh z^W|ea3BzP@Ot_KcO@S^WJ|ZP7?OL?p;lbnY*Db0%WwgASVTJU!MWi^DRbq$k3sx~k zQG9Tr+sw+5*mb)m0QB=T%pOMID0nFlOxlD^qZUPjY5rDBOe!;ThQ4a*9~x4_py(RJc)CuRJar}k=t}tN#C6gQ{F>rW^KkR?Lkm?r z{HG{}Ls8G011p3Bt*isKhTjh4J!4=fvW+CK-@#ZQuvFAV4`rUZ1F@vzQZ~DOJhY*# z{a4R#`N=JdT?zmjK#G|a=Ha_IHhT|iE(#nLlsHKY1?mZ38nX(I#Zw5UM-%OAcw|qD zj4rFxd)%qMibb3t?lMxau5M9x9`Lz8WUAMQ;YKX7a+TZCAX$R9blw!W|RK`(Kayv`Y?v@JjPy=fIjBfIbiC6fnGFEd4)`yD$-bZK@B2F*bGyqR9JIu zzqZYP9wNS88sci$pk`_YOaftWN6yxU9mrZl_5v*tcwLqv>X}*YP&c{qAk-4%xiTcx zq$Yolg!hP%C8kjt;%^eb2uhKx?_i2E^;`p*tj#6hR;ge6S)~vSpquAb1IuB9_9myY zDNXibxSP$16EhB4NP1viHZP!)Ir|?xU-a=wB`yp3Hbx7R=S!AQ9(U7woe_ed%(!TR zu=O*LV_*jnb_hbO+SX+W1V2Z%6M1OQC;s1lr+iAgZNLL_A$(uaCFuh&EVrHj8rDow z2xVTPzd7aiiwl2GPRl4FlM!u9>tU=e*ackKw}`h3^w*&qHn8#>)wZ`(E$r!HVvRu7 zSS5p5Q}?Sx4Gie+eJaV~d!F73oPW39Rz<*6`xq@fbw)!`Dq&~e$Xc1oh)71XW5}TP zcNIk&W#Fc=Y~821mWE;*1u}9792q%2FFZZ-7n;Of&`{{coLMOrq`rLf&wpt4P9cLF zQl5d8I1uAQsN8VSTMRRvR|vzBXUSORXNEIQqEpmsxKz6sYe_)|nI{EBu~ht}+0)S9Gq0rH%njuCd7e z!&pR(`A;5UflF2NH04K+Qyg-pX-fbfbL|XD&W@rm+G2+;o(6ew(csZptpFYN>U+Sm z?!^H+4AefiAQi#PcEmisa%;i9R_o`vx2?ihHC(;@KL3E#G$&gFU&nf-A4NyukKXOELHwROCbo7%@AIk+)b`bMq|m)1>fo& z?vFVK`QQi;dYv;anZw-QNT7QGN?F@Ne%TbWPCk_2@gq&QpP=mT^Jt9USs@pkP>!NK9o@+<~#-WWZ{qLqhjg z#dDhrPp&>}`!3gC3Y#Z_v2LDk*mGNljN$hy-usf)O5*3g9Ji}}^Q=5O*RA?6P&VCEWXA#Y!EN*7uv`X5=}UkxI1_#v^O zCdzmq%6pVCpu+;IJe*#y6~m7O6_~kZ8cpsXy{(%T8ffoQ!=!4XV{}B>e??}(C8l{8 zrE%LYz|b-ky*+S`2JCIa51fxr&N~CKE@s<84f$)HE?%|pM}w}0($^N-BC6*q!>tDL z)o>imZ*_#%LAhxd_TL+P{y?B@^l`^oyHHA8wh~5UUHzdy%)SP%mu1AL_G}N23dKezci1P<~^SUHt1JSG%Yy4u5T`blryRbcn%ui7q@| z{r>NH{WB$ZAJr-Iff7d=Q^%ilwk#n#{WIWoL{2fo|r_1hADOJAxrdSu(a5>YL`YiJ{}V<3CmJpY!Gsl{aU+OL9JK z``dGh+tfYDENP0#)~X4k_vEu6qd}eL4Bfn1`Nh3B{=_oOi8aSN3Z<+Ro5wH}^1{ue1x3*dtLejyH99+PpGTMIto(mekRmR}+WdTMhSBMP!Fj{UX zFb3z#PUDqVQJbCI+^1Gl*&yamOUbdtiI;T?LL9xBneiyK!Eb|^a8$P=_=ipfdU|4t zvz0muxHVu6yH>t)@)|-a9{k zi<)j63S&sbNm}OTW<}`KPa@gnikEi@h=-Cv4ARa*&Aot zz}NmBpsI=ig@*foLXS+KLM6zT%&)JFAI$Ep<91{6>D47Yi)hfPUg4shs z2PwV4%(}Pb0{)h}v3mSK$4^&Os$Y}r&064_oXjj`1HaVD{4t#6 z(k3f7(JsigPX9FEqJwBV-Yfw#gI?%n`N#Gd!l|N*f3UObT~IWJ2!jJ4t!rV|z|&8z zLBz=Ib6P6dj4aSsD>KE(6cZ|i1GkiE3_O~P8YR}-KoY99n*kc8YK(qKYYR`!WKID` z;*$u;Lr(IETY0@ODYPdIiRaX{lQ)y;#JGPcb&&)0fvYk7o6cA-BnxfC~GST>N zY$y1?v7OQvt;;5*%;4J@2H0Oz+Yx%&Nmq%1DNE1ui5D-cqZ93&EjsP-k)Ld?bE5Z{ zA}rrvL`-&9AvagIfK&N(h$4N^iM{7#sq<0)v1o7BuS|%be;;5|oraL^er?3%6UZe}uXU(_0jW8FW3w?tBO)-@eFFDZHh%KC9vR7|8{4AuY5-x& zo8*6kgpc?uOZ{z&R`ai&pgw+>wi@C$ zRcPIFsBG545M(9Ol>ZvC+h16Vf?v8Z*$F4kw4u$~>25#2Iq*D~64bEL-EOD2i{^9S z3Yu*f&zp_9@IexPfFHsDER9iVdCJQOC}l{p$F zBbTA9u$+F0Gi7gV^oKiKUg?)0Yzabt--in3E?(vg6oGj$x${1V>w+Xgpg`y(Mc(}| z^jK>ob@+m#_{ZhtI5%~kYGPi0X1n`kiK;h&b`4?_LDay>HQ>j2vl?`fHyzT#aLakC zWa0vHUy8_qHaHB3HdYFgo(h}Wbenp&*QkwW>J(Ct+&sQ*R9J? zT@7cenj5QBdd`-wkiSrb@EvlPBEM^_+t%r(1GkGTT(!QiabRKJTrwy1W09=H{Rb}x z@?Vx!u;m}PaVRCR_&0yl(Eu?tx`L_tst zpr37Q`n(m^SXvQj2n83Q599z}JBYdV@PCG;wJk(lcg$)SCw}cjwFAso*db!Lnt4A@{>$!_{~xvbt&IF+S@v@L+b(K) z^vmmCf!{+h`-8ANPh^pQJYV(St@g>W)49t1Ue70~*_e=mhKNZu%?nw&su7b{?NE^a z^&@e>lgsCnLZY5+51P^MSF$nbf{aR2PrAD<{p;*larO}nX{qA~tugFw7c$zOV5cH( z)@{?VW)JEAn^*`yO3_a_FF%H}Fzy3T%jeX(>N?1sz}soAANg-3gj_>#%{Lo&z~`uw z1bZ*Z8C+-40&_6)HG`c+w1o>F ze~d;bARo^xmY8!8a_ zmQCW!9|0Mqwa>WfXgqT$M+V6!@w*fdsvL1xWhF`4fi-P;+y_lXeV6GTf-Kxsgnycb zCc%yEnda7)HrFFJpuWy2zLI7{Jw&(i3YX{hwWgmMA{$t=#0b!}!nYDp@Ax$?M(89G zt)SQuJFHzqeM+1g)iOXRv`2Rb!rK+Zk_zJ~3f66DVeauNa_$)PMMZ@G6Qal818MRlJE@RJGi_YwY5o znszACViUT&awoHJRp}od#~4FzbxO;VgOMW6i6sS-iyGEA&+{XTRpBQfn(|lyRzM_* zG0jxmR07J6L;5rLKG|w{B*$iFJ=gI*q){Vy=zlbcoftt4q?HaXuM=?#ox2fR z_6L-JWb9NQAQ=UQNzA(?#`4CCW$y z9HzZJswCF`W)DXTgB`+FEZGwklC}k*iB38l2{z6g6MNL{D%eygJ9Rrq)3 zBD}+ViH6t420f3oM(8?N3I;>a6tU3BFZw%sDA^DYS+xs4{s22V*fqhn@=f!QY-_UZ zcWJOpUO;Fy@cW@<>HT@O&eJBRoyfCV%W>y9aweTDXGl$vu9zEG>F@k+rSAuj>Xwmb zj(Xle<^n(@9fgId+wGA?yom8Z+=MKQ=i=H6=~=Sj_m^m($5a)a3Q?q%vqouvPWd5^ zqt<+w2fdf}M!ya05e~Z>&@SEqjFVlQO%Tvhm$uymfUU2jSuIAta0wzJofmjC>GSX? z9is&adA$}+h#BtBEVZ!kKHm6-*wS#mE7#@2mwI7sG76<7TmkVczOMi?&ApuD7`Tr; z;>0Du|HB_dLK{=yTRLzJ>R^^Uq#2K78@wcbUHxpj?BUuxTO%yKRFvPGNL&0u#n?$Z zC5&zO_8`%UE|mvC#ZaFBAP8iJZB#9?*d;<&U7+nkqnmnw=xIg`w0+e97K~{oFRIKJ zSt4f%wsOwhqOhMM*cLC7hBh18q_^+=sKA||e^H}{|J$u*7>}uW#k^QDp}`}D(%FOx zglu@8qi$trwD{ukH;0L9Qb3|LjxjASmo% zS+Yeofl;)wWKq#HI$O`j8jX|$8j~F0^F+MRfBI{Z?@%3YwrQr)92rBzkvwe*qAh2S z=4%CZw}QQphzhzMAK(;A`lK&VMHo_ZE3v6bRfq?>$e+u|9rC62hDwGsOT_!owjRTm zAD)83lS5Ipf5vp`JA8*;SI0eGsxsim&EbOPV`@hW5RCg8M(&Up!%s`Li1+aR&*-Xu z7cwN`nADb^S>q=)7G)Hw$WEZa6oII6#4^VDgQ65umA&)cx7d>wu2g*;bT2uJY` z+oWW-=ECu6iEWVn+<@H4Fy^(BJB#<*;R{S8O96JC7oX&* z@D@&d{7Y6AzJEd01WBuPJ?}049rW=$e@ebXd2tBTFnLI!;Vpk*74kM3%@Fy!G?aT( zQD!ocH9=y7Re!9DaYTFR17>`=t zt~kV^R}M?%)`40eyJG&wcDG{}e#ChwYY(q5Gq?|ZL9%s&c%`R{DWWMoPH}P|OcB&G zjApTgs=IX}ybC1<)dY`9G zCmVB^UaL>HVObWp{=d`x_tGs}TG(}9!&4onrH3Ppe_sP6KZ`C*{rWdar=$zPpb~&~rIC ze{$xz_v7jbcYGw@?+0VuU~Yrihs(bU{5=G*Jd0xa5wVO(UANyDMB%p4+L2M$5kE+Q4oQgQw@Q zdb9I_VjeIPbL4ukmBt5b8^6qo;d?e<`~HL~y6;Ycyj_;p!Ia(`>BZsl)9&5+`c4+s zn0^|_l6{Msj`4lY~3OZv^i_YL}(F1&76`~15|@h^Y8j*j_H z0C(Dhy8r$Pnih~#(Bs5;H+^Qlz1wX8^8=5prkN~hbGb540!i}fggNS|MG6{D@{}B)$kJ_J!~DafP`F{PZni&a_}&T^C&cGq@b)mb zmep@IobJp8?xUFjqgJM)p#~sIRqo>ly|e&JsGMVn5XW=8FPdR+^6Qo8lz-Vtng^ND z0kXAh-u7qn#a;9IRyDSaX+tS&((xf{@4(#P3XtzF%q?iu22ZC#*|R+)P^Qd_)G^OZ z()=sJy=g)`NmKT7d-4m0==(kS5cO_6KJLLd_0-T8G;=EijO9^*p37!heMfOFecjoH zq_}t|ffnwoRx8&rXP&(K9Iq;~D=p8+#hOzf9h%%U#W`dJECs>;Ux@dG>L?tx_uEB_ zz9$BQZM&uJ2gbxLK(sZTdNX7&f;{LXGBe(fomi^J^nX=3jA4v^+`Lw6tR>j*JBv7( z-Jh{-|9tIlK=52f!L@rO6^%(k4ltwwL!{dD^Trap!^jp!N*OgO3E_3B(%|M%vrL6V zdeNvN&a=_jItw>%2g<;AK536h=|A=5Urck!)8L8nz+0|k*v8$m2*LesqwTD0Qaw!v zX&ml>8;BtRM|hpr9Qfx1r|G|J)#z-{(L}17mp7ss+(1H9WL+_Xnt@AzVAliCuXJ(QZaXg zW>#^i-jECF>?VrE9tfTk*jafdhTz}sVY?$5T298%F_o1hteWxeRS^Ko#luxLgqxQH zolG1APKh8NBvls0?WG|Mm21G3^cTXE1dK`Eb6}Ur0;9l}7&8m$JC>XnW|qV((~c+x z#KAVBEwhnHDVR2u(GXT8pHBvHT5XrxZ&`36wsA)Vju*Mv(O#dyJOo6A)$j*W=Rr;~%BHqYh-VT39!c zjiOR6KhX}DQO2%8@ttbKceVKn1od9~1`d-q(!$nVX3QA`NCK&6@1bq#0jUhUmnp(= zV1Ibs5`Q<93OpQI>T0QO3&6?t+OHVZp*UC55}!UCT?npmywj!KPz5WEQYEQVtxpJ@0Mfbhr0U zPHB@7WMHi^L&=-9Ho~AmE$K9{m!f$d+~VqV+BsnY(~`*S^B{E@{W8G8RTbEaXwTQi zRDI%u5Iu+tUMfkeFb7WZ?kn~@dG@~6nSPZ7&F8hCJfP~&?CtiQnm%C=O_dw%q{MYW1Y@UNI?h2B&jZ#trO`i$eMuK5wj#_96 zMVL_LFth)u?0KC%cQI9J$w(UdE_hMPuB}1G7i5UGu9k%x*d*Zv!y^mh7ICqh#&x@r zdvfdCx&Y5x_{7^)7ypH9nRU*LsXs4Arl~o2)#M~FebmPd`PD6ufC%h=E(ZO*w(ifO zjt>d^eY%pDl6qHSCkKQIB1sI%42>eORv`Ue00uNss*Z;tv@D|?*PChj-{XTT$ES{U z{l;N>LLUd*j9TAn0p?Ywi94*7Y9KbK#t%cucJ#Fbodg$EndYYP*ZoW_tK<#Py*D0? z8k{19VH@r*G#AX!kTTu4dttzBmAtihK}O13dYB4lE^?XMpB~T;3%>>t_jhcm4u%uy zxhXx_`&O13EPWA&k4QxZE(MS8d}iIKsJbCT%h&K+LvvOR%E8P|)1D%wc78MDmLiWM5_{fORc>#ULIh3g#)NBhCj z8B|)=MJ^J{{x!Zr*lg{qf-uwMBhXxk(nlNv?OR@UdjqLHttI^Ky-E&W$7WPp=EHY$ zaF4lYUVD!I6hR3>;5!+BXAjI22z z(P20y9I#CIjmYy}?HJOFqq(oK->2XdR!)`(JYY#^{M}yuw8rYm?2?!PeDdeC=2Tc6 z?3WzAWZO~B4Y-3lOSG^|`}fVTi-Dg=7Naqt@Jb{M37SZrpGBZALMzN-d2H{ZO`Y@p zV+Ia4%t08jji@iRgv0Ofm7m-=on9Wv1kCSmy=WWArKz@kfs=^!bTRX8ZxJYOv)GiT zFQZxy*gtv3?S)*wl&GI?*Ih@Hcf3eaLx^)&+K=A+|Efh&03uQ_riSB z;cK+VH*npTT4!gopw7h0V!aVog^=P*b6B))lAQH3Pbn+YtcQ<*CGiac|zbkzSQ^i-j1y;NhVzl5`^h&uOfJrA#?8A4>**HUXYxtSUM zgqKT3XF8qnugL`thkvnOgJ3gONPySRH!ZK#UUI>ggZ5)WMrA<$&a(Uq`zXX-FofrS zr}p0${NDb;?$m6?`*#ZP+eFG64Kwz1(vM3DYIR2#1RtWk6UW_tZNC@6k-~lgj8RW~ z-aD^p|3wOZvIH`E5r!`4M6KIZp8M^`o?EgEB&c5x*1ZhfiRs9Z-H+kXG}LAsTpQkw z9g~oXnn_q!K`(>j8gQmO;e6H!Ml68cH3{J;;Aim%E4nA4?E^=jxGE)qOv|x{M2d@J zMW37CM{<$XltAKGHkB6ah3U@msPXbr1JxKD;ww>jXk>@TZ zgt&J=Lc4zVyn8!8Cr8v{Ffm!sr2BjGA^c^#b=RiD5LRxUwhGj&Y@BqmB$_qpuM#V% z`@;!Zn-*Q3Qh*+De|Yl&Ao?(C0tN+pO-QKD_JV%={?5Z8&fl*MR}q~*n27NK5L8lm zaE}thlMlhybD=ZWY)+?BrPVE%EUnS!7ULiCN3`TaAGeA;Qz4}VX#8o zUCa#YuM&i7*9}a<=ETjGW$`E=l5LclqVS~Bqpn3rPDcmy>>NJ+G>{*$ zXPglbZ|r0bftHEAnmBz>uMdeMeg#w)Na%&|n5~LM{25^$kCE~AgZY5MnH^)YsuZh% zU$ew-1b%fxNAx}Kf?u^S6odQZW$7J{6D5~qqxmj=5CCnoI1i(}I3O9^hB>c9w|l8- zgPannVPtI{+t|zl!R}emn{sk@VUGR1fYh-S%2+T&W5f*#j47IIPgb)sGhfpjJcSLnRtKXTi6N`n&&tI(h#Ws52>; z>!SQb_5$cdp5FYWN!`-lX8iS@p82*liR$W~VnSy7W3S`V?zM2F>@X*80fX3~gCm`+ zw#^)_ILr|cNHiYE!jonH>^x4z8k7{9LTY^ic=_#5JYVIY_s5YUz@FA?1%|0`1a5#@ zzfI`)3+sU}tSYtv96JFMY2bfx?DPss4>OIxY|}4cH-84&8L97g1_)Na;RTrQ)^s&z zJgGqZdIFf(j?6iLQF2U_U!>pI8V))@^uk&sl*DWrtyRVO^J80|i~M=W;HL7a`{|6K zrSp9A`txyckm$Z`yGm1#5Qz~F=}N;SkqT&K@;?-|NP1_HuBE zV9Y0jLY`z102i9cn&%vY);bxR87}s`jixIApls2p$bd6>nYNeC4j5zB z)QMhygj=3wSzGZoXRZhkRg#9W5OyCG6Y0)l2=wHbxG}t|NI=qO(z3Q)Swd$i|0%c? zzZq*mD!+YLI4==HER+*$oMMu+y#IyhzJa!j)*I4)Y1r{yzpu9eWcMp5RKxtaC8!#k z@+MZIsScS{HJb4dd<21Rkqk9FaRj%XInfzBSJE6!Adbug@E8@!J$?(!v6b8;n+&)8 z`CX*IifAo)b<8eUqQF20e_rf?g3Tm(kW&av^%spSKV}GJfw8|Jlmy%XOf2wi9)$d0 zybp9?5yn>X7Yh*0-<3;<*M7@@#`O~BRt$|`Ux?b~$`cy#+xGJmyI{*7J zTx2KeRLT)E4X3zv1qR97^lZC|Yk%A|FHMeN@yvvvfmp5@qIyTeZyp9C!c6XSKq{sy z`WLOTssmGK+xnO(ord^MW4q7Rzvgz_4cZ!LnB~0dGXAjV&FhM2KB&5N4dA10B-{D^ zWBPGf{Uu-SN;(~j#M^<+77TO7MW}$Gzg9)~CSR3m{ds4g?6%y%Wr9z<>u&QS=>C{U_y&W*YP;u}Ao4Yqk}oP@^}mvnRJGLane(9#l0 z&44M4u#$d8ZA{bzUn1_?R4mt$$oqvk#}DmjezDQia&H`~SS{th2QoA9`(iP03AAA> z%8Bxtfos*R+4quy6&0axeW>GPUI%0yaRh?iTkNXvLXZeKUCfrf&TkvX?H%aC-X{4> zQ@8NDO-ae*{{%Vq40I&N)Oe0E@D@o(u{=*OaRoR7um&^J|Eu2pk3IeSLVEYlzF*!i zz%;AfN>Rrs>NL&cs!8PQ()Buu*LRT0w#>e87_?>AfzXDDkJ!2SXy+Me9#Dq(p%hOW zA8vlF)pOMzbq>%qzVXy@z2iEQe1#m40uVcqeGrbUKOjy^m>6UuQH7F0)cuzS$(6k} zXpjl8zTI8{kk<^`EeBfSKMlTA!~5;5mbG-23^4Wh+;TOM#ZfnZxLh`wX3rg<+TSw; z%caM$95_Zgq*)ss{8=-Ow^G$Gj;*AkteIyI;qd~_b*VlPTs<#oAr1gB9|ZKx1y~%{ zt2D9Y6}EVNG;Tusb_!4A8+<)PVoT!->k0CSGnG#l@)@xUyAW2wfBfg8A4mP(=(Ir9 za5!)o0BN-edR;aeihey+oY-HSW2cBV(rek)I}A;$qHhUUPt^B6DFZe}CJk7D--lHi zv&auvG<2W?dPOoygRDyJorhVX@D{Q}dcP)Vw^rF}xh4X$_s|N^bJ89XDVU6MPWr-a zf*V1GRrV*4gLMN)I;SU~@XGlrbigGE9RzJ) z6ULl_aP$0>$v(?olpyecTgsnI`Gvlu89&4sT980SpUz>sWT$~{CZ{8g^=Y70r%I1t3UnQ82 z2m!@A#n4OT@c6**EeH2uQcRc!o$m^(TkNwQ2Mup1c@NF4JE3;7dpcFRfB48kNQJDbgP+dg*$H~v0V6R~CDm7qYfkG%{cG_Ger|eiz5Qle35tZ1{b)&Jo zZY_2*pe%~!r|eMG?MJw+Wi?8p)E8%OcXG>x_~TPbAmjbGI>YE(nsuzA!|I)sbM0f^ z1-!|Td&$@sQ?2F+VfZgCH|ZE+UogW!UmM@92#myq z2V{@xK1E`Y(y|9=kOh;e=o*Y&F0TBSjngVK!P+f66T7rC+4B&efE#j#1=wXEHJmUC z&S6^*hUL1dwP6GKR#y{HM%0Xd_wxk&*ns&j|9^{F zd#z#0A=5|-iAe=a4CjX`!k0Qz2vO%L4h|#1TixdMnr8=LZbO3FG9-V;4@1<-IIlpT zA95FP1Me#7J35(BexLVQQZbEjPBmCE1Y3_aUf%c6Ow{IaNLq7%n{LPxKAHa@#y{ZY zk1_IGEkySzV0^>1>SUAtgRZCfYKu>H7bj#pD*y-HxD*5kk;T?pT&t3y8e@Wfk41S$s4RC52OXPibWQHk7C$Qg;-bp z2soS6jz@0F_x|t__S?5%HR6KBk}QRK9iGaDr9iH7PKREml#}Ud6{b2Pyw0#*T<+wy z&Y~4h%?*p1p$aAGOSZ)p((vOu`>d%6)5q^~W1jpaI@uCoPpH=@*#-Am;S37c1(++! zN)>yU>0yyvK`^Hgk&Kb=w!y9YnOczUvI@Kw12hj~7Nty=?}oIvYK9rPU_bRAiag!L zg8_Zn7m0B;;cPgILENt0G7)Rry^jeJ(U=I9dNi_xhNbYttB;D{{a*vE;7)}c7H`gL zzO0xg$JABbuedLTYUzbaNdO;u`i&t0c()!64$=Z6={_apR>P9kGN3nj#HeXyCb~-i zH2|1*0JrHmdZQ@I=sCc*%`>99?_vybnm4w;Ji&NwXX!TLC$Jlm^#;J%c7f1)Dpml{ zw(5vxj1+&q3Ad(C{EOYA!SpC)$AjNnlJYPY?}0RL5>5{ZtAH_ zT(#_lQhY_BbM0O*_k)GU7YOm?T&o+nl)&?>&?#4Brn2|X2?$>}WKXjh$`?Y=KYM*6 zU!W^8-Hn=UH}wlihQvINrxsi87i;;%>O};eI7eq2nHmRFqJx3C;f^$gyCX0Two!D( zp&f7a&T_(G76_4$z$v?1wM0*1hp8QYK%lhUq-)pYX&-LKxl;X$*4L?6cUf?PXj4oy zudJ@H4|2;UpqvnUCUiRy(2peFd04n^e?6l$kq3-C&B>ZOrL~SMB!XTI62@HzX*hR( zYiqcmPoi)VPLQMKp>pk}sobsqcl6d<&d#lLxoals{VtvG4w!_apR4VwVRwP=4USUg zy3PjH0_m%f66aPcf!%Ym0ygC)IqI^JG4V*GF#GT=0Ap2ZsO- zQ}k~Pg_7q1g2e%OABpO}6(I>5>6MsHBa?YG69jJP!(c$LeBea|!(2YO!e6_fXBr}?GPH6kOmB-`B&f#jJe zMPKf_o~#U@NJ4EdM8KUC$6s&KpnP!5438o|rSOO9#Vr9I^d%t@e*Iyp2(+zk;q`gN zk7i&{!o>Z&gJL;1-iad&}O{)#$z%4q?o9%&JQX5u$=0gIZzMHT`~RNB`cSm1-2 zgH_S}U$tH2E40=tcPwq?PdTvG_Qk5H-cZx;*AF-lQ0Q792b z`2BmqiM-8*u+ANo`RqVQtp-$7*BLqQYX%OEtz-8-yM3tL_avx1TDx`ey2iId`tK_v z0`AP*Zp_>lz!AK#5IQg&(EVPldZWT%E66Qgv(mSpyuk(!H3L{-V2kbET{XJCrN)D3 zkpf&?>o1=c^3z_}qTj>v`Tj+aSxGQ%B@zi?rK0@INu4TgsjBr^s$Pg=5uqxth|Q@Gqgq4nJi8xroeMsoEP!y7X{T z2lKsVOI#hwIL>sG`mg&jg;y`X@q&2nnq%X%L}y;f;OKgtE?bSUh>=P3>z^pK&aq-dzTvKf z*rXjA?A7%TGDd-2pc5fcjDY2_IS*kq5j7TB$_VwojOEielEC#gMdLW7FnLPjo&afp zxVqF`GO95xYpg@J^;Bkn%IsSyp1vPPXLmu^Q1aL6u2$iD6XU`EwwztDu=J8LeocwL z3uST{?E!Vg^jYh#dw!e$d|S?CgmHH7s9pV8cjcU?QpjZO2<%aUI}QO%j-MfSbNK0= zZO3dT7r0=)UdGw*as8hHfQmCGBm=z4B!U=z`c4{;V_0CQNdxD(rwBZW10)6B-x4NT zaK>UD11y5TTHrgJ!NE=9fatjP`=qbu+>PW~SB_lhLo#ThGN}nf?q3M%g?~B$!&Cjr|(_+rg|yRDX{FtIFzO z%}&tA`9uhHI0))r6M()XR zV@w6j{)R@>fSav<$?qij!(K=~3~njkgILCn4$EF6Fk}v?;06wL4XU{Ai$PG1n>0kztOXOeyfki_bWlqn<8CN;KS19O6?w8LTve*!c7E*Mkliet4Z+b zSfN@Aj2oe668143&r@0JH{89J9tIi8Nwt)9zqzyQt)JRKo5JzEVt0=$K8d#YNarc4l5SLcefij70(B{)00Z6vSxFhz8HDHT+rl1-|%rVxEk14`@auuts{-A zX3!9>T=mv16zU+mj=$S~Yns$l1#ctUb9qRqH$N3|KP^B}bZOE13WCo&743U~7TE6) z8oW4FeIg?q_@TK;LJk`fJcH-BAAGI0XE@rhQw#K*O?2IG9EmEbn~DbkhMFOUnSPST zHLJ>c%uXmy3}vQbwvw_uEvO14K|>_GXb4Q!G}WrsY2Lqyr=;Je0k6fs>*jUZkcC_i zdQ#&t<8^~zRx@VcCqnw}Og%kyUdf#hz2*1{;b1OtRom|c&(7%%wZZJWClIFreQei0 z*MinkjDZ!s{;W9j7&dOVLq@zzjrVLYB&CC-z3Bj|ar<+wC3c2NoY`lWSX>$)5z zKMRESsuFzGZLN6;1X41|Qnl#&F7d2gUU&P%#53Pi^0lDmu*i|2P>U{iYzv9E@6u{| zBe#vB*X+k%63G3l>1&Sa4O-`AD3a9Xjj;5mU=o16v?@nhAxB@MW3~Z;?ZXXAH2Y~~ zac)(*ys4w@A8zS!oHcyUgF-SRk2`8uOiJbmEYfV+dbmtS$oBHML61NwKl{KUE!^-= z4e$&Br;y&keLdKS-2Lk{%hA@1Y6J-}@%)tn4sqFpI0tP+Q{zxMp3vVrZu9K(YZ*4( zp1Lu<;CQA8^6-V0)!Z4nC?)ko3H~utcmv(#N&WIZy7SoHX)K45t1I`mqm&>!a&=kp|9)iMtiHHlTyiVDho1n zmjXCdwqxHu9k8FpQGIseH&IiHEuS6UOUK6ivpLSql-l=Elc@qc$#Ww+c!ANa-5|O9 zF123LXjv5X(r=gJwEf)5IAY@=NkOpd4X=$4q>_)PjD(5l^ZBCtk}vJ{2_$=;U^;}P z=6-+3p)!6~P5XJ3(b#n+0aRQ8KxIy_LDpchj*;&N-P2P%s~n0hS;O~N-HZSLkt9%A zt4H}(UVP?swGA)fLex&3vZ?~D`c!B|5a|$Yuo{TICD(u&UfnZ;Pv9QThpl~a-3sqp zM~GlqeJ%}tzh<(OC9U*x{j6Y$bl^8BS%4D{jpfI`tf>)%Q; z0nIuk`3!jeMA}O(-?Qy#kB($Jam1hpvl8a?^q5oy-f#Aht{)6d3!hes zyMwI8{{Me_mtJtwx6MV7Cm=MRfI$?2IiP8HQDW~?Tw{suT}23a>UZ2q?A&m#>kz5IQrcSBdWXS(U`*(cB+Ur_x1@$g$k z7x>#$bu~Le5@7PRr1%M#u2Aw8_V^U}sxxYP{9f=;0`7-ZcCE$#av$e9Y=8di)!m&m zzu^M9I*v=XJHd#!Qm=!y(fH38EXfl-!Msp-UuwUDv z;>03>+5bSV&rdzIR1kP6LIzDXoxY3Pd2c|F&yW?b2?x#>(MSZ$U?*6*)V7M~y`X9+ zDnZgck(%}S#HSA$*2h8*Y9M4*gF|W)If@kuSA3%w#SHF2)trkXF;1XeVlg4a#gsGW za3Y#^Nw33Av%TE5(uAIIEJxzi%q_5-w0C&J^nR1X4BWPgk#$y5Z|>aJwEKn8N@||< zE)ui$9E5nZ{HECbxpoC3r}NQNi)?iDwHPve5ipQ9IlQ#V56t`wv%sKV_rG*o!{au$ zT;Z2%oO?)!CndsKE1V-{y=Xf&sCNEcZI>=Tor!?7I%SKO;JHNDN4A@d@u@n?k*5jf z31P|QT<@m9nO3^VIfT~O);J6zFzXvzCW6S*&b940LI`x%0euSWvd?{2(Q-DxIvbL#!HRa}{^NjXrTfe( zuAH*?@p?`dUmp!TWC`r(IH| z_Q0Tg{I0_U$rY=X0- zloL{!Ik&{OIGKPJ8`Y^GGd$X|6Gxh`MfgCMT?4u)H}>Azmh?&7DL6RkW%5-0sDV*& zm%YNkE~kEsvdLVuHrXXK33#J&P$k1f z(Q0TS_(=9YB~1TKoS^rXBc;!g1xPXgOPfQ48~s+B>41+v{ei_4@T|&xt)}(Q3nqCe>_Yc>Pe}dHfBIk! zr`I>Z@E!*vQDb7iGcW7lKM7uErBOjpGHR&;B<|x!{r!g`J^NI>>o7h0V7=Owegr}9 zrG~SSO6Pi;HdD(;U8TDpEb?9}9{X8wt}PLGX}w-bt!?D@Gxf^4YiBOtrE-Bb#Js0w zGM)usI58anXcaG4v|Y!xNsE{=-5sxwe8D)aPFf9?9Y`Ft)9HnC5v-ERJvX)scZh8Z z^uO-FTGQl%-p}4rYx!d^X3CBJs>05F)3EP)oe~K{)I6F7tepbx(4(^kC9tFzr*5n%OBVE%gGykO+YUWsVUcm>pnEl&9wbW>r`(EG+)_n*g|9Oq<|(8tHu() zjyHipLHDx8{O=55=Nqf?zd4b-^^2Ks_ze3 z%W}E=ZJ+apKy~#yld2;r&-gQk0<1qiCsV|#W!YUY4GLPG(pvJ!_IRzIYP%DX-+eX* z-=RuAEhXzsC$B)LyO}H~X|KGFUCt=m)@q5T0}x#d&JqVpTSlPGax2Qkt|SEdoJT3n z_0qzC6^&_RT}6Hkl4Fp91L?p}v!(4X{aY7&$efvM#bSL>9(-REG&$IC-+tBSy+p#k zcg}R1mb0xloj6}7bb&)M9OBs?K<#N;?nv_Ne3=?zP@qB!2FInCJB@VLoo z+Oipyq%u`6F6Y3{hJnP;oNLwHWHqnmy_kc*+oRI zd)g{#^kM09NKDgCwG6=!(t>b*nJ}m-?T#&gd{WHwIWLON15Sj-Yd-gzaKHCCmNS+& zjg5^lsq|jX)b0QEV_&gwx=nQ6U)8M`(b;z1dLG0m9BHf?hL4;5{%KtPBQZc)Ou>ml zQSXF&d(5O9{_}2@yzd7XWlMP_4T1)o>*R0WWtJnT(cXhQUv(kc#P(kGn-Er{YNtl| zW*=fmj0P=iR)c3Cg^s+iM3LT0Z3&f`pcE{PqeN*LXoH*-GVH|63?t;^J0LlAaUaqj zfg36=ZgUqR$0rBTZjOL#Ax)0ACmG6^`R`#u+pDYCtIPgawBgi2yViYqWkpeR?B8oV zd`&L1u+63gf`!fPkohR?SOeor21`Pu`!WjzbASK{mz{g(^b4yBT5`nnW(kX?*ok&J zJuV^2Z@Pe8xm)ncWEeH?OOE|_%ZV(!Z^*{=>2Yf1c^b8p`eF3Tj>4cFnKtkHk zH@~PhmqBcuWX;>3$DYj{J3+GlyfE`_LcF*H!2KR8EoVHZ^}4o-=zX$nKVz!dz-KaQ z286ptz6Jl%t)UoD+(iKBSvTK7?~s+opbX>jzej>UO64o_$M$74Fy`+S@k9ZNO(kUUAXoGi$C znK_VKID_nLgFB*0nwf=!!wo92_Dk zF>P85nz!0XVb!AK`jTrkJrCP$M1$YGiiA7FdEmwW%$H)`wf-~~$2UsyeX8z&aiu44 z(}*R-3tax*pRIoHqRU5h2@I)HY*td~mKw9{tnI_VkJ_ZO)ZXu}V-bq%09Z3haTc!q zt5$hTaybet;r#$tti`(4ESNgnK1PV@Fa`)P3P5_QbUFGA3$@Bw;OQG-0<8&bMf1C zMyv2${R6VT9YSUk$6Xhuhy6TY;oTA86T1e3uu;zX@73=QWsf*GbR?k;pk7Ei<;fPv zKNP`eA?|XXZ|f7?;tD|aqO{TjOj&@ z1k970UnSz4_w)G`<(N)ilc%{Gh}1oJ!EYk{*B7Gou&@;lra33oEP?%f0muZ{Ae3^G zGGM|1wWuR-Z23uh#yY-go_>>v+@kA-%WpSA>v;;~5c`Ckb}YIBCpcFNwLgAU`q>$L zxjm89&&vO%6Q0pHK7_5masCL53)=s!D_f%vQ zwG=)2h1XIhmY8hyj|D5Z7}w`rwlp$Ad}d=eQpyE8_FWjxwQ_+kL5gUnUuDu7E}Mfj zIQinrEszG!7S}u~Hci)U%aFj|5#MU3$4$Snu;ZG+KasJmGS;&Vrgm+$ebj<&tnB_X zsCAzi7`r+Fy}mZI{bFP(31eI%Sx_Kjsr=n^W!W;(ykV>BbO&`hALo40x}L#)6ss3( z32m&Y|I}`1OT3Ufe-XjR>bn1x8PTLU`>&y(=hs<_{x<3LjDxEm#!@jO2(jx`hMZ&H zFhk0C*VGoI{U#Q=tX)L}p-4Q)M}wMWVOCFwDu=mC>*^?gXZ!%kX2Vo)rnepJ(Uh@q z`adr!zy~gw=g_}1<(_IRahmf3Tkfp5qC zoPtkhlbKn^4KcPN2+}l{jUxZ?bp#)1pgnSawIhxEh~rbU8xDEaKSmW_o!i{=`3A~) zxW$T_F@f(T;*s*S(u+LcETv~bnV?`{&v?iO=>#42wZti<;Kg=~-VyL)q6%9WT+}+K zP_<3@Uj!0_f!|L>d*H!nSWy1*1ImPp03BDE=VN8v=-XOG5Clc>qjnCN)b z2DGr|p;75kesug)rOaGbFDPc(0n-OK12>sz3%^CBJk)k9$sRI|n?7+}f8P&Kr?D>H zBnx+U6Trj@dRF(Oc>=o=@Wff|&@#L7Ntd-QK*ylC%H*uRI-*M?defj#H?m_Kk5DN~ zgT+9N%znYJ6Xot7t8P$0pHON;Fo9xbUvXW&BPz>b6*8g|JNa})_6(Ao>_cPqux%Oq zAjN0_+Lc}@2CXTZ?o4ITVK@C8oAPRUw^R0M&R)Rl`m{A`5-?&M9@qNX9@^X{&fAP> z8xiAVb}r^xQ?-%nuY?TG+I!0W-i-OT(LfCl`SQZx+7iS?48(sZBRd+9>^3 zO!UaXS~f25wnzr%g~^VDmFzVpON(5bR$2Q^PVn5q^)BU?V3XF5OC2|SI}TmfRI^rx z3GCEUG>!AwS^T4x4Q2NM0%fup-yc?$K$*|0E=Zfyl_QMk(}81NO)@5c(?lcCdZOg<~&dSmj2rLnh}6C3ciqXS=Y7n`K`l zyk8-6V2aF<>afZP67omn%pU{yTYA^An3V4q&`hmIRSjpdLgeOJ>3XlTrs=wzpm(CH$I@xG8EL?c zhwrwsyY~r#+jwYS-rVgRr>aCsy6=}^5*V`VdD?Q#x}|&x`a4Fo9N&)v9K!zA!k04= ztvLAr$izs;5tbSS)=xON zhgqy$BQ(Wl+Wyq_i&q`MTR+NPo(R|prPzImQeR|`Bq0p~4;k6M5HcyiZQ{0S`@|{%jCLekey4^hgl=c(!T@?GkOAh~Y0CO#;S881!)26`o2#$rjZ29-fl z1#@Y7rsr@$qy(V+LRBw@co*+aAEWZN7kw@lFS}pSmX@<=6v`d^%--xuI}FdRAy zdhFkwc!m+i@ajqKr4Yk}VQzZt8$qBda2JLFeF{9^Ra0xy9bk#!@)Mh1UJSj+vFIIh zr1|YClq&m2eDGwvAlbJkN=>X460}mFE%*p98m$@OSCexN+@A?J^Fj(qjYg!SQ^gg~ z|CTg)Jaxe4*El2-G_>J=5wFG~<^5Dy=3F3^4FoP+r0zvSSAc%?Da$_3Wur18Qh_ra3MwW! zqTG54zNU3q9A~>pwSovxZiJLw__~zi>-L*By_Xk{Wqdgl-2cj1{5t7(`Td&)@@ULo zA^m@tcDp;u>z$Jnzg-KE%Mu$ATK40aj74em%4$N~!_ayE&9NbDDEKzNcDEvWYynx zs=D7D)W*i@Qeboxk=zI%A&(MZ22#t|x>X<5&xyEK?3=)Wpjv`C0M;Td-zZaX=Y{)jK# zL?-^je%p*f=PI#$5+wQ;P2!h1rZ8kC=1R2=1Tw$$P_?zTm}~E52D?BT6uP#7X!2La zeb&4UWX<;CUk*{Gekcg(o~UyIZz(vu{TZP@WZsh*1I-`(NpMikazel{BQ+@zif{|1 z@PMw1K>$4+1|Wtf@v&nEi)@3Xa*xW5=hOo8PAb%6LrV%I=L{q#gym4pGwd-Qnz zpXk41^7O(wE}JpnS>;ICj?8mdo-6y6ZUp}4>^`ZmYLd+BP=ZN%^e^!`l4=RvXE!u; z>|g)^_KC?)N#AsFl;^6`Er_qm{IyaJ z${C8T`lo&>6^2hrJeH|d2nMcHItu^n)sg1pO2(kg8g1nw*JbmnS+-s+mtnu_2dY`i zrN3FnGluMi(>RTawD-I;#Uue8Pztb|cQI+(>?e<4$ohga2g>ta8k8T$=v9f9jTN(Z zIsa;bER_IrWTm#qJi5qq*~1WISH~)bvzLz(cW5EmBFm&3i)JAOruQ;#lq89oFe#B6 zXjFs;UP;L)2ibMiCi_hyTH33w=;j(i4cMZ_`#q2j0F6w7*^Xa8!|^S4o~gDzKAHc3v5uO?cm@E`06*Zr+~1GEQ# zP&p(x0r8yj4YCEz`u`#8E!*O1qh(#(o#5_}1Zyu5+G}=^`bg-wWvq=GH?uF+`#!eE(%?hEL6@d|*W~$K>0|!TgB80_|oj+F`VMDHhq#B=*R1J-tww zBO_$)QqUZIFx8L7)a?H0jEa^}2+J@p)k>2Cu|4RK^Ivp%kL=!}p^5t4u;9{(COzf_ z=oF&4DuB!I{RlN%{fZdC%rVR`2t5rmH@+TK+_#)XSxvGbq=KYpcc0&5a2d>PNMK2NiLzlf1+&5mn-vHyOZi(`BIUf)` zmT9-Op&Izv%Y40I)4Qpp!1|AR+J}s)V@6p2H}-mq)T8(FEJ#T68@43rFGzQ}2pSbp zL&}b@Xk3P?QN5g;ZK&8T@MX*PhUN#_upST2@PxGqIe}X`nr#QoS@pVa{>`pl=~ir77ht zX4jR7bUM~9VxGE=Pe5nMo!iZr{b;K3`;|ULt8-64DK0}L>`j!jhoq}FvDdt$hmTc^rmM>L}leFW+SdcZApA{>AaLih3Ei$l~ zS3sKEoy^BRASm&;UcbG8Re0_@+d(SCJ!1k7b;!70gAoUr&SpyZOM+udM+p}-mOww| z8>{@=IOpC|Bj6F%3uj(D(Y)Pd*ysrbuDg59fQ1`Gn{0tbG?{mG-?)hQ!n2{#Tevg| zqF4`xt^+E94RMC+4Sqg_X?$|t&?LFnRxvOk%|pJH40s*YMsSg2c^VeR)P}fKpxTg& z!hpI?;7fD4OI3y*ZvqgAiN-o!lxPfsFjN~zh=c#$pnpm+B1dKAclkj)f>z+f0(4Rsca!>xRg-j;C{v4 zv7TPDbL-+1jAAwT0ZZ6Leht(Dc?XF51E>w#LxbaG!o0w2!blBLr+eI-)4fb zMP1JcS~st9gAt!&^`NqDEpfzdhvEcqIG_{Y-^ZcFBL$^^)wVZ7ZhI@e$sC|ggzd{5 zKPYB_0D2w_*qNnE5OyDB{&Y`6^5C$S=!r`T?DLWTYo8xMWwvu9ZJCXT6U^&+ zZin8bwyD{E9gPAKxD)3F*uvDYvl?VV*uhlS;j?=ryv(;X3re)ZukqLE8;W0x$1C!H z_{Bp-2C9o13bPDfMv4XNO%6v2>%ItuxBzQ?@w?p@ z|7+vlZh;IEu(GQ*DBe#i8w-oTy%D$^thI0Yjqr!+t_Dm46ioQQX>PXUkPmF%TIUAZ z`Z;HF--F~H`4%_)9|osg&fR@0e+;xWDpGiqeL zvEl1I))val|ZynA@puK!m%DgnB$pB)RT4Wh6Tm-IgP}`3$9{31IT+Zyv#agvejo}?>;k~ zb;!Nfdw-GY+E0_wPu04Z&As?MW$xA<%IF^~yDvML>h7#@7E^k|L1YP3X+smH#d52B zi!uJBIaSS+3%x&$H^eMEGqH!|2{mKDg(cZ0k<>7~>o!Ko5!WsSUJ&Lg}9HlzI2*BrQO(X_niRhd~YZ&>-+kHl_RyLZ9g8c z>PuEVlnuvQYgskpW&s(rd$;!L>XlPg)m!xqHRHLf!Nuk?m5_KhQ;6I}_G8~>AxBO5 zEB+}^#cVA7Lnl@K6Y!jRibRkTa%8z`t&RY+IITy5Bme;66a%X}|Gv>*pG}xyKhZVE z6zo3~s(VkDGaQ4Z+_atq|NjhkG6e;kZo63Bxr zqjeppw(vQIx>_>h%l=}r74p-yl8_}SP$~kBIuyesLt^3<%NASub}gt3C6?++?GFXV znx%_ZV0gf?Rexo>IoPGILT#H29&u*U z7QhDnhm>9gyB|ms2W}zn218zrf6Q z-7!w38xp<5Bc4$WEZiO&FUQ3b9s}(U3+ehuQypXX&69~`Y*wpidX_tO3}6!tvjQ?0 zuOI&APmhBqxIsYof`L3iZer>_i(V~TNkn@)(XZx{N+Mg~j(Ju&fxQHj)~D-Pc~*Jv zajv^`@7RFqkg%Cs0?j%>x+pKC&!h>S$fr{w)>yCmJX{MK?@Amv6gIxVkof#xy>dEI z0Z3I!jHm144GhaobFdmpY-=|z?@o~wo33d4oWPlL`^o$J>)%bASvfA}+ZM>6x5d&) z`)R3sJ5QBGiav1E`_w}NJ9?DV{=ib27s=DvY_teNP#xHCL_2{Hv%i!yriqZG%J37F zoHhh{>93qn_67*8{xC@(*cA$gjnJ}4^b3ov5~^FCSuznSs2%3WjCk2JQg+});=~J0G_gIrj?fh0lgP~$m_hfAO01T{KFmliN zj*a~5Umf>{13Nc?onLbfhhT=C(yGeat%u*9?J#fN?N4$-H$t_GE0vSG|FkY%wJxgO zoYmiTBe^P_sqeJEK@NcLtwS8rJSYx+jHeg=rn2$)Qk_J26m zHpJdw-ZZW$X*1dneF6$f`<|#~=1K#9b-b*JEF=W?xT?#20^V`Y(p_y8tL8!p$RwoP z-+3#L;yzC#SmMLonf2ngQ+oT|qoJ{%%@yT2X?0d-&BkPgvySQ(gRJc0{g)Z{4soz3 zM4Hmym_@j;K`s`{xuds*>MqGOdIpb_NbS>HK^XBGDvb@vuGBhRLd|X{oR)Ofk!D4jDVdal$Y>eAJ(h9WlF=P< z|MQj;v4;(9|F8s>W&<5xK(dQg`#-w<*pFB{`@)GgKuFBsHU!swjeP)@#Q@z~gvNE8 zvN@ZN``_&SZk)`Dg_2Wu$SG`_zeat}x+!`;32g0udXI8ewCL+au4#S+@WeIh)?{t) zl4@S_e_-`kM8;^@MpTvtHV9+u3UD5Y_s*Rxmr_*kVTdmEIn}=qAU1pa#gA}8gICe&)L5v@M}E*CTDVf2ji`f4 z7At5S=nZ?f)P=m6^Bx%r!nv%h9Ov)fhII*RC;uh`4UQj-d!$&@42w~`ZblrEdV?gt zgep?b64)`4!+c1T@N!B4N+wVmTBgo$vzt7t8i(SuJy;#bhp&4n7J_$a$Aa-H{`r0u zsNWU$Obs!uYxsGr{0ZlipU7IN(pPW&`#O9-i(XuJcGB>#R)2$tdMb2%UX#( z(Ce21&)&3ID=H_oG21pn@~-kpq7EZ=x)wvWhQSsxCt7B`{e!u7nG6|jVLg@X7dRrM zI(5obLRwr<4D-PEU~;_D^f3z`I(_k{m|XVy5O&w=#TIEr?>>$74M-WJn*gqeM*aRy z7@{QLl2&;jboW;S55_N5P3A*7Ld!5ip=vli4y8>|#Jh86nLTAIGI~y7jCdptjytZ1 zTWKgZFmRjSoh&Bt8{stIRq)Su=4^8QHe?@$RoZLw}K&D8vw zW|8%FMcFcRd}bmo*qLw9X4|ae56E^2^He)cqD8A%v|(`q$XQy8m;iq?&xB7QI~aG-qSu9C=n z>o972#ocV_nm03~Awg>r+ z9d^iH^HCPxbESgC-$GtgZluT50ADdVly_THev%l2(*+$2WNxX|o!6eX{e7>2J3}Td z^37*B6_2ZDz0oA~q)eL8PN@dldUQ!Pbky#cYq5riIJfpYGmV%;ab$U4YM$hbv^4%F z>W`_Z-PYbKz@dmJahVag)#rmWfPcABEz);ddwy2B-;c1>Lz&JCs@eJi z!7h|fXp>u51W~;<+(@)tVtbR`EZVJGLE<}=3H~qGgtqPyt6nduZQD{A)pNi1@Eq7t ziib>xiOyTAvUEwrGtTg@=165}Weu=|VfRxH)`8=UX-~kX?5hZ6)_TSE113G(yCwbR zMs)_c5sDP;qAdQWb%4g%!2rp;P>iq}V;7gE0x-r`6wXor!J%^irweFJ@TAH>O+KDA zAgyH!5t`lPilvjtCB5d^Alht(PbiWnS9l!Y`7XYwsjR?;vN2Yi24ZHq@U*Uu8=Vft z!kuKBMpDwET8pH}btSW2(^8ON1RzN&GGq4A+QcI9S zjaOgaWGmlWp@=2jq%9^uLm?zxFs6x9GhC^rD<+X6QR_3SqF!lVYWhUS21rcBV~Vj& zD=$_2z<^4X$Rp)03YSS>Nj`+A=E&T3Bd*Fd#cQ4a9Ut{GD+o_>#LiDGs}Jf^5F@}E zwUrsPU^&B6V)SU?v^oRnLnEY0BA`jH-THTJI|-G;HVDyz&d>@hoq^CLRg>LzA37GN z8`d_)Q0wsp1Ju(?B*`;H3C4A`;M->FGT5h@XlMk1D95t@uVEAs-7S^LEfBOKBi<); zT>kK6@i762PqYrVX&9X^z}P1oVKjjM4gfCmU@BNQ)t`LebCMSL7VsHH|&~SX9(&ew2#n>EiGk#odYS;^uL>}CR zt^(I$e+)!IV}gzGq$I5tkE?FP#T&U%?DkSuI!8Wf;*QB;^0nVOV9M__RC@-kTiJIw zWdSp%Ch3-q7w}z32;1*IQLc3(*o+oFA6p=ySOP1X;G~E;w?Nk)Ls(7e9jb>8bL&9m zO?t8BGyVEh?7>KjyX=v-Tf+bgQ(?#%PoE7q2hA0Fp}!Wunk<`a)HJqhmTrHqod zxIr4&AU%tJB2PFom5o|&*4f;W*F`*d*$?eij3Nf^yi%eDG?*;SyVCMr*A(vUFAVbU zv$$DoXZ2Ogt`kBKz`o!*zO-}~ProK$yZr{3GT__S=a6yFTkaNGUFB5aq8V$p4n7Qj ziHto?Gym&!5<>IwfFJTY<5OM2uJ`Q=c9+4EIN@?8(tozMtUv4uwPH_`-V4F&t~bXhQDii|` z2x}H#@j6JiK0a$))c;VPbz89G-oBos-m#c)!@6K!j^wc%R4P7S5%TNXq#kj2{XMvT z`&OEN24!xnFi;RId|vDn3S|q%|HKKcxp{=*JNhaHVspFx4JD5=^&6D?y9xgKN<1eV z@#!`Nsz(kz-~8ZH0t*M0K|BgQr;*ujm_Cb=&AS;JWlyjvmos{M%^fi!oT<4~V@g=m z{SOlOrOr?ff@)sz>lR<$mzFm3UnGNC-P+>`G}wfo3CHRdTmLQc z?J3iiglS5x@8jjs;wZC zl}=)da$U8|p!PAv7U$N;t0_DSZrue+Z8Fs?>&499#N%Wwp(4sSnv%690GB+9AnXWz9d0fLOjRV7S!Ws4A9|tslQ_BRRm4Qn5yNW8L1Hu4muS4CkKMrcqpjZN(_kQXW-w*)Bj0X4-OYVMP^+%t_A=1I z6>~-^{JFVath%Sz98a_BpS?rhdXeB&=tJk3CF~@|z`!}GJr}Th8u~6qM$TJ9k45dV z!HOiq4(irCA9I-_dncqu)x|E(_DOSjP^KV|SZg?q>g%23(5cU3IkW$eqRgRo@{l9{ z6O#melRM2InN$S^h@_r)*mOiS6_nVNGIPG5(Qm)b0k{^dE52sk(5CZB1=}rD zeGS9h1XX3M1w$~OH`ZX+I2ztlrvmv<9&1OFTQ1uE1Ro-2m<_`ZnV9aUvs(El60|4s z#s!u9j(=V9s0A+P^4={ObTHC2pVR8F%jaix|N2UV||I{>TgooPftKQ*v2e}0y{L?{+dbR5=(ugC?4O1 z2IneUBvVU@B8o?d0{EaM3CcV6CsF|xFrVE}7iSz~xuamZjMq+9hAN2r6_<6tyM=%k8Fzsm91U@-51^+6Ir5*w=Go`3vtB|z?!K}S_M0Ar1>EX zMQ|2C596$j)Z|4Iiuo)trrM?C6bDG%sbL25uO9se0gJrPtu;n;^yeDAin z8)=UGCer7^>(RQ%$1datpZbg9{OF;*+B%p+u;R=wcYa_-hB?!uww8sBn26odF+sm5 z3U!*J+TZzl$au9s?4#D(@z;@Z%>>NLYL??e+V(kwc^x$ogqS_|wdS#$80;cwQ)W33 zH7o#9Zs!SjtCN@Xl`vX#^F;&q?}A{lS8mfkwj_LEF+veTGY*3mQy}z9bvo*iMK16j zA8LggCL%`;QsL_Mlh34W(^tfVMHn-dONsG6zwW3Oh=7t!Q%ri2BF&QzirpHc-e8-d zj}D4bP2hJLL$E!5KeKj}_%9MFlKQn?cIe1Vf#b(fOT>gN^Wsc6Q_WZIC!nb|ilJT6 zh0`mN$expl;#CJ5F!$d%xYy4g7tgKre0<-_9rs1VSC8ZK9T$L*WaDHGiO(xi;k8|l zd}Zr=Xm5!Stj(>tz4gH{X+$s?CFc4nQ(;PDlUy1Mt8?SQ&Sj>5$Wr6*IxLTH+ilXv zHl*`KhcNv-Mi(PqEM@od2S-ovA7EixL|FKwS!X|$%9ZscJ5(1b9UMXl^eGMR4&UW) zkh-;-%CLIs(`x9#yL$OjX`~fBm&%XROydOY10GUN;W;3ya*w^Yn>0MhW39McHR#5RL3ok4ix9l%wv+nO$J#xuE5lTT- zzdu9PAicGD2enk{2|7PnV)$qolo6ZQMRNUQ=NQ%VDQwAyu@#~`pq3j}l$-|F?t_^d z(+UJSUEPmlWbj`128FaRiEnYJnA>db3WMpAKWCj(stb+hM2>Tp4MGEo=`b=s)%@f+ z#Iw$U#cts42V(c25MMI9^&#ZpJriJDO^Kr3xjD1`>$;);@j4KI>^#P^(E)690^4dm z58iLK2h`!8LE&hSU&uzC0KB9hy-2KmO>|ziUleNvM;-MUns!VBw5-u{Ao&-1XmhsR zmufCF&q2Ex!YY?E%&*p#Sk9+IqoRu5H-xlo73fXE*chVwOT~`Ym^Y`@@H>f$;e7_2 zv~zXBIWf#Q))MPMrt+{4H%)Qa=8BEw&)<7W1f~lrsR_2)*Kyqk{E-&D=$~2&C#PB+ zXQcfnM*@6A{Kkg%%wHg#DWjLZ76!yImPI=vgA%Jy18vt9@P`;;6Wk_^GBKuI6rQ(Y zi(2ZPQKs=Ya$w5p;QOCl66UKv>33?JBhoQ*BF>c*w`x$6iarVJAnkx^2l)L=ONf}& zXH3clK7Ph^rSz2{OTUEr9VrdRjV(+94iV$vo2qBWYS^LDL!*M#EHy&xk<8>-;qus- z6_=0^F-m5hft=tbrxxW$AM4G;OdC6Z6#gYFSY7WTW;)_Bd~K-$8p$v&g$G8Ge-;VR z`(#|PKxL@Lf`5csbREh?2KYwXnthXUwwwfV92_IfnZLoR$iOw5H|v9baaRLb3q%;Ib$Dl6$G zUT^nBgSy=E=MqtziDjmj3!y{!61o=*Ibw7ZJYb5c_@DdYGRbhy9Xw79WHY8fi8&>oYaSJ%{AG||vy&eneh*7C{vK#=D_HpKU7|HXfxFLX9T zjkgwsrQ?ao;E|1rgm&Ka3m^A=s}86P=NFu10|V)pVom>seio35DC?rgA(b0|R^up4(7H9dUJx z$&8+e-)md{u*HkV0pC3N|KH@xJ-XPT#4;t)24ESKx0u?nqwTKx@%lf4=#bmCHw7Oz zMU-aY2c7vHL`k!9Jae{GoX@>4{payzDX~a~Ey!-oEB*{uB&2jo^Vav{-}zr!VW)a- z!qSn0G!uZZ>S`RRO8IaVi41|K?dHt-P1gPV9)f=~9XwBf{9NMorvLK~O^+*~X4FZ^ z2A%eo8b&RTY|p>3h}0uM2dL2Z!6^e*$@L$UP50nCU(7Gfzq5YlvFuNs0J$X!tMtd0 z4ehWvSs?tu#kBUM6L{IwT)!RW7@E60yc}1ekdtaxsaI;*STV_u?z>_)iq3DoDiov_ zsNDXSST#zuOBD6ZzVq!~-DNA#{m*&(!+O{NngP-%6G6z=HzOR!_@(@py@Y`+ z?Q5jXmXi_Dp@FfM{z4VsO1sh1Ip!Wz@~KdDVqF}mk~tPwHe{ZB0q#_Z%iL<9i5hOR zZBfggJFQRNv>18{Dl)0vy3O`Yly*o;rcHyGPBy?COf<&~N86qB7LfHO$;~%i&gIjQ zY6|5^tJ@xl(1)Z8GO^%G2r$UFjK$}14~wz(x}jY0ji8mIqJ$0f@9^mkaP9Rsa$oE4 zm6)acYogcM_p^y~gL6IHK4B>Zc9YnAtQUiyFZA#fw)JG@54I)71d66 zoIx{9Z|D%CA=Wd&Pqij+Fg=hMfLR{mHo|~QL8GOg@XL$nQauqqStq8X?k-@b-6{vv zKnNyP7-&0Y0A`KomkbMuVSKI3f)0SeF>U80^buoBep`fIsNSGUab8c4&xPl(-Hu2u zxMdx^Cd*>)Ki?7RRTUWxkd9+d;ZL0XRCSd+b3m&+7UlkRHwOH(CBwtclPscmhv%yM zi#K%ZNoD^*$IJ1HhEt;jw>C=C@!y`E^48Tcri9`xCLrP6RrkIZSkll1K(Z>KApm>HvWe!^DNPUtk*{#-B&U1_o(zoWcD(uYTfi|)M*{%IH-PcPTIG5l{Y z2~SbONmT$fyw#cKUY3@OCTJFz0{%`fs^p*V;}bh7@N&dg7H39pK*RKz?oR|K8l@>i@} z8Jwg=gGoTy`7{ptE5}_5|2)9+SKwnli0?lyzhcmTxm{oYe!tJ{C#a%%^t>qh#v}gs z^t59;Yy>OeZm|mP&lUph%^*1+?=wjgn#9@ahW+Gocs;-y=zO_OUJNGGeiRMlm5~0? z+Jl0(7w#j*>grW+;VJF^u+d3632?fzWk*UsB z`CPB-iUseYZzf*uka4Zj-OpD5E+t~*Nm80Th?V7MUdQV-W_i;#IuNMi(CryqRN3Kn z=|;b(f4$z@btz8(3QrOSh~l$P@VWq#?;Rq)$HySJd;t*SGmt5Sy#mrUFT=h`5nq?X!G|7LnTY1gu3TLxoSr`e2 zHCu!p6Q){TGeWrsJ0_tnmAM=!$R429%4d$I?v8}RM_pteni|Aq)(9}vd!UZT5z`TR zyo<7{n`8>{6Li3AvZ7)UrQms;e5$jYzhy(slKYaBFH^*7(u{7iSm-a1{8eqEE;Hav?7cG6q)xM! zDI#($T|KhvnATj>h-Mc*{gmT#tWJ&gTq@Ad7gMYNq-nqeaYV)-7z030zv!qwB0Xvu z<)|Qjg(pZ*|MGVGUBnjS29e@31ywXxK4{ zhcOB?yXtoGY@{7Ute`*tA7Q?h#4yt%2wDw` zjr7Kwm18x!CUFl7fRrO1(gNO@vRwBC>LeqAS?1(vLWz%{bkQFvK5}N50Dai?w@i5y zm|3Z%4*`aaFphSG+a6gk5`pb)LoCrSj+xLmpxK1A^L3u;WalK&cPR{!bZ7w2%~oRc z7VsO?6Qjpns0UafqZ0-}=dQ+&5UACC?1_?6i2ekmFYUJzzS$DzgXQ?aVSP}9)r zJVv(1^<-QB5AAomdPze?qhcV+8!=)792Qf?soz7~T`t@|>C49|+EW3zuKAH9btRSj zoYyYIpCWi0FZb?fgYwI?n>P?uM(h4aSVc#z}2dfyW~g|)6F&?WI_L?Vk4oHm#M}INd;AX zb^y1ShxFI`hM2Vxaaz(+;;N1aeR`4UgHq12OA5z**Tj0?ugW?ne{nRiV~yx^9wg zmo9FRFXJY4%_|?crz=~PMD;qBjQohGmyux1Gg-K+mNVVV-egKTMB;XVH%cNs=iGFR zo)$dtGd=P9{k0AZq$q~o=WCebr%&X5EW+QB)Sc^(`mF3z2X=x6sD2AzxX==jC+bF^ zZ$jn81eu;eS+RN^^|F}CzOTwVew@!XuXHEw#kwVN9F?%TC>~NV^?y3(#NNZ2u{{Re z;|d0x#h`+$N|EA~KAV zanI|OrO6%p!LZBlVm@P&K9lrF%n4wm2(ZXeNZgEnz9_{Kum^gP3H42 z;?ZBG3h{l+A6rgqpv&fBf{+l6aA|`{8i?Ri)IzAH4=Pg_Fe! zF9bwnIesL1fUa!D$6S00xd{#~-A>Rm$i6rhINjr7n4BiyDG{oK#TU%wba*#_-X+L{!IT+*R;^EQ;KZ#Cjb-I8YV8*dQeOhY z?@q%PefmvoHcHU;PeE7lUK#vfU{~RP)PFDA8onaB0}YuGAea^G@*cmx?tWtGne{Ao zEfA)#9=ir#{AIFnQA<)jqbWxP@eS}p=J+1~%=;+-jlD7HvA?Iz>-%n;#d|ez?z>%G;eckf+GfLz1?{ZhJf{c_9Ug9#qWWIK*tM|D zZ=$*`Yfwu)!j$_R^)>4mBK7{NU&X;4a$F!X(K?I|J?R)A?x)&0rqiOz3f$RWLyug| z;wQpx%YnqdB)rr3n5ldo#&J`7dp#KasHAEr%w|ju%}6i$B>+H@LhpmkWpp^GG22wt zk$Mh|Ao9u_F%1;lHD#u$r`+`cP}ct*oCw>911uT?5F=q02s zI@4Hp^;H%8fC;qn)~@+|gZj5$n;U>66?=beIvuxW88zsAa(rt(z&DQC=i4Z4Uwx}u zZUn-U`gmmdtML zpBQADsux$R-=B)vy>LlMb}}a~Aj&26Lj*j6Gbfs0Z`_c@F3ny1z~R zI5!w3A;wHwp^F0Zj+|9TJ!3kAZVU+WayldmwkEq)p!+1FgG*#wxN%B$>76YdmIH(B zn{j2<+!XKkmtt8WkCQ%|swhI5<0{)kda38MHx5biYms5-+;!+AQ zhuZQa7^4; z>gS-_*PR(;UDoWg-6zxD2q@P)AJ!C#WRLFLWSHyc{-eGQ5SvFtMvengJ*&soML$Kx zAZSz(G@uUn;cb=q!w`@o4Zo3FWqW?i!%5Z|?QNca2%+voT+nhSJ{WWa%5v`P>s=4p zCv5)v3YkA18P<-E2ub@aYP~EV<4$DqKbeU{Q}gm|`i!*f)Lje6PBZN0y*)5^Z=uqm zec2N?`9>lEc^nLlmI!XC3MgHz#y>*p=Hj5e)dD!jbkBw;` z8v`tIv%GWsa1*D)%_^l7y6hZSH-w%r`L%r@k|#+==CjBRrkQN&Z;rj_3P&$ps?!tP zv1UoArGNOoYXCN!?Jb*D(PoTyIGS?0x3m~zA4ZM8TXYV2t?LKhd_^5e0Ep|~Z)q6V z%V}~C!PxWksfgAJed2;~L`r-{5xh2TOXFXn^ihqn@7-D_M?VdxE1ogVA)VH}k^{ftH;6NJ;%qI@*Qj#U}p# zlg%~Im99A3LF05;U0qlDb#g8!Xi8bkZP`f9BH?(I7;`H|ywOJF7(*9wbQ()i9JZ*Ir=#w9N2?tN-}J98wuqkg zuPg>bfV_NvAMO32_XERl_B*Eu#C$ZlQ$x)W=BL*KueUiw{;oL-2<|571e5)Z{0*B5 z5Q14NjA!W+|2RG8dh^PjAwnf?$!ECORypfcIgckWVH%YQZXqWF2Z{|Ml2)wo0_n!6 z$hD~pJL9T{Qt5avlMaOOnH^Gi`YpsK1U^aRXp#s7vY>Kkeq`X`gcg+V;?m1oy#+ew z8b5bOdnwA8CSv#5jfK002xI-kKtrP7{HE8ExdrZx5^=xYb^q_02$URoE2aXTL($Tx z63^BOZ#C%0@=h;!wq4r~!9H2dwXbmgOGDInH$$qKZ*kdw;r*sl-W|$^>;%PTQq=g2 zF+2|Y2@fHc!C@*I``xOH%-ukRVOlj)Qv_fcQ7q7JW2TJ58$MQ81Dh-F)Mk_YgK_Jx z&!v)$Vd>om+Wko?c7;gq1bvlm=_LOC%S2|zMXegYxqjE%zN z1!E;@TJf&8`$lE4(>VLK?&Gp-Zrkn1_Vs#w{mugfC6(L>&q0C4>eCvbi@U6j!#sjZ z(y$oMkp!XW$TQF+zxU%N;>lvPwd<&{dwXWG+A&X$!$gF8Iv^e)%^C9*;0ywnHp9n_ zSEHvO;L?$jRWeAXJb8)^eKRbtG(LM#Evb9Eoz;2I73og@qr7VOYP%`bujaCc;MVN| z$Q7Vgc03;|$P3(seX8`~--)1xs;lln`E=`+3}^+MTl=QPc)jLT%yc@VhBJu?T7C52 z?U_XOIyc_VXZ)FVa;_$vlhQxXRy64uh8}-ov#mr1J==elTB5!G{+gRV)N9kjy6Uu2 z@eSvv8LATP<iojjJ4qK9(cHaP2l@Psi&C?Vlr{BF0kQqNR@;Keez0AmciYRwBo%PBC9mrxQbW z#|5p~%NK^5m;d79Y|djb$zYq!##|_@A7XYSR?XBvpsrwS4wvU^Bu4m_LMdn9miAQ` ztmOLLkdl7z-wi)J8-fv*zwCq3&hjx<<3J}e^}y$xPr^m3T@@BFbtGO$V28Pi>2s&< zYRa2Ao0_-VVt;Fcsj~%j%m|z7T}T$&R)*_=rkJ}$`Fc%K6#Bq`OMLK~DkXC5p#?%2 zRlL49I~rCQM-0m`tuhge+^U?{umz2Vy&M4KK+ynMk+JJ$UB89_oKxmJ+1(i!PauKUa_JyF*#nq zrMx&|F3-kNgDp8>ajz?Xi^9>Bch3EKZGJx%Sdi&uU1I2YR{sUr6r|9@2xrTC=y`Il zpJ)cix2dEUeCa8GHr-;za+ys>$)_r#m92%g{MCJ;tu3SD_l0{)Ju_ZA!#{Bgt($P} zHMRpBC27IYdI=XrmVf{g-J{g8(=#vNh6iOh zYrXYM6zX(^eCYpv6xmIJO+Lv>;~dSaHz1wZPgmhM?-kFpDE&`;Z9BS zssNaG>`(v{^x1#DMyCJqHFkRJ(j=1eooDs~_RN&l^S=t}Nu%{Zu=}ncJNTzd-+kt5 z2H3Z{y4J0oNj~;)}n`GjuqM8liih34i+DWAgx4E9t3OkK@3D$)qp0-W7)N+TX(;zMBfFsNxALGUF+9dk zz)Qxd!4$ZwfSt@s2%ox?aQT$Fu^rx7zSt@+_IG$gjC#ein0WLw;mZ?}Pau*U(z4*u z_d`mniO)E}6^&W~I-q4JSwB0q#II4>4T-Rc^EK?pzAKN3!sA9&kEGg0B*BoZmHgsUv+3KrP!VCqT4}Z_0 zd{QL%-JFgYNNgK4D}lxer^v96Ay2L9klQ8!+%{)<(68Yj`#j3qo>L`GX^}mW5Rwh41>?z#@CJ!o7mlA&yf6 zS4wQz?jTL$Bb~RxGR56+h7&v$fG4m^QXv;-rQVCxOe;GP8Dx=fo}#nF(($<2h7zE| zy~RGw!{JhXDV1;VRjhdmD@BcXq9h1T4o~ynxvZMM>ny-Bw*i7(0prYMsg3!6NCxr- z6nGeq-&O%^rof0{_Ma2xd~j( z^2f7Ke3glolO$SVJ&xGVFoT(@CQ}W+x&X?OoSJ>HZwfwA&1eI(GmR{Du@gB~pPR4N zLOT=bx(zZ;!hhctQd{?&qcLR?q-x6)nKPH9l1g^tNdVoI65|LhxBE2tUL^;dsk!+` z{x7f7{b*ySrcj5S8EX0jufET2bUu#dQzsOe#We<@oR(k@yz-t3&en;0bj+NivBgQ{mR77j(sMifq5XQLl|RPHNW zp`t>1cpzt9&Es|zAxW!puPiph-nw4+cP2451`22uIZ!zH^$D^#?KedZxwuo7w_VRL zmi(_>ALq7r0&<~qf14xT{w~)4OlA2MnwZkp=;f6b&KKBN&0ukFc z2{^EuDW_gzk!-1OC;BuVE5)_L4hPq}(RV5quGK_&FsjS(DDl~zhb;j#T7ErO4>Wq9 zMXTlT1wI`xf#Qucrurd4fmrC>auhQ<@zL?r5k~JG`i%ETl$rP@6NCS zm%^T=+(S;EPFDH@$aS(#ZJ(h*KCe<#aXG*A$qA z*=ms^4`f+M;2=`Yt!&?Ld!bxW*k})2g4h}g5JtrDOVf;Q9pCu^T*Jf(n2Coxuq@9s zW(-cUfG#U!&<=OF9*!C8p81$&Y1-n@F~=OiZD$;M=$I?H-W>wac#6X7XvVG^$)9#- z$6HHRQ_%pXOr`Ba52Oli)qp%GUAE|WU3MF;s8q~&OCyflTPX?#jy^u%;ne7&egk_* z%0Ar|Bi6p`vC3$AJOeQQL4+ShkByz}ecae|2Nhh~{dv_#F&DQ0+UYkg{VMoGAgBFi z!jZ^kxp=FbZrGWZ#Bxl~)>6wXVGC$hfUQMtN(@}EX(6|h%5-Vz`rPi|xt+PyliCA7 z>eUh++KM9>q{MVmxW89&w~_}r>ZZ4LO|gg+A>d9#h{%afHFI&{junE1ZzlL0xBGy( zrKvP}OdA#h>7OG8;b=F!m||M)eB0A@d2N^xxDKeA&DO26itVOr-K)B(30gIa<3#&z z!FB4FL4}PLlL1A%FY3!87UYBWI6J%@p8T%chw$Vk(~*UR0aYlYAcdr>0pf(Y{fr{F z$jX`GwE9j zIrZ*8pbD64&M|s#4cvs$aA^7cvE^4jid8Jnd#E+l>a*}&|-wXr0=;%l6I^vVSmg31UU@O_+WgIpiVngJjBMrP|RPqER47s{$oN) z8Bp@I!qU{t3JKTiDI*ac>l~MrnntREr@WVvn^i>Uc)qvrYWo`mLrCg8LYQasHjr1IIlRPh7WYc*xKd^a9iE;VB4(sYb49}v=+IN&QN#}Z zHOBT=&HLt~Z2Ou+6*fpry58@hZnv-S08bxnu}u5#u;}Bm$@GUu5}>n+m4S;ngeJo$ zR|1Gdg;?RGTEK<5JD#^ddA2(UNxdQs)kKFtF z-pV3Xk0|i8D47nZoRI~GjJH><>AE^v__Zq^2*Y(+UQre~Ijs!wSoj5Q0GpUlub`6Tz1~-x+DDj_qejeSoH^C{E}be8MG{5E z@4<21={`J!3)AvoCOm)PA|j-=!AKe>hYvH#SOI`@gbz-8^+E-mHRj$G3ALY@@iW(r zHv(hnz1tj*S=sj+V5(@40RH+~1fHb}Tn$13rRh`=9?@du7KduA-4B!N>RpI$pi`1wZ18B=1EnJ_Mc0rSSEN~fQeX%9-LsCmsE zCjscMO3 z9XF#daQ!D`Xqy=}Nj_xvUoZb`!v!XMlk~W4{Z}lz*AQO;Os0rK3v&^eXr}{O-kdqS z7nYZ^TalmuO|Q2aOAghWBvCSIGVn+do@azBSbpGA8>uj)ocYODmpCkO9@uX*<^Mq* zGjp+-4a+%tEOh@34pZ3bcWEkef8o_ZYL&aaL?b7mlC$+^*~nE`c~%0NfbXDqnrzFa zZ6bd+b#)!8d&JN4sfJvdu&Sy3+_E*rmYX*_xiRuH#npf2mMVh(0Bytjyu#ujmA58@xg3)}#u;M8HZ&VOTh+s%H`y0o8hC zir$d-mALdzop<#q^+idWJ#w@{T$Cxv0 zrM7@ZEdwg(+|E~jOr%@nO%TY3EU>{{eQ~Ad2?+|-J7I>!9dry><4{^d)ZmyuxgYh4 z80$zzq5!4Z z<|ofYlGWTO_Kb<=yz;%RhEzYDSE5Hp87n5SoRT(C;s8U;JB|j^QDk#+))csNm(#ES zhQl|9@c^%j&WfHx=u2JI*2|*vDV~9@;F4f1XYpX0SxF(A0V>-n5!(A@_tu)f)HX!o z!6}(~oa)fvNf(jf{z)^}cbyFMvNiSSL&${#epkW-e;6&*4p*nK-NPAb)3sGmJYH@G zn?<@?vaGB25-*BA;GcTc>mw%WS>i^r`mAyIzooB4u&J zx^aZJT{Dr5dEYYKuybrkst3oMB>rD z4a?#=cQ=&{yc&&-c0}MwlE#2RMbiHe6J!54?x4Doh9Jpf_)8}Yz`R}>$OJ)a@9?f# ztd7d*vkyZ8`9Ty1$MPz+$8{yABs826p{eVouFcMyQ6XRuHH?V$py${_wDx6Rr{%nH z?P1+z$_rrR^ai(R=w3@3g{^lc17XT`&!($8n@TO`QO|?H3rxu>CBItJy^+ecN; z)>~81M117Sq{rVLr^BJJ;G-6=2DHbm{zRzo@0c@RADJ{B^U)UgPj*>=gqZhYcj{2C zQBX@!66MLPJHn6(Gb zbHi@l-ObsQPx)3BfUGR;SOyc|KI?Qx9|3qio9B$nBXL-xR;;rC=m;Wod1@pY?vS*- z9(bKOv!Oxzp~P4~)A31Cf)xsChZf50zY%7%IFWg_F&FIjBATvJ(Y|#F0Z?K6vB5-^ zJoov!!ViRmXlM_bh-lhqd)?Up0dI=#l!Id+YRd7X$prjY`*zQ&8ZH;qtoNT{n&z*W z*_>kPEC4t7mPo;nja6VQQdY%gCX3P^FsCE;-|iyYuz-$R54`r!>SpWxzz2nC^3TlStS&BZPc2!4%38Q1g*(!E=lfbrh* zcz15F@dxi*Orv$qFn-blUCLK{y%TAitA3jr{_0VVgSotog*2`Mro6Ud-cxh3)pBSt zc2|~$+i%54dO_u){kfcspAy6r6x7y9q6;4=A#o@dKeb5*WoKS8us=3^-dvE}3Ceoa{F z?r#}ttt(0$Ed$LoqOliKRq+4H#r%4@tot-;B@mST{h7mNPoZQNoMAGj8s?6#W~=psWUZ5&8btwEBd^3GDp zBM9FiKD{t~gD$BbH(;{BeNF+C4i4Zb00Crj&`M9Fxkcd{P^A4b+u`DyI ztY4`9e7z{s1W)-_J|Z5pAg%6_JeSB(cF+j%WY+`cXNuMQAP$29(z;@}a@kjc< zR|5bvFQ(Oh{&@iafI1vu8!VJ%m^ft%zmUwVenIjL##l=wSTJRn1P z5s9%r6G(HWQ0wwH7bUxImTVl@wp`ESe+qzL_gKJS@8}nUgL?iI{(A)HT-`$t zNJ%xQ47=8R^#{LtI|n0r+d#z%I%|8wRbRB4NsKXT$SE}uFeX?Qsx@he*9fmMCk)?; z5kR5Ha~3g1Nex9wNB|zY&|qFdM*J5F$1;iFe>^bwq1}3)l@j)&D)sFeWJ|F>hi4nB z1Ub9M40dvqHvZv_0icDmX?@X$Vt@Fl&@6s*wK>}VTLxKtdcdAEjbzos?={swxlY2R zGsai^IZG#Ca|DuydZ9SJVVhe-)i+?=jEhAhb$bz;7BASW^wi6%9JdizHrN=;pQ+Ol zo?Nz^t@-CUjw^}&we(+{AVtrZK6m$*(DDMaZ-KNGzWF2zzwh`>Lud-HrG0-v0G(dDmD zf^+_sc-r-6f627iT>k_clw+GPSmoDnXxUZO>HTh0E%0sC>+O1BpnO9DU?&PjJ&X3r zhrKWh=YfsMuL}Ks1f1ER-S8#x^-ARyw?A&)w?Rv%&HoFcH5B*M$6*(8EigKqp$lxB z`#I!FrzNfzw6qa)Vr+#U)rXZ(;Vj0Pr@=8P4Z9vqKUgGzVU13x=V)^jE{9tnNro(~ zqfmxIAa5U{1NsTcdFe>*^$M$AMnO*u8E@Enq>@5~E>D<59*Ri2^%n_6IZ#gSPcd%N z;i&-lzDiE$aBS=w6;%nJ-g0&R#A=|qTtQepRv)Wau)j@g7feaEdIG|xJlM|R$MM~q z5*|tpKnR5v^Eu8JL*<1zYzIai*Zo+JfVgrmhW}#Lewv#Btnt5gq#-qT0JBxhv#4qs z+Z)f~=XA9v34aG*n6}s6iF1@X9#);@C~f^JFEP+EIIW1n=~Bt}aOjEzZqt_@yzzh- zg$i)j)$@U#3iE0@Ygp1p^?>ODI?g~pG$O^((xLD>5Md-1`|+jLd0sggzr?my=JyuQ zt$rl4IvEN*&@4(_b1<-53BsoAOjiZ;j0uabzTj1RcAB8irV>YAPAZPn! zqdo~beVInNf!;*4#>gHwv~4#c;}0*e1p6JwtBaqBh#8AgMBPk*7D)9*w8{D{l@FyG z!K_yXgJOcyBP{R!WbFi5z_O_o-}L0$r%$Px1)zUN$yLPYoW_{kp;z6;GOJWdeT9Jp zEc*6l87=b1gK*O}2m{N=We7Ci_bbqAj7TK9YZyreEOx{aSC46^ZN*qZ2|18lIOD8e zdre)^CF8*N2KUj>xR~;7u#Vpx8orN&=F>nRT94H2M&OWJ2iq10=y;5xY;{xQaU+d# z!s<|YN>b{@`zS&E9^I^>f6MYyDA%ZMSM21x33Rco_DU*|Q_GmMQ3k8ue3Rpj0 zCvd`|hA*ueF3O@Fv*&o>VrvRo*ASyB*&XRH6}j!Wo=q^7E{yyd*sD`=rJme}D<##V8ntnSfX$k~7oufFDnwuW(OhpQxJX`KhN<8a5A1>3%}WeX zA~(yba27l$3761jeuIm(VgrKx^Fo4LFfjKV!^j=Ue3U3c66C-tqjD_?z_j$ zALKh_24Aa35aKT1%FHHTtl=qVfmeF8BV4oH8ra`YjvU6gNq9L4-O;e(YZ?;k2 z{*N27%6a{G4=Sb1Pjt<16b7pb)u7-1n#)4R=XDEA`%HhavYv=D1q`m!!2OxNO^aL6 zVzo<>f+}hHT4vb16N=V(EWx5}6oPZ&4a8hB?Zm^CfG*YoJr=F}GQg)NP5Xx?D|G;t z|DUnqRobUZ(BH$-tb6+07d4U#;y1q2`QHyTsY#!4Q|o(`9S33tI0W4NhiQ6yjRAAtSJ5ojL>)MjS;`>KXfK6lvPa`Q-7rAF<6zfS*IRp6K zf1e~@8E#GhKX!G|-OhX^17{s2g%y92R{a?-;lEGCRjH48*`I-J95hlE`?Zn%7E7sI zUqvgS=qkpmtDE$P8jBu)LqTa)VKZj;+6j@?2mq9->a6vE&GaEzV=*xV&96GE=4k}` zhEV9|NeodQOxe#8dY$;x2k<|QX!4pMtKM}-F^QD9Vw^$Ui{`>7h(P*LUS0R){C;z4 zgXd8QF}NOpA3V?T{>e#j#Hd>?O4?F~y`(h;0@f!D zqz^g{=LD%^+|g+ms~v5}MPUy{Qd;uD$dZLPYqnfTsL_52dAFiSHagrQTdo4O2izfD5((e>$7n3z5N?z zt$@_ekGTh5k42F!?lG13!v;{?YlCa%8{nXPZAGAyQrG5?uoFq>iyg?j?|;46*$Ur z`NZGB)b(}~mucVnk0wKhWZ7B8W z6|d8AwQWleBaK{)k|97ko!f3z&fsMh&{~7r9bSkWc$3{;{b84wjUykjp(Ku{bUY&I z(mlKYNTZAp%fQjW&mKU@rulvyd;dZ?8RfAf*h0tUof?F^DF=w}PyXQS+O}GK72no! zI~wGXqj}~SX(@Xe0Pb{@$}#DfJf44GQ~!Z#hgn2>W!b1+Y{68@#7VVV<;kSiD@`}2=plgm_u*hTC-!RM3c9E z5?09|US?<}8U=~qts4i6rCpdodm5(Ct0zt{&4FJ$E>uvZbwbHy#o$ajFfUPSelLhi z>zNvx-8gjla!r@^@jei+8c5cff!*$85YMW_)r1+=RLCJ5D&`ECpMz1tsA5XFBv@QI z=-J5t<{uiy$)Ch;kT)CwFxg2CeHniCf#~p21$fXLd^^zvsZKi^A+{%@^Q4I1+*#bv z%n{H^@i2#bQgkW{p3fW0G;D!F*?omo+c@(RFd8L2O6R!-k}U)eVgd+AlU0_K%-O5(8Uo7L z@r=Q!kD1uXI0CG+%F-yv15|$OSqu^*O$q#u9W*o@^*0$D)ft4E7`qW;qAsv6nEXen zzE0-lA1$Xack^Imm+j*^g6na(Bc8K$0B_Lwln8K^e>yb1>&VHO(S$j{N60A-5hPdn zl(BTR({){ic&iynF6nYi_W`8#KU~IkSe#q>mz62!nYLX!HzFvl5rfW6OKrFGN-bIj z$oIcdGCcma;k?&567kyQu^4?bZ?2Burxj~N+rJZmPql_C%)g+lvz9c)WS1=`b`=79 zk=RpwlQOKn9)vFX?OLim(JsJq5PWqu7e5x>eY_A=4H>9#KH*S#Jg^?fw5ola zhQ@5neMYUGq=jX*VkURa+DbIs%yJ1v2%?bC-d3N}@%}S_?`rnz7hzESoSbc*Wcv^) z&Ki&2fEv&{gYkAk2|hb1N#`^%6cUvZa9I*`bG6ZAcN?CyyxJp6jl`A|d~BHmM*H{P zsE=WIykG+6+Ot$5`{o^bC9l!9+bOW&>splZbC<^dR51jKZ&JIE1&`xo-*@psl=%<3 zuA}*maZqo7vQ4n6_j<(b`>M^@219QU**n4tCSbs$Bj1yPRT%|pn@#!-&owpt0C93J z=WT!N>0=}jEcm$oMFAlBTbEV1??r!kKm;^J)d6w`2P_8XBTD*qyZs9}*HNwF0V586 zs?Uy1rR!}(vr1Lun7HLTm&t&;gU37p__-nm3^1rp06JWQqk0&! zsJ!n%6Km^dT4{lrSy`MKM8aKt{IMJ)+Z#oiH?S z$h`N9)b(kualt9QSOR4aSa*4Rsn;o#wIvO$hANNlf*7% z5tV$pBQl-j_!Bo$HCx+>b>1G;{duuW9^={*C^}YuM&|hE7p_JHW~PbXI@`yE@M7IO zE3+iaNGER-vaIBKoCRy>L$<`dlJn|qrzv%Jsa;t$J%JL4IstHuEki3qZm}>B)xVS21s>l4~T5XgA@gBc+J|-_cd8AJHckb6vHUG_aCnQ%0&H*Gj zoZBgSBUny7LT^T1KnedSPa%EpKM4=vVkF+h=QodgmybUtCYL8*yl&qa&H8M!Y}TEG znwrxf}?~a60#im3sB1er|=BH^kDf}Pn)}8O81dnji_o^Y-xp+x#UPe!D!#fV_!-Vl% zfr^P-n7oFi2ya=HAWv30JnH8hO&b`o^W$qJ@#~hUh2IO|wipQ&pO^`6LBWIAH{~#< zR2D%!JVbMf(Fw~j-ZM!v(IGO}HX!N}_j@D*9t1+G(23*B3o&anP9=C?q9uQUmD>$I z)W2+>Q{=B`7SLXC>_dT#^KaBHyzy`NpAx2Lc}Sn5N>$s%_Sgv!3nRG}0BICCqKOs& z{gvGWY@<&vj8#l{WjrrkwQp?_*By-Oukq z=ivP*dhm#LzG%{&@Z=qOa4r16Aje=o z7z@zvQvhL8prVZA^8DkUM+CX#X2S?=a_@QPkKd*M-N^_=(8pRxn=s(v#|wDH zBKE87DiC$!{s1o8#N$DvQ4$dSK(te=+fX`(>6p+)ZT(NG8O{XxTnq>97eK}}Ay;); zRmFM$WEptF#U;qz3|o%;PuEHY@n&L6LxKSryxzxM35^Am6Uy8_N#t-63P_Y+-9a*6 zN#o3RAq(pt(DO{+tko6HISJa`2}6gEl<}<#eXb+RDj-D*18L87D;L0MVBN-W@l|e^ zUxv+W%<6X7V|k2jrON zvSpLgUKi8U!PqSf&yx%~-!+l!0YEIr_2O3%iU4FdGmjtuO_~8`l$<=u%-gjB1jE_b z3}CkH9Lg>kvt1NB4EinrMKhmWuU#L?sa66>e{Y|N!tD;zt4f;3BxJ2wdBC}ta!+$v zp-7)8E~|K4AV7N}I7c^>bI>!!A4{#mn^2SJm!s-PxXq((mrQI&Bskbhaf0-*5mHZ+ z7;+z*=1?&2E+5JcF;u{zUAAOWAWVWltSz=nv~D{v91jDtp3_ZBzqa3+mtqGeOIp+0 z+erO}17e^sG4{R$`m-AlWvUhw>s+$91tPE4sW(GHsOr;jJ_}_Lf+h!Fxm3uD71L+a zIi|{wbaiamp5ilVC;8A`{j>a4pT`WWL29GnS0wamI|4h&rM)7ipLE~G^dF{y8n=?` zAsu&dxF!O~`T3yC&iZ*N!Rs(Rqu$^4ETE>Q@U;q>Nnp4@;D8?Cf`q6ov5(8X4XHGw z>vg{5Q*29lLZY2H*@v)W?UZ0LbrTLeUoDKG)Eu?fESsB7amT}7#FIADql(`bd@Ihq z&@gdYOk$P+^agfv@zNY8>{D= zj)3s<+pj{w&-wc2M-&9vdKK-?6WVJdRT`>G@;k8aOCQnj8(M}hvad29|CE+EShlO( z>Pg+y%w8#~9RZ)uJtZ|&js6LYXxv1mWeKGGgc++fDL|8@H{h5OzyoB$E4F^s0DEK& z30vwC_O0tbi0l8SSYF&kKS}{8@P0aF>pm`er2alF#1gs*xm=@YsuvwiF>dge#*qt; z`(8o7LyYw0<~#jS4*!*yu`WdjWyX$rVip1yGWGth2aTWCZCvkZT+j5zE!h-fC4PM} zfI*y!&<%`$T4p*rcMfVCivCF3>pgOUz>@+lbK~2GI zs_Qb*8)g^BDPx!_3hB`x5nVub;(cyoBW_*f!nf~aCQ`(1!;U|nKoc)1oYsfRXz*GS zn@qUp%C*k*iNJEidAL}f`BEdbRg)zUL+0Z;ws*YdCR|A^SfpAY2B6Es&t^y`%@Jw| zy7i)pqy@E~75 zkwr=iY=papR0V?QMt#C~m}YF@$mi*}p?;5z25OP+NuytQqZGn%ftcVw7JLSBiyiV* z3~p9S(s9F%8*VgR*=hNi4Cu?KTQBPGDMv^KbSTR#hoXig8oD)`e{ge(Q#>_TVCb$# z`bMM5B;ytkVT54BhNao({)Ei7)`JMJi+1KGmb}H{bn?&Gi(ELdm&>sUf|k1c;Ap2X zW^?FWFC{x-(K6x`dP5054X6G*JH8kAl7PaD(XPO z7&JN#wvukd^AUDF5NPt%#)DzbPafmdIN;XRFSH5}-oWRk9>2?N{tg7_WFf*HfN-HY z3c=T9aj*AJc+UViyK8E>j>wL4@4XGktiEF!p(bf&WZSS5r9lnIif>(o_9m(u0gphv z$yH~|Wz`iPZu$dLs~g?6w)_P1BPJ9{{;rjonB0j9bG>dvNg+>TGn`$@2C*o11I@g( z32q|Sz*Jj)B1HL*O5`1~ZjL`Z4g8>Q8G@k+I&(`9jSNtj)=izOyg~|DGI{x&#if#c z=YQ8YGiAA!T~Nor@%^Ug!!ne^ya%$oVYmp3S|xA%J(`gmC<^OM1Uqq{t6j2aT}-a= znXAJWNo3Ye5mLR-t3PfYr79SR|FWckmxgb$bHhSJfZ3H8gE6!@cFuL^)t6C?oq@YL5wVqGPcF;LqXu*CoBO|=a^ z_@Btob`5T47IdQAK9F`d|bQMfkJ` z=j*ukgx$WbZJqo&>hjVZRtIcEm{#c{z=v|TgrBgt9`Kf+>5t_)zuzBlwB{_Be9rxSUf#X?K66Cl??JfRu7{tex?$`rVy<;laoSgKyQ8wc?NSwQ} zUh3s^>gC<3WKQBE^t&eZcRGw77HV zno@5gv7xrl58M797QPqaXj`xP;YOpYZI}8z{|(pDc-3Qgi`7hvgLp%_v5kETf0ur> zLuncp?MuQ*Tu4FZ4g$e&kP4BG1K(GK4rK_R|A&n9$3y@Fk(yW>myK{ZMY(mXHAn`U zy*C#AR#XY`99pui)>qU_9L@^(Z9)&)4UxcOl;p#jM%xj3p?4#1K6b8BEpnEVFLf22uC(U2KgurK$WD5Y`J7y7`WJL>-2}DA`W$k#E!G=l zJl%4bv3jbI$#Z>JQ$uu^d07AuE(nM+8NAF3ys~lhXzW8dv%XrkWjo8-$t2pf)MPMA zh-RH5tPX1sh2|kjI!ufo!?}sn{^Z_#QOjFKN49QoF>p>AjxUPrx;*MIB%WKNx1$+)Z`1un`Angpdd~XuDD2<6{f6w4+Jkn9z zp?o9kz{wet3G#eCusGwttsQko@7uPC;rsiM5L!Ab)JvyYf@`KPb9)KOGEcIqeWoE< z(acB;9?FMj_>L~!mZI0_Gl%B)%{UWw;+qxr>`7yu`QOx5qo8`M+o@uRz@1q~$q+GU zN|{DPLneYB>X1ATw_!aa(${KHVMk z;k-B@#L`j~z8= zy!1kS{CDuQ7Ypdc*1}JK!0~^KmH!vse5DzQ9Jsf`s&3#Lu+v9<(n*K`>7icHGApx^U8ie1}-%nWTteQUEcJvkl+YCOo1WpWtj|@CZ1i}(kGQBb~&p_ zrm(H<36L2D5DOl_9^=#AaPbm>g_?cU1T3NPPRMB;s-GG)1y7uWOF@EI*6;sPUVcd$ zhhPByDCqV%wji=SX8(G~v~53Om%yO3XACp;@w*A#+vw?^&fDz2Jpf$7fGs&DgQ^kc zb$Q7888fh=&Hh?xar7NfSmN;gV%pmt35EVHUGQY<8x2C`dB00gkhMbGuN+=&D?gNH zD=Y;G>di}Fj!Bu5C&@s6Q^x)cm^bcADLqxC3y~;(sNpL~^17x~hf*U53&u4q!c0q7 zO?;_JR$wulSpdK+Pi5xda_S2gQ;gsDpg2C?Ho6hE`VzH3UIyK<&v2#mOB zCMj6oYCB1DPceuGKW=C+=75T^KB91QSsk`PKTP0yM}1%-l3g=Gj&~D8#nX)jHq)AJ zLRjXRf9O6I%U})V4$AkNwN63pKUf9-#MrtkCK?*_n?6<0v8^ct+NkwM0!L~3myP1|Tp;ZUdcSt}w4UlPe7@wAE9;Syy4G(xW(Dlz4R}Iu3V}8( z--w=}4W~D9`YEu>m_!BtMDt5aK>=89@-vJ&$U@g@0i+7N~VMK>)OVn1=fsWgrtZ#p++Crz^3mycSQioG+nMp+qU7 zoaob`aF!lFKg*ZTo0V~RL#L+I5fpMTJ1eWJQ`-%W`?jNr&2VA&|+N4g*t0RKJw1|ej)M@v%uB z`=|;->(7cGq)HomJbJU#R&JdAEdE;ly1^>r)`-XF@Is|&n2qGy5E3HfTCavDQ3JyB=ZS-Ec7yUI--0p=e(6^ zZNm3MDf85E9*?%^Rsqaoo}ADJCX{n6sEnn&hc6vg!d5&D-_0df5eEW5;icqC0yX2b zo~)cOp;p1)p^3){husrS;FY9P4DVNpbO#3ev-DP~+s@TT!|TKCqhZC>>cc`O_6+lA z+u>w6oL68tU<%(?m;O@J%`!IG>O7-SS%@+lj9TOaj2n5)&Jd~`9aG^gPq>6&_|~WE ztD?^vrGD?HEXs*4*8^xkd!3d0Ay0FW7)$lRTgZQa5rkE|R-r{ZM;!|{0&Oa0#dBlY z=}h#uP}8MI(qkl?NyW(Tyy2cX;h)&N-x9_?X7leKZ7?&EKl9t{YEe6)FijJqv*IVr z)D?bqTkQuFw6@3SY^KFf#MtH|){6AySwOGw2(!d-|N7TBrq%bPjH_ul2yUG~Hur6U zn5rh3YDcP>g&0F~s>KkL_BPKr{DnLSv&PQ#VV42AY6XeRILcPC-WSmG!~tXAn4bjI%RUs7 z6kUqoEw3Ztor(hVFl#@;L2pDEjUN|U#x{;Vw3R$M?wc)s&Thwu{Fk$>~q7 z%@uRzL{bml{+IWa3zBG7-!gQK!^?;!+HXG|Rpd5~(h9I_j4V0rYD96@rmy7;7^pRJ zas$ijRYnZEPH{5!_bm-Ab@+v+tjB^$)8rJ#kn`cxRqZUBqJAUg5VjCO`Sw+>G1|Es zJBe-28ZDd^VKj}wIr#qw`2yGQQb3LiiZZ%-#;4N52PBdbP=~PJ_z+QsUQI6+LrR1n zo~O_TMH4B|n{69E1;MwBW3vZaiWp)=xecvY{mJgMb0>_>%%_-m1Q0Yf6sCfzka{#f zA11Q(FNc(Vtgbvw)$96P51f|QP0ro4_$!Q1)(?y1q4l>`0z7HcaJ9AO_&BKHzDK#EwPzto@QX;1Ty+z6jPwx?b zA68=!nZBvZRnGwK;g_yIFYlKulE-7}nD8 zalB+Xr0n!=d1nsXTj?x z&t9P3mC=RUG*Occx>dNH^6&7K1sBiJit3g3GL27e20I0jI1dX)I}4c=M#~!V6G~E% zR5Zx_n7-h!kCP(#{?}2i4R*p#(#kcz!s_QWCq!*_Fh%t>7yCCcC=2Y78m>R<4M8(P zK9;q2c9h-N&Y|^Vi*Tsj`vQ>VtB!S$KrgL)!D`wdk06x zuPz{MZRBv}PT;Z-8oR=y-4I6Zv#8?$SA4#>UceZVaPB%7P-44Y5k(|hJtau<69-b! z)-4n@7$-oUzk#OhVRg5P*kgU0B598%YhnQPWg9+{qwJ99E@;JbuR!Q-ns4Vw{`q;z z#!|9ZZP)DPYdK9yY3$0s6i*<#OTzNFsgnv%qISZLfz^IJ*c0XG_^&c%E#_uXFr)gxrZQWC%)WXg+!S zGt2(qPYV!OqfJD@lUV5d^IwkiT`_;bIsV!c-rFu%_I)IIYaG)gz$=ooNsD*kDbP*@ z+(2TKf3?Dx1c<6D(SafN0Ch0I{}03j%nAN5dGta`JDA2sTxlrMU;?rJlRX=$+aH^% z^xmUpso%@}->#E&a$Hq-OO`q+JF)2CFK|bgEnMalaOA?rfE_}_JdM!91+K^%P|=N4Ndts01EWAwWjkdz!5~#nNF`qCTGJv+88v(iV@}%SYP}E~^nU4Em4y;N zzIw)^abG*8p4Uf|{sg=tVj=YJ|2j*bCo4KLd|U#@kHbGpN~ngXnF(&jr5NZOT4SC8 zVULaPD175$cTrE>(Dxm(`QbIe->?}k3xr|BH-22cpkoSFW>kHjgD`SUB^sN+u6rH) z5^;u=TS~+8uv~CdV#GR?OMYT$1!}Jj3h#I15k3s;UE5SoRqHo8vH{;XvbSGHOMvTg zam-_IW=iM+Nh)Xj2^t1)3O@@_HWG?^a@C4EsFgrcp^j|~p%fFNhSp8P9G~t4*02Ts z^F`DIq*d^AEfTB>0;j``kf_}8p*V;Nd+B2!R|n;`j1^)>VY^E7eOz`V>_bY1AjH3& zH_6)K-ouk_OEg~JwBN^As<_9DD(|oYZ?l3*^^Ag}fJJevpS+NNWm4`Ta0o95o>f~D zE#(CXjmQ{tAqumXS_<#`E^2Xo8g>?jDl6PzdX9%caSL}fBpcnejg6q1U{>++Y74PjY(;18L(D*zk(`J|dJ(b8*GUg`DdKrzkws41 zIeeAW{T7@O&c_6F$F{uineB;rwc+H~E;)2x7rUEn}fOi7(W*Z2P zpsYM;bZJ*cbX8Lks~1<_jGCou=(1J2$kvTzkU}ZfYDp7qv^b1x(4@Av zEkT37F6qvpi=V%jK;VIQ(C+o1*UQ-@Ae(GChnR}o7bW`86*=rgZw3?~Y>G5y4=H}B zU9S$hji#$z*})SGPfLm4oC`H&L}%^G%gS3KpDCC4ekkEf z&sd>`M&dd2V6V|ahn7ki>9_Sds)R1%2RxT>t`k$jGTq|2ks=2ke~nbnNZ!Zuc+m75 z{s#WWoh7o!s^~fQJ&Ud>bG~%^@gXAQ9a+#=IznWIO2lzdvv>N92)qA~#rRPyEQg7R zidKeqXOR6AWr5t;OKy>9<@j3$6Sy@>#s~LNqe+3UV>OC?^S{$!z6N6l%P+%FgRSM0 zexiXI%Ig%B6TfJ*E)OmEkPo0|-TT#6=zEOfj8{Wq0we8Dr)wRfH(IbII+69WA@?mhKZ?3x(X zzNB1EyB+V33mX{TDl^s1Ta<))c)nB&M5qcypW?U|*=?#Nd*AJ|hVWfYo8)^j>p-F2 zqx8RXeIBW6==HRGxsW;P>Rhpd!+&1)pqE_-%`5|>nsSwgl@ji9%|&LXGzbs{Q;unz zcFC^~ia%e`?&a6@P8;^1p?p3Gac9QSzm=tGte zvryC(XDAbWoWAwn>c!nNd9U{6JxB#k2d5fX*1h{_uGm3bHlH=vr*8<3X}^-K28*1L z@?00+m;ApEUtnSZ_VdQpqZ|%y<T+lXl4O(gO zyt^h92RL_i^C}Ih`x06`aFeZf*0KoHZX>%Vy%3I>?7vY9@X-$X_@(I|dXdJ=XEDC4 zZGnEpS4$o)nTzjOp|kHnMGLfk|D}K_Clhd|?bsuWeQqo*)zorZtq46}^%iMx*ESKK zpde-P7Sd~gyQ= zPCTx7wC~~Cwf(qgxjeb|I|2DhCIUhgf?0vvEW|y`^uCjhOOh)@%>8lT;RIUKM&fpz zDzNM>a~X@UG})zFwr{J2Y0HEYHB`=`wyFzuRg#h?PD@96VX8lfoY7WKrBJ5=csdb< zS^KQZ5!sgPK7?9)m^pCuL@ElCKy2~@hcW_XGf$NKwEzR2EJ%~qpg7Wt7xH*#S}e>h znUmD)5Yv=a&LnOU%O*N=CynlxF^1H0;NABwP(iW z@zX~jYJDRq@YSCs9#>li@hJg2y#8(*cxJZ*h^qm4o=lC=21?we>nVTG65SFG+de@L zypSeo>Ltc^IzYYH8Ei7V7OPT3xv`~mlMRGzd>dt0Q4DGU%KdDF8w^vk$+e7>rY^NGBIE>3?w3w z$XjpuGJ@t)P1NPn$AKrm-oDA`<`2A@&R;0Z#cUvN#icwz;na;WD#N|moJJkDE65xN z_Z>-IZ&ca;p-$Gbd<@9-rUFcAvc5#JFS{$apK}EqM@)+uQB+m;OkA_91`mKM3;X^W z8Q>pFEHL7e`O7;r3M8?w?&t--jY}_!sG-vY7{YKy4b9iz#*5M>zc>Xt-YW8Wz0948 zAoDjl?p!YJkD$>Wj~v|QJbt`@ zjbZWz7}Za))Q61wZrFxIv~kw73<3*mJ9@z*!i2vN3kTs*tkyD6MOx)ET>U}05B0A` zXR0lgV@HCIBV~J;KNZ+ETmoP=%wJ#5-lmNB}A! zmo|TDib@|YYrR;2p(Y@Yx=;3&So2!8PytO~z_ERVUqZft+K@YGQL-rhrHx(us)G<% z_&-dYQ*>BexUOT{wr$&PgT`!ZCynim%0+H6axvGO-}k=H zv!_v$4m*Jt3YGR?s!sPyyxdvV-=>oQ-fEct%_SL8Ms6dqKRu^CuJvL|LBKZF&B_OG zIQ2%BWWK0f(D=I(WdV_hx6o3*OJ{Jr{*#e&O3AnZO-0NVcf5@q5S;_c4ObVP90vN1 z&>fNpx)o=HG>kQM0y*7%0(wRxuB!No#JkC~FbYlEMr%N4xcT*&ZOMQ4Hr!{_x%r`GYPOz4R78tnjt{K(js(_sjFK<9OE6m? zJPSdOalawvk&)P*0jdPoX%m_o5RB7`0I#&yjv6RERot8G?@a>TuK0|H+bxc zDgGs5IG1Me;O3%VUA13ZQWb;8O2zg* zoa58|4C}wwHpq9rLDk1*SaX|L#|ooEpPaFMN+u_2FoAJ`qwKd>htCwZ^YJY~{a57- zlMgJt;EzT*ZX6~Wtn?ZZn~i|NV*x;n>HnPre&)PDL1~Q~B)VG3kNN#JV}F8WkQ+o*#R}<@RqH6h5tRT_`HjX7S8x(+$^g zCVK%Ct^!qBG-nm6F=!_69SJ3TeP7M}$AGIiuoHHg{0v7YYvC|} z-4}yTgbq>LUj_;kgK?okcN2Xul#+~-tWl2xH&RDnjJ>aC$p-rymO<%&P14Hv4{5UO z7hn9?03?L_rdFo}o)*Xq*A&H2pJtJVMW22* zo6g_j9Pdoh2V)pM2@h_^trfK(H|QWNV1K(=rR0_1Reb z{i?zMRD~n=XDq$lUY;2Ks`;PF64n2K4;`UBNgzP9kKxB#l@cZ^+S-CpFSJso- z@3+V1rN59n{PYWi)8V;81de~Tz(HX`70H@V#EvGAYTNO0VYL(lA!4A^eEdEMS#sJJ9RrTOT=O*E_@8e|M3Q+e@ab)W_{lSSk+jZshK%MENxB7QZX(v6)&TJ=1;ZFS3-m>Gx|M!M6?J}ga}_R;?uc6=dd0d4v>3n;)2 z*T`7@ly>>(Ujp&CVgTRjci#QE*9%yVf8Op}u2lMqbF4?{s|`Gc7}r?-2yz$N_Kyc( zBUGYUC?K6qVpisEj5G<(^Vf=qgFFG-7HxCe}(RNaoR@|_ycs;2p zoX2L14B?1tGUXvj{&S2{0KYO{@B=w9KSt=4_MWp!*Z1Y%zZOFuJhK1*ZD;Iy-o5hL zdJ84{0=m4}?ZC)N44#n#u$_>sdEZTb@r8Yz{Zjj!{J&?)i4Yi&1r_hQDmhDD0MKb! zUYEErvit{>G3rn*`LndQ9#fh^3}edse+d|y+wP_gJ`aM|F%{%Kk-qzbz5H=U*t8jz zrHEFLW%HO|#YEZf2L-ighOuiAFW(t3sQBtSd%GfD=Q}OwohDI5XgJCWY6`@M&TfV( zVck(`T6dx{(Cyxhyro%B5uodiUb<Je(Uniguw#(I7v7|qj3n~{Hmlc+fFS9LsBKw^aQsPn zH2nDEwXCLCV#?-dP3B81XB$Z(GRZz;rFeiaf=v*wMbNV+7m37M(8bLput3-!(UJ_8 zQjY|;wMj>dL{>%!^v_Q2Nu8WdX2y5yGI=i;2dw0)W`oqQ?+@a{Wmmc3*9z4AxytZU zTtM$~!U7jlE+{R(%dS?68g+lW;s?i6Dz*JViGV z=smV+4x)$+C?)CFp76|8zz{(`q70vOsVzN_V5~%nu6+d3WYYF+I#gc0yi#U)WQ*mB zT(JRcSU2a)CeJ-E?e#Huh&XBIGaIR5?ie%oP@#5{cw`Pz^F70<+a`v-r@7BWHNndY z{%u5a4(vhF?@eC{MjcK>IzJZ9xt+wF z(C7E!44Vqok<-)0nXKrW=z0b%pgM{*AEi9g>R#9P%J#A1?v=lIX70sS2GmSk^W_G5 za%=8ed^onw)C<6&G}j!Vi=^10_h|5}fk@A`kuh)C5atg|RT&hJQV+-H@$CgP=U9SC z#g%Yy?kmWYNRxrxLyd}ujKpC@f_AVWZ!9a9TcQPpd6amCY!!U!O>oSa$zKoqKr-*K ztKunMa}pzxP-#5{nwato_E)ZcshQB3@SxCr$3W?dAy8s5u00F{giJ}#I8eWOhX^9d zt+FN>Cs$D!JI)c500ayeB6_C&fsH;@it4c~h)samPC5fTGvM|C znPVdWC8??%!ZS8D20~3wfbs-CQ2E8+I}ls^OiuW##AjI!(Caei&XO<5{r@{Od4p?fni5-sV<{RdY8l`K1U8t7fegp=9vYi-dfqOnl9~P5MgR%!L zseF6-ZTnW@QLI@MP753o$yPrxU3}~_i1>c{aU{Yb3N7#{_pa)2a)6D|N1J5?$f&T( z*7~Y3bebqTs(>V?kM<62nB_0P`Zx+c1OlI3qiqL|-suzpdlABJmY0$5VPWj3fxRx> z*8ZfPKLPOQ!DiNi-xKq0;cKFrh*iKGbi1_5^vqpDV-4EN0~0IZ>u;&3;Y?R)Y!TL4oF zCMB3ll2iRdKL!aGW_xb8KwZ^$xotkyzQ(9YkvE+E`@KI;h1jUmHf5)3(R^fB4*V|_ zS}-lSS!CnJVH%!r_(rXe=yb>A_kkkT=HO@ehc8x9gH;%GlxSCc)C#>r8i&%N zs&!7jEYVN~4$Gh_B|Js!A@aFSMU=1%VVb+RG;y=UA5iY#u}KVwoJfDv&s_K88eah( zDe;`CDhiJ?a!zq9Rl#`Gbv^h7>|=KFq=~pIDO!_T`r)2`RY`Q^%FfB`E}L4t*B(B+ z{U{D&#@qPb7M#8#E<@*9(@M9!3QYVjH$Q=Lqw*zI*c{fTRnGxP}>{vzd@ zr1VN8<6`py?hF(p4?r+pp{_K;BK0Q)xf%lBow$PwwE5!IVrnaqV59wc9q$qK)(f3X zPfB_gub<`TO9=0QO-OCMh=826{J7^hj2YIrR5cu)s$sSPIr0lv$tpL5pc`PIBr~?| ze!@`SQ2&yyR4zbTF21maS zL$`Odyjc8zcx9KTAZq(z8X3Ey9+?r2)B;}VMqTl&ox|IOX=HJR)0i(%e7x?1m){!} z23rP#9y@;PWP@Qut3V^#@Q>Wc!;Coba}Ts`*VhO8r_$cr*4HOM{syL(wY?7|@7)If zof+;)z&Y_>r-}bwIJomTFKTngA{Dnt2lyS4^vgo^SSimUwq66%9r7r!X?I)zd~(w7 z*j?YlT>n$pY!w2R7Ei{Pvhqdh2^9<@>*kh&}-8!t8AnQS8vu5<#kK*J@g-lp)bc#`r8?x@~vzcZgvw zl3rZ~FQAcDS5X-a{MKTxde5>rG3-x?zr1UzKWxAH1R<1=y;X|w!RMPi^|Y7%$_{OD z!i0FX8pzhT3oELIAB3eg+um%m2uD4~(^@x5SU){RP ziUj*6=qmC%Vx#x>1;41U>bh<7tJGNnZ4gVReZ_Zql;5-{AgL)Tm0n#F8BCSr zuK*ARF|U0`B-?BiIF-O3sBF*9YTgP#N=x3z&4alVpJTW9LD98(kI9DnyM!J{rhsTw9S-BWJd~+@ojgLs4C`TU*zQNPUOQZ z_w7cOW5m~Z6{ZOy1yh)P+bIp=k9|+%7bq3ZnIZ7h*<*~&;F2QB>(FgClN@>f;uh?v z>$j?J!A?VZKlcZrJ52$&H93G8ys7WCfJ{6xG#*_OW z7n^l6#C?Bjn9;hH<^dbx$TF-@>;{LB`S0z>dGmIhhIcI?xtCUlCKiYZ8-%E9P$~F)TLD(?pvtLmpadH(@mq1G zJijmlk4hZVg>UD2Tb&fG(aCbB6m$VMl%YA61=L0^p75e^(! zy$B*yd_9ELt1efGcFaK1?G&!dZl9uFK$k*01(YD1o)d0jK(Zbx%o$UO5tW#+4ZK;$ zD(@BxBQdel?E!sO%ibT|qKc+fD~qb`&)5Hs4q^TOe{_HxaR)p-@ zrP!2#e|5qHP)7&lG_7#8Ui2*H*@6~FA@AY_pedHX4CPjESE#Ck(BIpY$9P?41v}d#QM7n1d$!qE_U&SC<&%U>L*QleqNH?D)ee==c6a|mqu;T>0?a8yLz^yBy6+1c;ckk6InsLw z%=%YV`=Xxd+l4%Zoo{~hDSNrOP(9J8j%sH~G7jI+kNj`fMwg-12bk3~S?Y|_SbMMnGZVYSs*| zS&JXMW>W`2L@)*>;Q{fgfYv8RpZ5hoWXnivJC7cxMD1W*cK6Hn=KzqWh1oY?QRI|G zvz`F@lYb=Xp9SoXXA6-ri1_$X^!cLFtgaUKm}o*~kDB9ezxpnK603Q&`;V>s6@ zYW*wGpEXvb5A4|<=E5Pr{FRPLU!m29sXpGetkZEMrO~Ls|8a57x!{%tQsCe!3~y9z zHY_kX$^=0Xm@?4@Bap%y&aN8aTdd=?oH2-PQJ%TkC&R2BQytHap2z;~{R^s<-2KRR zhT&|^DR?9b9sqgcX^BjUydfF}VR0?hLfhT#0# z);(B6XHxBF)nUnCWq73SsCk0MeNyUIveLY<&axnv937 zp1Y92vr8X=fUV6`TqwGo4Q!*VoD1XDHWoA0hzLrCob)sRF^RnCbJY7eSfUK; zDoc-lgg|h)A%@wB2o}22?(EW-AAQ4bvB-zxhQsG+0*6H%@ z*!=|on=^P6HqEPgHaq=)DMSNNQjiq6Ou)f!u&wX6e(`a+B~!{6?53h-y|fJjFDauT zFnI5yh;QCCCCn4!IB}_B{rRBUXfVPOCb^uL0 z2Bb(S)AKkt%s0PNsLWtW=*{NjBVbOrUDKu($mqJWxQ*d&UPEytBOMhn07OQZH5U{ ziBWJ(hY6$7Yya?9S%D^1Y|``*b}9M}s^VqlM{uKkvraDsqT7iHDw19}ab#Vh@AvzoT^vBw~Oz}CS$5AF7 zR;~Oq(}yDm(i)3+q`Lq{<@O%B3GD%KGpX4?qQABr0r!eIb769O=7?xs@3naZ@?2LP zqhj=Kr17zo%1VZ_1-;U9r~9K9>iBB;Q(_nh%eUBKUw{U_STs4w^k zZi;K|JYDTn{mbr6r6&`J1vF>hW!T?;VQ*K})>>L11Sj?%0ghu@obhmo9)W*lHe<&e zA|R-Y7b|!TJ8b#j?ye_v1&y?zI&UK=BZh3liyGjf>dsuCwfeR&r$4wuU-l>UoV7ep za0CAVUtUdH%i&VLUl$Y_MRPprWTX*vke_*3YwiLKl z9ksyDX>Bd;77|Mp-&W5oHtUD;aoxep+GlL&5Z!P{Q(C68`M~pt^eKTqtcv2Q3u%PZ zBPz@tL2i!&zOC9;pZ~PpJt!51^#mhG1TyF>p)-KEZ^GfN1!8_}5X)pWEiP#A0Xvx+ zXd3(N)X}yigvLio^=H+@I7XUlq$_v#!6Tz=*@=c}zpU7+`#=F^-@TZrbaX-#hf zgT;!}vF_B(Y@eti%>vKcL13T2oy7U1FxhwZZ@daaI+_S~56OC~U!?@MW2ZF5?42vbEAf@SmEgAlT$$(dzQ%v! zN)7{iLZO_)M+xQi&1bTW1GScgN6`-euy=$de^YVg=hr%Pa^?N&_(+&}i$ut4UQEE` zeG5>hk1*{&Y4Y$BPGXVTOx*&D%dMa7Pg?tjjfV*+geh406-giAqmE^(%eB??Rg zkRTV8iIewLGVu5ZE%d#a#~APV(!D%t`R2@^`g}@6O%W#nxVjtsJro5+0&=;uf}j$5 zz%%6}jBV@v@D-{TU_Et67UIH3cdZLQb&OIy^aRQwnyZX?ZRxP>eNEb96*AS4G`bN8 zGyh@B=5G|U`KkHw7@5zjKA{0&*+s>Pfezvb9x$2|+XhLn7lgA))OYXMjWS2!jT>Ljsaz* zSna;NyeyslJg~&ram@|k_d@42pzkz#_GZBIE&gSDf3z7epm3;uj($5Og;dAYv&F`F zH6|{1STU2Bvs-B@&QN*zx*bmzU}=@?(^TewN;3pCxz7ezZ*Hjz_9G(wEHRgT{}kZ; z!f*nsaKznh5!-#cKjd~u4T*x?8TRXxxg0?7^nzSjw>7$)W||zZxY3s!&C*R_ilU=8 z){-x#^so9qa{L_VwbcFYWA4k|rG;M%^0$2Ls@>0AUfJ z@@E=0IHn=hP_LZWgdqPK>4CSPIrJeQa%z1hXq;4|SN zSPg4l)mnU5EDu%9lq>W@GaFPUt{0^Z<0i9h9=s6qy_LF!0e8XxI3f|RE7OY|ZPilg z?50l}^4iYS{fOKNYA@PYlD+&WKv|3kKz3m{qjhaV9@tK5_g8Tk6oVpVFmUbyvo)1H zzb8*&K$(A0@O;rPpZ)DB_TgC`9mBfP z2gwRI7~tPY<7y6ja_RDepJ_h&M;Cw2j!lDV8&yE%hWl>BgB_C51kf+{VspG@Xf=Vg z&v{rPuHc~{x7jduMMS_xH)Uj+%w!q57{g@~F}6g9CD!Y!Tv4&=@m<~on1d}8z@!r? zYY;#Lgdn3gvWwbE(?OWla530 zq*tf&VfL3Wl5oeN7=jOLwlx#=;}e$lG1*YevILC1@=u(Epd!RFRtgXcP@}O5V$k!N zex#53Lhi5kyZ?$J;O8w)D*yrhI)qsQ2%h`-`r{>jJ^e4Dqy|N~_ir4TKV>rD5K+77 z!tc3L#~lhxU!5czsKz&bQ#wbD``PKEONXihuh%03QUu^vJeSdkKipPJh4zn-FFW1+ zwX7@0jNR93JAhzk(ppkL@xVq?#b;cki{5toWn2H2w^Hw9xB!y@POs2yTw4AKP5ZeD zyKAaIfQF87^w>;QXHy-?*uUC0y-)>W;x@9ZrpuR9GL7OZpi}12PKK7(DUMX?e_}3- zKfxy&5fe5j@_N>PSPg=va@_y3j z?FBnYf2im>Q7AkxnPv_)MFm3`lHgexhtjwoz7#)#6T5bez2yAE(K<0WP@5j25iQb5 z@Qv@{Crqwb#fF*=k_z37Mal9xe)*(2{ycWk7{A{5IjitTtE%I6yNc7)P->c7EZ#7& zI2!dwPo-@&ke#qa_Zm~5WrbM9Gc%ILr_uADNo4`H;`k;&;RdVDqMw6%wZvE1d(%TQ zRoW?bHCI;L7Q+>M#2aY~l8~0TP|DLZoJle2Il!`sOC-Z~lL^#rXGPNLd*A}8(HD6O zsDzq*MzhwAZd@ok1a39$MJwnkJ7g{}cl!d3(}4vwnp zO%E1`JBQ|#X_V{VfX;9{tsM(8`?(8vjx+KejU)TYKV~|?sOjwHv>}#L!3wLUNH3Kdl%h^I>W9*BDIki_8_!Lf`+bpDPM6TtcrL~f; zgE(lQn>nO^sS!N#$|+15XBF1p;-aAK38nyCQ{NCRqu9nUNWNqR{ci#8150mALop}1p#bHJ`7hCBTe*CF>8O!=?Ts?&g-? z!4a^Q*I4ykTEbd$Tl*E(|Hkj>RPFvIaMy7I;7#IO3U)pvTv{D(_g_IZjN#crs9sQ7 z@W15>s+oPjYy(NJOF#=&KZvC>!GF~ObWhoRGn<)Q$84K7ngCmN8$XZ%BL-Z2;O8ap z)inP@p)-(eqJ2ujq#tKCh$zXCQ$P8hqHQ}+bY_&F$XQ`S?ge;j zQoi3NV}gc5wJf}szkEmax{2E@PU!w@+!R!q6e)o8Z!k*e@K`cx!Z*J*D*pQ{Z(qHZBKWbMyKG_dAimx3 z*Tk;C9rrHPNH&@WDm5T#D|#Jg&zIq0M*DSI4!r}3w9fmH;i5tdH?68vdJgY6z|O%& z8tx*7eaY?=DStnS3+|D3j#0xnbvAx&4z`XL5SiBMuVB+uhEG`+=HvohYx*wV#f8GHVhi=)f!?ZDH92{^g1;EnvfVm;X z(h1SHf~p)+-}hU0HJ3@&Zf2sBlw75PaA>oE^1r;pl(ZY%9A)goeZ zX`+KA4pG?5$1*%Ie65D9EXMtBL1aW^;}$G)~ky z4>cKE~CbYDaT{_E--9=ART`;Pe2>EWPbODlBMqs_T1s9UB_G&Ge&V`gE zt3=_2Skbb{U%cH#Hsgx*)kO}x_{fM~cO40$cvruq83#O{mh-iNRwRpJgWZ$CJ$rEU zpzN}I)JY3(Eg&<(!nXiAPm;5k8UAYyYrpJZ=qM(vIZSfO8(EeVI^pb@gbj>B>hhB8 zbEK>#Dn0UQK_+jN(=Cf8rKP{(hqm!?*6iAtINfse(P0iovq%JN7A=jV#pl zJq}L1r42Pd700hpdukApcF6sU)%TOu*@e@X1GtYGQp2wDMfB4(xt zkVEM+uqu5$^d2Wo?C|(p>P`|3>-qTYBYc(@l0^jNX^;>q zh#zvjU!)_vJ+;cw`;<`o5?dvily1!%{q8eH{`J6Z@HkWXFxJgS_1ULi%rCLFIv_7o zzBh(vo#1}OJmho@%N;js{cG1o=nUTA7?EQsQA3@Q{gg8VP1tG^1GOLM$4d^B!Yc~U z2*1cmis5l@+}Gy+DZ}-c{B<)>okXrXS2dFM{Ot2o*_P)x&PeYw#;hhf1WqNY%hnu? zk%0lAXq^uN`q;G~q>_S0lfF1mG_+)*PKQF7wdBj!!WR>9D6OGAZLR6tlF+6&RDGIg z&w(2gnqFQHQ=@(s5HRaUrxFOC8W~}NXLP|=NvVxFvAz4_1y7I{kTislW2p3ZyUy|t zefSi#wDCyWY6Zf#sLV#q9c{Y{Gp=L`qq3Z@$L8cbyu?}_>K&l8Ms)WNF158k>w4q5 zvbjp&y${~nZKRKl6*FMGA-|2ob}#zuj1H*+mlNz~$KxtmR0K;sfQiL6VI0Z>CxCX= z!c)OvSI^f^IbE6C7qi60u2TTliCWo+ET~st{Fl8g(Fxk1a9VQ~STidZlmAzCE)NM* z$ZlhovH!<0Y{r5{HQz4o+Ba$xAyrbHrA09+%NU}=S{WLW5pT|koWh^Vr8pt<&9Qe2 zS>AT7o1U)WnozD4b-@;J6}Dk8{K$@2m!IlCLGUd2xEO1$)w6jVca)BJ>5l7pRacL$ zT(X3X#5(cV3r#_=&Rx`T=QO*=7fy5qi+l)J^!|#|842;td9udBjY^=)6yg5WeM<&M zIBCZ0z&xEo_+z5FEgha>cHVeMFVa&4)b0FVR}kKyEH8*HiY2=GLJnHdGx z3GD;dBTn7ws-^C(t~4c2g~{@^ZWqJo#ld7r43-EzLLepd?dwi5h~)cu6K&PUHiHGi zD3D!A`BDsWSzwX!N8rOKK&yH|`AUh>5%IiRK7rvsR1Ki5_DL8#Gx@J27UhkHhhoG-9D3?OZS(>357}8k&3MV zCf}(YKzX<80ofB@vS7TVuK_l12o{DQ(`T6N(nNXYO5MzUlvkPzj`Hz~1J|c3zwYzT zNp6iLQRsy&NJol5eB5vpb(7RB1o<6glR@E6N3A=cz{)b5gzQto<~>DX!1Ub&^<~97 zM1Ew?zvJl-D3SHH{5beQ)7t6W9;U{5r-pFme;}zWhFkgT$<$1DeaT1dh9lc=J*07= z9?dI7?;imh!kie0;Q`vC*pI$nZ%&;Z$v?zr;+OA7$i1rP(qaBM5O7A*l%KbnBiH+c z?LP0F#X&0sjF=1Sbc&>v!C?Fr3+wp-jDWe|Q8j!qns>b}*hamR=*whkIl-7;-busm zb(s~wLugO6=R<_J_<-PP`M)8pRd!u0gN|E$T`i=lx_5s=4l>01r!r)cwVBT~rK3fq zqhv-nXxJ28S%nl%HZ~8J`!@ROj8}iDt3m82YwB+q%WtYZOd@BUs54?!5*oO((>o0y zKD&x2P!LuLP0H4W(k{w$uMD1U@Uw}n{`%C)G^xm^pk{etMJ&3JSx&DfjkA===YsCz z*iyc4YjDZa0`+W&&uU64(s}{WBE^18hOYC|MiPD>59Q<94fSX)Dj|@|hCz5$dRD7> zZZHk=7}k{wUVBpHzG7I%PJ=b{Ce48wu0NHz)srQDX8RP~-ZeEZ1j)qN{eoHU5?BHj ze4DHgJN1a?&;#JDw%VvBOD?4aAwDEn#k9=Af6?{@K7%~wm4CoW(68eCZWRQCh}k~25xSMoOaIVdgdH+NF8c+ycb=b`l!eJN~e7(3jfxUmKH%jna zMyVTNt)$7IM=sS7Gv&8PsKQQ%d$d)Ens%KQsHdslT#CM%ioWz+s%{7pPP$gc`o~js z{{aY}kja#R1^0{t^yE-wtyHJR^a>|eV5}Utw#jBge*=w1X;H_kU*Qa;e2&_S69M^4 z*3JZ>Tw5alFW4&8JO%0gc$d8-BI2@W z-HkwDi+9$6(xM|ZjiM^SZfO}Bj9x6#IU3u;`#mYzm{VP&0k6oqyEkI#65mVbiLdl6 zKe6J2bAwy`@$~f31i_^n%vtmant}F(absffhtt~%uDSPeQTGm_>K8I5?QFfsx$?+M zyYLIHMVnPLz}8m63cFw_!VZS{4*L57VEfKD7*ffjV{*ixz~QBfG#tBzD0nFbw|K&s z%{P!>khq(E&eUgrL~1&Lv+v=WC$Ktt-HsML%N5^|l&?W41vsU#Pw{vpX%SttExkp! z7p0yGlCbrDTdv9IM=JM^w%;AOb=zDfCdGS$*{&OB`nz_;b_lxyJjM8c7QN8xasDYl z!A{<`X<9MsC;oavX6ly)>1Wdn1(wO$JA7?6w((8ykE=FJ(D&Y!*};7=4AuLw})L*`gJQIE{$8%Ub=EM z09i0ejP;u_-9`l#s&0-MD{!szsmi7|G8kUvXYXS6r&_=us`R~3X3ajtWgt6dD;Drn zs{TQ=`v?GixA;*o4_-e0Noyn+V~7ZJMWYWoZ0=*QrHKvwj0DWx>cjAnPBX(SpiNue zXvlzO%O^`Di!?k9LZ61}*M>uXo1SH1WW&58(@t&V*J&4~!fIX>Fqu0Uc%`jlJDKBJ zoA=zB|4rIHFT(F+*^)l|mN znIyxJ4F(c(aJ_b)pE|4W6|ckU^w+J5hvug%f0%6g3XwbKpr%DCSY9;38)&eFkrarX ztCzu3Bsy`x?7wXId5f6rMVAAXJwtwl$cmabK+x$cMrSB~cN!Z!S?ZYXM!-d2$fs)l z$W>Y&n*?!87dUZvUF)f#{>Wc>n2_?zrYK*n(} z3(`uhHv&#?Fi1xhsl0q}XodEKvQ8G?5Q-P`HPnd<#sYU7A0o7H4X8Y??j_odky@)9 zUbv&nXQN&k$&RIycnKx!9r3u^V|gdQv)I*Im@iZ>Bj4_imx%6{gjSgWDrNp)6@! zq~m~=)-s6`^OyZT4@-6Me(7$FiS*g|lti!4gnZFY%+zm+MQ<8*r-mmXTxxgD2!~RF zid}VQte-Qp&cG8K;XLMK*SDteZ}RPQaZtR=9-_6tdQ}m*u*sy*CZx> zISkmby(tNQTtZ?CYMV2oq1MZB@)Vtx{XFSI0O5l7q-FEFJwjmNP?N}zp(w3 z_+AsYk`Cc7d*Y#uFo6MT)hP66t=ED^~UG*j-8&5kB`ZVtii6( z-aio7&&P65yIN>cEb2BDUc26s64!o4SqYz2#OwRvzQKs7e+6Q9{P%Zvf4wesKc=0^ zKAqT%jcvqQ-|mmzO$&bkVc6TSte5OLf+X`A1Y%HxaYI}ouwP>#)MkM%_CTSG37@f4 z=;Pi=j178ed94F{A~VC=Y4CpLx%iX1GNWxmm1%OxkG0LI}6MC3b z`>s14AgeI7S7`1I;kdnUeMOEwa)VZS@8KujpYmOG=#RHRatbK~Qe(aB5ufqHyssze zBz>VLc<;bJIEDq%U#@hB98V~Zk|7DTsHgc!IndvZb5n)O--~19nLJ}rYDSFjlOJdZ z(EO9_ll>+Z=)oZwX(BHqQn%#9W#izMtgE8Lnq3Ie|8JmxBXK!k`S>oIc^8ZgW*>R@ ze8g$UjPw!XCEW(J%Mc*lc}1Z?Z_kxn!*U#k5fS;e*o~U!hP3Tv_x_x#B%9zMab7Ao z1D|2}fz}9trn79ZBq9zTOvO?A{&Gk!Ted9fWPMYzdC|;lDL#a3<)%)V{kyT|Fk39$ z-6l#Fot+eEUa#IwM?A9x>(e%Xkh^qK3X~18w_ZHptATq)%ozaY&jOblhKo}k zOg~f@O>#y}li(C)aln=Ww5lI!tZ_+P8Z+OyN|`E}q|6n`Nk`0d%o@k&9$3>JO_NF? z`bDBICIXArxG<(k6Msmg@D^Bp%a4q9GnKu4A2*U1E@+zi$|*>an^jI-RDfl>x$SYW?vjP zFvP?Xe8!BpMY3{krD4wF&!9>KgF}*5)fv^@n0{Rm?Z}av0pc$`sK;JCy#}qeY7hd} zqNi+;KMFbH3K4>d4Jm^7My?GsF}_m*&U8qI_Iqb`gV`R-+n+0$`m@PE)+rZW1%n0&-c@V4}u!q``qwv3l}Lx1D~i*>DqT zGxMsldU(Kv#-y8^9JwKR4nhLy@-v^%~z~mOsP%J`d zHd!umSP+9b<@Lva4J<5`4#2;!U+Vc?bxk_VG$_$b2^~#{#ks<7V*ydyhD*d@&AMnu zCONXhp5fxiP_r3i!MKu4_400&v(|caNeCwo?~@Sy(^+lA&t%_%YgcPJ4MNcn98@dC zdw38Vd$n;%{k`a*?W}G0l78^GNV&#jgD#NzYB|KKtwa$Y6=k z514cvy0zYn0WEzzvi{pEec(0{YWm*+B5;5{RAW#%bh1R=;4@J;5ES74mQ+kM+V(;y7H*6VJ<#oYZcGUmN3i8K$@u^xhGKuwM_AfU zBGO_!i^x^ddOLLlkcU1tz37WyC+$6z^m>9B(%K4c%;ssDk5)AdIFQiqec5S@_^1x%xYnYDvp{Mw=xdCT9e?}~Qic*WfqmfLNDYaQ4m zGP8h2?c^C2a(puh1uKfFic=@vnhU6NfH-pH+55&;SLlp`TJX<4yU3m8$Z>HL+I0Am zs(tmo>YuK-I4V($i}FaEX~}k~dc%)_@Ny|gd%Q<#_%9@O8Ees9vY5$+~sPP~2mn zs!@G|Exo@D8;@$0@HP%};$ozRU#|P3ewd>)@BcN&)sn|bw7~2s&Z9#S*~IlA^ZzC> zK|~qx4sKMsptBfBJfha%_y=an665Byu*%ZDA6&Z+(3qQ&E!g3jv?V8U!IaLNFIJy- z^&8x&{Jz9mH#qS-dU2k7uu$`aGyBB5KAbse%KmpUf92%r2f1Cgh}7ni1?NJ2`eXI9 zE>Zg@x6pHMRxtQIb*Ew|NsOzQ=%NIJde|SP=w($8KtF=MuA+et&0gKRMi}ohZZYzg zSI$>%LxN$HuKeDuskWGmdyo5{!gxau=>>E4%Y^yRhjPQ{Uut52Q88Pf1t{MyTaPyV zzCIf7Ux^HgB#mr#K5in!t(*1Xl87OD76745YIo=2;9KmhS^7fp4V^k3@jzb--PAc? z4Qf3F91jsLv!+!U#g{BGh7i_oxcG5)r{cymI17t~a+u-vPxPseiel7rG5<^X>{|2h6OaT1_D}%H9e)hE% zw@cN{bJ^(N3+SX(++F!X{>N^hZjrlXHko?_l zpz^y}SrgH%@N((yMLb9kxR+kgYAxvj9B(akG&VHM$ZY}08n87&hA%RZFqXP;2D0?k zl$6X1&a55V0C7Vg+rv!o?;+$1mwpEH!L(WfOz1OXfRG9h_~|#5OG((l$Eh~6til_F z2oB}R0xn#yg`Ge~J|N=&2=c4!`j8WpCLA!-D?p}^QT&`{X46deNY*YBDu_nbw=9Iy zT+(lch+-9>f98nOU!tIht=H;fMtVL>w}ur9Mgg6zk$?iljnkxt)ELp8V%G&?`;tVe zpljfawy>y95fp7ukI@nf4Gh~_y)gjQLdWL{~fN9mZ9}`AP%!6Usz{~cR zhWgBafQaCx;$~f4Y7b7St!WzG<{ZB`8 zXwI_6mqW~!>UKLzJlg=97Ojb83Y!b8x6*Hdmpzwl)|P?&Otrc18}?dBpYX|;X%RWH z-5(dbx>5x&ubgBlOQ348lk!+f#0>?n5$fb{s_jfIhBs8)Gl>D}qSFy0WtR3?s}Ng8 zM&9bWwdw)kZuG7p_R3W=ucT{)A_8}2`5Ry`5Y|$RzhQUr2(#CvexA;NlW0TP(I_?i&(3Vpq*2Ic(n01i4bLii*C zt5ewZbTEr=g_DEtbwm9f^_k zBA&OOF`s|`RFqDJgk>C5kZDAhB9z4HKt+eRcz?h2b^O@r*sdJ7O8pHJmZ8u)GJ$YbynCSTEqG4l!?IMeVrRF5TAf9=*|Te^A7 z9<*+w41NJ36a_k|X{}t_h7fFQ#UB;z{rr!+<4G|rcA*dn*KFx&Ll#5(7nT%TO6C+5 zT@vho0PAOd{#Ke%Xlg~m-va=E6G&V}C!`FdO~O@!jBt~v|M#r}7;+|X?~*F<9@KhW z(&94;eqM)-TeUl3vYCXCue)!({@DUZAIg7Z!lf-G*+A~3h0DHyKpg09h`hXQjTbs1 z1E|w#Nxrn{m&672@_QahuzveSZZH+Q_Db&|{!L{A0+hgxw~av-=3hG@g29gP-}>cc z86|!hM+JX}FuXvyo^Ax#<_BVCN1q;mth*c;bl!tDYPW~Qa3>easQrSDQCjppmphJ< z*ARj8-^9bx67@To7<};8T=wD*|3op}ybR+%rBb89U!Jcg3q%|)Y6E09iy1dYVTr>F zV(~x)T#&~?Sky);YoX*}i5YI7?s@kIUd$#m0(jDiB5U!e6PajR5n{D@40ilRwny*nNt@IXiqI*PW2A8$pL!rr8la} zGWl{^r{IoDUeB11Eo6BYn}fK8v% z_(BlK0dRF9BG`AHz9>9!B7F^=SL9xx=gQOnKU|$-cV5xjMq}HyZQHif*tTukwr$&J z>@;Z5xNV#?diVKs&UpXAGsd&mTK9cjbEb;Ma@lH7n~N`{g8=Nair1J&aID{QIf~G3 zWeL7{p!*xl6s>7d1)jxs<_LmWN!L$A$VJmWNocv;*Y3 z^dF4WD@5Qq9QawgpgJ9IUG-H3o;yHAjT@-1Cm(J>2pt3&x=di+=UE{OzyAe(YJews zWv)cKTE)_Eq+qgmSwFf0*m=rB=yCar>LS?qvwtjozG1iO!*hf$=o|v`WI58I*Y6&F zmo<`U6K~(0E?s=;QR)DTA14Kx%C>o0AtV*6T(*=H`Mki3@eSLUe7u0oAf`0~lK6-T zYWY+2xh{?<@B}sF0cOc_b{-Quzc5#5LC znL4KQZP{y>s0h+p04Tec6h>mT6KSql;P$^e8Cq}Cb@qufR>`KU;kRfoSiQY`8bgf_@YI@Fak~zQy`fS3sl& z9oPaB3#ACo^##Ojn+-jMKkrJAGum&7GYc`|z%1bh@BI~1jbfj{#}V| zNrZ5UEige$(X6#wBi{o2P>&0|;$ULA?)!yD-^6MDd1>YINl@rD>22T}SL4nmNZJum zH>^R*r04Z|I$)qedc3KJ(w2GGme|OT-n=3UEpyTIGbjk;;XqNm{)M86WU&;^RZx2ldj-__OLDhZRi>R z;G*sHz}o|)^6=+b#_)HO?OmSNgFE;O;#Ot!rKAR#ck}P0gVXxH@LukIvm$(=hfcn# zhrzI{xWWDF6XP{-$n>=LA@I#6uj!JV$?y=%TLO(x?% zfujdng*qMyoeD19KigK%8d;Sc+~nP8j&pJ$7HaY^;Zi*E464X-1Zue6fwpTovu^=F z3VHtq(TQd@amzIB5kZE+{+e!Y$Si)oLwqhtx7ii%`OoJd`3(K7g(;LaeHi=m505}n z>zP6}Upn^;%cEJ|(2b`7;@+~$xf}NRztQWggb2n8Om!It8T^;kWzo0MBNN` zOY4QEmcU$T|G@n&sJG;|z={Z7#cu>LKyV<&9u8KW4JN$9y7bT-GRaVN8~*|n)uhT( z{6izHAjZ_dyFlkzHb>hqwd?16^T7K!_dKoW`g>!(hZgJ?kd$A{oKXQB>3!F&WOMv@71^75 zT-)W-rB14qT(q4LC8=>Gkz}RVV zm@V%Xy!>h?OOdy=xkNnKRJVuu308`hZ`-8Onb%$u)8-JmVu)`QD+nWM_Hc?lZFB73 zlqL6Vl2O@F0+|>5mvu?0SZQ5ibt_5Twl$flFZ9!oN+j ziA6593MpM*v)o8|R1V^bJn}r0g%qc0Zk|#d1}A#ZdHD_}YR;;0rnA zX&h5+Z1fkfzt(3=UzLa=)KbP8^)Z_VQ=Micm3Hq|l>98FpSME4wagKj0P83t$ZZr! zHRi?Y{^2SqAx|N7UxAX`)LWbQif4ym@r%C5c+6ZpU!}_C_0*2Libe{V4YCcazons^;1|3~`1h4p)9Ker;`Q>#maQ<-IPOC>Kwi|Z=a>7->H|;JG!7<#oui4Ma zfCHd(X0^@&Y?|R%gHFX0cIAOSzv<2wl@y=9fAMYi;{CH{aiDHa;e$!L>i%8Hs^|7_W1a_!Dk=WQ zW{@|&(=li}5mmc!?-8SiZh$X%f`&MhgZfJLlNL0P{}hR5zW8(oxt9sXNF~S@RWccT zm22K1Ri`-f3W2Q6YS3}}zGAp?i0dL*$O_4l5=${9Ml{~e_M5x(EZZ!R*Wv4UE)Gz3 zW*xdJiM*t>Y=r9!FR`;Yn7^YazDG4#D~m>@~j*h1Uu{RsoEo>sRqZR|d#HXe-Vt$Kp|Y zp!Ot9yUSkC55CA6@LAMgfoSW@@(1kff%PRpV|K=Mql_4CL0!lRN{G~r0qVEk=NkZ! z6c(KbkC0I->_E7D^|gprxQo@t-942Fm>WYD?_p~HQln-XUEUQuT(1Ve9>{GWo|Yw? zy_!W1os@h9QTNY_aB<~v1ig`?PXQiB<6+WLNdBMqP1!b;GxmwPFmz;W0&cXXjDF@} zP=>DrnI<`bz#;}Ga|F1X{7s(|N6t{il5!h{(;k>-!@PpG;Boz>FINv^t>ebSwus1G z&%-}dm_bGoGJod6c(f+KX?0ERbRefq*2B=oC4TF?*5xj%z;zvKUM00jY&+O!{zh4Q>J+D(~ex5ODQGM6_61o zi2TBuN1a{_GISy%L8_{V*f9YzAl*JC;6%aRqt2qpL9_;E_dvRBe=WAB{xsW+4r!RK zXyB}nlTMYV`!w?(jg)cwK_I4|=<4(y9N$eSZjS@zEu15JxJY>6Xh)vY@9(2;I|n?j znDw>YU_Why@hr{hmy9XbFS^>hy7xwqKkcU?56KNuigP zW)?H=yQwu0sZ^RCl}lBKmqF^CY)!#h!P|mQBP|U20oKwdqKti|RpcpQV;zu?v_JPL!7 zildhT&suXs9(jzJr?)tJii0iSfL(E$5EVZw4x`g{H%FNwatmSj;QblytF8E=+O|S5MlMBT9z}@kZ)*B8LkMeW?9Gw$~eKERZN7LC3FTvAJa@25dehvRFs zF}0%!IJNjiJ_@H0*jlSJy;0-hS}n0%Letq$7^NBix)dDTR@GV;Om*6$k_FbkjZwKvsh}C4GS5xYzg#b8FPPy^LOt{@h2Ns z$k3ak*zf;TVh7%6C1E(|?(;Zmyo4(RYNSB`!Q5@|Zgw#|^R-I_WEXFb01~`7$;0?1 z8HbM$1a0p>|9i!cI+D-CB>vYEUy7{Msc0~ehq91hZfzY*GP0i>dSpjWa|~>n9@M$q z66$l7d6zcXQ)CPa) zF8W57nEg$$aLWhF1l7rkj=mY?YOzLkSyB+RG!@xW&<>8G9k;VzVzULY%$ZR2RjGJ8 z?9-Ey`aNzU{5c(c5(E(0o`FFq=bkVR$1G`WBf%Gw60VOY`5*P>wN#2$*d8vi~@!88&x7!lq`C(gwV%IXC^6L>5nf) zL58tA<^M^es^i#Y8oXCUk4C)pXT^(6FPMLwORo=J);?PMhavhFIl=gbOE);f0t*{b zFttl?$;Qzsa*stpkGIDr?dw9d`R% z>&KZd51P&L4A6-u@L$&)n7qJ#1B(XuM|?xkRM50kC|fo1Eaiz?=za6-i)P&W zTlfC{dHV8kO^7fM*x#DzUNnSHl1t4z@{4ruG@~)*vhZQP-+!J(34hbYJ&KIO7xCj1 zkM6mhe8hl4u4MmHk%c7>F*piGnFc@`aXormpI+>neCBTLW0~k@IkV5FJj;IVm23eltoqOnl5`o5UJmx&@eJry0J(@grYz(=nepuA363vTmTGs== zuCziCbt!eMt`M_kI7^i{!2SEEr%k&w@JJbmFGC~1ECVr5wU;M??}g&>VhHb&DknwH zC44=hzB)yckG8aAgl*NATSeZQG~cM;e(x%uZtxubrOs}hAODtbel-J|{oN{TSDbp%n zq7JWXKWCRiHJ;_G+t=}o?%d-%0JJKtPpmR&ZUQyxO-6d?2Ha|OWk%)l`hM3x$oCkR zc$6t=Zh~~-WvBE;v}y!L@AuCSSSU^ui-V%%nwH}jJ_XGIo8$s{dt!>|na+hhu2(2F zE##5AqL07-GAAW|>RQY?fI|JXG0@^;yBk(uFKE52P2=2A7agt4+rSJ25$dChb)J0Q zsY9|SYR}n0QIE1@Sxt0vk@OBrVwf*Zh)79+{<<2X3b<77p#8XsRL*AM{Y2755BWup zI*&J&gmve#Kf%@RKJYjjdEyhLx^#WW9H@F58DhdIavi+nYPa&jFwZh%iXRdsxRQ~< z$94#S>s8OAA4YLZB15+`WYgrn4PW47n)s;wcYm@<`_5s;I0!%r@4st1X4lEQZCh#g zxr;H4|G1xZ#?mQnJxaH0V(cPaJhOi}6p%Y-#(RDzK zwa)=S)US--?*Ro$w#Z#1lCbZ(=Hm}SC*bP7xEX;28^GfYJA)>_c75`77#7hq@Os_Q zdAYFsktTV4q3IHVj99H7+Jk|ct`9oG{!PL@6DyDic|h3`&)lQ2#$A}pKYVySrWAix zVC&+2aP?JPjNaO}&nAiFA}fyZDVcFY#@bU31kM5Q#MN4~O!)d)8OKfj_~kd$qZn7W z+OojcVHXJ_yQ-9?siF=|mWL3sie)Vm9fh>+5q)w~^s3-d!8#Dh!G))D3^a^qZ(ew4 zmomS#YV6%HhF4lxmGopZ@zFXz*p~lvJq9w)Vb{Ub&6V~mIOWyt$KtPq#2l0ZNDKsX zqKp{M(e+`KDMY2m{dQh?ntie4Ee)wp-#lt0`fH$F`IlBM|BBKz%uSxQK<>|H46oHT z2)YJmF0~=z248Ue%DwpKL81*fA<`_ZRvp#uKt&yIlp&y4_AG5TEQ6_vCp{CiSV($v zu}+(zsWJUqhvAuYkn>8tm#nXc-Jc)>_2Css=0OS4q{`as@I%FImxLHKoThC`NPSAF zl}YkL_Cfz0gXMb-?QTsCz$`^TPqsh6ASG9j+FWxpAVz_8^~%-p0}5u|__Y}5_6s^y zI#cB)eQhzz;gEY%uX8DGvwFl?EhLd%l{6&KyXDkI3Yo-p5nxOKyigO=KGq4>rm_UU zUZf4Hujqk)dvGWvKH+29m^z4E3DL&FuI)+9&uTjj(kMwR+7OmtXCN&mEp4I(q>(?% zCok2U6ZF&(v^f4C@($7XKa@p`sZLr;9N2?GR8C4{8SSsW?|IVC11=AOE)%n=0$*@Y zj@=N;w*AXgWtbMb}&qK^a zp_V`Y_!({M&nn}F!x^+Df#1)@c1&4<%_r;kuCQVCwh6Nw_e{=dU%J2f z>@h#Bo`54WOfqmOh)oyvwjy(gmGKot-{>eM4)3goZ4XPGy_{i*cAe1nxA6C8%RXA_ z%kDe=A}6*_R_J8t++mO?&v%hpjPHMJ@ZblI`SJff<~t7t8F*He!vPuHvhWncqH=f8 zj!gvlP5RaEezzPytvoBB)Yco;cTgSmG{O8t^mj_|89Pws4L}wefQ$r{1IFYGnQ|F{ z?%4Zg7uC6&~oT51|_5&n9bCGveXFtw|bWj zC_hqs&-nckfKSfqX$2HIX{cpkNp$jB*H)<^Q?!w^QE|~M_TUn{5Cjuc@6idgFb&`9 z0eQV`cn#XL$T!-9PtU!|PlZf%CE5UMh6MO-ImoD+orWJ-v6}6Zjjdsf>2D2y{Or?HCi+a_vPO(x4OL9HAfnx}c zT@0l!D4$}o8dKM|2s^t5&6+{k<)FPQx}VrhL&t;z+ z>F|J48tvHD#WG+U^=FkHZi~pX{Kaglt|R58btv`p(37Py2WM5M;kj72kQP$o2urGa zqJ}Rw87S4y?j_)>b8J(9FFk>IVisPla3udxd)+FZ#A=t$wMFG&O|??^jWs)m)k7q5 zE4sy0C-D7v->vZhY&IB_2L+`Z83-Mf4gOmfYvYvIIWY@qtaQAx)kj{Eg{;|tAwjnv z{iuS%X`AD}c2?w{KrH;Y-tSu~cHv|y@0#iC2<|-geTzZyATqR08m5&N$CzF{+0=*%TzO)xH}~;!`*79viKs ztl23@X2PCpH-JACh5e&zIJ-w{$p z93vb-pz^@G2OVMSK<4!4$HMM`2T==We(f3thSO|MB+<7R8^eas z>^CQsrrzNwTHL$!=haPvzR2G>GweZ0fT`$$rABa=O17hZuw{@02k_6AnEh|vOda4I zmWl^n-OXKHm3Hh-~IoFSzPsG zhB&du!fyErkr>S#1bywx|A}oE{=#?P^N3(6&<3GWZj?O*h6*i`<)*gF88I5(9q(zc zX>@)!ngSFrnfCgBIyN^f*H5h zlL&7}28RPH14fzar?*p$eOMjo8CrC&@-pS1JS}`Ki@;GyW@R@mpk&aWS|geNH)a{F z*@QTPD(K6PQZZ@p#o7=NTuv;IHFEk$whbI+&?n#Tb1HSYj@PaOiYUwCbe^tQo0F-Iz*AFfd z!|dT?iF}O7K+2}*&TtHcF5Gpx;paz8{)>505~0o3m0oRMJDPK0@q)PKiZEJyP zMX*ooq0q~7GNhu^hb2XeOai@BEcg*Alb6yteX60b{MEy!;-ovJL;GlkG<=*wofIGc zRu`gP1f~GL1UvTO#<@HZ488+j!uY+`OkCt^7&LMZY%L$d%4*l)>Xe~JklpXBAYv(S zCv#@tveuXWQ@!YN+bX_?Z?s(Q`i7eKUP}3mNk0geI|LYS7zuP;U*1|Q@SXvPS)-l4 z3wq@zRFEkv%xrgnHY0}^4RbbJTN9qME(!0w;3nRP$Yxer_~#!ja5VUsLoTF9XUeIt zz;nmupYGBWk3HTyMqU}1#_Wf2g@CpLW&$bIwP{3r)rqX3_ZGiDjAzyuOOQO)oePW~ zQ&m`oIIXc#c!iqPd0EeE3m9H}XJ?oo!<`g(Kch`rbI#v4g9=z(jx6z=z8#Rm&WF?}aQKZH3nDj{3F|f@7BA%FN$rd8F>`cO3d8T~ zWo1@gd|e*ISPGZ!jz-2I@~&H(23_X(L7UOkRG>SGbYDgu>xH+ZTTMX&6e4$yviqFi zV}^#{u>F4mJWhvb2(L=I1Yd&d4d9U|-?Nvqp*QgEi=_#~*p{FIzg%@9PmBIjC^f-l z0NNkQRWf5Q!oObu7~kTh4|bzhSpwbf6UZdtLFboEMec@|$TJjTmV<`B{-dI_34c}J zjJ|g4lu;>IpYx?>0cySH?S$s*ZPFZQISxI;bP`g$KE-6KgzQ}VY|9kZZa->K*W-qy z58n_iODBQ1afK9H5K^jF7G2X&V1Q7XvH(Ehz=2JTa88Rx9|iPm9@BWQTuKYq-YTdC z(W5^6^d5Qj{G#ABpGVjOvN5;iX>=&sf0;G=juTyH!e0yiXpk#_liSMTDJ2`&HSDAV zSFp^$$GXD%Uly-^q!El;u5+%J$s_bex_xFV685E~nRY#j5hq?-C4*tLkif=S@i`td zk4Z%E>)lt=WQwo~ihi#MA`j2|aSQ`uW|$(jR!JhoAKTWLo9I$f9?cD0;U!*u#iF+!+VD#X(C!m_grV|-Ytl6+*koBlzl+O>$002UPh?r`1Y!7&~*42 zC4Ak{MGpY*9Hk^8irSp+F>~2V_?K0 z6zF(CT=WNU8=B0wNVq@@B}52>vX!+hflQMigh5S)cD^C+0JTmq^Xo7cndrqa$-pt3 zjXeC_x7i~2D|<&p;IO<1!@6j+g}tUYa;#G9lFY9Z{!0R{aOPXCoThoeOcZHzOL^^{ zL?c5C6PKKJHD~b*LrE;t-QpUeb0I1C&1%&0a!nA~ODMKL{JQ6^@zXZ+;$u6B8X^bR zKm01l5mIhggo$Qa)dpbr95qL0*Rj3VYdZZN!tk2x1G&P&NOe?S}{^uQuE03tfA}eG{7a&LL#QJ;*Iw9`Fyp` zGM=zwo|aozAQ4FSuW8x2Y{&7A#L=VYa@Kh>axC}+G(3Vwy)<{*YN%zES1)T4B&+w& z;KV!N?<}G&aCfU}n`3Bu-@|QzQ%@6NNl-%;eGE<$a}0Nw1VCL=!IGpElu#1#=fyKx z*(m~=OUS#&BPX!vzjN;JbG~p02mS(}n{1X5VC?6~hrGZ#_4;}=KOU22nf)_S>5Q73 zd_Z^v5jkH20e(rTu!h)GCZG)9OB~J`xsQ|PlO>qZiT|P}g7CaQoXlu)mk<27ollo%s$mJux9EXT3O<_tRK|xuZ}gs|ei}}1 ztXYJywlVTUURg8wqCyH^vafT|cnafC4i>38k`T??6O!8kvz6 z`~X>fJc_&WiE7}6t0d(8JN)klZEpf)!h?$IuB9|OuvisDDBagvu|TH`e?68pqa9j3 zG452w&=H{P_hjj4YLS}w(eT6DEI`T%hA3KZDd=a!K;zIygJHYR7=CPhMM?jTZAHbX zyQG{*$3;_168LW=N ze%G_O?i9)gx$CIEO>37H^H)6H9wsyrA3uWCbNe@PZgKFSCa}FoY{q&QfydVsLk|?; zC%~M2EyZ5H0TM%P$O#!!MS+O-6RILkz=dm-s zHs_U7x)C7J?fX+WA|k|R0<$7N`688bK{$v|WO~z3AJ6+FB_ouNKam$v8oCk=U#xT6 zG?PLOp3x07axU}--(8B~!@=!1MPwKh8$=P-1kX60$YkX88d~zYOpA?oWb=Oa#O~eP zrij5Bi1EIjbp#A35|gKB^vgLLMHxXB0KijWXuOn1!NR+uhEn| z$J+WBt68u2Nya20J)d-s4q;Y6!Thb`G^MG|pdXe3>sUpi$*5*-t4aSj_ zv9&eZ{MNQ2qqZJ8h-L3KASH|U(+tE~0=Hn-u}%dlRBHNm8%j)N)clQp#Hvz?jYc>Yi{BBovGL@SI(~4wQ_tyIdPZb^pl{8{T(6PQ zX7r%D{4fW~C|_jj0|R>=4OB%45P2tMUY_~QwdZd8F6}F(L*{CH3k&Gj;piAGbesli zvq#y6{zlaN%v$Xlfs#ZKQgcQU^1fvD6Bl379R}g57dwouyhdI0nV}>Wg(l4h&!|T- z9$Oa!EO|AcULZwF3g3gxqv_3|(d#5c+AccD$T}l|G@=N)0Q*8x(puy-I zOUlB%>9VS0VYAf2x*iXzWsM5ZogNWC5iml{#Ct0uV$qBn6?r?Xctc$k$nZsyFRUw# z*EQ?J)?U-FYbIvtp9lLJHsf2_25?l6Pob(2+c`wo7mYv!iQ{54(d7H=HaM|vjNmP2 zYC{~pH^_?ajB$OCI!t()r9yT-&H_?OtEuWJ;zs@LYoKtj9|bEpVyTM(#}x`dAGxpM zWrl&gfp0&XiVg@Aw2)wtR*n|f&?3G?f%EQYxy#>4hJx8vmxdYa#GfspZbu=w3Boa;_iao7YEAWX1lc#pnr;HfaL0nh zfkKBC?3g9#iMgT3;EvYaO(R4!HU)MRYSnk@CE;2JLw~(Y5x;Fs`Bt&r=(6RGEN=z> z^qtece9e_CA@*me;GU)^9(Av?lB`i#+Y)>S9ylL{7L&NtZLmNql7V*t*YW9hDzyh+ zP=Vj?sCm;QG873Gd&ciP#(8e4q?&A2@+Bz<%*MstWC+7fb#n|{Yn%op3|xMjeYKK; zj5NmHz}f7HUIE`7!JuKLZ%rBSpH)Na|EwAq`eDSGnff0$*jA4Uf%O&sck0tCpVB8y zt(u2pz~N+Wq7o~ULXFbwN^w1?Q#JJWxzuxC5*7Rwv{mI4oVXf!DP7-@wrGS?scx8~ zKY&iCGrC9ufvof3y>j!eYY4OMNUtW&ob5V+5f}@+mOPC?G(_J>;E4ISisT=+hkJ9v zE&^P6bu`lys-DxczfLzb<9l++<06qVlHWSUEmF?_rGk3&&d)ysUZjWW9OQ=WD#wdfJrRbA&LiF9vGh_ZtUOwexe-A6tS;R0l(K91tG}m*mdM& zd4CZ9ESEmT{Y={jgso!XY08cN0^cyfkHQxHp%#&o;svZ3!#A=a^Z<4OIe8b11Nw~Q ziva{|&>-5j-rAplpYT6lp}t;hEPbWgE&WTmvE z#KoYsL3ZHi*EZW6m~3}gY4NL8BF$kVt5Gm=ij~)QZQ#Vntr=)7yuf@xLsMWOk{dOg za!0iOK zu=|gL>5EL@jUv*LX&tv_AZSX8h%}wi&7qe|kGm6~XPeV_!wQ`cA*;y|_}lH#+6M42 zT~HKY8>1}v>=6%=uJ^kw6gzZiehl7i3(@Cl4(Lv( zjHM?~=Vt&eb{;P9Qv)+pg8x9vycOC`9x3g-oZHW0k=V1Lqos6rz~CSD&8!H3GVwL3 zLfNPlc)v}2`bw!OJ;81ycr|FVGt>{db{tHuJFMVd*=5lKJZdHX=7G;&m+z@Fi-B5Q zolsG2^R8XK&tG768i9u>RFRs8z@7Eau%#D*sP21lgz2jPuDLkp5vV*W8=Njlg@>X% z(JwYd|Ag3xa8^$Q7c{r;-z=8_@8{2?W>I1oXJCdg^FK3;wv$zR(v(rPxtY^R0Z{pZ z1MVZL3M^ozh~%;FLG9|3Eb+`vS+Ha9CR0Jb{>N-ZmX^KOVaUL4 z$bV!@b)EkGq<0m}kN$ZXcMdO$&pF7v<=9QfDp_z#Oy79Ui)#;ypx1G}=oXR>=m0O{ zsWE~1KGneIzuB#Z(5fy-ZG-hUuVEnYZMcAW8;0E2QQS5~)WP4qV-l6hTQsYDUrBJE zW3|x`BT=!!dynP{&-24D&?mq_*-7tcXZ5k82^0K3Nvt#>Gs>p;z*Bln?0Vy1M|XO% zY+2a~G?_=YIw3aKN4LUzf7KfOywjbV-kwz-%_=wLDmOpw*QO~@fRVL>SOqs#xUwJ4 zhS+kLaG@%`m7$M`r>KyIv-?!miR0Ns0s$ClT<`@Uq;i&BPxQEC;DLDsWBd$qpi0RZfOF0*i;yvTD6PdQ%*WkoS`rn; z2W2s45-6s+TY#P5jhkYaR?at?BB(4o(`o3?`kB?Mszv}hXp!pccGu7P3{p+Dh|QZ)K<|~KOQfG zOQW2c^Gx9ZB<{Qxd$Vz(K6aR744t2+~%TGL{8%bh|&1^Q`IY!%W|4c%CZf@0=m5VHOh^_UBD+p!BX|={Lea2AqL(7lJ+1ivO;}bxXy} zUk4hfP!O{GwKknieWwP@iDvS+XitoJoSCVi&{z&ZrrZ1U2WSJV~07J7GQ^uasC<$=^E^KP7;+S z(nZn)AY7LPz|evqby$9b&yn|6cI+4nJ7YM2+WMB2Ek44coh}TIL0=v86JE1O3w7~l z0=~ZI_MMd}Okko&_ZK)44TREKY6Y3|3ztFTt*0xU4beM*=%kU8FC}A>$P|#27bA1z zkNAbQCW*aH4j!lxO!=6qD>?nb5kX+KQhqlm@jdVEpzpU{;LhbVag@2oVaP(MFfr7cpk9$;@^Zvd5P>s=M%MBQw|ucoc+w z@UW!JXf%^vz#((Ds@Hchk>?^XVnW>!iZ$=+dV&SDKTP6%QU$quT?Z z9iDiJH5gzIkGlI^ILM`9uE8+aM=sPP!5eEvG7=YUpGG89jPb*O#lpq!k3rLhQ=h|y zt+$9G^9Of$VcfA|$k=gGQ}GX-`%?1Swj_BbU4d{a5_B_wH#SM7IsL8pCr5H-pQW^x zPRTSdCia-GVLi1HWYD@RhRnrfM-7nx)3evoN*9z2!PT|Ms1@IcChq+0;8YjI=378+ zaGiI}H`Ei20heWDSpSP#bXgk)UC5m0Wi6Xl;@xwjkStH~;xcQvduhmD0GgQnqxQ6R zFR?pz?`F>TYJFd}c4NzEhBL3?w_J8-yle}EXQcO=^frusCe}t_ zi-lWu-1)0c@RKt3{_r(8V@{XfJN0Ru$Op>%E2<^LBK8pSScMm8A=dy%E33pZc~harSmr?9>A5`de3Wy=xzZPe@GOP;uRV{^l`e^aA~^z3A@Q8Kep z2d@BT-W9;ZE=|K_9H;5JY}ZTt7<^v$aS?MFEhou9hZb&Qho?(!tL9QQF7%m2Xx+Lb zy^7U?(E}S8?aA+#zX?$~W8&GGb~XIGbG2n(^sn1@hOx{pc}@eZACWh7jS6F*A_xjN zOFs|{iEO3Uw|&)%$Bcb{nR?{JI$95=7#(z%fU`D)Q)2K`?gf)+n><2PTM*Dws+yVo;q$zR6*flux7RYp^L$JqoZ-(9!S z-yIG`T(8omn-+M`x%d6M{3j7Q#wD>P^wbcd<=9h^YW|64;R0Soxwb(@m~g=Pp2$z9 z`D>EllAM?pnHt>BnNFGw!a26_kB@T8_f>h}aVgqlul*kFvl!Udcy?P7 zHL}!I9 zIcpYSAqDFT^x?TGN;G*J~(8^b9SGXn&qnL$DW_qnAzfKQpRiHWR zGfP{c?MqJZZN`&83Y232F%X=d4cn!po+u=Yp}7Mh%^YCm>5kGHs;01p;(Yd^jD{Z3_z`|tFAtjw_Z z5pFA75|lh2D3g<;TTkugygeQ=HYB&T$Gk8f;NNKiDlE%O_A0GKONetg&RIwSb*w`v z(~Vv^rN$20wO%W&*~l=%&I~l3jX47gq==75(7fcvo^kAk0#CmDX=yY<`Asv1n}Zmm15Nkc?6w z+9+DzTx`u&Tro7P*RBjVceU!wq#)QEc^PogLVdTReEPnoVv2rc=q&GfF++LoHeiKf zgd;$Ni)$^=%9E|ZcDO^TM=Yo}TegZIC3;rj}*TQUdqhfUQ^2S=)SV5l_7&yAJpQw-Y<9WKS} zlgo`xJq$ik7^OP>L)W03LumIN(+=xe7%0^l44WPrRhT!HQX_x*rkD~$E0<9>mxK& z2c)f+1zPRE>+}?Iq}xa_Yw_NyKM~?ECVdQvJ}TfSCIi7O|A)T(5Ol1^!29Xr18D@h z;sc4>uyAA##~{0tl*}>re)l)>BIt+7`x<#no)^H_2SStJ7{So!3X6bZISYxcQNQ%5 z^g4+T{~C#3>$n08JCtSn@c?xBzwQ|NjGY*#<`7VQDkuPK=h~HNnNunAB<5R*1xG;v zhu=vHtDlOM04gAFuTh@3=scnyST9NtLzx=G5;DQn$*G6>*ydakFU9J09K;Y^aaY6N zf+K@8Q-BxxW4!_Qtqj+=F_7aPZbP*g*0G|@jC~8j*~hLp$llSR$e7jUF93#K!+&o9 z@d5e^LAc)|9Qpy$#^X6$U3aUkG;&wxR?QEWsnQrh1F!IRNWAUO11O}lUxub!NCCMCy_z0cFy6T>8D_FvAEd7h9_M6R48xMhBMl&j)NYl# zv$TmgMbRj^)Z6&hc2dSVpc)fdsTv1&ghf{5HBOKw{8589a}%&9TpcDA z>_BhQ3uZs(;ilj!5?=1yI5b#@BKr$<@!QZ>fHpsI-F6Obmo*tpAf;w1M?a-ZWv7dh zAZuyxm%WR)HA*0!glUa*zF1~3? zI~j!g;F=T=6|}Wb`+cekKsf44Lr&ObFZghCA6{iWPTmIvAF%pVV0xBAgKF9 z-wY5nw*9l^E1d0HObJ4)v-v!z-KACVL`5Guno$!LgXHCT-I8&}Gn8eZC7d@^*oMG> zHvdG<^Zsi}c)u=*vFOWR(CZL_5H#`l%d+QTr4S{T4J6ho=Ome(CQZTdy8H}YsC~24 z{Bb9TLBA3p!3W%3Yplpt&Zhza@PACm3Z-UCJDZdU62jDkESrtzb_()|XmE|)sZm!J zp*vW1@f+J(UF{fkB7%zy3eOYFnN1qNBFeDL`~BoHvKWLTHxY^F7;n{LCeK0ZK-X+6 zZ&X5ALiCbOfu>-l{JcyYPv?6tiFLUd55lgaK@O7RrYMWN9teb*n$HNlVj{ACtUa^C>k>F`_Ogq+Vmsjvm(cp_nl0al4eYC03 zD_!}9LRlHc*c$%lpO2NpRkq0ecUw*3wcI)z^(^x)fYGDyZs1Qta9+_IeJdP#5i!yU z^5FZaVVUcmhhUKZ6rso5`PrTfsKt`TOPIg5v%SxK-dskf7vewpz{VuER92x|SKxb~ zV)TA=#|NBfH5zZcVOoHv7G0m zLK(Ql6RS=V_o1avOGQxsQdB>Yf1MiFlAwFN3-ylB*9?y@8FtCt8C4v~+Qo}ou^UpL zhT*?%J_ z@7i<^`ur}+^ZY{%1h0ayQn14rmW~rx^U|}I*gUYq)f{C49#04Dhoto+u-s5*w#?eR z(Q7i^mK~utjiV_T9gJzLa6}T;1v@t4e=3kuy=b;&tL1AXjIwuWAl-z?nvN!;vhYeA zy^7enCXw@}KPil#Z^#MmsVJL8WJ6a$S7$g?n&4D%lwcqtOa_))=D{3ZPvu`4b<6r8 zM+e_FwgDnjvo>&pwS+*uM`L?T+x5TC>rhV~W6at5Ei>OR$u-yhQ@UW`>P;WvqV{Tz zPt)<--Egnry=PU|+5KURbPF>j{}r%501dpPq(q{P3wt19=&@zDf**`9euKZS;$t69 z?q{;@P-LL*I%C+{K*$!Z5;v~4i6j$q;rI1+6#}o?PJ3vMH7rsAkV?O~NaA)qJh9gl z5|ky}FbzTDkxG;|R6KIwbh-Q!QO^IC!Ik;h&Iy*e8tct{1(b9Dsp8mRs_Jl_0PJxq zP{8ba)O$O*A5v=knv>T;DU3)yQfZKW;&*V>@nuAxB(RbOrP}T=yYS1sS&}OnxnnCj z4g!$b2VP~J?btQ>0yf5$Q&z$M(SHRc4v0QDqrdp586CI89 ztPA^v`y+5rB_@kmZTs&OjGSsY0S=$lq^a3R({Z~DuC(d%l6C~=l&ilD9@wTL^(1ru zIrvuE5|jMNjw^ zmgtBUma`5d=ww5*>>zoEoB?T+(d(w)?EMQ9=*=gYw2B5IXr<7PQ6$Ac_t@rlB0@Me z6q6|Oyo#t<<8>dqdAp!;fx)SBQ@1%YqiP*y_{xVeRfvahDp0NdzpwuvD4r99kr$j% zz~YdH!F3mt(5n^?tUvo{$2|CI*U3Or`XiYxL z`ToJ&hL8k1VDzP~$r7hDtb9*qbS#+(&Ej+NglEBrOz_Zp1x=PGMY<~rXP zfcj$(01F96Y`9zJW53SCU&ITVDHf5? z(1jOl2M*}wr=LJpt48ED<6m1VoeCZ{Ur zjb^t<+LI$%4CD7F`xF}$YjnnbXl_wqiYCgICN*hPTB;P~yFk#4{AG0fYpRYIk{!uA zk%X#v%OF&0=PbwQk5S#E|1PRBq>wIReL45~ij1SH6m?`-E1_bRZaDK=(v>m2n(i+2m$jfZx=F6fPSImI)cIxU_##auYqTsqlYI1wB>eR8unn68C^?875JWyVvT z2p>|-H;S}-)H7^?$>yXLGod@&_e|OLs$t2ECjHn)m(=Wl#qu$veH8d4G zQ&Hu%PeNVES4AYvmTZW^VqIH`!G}xY+CK zEtw!z3%CM(pZU?H5X*z9VU(d~_a>l7VmED6EKIcDznbOn3#Qkc1W(5*tUrh4X}xpE z=$%63;+)g)9Gz>5$MzuW{R(g)4uNE0c6{3s`h8~8nh%d@ap%Ng zfKDc17qi=9z@?(uK^&QphWe*c!JN4D3<*sz+fIrx^wgb zK?DZ$4-z?hM?OJ*?u(fYy%5HW!DHIUlrwrjAF2J;k&%VAuAXFs3z+W@i*kiTGFHC| z&J0`I@$Q*C18Tr(oB*~%m=u43FP_WRT>)Q3qFbh!5Zn|28^*6#`V?$LN|xHX>cSz-nPCQ%<2ftKP)-8kXILR=*Y}$T7?oC(IkGAUDriy^5%Ak@ z+x~OUsXFMweB4MK(Hnf{_azzqEhhFCfatTFnBk2DX8-=AmHe z%;}yCk_{|8bwT{iXSdC^3?paz$x|!&(3e1gb$`9(yQzzagE9>28bJPtl?ppMt)Pva zn1eM7kq4nv%cA!!i3T8euYs}@&euSY>^s~CSJ7MUa*){9!RDY%gUo_KGkGTRZyI;` z-B!s&0H+R}0)l-2fmvCF=2hDHt!mLy2kAHvqr(rO@aK3vgp%Mi6@sIF1F6BYbIqCY z_sMKAv+5ZH^yl<|cT%=!#;n^t6|Q`m<34NEgN#5h=LsS8p^-x-{!Yl3JbgQx!Re4;&!SNH?A{x zsH{-hXgI75H80Fh%DG{)xgR?F(u722Kcmx&S)aD_EBD!W(w;qb^OU= zeg(rgWIE?w{RoQxWC41 z#Z*AT!(n9wI>i8A?m->!afr1Cl#bs?nNipa4HkgMhK4PaOAHsy7w=(Oc`i0UflEhQ z9d2$sSuaUQ@tHPbEbzy2o6C&o3O`SBIW5IUJn4KnWLa9hnS0bZ_%5ogB=`h5s)Q8*RJ_SLscegU7dWoO1z3yR&;13jVMXPch2W7~RMv;+` z)Tq1&M~>ou;({jlcjv#&^-)a|-u{r1jU#Wx=}XW8Z6JJ)vMySUklx8l*Ga{`YAf~m z#})e?*0LN+2;r~BsSCI0ofAu-px}}c(4kVQMF;KAOYTQi(}`FI z>3b=()l~ih_wwG!OUv&(M2hO@si=ia%JVj`YFXQ(ED+@=q6Qd2fa*YP0K&-DQ|lk? zU;tCfl+=dLbs&0V5uZ*q_$@r9ePE|NlRhyUl2i(kdx&FxV9J8pmACosyix_wVJLyb z(*U*0j9~aPy9F^la{JcLLZ42XkN9mBC%&_;pe{u+!0NRhQEfkoc!1pJ<8=v+l@kZ5 zr>I)CSJP5P^mqsmW^=2S&!zBY_C!&SAHyfWP$1-^yCvGJ%&{+)-9d|oSf%Q1d`x() z3JVC_#z&~ih}XR(Dn|A}`ZN+r8Gw5sLyRU!Qf6Etpn140Y9wz?uTlI!$EyZ-R2qKc z(auP-5cS?A{Q?rdX&?Ats+tZvsrdHS@?^#fEFmx(F%B z;cS>n^0)+y98VQl^Nd*2wOtv$#u_FGahfwWbm@sv&Ttv{HwwO>#LdOa3?0Grke0#b z9!iKo4oO2IC|=m`Jl!nIfueVM+J)zS!W78M=CwV#B3@KYS`41cuO*f-W_x)4M4m?; zv#+JmdZkY^5TihcV#LRGe5&+2lE|cE07NJzxmS)2C!+2Cdosj9`aS|4o7NN1@I5@P zGx}_?-OdvFbK!(TQTl%3M`|!UgVqDpBqJ%hA=r zPD;w1VIHi1T&a?IE4Qt&(rY+K+G)#{u7GBIl>x^^DuVF0fOlRw<@|%9II!--oz{RT zHyd0HBm!aZysRBNyJ8aQ0`x`8Gem*E95(;Yg0R~z-HI)iq1$kaOZG66GR}IG65Hm` zv+HGaq*ro=97lhvchmC;2OWktb)=03c!3@2?x?wu8ZW3segduP2Y(W^A6F%@UmCq= zF!YQ8{_kDesMK>`cLJ9wi5MSJWYhbdC0B`$s}+lrUy{No*mlm{FEYVSfcq9ve)nS9 zzDY3IO$MDo6`6ehpL6vRI&zntrbWk2NGBrDyvzGckROQ*FtTLGf(DhQ=k87DY!ISo z(iK8)yz;J5RO%?iB1lQNu4uKeUr6?_(b;b&k_-!Pb zJ06RcAgbWNUvsudEIy4mKWSaGtnE4J5xWH6@KNH>q)91f zO=cYl1i_H8@qbz$7vJ8IP>=$6V+mBg?>46A7}w3qQq zqK=32Bll7U0K~661}`UEVj?r*@MXH_WgrXWxv0VUaqnR*9$}{J#sRJY#D@c;&>o~} zEuBGD89J1!%YfxGHcnc&qR>DTmU{VHq_&NM87GRAlkROo!cN`LB75f|NeG37DO3h| zSX(xZ6B<0+X!1Sxb(%8B-dcT4x@e*IiJ*_s?9WV=PP zcxgkbmN;a~BTgtPMdkX5lbBewm=H074w0u&GZeluloz1*Q3HJL9-d*JOee_tK8u%t zBg|K$>hGDsAj8d2ID`)i^8j|^Sxrr)7(i!f(0L2)(D6n61R#dM7hyS~v?YN+lU8X}Fo_LwpBvZ;-_1y}aZI)I3 zU)6<~FXesPlu9A0#~?Pj^>diGBo=dvG+yH7JyVj-MTg`?Qxjc_c6@Yf$Vlz9N~q`+ zAcKk272&K*KfEvHr%V0a4ZmEN%Cg2&VvYQBi7R(LEew$dS-?MO}J(S4O7(& z&n01aew!Rk6<|`g=VBiIbsx!}mQ;cA+sRae8I~!u*q``4wY*LLn+u*`#v>pOB;H_4 zH&f-h?*9d#)%={h4nN}nUaAso3(cQH#MZiZ5r>GV@8v%e@g#ljVwe8D-@bx_*vC&V zJDe0BP_}k@A#`=Wzf3IvACJzh5l<4)!`M3Wj~6|k7vF~kxKK(}pl!2QV0=FHtudj7 z7uq<;;~jf@d{~CXB--B19173EQlsV#^#hbhqqr`JF2?^Fup2qP+K-W^CXFZGO5{466^6A73W+%IAV zCANlX<~CCJ{e|>LI4x=2x;_;xBEsK`>Vlgi9sC|c2G^ie^S6j4`r1)Zt95TyLkg3o zAO#A#lCa$_lYVN`n#_?IP_Q`T0PU6GpuPy;dRhJj> z9RX@dM(TC=J-|xArkf#r_5c<>E&_VZ9wJXyQba&+QDw{P&Vw%^zeHgc#U*pUze-~r zpk33mHXJ3L6zgan2YMtz-k6A|b+H}(s!dz@9ZPb|0n1814CskN(Ad!}tx698e0NFx zae;4!^CCW7_e2828EEA(oSxf95KOmoj8SF`?%5~{?GNAw{i5~OH`-4IbWwM}qoko1 z61TGBQs?|ykn12R0UpZZwu&)iVX+AbiVgtesVmdn|^*vM@_m&6sQ<8 zC*Q1WX@979ZbSpM_W!+i&gpJZw-mx8b56hi6U`9b5Fk=H+?_OAjPb|AA$7kgjJpru70;;Pp3b=xV*fO|KUFw+l;>vk00HU%@*F zbeb?FR&*$Y+hEMa7h%*;oCzt9t!FWq(6G4CE9OE}xeImg_dVma8GAU1G&k3^Dic?I ze8*v#x_)4iNWWu9T_fovJe$CtRx-4YWzD3mVpa8ER7_Fg&430nnr00Z{<+ zg9%AvTA#|sDJM0Y`wm>FFBB7)hgM8EqHJn6q0 zfu1B+rum0%&o?OL{dm34uYN)ce-fW{8USEsQ~ye{2q{=W82n$A#=Zm|Yru%XAjZg)DZdiB<&-a-c&+P(irOt&tizzoPgr_# zM_LWO*JFqM0++J@ih=~j5xW5-2VPc+x`8ymLG+2%Bf-bB<~5r&<5V3Cb$x#g)9eM6 zk4NZZX7fPl-x&vRa~>y#tHF4iFO!?8;+4U6wM)C6+p0V^5MC^(Qk*A67Ph&wh<<6* z@!CChI}&RdpO32IbII#Q4ajistv<8HKAV>8tw%@k&^2v;~%!@tN?=rWP7447n(ObA!R_zHwbZ|9zF2`Z# zubY99jgZEd*67xUjX6Y9dgRoA`ssx#_2IL#LAWF z0dQWcp8#=1cs|%Sp_$Xs4ZY>>T^MGqigHXDgUTe|#@F~^PWv{xPx_VtVe_=~c{6T3 zLi$wo)i6*uhr}*=z5NtRGQJ)jxK&o4sFLRhnZo z74zc0nA-9kd-t8?Z%Zp>T*=LA+SqGl4ZojuHA2lSE)A%+w18Fy>heaI>VX>LL)kCrc02A+I!I2b7ZCS@hZfQml> z$I2+s$a@VzElk;qsdy^74XKqGkJolt$&i2}0ghEZfdg?eL}au)`W1~~bC{zZCl2P8 zWwXv}oj2Efp)fXBgvKcAEPkUo)3hDLhKc5s!0A=irmBI>yPT)tan>)Zz90d*T0wk5 z4Qz#VM?`VEFH5~Q&Dk9D64B;$hp~fHJ)fdc>(boM)|x~eA9tA3b;kQ!z6`%bo4X zll>+xb~#41^m61H5Oe0#wRqy?n;*Q%f0SjLYn&oC#kqH3S>sI+7}yEW5_0(0?hjIH zjAzHGI0)pdP zn1`QHjPE2L9u`fmIH~EGSme%?;gvn`vJjvWZ3jQVyX2<=#oNXmupFlOg)l2;OV^GxLouVEpo8mUJtjc9s-SB0y1 zp*L4Sg)o1@7YTQ>cqjr+UiwZEXN>2n@A%oil9%|U=C zFeM~62ri&#Fz4|f#@UB{Lem;fxw+!RpbOaWM@L?D@dn4S91}QOIu#EtheQ;~3?JG+ z*vt9kC93%++slkE?+f18CqZ*NMln)e@h@oz+@V}Ov^57 zX@8Uh%t{G{8f#bWTemhyZ*4^XVp(u~=R;MpGEXzgUqH*-kVOs^N>vFObNrr|TM4BI zdvh_%ku6R~p&K2&eBTTzwF`>sMJyv_$ZHhbd2kp*r(kzkhzX4&FG$&7fBksBulSas z`t$FuRg0nh7}xW5LUN+=!Z2h9`>VM;l|sr*FOZ8@34hLlC1x;-J-NBL?x&Oy8dkxUpOY ze@!xyvS+(r)X=hdp-@BP-_HdMbDz!I$K}ScG7V@F$qReJrvF!*e2r;AyIiPY2ttbg zL!N3kK8JF=C65#WhAfP#Tq)GOj`Q=o+_#*E%C+|74wFo45xA2pmbU=7Pw&1U-1hFJ z=fIhnvjpqQCN+Ep<0-x;qcf8!Kp5Qv#*zjFER@(p|z>xt2p<==XHV>a zhddw)#H6ap0~Q{bpQqWISfkeO=ml%=Z2Nimj5=`)8sI2~SnpD~8+0(Bt_m(Z{S)42>CZfizl(_an7ZcATe1RQWsV>8RPsLS zCTF-k@b^C;#Yr>$`kuP=qzL~1hemgi9Sq*cifO9%(ON6Ey?~x4@NR)K2Gs4t$E2Bn1$M^z*(1;Z;@Hywe_I2uyoeo}4jnBfrGg@A9X$5nir|ND%R(ue_ zIYW87s{Z+oSO%awy_ASJZGd#?Z7R!n65xw_av8+#T>I?1(PHt1C%%+1BEm%$W1BKf zR|Qv0)&BRg;cl8w-1T-zzR&kmSplMHyk6f2`+yw~&;s!IS|*SisYz%Qn#O^(kkp^k zT}YUyJja%e2);{g{&W~2cV@HlFOs;YKBQa&lnFjak%oxZzg_5?ef$tw z(wQ%?jk)V^I#JwqrqQVOWH_3ph1tuAS5aGxp^dbz+K&sI2k>-Dov%920*53MPs?G^ zb=-Dz|G*3ASGpr(hDy59_X>9bMfCBR+-u7sDZO_?^7nfet2&FD3c*M3tFumsey4RG zPno*sU1#sP%uyC-6=wvAkO&IV^Hf2BMhxf>C9A%f;cc(ShJUOFdRBFspFM>wK1^ij zV7R@?biNbpw6nzy=5i*uKA;MSm4D2jWS&o*`V~;vO4UgDHw>vWXNThLlMva<&Y;N{;&C{ zz{>CzmivJ})F~GCugaTl1?;%)HG9{eq*aB&_d}BVX}7qZE~+u!*S!bl`%_@Sq=|P& zEjqzaF@rZlY9B?37NpI~1+paF*UxPP7dc5EcqzbRg>ZqTLnpJq^WitP`(IJM!;G^O zS<|t$!}gw;y{pZ~W+fmb0^B|{T{pO!O$-Ww*`2EcwmS_@27JKI_b{^bTUIn}rni3k zLa)1tg9(K2=50J`E3AO%!WbIYtp0$QyO(^7e(#EiufT;8d`Y8pvVQYVTr~Q4$P)7;D+Q^!E5^Q|o6C1%Ps>gNS!{N2#hisBEBFRpn

l&tZoI9k=ePt5dDjKA=)pG$;4UGje30>B`&ofNX`REm!bo7}C=^ zNNz=CeT4dB%HQ*4`XB3dfhi|O&sw&f4{*BI0iVQjf7Ky~$x7;id`v*qQRu0GYFw^x zKQf~*q=zFuoVWSxUe90~4trd>X+xuY+jNrJ(Nd1${sN1U8MqByR`ieREf_WUk;eyd z38Hv;Uw9~-ewZp{E1}k=w#jVP+j2RTJaa;J3dUk{$rQg82n&u4s^oz@Lm|nI0g)*3 zdTBDK?ZWLa@7FnWcexB@Jt(4{s^&kzJ!~C2)5GZ$YepKK$9I1!PP-9HlmNoosKsS# zp05UtTk!jVB)2BkB+hy)*~mqqb&Wh!(y^=T?kyS5rSsA(M7f2mQ@*Lgt$4vlozVAWbCWHj&Q@KYqJ z1f!@p>$0Y+Hq+=P@JGGJgd?Jtw7P7%^BW>-D6o9^3=>(xZB+BQtVPbM9W04rnfrn5 z8Eg~vfbm2ki1Ve}F--jEhKa|q`1p==y|vCI-Od_a#@6is*2&h0zZK|d0B)uHqBX9F>b}1T8{8do!wu7V!0Nlly;NA+>zI>>wW9!e&|@Wc=#K*2yDEH$=LkM zi-ZBeTl!hY<*8zp;xcRs{gq<2mxD|aq(DLUaro+%MS(<5XwW3 zNk>($5vfDvQYPh%I`*sK;ogP`7c!sr8fyIY6R+mEwoi?z*VEm|tCrn}++3y|nj=vO z)Zn_4W1g{HJn<0oCgXAQd3CA+L(${@q9Czvs4xz7`mo5W zE^Eo(u>artMVNfLvrrBv=Sz2lbh3c1S^n#IoNY=m*&6chbvzynB`|;6xQSg@5^5`G zrK-N~*sA*aJdh#uZsbSZh8g^P+B67#!0Q)erbZkpP>BDOmP!TGw>ZMdre$vG9D$b%J5cSc@oh@)) zY`vQV%M?Tafn-7l5ep#LzqLIKfe~`oT7bZM`&xvb0gM#$1^EXs=CHaRS0AW^)=4u` zjbKa9^U50{K+*~AdcGO1)cAg!ZM;-ux$TB)@~8NM5GqabJ!yBAlE--729t?WZoSA( zZ1NAnv(jKxsA&t!Q3W0wWLm>UFG84V6Qx5F-q$cV>-Y&;iQCLsCZ&|!11b;gU3#Ul zT=S)Z$P^O#zjmU|1HhkWCt-kM&@)nFkUrR4lSD;RtA&+zI0b}t-(sv!V|6pdh0{ni z3=%L=BrzGHIp<0Xkm@Y*m#Y{aQpJXl4+*JcjbzSmkyTld!66E?wBm>|1L0ylof~w2149F<+LPZ+l6t(Dx2N1(Ex1Jp!}u+p``cdP8gRpZ3tiLh`124dd-NoPh5h1L>Ua&$iuZJGy2O}u@(*Uik1p9k z>To^^Y20}5Gd2%sslxP$ob-L_m_?;GBRQC!0SC)mrA?$zK`}c! z0pUnF`z&dX*z3^*NT-r4?_e2u-xC(tcEm+iFF>R#yy)=@4+hO~mWZpYI7V~bI z6~GPG^RiV@+ag0G2M!&*_^kuPiYlJl$w;aN0<4m%;M?opNx*#!VIurr3D?sqW&r-iO zJX~}s0AaK6;qND^?=rT!LAaF0X1{CnYMX@MjG@RWZc04$7w?;Rf5dq44Cu|(U#$%G z_K6zIn_pv$TaoctLA9_u(;{cXoD`vWicZ^F&{EaFGrjXy^NPvBZc$@ndKeyeO3(_k z8b&oH{y>#NVcR5c10BcU03;%>eChI^4Z~Takkww-o;xU5}aU)A*Y-8PVN0;1WsX#XQk`br{~GtCLBOMYkk zr_$;$zV+o}%rC{Llb;hOOIKm1;Kf8a^rNva+j7PC3pN0l6j%V5GzSjYnz*S#Ac^gc zRf5#k{r*sMu*w{li<0Jp9Cs4~GYL6*ulJd&%5{{Lv8t&EPW4_PijdSgyYB}6??=mU zj-}Nk4hM9Cq5ozGmc1t?0^iA`MsFbqWz8?=y zYqkPQ*d}R0W7&J1-#@SW5xY-SYG&6ud~Zdwgucb_x0l37yn#VSg^NN9!IJ@dUoW)W z9ugD+kj}kku#2iCc752D4tgRITzV$-xyZd>@m=9g(9|N+-T6m_oc(l*75l;%*Z!WFw?U@;N%C2$E+k^aY zu$C#Kk28~m)ojorh+-8Ze>OT%7UyW{E7|*z`s2hWVuco%7suwhtk>O#o@S7H%wiN9 z!bsj>fp@wgrL`lN6!Bfg1iknVo(RT?$dJd|bmQzVdMpU}DyCk5^+u7MD5edJgi|ge zZflgcH@wIC&QJb=kuO9%&-pE!^YZ0*ATB_|K?MdE=%!mVB_}$Xoh5Yh0Z@N_@oae| zf3B=NQmXGq`2*{mAqI|?xtB3`*1sd)Se(<&h51j%pBBKj065~M(|4u~NL*?I%K|qw!dTacviJozc@qfR?Qy<06nv1^uE4}Sl3o$j-9Zv&~xKMjhpC$ zB7r!FF~(jGSSkNW9vKSRTTF~noU&euaKd~V+x7Ysu}{KvSrKhV`lgTIw5)M7!e9X( zALsleiZH3A5|(6(vKe3>KX;-?%x~CBJGyCUjGJt!Kg@9Dzj7x`RweL#zftb%wbFCZ zva0ha5hLn8`?MYIRseJd5`hGpXmv=?6Y2JYf8+G%AC2QhN6i{!+tvNDCh)BD`qY{K zG~>op5I<%#HeB_}{Zk?J>M;UrAJOTwW+8w;<4U_M(J>@8#^U9j_bw{{$dXSB9#+4p z#CUUOueC+V9?fM>wj5<%6$0dix8vjenVBza?3M00_eDHMZG=R}AEcraSIF9~I($6^ zZs|_x#tyQcmx9I*3ujg7xHeSmJ&L;M08Woq-9id%(ewSLm|ps_FjiFx4-W>*bBvxG zdnm|*i4%ap=%}LE?f%q8V=VFuACDPvUaBgMR*n?zbK2$f5F5lcox^jF1_c}85RbF{ zFoUsIn@0cb9k)%S)xpgZr)z0th7r)>1w|jtq=PGrrNlhiH^&K5C)!IEC+D@x=5juO z>gfagC!h88-xBKme-+MmDOmA;(vilZ@8?};68b|mV_~;$x|pS(Jz&A(yLW+IDyN0uEIkCWW%yho%C+dBR(g4^n7} zQESXH!vIUDuBY$L`4n#hi-;NQRZJy0X&Bm%t6xBGLw-^hPaif)@-z4l=#7)oz`BrpOhADQn5%BN%;V=4PAqcGN8EnEX#meE- zfphxXE+E5r$ma(sg42>-0#m%j%WiS3q$onsa0V2~pG-;hI^NEFL*w)$iZ^JX!}GwJ zPclk<`3Iy?ruC@`(NF_6w#)b>k9MlA=4%fxO$;Tf(9gabpx^7tFm6`;-ZcUsoV1$v zgcmwiOJzSJo~d>tDjqpA4#v5s69AK<(x1wj8=>=}S?zH>Zli&WjbSP}7;VS0l5 zV$>;0Wo6FhFXb{4gwmkg4=X-lLvr}{QMJ<*A^rnW+Sif4oZ-jn9aVLhaT-?jv(N~k z8{}x9wVSo~NyPJm0gwI+Epv)h=E&IiAN<6eO5cBL4u?`HmwiaH>X7d7-A^lmS?*v0 zF)oRNnNuCWgSw>a86CCGwHI}VXFq_M8y?iRg7mzn%26o&S9Ny*s6}`VXJ32N2&D19NIQypX((Xlt@@jiE(^&f6Q| zIF8e(b>CM1+)pik*mj2kej`^c!V7|wy06M|(LcFEMx8?#A+7AETvP5wM*D~H@wk}U zb}TveyQ8y)fvR_Zp7)a*v5LtZ4MGZCQ|>Ym6*fN-j&>q-==mcmx?iu zYKVw?()A#V&$s<{RBsR`yx^As&OngsdqChG&gSP+$*Ds&+%beH7Qb&+4L>zHL8k*T0!@6?xB$c0V*&- zw)3JIi{)0fq4d9t&Mj0QFZa=I241?aoB!=vx{Jch+;JxT^e_?aB?2U>kCT)}neRqV zz49HtK8&Z`ox1*fM0HCmGBTE3i|tx{tKR=9q-w$<|126Z>0+^>thl5M;eB8KZ3S&+;XoRyk1qfnD_ht4j{Ph2+*il1oLxjf!YP;=t zoYu{V#lGzZVi~4i%Eh267zX?IZ5?@*-g5IRaQolF(xP>h39HAphLd3driELe^k69V z>ai1yjzIO(g18T-w=6Du40FAv(?w<6veFxk0Yu|qh@XP;q!REpc7Hz9Ty(na9!bO=zx}nF#7+bVY_C3y$t#;BPJ@gzTgKsAxyeI>Dtf@%)ypM#ltsqo>r{_XS zW3>D?7%V!kAG7g%>geVjqZ2s!EYL#yW=t!({xke~_BbWUis3`DFE>l(nBp&R=GlMt z_i+^$0M|VV67dLL`hoU(@Fey>ttCGUw5!oX?5Nc#X`Q3(=;oLa6tH%z61MekgR^>?k+q_Wj)n@$hpPXMRwhZo_>}J2e%kprno}MJEOn zWW`MG$tSVCbT4Vu2Vc~V<8?lzj;_x@La4qy#y~CPDJCjw=ESS%P4b+uy@pv0C$O&} z$Jv zgaQWE=uB3aW(T>Mv{d^v8Pt(l&Dy=mqfc1hF{ljoE3s0Ada7l2-~P!+>vT=%$KB(S zxOj~yLT#NnapG`(1=kPMx8}9Q23G9&KI{0RZ0@}%Rv<|Sgw-nquH3uZPXAOmN$!8= zZ?!|)M9RMMDvh~r?Jjxo?XKmhKU*>V3f_}T0O%aC(Z{B!*?i7PPAh0_owWKWYT9*l zgJ*hrqawB1D6IdMpou5BO8IL{Oh$q#-J~@x|5PlRCn!f^1A)Nrq)i691CaW66JyU$ z<~2%8*xn5t*#$7JfNS`n57OCeW%?4eF|vec-evlZ>aW<+WjCZQ=b9B_i9HC5JbAws z#Bsf%X~c!1J+2Y_wGih}!)BDBNbTtNnl_WFC8TJNJ6XcqNs`Vpor9WKzUC0YJfDH! z63+aST4FjmvO||hdYZq;iJVc;Ar4)glq3P?%k^X-cbHM#sNjYU8n#0kOmPUXQcTef zvpcQDk8>;hkqu^LC1KH$S^oQjSU+sE7(yMoA>ryab0o4IvfT{p9&rO9Vi^#wcVC&FYxUVxdR@ml?{^~OMAX6Cv&-BoZYQOIK7$K%?5 z3%wwX=_m)8S}CXa{kt5s7fK6vHa~Ln=3t`&^Pc~h$9hgPXN!8>Pv=0cDc&hMO8WG( zBlFc8l|s5%h5{v5qjefdDo)0NVW&RmD?#cMJu?Xy{b0s+zb^bz67>Wgl$zoQnv46t zIF%vt@VI{T{MA)+?yLh*YW>4-7s2u`z;RL|L(ICd16HxTuF~(=t}JrY91)@+FFXwX zT4qCF+?Gv=8TL@{cL#*T0mmCTzKUENjfkIMi@tBXZfe3e^(%A~%^*I9#FO4q^!c7&3nLA6 z2IvMrg&kSap`JRAe&W1baO|!So-()b2NSh@am@Ed{eU_{aFeM^Dd*Ro1ROy%nbFzB(&9TN$ScZp3!kqnyvT7m1O;tg)z)Vo&Suo z&K09lf``7TU0E=b`*~GM3dcUjYfadXc)ERz+O%lHKslD;40KUK^<3pzgEs}7@|g3a znr$aMCf1v zi33Je#A3f&y7_)snbk{7g zTX?xI1it#YVC60jzRc0vYKuM)Y~9WQc6rlziyqg;dubiXs%14p7skLAVBz^Pr=NLtRjfTEI1VH*p zmCFEhi(g5wIxLJ3xX?s))jG`-BxvRu!59~0`Y`nF&!uq+Z5bqE0{7D%rE2F4JWcq0 zuBYIpz)ZWpT85+C8|`uAN!m!P9zkF>2Z5vP@mjx<9_~nUa6$~Hr-;UdCjWF;!aIxI zppVp$zomN0=dmBS!jqCBR=^b+zX7Ve>@GNlvaJ6s#pTRb$|S}=P^${86nQ~jr;D}G zhY~@1U_P$%;EoH(7DWjw(S*`^g$7u%g}{or0huP@N_fs4ia&9Rw8EV`+9-*rXQ|Hl z_oD&S$QZ|H$7j3aqM!I566OAz{%eZ`!asQ~ltcT3=`f^T%DEysw*%1IxRv%vYlem3 z)Kh8kl2a5Prz+qMK8YvchUZf%$C@)FL_69USSX9BJ5#TZ2aMI=N!|@t4`frR1A5?9IR%j+=v0?Ta&BilXvgo(BvoxtUd4PNNUE5|#+XbR zr*G40kPU48ODOY}zE2cDLsf9*dk&t~cL&+lVB2A={W5M_6lK0|&jHv{O0k6Rd30Za zh>PK$Yg;t_Ft!Geh(HxDLt3ODk@4!2WE+Id3&~u+yvfKB46GfT4x#KG)jeSQyu;_h zQc0_imq1L603W+8`^2P&dLQUR1bAF|b`N0L07FG!ObT7~{I+#QiL!UD2czz>{1AOw^VaZ0Q>* zx-6Mb>q?72pyNc&S@52F11}e&;J4L9jkU36dL*M)zE4>}Fh-R;F%QdLlpcHV#iXul ziw_@9{S^O_Qmx&r%qQWglg}`?v;C#piBwI074>~xfk0yp*xduS3?X9fz;1B6jN!DH$ zmX^9!O2VN9%-e1ypsxT9)EvdEVHujm)snl#q)y%Ikh5RUK$PmFVv-`T`JtGJdSGDKGXA18YUV{X)Z8jp508OKExkGq+;E9Sf3kSObSR z=IiypMQsgD7Sh?2<<)@q!VcsoM`FI~rrq z5@4v^^f&-%uaT6cCn2+;5I|jy;2kQ8WBgmY#A1`anESQiq(nYKTl2pBu=J$)*%XXa zJ7it@ek^|Q*L}ikDRn41k+eX0_i^9cFu==;jB!>tYM-JUNxtjcSgA0p?T{v*1W7KE zU=U;SxghfNPAnh55Na1$A^F2?ah>eb!0=BW%@b?88($FBnJq=8voBTBe-{8dh@g$o z|NOE&@A#kv&YQ=~;1?wTilaRp-CpvS_(OTjehA(3r@@7cP5JOmkqXfF%1;1+13j4E z%$?&$W+IE**K4o88FZ#?M*R~ZA8gDvw3sK&->wX4kfK7vB)x7SQ+1<+QJl25V<2vYnr= zz<#6r2Onb3P~v2D6I*#b|A#qB&UrNq6_yls%eLF&WP_ORY2Bl4r8l4HUYkV@tr0?I zY@oTW4CZp{W%8GY0ucuE@a&pbQOaNDZ)N_Rt_T%iUd_Q+3tP*lRpim-f-a&^tPU`J z0Htn~hc~G8*Y(C9PVv*}Fi~>r%oi+)C@BUFsX#$ysvba^2s$!% z%Z|cg90vaS1Ra+qxzZv5DeIAKqeXX^!liUhlqn(n*-yCm1NyuV81D?*O%Ek|5Dg<} zN>wZux6NS_~Own4@;((82@EW~45IuCpBO_yBhSw5)EA9Vu_8$zcF6DzVo%u^kGX$){5)M8nj5gVf z{v!e^1Lw#Ee%_UqZth{@DrYrDt0+vWkBj@&w7r*t2WQPnN#row^%F4e93TQ0%#+g8 z%r}6n?bOJaeIq|`8>u%BmS^i#xb$qR37!AuG8;Q=;uTeg{Pz00)F8sH$t${yL?jVrY@j2mj%UO8P7Vz*73F91I` z8))_K9h>ph=M$&7uZ$6S9ZcBrFBlALB8w-&X9aMuf ze<|;F?(uh52Dy54aGKm@%DBkZgv|PpuFvO>4YpAg81G6HV-DQH;d)#S3l0)(vN0hZ z-UbH?T>8KKH^;o0rbQp9>-#_>FI~|7|0(?fwa|B(p8XmaBY%%w7y9whj)Al7y_^bL zPe3-lK^$W7`az2L?*wCOyDT?pgdgqHzA2F4$ezB&Hqev1_fGTFx}0!<-hujm@<{07 z+kFAnd@Ykrs?sUr3cbLk?tA9PWtaWS$6uC0wQ1)G>O}v4oCV%9uKAR`=pmSSHbIuH z>pz=rhEPTPcEfS=z5hY;=gAyppVgN#tdBd!(YI}RY_I@R>3#@A#ayqQnr7qom9~I_ zwsh>VlYjd*%~9HN*p7Rs2I+|>do#c$>EyklwM5%??`=Ojd;m813d~kuozI26iGbN) z7-;pa@2Tf1J|Uskm}y1Fd<$-YcG;nz0RuT*E9%HsI{YR!RCv5$BBHXo^Pg z@~>v!6hw}xF(>63>GQ*Ki4H#3FQC!0wj`n8m>W@qL;&Px%Yl^lPjkCQ0%l}FsC*j? zf5;06^=Hk%_oXz8`z;(@g)eB`7M2IXkiYKt$Jqfk1)8B!45l?y>Y&N(JYJ)zu}5|p zd;yiIeT|y)9k7PqaR#JsDtbkY;2d^cNMsD!>6N4=#nEJ#p_nIqlHHg0fFHF80bXg! z+E&*|FtkQFO-7iF$NPFrLNFI%rX%JW)ec0d-CBp@O5@Gi*y0ybj5!fp;{nP`igyI0 zz4Pzy7A0c(vh{(XOG6lQRusd_QlCE1E8kX&B6043ILAQS4ClCB$Mj>CoM1 z+~t2<^jF0$@V?|>nVfIeEHVv0PP-(I@h!ZGGt-oqx3=qCU69DnNr>;`w<7~%P>BLf zF0JPP5#sZC-|tE${12Nd{;EBM9r6N|1G7w^KAS50`eq`sl47USN^aBvG}h^u$W%4 zm5miW&Lnfor+QKw=54mNMs+@FGnfS}s)+$%n&sdR7dd2-v~QhFR;VhOPL0!%6F}vq zzuz<^A1W{#2)fHKaOlA8d*0OP-W#8vKg2PZHcA8XKkfkO%id;;_zNg?C9r-EE@`6s z4wTGAqxgIZG)lez<>c@P@K275GJlc)_8sb@NLD{vh<3>TiMf_66?k#C5Esh*YANvd zAO;^F^Y~P<_y$Bvd@={odG)^G8d>oO&A?3%PXL!78~opM@Go<6awCL3kJ;H zLlwf@4{{&nIq6CbP(9<5pTH&a>OWWTUTU0kWbJ(D$8P9tj0Brp-j8$1vlp@>d%Jr5 zE38~z05Kis#a>dTtGV1Nk6t9z?Ri&7oeh{-z==!5AI=)^y(b(0FuFTlOrFhXU8-&T zwE^Lx`~8=BnrC5W=Xu^5@~lKKNUQX=6b#y`b?x%Z%^2_{ZXiT<#(Ei^e7f(l2EI(4 zF8b&u1^x8oWcmzb_+P{ZNXx44V^Vi2@Q*z@c>xvPAp;=f$Y}qUcot@;?vNj3p}dQW z+;LKl@NxJFcqjpITs(koL#4GUyZk&t^;`OUY}5Jn8cp9fDeSO|C}|4W*H?CM`1#2C z`?Ef_Wt#wcl0L*J_o`9GUvm5EI_MW7oX6G!pm6JXTCNXp7fjcUq>|H8ossCfF9Z5s zGSecT?}U!sH?9S~h81_?z_-*xr|IGt3Dh275t?uC&N}xdAeC+?We#Njkf>?wOAz>Di{eq?|n_i>lag)7@bthVw z>O}`v%i)i<`K{ZzZ1^CRNVn3G-)IZ1&z#0`LKWg`^9~#rv;l!TI)NX7eUvGj=}>Jc z9GUWmL(ekK>XB?h^soC_Vdn7|hz@R}FQZK(i9btw0PMd~36*Ah$_P9urj2?j;82*G zI~`tY@_*TY6;|~<)y^;X1QLC3?Wn%&0ouKv6c18>C!|6G{V&oN;!!$d1BK6@iI6vYGP1QUhtroV*zYAE5BqbPn`{BJnO&KE5}xeruys_i@p69>Iv}gi;U3TkEO!uSJ12 z7&c8IGz#h0ZWG_lqm&^Vq~c$PyJIw|Vuh9k5qH8FUiY70UnPE4WmN%ysmd$Rv`ApD zRm1f(r(?#EKNuvGu$A@2ztAoFtBC|+O=mDv-u|0DhrMB6AmD!Z6_|s3>E1mq3u1`xj_$-G~0Ku*gv0+|gfDqAC3-q%|Xk$vAE0ctIu!ZG~e4?hG@gt_wpOau%Zmkz6pwA|Y!@>LH`#L6YQ7J96DgQUmf-fZNDl zp(Rzns|`-prBAO`F`{O^m zPngJco#EpNz5))JYQSR(JS#)_E-8aRL3X;JPwoGk4Ohp6rH{#eg9R zDS18BVVnkLHi-FTpQ+Ou1Gs-a040DIXyv0#@RA6^WWhvIO?>0y@ocL+iX6jDxnlhN zB_G`L`t$WaO_X_5wH8<$%|y&YUf^JM7Dk=s*%HOZ$$t!S@GLHC+?H-w66D^_hbE7;u|v%(SgWVH`eUwi}z3)-S)h1!I*h87})H4AtW-w3k; zL9X;9`Qa%5;YVe=X4Q;K-tZZqc7@P3r2ZxK{YD?^W&}f*pGqs^8uXxVy0TZOS5M{= zP0jFEO8ZvPyYz-@(y&E=r|Tf4Y;*#?w)lIz_q_9lv6@=oaW7Gag5uAnMUFsBD^p32ElZBzwT6am19H^oktnD{xV7N zs{s4_Dk+j8qvzY(vprb=(o8%!=VeqfS5ER9rJIP$1w2aftzYeLyTR_tQyVdfxks0~ z{%Q#fs(3->KE2#M0P__Wg6@wV*0&EJ65yi$>!H=!IVbkbTQU1}y1n)#gTVP0GH39$gJ0|rJ{~D?7(VF!tA=go!PS!Qx za>LTHGgt>yj>^+ zj{rce8aGDI&3Rui29`bgCa0sptR_o{=tm5lNfVIzf-Bqa!D#|<-d(|!=&&sGHd$~F z7+R>Z{N|deTd~t)Oto{-W2m_{XT1JEO(R6E6=C&dbGY0%Y7f^#H0T}PePuB`&TjW$ z#Z>~>uVbe&B0lS`1zid{AdR6S?e%&@k?VfQSf(b~IT#Y~TwpHpcG0#iD$33D+4tYo z%;6;CREX=hO)%HljBD@(67+loR=SD4y%>(m8^0H^URKXfI2|^s%Vb+wor60J7`Tr> zH&!(njrBPbsMzNdQl(tenT+Y27-7;8FJaGR2f==N6l-t5@PPMEm`2lCg5Y?@lS(A|Xdwrk(`9 z2E+X^=VM-99ZBN^M!rQ_CL8Sg51kvYe2+{0L_}$>I`s>%87e0GaKr?@E z*`>p!vYth-!t1#DIVN>AmGz`KYVtpw_+WmTU2n?2RF z%{p{e-1Jy)YEbRT+f!oIA&@P|Y*5gqinmtRPY7mwd7PKgxdl>d4`k1OEMo6QLlIsw zjl#c0qZ7YFfujP6lIW?gwk_{;(jsWRUAf^2T*pTTE>a-3rrWSG$52H_9d4RMHsRfG zqVNkSFmpfHMj7T=3g2a6?1;f?u_}#oc46zB({ob9GO433!jgzLG62)17wv`C4zAx= z2|f@!_0AEJpwUpeGULM?~q3CNj34Nabi-a0%cE zXD?mwMrfF15K{iL3_!9P@st(50#X$Hst^eOW{+~P8`+$|RWHDQxjbMQ&hxjO*P0yH zumOT$W!l?1fIUkBfls5dBIULHq82)n(Fi3O;g?E~Sz+B23**!*?jM1KH=`?tX^*;3 ze8bffMOmgFx8Y-b3u^&JUK`)rfMQAS%bF!7FJvOvSD<+jrv+3UpijO3sy+T=6ymo2 zfVOUYI|a%amR!gk!}`vje~I?*+?=K8b8##|iHn^liJQUuuPw-Dae$KryJuy@^`tW$+~0q|sP zuTQuV1sHlt%~!Yk*W~2L(%8)xLsu=5vT5P2mcC-l`B`8HP1*{?*iACnGOdpCq{MZA z$4~Dbwl#c&GH=mWJ=fnU3{4)BBv}wv*lOtLa#U0k`z@1TF=PL**n82)gYyiDtr|*i$A7?*mF4)A|p2He(PP26^cDTE>Jb9|>r<|e*{BEI#L7+=bjm;7* zhr5C4aQ}|P1qIP2AYNzWQRS!2UcK9_&XWf{EAu&pPPvX~ZRFs+-2@&d?R!^GGL$MmjD( z_X~#OSkU(~49 zb)oH!`Kw-reqsMx0rhKdG5@#xWfaM#X=Iy#yKL{Mp7J zgJt5jX$R6I;UA)*fYE@zM^m!`rhL3c9fBS#}cz5rNA<1{jstHVK>{}r)|>vX!#U~G@#5!3NP8eqtYcq26w+M zQxide`ynis>9-K8rmU*G6lD&fvRd3GC;k}J*ta=364o)|_zRqXOQXPj)(Xc)aITmS z{k{YH5Zy-k`1fgLf7~YA`?pjBZN9Fg@I#f4RZx?&$A3a{{sPzi3yekLk9DNS-Me6V zW33y!-Ya^JF2JxURrCsA7LVQ#a7f>*_YG|1!5($onS%s(7qk?R`{!OVfy$9j&!bPg*>R!EY-Edt8;y z@d4;RXju4&TEK|Q*sctt9b0>0mNl@014rfxP(-TGhu3obCZMl?(<001$aVAEn_L@< zb3(H!+}4U5ChNRGCN zPG_ez*sXDy+_J2yt32UHb#xpx_ybwHl3~}D$4HQTlz@C|KRO$?=%6?Z ze7XqXyIyMNrHEGBpmeY(e3xOhi*N%H-!XZS=i`pF;a6$-yomW7FZwUHnHFv1)DSZk znVO}zb?OBpEB-63=bs{!1c`w{wSANK;=l2;iQH&vfiM5QOf79>pO;?%g1afRHAzf- zmW$cco7uqL1(2Y0sl|Ck$Llt`o33m=GY4ALb?#Pa46mZa>VYuOxR&@h%bY@bqQO>J3*)4X79zDEqt}x47jgs*g z?J-=NmL#_QR(d=(Lqtm=j{F%TW&Ti$c&`WvnuOZN`oJC;DjnsAJ*od_H5`zXJKCBg)_TYFM<#+rSmpj#+Dx}IORhs*IBxgr z6EFhlj@n77Pz(D>;jS%Q?+g$7%M~xg7QTY_kNXOtMr%eOYT3%&ck;(%xV<>{GmQe8APR37$DD>?X&aA7y;!z5eV9uH zE$$*x)}YJ&EBYdt0*57vSgc3N59)QSWIbO}5M}|LnEy?z#&#sG;IF4$+mJ)S`#B38 z;24`S0sV!>d5%|=6ZJc-a@VCgEh#~DG%;oKT?55~4+4EJzvCOYJVkszvUyPO+ofDwG%LLu|pR<2w&h5WcJM zl^M4KsX6_ok{%!dYCEW8iz*DyrqF=ilJJ9S+3^^3Lry`khL#0MWRET|INbX9D0>(! z8qwW*mGKu7bAuAm+IXBCN+R_~h$sjjL)Z7hCs2&1TDdeS@H%voPBZ-k@Xc-6HW}R<+fdQG3f?j2(s#BAM|rZv5ZZ@n_(lB zNV2(93D{oWtCoMat{F`Gy4tmYTN(@`GYkd+ ze^F3b%NJMn^g%Z=2I+aTUYkrLhq^z3-2J(bQS-JU>y>gX06Pe9tf;$`jE|4MzQa$2&|*6vZYeJ^D8<`aUh% zHq~e00NX)?hEc$0ajYGjg~BtCdiVVvn>S{WSc}UAkY*O-Vpfm;c)~Kjcg^ruzkhaz z<8&^|0X*;G0*>p6y9wGr(kdb?ntR|q@arIrAhIQvi&sxSm?^5aBRdZ*mzO44k0u_D zL2%BMrr5TGE;g#AP(ohEMCid8456`6RC0G+*_q%@@=EB6{>l;Ik=esG=li6*0Pm?` zs9!$&t_jk-xt&3|6mgpNh4w$llo)ZUx@_sXE$O>4tlv*^Ze`Ua3 z;5lW`d*^k|-}`dFMf6s8IV+Ar3XU|@{$F|Z1}ER?HavDUf)ZAwL)3O;2Ng3fe1G1T z&V7J==#NY9Qa$}^E?0%4;d3e}myW3M8>2X#8x-bdpDs_H6&T(Wz?qzn3yC-8U(yB*Zeph*9-ho#;5)kLHJiX0;qeo z@@8sTedb60J6is0G0S&vSO$tN2@p+V{EFIkGQ(7HtSGhQk=2&?2aGyMsr< z?POYX65Rtc+}W=hxbbm@oc#RwdKv-(z(>x@o6+L@?Z!&dnYuFdnMFVwy>OoA4J?=%clLr_|K62= z#0@c)IA?22af!iMMkKafa#4JlLt5wvq``7SZ$JNQEzb7|B`^hNK zI-A9u3<2ce2;Y@x&nW3^%|17vT4J-^m)n^luy+~kp?K9CMHMV8A<$#(0}(rZ8Kia+ zgaknBtw3|2LB~~yabNHg{38BP7dKf+M}&pXFd*!=emwr_ zs3KpjC(U;K4}(^ryk12saO5LQxL zT)tIT8xkLVjev{RepyT5IT>aqI+=}9w{3z`!&6G+-ECD@u;s7j!U9?5IibTTscu=O)KDk(-Az&MWj z;jn_BX9PZ*lKttUf6F-mg)KQtiKWT}_}->_!vgfoMEo^pY4v{Rzv}&+2E(TEKh6Vr zrvS*9Y6Yh)(8T-&b@U40jxI*O=*E$VshN7~q0O$dcT| zV(Y%j7S?h-fDqI>q-d?@oL4f*84R(l2imigLwe5YMhGdRy@lyiDDbS!qg|b$0IW$A zZ-fK+Q5k#=oQpCye^D&6HUUcCr_+g)OlGn{8gM3*1BksbcA_zY2idO0B6I7!L#juh zFL8S|2#iUNhNCfAJ4yp$)&Ac*!}-7RA7*R5S54~*tXr{J?fjRi&PRM+_Tk*Ho4N>G zy&9!cq~l(F*WoTYAN62<57mc!uOi+!imosp6Vidnf1PB#N5~FG31geC&3ACYL7s?p zVXIJ9%p2czNC5-9!${K$iQ^=!h%Wk_RYv@NBaKovFw_nMVqEe|;@y7C9r(f=x7WwV z3qD`|>rC#L`ZItCRQ~7kMA$c}CzTZ2MlpuA21iH4l%$Ajt6g8Z;lIP>ZU? z_N2BKGgU_u{&gD4w%VD9H8w&O+6sK~Jq^$1E>u?Q25*Rw#H-S+IxuvLy7O~M3EUwi z_P3nWIjcwrm%uV7Ft;^Brl7!{n9cdC`4c+bpicNA86tXLPUW38A-PTU>VPjHh@6g! zOalB66rB&I$b-|?Ji}kL=&dWuzo^*un``j`s3m6EhJ*ls!xm6STntBh3canR=8-k# zak}?|KP;zMBvfsxr_fWpe*O`_txw4pWxfAVh%Yx<%I56zv#)e`+$j$6?8>af zl@6}QDc1aJmJABr7&c6R8rrQm(y>7J{-p#1p7dz5x2u`|v3`e(I&bnZ)1H`*bY}N` z#>`-`nn#<~{g2*M408zrY!Q73qX83{pd!-t5ydPA0+=APFab4T?v&(5nQGhsat^r^ z%&@M@b+4nmoD`ami^B|0lC(e+bU&a)|GenA{jsy3IIEJh)6M#khJ;^d`ZW>>eb?Hl zP#UThF4&AH>fi@h{6Gqs={3JBF;VFJ*KZxe?a9Vt;7XQuQI<*bH0vtxEu<4gmg=t? zemDfuq7^yGn(T9;fm;?3`0$riGbIVlB&sDO_J!1!TBBJe2u~{YuGy+FYiW zAkzm?g_8^xZITcZ9(tVV)=K4iD>vW-Ja{Dr1W(83l*)6+soDG)wWDfWrrj(Avk>u4 zQm9=P^Q%FQON=L~wEw9F@UE69o&;uXI{oA@d{8h?;(B_d3l z4n@q|iD8|=G}%vmSkPttBli*$(+Le3B=uv%DDuCb-xka-TWc-|qbk9&;krwRmm;&( z&Eq#`Zp>=1PxF|j=Po|cMbaefDg0%q?kyo!8A2^l+i1Z3y4MOzD9c>K$}sfaw5du! z-SFyEqi468Zqhkg|E~-OX=);M;U=5=kPoiV*R{p^#bw@JerTnN$GPz5BzWzDOQjTJ znfE%_^0s*RF!)e6X6U8o84ctJ`(v&l6%FM?CS|9fYdO&(35E?Bay3jc(RFo+T5q=? zS83EK3bSql866!Q=V9&!P7pcFAK(jGE3^}2u-I5sb9%FBCG=SEQ13og)2QP%C^8zh z0euCs+cN!oH|a`%7c~6i)l=GG8g)z@NC1L&k%_RTe7-m^P_Oa*x9}KK9kT&{#TQ~T zGx5=DR9%^EUloVuH%czeO&?u+B>Kf|@Sd1;4#IUDa~O-uWDCRBDy{URUcAZc4>q z;lx1i!7$ha(x*DZj)ncTRKXYgQB0kQkF#I`ZaXhQm2K~%G(K0$iO9HQu!vE~hJa>S zPVROTq^=oa&~Py1=^5`8GR$+82#Br=^aY(Oj>QJ<`Y%_K=;C#3>2CUNlGPN==JPoE z3Cf4L+lLV&9=cKa6|WtyS#|~#65_d(KUqXbKR88X-0u3`@BMFT=cpp%zp39D{8Che zlL<#opNp~L*jUJv2~)-SkT`-*C{;PQQ!r?eSX=FuF|#;P<+7Ue_J&C-x*WPb!qJL84MQ*8JP^F5M!Vz-LxShd#y}ADP-B_w*7Hx$yVW$g;hV zI|Q+FXlqPi1vq_l1=NKwELEYUUD3_+p=Q{ZIQ5dByn%2>*Sj3!;~Py@F4m4u4r_65 zhq%f7o%j!G(C-f{Mx}~^Uq?MaepNqCY_|0G@I{qx5IZCl(DapmC9j)M@X^c(>Pzh~ z5U)ZKoWEu`NS`j?xvO(`rHeYLRAHUYuwq6|Yphn+Poh9uhN6$&_q>#EQsjJ5!HU#Z zH73|BkMD*F8J~yIkGBfS8(1Gd6nI? z$sVTW<*bS3Iqtg&jVBCu)F7a~Q z$dZ!R;U`gF4l^N3^H?}DkD-l%xY>V3qIgqMT3N(e)(~ixp8QgWz&w3S(1`c6;8M*d zA(M4eO58es?}X<%#h;3@Bz;5G=@1clTz{ln({6OMZ#-$=L( z|GK+>Ak;h{8I1--uNeGCA|HRCv9LmmWpuYo$jD5pOqh&&v#o}ls8KuqlDKqB*S9ss zXw2E(vpSWR#(NJKlTjImTMW| zHC=6KvB?h{d#LFfVGJ3x1KFLurRNE2Y*|A1gOP+QkXS}4T zuk-jPtRXDK`vYOYHXx$f8koT($i5-&z(9PG_#$KWA6IXUH4l`S8x1^|SuIP+)^<1? zJzX#&BC*%%Po(ru?uI;sLS2UXS&WW{6eVbC?%3^fy?wrHGe2B^KHtnZz{ReOC(j7Y z+JHL`ia34t+6+M8j95ftwvDb1K#ul+o-Nh{yxuNunH;! z5c0YlM2+3as;WYvU^4nYoa*D%hzjGVww{k95Rd3&@+e8;(TZ+CqqxaEzI+*k)%~Ya zhouubXe;s;OgTs7y4Y^nCBYHFrmucKkf?n?1SaFM%_ZeiN&IdB*bU+`mbu#u&lqYi>-{6QT_a?d=ckdEX|alY}0&!dD1eX{OY zQHkU1c@%6xm3#va9PqM;8FOKTICvm!X&NI;A;&OU*$! zkO|P!i>dHQr`+uD(WDG>g^nLi9qJk>nm=o8?P5ekK_Z{xaMs4f(LDAksQBVpGAH>| z$(~t-$<4BdnzT2Ze<^BJC6JDoC*f7i_g;}1kQ>!Jz1wv^v=vr_^BzUOpitY zMme}z0ku@niHGnVCYWaq%o8knmjQVPE4duXClZ5y6wI_PnewHS(q2hBuy%8;LO?^_RVvdT9g+W5x4PG_RPS*Nz zA>sqTu4df^&uwhmr)?|aPE8xyHFRGNj)ys~Y4nA0+amEM!_j*=Q(S|#nAhhvC?ioX zx(*ps@1~t4dfGCP!m~^n%ZV>Jk%T;MJpYRBd71G!^B=qt%H-Wq)WrU=pY-B_)4edH zDqqd*>6oM;E46^NCZgDlozz@f&B5&1jw-NDU|QbCc8)8M&O_q~tWQFSx$8n^BypOz|0Vl(j0v@FQ3fZ+@-l#R5f;$>tgz@j|M-^}Z$$6RjZEiPAE zRrRAUp`OANIvD8{Y|4B%=0$#*Mb~W4;o*3_N7xv}R|dIT&$4{M?gQyx{)C3cMnKRH z*6G>0+V~cW%lb9B8j0_^$a;3%azfc#Fe8;Zwx7^uDJqTEKvgwoXGa!CC;eg~wTIJs z1_=daCYciUk|xZl9}M5mOL!=OG$K_@UJ&VDtX6?Wwi4lJVur0b!%gvX&tq#I66J{IhDjwa`Z^@Y)w-+l{jF^dK96 z9_Lz2uAg;LOtgC<1V^;uCinV97^G`h?QwB%$!@H3^_SxF`}%n3-Y>feW5@&2Ky-Pz zoL}k$L94Rx?eZ-#F+dr66u+x5O^}Q1@c6jFv1NF=H1X0YsVUlWY?{VUEU*e2Qfg$- z&>#KspmVbXi<&+vaq0w)PsBwm{WQtw!b+e-B?KbPCq@41WJ8i7;j^c9x;s<`^#j_B zkY7_jL}60Y8J>Jt;qiBdEag!37?gAn*Cl=EM17y&aa?i+(XY zo*h+80^80pB7`VG7&uDYnTqA_Y>sHUs|*u)T-oS))a`z-Vuv3SJ9G30Q20*O`xw$l z5@P133qEEuNVa1M9P1*VOy7=<)n07g%M`@Fy*^+zijioh!*PYu6!kHrBk9cK?wyr% zkAuOtbc#e)i;1DbW4vQvaj}SnxWi)@Qe|-<%OfK2lMo4t_&&=1L!U3!cy$`9R2y90 z_8LmIn=Fzpb(^PfKF+eC%5_1&O=m_O&aog?8BKbT%48Q_3IQWazqcAkvt*K@2f#bTk=PX8fGUvRW%_c9D*UF1g>(L=ap-CLwrv>) zj9@_Zc#fTzzmy1xkfu4pSz59&*!^@oIDh~xSAf`qkDhu|-z)SZ~Pn1IvOz^Oq{MTT>(B#ZM9Jtv!6 zz*~@7D8GzkRy)x;ZLE2Azv^h?(Dv$vNGbc?t6Z^o1`5YvJ&3+s8lmW;!&QNgE4pqT zY#IU~R?M`_RMZB0?`ck=X*=>nlu}m0_F#EulHp=kw?K(Zr~*nyp1xZWo<3N18cwSc z;#7-ZsKFv+e4O0@rp92qok&1CTa4;EjSxo-3gKfUhb^H_22--dJ;9kIK{*C8H6l+i zj7F6{&+UR>OIoig0kPuIn>9E#B!`P=aNj${@5P&WuXOS64BjtRk6Vr+V-fuuv0xE4 zW(HspqJMDu(QBiFC&=GXRV#q3B(kG zV7I-FV>(llxmXsNCMZ!xyGlLW{SqM5yuIJe0!|#O#0sm)AGG+=FgVJ8Iv-d)H=SW~ zdDM#8Mn&|ROhQ9KG|J?ESxw>G4kGwGq}<-Lv?H9E+WpvT(s!*%blJh#@sKcyUTu5x zIG>v&Zs2(n@xHl|AP%>IWP#R6rr@o(5(=zLa6>2vMR{EagNAkVf4gwSr14s<-_9lz zEBC$hp4xvQ`@W9P`^9sc`1B^15?>F_L5hfNTp!MXF+aDn6r>Fm;ql%sh&8k$`jnmiN%+q{T{SB*kwb_ zLXl7)QQD{?Zgzi|bn|kF(@M!Cj@xrG;^QMoOS9S{VHX(^p_P1TR^_cN<~OG+ zz&i+*g{U~7&WCEje2^3$S4Qg7uQ4vubzxT}!YtsaZP8|YK*YtQ`g7GK;J@x_X7}snq(Y%g@ui>GQxHH%87-CxC~#h{H*)F*G3g!X3P|k) z>0duA+t`mqo6Y?wMw1xI%!|RcTC~0~e<=nZjB^H#**{SWFg8UZzlSQ-ahXv5Avp#c zq_~`@&vWR)x+VXt!s44xSA~X@ieLX(Iq;ngd;(tfB=9G_yD2;ad?3D`f1;(})Q_xk zBhmARssrbJNwNMqBXw@9F4~q&eI#eqZ^{T?}IL# zXUQ@sW|%9rsrNwlMrS9d9j=K?yrxKzks|`y)w@t+CO^&4|8?9hT$YTF$ub;aLYP+@ z7m?^egFA{SU4|Me%`5;YdDjFymGg!8oJ5Uvvbf~_E>-Glfn0?(%5hZPbf_|$WJtHN z$R$#NlQ557<5RN=1=v{|z@q2z66_Ov(ELOde!h-n^_c(0Y}crFgUklZUHi43IEj#0{bgWp+OxmlmVJ#T2Vajg z8*6F0Ps+nnrcctR3wta~J7zM5UF(qF!3fUU%W$cTV)BXJaqu?Pc{%*~W{UyTJnt6& zzmH=P%=xo*qwQ~ONyO8{E$8>_W(TuH@H2dcCF_C-mqCVyQ9_rA!?qfU8ZF;P-in&? zTt^eMyR%;^jv8>9CZEJfS>`>~-$%1d*_8{7l^<3ZQHYe0@}aEu%5Kht%fSZ+sjhxQ z$H%c4mLal~l&pz~xf~U&EC}$cx3PSC2^-_w*k8lPy6ux(s zeaB>P0s5UCHp1hyw~tSQ091y%)#IX8BoKRa&v}IF=ccZLwtNvtk2Za zw73<9u@ot4W!{)H<2_=6TQhl9_Fso!c1hsC@+Pyjev;vi9Sm~J2@H!0Ihr4HbKZj9 zIPAHiJK?CN@(jwO*~8x1^b}bhIJDQ<19%gIGTXpp?9MkSPPF7MA=hRuZNcqIoK-^d#AICOJXy_kr6`e)m%eQ{)!V%3)mrcX4xQp?U$cC$z*R@GS|tnZvi8h zobL3%?!9ms$#i;c(cKD1JY;4#z?`=_waq~Q>!af+4#&J5fE`bJKk|!2nPQLAo#M8a ze3UIojrFh8RePjHSKE#SvreJu8Pw8J3Dax)+ps~c5c4s{SeX1r2rHLm4oMN*JmT_r z8!Q=J%9JRHy`Ae4lS8q8yigcqUOtw_AlIllkeL)As}I_XO*p_5@o9l0^sWlW8;vpf zV*2%ES-w&H)fmrCck{^#eDVkb{+Nm8^4a-BU^LaZ`4~-t^dyRa8jCY9U_yMfOu;I5 zXy_12KzgW!h!_XO2K9!>6c3&V?OKj5h6ze}Vgy|0Wkj_dXy6QqM0^Lwg8+)1FE~t) zc6-Yn&1^fTX0LhzdW7vz^U&?hP<2gEgI{E)7s^a+&58!eRYkFN-8W~~y9!0q13d!? z9Hvg)HAq0)T{^<^8Jrbp&7<*$U%!0=+a7WaR}sDr+T5q!-|U#74*a%B7fan+-z2H+ zHp(yw>i_~120!Ch;2_F(x-ISA8Ixptj{Eruo9dJ&;DKdQq=+vk%6YBBYlT1R8NAM} z_ZmRM0u65(G5jo`tB^i^IsF?NITj;q)V^@_nTYqtvvo9vRHZ>laIcqO1|~IvO3H!T zVAz{rzLuC+>|)u5cI8|d1hgd&zR)<#nsYuLk#h6_#-;u*JMjZvGML@ru@FSD&)0i& zn72trj-{k8?d%#gU3{OkGr8!rsPMrCgVppMn)GV;TW3Yy&z4D~?l`30!$o6mslY+P z5K+4PlUkXCg|!q>DY&;d=l;0ssx(=^Ge)7)D)t@Pbg_KF{@o(X`%oU8@E<`1K57on zbT&2A*Hg{4T0CJxB4-#(dhvy0R%S_qx2FtP=Nqf4@LOj;=fk3?i;dWsR$I!yPE+YF zGHq&<^Uk^y;Yojc+-n>dU1V8p8fFM|{4r_8P&XHCLODmE)}9xuj1Mzf z=h+~}#$l3=v&+@^2DZjn=p}Z*>|!$Fz^Q~N6DyNOnQU95GCG^nw6}95UXII3Dj`)JW*A@qQ^OMVIputw{|9?~mv7vvEm?9z|hU4CCU< zL}Y(^0|hb?=2}-xGM+xGwUHHa+m!~xE~e7sr_;`I$C?NCUzmA$A&eynDhDYObFaNt zU|>mCVJJ;4;rSa`6Nr z3>BY<g7llcv^4|IxIoK)2*YBMM6g|hpJmpcCUkrBMi&sIRnFJm-NY&dX^wmt&y@@tQU-1Nt9iu(D2>LH&~ z2S%Mykj}0};_i8(IVW(J(0S@2lu|L{zLx{@f<#2!LR1G7A3hJu^Y^5rPChS-a zg#wLMg^^=kBOuuvEMlDULyL3}9LdXEruYQsU%MT%wBNZ7 z(7$xi1hQZC%`5w0tH)}D-U&bndW zvl5*#f@E6B7ROZaCq8J*j3CljD~x78tA@~N0!=;4)~aFRTSE{qw5y09NE;<8dyoa( zrS%5MZ?c^K2urBn|2#O#5nDU;m-7idZL`R13i-|!9MNCaRwZ`o4T`98}NJq0PqP|!+lVkcDr)vd_ z!w_nSs?U_&?4i$%1vPR+L(2yibMI~nrKEkO;!k^!K{w+=OHZgXfE&GvreX?6DhE0C z>8aBE!c02r$_eXMT%QNhc1jEzELQrXX?4TWSu}-QR(ana%uJ@U9A@w7Ha!Wa?|6s) z@Az_c5IbqGHiw8E(tXVN5#W#4?m{R#TJG~R^%u%Y`VBI=_F(g1wWMJJ?F?UdDFH&3 z&eRGz8=?zhvir&BS1X>s?mJCFLJu=M7KuoNmAOn}XhYD4PkHS)XQ<{i zsN4*8H@Zg4t#opDHkgB+w`$8C!_mdY-(c5g6A;9(RM{4r4?AD@QD#ff1PEd(r(4)% z1dveIgunAIB!F*S+9l^Gm=O1*6mdV4a78Pq053L$JO4%qk1Ac7jABT2-U(|i04-fL zBLumuFXJQI2l!)HITUZUzrK|&+YG6!LUi>+rYVdPaLP{+`a>IP#_a*4EK3M~a7Dor zE@wLVn5q^HQA()w3I#|kLj`jB775{Ih(J`$1;#USW?I5&nFoWiq7zOk<@*BZCa42c zxPr_T6So2g|7myt<-GlG%`_+|f|4tkFH9&TC6$g5lnrt+{5hP|U{V&?yoNr9s}%JL zQm$80+iZSX{12AWLcTyo`@D&&)C7EFg>1HTHaRV2MJ~M>PxzzMBm|mBvlEE6_4>rD zp&9ZpA)l$LY)(Cy+>A43W;*`sn9Jormh35nab8-y0BU^I6uN|xswC)=DkMd^itt3v z*$E*dL`7K*a|xh@9ctm&lyMfE`L(PPifdL*ur>)6)T#TFW@c87vJ1pYEc+!7quB+z zBUR=V0D^$HmX-k4P=XRa5nOqLtven&-ueY;rwyfqX{V~~n zf%uGp57)(gb2J-SrU;@k5k+)|_jO`_F;;BLkmw`Ag6@h>ZRGl&V05Mx~wtGR!UrJ∨m zE`<`mU1q<>8lFsFcw(#G?bw2@B>dB&2$OFTX!CNqmx`~l)H83AHPAUA-+{tJtnBJ^ z6req_sK?Zijaa``eT5;M8!>L_%$`z3TJ*;*Mmb;gH2dA7zZImL95L_7X=mUhQKeF2 zDN5T>?o{@R=D7QUOxw~d1xOe|$f`E!c&2n3i%J7W8e@LTA)D(jgPnSYY!+(vu|ky_Z{n$oAA&wDo& z{Xv){vfFyoGliRM>XeFByCl}u)|wJGOCQ=1Y*Y}|;cozpYu6iE_>~)cF}c4wJOuQL zJ$Jk$kDt><|L<9E^igZ~ucF$vX>KI^8EBY=r6z7=JS5-3J;Zgjp9<|3)yM_0-MmX* z`I4TQK+1stcRHTy+nj$H(Y{3Ev`D{T=Ll=Nc{dI1VBt`bNj(2U7wlsQoNE_ZmmT1o8=lFUcy46K_ve z_8ddmpfqY}xux=HH-jN}Z~T#B$9b$}4lRhBj+t)#{!&CUdw%Kdviw0c25p`JA)Ljk z5=_;U;!=nCG8^I}B`tSB{|S<#KXrd&s{Gr87FX_kEsGi@L=cPdXOrV+yQd4ZqV25z zH{6m!(HuPID`vbqW&xURIFB_t>2^g3E}8(WeNokiVq^dW8fs<({Vts${clug`GVc!z{9a;UqD;t&W=7UX`iUydKle&V+eD27fp#h}9_mN@e4Pl=es zg_u~PF+zmLixut(G~-Vdnmmu~KU&`4;C-8K`^|Jv!0u?VQokUcMvb7T_Hoeaq_H!H zSLO&yZiERyH|dDeJsje5w4Eb{Kwkz-peIp9cfEwBnhIbLelgS(VofC`(jxg{mmiJq z6ESGXs3mbLyjCPzLhovFIKYLDS{x7-oa-N}VqDz%sm=}lijz3aj*!eUvnO(TVWyIIExXp5`jA1a8;b^R z>?6d3n^Cin5;qKSatqFd?tZtE5KyO}R%2BooV zrV%jLu8xUAW58mdFA&Bq$d{vpBQ_PLmyS)T-%nfU#v z=}9F?Mj9aLe&1YoQOCV~?PR=c#E(R?WMgNeu0QnJAn}x3I}1}?w~|a@3asK`9_W3% zNvEW!`&Ab}fcY%&4R?gx6637o5#jqFhSDR-$eff|OA!Z0ewGC~ z?$dIQ-7-s~hAt8wiiVV-$N2q+P?-BM*@&)YZyrbil}g@Ba{|A>e;X0V^ptrD*Qw|g zcvJEOlUdYOMf7Vh-M=1w?mxLW#le$QOkT>CUW@rA7Xm#=t=Yz9*x(}Wa)YUD@ls>kZsg= z?^D+AXxPU{Hgdrpv&GjFT*i&EI3IV0_yiqUZKrb>WLJS|#Dbs_#?slc{5P6dp&z8v z-!7%3Mhr{e?P$#A(Wj@%$Yc{U=4^bumn{E*;r?e0TcQx|0h?7|tJ#F1bQgQ)B8Ebw zr_&i_*oMNxc@}&ke!P}GHzB^C(mSatAz{%Jy+C;RH;B%6*Uf4r1=JzK(}4>rrcxo- z%Qdkme9T9D<;6Y_Y?~09zRS224li~?ZlL~HXvl&hNws#cARHCis~WV_dwSoM`eZ}g zxnHplkQs8Z!F80Xg!KGvLo~s7tpsaLHQP=5izi}{OLkZdhQYm}cm2=bmAyW>Ar5eT zh$)FGD#A!Ulx>ER8&45xa0-RtPRcKx^)v*-%Dy~Yr;cv{6h}UVnzyNZZ^NbB7X+&P ztv8qbs?C~!X%phIEs`(6p?N|-3Etd!by)4x7NRDAxL{w!d-L9ut4#jueofquC;v4n zdPC z8mpw6^Q%u&bC|7_h0DpF6$oPxw*nZz!X|YFeTY6n6RiXZ{Qi2&w_Qy8x$Ol~Jd&#) z&oD#Bmvs5UXKEr;(|_E?Ax7FZ^G1=B|3m_t@bz;RwdQKo=hxAB&3?)F`jn=iY0Sx6 z#waI##D}y^Rx!e^QWjN2sJ=OMFPzUH-RmNrJy%_iiM%a5@{ zA6p#yF*vMbFH{M{xBie=zbM3++5b&rs(oD2UH&kQ`39qd2xR#6&WA>G^x-CW@IG94 z$52Mnt`#4=L79kSdZ3#I0oE z0HeZb=@ScoWi%=Zxx6OZ*R5zJvjiZ6xirw)Z8$nUIfuUzLt1aX@pg+`Iplzz=9+Mp zNi0s9_865DyAamVz#FUs(+w<$kdcN}p~^lUSMGxN`Seg8ndUvJ3i{gOUtmhtOr}B} zWI$G!&oPMRbtuwPE*b9m67gP+#wpuGC0TM}DpX_F!YTRzo-0+xP~@#A6>+47)YgsO zDIWe`FK_9<{WHftTOzR+>h}r_9`TdqqzeoWsyHUdy(3x!lc^kO^g^YI$`%g_;&fmp zD}2%zL_rsiC=^)%qLr&elwuBwn|nZ?C@9Jj^Yy9O5d|s4Tw$Rw$V815Yp6zEq%O)4D=M2!8i(K=vuqnFZ~&>Q zm>Kb{tPS+IXE)#YyvqZP@*+f#%%^6RY_W~%@V)LW~oMW6fz8fD} zuG9Njlaw}qZjPExwTjmkqJ3fqW}f#oZ&R-3n`9Nd?M;9E+XJ&CT0}d|Op+=c+_3^`?Iryg`}-cjkTFVET)_Yjr}vUIi@-pV7tZzXi6dr7WTD^c2P2?P zz5g@!y8E#6I{WEYlm#RP!U12GHKC6_SE)JKl$w%bPGFf#aINI%Ou%ez44D`*qRs+^?(n~Hkk zge#_sW?-$&+4z)F$OU7?q}RlPv(7|6e`0(4e0#gCTtxxoi7(O0Cle+(!5Bo@r}}4Y zNUqu5m5S=gH|GT?M-mY=wXI7B6Z5K?Uzw947me79>5u$fVL>8?8*Tjr98jVqjm9xl zlMvD;&WGgS(6CrAFcJh|SBDeu4GAEZL`Fw{-=TzxX!x@q!lx-%6xj^`;Oa}+`f zVN@E;m$0TOR@}`(xG`4{Ct6OQ8B$k($=$97;yUXqq(F zH%kw)34<+a(Uuz1FDsg7ss%@0?>gaMUjLR2e`U*7kzM6Zqo^H_K7Ou(g`r!@Is|G~VDq}Qy}J#DmRY#{ zn;96f+ou^LbuseyyBMi=W10>Hi!ub9s#;c%s{Kvtq@|KW_q-7{hR z^am`VTKAV7Rm??|cC%}o%U=2Q9}cwi3cfD@V$m>=mG-g1SVHsYB$FD@AW4wiNl#=D z#|8*d7Psod&~+=YR25VWXL)jH_B^8gy-Sky@U9PJnMMXBL&5ym6(mq%k|f zHx7=h#~bqP*TZ0s+jA*Anen7urDn(;=a~Ef184+1O775B!Q}gyLGfv{7SSWl`wuiY z@Y>PZnUp=|im(mrtJmF?gdMg%WizwH%a($IYKBS!p}4UZ=(NCa%k9HJ_&`6V(B%oc zH6_rNK=}IS@vQ%~@Z(>RA|9IuUMCo1^5Hjf%O@)Chl5X@XXN6ArSO-6?$b3vHyRqL zpdN`rKjrj7D`??I4L3xv*IgI^OW;4Ttby*+H726SH<-T^XYzzH#SU3f^N@mdX@)TP zzs@k1q26L3%BgSb`KAbuiwgQ`p9t;f?ZjoWF%)L?;l{t+{<{0E#D<((Sl<$Ty**Yc zTGP0t!nd`v1|sPi|Ia)s9Q{|QPM{aaQqp7V;-4cs3elFR(A|xpM+|V1U4P`3%Rue# zJ%3qa;3)!ww9|P9NC67nekb7c;N>Sp)~u8b#7d)YErS;2SbU(u#KFeA&e4V;!w8-h z9m_suBJPtPnm#+JH?T$HzUQ-vxhwy%q#=$OJ#^I&W{hbecq?93T+Kgcd%-gCykb zlAs%KQ^N~#NlK%QlT~MpoBYs$OmMgAfh+*pW^E3?12^;z%A#7dX+MiyMWLN6|Ml&4Lu)PzhZWS5rk zL7d#rjgwNZh9V=i;S=3I;#$%#q1|0M;>Mf^=}F>r`ToQG@|fBVfpso(G++h@2Bwy~ z8dVgD_TX+N506balUeVYVb&R@QWTQ&43AR^Y8GY^*sY3->Gm(z`Up-E$45ALlg#BV zO^Gp*p6~&Mx>!OOGoE}JF|GlrfigaiJUuLF(cZ>!^5a?T4?l|+T zfcq3WiTO8q2oU53KL*`GH`IQ+jFB-O)eO`fNV1mc@i-5CiQ`qbMk z9z2Q42Mh!h9Jlumt(@iZvcl%lE}dnX=p&=UuPmBai1znT>ae+y>&P#E)*~S;RV{13 z=6D`S{)PoE7N31T!M#72jZCR(I8HYB0tEoqm#Tj$g1Aw~uN7Xi0o&Zt8bt-7cAR5V zei$ds1as`)ME@XRU1ZZD^svQzN6r!Uu+h@eiX&m0%H)72c4*01wGde7KAbF}-)Niv z*obA-uc;r`J?MLUkh+{`kHCcI+02#GH5`{u1k~`oXFCTw;Nk;T)UQdFUz3^>KZ|5! z&t5f&iGXZWM1QKZWDdd(hBZ{PNLC1{hf~9zw#oQ;W{`f;J8cJz%oAd5(J&$|bM}uw({>1BJ!Rky(XzH=9GR|9M*8o?LJ`lH zDmuf@_s@jaH!_J{1l&sGYj-cW)2Ml!9;M=%3;q292uL`jBY}Fd<^NEM1D9@-BucP< z?}db{$065@mwDiC*uMI{nMW1Z3)l_ub!1#hLOubJ*U@|$5Z*()>Iv!QXhl%+vnULoS4l5|cy5B9g5;Yc?~UGOU$3|&0#H%K33;PhDOsv;&LP6I^=?mt zy4MQiDAbR`jD#>aAjx|m5G%4gOHr?5yVYld+z`GML~IiFrO4GQaVHF!U&V-YpJ1oX z;7>yb^3bpyidQ!f*4Fo~kNv3gZ~K58Yknj$CNx8j(8v-HF_oz>QLTEY!IBD{=NApD zBichVWIQVRNaY&yk3A9EcSJFshY&t_wEo0AtlTuFfo&y31xW*2{IEIR4DtDSTSMRLDFSn69`+E8k% zH5ch3TIxPHm?HdHYm;kH$z*S{9*(*?oVzkDk;k+V5c2K8pft&R%2&-o`Hf+# z6&DooW-P#I;JxfhQKuS*83q37?3-T|xP@dj5n07)YHwV}xa62}&4RSwlu6hsR%fGp zF^RR=P3ATR1^wgcpLqX*rH3XI&!S|rAD8esU^n3Of#*MaKmf1%KD*FBf3&F%c|l3r z3@R+fXM!hGcSI*y-_5)uM|r_F5fh_qspL9anhZ@P`IvAIbDM^-XdlkuJv%9{)L)W_ zUL=s(TVFc@MUgbzzvXLq!}eJBvWYdDNI9koq=R|WW{y{z_^5GEP0-Ytz#n!B_>VD6 zqwy~9E|R6D)GwLU8Py>%T3!#!MWL;Oqf6C%IgCXX6>?`O!55Jk$%Nr9yk;3{V?&Wl zI)@&&ZiM_0Y}~QY%8Tn5C*y!mgCiT(& zw9LtyDNE;4XwK(?%3^jxgK=Njo{?wb@VXVim#taIZ_7ZCx}bvw*~oOb#ql2&A&o_| zkZn=vcH{kJ$%`Pws}p|AK_Jj|Zp?Df`XMqpURi$|JnH!Ed7FRl_W3$p{PR#gXgz`d zWbXV#k#r;{b}R$j4?)7@g@cQFfMios`fR4N;QJqBdJgrgRY<}MUN&j2q=KmOxkuk3z6>9 zBdN|v19Gg2d54%mD`8`aOh6}L{SS2WY2Uw$UN6XwWwnJ2F4=7PtLpH5h4e@+3^?kl zw%F@nx6F4m7?EzymPxOvDT;n#Nj`-q#YmFUY-SrF*GUQ}!;nzRKqjH+j2y8b<*48Z ztkIa%mmdyxwGbff(99o`4w#So_Gwzy>q2SW5E)I!=*n?EMT3P#k%aR0^q zt+9b|s7h9bAoIy4@|}J*cXQ$KWrEbjYk%PL8N$25Ws0P3uj;$soK1)W)+M?#7*M(X z=i!TJ+9{?^CJyiw5~X$0cFL1yCX(^?1r7vf0Y>@BY7EDk?E*bvZYp!=&sLzJIDm>L zpg>cK)N=7zcD-26bG#EC4Rj%$4E0LIQ6lgQuNq!04gd!tOEE`8$B*nvf$bcXo*z6v zi}S&{C`iv|tcUl9wN+BIz*J%y9zdxVBO_2tluu;zxID4D==*(wH+j%Z_DOwi@Sbq| z!w7R`-@m+#vJz>3d9t{`a~U9tFZJ;;9Ytb39evC!Hcw2A+Xic?M<6+sjj|Jg(=+Vx zCKR%D_GrjHqH}h{?x7D<a^ z7@R7?lUee|i`e*wIRXh|_2xE%kV!hTZblOFpcsu*_|0M$p{<-Z?z_9Ym(8zo*MoEL zcot93Zm1EJ4TGbZA~OB{H$mQ4yef; zM&=Zy)PoVAZU8zbJ8}}bCO4>Qa-#8doSR?)ml7IHvX%h<0}Nv`AK;i26Khrlk+ScZ zM6SFj4Y3w55B=3z&l+2cx;w;-Ufb^~j^x;Tphzb4ksN^kZ6LApL&9*r6M#4EH4)=$~PlF0M)WipusJYhF$%p^%}Fq5=}rX_Bxgt)eXA@ z2eMM&h7Ak|6Y!&{hte$6_{PJ(+~x3VUAsgc?hSVRQ;R^iA^XEms2xk?jel%MwB@H1 zfQ&|KZS_-I8d?|N=O=^zDIt|pcg%R2S3N<5@88Wzv;OVX-0KOmq*sTtA>l_?#-RiR zhEO8}f3RI#jKIYNi@g@@duhRW0~E}AYr#Rs(n_yH2u@oZFbXLFxR-yadjE8S2#%p; z80Ya<`jCUFMyzie1}UApF4l4+Krb^~lrOI$b)6_M6@aLYt+v18K?ew+k|m&N=CeAb zxDGH)NOdP7XTuCwyQz|QcHY^|QhuK7{=96>S>(@3P9w|m*OOplQ32+v%;F%hqw z+0e&%lsxR)ur|w!Wy9dTi?en781APCLR*|v%>X_;f-{l#FV`3nf0@PqMAJg+mT+wV z_e|h?s=3(OCLiUMFT^(KJfD3NJ9PseUq;Pu=e3*|DfFsR9D#+7i4?L(9j@<*=>BDd zn5wlXC8Xdck#Wgmr%)XMb(7b2=jd@dy`a$^$JnS|=xDW;YIN=)L%Wd-?EA9a!bOT} zxx!5?ZP^^z&;}!I9a(HKAF^Ggkk#}w#Mp;_DhNk>&FY~lcOveAHa1J!=c>yST)5wD z*W?1Ex6^{Z9xzGk-sB_*;FQXc#}xk>j#B<`j&(|eSyiA)B0JC!x#O(Jsdn~r_a&{M z7~6N^8pZ^CDwG(VWM(LQvsbrFPf8F3lf!9uNj)y=Pk`1wOQG(tD0=>-3N7qD7 z^L;wy&`!s7I5@c18fq7r#ukyLtsipXpr_CD*-w!#t>C1_Ak$iDC1!A>c!5<|5)hk9 zQb#trTYogI4qZTxyauN}KmK~Vq$%|j&V}&&+7IL84_0il8I6%5+s31Cv-}@#oq*ix z24**4u6n1BPm?yeHXu4E8@4&#F~+bjy+zgI2^X`2?iI31(wJ=kw{RKF#|7~Xdn(-y+pO^4X=EE2h$ zNXw%ZB`_z&V}bXLwiPi*A*<{C>s>=3r3d!L>G7Nso4S zs$8E9`qf8xzfdWk$>}N6-eK3#P&s=7 zdJRIBeDkl;RO8yE`I>KUkLWGVSUzJ^MotXU@4);mV-l9q*wXI`ctry&$0B|f=VZ*+ z7o;eD&wd`5U?>De`Q^5?(2DuC8xDKek@dhlKX%@PTIPOa91dC&e1 zo?;Xni+iljCW0tuH-!Qw;efy&UP9rHrJ)Ua$o963pErWNhX0!8A3c>K@BNgTCWIx~ zP%7RiqwsTga6;hY)cNj4dTOj~7Cq@=MeNSADwQx@N2e3AZi+;Y0N{*vShg1f*_L!M z@p-W_(yRBm-7C=m{Fs8ytlBdZ!XWen`aBvhMxxQUi*^v!##1Cv=JBM6Mj zO7~o1aVqk@tOt!#Zo*-ueyAH-@=lBYyUNKU&%=_ajwuF=2 zQ9imH6$Q9)Rt=32bJ=7kL(2@5n4#7$S;mculL<)~NyGo)fo25knvQCNP zk^N}gB^Rt%Zd7sv6+D7rE840*K{=$X3pQ@(=l+g7oHlmLjc*gKhYtjqgy3*&jlmb@ zhakkT=$z`W$2?KlNH+j&rBXPbST<4yodk_zFq$ZfqoyVJO3-CX3JikVN`2-(@DTyH zO+HEW2YALL2x#_aN6bl+CeZtVDV)DUY>4RgNlIk6mM2o1&nAx}Fw+X!N>xamxZirEr7(1_m4*rvcX)@E`+H$cWkf`e8S=|b2Y;VeB9-}3%7;EvXCdz!}>6UyZL)9f#4 zX9)5z{Lad_!KZC?Gw=FCcGZ*ns=s~EOw%$I^!R0i_}ug^0=e;s50&#ip;1FCp3D>T z3?&#+VB)ijaYD5he`Jq1VC*5qZ;yd+DP$GmGP1q64cIXT*`L1|;WHW7J(x+I3`^_% zm)EJJMo>>Le)zj#^gXCFsF|L9``nSh4JRP#`kW)s_Ub{{3*v?)=t!3kV;qGp^p=s5 zSi8TCkc=6JKhWP}WuAgn!sYFE&chn1DxX6Q>zY=?gIH{h^b{(*Dx~5PU8qzZvuc<^k=RR+-!bNImaq8P1}m8beTsvY>cTw@M;-Hv*`(EwTO- zgQ5ypn?n4DPCp2oPhOL~Ycfv>1}y|0;EBj@=8VHB>)9}waC!BY&y++jMXY3~c@a?{ zg$YcU>hL^v0+&i?253jXc2ji0P6uQX1Fk`|Rvgd*bEhhlCymrgpMcjALA5lgIFHqE zy>LeIS4zCz93K?3y2s@Iqhs4g{(L{3aojSTOlVyaTCqq}5iZMQWc7LJ|_a zPWK&nfRKb$D`ZcvTE|tp#U_UKe>#omxCcyz-WJzlJCmZHbX5Dqti-EMHHXGe5{*7! zZNQ7;$MIj~%0+#$$}`Hb{r6rwrbv?b6FCMv^}lx3g*AD&zAmnQH8ykj3JlN!AknnP zFV|9|4dp#&ojprbpcUS)zwQPx-u2pb8Qj|TOpsba>L68o7{VP3Za$HwkiQm9L-aSX zna7BZhL>T!zrU3joxGobmbz_Ja6DLHpBJw)c?oIuaT|GZxvka+4UM4ESRKn&mM>HP z#yEDckQa$@(X#~CxJ5Kf-R6zXqO;l-+|g7OL&qaw$rR$nK1!9$R;8TEe9tGlc}$^C zJWrA%l-(#rEfyE(yr}r(`v7bB{MA)H+3Ha)YJwm#db;#Z%gb{xzbj(1ltC}Lt&DsP zjTw~&o@u>=xm4?b&;VeQFsUyu5(VW16pFnMMUuozC6O^&dJ*@Ma>9Y#;(_yJu~5ua ziYi^Db|k51JsN#hZP|*1?#unuXSVLfxB3Ff2kiA0q%eia89n&S{o(|$-OZ!Wh%IwJ z#fSBHe@Q@gEpoU2+?PUhQEQ?Jh=Z#d z-uMecNyWuEGT+rXDal+GO8SG`ev9S^s;Vf8^D;oN+r#uJ>C5z=e(pV@OV$j_;{)hi z6$db?82fXmzax=~r*)wN2W@Uu@d8jb}6?#s3OPZ8|8v;GwL z?Eg?EK_89&Y+K>ZvUFfo3zQS+mPT}9@y?N1G&h{V5G3l1J2(lZny(JHFAHeZzX9no zI}tf!QIEG<0c-RK*EEv{a=<#Ct#@!~bsLUZ3BFyL$QOBkxjzXPBHu38-26^lTL3>P zS^d9m4QVrJDUnhc3C8a@WcVK%-4~4L`<@NBn=+6vq^5~bUTDRi=1zB-hwI#r-6b66 zym#S?gJH9YV6`Ztd>@g3ZPZssf`;=+mRIi^$>{?TI{+RdOQYK4nP8kSTdYSvl(>w{-z}7mW^^TY?cV9c`0w)$<4Y1akbed!KCC%| zaNyNT&h)i+NAB;i0-ih$t*g{OL47J9glrK(JKT#1abeNts`pE(Hf8}73A!4(n0ix8 z%orVg3fQ@&@ZJ(j@%r%hhxuPZ3nh>{&G{y`q0G;$El$ zk>sX(e8{o)UbztpC3>wMcp1u|*N#%dF{SvKFqVBnD^9;^9X_)J8k?4n9TQiu@)Cv- zeibzo^9r9Cyx|E1kX6RmL<)^Gjibo$@0UF`a|R~66EXyJH7XtXM|#LUQ>WjsxK8OrF~K|5mWvSusi(8zat*iBU3I_qysxCP#brIrG-Tu%C6cr8m+>Fdr9Bv* zvMz1JFB_>U8O2$uZHQY}^vA)#wH?sTAC6{{Xt%j@7vTlC!JGE}FI5zSy^Z^uU3Q)c zD;odz99AgutZdlvN{=bR)F24m)Cx29dH6M(C;oM|W>V$qn^^Eh`qPCHJyB;!-PAm( z_}cG)7Ewur{?NAkP`f&ezYchCqdOms?A=((kHP4lJ%(A(tbhVB5N4-5BVCi^3Od-f z8Ru2XO1M;UQV181){S^LUNe^C;I_kfWjGXhXfjvOSMo2($@{~Cq3=IGY967BV%)DZ zm=}dJsZ40dsL{H_lZ_|EW+yDheu{r7`O+ws0SDZQHDllf5$e05iw8N4ZUuL#0`HdD zMGAOjRvDU6DCIdlP&UVLy~yFSYk}?&Yb$^7iu|U{bE>9_mQ1-{{m9U@ zyF?}_{E*C3zPOQvu_KkrSGvQ$_73Q{MCS7aB+XV0!umW}BW3#;$QnENt@$2NBK&+* z^N_Ds_OtudxMR_<9A-!4e1hNT4j~mp$tBu?H#N5EpN{!#VST+BS1?r=#0DTuw3o;K zf=xCd4DZSKgets+18)%=j`HkJ0#x*A(Kj`Pp5=d~GI*lHn^RLA;FK&tuJilh z=lCZ&_S-;Sh4m;3}TVv=f;4#uKjj=9v16 zP2TnUU4Vp&oExFlXti$hrkYBWNsshIjy6g{-%-9IrJhhdF#zTDbcQ)JiI>OmcCAgv zX@FlW$`lvEsk2g%XvE?L7xv4*ZVY-R^@88TP@J%^=8ue`$^)Tk~yi6gp^eC)? z)Ja~>y1mMw!NO*|?xzRGFkw}pvqx0n z+<2<}gihAOyArQ_`;-eFK$8MA)90h)%{OXXeF=sFA48E~Ce81aZCkO-*fLTHix^h* zPnEa&hR(sKtE`-q#<24Ak;hwAOh*Ax)yFmhov7$(&=9yi!xP@&)%L~IaH+)z4npDx z;|{l{P`mu(Yy;rDp=w99!iaE196^?BOTo zop9lS>`2MxVL^H~pCUbiDXBQnQnttHIlzqo;FG688izlb*oB!Cjjr5}F;SLB9;IrR zsf(2lmiy|O7%SxXvntgWo{{P|sAI()+p+Hy4sp;yburV0(U_T5b6Q z-6!B6D>!%QwZi|CN|UEBte!SCU1)^q@STR4_#Co+(8sSMlo5JRA3q{{LnOOM1ac~d z=DpZc5%Z=5y28rnYg||n^G0DcEIsq5-XZep8#07;|-UYo3;S25L!~F60f*!jVM8x6Tw${8Y z(Rjz-m+k8P#Z#eri%JyvC@49$YP6*E_eLUh5+-sKONj;x3}X=sRQ(hsaP=Vi=3a-^ZsccK@ zKQ1tNw|;(gUWq5$JGhS2To4+LmpLlhdzDlc(arDCdP2IjWwRGkYMIkFmHCSaF8F2t zbrj$9=n~Lh#4+<;eYf=zBm9Sn5$le{%522o9aKL*lzLU#@x=5o_t=C4 z(sFIQQJB~Sa{5F}A`KV57s_hDK7mdIlY=)vngWeU`oJ1bBrv!{k)f+hE?WGte=TG} z=FEvGd{Uaw>$~TE3I#ns0l+7|%kMqd!z(&y!A_lu;ECbJh*ls*sFUHK@ZWD1UCl&y z%Hd#Y$VwP0h?kWwEw%<^IDhx%XUfOp2@xUL3!ThRZchXIKd59&@`V_H zPU<*?iAXGJvsR_?`0TwXCOzfML#}<@s?H59mC0GDxDJSV$11D=T>|e4PX%pp_U_X^ zMG1%f4~pf165J4DYhK=X`5?sBPGiWUNn@;lwDF8kXUxDExg5{b9{AC(`ope{+>LEIq(cXxM};1E0zAVAP0Kp;55-Q6X@2^u^hxVyUscW2=)HFD10 z|K8`;eW+ITRIS}7T4Sv_=A3=?(MQ+sTW-oE%=A_4w;$LWs94uwIQM-)C*%4U^8826 z&nnB@;jD}`S;!o<^DNpESJp!eb0I1lwE@N6@#XwloTR`7>qAQ*NRq$)|SYKeWN=!JOn5a|C^S zdfcPM!dM3dyT?XHa>dgx5ccL1^VeJ__!lqUC&Ib3+G_R}h(2odqEAYqBD;Mj6rAd` zeVf9B^L!a6KbI9M^tsl+PN$q=S@|D{Gv6L1uRKcVbfm8OuZ zQwz;nqOl!a3cY2$C{(9+y_Fi50_W&D$q)-FG@CNWx+_b3W#UON!@(;vO!&&1h@GFhyj* zGec$!d~3R=j_3#{3?}Z+F?DH_597RF#7*?cy zs=tw`eyy@ly=jK0(1Ysb``DES+JqAr=WIOR1RL?9RCmoiE6x#9S^5`e3Ij#@R8NsS8proM*r%3dqgu}Y zn0CyI3}jS<*b;Ps^cZi?p9wOwx-b3=hz>!NzHBUEcoDbMOIP+|5FC4Z2Jwrn&vL%; z1pP+k@XM01wBbrIZn!0#$Ix^G=>jkV;w@cap@!k*rnPmTLUq(5`8?ZU5MSgcNUm}c zAGR=bA#m_BU|TaQA-i3UO0CsU;*Rp2W3U70GdqtbtZ=+OWeX4KG$S|!Fo+FLd*(fh zTaWs%KhY!TWOtHdb!<#%OTvkB{o{yV498s5i=!PmJ?OE>u-F%29~#y#q5Z^G)h>Av zU{N>Jx4Z2@NIJe;408;1_vGRKehzc%R~!~){?qt-B2%c~$GKOIC?f=x2;|+)J>o$L zDyekJv~h73huEsUuT^%xB7k^Mx7T)zhQx%SvjGzJX(OQ%ok+SR5{q>>EjFE0H}F${ zOXEop!3ZK5W@f6FMWi`rH4tmr6s6>i5Cnz4VN{~@hC4@Q; zJ1V8^EVKqt?sy&fHzU4C;njVNgV<0L$mVA>>Oep;gyG%AetBL1A$P!Fhgsp#l=ge5 z=X{F=46k2$72)(te0H|6fI2gv-ee7Z5f9$~SLyDkW(y zCmH)BsgWJY=Ztu+^Y9SD5<|j>_#Aa}8U%$F)nU)Nvf!mLBG;~@(s zP_gf(%=vdL)JE$7Xkt8_0D+q~pG?@mwF(0lmlCp=6VlLEr-jKP^C4G$d}d+A)?~x} zlZUGT_SdEX;E=yG8)BNPG`;;z!DxZJ7rH9srBAjhAsn)b_1VYJb2=1OH+*d*ow-1# z5sNk#y^s&q&#rYm4vRY+7Y66Zt9Qbvw(>uE?Bg7A@eGNDvg92LlR!U-wCD9xvSDYj zDYCI|k(Tn2XCgCw6sg!6zG3fl!)g!|J2_0NJ*x2p;y@zHs?u3Fs$OlyI-a@O$n_9^ zAad2Gedc!C0VuDia;;zAD@di&Z^Lk5IO8@A?H)F{uqn@Dr|Lp%-`6gpJG-C zD`fWr9D%}t($&!`#r1A3$9mou@x3xeugr1BuPwhIgyrJF%BotnpKa(i^ z7c}1;W}*BT6?Q|3R6mmD|MI@y*q+mx=0zEUL=WXhqjxYS3t2gZzFMFq{Aaae5%*Tm zwf{i!rXr>}d0aGu2_nTv3dY70=!o-1#liH8MEmx$uzRKLR93XkBor2LgPdnnpal9W zak`Q$0-~XGwdHiDmgAXASmW)U@dmc3-%z$FGImg0P|8}@*z_WqYQP6+#O!@A?8eCz zL6jqAj#yuEWy)cqpF_fBa)N1}5XcMD^zG*?ipm(fqll@jf-LbQ%eQEsd=nB5HR+sa z5~EE5DqX+tfN%z9RN0?0>hF{$33QL*3@&tLw>n{4I0c4lJOxDX!N;*N{)q3V zL8j!*(Xyc~25xX61ylsAKPP|?ZRoCOHKy!jabKPLPet%w5uo3e8X49Yu>T^19yk`%O=EQucw4%@6j z_9`a#&vh?}f=IJ-XaS?f9S#YH7?_zf=R|T0a6zFYd~Y9Ws6xoOm(vE2v0|!Z^Mus> zRjgmUn|wh&kcfSP(ByUzc4^ojO)7l3TaYRCc)hL=Pd5}pDb*E*d(~NCim!nj^aMvm z9k>cI`y1p=ttMF*prtjOyH_MGl%S(5mbog(g=(y`+&WS(iua*Cjm~?&eVnpA6Nu!0j^=!T;VHbgfb-Dg^ zQet__XQB5T3$}l^h{(0JIVIy6hRCNJYuX+sN{34N`@IBR=I;Q2!}I3?4#roDHJ$6B zjq6eA&I^^S5`L)8OLd!-Jzg%yZTzBSBRp5ADnSA-bW&WNSUO6k0geRu(bkJ?R6}3* zC7W9sP$*HN*fXRew0^Ua)V5)_k|lMFv_-^@eG7Mi^2~Ysp4RK}O`&iZWfak5rD2P> zh-QFqPF8p%ad>oyHe$3N&3c^IN#MdW!=JJ{oCyb<%W?-4_G)5Kj9t<%;>YhE?VlA? zyu_`u^n7eAU$7K#)7-$6b6pUy%bHpY*kseCnMV{zR%ayStk7C`d9N9UUi)&C753=` z9um!v59S)=yMq!<72Y(8O@Y7K8zK(-+;gO-l%$wIzKNmx8(IkIDZ4&bZ?rgDGYh(y zr*1umO@_-;RdCb_q4N%f#*6vm#Fl%mui`%MtSArBFr;+rs}7#42@Lad>l8#aYDV|8 zc)G7>caEfE(}VqCinLfCDvZ(KlV{dTQJQ1u81{iXlqZNV`xsCjHC!n%06c(Dm(`xA zuIr`KK-AMOY_epRk3;-iEJ(0TMxzXPanX9wXdHCuTVyj`TEhXq>XR!tF(&Yf!BU>`i&(F_M+3}UWloBn$V*>ys$gTJCjMYgr?j-(l zFg4)1m8V8ImOoh}V<-<=5_Cet@zW1DSNm}_y~2CA37^YIV7mJ?Bl##%tr~jDs27W5 zyite`!v6L>Owhp3{iVy*TXz*mOC+ma=UqT-^Rb^2Th;f^pXv(so>Cs1eB3Zd znb7cN&{YCkSqzW#?VppeWwsEB>beLopnVS&4yoyZZmDhD$ou@1d|!ziNz`|Q^%+Wi zgDDD9s6L!I*w6swgHZK}d6QuxJhb9smzsZCKy678Nq&VqftHKtm}NFAp9VovK6SP1 z3sQCb;P`GARyU%IrBw$YtD2sJOxFqX9 zpff%S5b8IE`2ucAYjR&iY;-&ePcKoI;zOlVifM{#Ie)}0P*t>8_6Fnr$PwJqYZo({ zd9XTg-%0W4EIvb$)^{glu!NkjCJ#Pm zuCYC15@W+UhG0-Y#W{za68~D~q*|<&@)v0Yot8og8QPDn@=2@>-(DAM5puor*_NX{ z&h)$_Jc*1AwKP%&q#+pD$}=2*{dqsZsPShm34xaO98E9WnJmH{Uvtkt^^7+A(&KQW`+|l2bl)9rMK0Pb0)p+6d@kifHUdP5 zC^Q~^f0jx+kch)5iA^W+l}2F`htaDM(o79dDU7fzpgzN*mi&(8*&RW~I#*0{0V6N? z25!4BTWf=auFYG%h@CJRI74)_U*kBx&5ACzbcBs7mtdcS@ZIW^r4guV;raigcf8zt(G z>${$YAVOe1qPrKstyxZCjStL@hXb$+8?RnWS0r-Pk;n9SEf=b8EyijA< z&~I0-#lS^!BHz9vGKkY3%oZLl*7pri$eBKx{b+$h^X|czTmB;QCPmy~GB@-b9`$%! zQSty%Cx;Nw=a&Sq6_m69n~9wgr{_CN003$2-+>6_SLyn*QQq&<&8Z?G9#O=`s3$^9 zn{Sh;j*-OM`d(E0$-A?WQ>us2>{A+XY~_}tCT$^kCwayI-;?_tYS%Ddt>;ql@-Hly zbdeA|$j;!2drI0$Qdl-3Km5F{?PG|s`-XosiTzBG^2^IWSp#vnUNYY=fU1LyoDf@@ z_E_yeie8gf8rGYUcd+dpw`U9d#Lh-&RS6O=VMKlz^NS?%BBaE0-t9bE4F9<2Z%dxQ?x ztu9L*{>%8|vws%#I&D$YQkH#^&$ zXq;?Nn2vU}c;x%A0HmbdDfrG(0EQR9YN^Et4dIi+mXJkwW69tDH@i9NTQ=MTt+14-@k z#=Yt`xrXEo&IA1SzpI{Cr*&Q7lSSy=oN~#H`g%ffBs_tSfxe@4r9N@x??a* z5PG)cep=sy%HI3#=Ck|z25B=qH?@K&5v0-5)EL4I^y&(iN|Fc?#!PJhA~tShX0$c< z+y7a=KT`-^-Oh)RjMGM_K2V3Z!m&g_ew7;|2ess(@wwa_R!Tx0iL!VwzS-L$mk?yn ziw!)+>dsWz{C@N2J%pI}q*2(Y?|NFnL^{SYYUBfwUbEg9=;2H-oh%zkv}zL&5CBkp z78LBzfv0S`8eUH)_HaH?4UcJ4X_Gl>3P-jp6OHMDAwY{IE9%|cI2E|rR!yTo1rt5% zeUnFk!iz*Iv|{dhd!Z+dcfbS_9YZ|@hc?+X^LP}H#s7rdTujgbkT=WXf=0h5))+L| zk&OfhLqsO>!V5j}mGne1rpjByphQ>6KhaCf?Tlu(}jI_USw;et&v* z(qn>9v~$u!i_e#IgsIAPu+2SkEo8;fN%(g;U--I|L6XT9-R^?m02VQdRv~V~7m=(M zYx7P!ncdK9EtLLrRf5$c863ys( zRPg@y9Rxpap}9%m*EiYF9^fuCQifHW0B4WT>#2#uEYG35i7twfO1Gif*6M=&L8>aY z|0*Y-c!n&Y3tN;Frwa4xDp5PYwBRK!AxVVcfQ`A@=oAj)w5v#@pMUsFsk_?*oyF5s zv3*O~I|U1+uRQI##*LHV{kAAwmeWdPr-t=BUt7d(6l2~miJU+zCu7`Kl%S>5a{@$M zp-3y zRBs>y2Kr@(d^>p-9_Y(dE#a8#r3qyOC3jki%sj<`OK45RuWe{aOtf+SXlKQlGDZZR zs=EW+s3merJPyf}{y2FfMjctbh3?QwwA!omGt#uxZCyu;4gUWAl~yw0c%^R}E>YPV zTkW<6zp(G{vp)D3M_4FVu|oNWO9cn8no`DoI;VB|=sHngp}{FF?A-5eFsqs%BfjXo zolX#GD3Y<{v~O+Dte?T5+hTBu8ZvXpD%l<|><{IQ(J4)*NcTkK)10O3ycn2nb<~_n zh=mm=U^i7|K@AS0O-b)Qryf#a(F})YqK>%elH}qy(qDs(3ou_(?a7ELL=4G!SH|nh zoD{)a984<@@DZ$`{9OqrJwB+sW04W~T!K;yc_tpQ8;yh#H#3e!AJw`~735O3hPsvm zU^pqG%|80V(4UNmUBA%6*Ei5_wP}8S3pig#eNNUlB{WF-0jzh&%6v8QTR}HXGNGd7q%{}OmN#la1A^8^vC8KNfR^ePE#H5Sy%{yqdatW51mjPVul`MB-Jt+1yC zc9#cK0OAWEx!SrQi7-bElTJwd08mU~JPsqGaj|{%>llPOag_2TrlUwg{tBK?C~XJK z!mq}$Qdb(@-y(*(UA`%h%d(pLk@72nQA23kzy@RmLUxBuwt`88Kj*4uW?W17BM7Q{ z{mGmv0lW*>w(plg;@PKzJOJ2=W<+`-pX8k+C^t>!+CDunJuN=sBCG zj@I`&S1;P>cqZf87gb+WBwfIyg~KW<`kEXhMAUxmW$L5;llW?F2?CHO05AsFW)_7w znq|)`K%%j>PcBHcU^IYtlXQ_LxD9DME5$do68;cTflAT_P}Y`=0IdOi@cVpObUT!R zq(ot>if{mxyzI8eSSKFT(No{PmqRAvMYfNbk@F~uTl{vl{q&v9&FK$RgMuh4bugDJ z@Ur}o^RL$tr#Fn!&z&UL_)2mi8m@iY4&_sLQDrYsVG`WqxtbKG3?M%x1GEF39mV2ZZ zo%x(ucQAwXk=cvs72?HIP7pfwHrAr^6C>0NULw1?WQHKSmJ%Q4w;#NXuMT{?BQn}= z@2Pofj~J~P`U=xw2W4*0(?v3(v1n>z_)4wNV?bLgwMYga@G29#uZVedpp+r9rc|!C zUB!CYx&{it(Vf&6wF3hE6>nsVOyxKw)PqlgD7aqnDO`N>N#V7E_`;rgwOt;bj^kE7iHhGpPd-sFu-<9f)1P^aPDnM64I-+$3V=o8j5203$Q2KUaBQ6xJRgpsFK^PF z17Z?b7^7`)7%1F%z_3-*M5IwSdYK<>n+dn_Ad;u{TI9tC`RDYrV$^AD=@DoPVtRb5 zH+A-XWSDs;0~H!{L85XPbzveD2nnHc1#n^QpVhf!)Zu;epovsyu!rtnJ@2X4;V8}3 ze*Q{94SE#z!D&M|(%LG8O^i1OPUZ`zZTr$dp&MKiG#? zof`H}Agu$FC+na-0-%@%A_l*)TwS`c-{J*obS5=t8+AA&BHRo+prZ8Kq>3|j7S8d@xEfEX zU*mm_Kw-*9!tdG*)ww(bYeaw9%X{GzuJ`>Nz))Ukl;~8JaxMrR{Qkv^yfvJ@pY}w( z60o|SAwX$;UiS9KX{qjJqji`ZDls9C{E@<1?^?r8JTTO7#a*n857??AYD>!-sjkwG zS>7DlKD_DBVVq)DN_<&eb)uZ<@k&Iu@fDu93lf`6-pgV9?_YUhXA?mZ=#M7-RsgdVkTP!RsZmRAIJIYd7r5 zVr1xjuj=ob$|-fUgwM{_h%r)b^=7UvRb2eIdpHa?hlqn;2M`fUvP6?Qu+{mfB(t-7 zQ7%z3)tLrcwE}dPoPFn4>t`baO)T&Wysd$e!`~8n&DVKpl!-E!rexsAJbR2cDHP&7 z$y6aVOS;ja4Ej1$vLZi#x`q~;*>kgpITm8@VR+zMd(nD13p2Ufva6==j%#b z9o(=SVV7;Rc0h)UT|q4;EA^98?fm3yq$@WjSt8`+PeA)s+F3cAuGdY&G}L@$PzlI` z1p|`2;71S82m>TR?a7g-A(_8?wn{Sa9pAEx)Y4!28hNJB2;CWGNkOm#sXhRJeMu(&+Xm9@ZHp}OnH1&Q|YFs!d8ADR?9NC-2_40s= z>pV7Nd~>qseL<*#YMiu{ua{;PtG0N+<(l0<8!aU?;7nvB`6l-_9OkUf7smMs+w za2u|B*!8N>&aS7l4edx$d7p#0WHl4I=W`oOU7xRm9~F%<6R{ZxAH40thB{xRi?NC! z_usW4nxN}b_GoSN|6*q_4}m;`k9HN=_V=6K?sxJzC?wz-fp!D8g>5$NiJC0Za}z1} z`TkDk7s6do!TE~6Nyn7)c-$1+Nx1IwqLx`^rGPffnZHVLD~7Gxnch*~;zivrX|Me` zslnKh#YBD+(ZuqrWh?z=mV_W)NGr54ol8}T9x6V{Q`=@2|NHlcV^SI3-EF{=J9@Ro zv!1(F{`2G7>-F>X?|VHX$7+<4E;%g0B}3OPEM)>ml$2}X+kMm-o}pN4el2%pwU1y+ zZ=;X3KRg@>+tmhRB&y~sr_y;{o^JjqT$f!lc)CnwIjnq|x!U*17}tE;hBDT39^Y?@FnQrY6pP?rlJgY4Y(_o|igQ2O zn^)3m<1D8Il5ymsLMmcO5ue{iT8*UA*Z8e2-F_+dc?*@$mG}xqa(`s*KKfgL{4yxH z0~;lpv8WJtPlSVmEYr!XoP6}LJ>b;v4XE$<`IjRg0suENEZWGs9D~=qh>uM zzA9|o{GxgXU&CSpc8O5_lYTyR*HcL%M)HERHsACd$T_Vx+t{tgO@QwN=^*?$8LC=+ z6~L={adW!X-_cE|iX_OFtwK8IP-18(+n|8$YPJ{7zOf~um7`3&x(zT>;j%2XR|}im z`X1YdP*PZkq&m#s`6GA}$h!61Z;h}MOV#gx1!s)vj>c^Sng7<4JU(m}CZ~YTWX*Dt zq!D`rRM+=U2h*$-d;0-Vq%r|Sym6PBWh~#)g==(-kRrr1x;r1<=sx0Pxa~!&N_I<6 z@@B}O^P7(4$N(rfrSFQ8LN4~+GQPdV>EXDS4lNV8$)23HAwU47w_+5Rd z{VhnpJ+ciUM*@z8<}=#s9HFVNcjZm^S)8*U`#A|7;s1`^XRZOj(XrF_*Tr}jQgV+v z^^S~vx>e?@X+8A%jSRUDGlqe!9m(F0Zx}?=5Z%N-m#BFni8J$KuwhtE*6p7>dfuE!(4SM zKu?jfmcbxrOC{nq>qqE`77ueS3+HD&k*jL9xY(Qe(sOsz5N#-9YilcdAF}gdx%ts$ z9`-Woe2u8xiPA}pMPCVS@ZtC-O_0hrq)bde$Zm~%Txrq!~K>3rW?_8%^gk0YJhu0zMPYHcf2nszu6{}rwG&H1M3^EY`9VP z!7?h*eWy{%!%Y>xZ)(Nla`H&SYKgzcih@9h^pjDDm71LhH z*_&~91a+7T4Kf`GV`T4?mht6dCAZ$z*kfw{R>Du{!(5obiy`m7>ba4UI0;qZNkz!7$@PDr8+XNXkoDECda=ttRN&J!sE1$ej;DleYd=M5>)$O8*?^qe-U;>woVnd=c{BSBx8W& zG(M(QdD0zJOj%$2rt2cWmc6t}W;^Zrg~z(_Ybja`D;SEL2(iXo-R>ycz~!<&o5M0m z;|G=QGLOwtx2T%Ka`R&T6-icRxPx58>LnW&pBC zLW{jAMQPAhuz}HH?Z(ynzCR?Ob=zSJ$M{7Unahh5SIK4K$ExG(;EiUJ>5?BmkNcT_ zz#mWR{a`b)&=8c8k*c6dS&VH%qQqLTHrYVTG}6Y%kP?u zZ+^VHTJ{!4HL;qO4g{v|5njKJY6K>$#ir42a{Uc135hRO(^baoMpw8Dzr!Zc;faz$ zhW;97s`GNBdJ_?j<4suuTY&;~_kCqg=gW%Wb+sBx`VabsHIzm%oIhtuD&ZF4DRN)p z&SkaHf8jP$$q*52K_})Dx!4xZUTkn?Kay@;{wOqq7S!@L64e^c-4&$ALM2_uscpx0 ztrM9(9m499s}SEk&djxd5;Dync*cJIwEdz^&pquONSC3xbgduE{k&RqHryT0OLveG zfvxiH$C-oiFJK8lIWqRegg=tm(y#N2GzO>_aB>=; zMtch%X(T=CK2I{Zp8CbUvjV;H zNy)6tnN|U~X2UG}O}i{o0UEv{q08Yf}^9PgtINH;#-XzxX{cm!c z$lE##%F%lI-l(mDu_G_6L4>QoGV|Y>p$tZ|;cni&HK@NA^4w4+%uKR0)50;KL5#s#{nP#-d>>ifWc}Xy4 z&%kvv5ik>Oj$~%8pYKj&iXGm=_JahJ@gu+?yd7wn0;FqLf2VaA@mO?x`l677pOH_$ z3&tQ_n>cO~4AxXfE=2oX#4dDIQ%g>wThbgbK zuV)jgSZ^L{MYy8TPUf(cpw|qGDAWKIGY^Fyzan-YZG*BHxV@eTY|9{ac>*RD)m6!P z_}tWYPamaf>!x4&b%`W2idx&gh#N`TO>UAB+GXc}!`lCv7dn%zR-)GB#Lch;i~!7C zyR4&IJR=R}6Ti-~wWtS^RQ9NBdVH<|IXaw_OSLP;>Mj|Jv{GDRPjpXpRlPnhmEBlB9{gtxuXYTc}!DsR%&6N@jHU_3?Ej z!R*Ha|K`fTL^ZuwmM#fn|QP&ibU2_j-CYReEEim#Izej&w@^n5b$h1yoTdZ|IdXvd8R+p;~ zz3jRjrCC&6pyJ6}1eq_KHSiQ#$#CyHg_FB_Ka{|@xfK1B3BAjWbR-TZe!b!k8V{yS zWq|!9LaY3na|oeBTuQUt`D|+la208C>vUzt{x@jiwf7y9nD@ijvGa2xCY#V28} zPr7xC=%0e-*7U`0au<-b4Y}Xeo0AM>WywqW!D-tmKx(B5d6!HBQJ#Z#m~)pn(Z}mO z;G5$Q)2p0UThd48PWutwW!1FjE4@KNT&h+!z<;{kpOTQU$y1!E*W>RS2Mv_w*RE}T zYwP220O|8c*_7hUyc@Q;MIP{Fx{*qc`DbCv!3C%VXHX;+i(85BS;W55j4);bc{8*zrR`?{6etY z%HIi}LnJl0_yA7D5z#9W0o&HlQ#X3$uK|ExNo!D$pTJt-MVIAdVJzTj@RFBD(gJFf zE-n$dI;JwXJ5Q#1cYo8tIY7W!Vo0@|nXCV^!+!7Ud-TozP@xDC!B>h1Qo#VbffV8B z_wvUmK;_KNc>km|VRWtc?_IKY@#BNpUZC zK3p7aJiE$1DZR(bhe#~8+s8#A7MU<^*E8AXvnbnL=cTy>2KB|26*`NFD6jhyc;`jl zp>@Jkn!X=Z7Ue6A?HkziQOBN;TPr^}dTiQTR^#?hWFre%S&WPt89`+l%`1md4GPW=jn;rok9)Nu1=-1hkdtDm?J?3yL(kKvfInIg)Q#_=ggk`17XT#=w z>H909jm2F`O6m`89fNuf3NBOC$EmR80Ay?|5Tz3qWLbvX)_fg?_otlxx45SF)A?=4 z*x19}fPveaECLjIWQ|LMU$`5{uhlV44ZV35Fs0 zOy&gS6ZbUZXyUPGuK5INElxK+jpviTtv${I)Ih{=poe7r#L(N5#;}`e|$((8)l~MPK*aOaDrTg zR=)Bk!E(498<~r%_`!@AcZNJ~R`Qno;{#P9bS(eP^7m&KDj7gPlHg?$iz~=6)2e2O z00YgcTUC3#%^wO13qbQB2ga#QCfJ+D@+FoTuVJC=x)}178_I-oMs->pT4vk zaS)(A5n+%eIH%j9066?$dd!PxZDHr51Dd8FpOz``qvSb&YBBF$WjgTnplcuVzpvz4 z5I1N#xSESoOlErz6w>u{BRe}=Wiqq!{Q#alh+X=?hA=_@3sevd!Jkr$;ZcP%4sWn7n*%`Qy=i%}AXsI*13TC0dIE5jqUptD(^TjB@$68P%p^ z-u->`vp=Xzd8YU4ukZAfJ0ky_Re$K45&YY1g()wel#Ks8YAVdb`c$36HmD;2@;Yu% zxpLU(ZL54J&0p>Q_qs!v1Ancn+y;btRJ$GpC}r9MQBCtuaTr?dK(JqJHJ5{YV8e^f zkNKC&@#iHDgIn&+P{5;cEJy?QCl{1sffw8TGB_Y$^84%k8AETUvKu4sVvAb!|7hf& zxBqhmfwkgaar~cO;lKZdRzv%br2qO?(EQ&{&VRmz(D4cRAEEwP3tYci4F)~`7Q$ak z+Uou5HUGLxEh~^y&78eV-9Il4Rn7> z-IR|DDF0bM1h3kh5KZ0q|3@GD%%g)W+o$Q0H^A`($kJTSNBWTm<9Ui8o?w3c-En6$ zJHOAiy6b{kPrd^+dl{s7azeVH<3i^&v+bG+XF3uYG(R=6p#a2L8Qd~UrYS?H2@jM ze?1I628neWG8(`LlYff% zN5crL-DmMy4}$=e;Y_)qI2Bd9;FX*A)k}WAEk*+|Jey(uA>^>wjmo} zK!P3Y^+3d?U;E-+PZa6$neo%(!&jD%|6_HV|Dn$WXeTgWoBp#Jf>fgq*d2dwGqANV z*}>29*B1M)Kb?PCV*d5O|Fr~WxgAJofqGsdIB)ScRd4@`XhtGt&W&#Uo4>)+$(iTp|S>ws_1(ef&Z5`xZbZr=l`h ztaq9!)~5deq{wSIy+Hxq2a{Y4gpZ*5S;v-M1Vj#{0qrkgyblxs>Kj3gfE6l*fhlmk z=4))WSHL3WEssLCeK36X8}dzGL64Eww{Gy_a27fuFxl;54`7@yhz@6pdslG+vxwq71@-vP zJGA`~h7=SKM*n{aeRmp{3$b9|JO%24pxuQ1HEnevO zZ2A;GKz<)`Q{nyOrHse>=XW@E-u3w(l3RK9-;!(nmofyoKm+UfFJ+)K0Nd+dx?vQ8 z|7R!uOBvSS{}{J_uK7Pp{2y8TQIG$l7yoRE|0l9==>F&X;A9c`e`S>a#}fZ{yN49HqI6dbJ6Ioox7A-B zrVpxHM(IA*+PR&}4SdU|q{}D!mvsRiDa9?T4@1E9Gb)Jp?(dV@@0=6c1Z6UFgtZv= z-y`B!>GsGz-9X2Bi#-Ul0^jLBr_!o;FrfF$Io%V#w&T%*vakHO5`T*!pMwumcF)>= zI8Df_t+XkPPfl>PeO8#x_wOtDB&+nGX5RlM5$chIq_g^1!ew?4xHz`rw!oPBTM8qq zr{X#|dFMLWBWe+h2DQx5{M*_+YFyvxL3tma;D6V0%7m%?%=v+A2v@wG%t6Su6ejqW zgBxpsA)f*c>=WWxqUyp$HRb(x&VS#%x>@_@Spc=JI?G_e#C1frx;e)B9LLW3>TVNKeI6GJkxF78H z{MnsfFnVp?g-WqU_F`dmI&104BpCf)pVktF7^A*`q(2c) z-Y3mMXFb0}`nR88ZPQu%KU@v})z5!s^8fXE{~KS!IfF zW#S)UQz9(r>On1E9f=yhn^$ID7CM`k+P*3fYS|pFNOTTlZDh6@TQpXLh_q}BAI2LT z%>DWq{~HrhY3lh2GWTj}G>%xyYeRaG;t%zd0XJS!>aU{KlEc6)D|Rj$xyl=1MYe_4 zZevIM$p@~Mb4$)ikm5#rn|<1SxgmpDHB)po8f>~d?r&}Icbc+fE_dF!+g-O@DJfulP_bUsuYLXpnP0h}v{(4O zM)R(oVR~I@YsshbkvW5RWj|4mr`OVPlMW`|`h+oGX&cl*2D*sz2frR}+}{bfUzR-K z`DFZ~4hu9@N1|09TLj?|%7!>??)f8|z-tXEeB@Z5S*T+5 z8L3BO`Tarvgba0G#bC;FEFyBhxrIn<>*F>4b2;veH(oR4)Dsswnum+|heX~dPCZ(s zLNyi>oBQR$HJ|Rz3jKs-HxGU{KeQanwhoScni;xwe2AdiH{&tjZ#wyH5$T;VZ9X)q zs-=4K?qVaTn2z@z%xB_a@3Cj9dGA#aD~O?2wvD!tHua#mtKwZ`Fs_QeZFm2!bG?cs zEtLFZ)A;mw2Xva-BvLh>#og{SKRMrOSoo9TA1QsQ`vs)5xovg(dHTn5?(N|eK@F^- zG(r2zd+RgpX~Q2yr>cm1C9~WvOIU_SE$9N`|BJfc?_ZzaaRwrk4RaZ(_Ff4~)_?N) z(eWFt)Z4A3E9{(A``yO|q1^S`7zkhR`CRP#l_M%xZT>^N?RQKSDml9U6xa>vU$oXb!INsa zIl9Zpl8d%`AUa5mYjQ~C6K!yI4htuaAio`I=3UOXamw0GrWe)Ya@7*qiu60{q0hK; zda)A=t=QuwlBJ4IzpX6uF#K)VO1we3!PR$lzpjgRka6j=N@exW@L!aJOt({mIfg?F zr<)N}r3LsFqNTRQMS*%MjMC$3Wf-phpCTM=aPDS}RM4y<@;!;mz6VW+Rw ze>suY_+ypYPyC21@x+g!)j^Kef~G%dE%sGLmTcX2%ePzRT~G85x0;UoHmZ1g%*;82 zb2sg=0?rrkxXf+l9ueK3o};>HvWlE z?jQ0d7~xtDGn!nz_Aj_oOH#*N4$r$S^Z9f|H{)M}R}?5}3k$tSjxKL;)NhjcCjOPb zakzx?*M~$tYBI2!ovQj&adHJs>oK{30-?iygn@4 zlC1M@q}84TDx{t&EzMfq!fc;9ah6UX5{r9SZOiRmO)A%vPE&K!M>+v0vEg*#?H2f~ zf1LwQc)FKlm*cIyk zUm2}Mgg0)a)r+qv+5Coh+*vzAB318#XbtCG?JrJ~&X9@<4zD&)DFI0s?2A@~J;g@z zF)ECZ4Xgs|dyq^9TqxW|tx%D5jMv&VP%BS2&0lXHzsA3nYBIelU2do=o)Mnd|Fkda zQSR)!JsYwC+x_cP%SY4X_~iMFQ?JX^nx)6$*Zc+ybsLV;&3g7;Lf@T|#Y_=+^#n>J zXD~?JE_YUOi1@Eve-~s2BWB!vvVDQ{@V+&_E;Cbz=g259`EzrusZ=&g^Cw?%OxKI? zq6bg!IU$$Bl5Vq0Z-)|vKZ)JiHn0Q>w+I)pk&X*rQwtNz-FZJ~9?4C&#`awLCvivQ` z*=P^7V|;h_2Q+zR#w)dG+_N6OW9z=n#n_$(e)6j2J3UIsnB=MZh7*JxzM8#U?44TA zSjTVSqNnGMsI9KUkM-u97V1f3`#+-IBzrF0n)TT93L2XZ6jgdQdYe9&QR|9qe!`U$ z&}Uz~r+k}^>J7hn|34gg_&Hp#KzGyfE!CZ4icdoC#h( zsk(9t2pwKz+;494YNX!t6s?AZqMyIR6HOiRVe|v5D1Z+%U4NamOf{I~Mz@RIu{dqxcN*o00#k ztM3eJ>R-AIO_Yu_r3)$|y+{j1x*$bBMWjjZy@ZwoMVbhxsPv*V5$RHs5Rl$MdJDZn zLJxtE-2Bfu_r3SLdG?2V+RsjA_RN~K<~IXtTgl$GP?Q|a+`ED}o9^bwNEALB=m&M- z@#E-Wqhf*C>_fSWaZ4AFR&>w?ZNDP(;ojfBVpmSlBOSt0gMcHo&{uQumlQ_37!IZ+ z%mrZ+ZG`mp06X?==+?;|MGqx;x`jECc-msH|N4GjZy!RUe;*~)JK|6MF;$#*53*E` zVff_(EP?VAXDCF%sGc|+mS>oqPGr^jtgf4dC-JJO5u7k@QsK0=P0IOa^)-+%&~o!X zRtFvc@C#tdy#7s+u@#a5tf%3W{7}AW@*i@Z;MTisS?R$lvgwn2bI~-I67&Y#Beh z$$WT<%>)tG6^N=1Fj|bt9Fk7bNI)Lh)a^C9Vg9SV!X!o0#ZgAjf*haYE zPFQ_7JVlwM8C)FrY;Cc`|@97n-!KO zUDPtic4uueq|ue6P#~BILldjkn%SQ*TJ0H0FCvqG)exr(%IpC-}jff-v(5?--T!K!mUbu+yl&#yJR(%#m`UOAl z?dBt?=p{?dBQWx0+DOfur|H|nm2XB5{9?Sy^usb$*1ax&)L%xS#7huh^a0_+4DkFG zCQaxrWF!FJ2P{S&_wCNQjB;#U)>W0)Iw%r;4k{zR7l6XOF-dTgH4YwbdxRF- zoVVWm^L6on9L8;s`gngXL6sAWhm4ws>;ND}C`1U#8KEO|_1UsnMLN zxOTI$*m+^gXaq{FO{7aCEoZ6@KvNWR@;wej&ox3W&+$qdL?u$creO^(XwZjVYo2^x z=qPJj{2?IjeOw%WVWtYN7a6O&%KFMlaV!t2KHPzt1SBSBUz`yshc=U@fq@Azf1#sg zlOh8#53KyoG8YhHNug>p943A%(c}TfD!BO}Dz${8gPGcfwRmemiCp5z-{_Ro!QB1m zmDE8#!MC|;oDf3&ex+^O5YII=Y+pw}tauKPDcHTO2q$LDvl)Op9)64@`fiQ2?5A9| z86P)>z_A_qD&qKwy+0M!gM3>zf*UlazEu<-SD>G=P~ZFOJUE81dvF*1Q_5|!TTJMp zjBqmW&C)%|nokM6)~(nmAhZUTy?@cTWO4dl!q)E(frf?gX__xn4$&1W=BC5juW{4C%JP2V?jy=QW_J1f~iXnlw0YwDW!rX%J?I`ThN|#>VGEZ%7a9#0hh1 zjsVhzf!GecC9XFXKRQD%gONm`(^68NCy4~UH-ZDx9=P>yPZXw3^huSYk5<$^NiOAY z6hn^Z&N~~~Pu#X{pIfF$`w|+ab!DQ50jyjg5iR)$;A4VK%m7g=deaiK~uPR_*XTCDj zI0m2V3|WDFco(JNp2&#vH0cIq1~AMJypl25H1_mAq^X*aU+zC!HaE6*rAy6Hp428m zlSNcp3_UEK&T6(|AlQU7288sJf_A4y^o}bWNV*YP47_$klX!sS1T4#Y%>?2Oow6A^ zND6dTpF9Pzll|e*Ao%gI#l+rl)dP>_6P>|>Fytv(Z!>#4eO$&e-{(Rp{(D}JJXrrY zZDA>7b+QUcPd=i|NpruVl zj`u%n!gLUNmp@6f9Le7OPTwQ#qBtO|S_=)@hPq5m^g4jXGvN;c4bZfLH90(A*LL@R z*~#>Q(&Z}fY4dA37;zc@4O?$A`z(-^Z0FM zPtN{+mK&Q3A#Raeqh~U0|Llk_wdAj=!17O<%S)`x5S!a!`;M1%>Q)YJ{?;u%H$`N5PCUV)2R+GMG}$(m!r1qB3r z`zFh+fv;L3GaIC&Na!X*YL1#gA^H@SeA#vc!l3p#MXee>IJU#$!A@6~`^*5Cdg8av zU2sjk5rR{yb!TryB`_5fv(eHWu3v{9KY-on!Gq?*m9bluMqT9*;V+x7J_(;JlsC`q zdw_GTW3TamoYaH53GAn$ZlSn8J@@)^^H!lcs~ubB5(bDc$l>@Ai{PJ5-7GFHKghxO zei`%9tf07ed_(0@FRs@7&vR?ldi>$^oz%g8WMEkES&7?{kWlv2DAYdpCn*6%{;?g% zfeYpAvwjLma>mz6(ZW75ii@nqfkCTuI4Cqncc}zF=#B(v` z+pNYCPAZyI7^{s!rdh<+zwFfR)*3Gd)4uXS$ip!%Clfupm$&ol9XK(J$zi%hCrMC) zKf|%`DARCV)y?b=>-acj4^D>MC!77NZ;-~2z4mr^ES8a=p-Nr3#SDi{XUA#ha+|d}eeLc=(jRWA=6FH!_t^&1OMafl!u{RIe?0pOS#< zGJpR3as3wHzc=RA^dGMF*5JN17LB{&b#<%xPC!a%`cJy>?@v>Ysa`67g%Ngq9*EeK zn=Hw1v)#kl#q9bl5VfYMrJI9@EKa5__p%R{1QZXSAtP|_{AY%T1B_SiWeR}P!)wf8 z5}-Efgj(Yx!VkK=N%&vl28rqgj<+)qJkxE76j0ZK6rn3;N5sfuQZudh%x^c6Qk{K7 zq+p$$iQW0#jltky-l@qb6@RGTw)v z&8{hC(hW_&AjhkjZxm)H>jo-{V93X&IZPmzICJOR?lHe-J_t27-G*6aRWR=%mto}H&T>|QDO~8K%oTR!ry|Q?D)60i`e$2NwDSt!!3wJ~FS!7Vhm2wH` zSDH(Z9a;zyU5oNK#9CeYW1ls`EA2d;zQzOvb6a#REZtcH2;TTW}fakPVeBYwl(1PaQDQ$j(J!OjA~>94qhh zW&98O4IK_8mF+M24z{xq-fqH}x;d0sBjWL4cq;3@xWw*d)en&6Qg?Q=@vqR?l0^(a z2TZ_+#@gw|X7ed?x8Ub}mqxqHp(jNtXrJ%1cs@1D>Q=@0o4*I3v=5E{KdeOO6~+*; zec_cXmlXuv5(jN~r`_Ly36G{45nR75!u-QcRWY=REc2J9f5$>Up>}9XjzW}g)$Tyc z-ZJe@2P`JV`U^q!Ygdy~4Q`s=8mA4y-2W>cG~nkpQ|5MQ4K2=i0Z`>;`%Kz4Hup%# zk~M;K5aCme>pzD8-P!ZDNUf>a$*SkBq%LGTJ3FVoua~E@J`eg9qQ6%7)&sIUOj_=E zMb_PZMf>Xfc#G6vvJChvYEkVy-()1G`Rl;PlZ@3>G3=yTLQs5gKZfm89BajWLpkte zth$RvtWFrTVVj3_i6;~}*p1jFBk!Lm;3l$I`CiR14w#aYv!_Z=#{ zB;>a@Sb5~95DguLv_gb_yo(hAE`GS&U&>KzgOHr=BCf3yztrTHzfEe0aNaCjptejxa*k3_N@b366xz^JngH@rcvz4|pu{`eK=$2F$Y`p>udsHb17V6w$Z%M7`#L$(h zlC2{>&IdjkhdM?k3Fi4N}!(o&^uwI*@~K^`^Y%&{y2F8 zI08j^lPPQw?%o~DvJPEq)~i`p*pPati2PrX?Md;)6m_NqvUoWUXzKydP0A3?jR0yl z+4u0>|FBEI_n^ZS-S=;Y%DJF=W0SefG-x~D=Pv1Gh~e6(%#@!CIIV+B*M5OPtrH~+ zTw%nGK6eoB)>9VRme<+WE7Tpxm*@ZSGFNifMu|oWLnz5>NL??aCO&^sI}iBc^l~#l zS(fBpv$q)tLt>Gn{zW(CtF*KtHt>d&0VWSTmnGl}@C4!OKRmuags@abz0NsUQA39x zw^u&G_`bmowQ?xRYW!hLg;TU4z=Pqy+>c_B$&B6X4_k4?(h%fPbeP`-YfHJdn7FmV z`X{Ju8n0hyJ!T1tz^M@`ya^yB=vii^=HBr-aT+|JiG{E?!Fos)o8hL}_&?0eW?#Ak z=!pEnNXfy^p>F;Lq>&)mu6lOBYN>+8^J^@lGGvOxG9l%6(xR6nGCEz!!d z8%D^Tiq5R10-$W0@+aYIgL-uTPe03iBM&rcME1N1UqA<#6NXGxjv&1TPG$vS8Ti)8 zPxGk~k$54)%W9zm87C1r+-2a8HVg2*=j%~jg7E%wh8`ND-rvRVN9*B<3Io2=XSuVcjI|MpEdgUm%1VPnyQj)=xp< zRK8(56Um3G>7NMkM(ioWQLxgU7vvAN7{K+1reE<($;Jc+SNk4&%V6|? zgtfvsH4&+Bx!qA>E{+LYz$5*G$JP=o?V(3%fySdUFwWfR>HS@TPv=QFsrI41Hx|~p zxwnDhg4O=*He`z_uaJ#sYcND!`mYQ0wqZ8ukqBH{%yo)M4$`P&Uu13cMV}yGAFm7Z z(NjCApA&&pR13=o0VvNBP-EYDVoUjAwCEQJ0_XR9r?(Y*v6Iyf z_}`4JLfa0HGit#VrQ&naB(qQqa;*4z7%!hvEc^-IYEE&c)|w)#JI?shws9HGQhr0q z+5JiNFFiA47Rgb%)1)1yfjK1*k_(~17Z(?qqW4bro|2MD%bgx^^6r{HiGkJHukXeM z(=J|Mkc^}^n6xZ9R~5{^L>j;`CR+7&_Bt^NN@^suTWsMOS_oC_8clV7dQHN7`)_v7 zy4u&G9a@Rs9+QJT&T$Wv7doUMH>S3*ETIzI5`0ynn^>~=Cd2b)pUn=w@{m}qFk5t$ zlJU;LApwb5gN7232bJ8pbOR&4-8H%R4~V5j&l76q>PfD&%azyDJH!ga1>l{48{ZZ5 z1tOL1wswO#=Do|{H8y5SDkY2x@5qgMG9X|KL{_x(26>*zbN)@0htpR}lY zMD_keAb@Qs{e3NK1oRp4r$T5JSSk*acn z6{#h^R$zG-`J73Po+4yQ0Xh{x*+(8{Rs(RUyTu_VST3?G`}qsDP~;lN{p|bZUj<8Y z!@+xVK$S*pQ88+k8|*S<>ofGsxn7l4&nmIqM=QrucP=>z$EPdZ@bL{I-><9dlXj(| z^D?Oeo4>r%yV`h-Z-FZEBvbLyrDMB6`j-@arCg=PFDX>}R|a(^O421oM;xGJ*jvRF zE5A71k@WhQi%mVtQe!kWBJ0nnF?*u*<&+KZ^iW1whI-QY7tBRsl}hu6aAb;sr9}1q ze44~o$G4QQepQCdb(u*1^mE8LaIx3bNn`*0cb@hb!#BZcS>%9XS7E?QDxO2PSEBTL z?!RfoNRO05xkm>{eE(kDwwdmJF%GAWPiAH1rzD5a1Mhvd22fEgzRD}SBS&}cNoPz} zAmkcU=ZOyQP`!S@w*dTkC3+1F7JS|2Kz5lQZh)Ruf;n6g3~f|oxCP|%<%zmij$&i) z$HdxzZ$Q-MQq@Bbp+6vh2cYu1eZ8Y4Y}v4X`W)eN$;$l_ycieJo4^#+6W$Y3Ktd(-u=V z3*unXa#V}k+d4LaiTg)_8u0EaaNHEHmOqC;Ja@){49DMxM>T`II zcKP{FRz2O%j<=tBRaMNnd)RH-@!j?pyWUK7ZH2RznI~ac)3otJAo}B@k@fD;DQ=mA zWZ_7f4mUFZxT)_*>~aiWFe8(> z67L>XW!C}RK-(>}N)ek!1bKy(>TF(2LQ_(OuV}7zju5&8qe8(^1E9w>Pji~XtmccD zY)7ON{DqsB?X7UpQ>ll>HdgPzegwVgblp4EBU)S3ls(}c#ouX+QDRI9-9SGfY=~=} zr`9{@yGa;_`W$4Fz<+x3oRaOosU}Tpm{kMk}IYQEJ zgr$X~*NoP))hr?`jvLQEZcO6d(Fd<_RSfa}%+ZC*3GxEFxEbH$_63rI1^i&Te7rZV zv6o(LdT%Jn;z|RUby54m(c2fB_}us^VZ^ke>Bfe`JJJik=h7j)#rDF1^YZfYRrCu7 zc)S?TKQ6+5)jlnyj#1IOK;pxJgG$~I+|Ul?eytYVzy+5k_BHUwGo$*V(W1S!GL*?eGqYht_F^JG zhxxA~%9vB$uHy(?#l_yl@$C2Y8ugy=?C%$KBHkJ=>*>6zROt={ETBK?y?m_%-WoJ$4KxTA|I3;@aR>zF| zAwHP4^I)vYw>_uS8U0nD%}?FAPaQ>e0J63;fPJy&Rg=4)@3Co69zf+oS0mgiUNAAY z6Z04##!qso6qb#J->7Pn+eE|BxC^VJQ>A1m?XbAV?7**qiL;aSvj=z2p2eK0)tVVe zsZxFL9V_rDqpZd-{Sk`fUe_JfHHXq`78{w3Ila9AujT36Y)6Sif?(odN|9-@R8dxVru zG?XY8C5!fTnyz`=r>=+it&BUg?QGg0cSxy%$biHf4U}uIlR`=&uBtPH#Zu{?9HGwC zE@{q<@#S2e9*VB!m3BgvwEs48Mpv%{u=8XL;IJHI&X-MM3cJ_Xe+fJaCh`5wK4-KgB@mP_?**stqXdp`7nOKnD+4xNX;g}2xEjMW6ZP*$*CQIW@AdG=!gV{5cd5i%~X%-salens9I={gYT=U79}W15vEy}re$=PuorRX?c*EM zB60h?T9gb=cxe=RqvCu8O<~)KA?3UbALcI}eFf?SFRYBt8H=Oenayx=wCoI5{N^xO zh<3&3{0inbnq^MTj+2;t0l=O98 zhgQ3zj=OUP?Y9fL4MXpwzf7tvmXeeNJdb}lY$QUv zh?`~rD9wYefYR_$W{W5Tk))Zipk&)=JVFY0Ua8njn8rj}fQ-hM4H$`{z`yU4d z1(}-naB5}=;s-^dazsB;~ZyGvQ!dnL>I`qw6MIu{rD!88Cb`^T~W20k}B$H#**$7PZ{^gbt( z?{7(YnWfe1_@nG;!@|69NlIaR*K*Rvqv@~zkX#`NP1ADo9%w3(k>;^jD?-a z)lDyy=T*RwZUu#>Hz8w^?9Elab{r264+4QWwv+o2)sm@71-QSrw-+BDpAs7x6{5`h z^kEGW$tPPPNZ^%jr1+87=B9fWo9^wkK;vKrxDx{LzxLRi4z~B8wrz&js?|xrqKrcy zRz8WftfdDAC8D-(p15B4vYCr4veui)2PQZVLlUT^Z-w5yQ+AhLGt7tiOVh}xQ`DPu zl^s5~h35zUyw-g&06Bu?xQ=}b zxVCDQ-15dY3!d*3jc*n`TX<9P-mK!Ba^SrQ^nGm-o?yhFV&V5D3}F zhobjI4UCLVPfjM~CE07561>T#!dQ^;O;oQEr66C(AcYK&DxF?oju;F%;LYc<%(Ss4 zbG>A=a*P-CqGBBP4P#2~rEkid{7tEcJ&`FeVIP_gdCj5^gQ@*VSE$hUPVH&hSCt^G zR3zrj*oSvn94GVwwy%nW0gLu$HMUlMNYiS-O;`4Za@<(itz0a*<6DL1rxpjMZf@y+ ztGNrmSllnAn4_->7>yJL{41#C@vUWnZx@@e!y*(iE7|&ZgNh7Ygcqpt;LMBs8B}R) ztrx@>r~T(nJHJAKE|*O~>?|A#8i~YE;RE7#%{-YkOF-se)$aH!pnV%e_|vGu#Tzgs zDb5a4_q&o*MCKEr;c7rG%aP30%LV2EYwP*31t@fI5LF+bSvsZqglwP!%E5oNQt0jU z`1ttk>(?mvf3pJOdNMOJN0cN(uRct`jjX@D1t_Dqj3Jlgxbz}k<4E`a?qmN|MDUB# z!KZ{5kCwPZA3PWk-2?5s4bXo6&at)!xjW&0L(=PJ-4=JyCTGw#x1T#tpzChE7ys;s z^L|d%8wj3paKgO@?|Ts3to`VD{N`mu!tOw7mMBl9hz#p3qhe%f;E$DH^PRm?J+_Z* zJ}TD+ZYEkM;SA3v=lyCih->tOA@vfh;KarC?R$kcSg+qhY1e*Df98H5@r*@8>?q^% zKJ2h5j9$il=g_F0RWI`T^6hBDHbCq#2DpKcf8;J{>?LVfB5zba`mSOm#I*3bS;=vw z>4{Bze#&D%6O(Yua8k9gvo3$z)H*a&8=`I(82G!Y>L$``hHMfag{F#~Pe=;CUI^|p z3jN9p5@8PPW(jKNX<1yv_wI{sv3hlZ$ z-$iELUULc~UqOLz<`I?8SgJUTPQfX^3s!(;PLPH=OuO*>&QO7?yCSUNRcg*HCXUh*IJ9j;`SZ;Zj3A<>b!&zRG~nhYpbc zD#kx$mv-qtR*rREj<{z09755{MK;lA!b|-^z~CANx80N;+{yO%+k0Z z3WkS=lQ8*yLM;-gt*u@8iuA3E>cxw>Phb3O>sVQzkQwf_n_s1;r?Qhf)6R6=WPqsO zL+|V)@KTy6#m$mD&hD!FpVn)dfS1(nW44LBTBBsHJZZikuMPObRS8GFDG*%M_*$Je zKQUPWoSxa94fPyJn)9nzeiVGM^_RD>iEMA3u~STNeJ`Kg%fVI3T|Ln9L#a=v_*l{- z()6EptY^gE>K0Dq>HDapagLY(nP;rw2xN-n82d0zd|w}*koV~>LiTT4FV;NeC(qHg zG$)EnHT({HXC?ZL34YML%?6yTf zrfPZ2XOUUcdkno^x_X|RR}@@$;afVZw&t2$kGp@C-YR{dA#X)HTg2t}XP1E?bz}mi zDk(WU^Vd{Y;2Atjo1dw=y4vioFPXYJ*El@2^i0D1)b`ZR;@d9tQJ;Co9BpRI$1E{! z{jat@ubTfhYXpa6o^>a&IKYwwtYSYR#&ju8%>u~q)E}ZEJ~L8ZJusCf|D*i50B}!0 zxlMpPJKQl0H)yV3Ix`KlQ)p=*ne9}TMeASnu(iaJW)LT$R`HyFP)K29FEc%0=H#eFm=@(V7%o}eW0G_2e0 z6NPx3HRpNKW}7F|QNH}rmKh*rWxq!kz|=EJeqjvCa|RR{kqz5YrX4CRP?9oQJczA3 zTJ#IErB`53_U>*AGZ>i6GwJQac$;QSWuY@Eb|yg)F;rJ%2@|a)Tm3~R9KZK&^z6Ho+s##l>kLTA>X%y?a`kwiI?K4 zkTr`JpmTLUmjKF>OrnzYmziufPM$S)9*HkMaxe4Yr_fw;|A*>jf7_&gQ?idenjg5k zrf+5ju%|O5Gl=m%Z3xK@6 zvbI)MUS3{NfjKOcA42k`O{2!j9oK5FI2TSLb9WZ*=^0YSy+RYj@qYOUv4nwxWgbFXRM4Fs^g%>GKA7Qy`LkJbVc$*wlu6V}?h+3~d5 zbh25VRUi60doC+&7L7_9tg)q3{;(wWlXqW_6H-sJMR}M+xD<3YIlA{|QzjbGemi`; zcRXYT&c>|!kr>s_c-_fvFAECH+^j83r2Q+7WxF=zr?(n3V9l=)>W6sxv~`vyzx+NE z-Xpl#ltkRQLH!C52H(n#?Jaw7*r6fx!6Ue}mMP>(k%n;LYutl5-h%=wVJ0G!$O`Bk z7!bQBSy@^6<6HB$va+(ZdDwYVQ|~((fsb)R{RRe)8aUX3fVaoy=gmlg(Aaordio|8 zPVkjQGWuy(r%u&o?)I;DxL?|T47dg(8Tw)4FBmt6IQ$%uOs(HyEnVVk zf)CooX~4F>CAn^Ja{eK>nY>O@zI~f=o+I+4=sP`G5L1)!rsPuhD#I~|FcR3Zs(SA{ zzFCaK$XI1%uaFNN7gdg-t|zysdk1tKgZ<&?IM9nK}LP^B@yhKR*ImzTkkd{G_f3vZ=r08Ge^|_UwsYO0Y(v zF4|))tvBzxPCQJz>~;m}N-^&zFHo7bd99v#q0NTKUXp*}DaZZ2!cvb&-wb# zzUzMxd`uDGaoXe{90{UYZe>v8rvik8hjXlM$d64T-MqcsJ%5#zfl2LMCML`bu?Y!@ ziSTfFQXHR{c&@JAIyH6HRRjRIxNrbjW{ctH73pJKXtkz4tb=)jJh6bJA}jV0b_`%op|iedNCZ2(zQCjD zQujeG>6&^g$LX@pYTH=DZhL}oa`Zc_;)%?}3+Ed^+^f{6W+2mQl-g00?JvVGA3gx= z{h89E^aBE9f&;lPKfvM2=h^s{x3|oKH!&FMHZl_8>;XT?Yg?@av(OolH8dyy6)1r} zQ=>6%aW>XRt}+LzK5vL_65)azLcIYqI>GgW=^?yubX$O6NXpM4ojVl>cQo~b`N10v zs7jrR0}5ptseX9zM?Yf~;lm6^t#43Xy*o{FN`=o4P_)F|mrD=vD$unX$OK04Dql!0 z5)&%kyW+W8Cd2Gq+-7YY+t}?@naJ4x6T$ubC(}!R;evLdeCGsBc=6sAz*6rC-gC%d zG{P2*Mq@GaA|hg5?(RP;N=twKqCCOF;lIbmrlzL4yB{$TZ5zKAeE)9m`t$U?T_+^k|rhj7FJlh>?<0;zv$S_g_ian7gFhJl>aMw+mCjTa)=|y4(KVBywOR{ zOYecvJ=lsyftJmAOfQ^brA3gpX6^cL_T{@Sn(Q`-8?u8a_jLR1V-=e^DnplE$;_|h zKYsosKT!O~tW3jXkB^?bCKU!Lz{sdPiW#kNqiO0if3JUKX22cV#m&uEPEIcN8p1_I zdFaD@A8F`aYI7{hw+@Ti0YYOCh=!}h$9cd~6=M}^+*}@ju)bbi-NR_UlWDV)Vv|te zj#~b3>g02VuWM1G_3^=^rKNpdU0p3GXn*^bnvwVH;$n7s+Re?)8XjU|XgJW{-#>CN zt2MIlHYz{mOQK5L9$#Dkmn@rp%z9B92a*Vt zCgC5#cuwI;zrC;JrOa>_+4_Z}#Bm>PUJc~;3iW9b?{tewq>W}$ht(!DD>W^qtux}v zev(qFMpjU<2{?#|E5Yy%0_kwXVmnvkn8#egULXOwnog?L(TiJ@+) z3L&^E?gH$O4c*v1=%3#E7_>g2xjQF&n+IK98`|_&DgJr;u3%MwT1HArN?F<7K&E_| zsF?ciisIs8@LontOw8A>UrCdoNJ`3PWYDEN84)!#1AI9>mHBe6K*ITJ-6Frj34Iil zHG{kb3?z%c$vKk##_sHd%tD01|2gHF=d~V1-Y)@yau*{qzlJt6|GT^ZgOrj8c)0^; zhD!jaliy~MpR20%4|dp-JI>#F9Z0C3lwEwc8Ebw;$yGHa(GjQQC=EA&g#i9dB0I?f zIG^bMPDM(f8cSG&CZQ%P{ZY=+% z!{OnfqqO410!=&qzXgdm{H~mmQ~-4|0CSLwiwkx3DfG=rKDond(hym`9o!2a9|@cT zm`M4Hsnn#E74UCHno^y3l_Yz)(xeg?|NLJuQ=Lin4o51H@oTR`w5ZSDOaSSlr){KF JuJP*4{{aH?T%`a2 literal 0 HcmV?d00001 diff --git a/buildPRM.m b/buildPRM.m new file mode 100644 index 0000000..1864917 --- /dev/null +++ b/buildPRM.m @@ -0,0 +1,204 @@ +function [nbNode, obstacle, points] = buildPRM() + + addpath("C:/motion_planning"); + %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +%function [x, y] = buildPRM() +% +% Task: Implement a code that creates a map and the finds a path between +% a given start point and a goal point (in C-space) while avoiding collisions + +% Inputs: q1 random variable +% q2 random variable +% +% Outputs: JTee +% +% +% +% +% +% Yanis DIALLO (yanis.diallo@ecam.fr) +% 30/11/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + clc + close all + S = [2, 0]; + G = [-2, 0]; + [Sq1, Sq2] = MyIK(2,1,S(1),S(2)); %-28.995 104.48 + [Gq1, Gq2] = MyIK(2,1,G(1),G(2)); %151.04 104.48 + points = [Sq1 Sq2 S(1) S(2)]'; + obstacle = []; + randVmin = -180; + randVmax = 180; + L1 = 2; + L2 = 1; + GapValue = 10; + X_space = [S(1) G(1)]; + Y_space = [S(2) G(2)]; + + %DH Parameters +## d = [0, 0]; +## a = [L1, L2]; +## alpha = [0, 0]; +## jointNumber = 1; +## %End effector position +## Bmatrix = [0; 0; 0; 1]; + + %____________Generation des 10 points_________ + n=columns(points); + WhileCond = 12; + while n= L1 || y <= -L1 || (x>=-L2 && x<=L2 && y>=-L2 && y<=L2)) + + n=columns(points); + + %Store q1 q2 x y values + + + + if n==WhileCond-1 + figure 1 + hold on + text(Gq1, Gq2, 'G', 'FontSize', 20); + + + figure 2 + hold on + text(G(1), G(2), 'G', 'FontSize', 20); + + q1 = Gq1; + q2 = Gq2; + x = G(1); + y = G(2); + + points = [points [q1;q2;x;y]]; + + obstacle(n+1,n+1) = NaN; + elseif n==1 + figure 1 + hold on + text(Sq1, Sq2, 'S', 'FontSize', 20); + text(q1, q2, int2str(n), 'FontSize', 20); + + + figure 2 + hold on + text(S(1), S(2), 'S', 'FontSize', 20); + + obstacle(n,n) = NaN; + obstacle(n+1,n+1) = NaN; + + points = [points [q1;q2;x;y]]; + elseif n q1_stored + gap = -GapValue; + else + gap = GapValue; + endif + + + %getting the sample points + for g=q1:gap:q1_stored + Q1test = g; + Q2test = Q2(g); + + %Is the end effector colliding with obstacle + [Xtest, Ytest]=MyFK(L1,L2,Q1test,Q2test); + + %filling the obstacle matrix + if obstacle(j, n) !=NaN && (Ytest >= L1 || Ytest <= -L1 || (Xtest>=-L2 && Xtest<=L2 && Ytest>=-L2 && Ytest<=L2)) %verifie les obstacles + obstacle(j,n) = NaN; + obstacle(n,j) = NaN; + + %{ + X_space = [X_space Xtest]; + Y_space = [Y_space Ytest]; + %} + endif + + endfor + + if obstacle(j, n)==0 && n!=j + obstacle(j,n) = sqrt( (points(1,j)-points(1,n))^2 + (points(2,j)-points(2,n))^2); + obstacle(n,j) = sqrt( (points(1,j)-points(1,n))^2 + (points(2,j)-points(2,n))^2); + Xplot = [q1, q1_stored]; + Yplot = [q2, q2_stored]; + figure 1 + plot(Xplot, Yplot, 'Color', 'b') + drawnow + endif + + endif + + endfor + + endif + endwhile + nbNode = WhileCond-2; + + %points + %{ + figure 2 + axis([-3 3 -3 3]); + hold all + for i=1:columns(X_space) + if i==1 + text(X_space(i), Y_space(i), 'S', 'FontSize', 20); + elseif i==2 + text(X_space(i), Y_space(i), 'G', 'FontSize', 20); + else + text(X_space(i), Y_space(i), '*', 'FontSize', 20); + endif + %drawnow + endfor + + figure 2 + hold all + xL = 3*cos(0:0.01*pi:2*pi); + yL = 3*sin(0:0.01*pi:2*pi); + cL = [0 0 0]; + plot(xL,yL,cL); + + x = cos(0:0.01*pi:2*pi); + y = sin(0:0.01*pi:2*pi); + c = [0 0 0]; + plot(x,y,c); + + DrawObstacles + %} +endfunction diff --git a/buildRRT.m b/buildRRT.m new file mode 100644 index 0000000..4d8c26b --- /dev/null +++ b/buildRRT.m @@ -0,0 +1,166 @@ +function [nbNode, obstacle, points] = buildRRT() + clc + close all + + S = [2, 0]; + G = [-2, 0]; + [Sq1, Sq2] = MyIK(2,1,S(1),S(2)); %-28.995 104.48 + [Gq1, Gq2] = MyIK(2,1,G(1),G(2)); %151.04 104.48 + randVmin = -180; + randVmax = 180; + L1 = 2; + L2 = 1; + + q1_1st = randVmin + (randVmax - randVmin)* rand(); + q2_1st = randVmin + (randVmax - randVmin)* rand(); + + + [x, y]=MyFK(L1,L2,q1_1st,q2_1st); + points = [Sq1 Sq2 S(1) S(2)]'; + + GapValue = 5; + distArr = []; + pdefL = 50; + + figure 1 + axis([-180 180 -180 180]) + hold on + plot(points(1, 1), points(2, 1)) + text(points(1, 1), points(2, 1), 'S', 'FontSize', 20); + + minTable = []; + + n=0; + WhileCond = 15; + + while n 1 + for j=1:n + q1_p = points(1,j); + q2_p = points(2,j); + + pointsTemp = [points [q1_r q2_r 0 0]']; %new point r values are stored in n+1 column of pointsTemp + distArr = [distArr checkingLine(GapValue, L1, L2, n+1, j, pointsTemp)]; + endfor + + else + q1_p = points(1,1); + q2_p = points(2,1); + pointsTemp = [points [q1_r q2_r 0 0]']; + distArr = [distArr checkingLine(GapValue, L1, L2, 1, 2, pointsTemp)]; + + endif + [minDist, minIndex] = min(distArr); %validé + + if ~isnan(minDist) + q1_p = points(1, minIndex); + q2_p = points(2, minIndex); + + q1_pdefL = q1_p + (pdefL * (q1_r - q1_p) / minDist); + q2_pdefL = q2_p + (pdefL * (q2_r - q2_p) / minDist); % from thales theorem + + points(1, n+1) = q1_pdefL; + points(2, n+1) = q2_pdefL; + + if n+1!=minIndex + obstacle(n+1, minIndex) = pdefL; + obstacle(minIndex, n+1) = pdefL; + endif + + figure 1 + hold on + plot(points(1, n), points(2, n)) + if pdefL == min(distArr) %which occurs only at the last iteration + text(points(1, n+1), points(2, n+1), 'G', 'FontSize', 20); + endif + if n>1 + text(points(1, n), points(2, n), int2str(n-1), 'FontSize', 20); + endif + Xplot = [q1_p, q1_pdefL]; + Yplot = [q2_p, q2_pdefL]; + plot(Xplot, Yplot, 'Color', 'b') + drawnow + endif + endwhile +## disp('avant') +## obstacle +## for i=1:columns(obstacle) +## for j=1:columns(obstacle) +## if ~isnan(checkingLine(GapValue, L1, L2, i, j, points)) +## obstacle(i,j) = checkingLine(GapValue, L1, L2, i, j, points); +## +## q1 = points(1,1); +## q2 = points(2,1); +## q1_ = points(1,j); +## q2_ = points(2,j); +## +## Xplot = [q1, q1_]; +## Yplot = [q2, q2_]; +## plot(Xplot, Yplot, 'Color', 'b') +## drawnow +## +## endif +## endfor +## endfor +## disp('apres') +## obstacle + + + nbNode = WhileCond-1; + %{ + for i=1:columns(obstacle) + [minTab(i,1) minTab(i,2)] = min(obstacle(1:i,i)); + endfor + + for i=1:rows(minTab) + if ~isnan(minTab(i,1)) + q1_p = points(1,minTab(i,2)); + q2_p = points(2,minTab(i,2)); + + q1_r = points(1, i); + q2_r = points(2, i); + + q1_pdefL = pdefL * (q1_r - q1_p) / minTab(i,1) + q2_pdefL = pdefL * (q2_r - q2_p) / minTab(i,1) % from thales theorem + + q1_pdefL = q1_r; + q2_pdefL = q2_r; + + + Xplot = [q1_p, q1_pdefL]; + Yplot = [q2_p, q2_pdefL]; + figure 1 + plot(Xplot, Yplot, 'Color', 'b') + drawnow + endif + + endfor + %} +endfunction \ No newline at end of file diff --git a/checkIV.m b/checkIV.m new file mode 100644 index 0000000..8caaf03 --- /dev/null +++ b/checkIV.m @@ -0,0 +1,19 @@ +function Valid = checkIV(M) + LiCols = licols(M); + n=[]; %count how many times the Linear Independent Column is present in M + Valid = 0; %booleqn representing zhether or not a Linear Independent Column is present only once + for i=1:columns(LiCols) + n(i)=0; + for j=1:columns(M) + if M(j)==LiCols(i) + n(i)++; + endif + endfor + endfor + + for z=1:columns(n) + if n(i)==1 + Valid = 1; + endif + endfor +endfunction diff --git a/checkingLine.m b/checkingLine.m new file mode 100644 index 0000000..ff98f9f --- /dev/null +++ b/checkingLine.m @@ -0,0 +1,51 @@ +function dist = checkingLine(GapValue, L1, L2, n, j, points) + q1 = points(1,j); + q2 = points(2,j); + q1_ = points(1,n); + q2_ = points(2,n); + + + dist = 0; + if n==j + dist = NaN; + endif + if q1 != q1_ + + %defining Q2 as a function of Q1 + A = (q2_- q2)/(q1_ - q1); + B = q2 - A * q1; + Q2 = @(Q1) A*Q1+B; + + %getting the sampling direction + if q1 > q1_ + gap = -GapValue; + else + gap = GapValue; + endif + + + %getting the sample points + for g=q1:gap:q1_ + Q1test = g; + Q2test = Q2(g); + + %Is the end effector colliding with obstacle + [Xtest, Ytest]=MyFK(L1,L2,Q1test,Q2test); + + %filling the obstacle matrix + if dist !=NaN && (Ytest >= L1 || Ytest <= -L1 || (Xtest>=-L2 && Xtest<=L2 && Ytest>=-L2 && Ytest<=L2)) %verifie les obstacles + dist = NaN; + + %{ + X_space = [X_space Xtest]; + Y_space = [Y_space Ytest]; + %} + endif + + endfor + if dist ==0 && n!=j + dist = sqrt( (points(1,j)-points(1,n))^2 + (points(2,j)-points(2,n))^2); + endif + endif + +endfunction \ No newline at end of file diff --git a/licols.m b/licols.m new file mode 100644 index 0000000..ef6d3d7 --- /dev/null +++ b/licols.m @@ -0,0 +1,34 @@ +function [Xsub,idx]=licols(X,tol) +%Extract a linearly independent set of columns of a given matrix X +% +% [Xsub,idx]=licols(X) +% +%in: +% +% X: The given input matrix +% tol: A rank estimation tolerance. Default=1e-10 +% +%out: +% +% Xsub: The extracted columns of X +% idx: The indices (into X) of the extracted columns + if ~nnz(X) %X has no non-zeros and hence no independent columns + + Xsub=[]; idx=[]; + return + end + if nargin<2, tol=1e-10; end + + + [Q, R, E] = qr(X,0); + + if ~isvector(R) + diagr = abs(diag(R)); + else + diagr = abs(R(1)); + end + %Rank estimation + r = find(diagr >= tol*diagr(1), 1, 'last'); %rank estimation + idx=sort(E(1:r)); + Xsub=X(:,idx); + diff --git a/mainPRM.m b/mainPRM.m new file mode 100644 index 0000000..75418fd --- /dev/null +++ b/mainPRM.m @@ -0,0 +1,18 @@ +clear all +close all + +points = [] +randV = 360; + +L1 = 2; %swap +L2 = 1; + +for i=1:10 + + q1 = randi(randV); + q2 = randi(randV); + [x, y] = buildPRM (q1, q2, L1, L2); + + points = [points [x;y]]; +endfor +points \ No newline at end of file diff --git a/motion_planning/.gitignore b/motion_planning/.gitignore new file mode 100644 index 0000000..d14bfe7 --- /dev/null +++ b/motion_planning/.gitignore @@ -0,0 +1,33 @@ +# ---> Octave +# Windows default autosave extension +*.asv + +# OSX / *nix default autosave extension +*.m~ + +# Compiled MEX binaries (all platforms) +*.mex* + +# Packaged app and toolbox files +*.mlappinstall +*.mltbx + +# Generated helpsearch folders +helpsearch*/ + +# Simulink code generation folders +slprj/ +sccprj/ + +# Matlab code generation folders +codegen/ + +# Simulink autosave extension +*.autosave + +# Simulink cache files +*.slxc + +# Octave session info +octave-workspace + diff --git a/motion_planning/LICENSE b/motion_planning/LICENSE new file mode 100644 index 0000000..d41c0bd --- /dev/null +++ b/motion_planning/LICENSE @@ -0,0 +1,232 @@ +GNU GENERAL PUBLIC LICENSE +Version 3, 29 June 2007 + +Copyright © 2007 Free Software Foundation, Inc. + +Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. + +Preamble + +The GNU General Public License is a free, copyleft license for software and other kinds of works. + +The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free software for all its users. We, the Free Software Foundation, use the GNU General Public License for most of our software; it applies also to any other work released this way by its authors. You can apply it to your programs, too. + +When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. + +To protect your rights, we need to prevent others from denying you these rights or asking you to surrender the rights. Therefore, you have certain responsibilities if you distribute copies of the software, or if you modify it: responsibilities to respect the freedom of others. + +For example, if you distribute copies of such a program, whether gratis or for a fee, you must pass on to the recipients the same freedoms that you received. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. + +Developers that use the GNU GPL protect your rights with two steps: (1) assert copyright on the software, and (2) offer you this License giving you legal permission to copy, distribute and/or modify it. + +For the developers' and authors' protection, the GPL clearly explains that there is no warranty for this free software. For both users' and authors' sake, the GPL requires that modified versions be marked as changed, so that their problems will not be attributed erroneously to authors of previous versions. + +Some devices are designed to deny users access to install or run modified versions of the software inside them, although the manufacturer can do so. This is fundamentally incompatible with the aim of protecting users' freedom to change the software. The systematic pattern of such abuse occurs in the area of products for individuals to use, which is precisely where it is most unacceptable. Therefore, we have designed this version of the GPL to prohibit the practice for those products. If such problems arise substantially in other domains, we stand ready to extend this provision to those domains in future versions of the GPL, as needed to protect the freedom of users. + +Finally, every program is threatened constantly by software patents. States should not allow patents to restrict development and use of software on general-purpose computers, but in those that do, we wish to avoid the special danger that patents applied to a free program could make it effectively proprietary. To prevent this, the GPL assures that patents cannot be used to render the program non-free. + +The precise terms and conditions for copying, distribution and modification follow. + +TERMS AND CONDITIONS + +0. Definitions. + +“This License” refers to version 3 of the GNU General Public License. + +“Copyright” also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. + +“The Program” refers to any copyrightable work licensed under this License. Each licensee is addressed as “you”. “Licensees” and “recipients” may be individuals or organizations. + +To “modify” a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a “modified version” of the earlier work or a work “based on” the earlier work. + +A “covered work” means either the unmodified Program or a work based on the Program. + +To “propagate” a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. + +To “convey” a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. + +An interactive user interface displays “Appropriate Legal Notices” to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. + +1. Source Code. +The “source code” for a work means the preferred form of the work for making modifications to it. “Object code” means any non-source form of a work. + +A “Standard Interface” means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. + +The “System Libraries” of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A “Major Component”, in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. + +The “Corresponding Source” for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. + +The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. + +The Corresponding Source for a work in source code form is that same work. + +2. Basic Permissions. +All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. + +You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. + +Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. + +3. Protecting Users' Legal Rights From Anti-Circumvention Law. +No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. + +When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. + +4. Conveying Verbatim Copies. +You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. + +You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. + +5. Conveying Modified Source Versions. +You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to “keep intact all notices”. + + c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. + +A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an “aggregate” if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. + +6. Conveying Non-Source Forms. +You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: + + a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. + + d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. + +A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. + +A “User Product” is either (1) a “consumer product”, which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, “normally used” refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. + +“Installation Information” for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. + +If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). + +The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. + +Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. + +7. Additional Terms. +“Additional permissions” are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. + +When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. + +Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or authors of the material; or + + e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. + +All other non-permissive additional terms are considered “further restrictions” within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. + +If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. + +Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. + +8. Termination. +You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). + +However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. + +Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. + +Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. + +9. Acceptance Not Required for Having Copies. +You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. + +10. Automatic Licensing of Downstream Recipients. +Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. + +An “entity transaction” is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. + +You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. + +11. Patents. +A “contributor” is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's “contributor version”. + +A contributor's “essential patent claims” are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, “control” includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. + +Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. + +In the following three paragraphs, a “patent license” is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To “grant” such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. + +If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. “Knowingly relying” means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. + +If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. + +A patent license is “discriminatory” if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. + +Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. + +12. No Surrender of Others' Freedom. +If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. + +13. Use with the GNU Affero General Public License. +Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. + +14. Revised Versions of this License. +The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License “or any later version” applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. + +If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. + +Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. + +15. Disclaimer of Warranty. +THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM “AS IS” WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + +16. Limitation of Liability. +IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. + +17. Interpretation of Sections 15 and 16. +If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. + +END OF TERMS AND CONDITIONS + +How to Apply These Terms to Your New Programs + +If you develop a new program, and you want it to be of the greatest possible use to the public, the best way to achieve this is to make it free software which everyone can redistribute and change under these terms. + +To do so, attach the following notices to the program. It is safest to attach them to the start of each source file to most effectively state the exclusion of warranty; and each file should have at least the “copyright” line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + + This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + + You should have received a copy of the GNU General Public License along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + +If the program does terminal interaction, make it output a short notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate parts of the General Public License. Of course, your program's commands might be different; for a GUI interface, you would use an “about box”. + +You should also get your employer (if you work as a programmer) or school, if any, to sign a “copyright disclaimer” for the program, if necessary. For more information on this, and how to apply and follow the GNU GPL, see . + +The GNU General Public License does not permit incorporating your program into proprietary programs. If your program is a subroutine library, you may consider it more useful to permit linking proprietary applications with the library. If this is what you want to do, use the GNU Lesser General Public License instead of this License. But first, please read . diff --git a/motion_planning/README.md b/motion_planning/README.md new file mode 100644 index 0000000..43271d9 --- /dev/null +++ b/motion_planning/README.md @@ -0,0 +1,2 @@ +# transformation_toolbox + diff --git a/motion_planning/create3DRotationMatrix.m b/motion_planning/create3DRotationMatrix.m new file mode 100644 index 0000000..0695497 --- /dev/null +++ b/motion_planning/create3DRotationMatrix.m @@ -0,0 +1,62 @@ +function rotationMatrix = create3DRotationMatrix(roll, pitch , yaw, order) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function rotationMatrix = create3DRotationMatrix(roll, pitch , yaw) +% Task: Compute the 3D rotation matrix from the values of roll, pitch, yaw angles +% +% Inputs: +% - roll: the value of the roll angle in degrees +% - pitch: the value of the pitch angle in degrees +% - yaw: the value of the yaw angle in degrees +% - order: if equal to 1, ZYX; if equal to 0, XYZ +% +% Output: +% - rotMatrix: the rotation matrix corresponding to the roll, pitch, yaw angles +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 25/01/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% convert the input angles from degrees to radians +rollAngleInRadians = roll / 180.0 * pi; +pitchAngleInRadians = pitch / 180.0 * pi; +yawAngleInRadians = yaw / 180.0 * pi; + +% ZYX or XYZ direction +switch order + case 0 + thetaX = yawAngleInRadians; + thetaY = pitchAngleInRadians; + thetaZ = rollAngleInRadians; + case 1 + thetaX = rollAngleInRadians; + thetaY = pitchAngleInRadians; + thetaZ = yawAngleInRadians; + otherwise + disp('[ERROR](create3DRotationMatrix)-> order value is neither 0 or 1!') +end + +Rz = [cos(thetaZ) -sin(thetaZ) 0; + sin(thetaZ) cos(thetaZ) 0; + 0 0 1]; + +Ry = [cos(thetaY) 0 sin(thetaY); + 0 1 0; + -sin(thetaY) 0 cos(thetaY)]; + +Rx = [1 0 0; + 0 cos(thetaX) -sin(thetaX); + 0 sin(thetaX) cos(thetaX)]; + + +% ZYX or XYZ direction +switch order + case 0 + rotationMatrix = Rx * Ry * Rz + case 1 + rotationMatrix = Rz * Ry * Rx; + otherwise + disp('[ERROR](create3DRotationMatrix)-> order value is neither 0 or 1!') +end + + diff --git a/motion_planning/create3DTransformationMatrix.m b/motion_planning/create3DTransformationMatrix.m new file mode 100644 index 0000000..ffad708 --- /dev/null +++ b/motion_planning/create3DTransformationMatrix.m @@ -0,0 +1,39 @@ +function transformationMatrix = create3DTransformationMatrix(roll, pitch, yaw, order, tX, tY, tZ) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function transformationMatrix = create3DTransformationMatrix(roll, pitch, yaw, order, tX, tY, tZ) +% Task: Create the 3D transformation matrix corresponding to roll, ptich, yaw angles and a 3D translation +% +% Inputs: +% - roll: the value of the roll angle in degrees +% - pitch: the value of the pitch angle in degrees +% - yaw: the value of the yaw angle in degrees +% - order: the order of rotation if 1 ZYX, if 0 XYZ +% - tX = the value of the translation along x in mm +% - tY = the value of the translation along y in mm +% - tZ = the value of the translation along z in mm +% +% Output: +% - transformationMatrix: the transformation matrix corresponding to roll, ptich, yaw angles and a 3D translation +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 25/01/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% determine the rotation matrix (3 x 3) +rotationMatrix = create3DRotationMatrix(roll, pitch, yaw, order); + +% create the translation part (3 x 1) +translationMatrix = [tX; tY; tZ]; + +% create the homogeneous coordinate part +homogeneousCoord = [0 0 0 1]; + +% create the transformation matrix which shape is +% ( R | t ) +% --- -- +% ( 0 | 1) +% with R: the rotation matrix (3x3) +% and t: the translation matrix (3x1) +transformationMatrix = [ rotationMatrix translationMatrix; homogeneousCoord]; + diff --git a/motion_planning/createVisibilityGraph.m b/motion_planning/createVisibilityGraph.m new file mode 100644 index 0000000..2d71c50 --- /dev/null +++ b/motion_planning/createVisibilityGraph.m @@ -0,0 +1,34 @@ +function [nbNodes, visibilityGraph] = createVisibilityGraph(connectionMatrix, points2D) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +%function [nbNodes, visibilityGraph] = createVisibilityGraph(connectionMatrix, points2D) +% +% Task: Create a visibility graph from a connection matrix and a set of 2D points +% +% Inputs: +% -connectionMatrix: matrix of connection if cell is equal to 1 there is an edge between the corresponding points, cell is 0 otherwise +% -points2D: coordinates of the vertices of the graph +% +% Outputs: +% -nbNodes: the number of nodes of this graph +% -visibilityGraph: a matrix containing the distance between connected nodes +% (NaN refers to not connected nodes) +% The matrix has a size of (nbNodes+2)x(nbNodes+2) +% +% Guillaume Gibert (guillaume.gibert@ecam.fr) +% 19/03/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +nbNodes = size(points2D,1)-2; +visibilityGraph = NaN(nbNodes+2, nbNodes+2); + +for l_row=1:size(connectionMatrix,1) + for l_col=1:size(connectionMatrix,2) + if (connectionMatrix(l_row, l_col) == 1) + % computes the distance between the 2 points + distance = sqrt( (points2D(l_row,1)-points2D(l_col,1))^2 + (points2D(l_row,2)-points2D(l_col,2))^2); + visibilityGraph(l_row, l_col) =distance; + end + end +end + + diff --git a/motion_planning/dh2ForwardKinematics.m b/motion_planning/dh2ForwardKinematics.m new file mode 100644 index 0000000..195a16d --- /dev/null +++ b/motion_planning/dh2ForwardKinematics.m @@ -0,0 +1,46 @@ +function jTee = dh2ForwardKinematics(theta, d, a, alpha, jointNumber) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function wTee = dh2ForwardKinematics(theta, d, a, alpha, jointNumber) +% Task: Determine the 3D transformation matrix corresponding to a set of Denavit-Hartenberg parameters +% +% Inputs: +% - theta: an array of theta parameters (rotation around z in degrees) +% - d: an array of d parameters (translation along z in mm) +% - a: an array of a parameters (translation along x in mm) +% - alpha: an array of alpha parameters (rotation around x in degrees) +% - jointNumber: joint number you want to start with (>=1 && <=size(theta,1)) +% +% Output: +% -jTee: the transformation matrix from the {World} reference frame to the {end-effector} reference frame +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 29/01/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% checks if the arrays have the same size +if (size(theta, 1) != size(d,1) || size(theta,1) != size(a, 1) || size(theta,1) != size(alpha, 1)) + disp('[ERROR](dh2ForwardKinematics)-> sizes of input arrays do not match!') + return; +end + +% creates the output matrix as an identity one +jTee = eye(4); + +% checks if jointNumber is in the good range [1 size(theta,1)] +if (jointNumber < 1 || jointNumber > size(theta, 1)) + disp('[ERROR](dh2ForwardKinematics)-> jointNumber is out of range!') + return; +end + +% loops over all the joints and create the transformation matrix as follow: +% for joint i: Trot(theta(i), z) Ttrans(d(i), z) Ttrans (a(i), x) Trot(alpha(i), x) +for l_joint=jointNumber:size(theta, 1) + % determine the transformation matrices for theta, d, a and alpha values of each joint + thetaTransformMatrix = create3DTransformationMatrix(0, 0, theta(l_joint), 1, 0, 0, 0); % Rz + dTransformMatrix = create3DTransformationMatrix(0, 0, 0, 1, 0, 0, d(l_joint)); % Tz + aTransformMatrix = create3DTransformationMatrix(0, 0, 0, 1, a(l_joint), 0, 0); % Tx + alphaTransformMatrix = create3DTransformationMatrix(alpha(l_joint), 0, 0, 1, 0, 0, 0); % Rx + + jTee = jTee * thetaTransformMatrix * dTransformMatrix * aTransformMatrix *alphaTransformMatrix; +end diff --git a/motion_planning/dijkstra.m b/motion_planning/dijkstra.m new file mode 100644 index 0000000..03a919e --- /dev/null +++ b/motion_planning/dijkstra.m @@ -0,0 +1,70 @@ +function [distanceToNode, parentOfNode, nodeTrajectory] = dijkstra(nbNodes, visibilityGraph) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +%function [distanceToNode, parentOfNode, nodeTrajectory] = dijkstra(nbNodes, visibilityGraph) +% +% Task: Perform the Dijkstra algorithm on a given visibility graph +% +% Inputs: +% -nbNodes: number of nodes of the graph excluding the starting and goal points +% -visibilityGraph: a matrix containing the distance between connected nodes +% (NaN refers to not connected nodes) +% The matrix has a size of (nbNodes+2)x(nbNodes+2) +% +% Outputs: +% - distanceToNode: distance between the current node and its parent +% - parentOfNode: index of the parent node for each node +% - nodeTrajectory: best trajectory +% +% Guillaume Gibert (guillaume.gibert@ecam.fr) +% 17/03/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +constantLargeDitance=10000; + +visitedNodes = zeros(1, nbNodes+2); +distanceToNode = constantLargeDitance*ones(1, nbNodes+2); +distanceToNode(1) = 0; +parentOfNode = zeros(1, nbNodes+2); + +fprintf('##Starting Dijkstra''s algorithm...\n') + +while (sum(visitedNodes(:)==0)) + thresholdDistance = constantLargeDitance+1; + for l_node=1:nbNodes+2 + %l_node + if (visitedNodes(l_node)==0 && distanceToNode(l_node) < thresholdDistance) + minIndex = l_node; + thresholdDistance = distanceToNode(l_node); + end + end + + fprintf('-->Visiting N%d\n', minIndex-1) + + visitedNodes(minIndex) = 1; + for l_node=1:nbNodes+2 + %l_node + if (l_node~=minIndex && ~isnan(visibilityGraph(minIndex, l_node))) + distance = distanceToNode(minIndex) + visibilityGraph(minIndex,l_node); + if (distance < distanceToNode(l_node)) + distanceToNode(l_node) = distance; + parentOfNode(l_node) = minIndex; + end + end + end +end +fprintf('##Dijkstra''s algorithm is done!\n') +fprintf('##Results\n') +fprintf('Minimal distance to target: %d\n', distanceToNode(nbNodes+2)) +nodeIndex = nbNodes+2; +nodeTrajectory = []; +while(nodeIndex~=1) + nodeIndex = parentOfNode(nodeIndex); + nodeTrajectory = [nodeTrajectory nodeIndex]; +end +fprintf('S-->'); +for l_node=2:length(nodeTrajectory) + fprintf('N%d-->', nodeTrajectory(length(nodeTrajectory)-(l_node-1))-1); +end +fprintf('G\n'); +fprintf('########\n'); + diff --git a/motion_planning/drawCircle.m b/motion_planning/drawCircle.m new file mode 100644 index 0000000..1b45209 --- /dev/null +++ b/motion_planning/drawCircle.m @@ -0,0 +1,30 @@ +function h = drawCircle(x,y,r) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function h = drawCircle(x,y,r) +% Task: Draw a circle providing its center and radius +% +% Inputs: +% - x: the x-coordinate of the circle center (in m) +% - y: the y-coordinate of the circle center (in m) +% - r: the radius of the circle center (in m) +% +% Outputs: +% - h: a reference to the plot figure +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 14/09/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% holds the previous drawing +hold on; + +% generates samples in the range [0, 2pi] +th = 0:pi/50:2*pi; + +% computes (x,y) samples along the circle perimeter +xunit = r * cos(th) + x; +yunit = r * sin(th) + y; + +% plots the samples +h = plot(xunit, yunit, 'r'); diff --git a/motion_planning/inverse3DRotationMatrix.m b/motion_planning/inverse3DRotationMatrix.m new file mode 100644 index 0000000..b996807 --- /dev/null +++ b/motion_planning/inverse3DRotationMatrix.m @@ -0,0 +1,22 @@ +function invRotationMatrix = inverse3DRotationMatrix(rotationMatrix) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function invRotationMatrix = inverse3DRotationMatrix(rotationMatrix) +% Task: Inverse a 3D rotation matrix +% +% Inputs: +% - rotationMatrix: the rotation matrix to inverse +% +% Output: +% -invRotationMatrix: the inverse of the rotation matrix +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 25/01/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% checks if the input rotation matrix has the right size +if (size(rotationMatrix, 1) != 3 || size(rotationMatrix, 2) != 3) + fprintf('[ERROR] (inverseRotationMatrix) -> the size of the input rotation matrix is not 3x3!\n'); +end + +invRotationMatrix = rotationMatrix'; \ No newline at end of file diff --git a/motion_planning/inverse3DTransformationMatrix.m b/motion_planning/inverse3DTransformationMatrix.m new file mode 100644 index 0000000..5351ec6 --- /dev/null +++ b/motion_planning/inverse3DTransformationMatrix.m @@ -0,0 +1,42 @@ +function invTransformationMatrix = inverse3DTransformationMatrix(transformMatrix) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function invTransformMatrix = inverse3DTransformationMatrix(transformMatrix) +% Task: Inverse a 3D transformation matrix +% +% Inputs: +% - transformMatrix: the transform matrix to inverse +% +% Output: +% - invTransformationMatrix: the inverse of the transformation matrix +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 25/01/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% checks if the input transform matrix has the right size +if (size(transformMatrix, 1) != 4 || size(transformMatrix, 2) != 4) + fprintf('[ERROR] (inverseTransformationMatrix) -> the size of the input transform matrix is not 4x4!\n'); +end + +% retrieves the rotation matrix +rotationMatrix = transformMatrix(1:3, 1:3); + +%retrieves the translation matrix +translationMatrix = transformMatrix(1:3, 4); + +% inverses the rotation matrix +invRotationMatrix = inverse3DRotationMatrix(rotationMatrix); + +% inverses the translation matrix +invTranslationMatrix = -invRotationMatrix * translationMatrix; + +% create the inverse of the transform matrix +% ( R^-1 | -R^-1t ) +% --- ----- ----- -- +% ( 0 | 1) +% with R: the rotation matrix (3x3) +% and t: the translation matrix (3x1) +invTransformationMatrix = [invRotationMatrix invTranslationMatrix; 0 0 0 1]; + + diff --git a/motion_planning/testDijsktra.m b/motion_planning/testDijsktra.m new file mode 100644 index 0000000..34ad80c --- /dev/null +++ b/motion_planning/testDijsktra.m @@ -0,0 +1,22 @@ +%{ +points = + + Columns 1 through 12: + + -28.9550 -19.3630 -91.9319 -174.3179 113.6085 9.7763 -11.6645 -1.4659 47.0429 110.2832 65.9202 151.0450 + 104.4775 -103.5474 110.5317 -125.3647 -107.9741 -113.7357 164.8849 -95.2513 129.1750 -145.0642 -86.2545 104.4775 + 2.0000 1.3435 0.8803 -1.4950 0.1942 1.7297 1.0660 1.8824 0.3651 0.1280 1.7537 -2.0000 + 0 -1.5026 -1.6799 0.6708 1.9308 -0.6309 0.0462 -1.0443 1.5297 1.3055 1.4785 0 + +%} + +visGraphTest = [ NaN 1208.2459 NaN NaN 255.8516 221.6238 62.8332 201.6116 NaN; + 1208.2459 NaN 226.0445 156.4833 133.0452 30.8691 268.5426 19.7264 242.0113; + NaN 226.0445 NaN NaN NaN 246.2527 NaN 224.7904 140.2197; + NaN 156.4833 NaN NaN 288.4511 NaN 332.7176 NaN NaN; + 255.8516 133.0452 NaN 288.4511 NaN NaN 300.2422 NaN 246.3142; + 221.6238 30.8691 246.2527 NaN NaN NaN 279.4443 NaN 245.7527; + 62.8332 268.5426 NaN 332.7176 300.2422 279.4443 NaN NaN NaN; + 201.6116 19.7264 224.7904 NaN NaN NaN NaN NaN 1229.6089; + NaN 242.0113 140.2197 NaN 246.3142 245.7527 NaN 1229.6089 NaN]; + [distanceToNode, parentOfNode, nodeTrajectory] = dijkstra(7, visGraphTest) \ No newline at end of file diff --git a/planPathPRM.m b/planPathPRM.m new file mode 100644 index 0000000..e5cd6d1 --- /dev/null +++ b/planPathPRM.m @@ -0,0 +1,67 @@ +function planPathPRM() + [nbNode, visGraph, points] = buildPRM(); + [distanceToNode, parentOfNode, nodeTrajectory] = dijkstra(nbNode, visGraph); + visGraph + addpath("C:/Users/Admin/Documents/ProjectMotionPlanning/motion_planning"); + Q1plot = []; + Q2plot = []; + X_plot = []; + Y_plot = []; + GapValue = 1; + nodeTrajectory = [columns(points) nodeTrajectory]; + + for i=1:columns(nodeTrajectory) + Q1plot = [Q1plot points(1, nodeTrajectory(i))]; + Q2plot = [Q2plot points(2, nodeTrajectory(i))]; + + if i>1 + + + A = (Q2plot(i-1)- Q2plot(i))/(Q1plot(i-1) - Q1plot(i)); + B = Q2plot(i) - A * Q1plot(i); + + Q2 = @(Q1) A*Q1+B; + + if Q1plot(i) > Q1plot(i-1) + gap = -GapValue; + else + gap = GapValue; + endif + for g=Q1plot(i):gap:Q1plot(i-1) + Q1test = g; + Q2test = Q2(g); + + %Is the end effector colliding with obstacle + [Xtest, Ytest]=MyFK(2,1,Q1test,Q2test); + + X_plot = [X_plot Xtest]; + Y_plot = [Y_plot Ytest]; + endfor + endif + + endfor + + figure 1 + axis([-180 180 -180 180]); + title('q1 q2 Joint Space'); + hold on + plot(Q1plot, Q2plot, 'Color', 'g', 'LineWidth', 1.5) + + figure 2 + title('X-Y Cartesian Space'); + axis([-3 3 -3 3]); + hold all + text(X_plot, Y_plot, '*', 'FontSize', 10, 'Color', 'g'); + + for i=2:columns(nodeTrajectory)-1 + text(points(3, nodeTrajectory(i)), points(4, nodeTrajectory(i)), int2str(nodeTrajectory(i)-1), 'FontSize', 20); + endfor + x = 3*cos(0:0.01*pi:2*pi); + y = 3*sin(0:0.01*pi:2*pi); + plot(x,y, 'Color', 'k'); + + x = cos(0:0.01*pi:2*pi); + y = sin(0:0.01*pi:2*pi); + plot(x,y, 'Color', 'k'); + +endfunction \ No newline at end of file diff --git a/planPathRRT.m b/planPathRRT.m new file mode 100644 index 0000000..e4d2e1c --- /dev/null +++ b/planPathRRT.m @@ -0,0 +1,32 @@ +function planPathRRT + addpath("C:/Users/Admin/Documents/ProjectMotionPlanning/motion_planning"); + GapValue=5; + L1=2; + L2=1; + [nbNode, visGraph, points] = buildRRT(); + for i=1:columns(visGraph) + for j=1:columns(visGraph) + if visGraph(i,j)==0 + visGraph(i,j) = NaN; + endif + endfor + endfor + [distanceToNode, parentOfNode, nodeTrajectory] = dijkstra(nbNode, visGraph); + + Q1plot = []; + Q2plot = []; + + nodeTrajectory = [columns(points) nodeTrajectory]; + + for i=1:columns(nodeTrajectory) + Q1plot = [Q1plot points(1, nodeTrajectory(i))]; + Q2plot = [Q2plot points(2, nodeTrajectory(i))]; + endfor + + + figure 1 + axis([-180 180 -180 180]); + title('q1 q2 Joint Space'); + hold on + plot(Q1plot, Q2plot, 'Color', 'g', 'LineWidth', 1.5) +endfunction \ No newline at end of file diff --git a/solveIK2LinkPlanarRobot.m b/solveIK2LinkPlanarRobot.m new file mode 100644 index 0000000..3624df4 --- /dev/null +++ b/solveIK2LinkPlanarRobot.m @@ -0,0 +1,56 @@ +function [nbSol, qi] = solveIK2LinkPlanarRobot(L1, L2, x, y) +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% function [nbSol, qi] = solveIK2LinkPlanarRobot(L1, L2, x, y) +% Task: solve Inverse Kinematics (if it exists) for a 2 link planar robot +% +% Inputs: +% - L1: length of link 1 (in m) +% - L2: length of link 1 (in m) +% - x: target x coordinate (in m) +% - y: target y coordinate (in m) +% +% Outputs: +% - nbSol: number of solutions for this IK problem +% - qi: array of joint angle values (in degrees) +% +% +% author: Guillaume Gibert, guillaume.gibert@ecam.fr +% date: 09/02/2021 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%config +threshold = 1e-10; + +cos_q2 =(x*x + y*y -(L1*L1 + L2*L2)) / (2*L1*L2); + +% no solution cos_q2 >1 or <-1 +if (cos_q2 > 1.0 || cos_q2 < -1.0) + nbSol = 0; + qi = []; + +% one solution cos_q2=1 or -1 +elseif (abs(cos_q2-1.0) < threshold) + nbSol = 1; + q2 = 0; + q1 = atan2(y,x); + qi = [rad2deg(q1) rad2deg(q2)]; +elseif (abs(cos_q2+1.0) < threshold) + nbSol = 1; + q2 = pi; + q1 = atan2(y,x) + qi = [rad2deg(q1) rad2deg(q2)] + +% two solutions -1< cos_q2 < 1 +elseif (cos_q2 > -1.0 && cos_q2 < 1.0) + nbSol = 2; + q2_1 = acos(cos_q2); + q2_2 = 2*pi-acos(cos_q2); + + q1_1 = atan2(y,x)-atan2(L2*sin(q2_1),(L1+L2*cos_q2)); + q1_2 = atan2(y,x)+atan2(L2*sin(q2_1),(L1+L2*cos_q2)); + + qi = [rad2deg(q1_1) rad2deg(q2_1); rad2deg(q1_2) rad2deg(q2_2)]; +end + + + diff --git a/test.m b/test.m new file mode 100644 index 0000000..c445c4b --- /dev/null +++ b/test.m @@ -0,0 +1,37 @@ +clc +clear all +close all +L1 = 2; +L2 = 1; +randV = 360; +a = [L1, L2]; +alpha = [0, 0]; +jointNumber = 1; +d = [0, 0]; +petitcarre = 0; +haut = 0; +bas = 0; +Bmatrix = [0; 0; 0; 1]; +bon = 0; +for i = 1:1000 + + theta = [randi(randV), randi(randV)]; + jTee = dh2ForwardKinematics(theta, d, a, alpha, jointNumber); + b_P_ee = jTee*Bmatrix; + %Is the end effector colliding with obstacle + x=b_P_ee(1); + y=b_P_ee(2); + if(x<=-L2 && x<=L2 && y>=-L2 && y<=L2) + petitcarre++; + elseif(y >= L1) + haut++; + elseif(y <= -L1) + bas++; + else + bon++; + endif +endfor +bon +petitcarre +haut +bas \ No newline at end of file