From b77c4aaaa17db3028b25cea9e0006a6a54ea6932 Mon Sep 17 00:00:00 2001 From: antonioc76 Date: Tue, 16 Apr 2024 20:09:58 -0500 Subject: [PATCH] small pf bug seems fixed by just slightly increasing the gps noise --- .../autonav_filters/particle_filter.hpp | 10 ++- .../include/autonav_filters/testing_gps | Bin 249600 -> 257488 bytes .../include/autonav_filters/testing_gps.cpp | 57 +++++++++++++++--- .../tests/particle_filter_test.cpp | 4 +- 4 files changed, 59 insertions(+), 12 deletions(-) diff --git a/autonav_ws/src/autonav_filters/include/autonav_filters/particle_filter.hpp b/autonav_ws/src/autonav_filters/include/autonav_filters/particle_filter.hpp index 0fef01eb..88fab08d 100644 --- a/autonav_ws/src/autonav_filters/include/autonav_filters/particle_filter.hpp +++ b/autonav_ws/src/autonav_filters/include/autonav_filters/particle_filter.hpp @@ -118,7 +118,7 @@ class ParticleFilter { //printf("new particles in feedback: %f, %f, %f, %f\n", this->particles[i].x, this->particles[i].y, this->particles[i].theta, this->particles[i].weight); //printf("\n====== END FEEDBACK ======\n\n"); return feedback_vector; - } + }; std::vector gps(autonav_msgs::msg::GPSFeedback gps) { if (this->first_gps_received == false) { @@ -132,6 +132,7 @@ class ParticleFilter { //printf("gps_x, gps_y: %f, %f\n", gps_x, gps_y); for (int i = 0; i < this->particles.size(); i++) { + //printf("particle %d \n", i); //printf("particle_x, particle_y: %f, %f\n", this->particles[i].x, this->particles[i].y); double distance = sqrt(pow((this->particles[i].x - gps_x), double(2)) + pow((this->particles[i].y - gps_y), double(2))); //printf("distance: %f\n", distance); @@ -190,6 +191,8 @@ class ParticleFilter { for (int i = 0;i < num_particles; i++) { int index = discrete(generator); + //printf("index: %d\n", index); + //printf("weight before selecting new particles: %f\n", this->particles[i].weight); //index = 0; //printf("index %i\n", index); std::ofstream index_log_file; @@ -202,6 +205,7 @@ class ParticleFilter { } for (int i = 0; i < int(std::size(new_particles)); i++) { + //printf("weight after selecting new particles: %f\n", this->particles[i].weight); //printf("new particles: %f, %f, %f, %f\n", new_particles[i].x, new_particles[i].y, new_particles[i].theta, new_particles[i].weight); } @@ -224,7 +228,7 @@ class ParticleFilter { std::normal_distribution<> normal_distribution_theta{new_particles[i].theta, this->odom_noise[2]}; double theta = pymod(normal_distribution_theta(generator), (2 * M_PI)); - //double theta = 6.0; + //theta = 6.0; //printf("theta: %f\n", theta); this->particles.push_back(Particle(x, y, theta, new_particles[i].weight)); } @@ -277,7 +281,7 @@ class ParticleFilter { private: std::mt19937 generator; static const int num_particles = 750; - double gps_noise[1] = {0.45}; + double gps_noise[1] = {0.80}; double odom_noise[3] = {0.05, 0.05, 0.01}; std::vector particles; double latitudeLength; diff --git a/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps b/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps index 864c55d2fe3003db032727ee1b5ba81bfb24d154..8955070a110921c0b2f20ca5637c31a5cf4a77c1 100755 GIT binary patch literal 257488 zcmeFa3wTsT5;lC!WRjC%0tpB#3c_#?2pA$FHz5eYK>;Hd7ZD602_zaq3<)3$3PO+= zKu}Nwbx~1K(G7}-3KA}osE9#O@rF?m2SJT2YF3eaZ&i1n>6y&nuHXOs&;R@n12c81 z-|Ft_>gwvtIWxI4dDsw#X&UMkVe~hMo7Y~XBuOCdXoS2nj3lF%Q6HZjjSfZ>Qk{4w zNi>)qb_hVxXemdfQNCuf*kIa1$|h@wWE;3;1uU3%yPFAsm(w8=!l zE2`(?`j$)iAez@rq${fDBiqF96L|b*fwWq-JAst~CiNt9QNARZFG=Q8)FbVwsIn*N zNbg><++dmjj9!Wc=gX4$g6Uw9%}|u;px3Bx3NrpmeJL`ZZ-po)n9h-kDXQwb9{I>F z|Lsef(-C?I;GERDV z@TTs&dc+t5-BLzrvN*#rPw=Wd!Wv7QVkqqfg zc}Rv{RG#c|nFy%B3Q}2*4?Hw7Wy(`1W ze-WmC-w&ftN*MXmVf1VlMxU->?65zK-6n-8e_j|p&x9$T;(-V6;8#=_J--g4&yQis zj|pQRs2Q@}8DaGA5=OpL82OvR=-CAAY7^X8@c%|RZ4e#1BndDXJiXeYT@8)qMp6~C zMx0DHQd6f)otB$Ay&x^WAT`xU9Xfh=YDQ*$=9KK|1)2GyhY!k`mYX>`ZBkCAz(OPA zMvN-BA~iLA)~xQ`yC+Uco1UGHBJ;CzrwmOWRnWbAdRAI~YC(QlcER+a>B*zg@R8j8 zveZ$j>C^IVPbGAEa!Pv2wdtd-fDYqE7354GS~p+vNTgjRN}q<}Gt;IHO&^__JnHh) zbk3ESkeXVMl|OA}YEEYEl!C0(%>4Xm`6w3XU(oQ1RM;Y|APuVhwF0_#M+xa^d1>j{ z1-BgWU*q9<7o zE$x0;ep+tEw5jOI8QJNXy`jdG%z_zdIb8N%Fh%!7YRR-*SiLa4U?@zQoIGQ6>Zo3+ zqY4reCQr+snU6JZgdMbJ>v&Ycf>;l;~(fE`hBS%dem72_r z?GEn|JvS*WBQ-52XIeU}0EbFTodjRZg%u0ZvqCnGdTDZYZZaX- z$ZP*XUkHo+uOmc^g4~(H`w9X(M%v~tC_}E5j*(c9nLKhT%H}T1&*Z)o-Sxl51=~sf zN<CU<5wnl&Z4HQf^kav1PM*1a}(B_~gu~Y4iST@O3@pasrRU zKg#989;80gC|o)5rc?)Ci+S0^^#aW8YCV(E;dZxyJZq6gFUoO?#Ph)4e&Aog-Nq9# zEvx21tQhJUrINp$`DkN@%GfXYga5h}D}zYmbIBKUx(_=`r{M!nFB96`F0lmg z#VZ~F=Q2*qw8D$BU9|hEwdEs>6%wQTjkB}s8%B)bwnUpYbAHQcB6*SDVdq!-f3@$P z*nvvHeq8SFRr+k&z~R*^DBUCFqpKK3FG(u-iZ29D>L!Xy{;br}p_=_Vtfj};sfJOd zrN?XOJ}tegmR_x;U#g|oXzAUx^tdX)&@!!^maf)s=rn`8Q@vm%(UTG~;{JS`oL zVZRn@=~#l>ujN`gmb~_BwU$nGtJgX$oouRJ8?2MtTwN*>6XQvuQnU)Sm zw_g=nIvmV?Rch%C>{P=ztfj|l=~Y@fjXCx5Y3U7BB51XiuJ4m;wDb!!c|-Ou^$VSA zs8_U>-b5vW#%byDh>p=_TKeBKd5@OfOiPc~(l6A~6SVY;wDewDdUGv3NlR~`rF*sX zi?#F=Exo0dK2}R_rKL~Q(mh&wmX_XHOV88N_5IH*ExoNKKTk_biofSy=PhvF0_QDo-U8<> zaNYvvEpXlf|L<7f-?1%!^Da0U?JbG?c!yzli^>WdwUyold!l!<0=1W4^@d@bs%<|A zB({}7@>ztOI{syCZS8XAX=8Tk_yL=z4cV#VJ8hmeVyBL8vU%EoojU%Q&C|x~)bSNI zPaCdN$LHHTZ8A(ueu|I^NypX~TQ!cx#)d zjn=8-4Q-w_Sf`GgHcuO?Q^$WgtJ+H&Dzx9`X(NU9+dOTc(0-ezjT72$^R!_?`)!^! zN@%~$(*_Ccw|Uwaq5U>b8zQvd=4m5@_S-ydfY5%Mr;QKVZ}YU_LHli=4 z?YH?>%>VR^C3@pFUt!XSQX5T6;uPYB}21o6Xz z_~an|${_yoAiir5-#&=HIEZf&#MckvBZK%qUJJC(&q4h6LHsvC{O3XZ2SNP1LHwIR z{PrOJ^4h%XA_=LYeGLHyJpJ~N1)5X6rO;)e(E$vWTt`=P}L zZuS;`2%gxTL1Pr~&8wn- z=-R5uJZ@Be8b9-{BzH3kFB#)qaOHiFG`z*%6vTK-uG|a8SA3?n)|Y``xi|6;)L~9Q zUb}wEe|#oDx)_6e1IG*;J<2=(B%K6%7sRwPg043p*k^c4ob73ldyA6~cQ5lUEh;-) zTk9<@_g#-rt+DM8sf%|ZA>}0DACgEl3N9~NhYU0=l^3nIuQu3M8||x7`)V_;GN{g_ zoOx*Ro`KtGA_AWWh>G4pIxk&C?6Bfv!-{_#R{Z6#;uGHDFGvLzI^Zq-jYJQzsGajk z!3vpj-x=SSCek!L8<`PuN?Nf?yGZz3TF7l$%68`k2SK7s~ zz;XzbKxCLLQoI*#(-E^b3f_vA8NMUGQFfAGtf`LeBJ2^Wz*ef_IAOwW<#t%(cuvJOOs>Jl@aoT#t3RDv^?7m)F1$-K z+Estrubra4kN<;07VPl=JF>I3&{tbnWn}8=G79mR-r8`F2Hg9p63` z8&{O|QElz1*zrYqpeXT!0!>8icfRDK9F;6|J#QD2-bldbB14 zuRLZjJ6@QfS4sL8tD$$J@KKesvtWfxxo*UxU(M=7DCNe67ii?&DLo$I+)~Df7T$F$|!MrMUkVs8I>WN!W0mG2~0_o^Nyc-r( zpdfM$DjuCDd0AZvv#O_NZ>CDhefOb5-|&#tz&u&QJ*JADNL3<=kRqx=4iXlCg=Mit zg^1AT^==4&UJeEAWU2dp1yH;T>XRy>&f<@J?P(m8G+Fi%$#Y2uNpNXV9901YdcjBD zpuR_`hgquJ7e`9z1uc!-E};(ql^69x706{{O2(nN3%D9{{&uSETg332!d8bb9_-9$RJYti&V1ai92k2 zmitzsbgF(V3R$q7K8-@xf}$i`m?wsa6q8a0b4m}9;-C~Sr?e3%5tK5FQ{qI5v(Q>l zltL+5b!NCueFpwXok|-dm_K!r>eTCAq^ok@uRoK?c9pPd=x%iA>0hYfO}1~cJJdlb zOCuBQ+zn;!S5M%C1pyv045BgNB^NK^XMta%1F2svgJji@rjy@ zYF67tuDFGRtXki&aYa1&9ssLBg+y_q)MOZsV4*ZD6B-gx z8vc~3nd{6?7>lfxxnMgf=ZamH$>T!wBve@Hq&cV;FcUf>ZqTLFRR)&TP)3N58AFN` zaznUKoRqKzzWNA)2ne+7I`o1_T7vF_zl~v*W6~PfP}cSaD*%-aVWA*1u9X=_iHt4$ z8Poh3$&!t+aMrx7If?)qC!OyXbUN5-Y8r(95W;y9?Tj!8v{IsP31PL$dK8W3^`ci_ z*~KpW5Y0Tk4J41h%6miuy0xW1N4kUHD~mGtyDncgo*UNxalki4q; zW@xLIqZ)M@D(UH}b!9NRTtmjfqP}tP7_1>H;zO+=ni#V-<5+x$nkmoTK;`jc-sHJE-S<_ro#$OV;K7 zOKnlH5rBbHW6Pkq2{gKdy@k!9f4g4;cPme>#%M53M0yt_SDSm2e?$+A!L|~6H4{TB z`9~U0m^PQe9t*0?g=K{wGFURE#=q~3^sV@wIyY?JJ8)#6TZ_Ek3w0`>IGk|IR$VO` z1tk+IPz~U6-()^+*a>zkjdB_UU--VH#07K93_6k#emnx3Qs`dhH7id<^8AglT7?w6 zhoeL)jR(+U=$aEP)hLj)T!r>Yhc851Ag&FXNZ%%^FO2`Q?Z?pgMnCX0Q-rw)&DA?s zA1QHItLxSX7z=1I9=!{|$y&Xr^XNQ@YB+_Kk=f9q;gxkvmrSPul~R>GP(_7?8oH*F z5Mi)`%#vYIusQ>|3U%wo0aWh$H%(b$>pzwa5ony1CzNr*wRjy$<>eSmRN}=A5TZ!o z{#Zqz9QMViDbR8rG#p(K=(Qzdd}xI*M!D}UQ2=@%&?(P+7Zh>!(*=)3UQ-|4u@jgGB*keY)zc*2R^C?F3lN(t@6200>zj6Tp}3Ov99num=ZOz z0lC%#$f=J-Ek1ZlI6ioHRyigMLrC>$mOi)uQY#D=G!H|+HV z>GldG(u_)L$MUgYNjJ5m1PYV)Md4JGc z+J>5nqX_^p3OEX2SaB8AdGL7M5gIGfDsY;Vfb%GS+t9Gk{T|>$Tc8G%t>Z&meSgh| zCWk36E1*2GdNXoxI1$+jwA?qGvo-_EjpZFM221bVv8&30V~|{{&|o4TW+$L7)>kin znZWrVz!y{KG>@~F`;MTW!p5hP6fWOe674On^meMi;kLteVyOYU;oB%hm3RXdZy`&R z^OmU{jo;{FLYuZB$JSXcj0&P*VY!b=fRh zqy|t(vtNS)4R48U_P)#pm|bPJ$1q!6D)E=BJ{wb!()=@Ydq^9}Uisl%c!*w!2-z!J zg|}9CcZodR#4*c(+S>l5ORl z8IA>JZ&I_65jk`ueF;VAYSdld2>)eEb#D-CsYIlN3jdTz8sS~aL>)~2DvVHpB>&n$ zoBInZY09q~n~_}Z%SA4P<%TG%(%Uz=qQK%M5LQAmV8>#AG%AHuEcbo=6%BSQA4pi# z`gdOc(0U2)1vRlVu0#kY?l5jMQ7#@w_Z+3sMc!~&=JSc7SW+exkq}E@|MfLxpy4Ph z!(#G1-zZAug_&JW63SVQT-vIu?};AdWTfy{U;2w2g3P`&d3rdofr=d&^IZhKU~WR>rmg|z0=py+g)B~mt_`PITEU- zvPM%`ri8(_RAuv8!1*>WuD$c;R!_quHe(H!UOsOgo>j;T-lrg1V>9aav|wKCy6nhl zJI>ER12bgY_lG_?+q}yiznfKp=ErE%@bciWu%R~2<2dkX-us>$Vw(59jihsUuip`P z!2eTt9ZWp|)sZul`wH0I$j8t%EVYuVp>4<)zJ|iE5OlCSuV;KhVd<7UKXFN&xg@c` zCBZ`JgYwoI?Q@E+iiXz(?rWvp>Z~AY{3|`!oSZ_acO2^J!<_P~xWM{>jnn(|&&M>Z zu{8Nxvc_2W2S(zze#5aH{z)d0BJc410T{0w!Ht?+p5&1yqup z!VkB?#HEOb8|ucx4XUxYtwJ%e9*4l=CE#GiQna)}_S_2cCT7chPvDwkJ;rq<8e*5? zpb(8+la@rX6xEhe_{3y`gXQ;pommcc(F8fh&@Pmg!b{0!?9i8!DE2V=4*I$yb!{b< z2hB)GeY z6t1HJkhtM1G(iUzmgzlDPcDcvgEA_pG2I_P&n!*;NSb^Tt0DF=chEI=A5f*|tE4>3 zm-}w#+Z^KfVGx!nLyO-;GZ8(Sfp7)iV?l}iiDK^qJFNIPw$XT2ffRUBv>JMHfJsIl zsuQ?DC;Iuv926+`)uZafDEiN5`j|uZa$k%e{S>IL13s|HiI+Fs17?bI#~lve=wmIi zsX3yY0tI{$L9ILqi&Fa<_r2f@S`KZwhvDbLAxyPV@Hfs$yK?{L_ahio8@O^CR>LY% zMmhg{#ZH6R9k7S}A}}*~U>4NhfZXd)?P|U6#SV3YcWIMHuEvc}n#jp+N4Q`d8qs*f zN}Y~O_!3)(V(LsJLrk1>CL=6xXh7-g%lER6$VgB!W~+)AbXt!GWsn=AfR{_FsgxF~ z709tPrihHjA|}l~sE2+2Cp_ebrAC!Rx%x#MZ|O`1HJAI|v zVU}Fw6a|+1h6Uyn;SIIYrW-Sz$jO6W=m{f?!Fyz!_YxeE?feZB=x|iPnzba&*f=z} z z>v=w1C)a?SI(ciRN+X7J4@6Z1!j1_{Qgq;0orru}F=*;cm2~zS zI2kS^*Tx}h?3Scvm^GWzHEoxOqWB~}pRPRqBYCKtGp8X7_H|`|>wh$uuE+Bpk5(@g zWU~>Pz!puQiu659+qF}%H{u5~N+I53 z${2vwJb)guw}X|)ItCvN$EqFbfujk@>yVlZC@z`r^^&0jX5S2?cCunhLhUdpFR*fS}11bL>D^V**I9*#J9zovU;f+_`VJQC6~F$>ffe8WNaS8djy zF|XFdmjui}Vm|R9F4l15W(~`IpP?Sj`@=|m94sZ)F@-9Qz=Je_ri>_bm=U zJ}scV`j1J}spUTFAbU8bgTVD-t3!2Tt-d$pm`FEA&@h-n%xXobULFb5F|Oz!nwg7f zr6%Wc$}i@Kng6Y=7eG*(_{loG;NNT=I>A8s0c$rge^Ud?q?%)dl`5(I)9IRz4`|Iv zvo6nA>yWIkACX=z?h1*8RH-mq!1Q$TePuG$_u|~!L)z6{QE-tXov406jT!qunLJ+M z?r$AgRCpq`h zz`_!lEr*j-VQdb=v&+Rtd~?_?$i8%JGgZu!e4mClh{qHxcWtM!BGziSB(R1`oJxyw z$&8J$=;I<)(XxyoRQv*;Dfi+(LkvMK^7H;gc^(Qd_uK<837+i?K8+7IM&Cktn%{6p z6fr}(Fm0k$&%vogIqcvDsqJd0h37K;4v35%dKZiNj}9Z%*!T?D(dueATR^nlQW>;Y zB6mSUgYHNnU* za77scPxb{0HJtlt+``p^LST#cg2%H`12L=+E#O5o=0sZ5a`@fD4H{F0(jdY~-y%s5 zBuFp!MbTk~2qaVNO6)abo%JUNN$i{LWgQ$AT|u2#2=~HlChA2mV>_sOCe4fN!Rr1; zv{&6#i3o6Zb~H8T+eAM6&_13Av_QNofKq1QayJ1~J z)bZQd$PhfJ(O~U_GgP0UzwihM)^_TC%-$V{!-j7I_P)iXy*WlCZvZj&p!_=@vtAopXS%MQ&PpAh&%EApC(s65iT5K!j=rp99ct9u5JKfOCNA5a$4& z@xt3a2N;TneY_7H0F^=+J_m?qjbORQ19Qf5PSi?K&OQftK;;z8KvPDlbASl# z9AFJSNG3$ktT=gDrJVz4O`;74IwHh5z=F4^n1C^gj!Qtt9o9RH=U}p5xo<58T$)3Z zef9}XGodscW^xqm%y)qTXXj?9O7l<|Pq8dXinh0E0nb7CCH#9i2-yB9aV;fytjG}; z+GF=)oux?xA^XJGvMD=N|hJ9R$|(*bhYRV2}NXo@otnauw*Y+A)uQauv#B z_Z_1GZI5+_^w<)iOyJ4YeStX-@bgx|9(%pYS=VC`%c_ZSJM4N62OvA-ntC%p3wq}WH@8qoYHZw549E#p}w z5&QKU&V?vjGnNP0K{Hqw3(8yg z*i^!G0<1ZP6$qHMdQtF$-sl$WfbHAiZ2U*51U9JuF6ch{PCHu5QY-ii6}-7y!Ow=# zsun{5olruNn(l()Yo_Gm08%Ik6i>%-Ni>>;Am#+VK~wJgh?gr=Oo+Rns$ji{%$X`ej6w8cv1%s)lynLezubjIOOweNF0N9Q*UB$HCEGajp%6T$QuVp zkwlf>1qg`?>?RLfu@mQJ9u)G!R5)5XnB!0fkop-dRx zg>nxcf0k@3d-f*WEg;{Z(^3i?hsjneNrPg#a|dsNvwy@XCkCrb9YiKLQXHMmit}PS z_iE0KbLTpxaEh$>jlJ#~D=vriKkb^_ z6`ymfkWlHN?kG>@KNupPlS(dyX(L^bp?=v4v}TZQU6v5(_Mks`^#dtl+l;*>yy%Rkn9)qFaLt} zJ|WD{&u7^Eqe34=G#Qb6JcI*+{MSed7!yf)hz}kU;!ZhST*Pu2@lQ;HRejzA7~$j# zGz54DNcF-uS$4gsx&l*w6_U&40q8qO#<1#uT#!UgIe@-raTIz9O60>jJdzg;DU2ti zE|}{x?!1Sq3L4}4w+D=IvQpqOB+Lq4tqEeed^zcqkQTfU;>fLH!GF$B)aAgaFNsER z)&6m%cR=9GdOgYwjB0WIQ5euY|Ke#`%tG@Kp8vaCSI`kBM_ig&{WG6Bo)P2Co@mi; zp`t93;W~0M6p=k(Tl*;Pum`wKxJG;@?#t@;0sp%t&~03UZc&eIC(?_&&VN%Ey0WX? z`g&k|Q~f}ez{nqgLWzEer+zf`rKiXnr?6SHeTJpoB&oCU4|C-3JJw%%j19H>^3Q`x z^G&Y>YhJg#&^!YtbchrjC8}TqWZ%1k9(VAKz;=$}OBDi$?qUD+*%I9+@SiO;r>{wz z<7}z>t27YA+0T!(h4E*tVwMJUz}eE7|A?Uzc((Ks2?w4nkq0A1J6l3Z=(D9ySquGO zh??6Bo+9RU@)B5W8$XNF4Ek0P`#iI7+0X~eC;^zK;kuA#f-ZqUmTSm2b zL>f+|PTu4>rGc}{y62QA;J?$=5mwg+>06^AbZr=@tFpg#LT`7A9L%ZMo@uS)94eHz z(v}-_#~;UnJrrJhJnWaYfV72MVQkd)%_`rZ1 zG+Ze}1%%A~7++e<(S2+w7Rdf3?1wlG3lIz}IrP0vI$f@l$v*~4lAmn!`FcAFB40O54*kNng0{5Zl zcvgy=@fa^k;IG^)o^#(sH);KYVM?~Z7?Udqd6GomhsFF9O*v@>3bM6xt`U_!oEZ}bg?`;Eyv&i80-#R|wzcUZRiPIk3 zq^LymIp$79h2nNL>|5@m;=~lnX1)o0vA;cC zkRP&FsU@&@EH2zPw7zDA$m0<+Z8y}vp;d~xk57t;Poz^aib%>DzR(qmB8r!Dv6NMOg$0cddO|qPj$nbix9y^ngS`$~g__IQ zIq>^!DBeF>>cq#ov1Jiz@n;A-yq+dcHB`p_U-|+~!8(jUXI2J|h#Gr!6&o-yd2D-& zy&WQNx$jR`XszT5?VF8Qq2=KN^@{^6_t zP~UIy-_0H+=VS<8STRFP`wAXBmohdswk7s zraMHfd~cA}H82By1LU26oC7&0#vm5Z{=3-~!U&}220(a^40ShqA3cC3M9{1_d09m( zaa?cJj?*#JD7Zm`5O=d*ewK;}yqisaYR`;RvOM|axkS_zxa{%-3{iQi*qUzE$>sW7 z+KcmSQ-db?WLT&V3C-L7m*Ii$Lg-_%9o6L@lTE<-hetev`tZ1#QvQ5+!h_Eh{QTP` zJNUgx(*-tnJ~SM?!olyQXSky%HcD6qzu=kTTv4yimT?Ux`yktiF01wz6Lxl3Mk@us zx$a~(Xz?|NR}=d233oE0xW9sM0fL?$2z?T@=atYWQB?Lh%B7Q*Lb`!abD|IXl;4)H zYm9@PiY6Fg@@}j<+*TK(`NlT6TC_@E{hFQ_Ezu47=dtqlz^U6mXtW-vYoIzE`Aywo z0&IMaIpV560_KRbJ{SmBx5IDGx^+9kIt<35SfPFb-C-ihpZ6XjpYG;?%~JaCvhGBC zYDWn+I3)$K=sT2NId^KZ-Mg` zIB$XT7C3K#^A=`UGGc$WiR>5=+S3~t>&dNg-xdqv2IjQ-X)1j)+qaZ7@ zAWdAd?vv7{XQ!u5FUZf%ozkaI>hRR`X}RDE(+fPgg*iE%+-U_KG%7p8n30)YFfE^D z@-x$Na;BxHX6H`N%ojFDPs=6IbU+1}p6LY{efo$Do}9G&DQI&+R$8uSYTB&S>DjY0 z<2%{KLAlKQ8JVn%|079V?z-%;p_AVFalrgp6Lw6zq7+}q4|vT}+`Iee_1SdfyRSAM?4;W-9kKQ z1*jJ^>hapzEYKF98$geMR)U@dJx%FP;78{CwM z!MCj@fp!611Ud}#VbC1V3eY8>7d;32gFXaW33?c`8uSck9KNg92=_e`K>LHHfZhz6 z2U-fc5|nO^ZU!BR`=N(G9|xu1QuqXvekUOo_icNC4h9_!de6UVYv+LWD6Or1n9@PF zfsO|K4D=4rGoUL$Ti{#7?}GLNb!@7w9S^z%bRK90D1AHr7tk`$W-r2Spp9RGAK)AG z9YEtjM}vAnlQyH>pc_D!fL4HR1Re1*^ajnv6L$t42Urg30eu`a3G@)?M9})U>o5=W z8qjs1PTY>#1KJeyD5w|I*%&(0QO6Krh)=TU!CzAJhkW z3^WFRd-Duv7tng!(O;nLKyyH^0bK%`2f7jTDbRhO+dxl(z6~0Kzt!mj?E;$j2Ko#1 zY0x~-&p?-hM(sd;`%mGz+xN9<&>DDCh>zHJ}xs8$o@bUxG&CFK=D&Ci)As z1E?1?3p5M#?|ad1&^4eNK`TM`fjY|3ZqUY{F&DxAK)Zm(yoGjy=7Z*et^{2Ux*4<- zbT4QnsPk?3Ip`bjz)zc_ef!|2pjU&A23-zX0Qwr}O3=3N!p}jk2R#J32=p}Q8qmi0 z8>V|edw{+VIvO;3Kk|ca16>XJ4d_ld47#MUwzdZJFlaOU&C{v_wY9xKo$uGy zjs^W2=q%77psPX0fNlj{2znUwfrGF+=qsQt@Yl>vg7yR5b_o3jx*v27Xs-{@Z=jPv zw}Gw({S5RJ=o!$CA0mG%j1$m)p!a}|2Q34g19}YfVbJ;?AwMYnou$t}XM>&r-2>Xf zV;C zYnul;4s;#p0?;zht)Nw)Ek46|YlCE{@)pz)wb zL3e;U+akVzwgdeIbTDX-BghY$3%U^WKG5}`rJ#F2cY_`UtpRnmGmOq(AU|k7(7~Wj zfM$Un09_0kjVH4xp0qp}#03C4@eh*5|TIPYi1G*eE@f-Lp=wQ%8pf7^ffPM|ytRw0< z2EPOSHU^M!ZbchXj_rQBz5n_k~7Y*WuG-!5Btb1nkJY&E`eL7#(4jv`)j|Yuj zjJ}}+`J(y?=o;ztcURPl>RN*L+SRr6_qYrrxk20_$DsOAS3x1Lgm1)q5pYaVetf7O z--qN`!29cXp&vhq^ap?=#QXCP_v4go&Q2M|max_?9c&oQl|884^v*&4ouJP9G4Pa* z$qOPJFNtzIz=q)+^$@=KOmcTAcL^uFK3J&Uk%&;DAb^C$RG;JcxJUtRxvVN0^r8QAiJlG@rYT(HHjXr<~` zWvdrmwk;AO5I0a3!j4}~n2LQg1^8CrQ+3>tVdu{Su6)C;N7|D7YcX^sd^fJ0&uhAn zkG(8(ras$>avp~q4`Zconjb$5d}A2@p!_xGz)6odiN8pCToI(ldQp!DSTD%+T!Xkn zaxFBuJN>$3I5BrYhQ@{6X2&2FAYB#$Uj#fQ0KeMC*8|@IJWh6nF#U2T3Q`hdokTd%0dl zj^B>GfOi5OZk&$=J_C5Tex3#VDd1P=<>&g#Uk&_?bJV{T_`xtZ*|icj@BvRoY;!(= z#kp!Dd@14z)9xz+lWWvJYipm;^>D1SaS!n2z_E?>modbzC;b5QymR0af#(4a7pLX{ zpA9@*U$2w-d+YV14YxuC>gzJ##mFD3pFF^;fIkZSrJ($dC;e@3BJOuv7k*vQ4!8$+ zH@%EZfBwNTe`_5dD{$(I@z5aw`G3c?a{xA4T3q4Old7vb7@H#VJmTV{!R;(?_= zE}zOF|C^@C4VCMU`hFi=h&m@fQCl0zex%cS;90=Kt^4)>9|t_t{6P7S0?z>+;6r(S zn>exHECPNdWbO782;76DcEBG8{wmsH<1~(*^S8kZnO;wZ*D(utXW-#uqqX@!NsU=C(nG*7vpy4K%Q1$1cDtfj_6)A>wg1 z0^!4e-}H278+d@{03QMTTska=%=?fDw?;1oUI84(a(*3?{W?|x-vS(?%#UC1$E$&t z0`H*X6a07_&I>7jIGldpcpLDZdj6^Y{3*cCrGFmqbLqca)*otL;6a_Gz&E4*yY>3v zi;mmaIlCa2ulozHmm(&S(@mk=OgjWG? z2Yi^0Yimyf11<%4xOv(Gd>-&{{hb8-0pNr5^3fl(?WFoA0)G{FxV6wc;D>>O`1P0b zs|QKz0F(m{*Wc71+t9|&&x!q;vm=K$XZJe=Px0e%2@xEQ$+_}Awse;@DuQ; z0&fZYTyxPO$ZWk`fUZi z7&wN$Kfg8)9tJ)mO#L2YsR6zO_)7u#F^@dy*P#VMNsAY2Ydh&O!UVh?=m)$#@M0Zz z%(HDY9{4igE%o>x(ZpUa%mKdSrSP%&Vc=VVTY7%SS-bpgz}Mm46~#b1p2g0iFRI#6M22V-xZiI|^Vt@Jt=o&bOV|o<0V=yN+l1^S1;3BJfT+uEoK@ zz+VR*$_G8jGamI<0?)v;^Zt5%9UUTAk&PCkjJVgr`{4%QO@W8=!wTRnfrlHXKH%}d z!>vQ3v0?H8$F%6zPn*-@f%gHPpyN~gHu3_$<{bI6fcFFbpq}3$HVfQ-;4c9WH=k_) z{uuCZeNX}XS>XNk^0j+EKHwF=d+WG%1`v%Svaf)Ln@i$>9|IoF2fe_L0uSfIS-?L6 z9?D0!{lHHG59fm$fS&~(s((CaQw8v9;8XPWiL+^5xltV_A#>U5;nyrN5E=+PTpZ{E zd@S%#HXt2_0lxwGb-E6;Hx=QG$6_92=0hf&9hL)s0C=c&0y0YRu^9NBdL0h`*>fdu zAMn@oIX7aHz2>L}e%JQ!<0KA8-b;Wt(aYD)&l7-C{!lg`{ZfF>10Jd$J;3vTuK<27 z8?A&4J0v;~D zF9x0hJPoq8zc|FEl=5!?z5;k_9oP1(6~ONU9?k|n;71^zJbbNN9IWR5{55%P8$<$X-jVF~b>bLg-UxNBE!ZMvS{AvV2~e;@E+z(M@w zYc@IwU^wt_Hi~J3XBvSAoMp}S&+%P=&p$`~!+`HONBKFxKL9>f*UupqYTSO{U1rqQ z-VlHbM2lan-59+;YkKF`oi5#;|DYH z_XuN)Bl0=9#$4OTD8E3I(BLwxGH&WtVjAmZ<*w6*kZEkuQ;piS?ahnEqi6S;k&7JWj|4vCsP}}!c-etVv_ia)J?@&wRi?4bjC{#7 zUNA4?_QhOEHAhY|{vkAJOzoWaNYvvEpXlf=PhvF0_QF8|4|D}gyQ;#Wu>k4cG_M-V*n!>{Ohg7O|5m+_wo9!Jak!Xp;^!giEjy(CWicY4vY zWc2#^Z0$6nr4jUL7}$pLi@x_tFR6x6C2`y};g`n}6pypo zP_5*hGGDdiYhp#he}Zr+_Wu}3lKm1~V1h@aBuSbg=|oBMB%LSea!J=oS}JLoq?M9Z zNm?zb(c0iwoTMH}6C_QNG)2;hlIBS|PtxU*u9LJ>(lSXaC9RUQT2cdNN%V@7)FWwv zq)C#dNIFr{JW1zCx?IwAl9ozZCaI|9uYX2Y1?Iha(4an^_%V|Ta|;SR-Me?|(Ji5C z_d;g7-;tQuEulvznQY8~t2sEgaLVisqNvVtEZ;9fh8jwbN?witqg3+!r3ODpo{vzG z=IkMWof6+Gd7L)$>zL%#&~WlSA3S;}@g9;_@}qmMQc_L47<{8Y(*C3&TvgYTc?mW0IjN}g}IBCT5TNa$;)muc1d34|22s3k|Y{JU$LN9{y;&W5yWV5 zmAH@*-RKg;_mjNxpUIL}?VTfe+0Dkwl2`hCC;69TeUAa#BL^Zs{*AOV zBL$%3JB$*%s(-NLFOm84B(LJrHp$CsjF{0vP__3e$xAmkiX<6uk7`f)3pGCHNZupyhb6Dd ze?ju9{F9Pb(}@mdpvPs$PbReu&r zzNOS>rR1AQexu}7{Anl`D%~Z1mE=1~{#MDW_O6q>bOXbgD+HDOI!j*JZ=~c^f6kHo z09pPv$t!=@FZl$CpAEv}rU~Fdi9ap*29keS@=E_BlJ76^7J1@A&A&HDzMaHpOJ3P; zwd9q3pOd_@N0sE2{TkgS3R3N9Cwb|nMv3IR$@*TEyz2jI$*cMs#6@T|iUe*7rFk=Zf+a-e2;n{V9@H?SDh^iBg~Hp!}`x5P+OkjD?a{ z`aCIlRo{n_SMl&d>8L9I9LX#B=Or(f6;ca7+1Jj*v7Q-CDfgNe))+=>B^u+G;;ZE* ze!;)H@iQX88 zixnmrBy0ZxdUEp}eB4PZi5XpQ#FOQTea=ioOJ zsY8bv7s4u5>UBdo)g(@QkdP67Jq8fj+lc?Ii@f5>NmnDH)t&Aq(A5#G=D9y)y2u^B zk@#Zw5T;AqX-t>8XEI&pUdr@d_Y+K4xc4(%={~{q0k`9M%KwnNCDS$TK1|oTCo+A+ zJ)h}1_v1{TaBpGyqFHm{UxG!h=oO>A4jqZG=)lFS+gNRl? zH(j`#=r2u|ae7VDXPN$|sqrsL|E*~m^S?K(VtS@&b4vFlx%V?&>ds+$ultTol)l`( zis=gXCZ_kf-)DNi`v;~g-Syy>5uR1<4on|#4`TYDJA>(J_dl3EVsG7xm4iuk%H7vjMfGi>Ia8fQ;S6)7or6R_@|yXEq@7cJaiU z4Mg@%W&@GEv)O>M_qlW#svB$GYT+kgw*QRl4AXk%T|7%0iE;TEB+M`IVYGM-Q8Qwk z*}6Z5T|EN(X5MB*WI?z_4AYM(1IdaEeepZA5jm!{aIAo90^z8)s5=WxYit!3H3(!E zMBDrA{* z?(UnJCc1B7+Qa=Q)!h1W_p?lUy0f!7>DBH}n0npEm=1NHVtTDRm+3I~Y^KBAiV7AMH$G4?> z%vo=a+i>A|=WX|aX@9yE1Ru8g!V&%n@h9lfUz7XHjN9rDhm^To7WAWdR zaebrc3-EX?5q0DfAfJIE7|Z59$D+Fb6Qh>Q_!db*$5M)V5zPSA^& z_Jm%|HpJvX$*bPE2H!Z|=<1k?A65V#xo^6dSk2$cAVnX>O7rq~7W(;9Dd3-8=?cw% zp(Dy|VP5<`%J1>U!ljr#|_)S#Jm=n;-ZVDVwYlIU=Wd z8xm(y5hqETP#gecuuyW)0-d+Oo}Ku~cjOrnPsXg#YG7@8B)8Y@SEC z-?Dx}O;mx|6Hq@t+<3gkX$<$Q!F0;`$@fM)w)3a)KGvL3)N zVfcPP5BXs)JgM!c)?JNF0lx@ns~;Xy4EQVSHuM68DDwcIk8HT*WA^~gtN#=APV+%e zg7H}!FBc-_ACQZVk*yRxJ~FMqX#3+qpO9z?uv4Hw^ZnT3xBZWG&p=toRlvPU#&C{k z57;oR7H})l!<+;x%f?%-jDf9kg}XRgJPTpVv@R?WGUmMyTxAQ#+=cnHZGF?aXafp* z4(VG6BmWoL#!Q9}wQXWrAAEqMeE>fS5^zw@U1(ZYehh){0oK?8-D!~ zJvGP_(LlA51AfEn6hTOCefTSKM$mjf1;AYg(u7l9Hc5>N{IfQ%4}ID zveHkU3j=7%vgC`Vb^lr^*$q;IY{_6{S$vCW{gEuiCqQ&+U2(&i)E&ycW?G}*j;zAn zkb2OT)Rbk(9f$yvq~s<@?X)E|Wm$5!X>I$Dl>8J@)wX1?vMgQ>D`0YA73wv_j~C%x z#|`FUW78H3#0xQ(vt$oQ4YnmUWm&S)wB}Egk~c#t*Ot_jWl1a?jm1)OF{B=`C4-e^ zaV#r4QxvuBjo(1oBT%+bN`48cpKM7@S(g0Tw2n5Hl5R|t&GD||1}u5Z zv_6lQl9xm38e1}0Sr-4!w9a7B#L8wslzv7g*s@W3DMX$&t=>~az*z|)Eou!gh6ArP z8_`n87;u*toZ)Cf^+nsu=@GMj#hFVa1nN=ah79hDz}9Y(JAV_=boW2D6U}t5U^?0T z1k)+*SD9wHE171yzh!!h`wynKx*KD05z#KkeL2&q?i-li=FVrD?_SNc!2K%ILiZ<3 zXSjc7I?LT?2j#!r-HGWP?w(8+xV=mlx^HG$^j`OO zpnc*nb2nORzR(y8$XhYC8?86%(+m~W09rS~PNfKT*o5Wn5xmW)GJI6y%4qT73E+>K z^=Xw`kH8kR%53zK$;(WU{d3d0^d*tK4Jz~-K%Tbct5V=WR)Je0^UR~ZI? zYjz@e{{`vjXIGI`x&d<~gy;ulOu8_}e}X-k>mjQj`s*|joK2y3Z`5njm9WCaqmN@7 z;#$(6Ka$21<67pP7-t&o!6#6LTPXvV*I)+5tn1zwW{d_aSAct=G5ui(qe07e!2GKb zsU3YgH9W54g>X{WYgR^m)5u3bbEz<{ovqoi{W8FBSR*iuR{(n0hS?guIrlEhQHqr& zirWnMH4+&Fb&THMpG4-pR-Xw1eIE$@fe0?&;Ps{}^YXu~g62ZB(mM5k5cvaQ5!f?| zf;#qk7X^J{t=WRVVt~{(gs_sVMaQ?W>vSElnqF@hJpm02gnPe*g{A8o>vkOA(n9=3 zz^No6l-vRzb$w@@oGO%@3FL0OfZ=3TQAs&`-SxdSr9FBX_+v`O=$M9~;W}-N?QR$^ zBehH+B4g_*p8~FDS`YpM-`fTDO#p7v++(z!e-=V*O>5IV*s?;PUNgOkLZ~Ih3Rh}d z`lA?TJ(6(!{3AZbHX98acHN3qmaBtl{oW9}H|RYO0#~bIB;47wBE0w$7=R}NnoKa8 zq3im-$lc$xQtrgB+@LG(1az;0xh1^&G+KY#4}xB7Bii6+nIQ0Lpb+I1l3lAVfh1O~ zU+x!0z7NT->Pj13zbk>@ji&V;)S@2x9YRs)Q&vqBmY70?O~S&YnQ3$cCf5Hv!*Ty4 z_WTM0x0=@3RCHu0fgw}^&eIO8!{2_g1z2D1gT%aC2;2>U%}~P@;4AttT2{1#z~sRN z$lrQ729N6*(^@$L zAq3bA8@CG)=L@2^GAQZ7ncr|s2_+C+TUXqO;n4L8ghoS`O^|p+Ng097yU zA1O$LG?BN$w0@3e`Rw!nB&SO|PzTCLm=XwV!>47~j<5^d+>B_Vp$v=Y#RW^ag% z2qDVt5~5hye2>ktnE|mo!ief>Mmen9EXc2f>@&8!?R>iEL5Hg)~e zVU4Avk&u|6q{OV~q=Pxv(+;cWrHBS3G!p`MDIt@4LI`bgSV?20(8CaT+7@E}6hhk^ z*3U0Wp`8%eXAAKV6GHDgtYwH>T-`AU{A3HUnS@Zo2x}1rEDO0Wh7s@y|KS%N7h&DGSIC%AC@KbT*(y2>bEQXEUIZ1Y(Ch%L3*j^!8cxP@BCL1w zWd0$*hWYc;xt*&p!n%BcZ1rSdIewfD?p$*ttQF`)4rPmgE%D=Y+~!&oVXeh-l-giE z1#F`qr}H+~y%E;(nG)X%Y@Z*e12@;|2&@0sVoETN0Xyl(>BPiptbQQMn9D@np%hLesdT{k+d z88|s7jm+=xQLTgwfoC|a+qOy7>$S#06>sSSbdKqo=CszH5p|fIfh7=5m56gr*KDUX z_Y0Z-8el2@{G$=cU5lMo)<_v%ZUI)P^2?CNLMxnBpL$a0UI?tQg+$0>p*2p6X0OSp z+uRI+9k!4Nc`Wp_)7m#&3VjTLqqdNUX02c^*LJ6M!Ix6#ECgIwVF|;DFw8>xoz{s$ zDbyAMy#j=|6GTrqS^N{H^`s@mM?!RxEpE?VhLHT$Y2_`Hl5-$+cYvf6s&QIr$EDC? z5ZGi3@lX&g=87GW*2X9)`3|H$v?aO4F+-^ruZ*-3C&O+h0sd+Wh*GxGdS+Op)o_d~ zrD0oaHu2U?!a}!4TIp^n)Dr>&Z6PtAu+Z{ID*}$k-E zAiBmD*X+iUrIFUuj#6?nq;>>I8cr748EJhOD}_FWz;Rnhvl~l(9%+3yL`ssv4e%B% z7M?O09^$$n%38is&TH`yxY8Elpskh3;%QOV>?@`C-yu3BP+Ti`PLwqOzmmgNnh&WJ zwj`G+{E*AMKgw!!mDKY&NWEECQa38+c{a*AJ4fdE0`jK=^Jtc3@$FGo0_GD|rUBfg zCEmgmtc)0gEcro{H7i9H+zV2}10{p)@okj#dS_`5+Rx3j#pz0JwvIjmLl?9pgF2kM zX*Jx|vS$7vYk3rcFWA|*0{Sq7WKYZbe7dZl0#XNUNvc2!4YjOxr=-yLNd6;0$YjYF z_c2sF-m=nnLa_@v7{-Novk?sEkO9C7E$h}2snlh_ybAYQUxqXmFR?6_LyAv===?C^ z{@k*j^_JBVlR9_CT4Z`TL`JOxxw7q+l>x(Xp7$VsG)x{@#RrzP|9dHZ7NYdW_SKt$SXI?}6x%5aOCcvRbLp)~8cso*KwE!ZJs++}{fSUQx9CmT0T*Co)eL z$PWpThnphC3D;8?ZT)?*%tL=#Z+3`0{{60~XI`{r)yh08A^$>%JREiCL)ze>=q49p z;lU=WfIOW~i}u)(CP$sFm(hal>uBo@Y%@vx7f8l+Qquk|_gk#%AaeU}qpd!-iyAsX zd{Bri{(kJ*f~MCK(bj0}x2Tr!5YMr*_yzf%qw7qxHM2-A?iN96ElCbSHnAtSl`>-J z9;PeGWnJ(#z)cX_W*17;7|uMbaa?gOYpv5TxS9_k@R=$Pf9mU56wtzD-Gir782<&> znIOEQ%j)z7PE#RkHbvZOfwv3+udhM=OI_AQL&cGi*%Mel!bxA0k27A^0GBl)O19?) zV7DsVzu)KKF2#qttao3R;zbZ$WsB25(j}+5tc4h`Y>H`hq5n$v#I?5KhHV$-gD>PJ9lQ>%h-ldmJr4=cE;G3 zvF{;M(qQBe^U(YF*)QE5?W-{b#&f1Y#Bof-OmfB*Y>o%1a3 z_viDh=XsuU&gVYIs*VSzICSL~NL`p4lk5-iEJJkG0IQ|P^inUVcxRIR0UlcmeITe~ zFQyyvVlnBhB>PRQJ%!18(EB`Qfz0xiTGH_(doo%^n47`c?J)~vR+#@J+36UYr&)I7mG>dL-u+sRD@XR$iDNuL*EAKzKiLGyjV<{7_vX!<}g12 z>wAw`AhUd>mNYwLpBm~gL&!^M92a#1VLleJpPAz@>w(q5V;0S<(6@x_`nWlk`Wgo6 z#Ea>MPnfTT>`E~05awdAR(Z?4cNn)S7sgg5#oYAj}eBdvptj*%+*j9+Tw` zCV5OLDNow^A*oT=u8UQbm^0i7)&m}s#d1jZh3)BRC?P!y!hVnBsdLsJv~)VD7}>|9QV2*!AotjVPylg-k`Rx)Vh%ZrW#m zLP?K+e~KwILhb3HS03eE{KB-$%q)C@H3$tMHj`0r&)1k0(`to(LcBbMPOD#9l8H8o z8Ae*;VyOW1yQ#G7l4740Cb4Qjf>mzD{F2r@ZB7?h@FU_{9OigtgFZ!$eqNo{ zK@m$)1d^Cc0k-bkKvv zsw}Om6;pzK2HW$Wdueegh(FeuckgfO;m`aQ*#!Yk8PVM*!F8M&x z#Co_&)q83KMQ)x1dovDm6O)P;#^E6Zph4sE zrx^JG|JJrT>}!h>_=gAlm72q4#Z<40uQTH?cQ64T|E}V{KHzUVOADw@z`7Hc4Bo;F zP7L^8#Lzt)vEyAty+rX__(*(GAhZ*#Ie_je3|H8VTR{JmK&S-Pevbj$1@BJ zPsVjFUI%!PgvlC1TW&dvmS+w>Mf_JDCVw;X?=)jSX-S2oY#gH6Sfz@ibNXKmOB$BH zCe{(mnZG-3XQ|8x&4sFr#@`|z{<+a5kc1JPN*H;xn#TkGm4NaIZN0u6wOzJQ&d_aAOoVh4==Y!t)oW(9=y}y!n4lBi3p& z%n^FpxzkauRd~q9f^tk_!0)rPCowWGS|v_0Jj6yH26w4FX@t(&ROk>17P~;EI(P+# z&ndXBq=!`aoTwPov%pYPsMh{n*qHj(LA=XXVU8ZF)rM2hbU{_j!|2fhbE6t>Dm|q9 zrAkp{fXMp~L%vuf5_Dgr8tl5GUGwp9tEhQ0sxeKY|AmRndXvkK8EP8-y z1h92sf($9uO}la@!=Qu=DX?=XQ$dF#C6SE3k!cTZ1O-zeJl9ij0GV^fl%}T5ud7po zS`ETlmt<6^hP8};t{Hg-lhF%^-t9p-bD+RK-%MMDG>kQh#wzHOX}sWO#ry|wVX^$^ z8#jq36K!*y_{N)FGc9JXoFK8~d$|qv@#f$Ih@LFbVMJdeKH8ojdZGkuL=P3;tUgz+ zLi8jFq#)X9Yh&LzM30r|Vu&6gzTpe)u}0ZtdB|(EKqX#it&%ga0QEm-S89TnruRON znc^io2lZ8fem{&rUi|@Pz-aAVILudB+J}{3du?+vrto(Vf7->AjNEeJ*7%;?>@C|Y z{vcdj%71~RpxHb~B{kNw0uS3}>6IET4JgxtTYpRGlXgUOS*_QR{gDm^EhDrH$|6V5 zar~!kI}F1hbrocXQ2u?Y&lc<}+kPRA*8qr~>q3e?IXSc6PP-Hn2{B%aowMz{$MFUX z5zl*Kr>Hh^vOkji&9-+BhLVE-|Kk!2pA`7KZ9nijIMArR1@;s1GnDm7iTy$Q1J*zB zgMX}S0l)K?4?R9-Fc{Mb9E|^aRun z2-8Vw!fNm=0?#ef8C~u{o<$%Vz%v45rt1sbUt9HY%_#tAd z$rPot{U<6#uV`n^`Nl97cPuIpK^0b$W-cJ`_Ls<>k#Q39a!I>a2z5PuvHkS4$um9hb!vB#>H#GIqZCT@73TpiaSIc4W~tGQxZc>$5u$ zd%ugQUIHJ+a?~DY-g?$Bo&vPZgZmSnrRv~bYjXSy*1#TeH4!6J4G~GSMzs4UZCZ(Z zr(yakY0rvoY>rhMYcQ9TDvY*oGxy{gMlz5X4wLTz9Atsn^KbYOTgOGzxCDHcdCO(E zfdbUsgC`{5rRK`=SpNbV@4+`E;QP%-f5!S3(7lCVB`U5;Mb>t1zyR-pPS;Nw&;ohx zTl^CgE5zc|_!_C$ab^F2$zdAwzmLe1l$y=NG+a{I$MB?ung12g--H(tmTSRI!&6UG zN{I0__{7sL3oEz#HL*$#B5`Pe-uGhkw=-d7JrWND5#64UBvnD6N`MAp0f6XhT}Uls zS{jFe+)r3AO$WBX!)0x(@mk7$=P4}1fNd;Rhd=vS5L)Uxq^bX*J^rZVVx@nNsu=IIZ5}CQ?=|fd^GBcK;B$ zTESb&-Zxz<_@S_@s1gN|l|Y3jk=_wyuR=`_E7P)2QXbvtvnU_TFBF!5MlF!CahQ+o zL2;E)2U7YS?m9Mc{j!?Lb6z+8_&d7W+r$zli7zPCLzf-uG-QHzjt|Ip0N zrd=2MW`VWr5=?0$o$_GQ4&cF>dJ43i7gL@5-2n5ulSt$o$9G3xJ+2tsyDKVO}_nP)hpF?T^LMM+T^`%M2 zVSu>YAq@v%yhmc5j0nvT>~Br`vld8d9>DuNg7gHosKY94*&`nSYXcb1dn{2?p2o8F zqpBHiOU2sGu5Q^A@6kl{5!j!(5=MFcRn=arY(8q!ft^jyTNMnY0++ z+0Cqu=!;CWDv(-4rRQt3tu-V?iEuk0ojuv|G|jUgS6QE6b{5k-yDJP0k7|yZ1maXr zReAnT)n2EvKljM}U^<7}1aj2FI6Y3Xc#>7Bj8vajmn;12_P+{4AF&R%cX zuOOf5Ma1tX#pMCUwO;k(3UQtAX|KYVCQ4L=ABr5srukY4G^$OSrDZ$)1m9Tg;94jG9=#DdPw_t~!vb@HAE zLJwDswy?9u`s}Gwot%yZHo;Y*E$Hl3DpOG2J+ zwe2N7JMBCDU|YQf?45+X;P=9itr*&ab@L6dA3b@o4YMEh+2?YB1+m(Q;m}o}I|+@) z>}P#;eI%f&0<7l|jzFIwW;6BypI!TB5IO?v<`RrDBThl#t^QZsp=cDKn_XDRr6;NQ zNVJpvwhuj?1C3e=)}w`)lALCi^VQY>w+VDIxcNpLQ|n+s^g-E`}ew73{IFCNW)o|Epl<)BXm1& zuY$rI4cNu|I?T0TZM_t8@@-(A2-v4@&_k8^Hdr5%>0PJt+}*f3ydTp*pbJJ2=Jp>@ zbal!)?doHg4ZaUN^o>SKRYyb|#ZaOeu+0?{bLKXAmJ@}I-B zAX9TU-~&7kqa4n5|JYj{&LrS-3UQPWD=e&m)Y5JH-~l`a0b#vIk|mU^t~Kd0+g^bs z!Al?}R*S$}gTs59 zSTrGNqB0%oBcXA2H`F?ZY_%UE|G^=JVxVAJl8ko`BrkgPJAvUv9qKOqp0^l8y!X7*u=r_#h;BH{4^f4RK1GiAo>%m`?|CbHVHh_6y~!2u z-t+!a2RESxu^?i{8SYKHjZ1AB`zn)s=X!I)#!R?2h=O)n&UH-lmm! zzxtoM5zpDX#0S-*%w6BL7!xYzB*(z5_c;8)%2$Q`2t+@B0ZZqB`X%TawTvS*yel>w-w2T!21+&@&FZTB0824?XF03YFTBn8cxYya|*!~aCT(EzmHg%uMu9#J!q*UBqWbMA9iXQx5no|Dz}))i<{%=Ig6tX6{Z-W zE{HI!D|&<<25w!^GrUaPUV7)cD+Y$QNO*Yopt#qDzZ7>=_&nTO)k7a*4(@^WePbF% zn^FEBhr>|pHKf!8k!^99DY%9dU+Np>dSlA3)~;4bL@N=fHr5XRg?~^K#|`XQ#NOly z3`UezTJ41WC6o$h3GfvjN3P$CEmw@BBn-FJ7gu09kE=V8beU$w7Q$ghpHNF)M?}X` zEO=6_Z}AXkXmMW1R*k0Ns%RmrMze6XxXr^owldrzToWa-YUG9+i`z2XTijOR@#3}) zFA}#+_+fF|hIfhEF8q$TUBfquzHZ?!5$-$v8*G)-HhEl6^j_&4H3#`hJgI7a6)8Uz zamG#M(At;(VaDeo^pr|RsOD{vxN+l+L1omepCNyv#|ZTj;7g4}w9#}&qLvswjEo!R zp~6d?jQmXr8Ph)2W15U(rwWW?r>oPXM@xTNy&a{S<`11{WR0|*!ob)as!L$Ot>|%( z-d1X5{C@~ySw!e@kgnDs$ozqd??{9m2kB(3MOo4?lwL!G9tUY>^@I#tb_Nk?Vx5C# zR%xX3Ba|#BLXRWU(7FJbvxwM2gdQXI#W>7G1FSKJbPnDkB011VU+YF7O!y2D$wBPN z3bAI^$d!CozGSSgY#j#O`nfoq8H}{X`?U%X<4JExpc_Hkt~u-8u$@DRS3)Ez@Ko z-n9icDr*eJJ!bPmPe?=Sl{FaAkVf9L?f^pS5Kkts6N6}Qx3ZqY1kL>2;t6SJm$F_4M5+4{Qo}kx z>JMc-yIM;KNoi;}+7A$= zzDY<8=2~T%vX0HxQjvacS%>XI`vwG`qO5W6Y0)c*Q->N)yvg|MZ!&@ll(n$Eme2F# zS#k%TqpTgM3yO{P z(~wVDH33noMM5eG559tBlyx|$rG~gtj;P@2$|@7mqO)94r~hqy9yz_-v|cZ!O+{C@ z@-pJR3mUJhK*ov(>imXR@jV?t`~v2nbz_q8tRu&C{TOT+UP(N6AJfkg~IWs z_0#8C>du5hfyS8D7Y?*Op-`Y8!LPEEiRwD=cvw%WE zGfWFTPNa$t@QPd^56~*p8jpK+-qU9h(nS{N0n-}lK%EHbMiFS4Y0Yq;5ebDM3_QVS zO>2^q);w3CqgC)trj>~~hY7B8wK}Q=f6BCQ=Oy?)SGChduP=xGgJ{0XHGZaue!&l* zH7aO4Fwn`hqhIj7rd0>iEz_?|oXzj(&o~PGUzpbRP8x4ZoE75aU+_;&YbHiH%8w|b zU+|AjYd$KL_`D+ee=Z6A%Cd^D(D=F{`UU^Tv}!x`v#*GL!T&I=%1-^9DWbm;UbzIz zSXQSKT7O_r;rt7pZdrSeYrHaXwyIM*LFx#?TU99mDMf3|^ z+p_9A_`D+e1+QUQqwdu5>x$@~z>E47pS7x*9%c5p`i+1!N+wBPy%5L5lx6*U6Se~G+i`K@JjwNwfg;!c7BUFo;h0HRbi zLi8Acj=Y9j`mMiy(^72`QUW#iTY=xT)R2VK0bKIIUVf{=IxTfeLQ0@+eybHACUIXv z>f8)SjqqEo4{E7xu9TBa!H4>-UN9A>=uubHsh1Js@{QnBzjfEwTK=y>@>)p~A>HV= zE?|bBlFT7aSw)Fc>aWitCwKa-YvyQ8El4VGSkLl8|XWXuSxPQU*{SYQl4#X z!Zps~rsQ9uxI)_Iw?ep}S;|@@6)3LYTm05E;8fDJkP;)X_c~f&k^IIzcF~OY)sT5Rs@SNY;e67BFI+~CY=&av* z(Sd$QNCihjN(HQ;7>anS6&dQ3&aKvf7aQ6umiCjVe8U=1vxo1tYwN}!a0 zbuA#02PLG&qS1qu1J?bmwbYb^lt7mStVaM*YH31hAM3DTz}h-ZOFf;C5~yClT7uhc zN*zc@rLs0U1}t9&cUC1j@07)}b{rwS4#*r>su;f)QdcYF`p1CP2RAj8Qp4R+ z%j1NA;NJzTea=l!1>#a_jlYK(GU&6dryFZ|?#iP_1bu@ixM5pgHqo_~@5yU?)0L1f zVOxh6Y58fcyb%znm~EW|#1!v$MU6n2zae#nZN2s%Ewv>fB~V4%`t5Qpb9fLSlaPXIybH4KbAZb)iZ0cP=x4G9BL%e zP;22!n5a@qh~TA7RQ<=a`1^@&j`qPhaB3_r4?6JydkMbAXF>}ov2MKr&nrpB@w zJQLNDs3zv6i3fQms%&S^M3tGYv%e>b3lr7P&<*c|fS9O~CU0$KAf}ph4xJHJiu&pd zQk$8z6Yo~vEGn>x0`b>CC?FtVBV!-hhbF3X#}qJ8opf!&MD=F)Jrh+1JQGz0JQLOJ zxDPFkh%z|LTUd10M0F@Sb}hsQSJR$0Tb13qws!}HJD3^YoeOp8dh=8v5k7}m9)ipb%9v}w{>qI_B|I-4<+Ec z%&nF14WKt=zj-%mwhEvIgS-hNPetS`N^N0co{4HhtoWGu2LP=myo<1BqAJ${<2@7A?n#>X z1|ko80-lL#GCI}gh(1e5lJZPc@B0OsN8|5TI0RDrn3iXvx@Iq~0ASTUoUhIu944w2 zs^bX=ux^ELt;91?t%he!!$BDDk=}g6Qvws!EqIbY7uXUHm&*4{RR2LH*8;gm0! zQ<$iZZHe{=;kZX)Nt8~>HBsFh#2?~8_|qlnrt(Zw=c0EcOjP~3cvXj(3b>xG#Gxxl zSAc7x`YU=yF0k$%PKhEWs>eQq@JKKwcr4K(uV;Dni-{`R)d+EnZ1w#qZKB$Hier8n zgrL}=G9Th$5yZm|B%XZN^9($lsV8Bgx(QF>d9(c;#EY1yHbn0rlr$EQygJt=syAc& zVZ3Le%7S?&s>3k7q(h=7rRXVeI?RffH}#&0D!YG(T+c+c+2>jTzp7Y3R#b@s$%<#9 zIs#KSv6udZ?wP2LIf6I9Abo(td=EKEn5h1Uz_*D0-G$W0#61&Lxv&U&CaO(t2RsgA z9u85a=ySvhnW!>e+iJo@b!-H$y80q!Y+N^qWXX%{56p8iHfXeqT2OlByLATg>EkgQ6V@X4GTAo=o7biRz8dJNRqB-bmoCiRw?da<^|h}m0;`t5T@%$iEeCH6tfPl}CaP_kBkduGA4807A_GXmMD++C zPR<5+cOin({p!`n(IzlaZM7Aw$HCa>vJBZBk|wHyOeYJk13O4uH-T%S`d)WEjH@qz zee2<_iRzgJP(1;C7)OB&dM2v*?6IziYBG8(iK;G6&5KC5CaU8+37DvUiXnkSH5{k$ zlwj_hN^nh7^It*yJb-r>CO9UlH5=+wp8)zS8HsvyOjP$B(y6=w^u5A5JQLL}e>r(S z2f{C|nuLk!=f#xHY05;besMVUC?=>dQ5}Y2N!e=w%O))jLL|jvB}`P`!|GG{CgUL>4qa}}83_~Bif^OdDgmtS5)vk=Rq>F) z%td^67t<>Qef_#7s()btY>otDLLpYdM78E@s96ATxkumv(P?4VMD^(y)I1Hws~$^= zn5ZMqM70^l74sNqpLtZW49`Th)4O_DFwcYFyU{6m!bJ6aPhEdzIbbziT&hm#c6Lov zKj7}FoK)I_)$dYF*F^Pxzq68>0M@N!dV@hB6V<&XHE#_l1r}V6iE4C?Mt2akrH8vF zs_)?`q4_rAk5jn}6I?TTCaO=5a0>Mk@beyrx%W&|N5LjZij$7HrwR_OM=Dx~o{4Jt z_wg76gglQVOQ^yosvVFfzI9nTJdN@Ea_W1yg%h(w-E)#>zwYn}%sip7oa8PJat3Zx^C6CyityG~Qs z=`g%BYe1kS4l#x0Fs12<{b$4!*1Mk(b5ngkb35)h>Mg_|NORMUHz&+ZMbjdKObx8RkPn+vDafJ758U=#4I<#J<0`i0+A- z%P<oNSEBp|F$?s+5|2(yK@+p8z69f^!mJv{a2Mv^8#kZ36}I6mFz6vy#c-Il zs3h_OI%vv}kbfEOzN{+{Uz3<*u=Oy^8UAPZd- zI~})kS^;|l@$b2quBU7vd>gm_9*z|tuwOh}>PhdO@Jrlo%=tBZ3!bCm(8_&MJAcRR z{+&qFILPW}=Ox18)Ld1ylc@V(KxS6*E$~%D7pG@u> z!}ioAq)*z|*rszzX%+~~aLeAj zK=rVmjK*1*7eT37km6O3v{S3aC`mB9z~rNb&JS{-(t0cA+3+1^jQ?^o%-;; z-smpjS515OUPsg0AiU?23}1(9fgdpK3YLTOefcj%@V8C-2=1d;W|e|MmByj7D+Tsn zKS~b(M&s!#rHjqdOnehwCB6wiM|JrF zv;E@F@Nh>x3sQq5AKE^zHAc-&)@KmC4$AdfZ_KpU5!=!#bsA(ZHc%WxfO$swANY^X z`(8ka57GbckJi`OybB8MxBQEK#DhKvd;8oaYJla|d)!Ig1Z}~UoVWG>ER(!2B{d);tMn23G)4!&^W|qNpU!+z!Tqn}>25+e+Bapui z7e$uo&wX2uW;syc4Q)=r_W!C2)_aq#g;^IT!nK(s!ip){w*rk&NoH5&zXq!gw!?Zi z5oxfluR5(}1P0Uq5e?R-y(WHraZ3NS3In|`7_h<4U5AA+Dm(o)r#K9FSG(-TXas(3 zhSYld{11PnQyWM!w?<>O{^#zAYQ8d%$j`VCN_^*^H~`-tz%V_NI^M*U=M@cq3_N5Q z@y`BcFJpi}HXZ>*T9g5`2G@fTc&Q(s1Nqimi(hu;$G< zNSzatG(!)Lzw{Y_6(|uaHqF*pD-etHlmFg?D~mxvBjvw+gMOMZ(oIQL&z;3- zRWO`|VJR@WFKYig%l}n%{6`$*%{aV%>}}_xuU4rmIn_p$7=ib{(1~?jq-*0{H!+WB z1P=TT4toB%R+>|M?nNcy7@Md&h6-%N8Q9QH_xvi)8wRmPP#|^Z5skoltbNTXKL2IT zfO|7Ip2q*#LyW-EwK|jaYwBu$0rLM})n4r}oyl9%bhUp31(L}`wFj2;L`|pq{QXeV ztf0&1fx{&m1KudAaO3vidgi7R@wPZIlgECo-9~mn{nl(&+xyC z>528#0~Bw)>s4Ojmc|)2U+S()&=vy}%d}85qXhr`D*AbhZmRDwqEhUTn;HX>nt0e$ zyvde}x4=o)@CtOw^fcw~ov*VTUEs({d;iZ(Ut8Y8YJ9{0^6M~kpeVZvEB+GIXvBU) zjV2HEFS!GMXPb%F{1kBOU0+Rdx#+QQ0*r?+7QVO)_W~d zU7qs$f5qs@%Gl>>W56q{e`{qt1;!ezKyGA?V4M;AgH3U}|Hx&!DZVRMkc5O0hG?$Ok>+cQB1}mN`WtnDWRnCy!c$7gSP#gDl;Zvr+ zXNDF#Ofh$v?p(9G*#5WsmrvF0&+S0GYc|nij98-=WNw~*r(rZhKPj^aJoZQF9ow*u zG-8`^A)|M!Tca)_C%)4=owh}@i{nY_q=~Ko$P^3hB?4ab?L+sX@gz`gc z813MuZoNz4!wV%(FzTd1yjW*Uyr|C;OvN2>5-sdiz8+fY^uugOk&?(`3Oc&iX%iKi zXb@eOhgp}m`*Ygqx@=VF-H7#P9o_DK8@IizqromOQ9bk-v4$90BlG;Fv!G|a zVJvfbytES;Ph99E8G&lJqpY^U^oMUiw?L17g<|m#Uba06kNf3sMaT%mF zjC2`UD!d7dzP($Z6I2TGx!cIrW#F%pG52mbDmzpkaZf7=HB1@Q6_Ljv{xJ^o@(s{E zP@o+D+AtmiBlf(Ds7>%0o77cHA=BDk^_I?eCFt`Oy8aRv!}!R-ta%D7jtF`uO(Vov zr@>KN{i>sN5Zzm5A*=lUa1vVGD*r+F&Zp^q8h%pT&%(RK{XG1MxL<^gO~k(pmx0^# zno&0z<=?Z0W*Yd=Ha5XQCgfkh`mexN=3n6%J8Fjs#o&6_EOj|XjNi1ew)h|3iQWgH=Uqe$%yjy(Mp!XfFZrux;E@?F*$>H~ zr(g;_tAq2s|IH6I=fb5pQX_x)AIIfD@yk(5T93SnWJMUUCs;Le?3Zyj#fWC)B!TQy z`JhH`p!!3Mj$O_+SYR99YTC7=O8v(EfPi&}T{A`3*nC%s*0fm-zkY;aEwP*R(2}u3 z_-BxHuU+A99p2*d3$$&$53Ys!)CS?^_hKc}VF6w@b+!MjjU7Ni{uGB<6IJLSJ?uN~ z!)-WY(d7kE4Fzsb!TxqDOr!iZPz4v(Ppaj^?y1d7%lDDW%ta|u2ih;=Q89U{9Zo$c z&~xi~HHr0Fx{JDaJwrTGVaRfe1S zrjE25{e}l@=$MLTVEZV*f+_mcySQNVOSIG`<)zUob;gC7I>&yX44z+t@|!0hIw)n7 zp)pJ9gLdZETA@ls6_&su1u+`6A-vbl!O%*6O(69=RE9zsDMP%fGLEAAs!~}Ye!1F$ z`%g@}FF9_lxDI!No4Xc~v91_YOXX*n)%1r*?t*IlN#T}%KM&-Z%I&wo^oOwnSWupf z2C2IMjVzOa`H^E}g9i9kcd5~3`ptH(&>m6X$iU=nTqN;S#;p7D?04uA9P)ZOsY z_@z`%c5(PKK1UO&Qa43MqYjcvbOJCXcMXISbtUGWQ-UZ-tJ7gVO8>@Me?JU}8=~KZ z&sk|~9K7GGia|Ae!76=ZD-^DSwhcJUBrYVf1+#p1$;O7U2hnf2kctu)`h z;%b&>xg~{RH+Ol!ytLCi&q%tU7B+o{M2FobI#x4AvZ#iHoH&4o%h%)XVzp z9o?{|gSct|tSxcLnZ_$(KfA72@gfa11Q@p@5L|B(;=6{4RP)*Qk8zaD1!0j(GBjSt zXB)1PwZJyJxTAz-N#TY*`_u)eSZ{#v9!V^gqR%MLC+gwftcDM;Y`v~UpqbC+>ukyU z-{9D&dYw0s@C{A}sin_;tg2Ih3LsobQbMhdrrY6mKD#b@i)d;KLU)o_3p#Dz%yf|Q zQ15LVO=Cc~k)#5e_Dlz5l9AFGL5>%LG!gMD=l{`x$eDT&*jg7a(sM@H zN-KF8guN~)(R0GUMajp&zIO2a0AU14tSyJ+_MFqjom!X$!lELY+@7=PHb>K15H=Ulb~Qf+s|QgDILx!VQGPv(_OMU%###We zHC;sgBCs=8ZWxWl6rj#7TzIbh6I|ual@kwWo|*{q3<~)60H)8IE9ExFoh#+7hdWmq zQ&3N!s%LQ86kx#=eg9>yydC`^hMKt?hZc}BP|BMt zN3PWhRa1~!lE{L1bLBk?HGCD2As$+ZyVa+zF=zgPeV!1z5{LJMTdZ*y>ugLXIhBOv zF1ym4Z$$Qkud&?~SRY&@%UEasw}forP2h|WKUI*iqY287xtVuboTF2kYWFbW8P0XW zL*eE=k4SfpUf&!^AY6AP6v)R5+&TI@?iskTpxkWgJ5G0wehB*%6r7`HEG|4pKZXY* zf;)3`>L-Qg=yx$#6r7{^U4YO-NXwn0`FR0%E^dKVaOdJS@MpARTVpQ%l>*LOycQa~ zTR0=JJ9w-4rXEpSV$tNy#ebs96qt)|#9X85pynFlFx%kDON^*vXP|o{x}OUvzOzcq z#Z@qwc_V7W0h*|0f<2cKy@c$}#bro#=VJS$=BN!IZt=+8h+6D%7~Ml$y#?$Y;*v9O zL|unPmfTo>1MD{!FEXNzzz`xz(jLMC5gd*ZnX54uR{}0dY6ENP;zdT(*@K*7^#LKD zBo<52ml#n~ST=Vq{^4yW*#+P%r3CY?CA<;!+b^87H-fO8q=Z^;F764E6yO~YP8QMR zj;KdpaWwr#0$RGDCU-<#hG#SKzLEa|}bd()#}&T zx*IKgxIj1JNLHX5l`~;rax)aqr1Gh60`!)2$#>yf2#8+oLTV0iZ(?3Dy+Aj5e}yKh zePF*uiG@OTyU`qy-ELF`H&W!NpK$uaBYWNGlPA#v5LdA^SheENIrF+v7vOU1Ul&+& z7cbI{?%D4s=?B8qE-5iFX8;!^Q-Iy(;zhdA6RVtJtpec*l2|N7U!ogLVcFbnbn1wc z?AzcRrvz(NOL*Pr{ZE{Q@;^sA$(IS3s{Dxk^j zMu*>lZ3A;L41`fG$tX{YkMJ*6qp>J}bfZGAov{%$nx@|SF$iLorX96=M>{*Hj7`w9 zmAbOuFkGaEy{e^Q96;>5E~0V-c4p}Xn8d#X^pgu0o~7l{pF2zMYOHyx6xMMSahR>4 zO3~-d((=60ou%b@sXI&Gjs;R}P*q=?hI-QUd9$=Uxprr1yEFRQJ_sxTWjO^{Fh$>g znWbMxweA4rfF~e2DCN!4+5NRbbsDi>lE{L1v$UG4VFMK$z@gDf{KGD0>6>uJRtK>y zad^-9WR_;EV`D2hm4wC6wi5rd3)xRG=UoTZjEiI$>)6{SWW{<*W+Zun7~;RRGj7X9 z`7s;wB?M>XEhDr$(Q!X>T>gnU_bLS3S^6mE0=^YIhNSfWx7}Hq`>p-VSU%sClXoXQ zsg^VAI(O1-(L-fccJ8EKOmo7{EZygz6L#*TjbC)wy_4o&qeHEcb$6ELKdjwZ`UWKL z&eAu+pRuY0%X(9EB?X*Wx;-=`>Ll?8$yOiyt%uhy*A*CE*#-rM*QZWH;Rn$65e~CG z`buJWt+xZ+8`0-oNcAA@4X@8nGZM3O`-YmRDy@b6KMu36klo>xj|zS6@VfK`%~3r- z?B|ia;dSsVOoc@OabAxBAVRc_1sEF(<%_2D5A+7UT=L0Pu!TmD@Bahp01b8T|CH#3VTclWZFNKK zb0rFuN%1YEobYD!6`iZ_dpcLYyAp*a8O8VPaxwysr|2{$V~FGoTkQ#_9RDT}TaDqM z_;UY3%u^gCI#VE18AcoQ66X!ehaW@f3ZH*$SkYmuM2Ymxt2mv~7M z{IoT0OHI25Qmq-ZKRJoEG6<#fJ`N!tGp{8dW7 zPyat(!GA^BZS<>~;jbEJLZSB1lk`s`L{uwr8>%YlXm$9nEX55)lKRevzeXA6Ice~< z@YgF=lKkucfImA{k^W>ncZbR zHk|&Ezro)megplp=x<+4(#<~se+QlJf3AUlxz0}sTmf|+C?lMu)!<*L{e3=we@$t| zZ&AUd!OaldTYe{Db)5isO=CVYGzu~(KS%7SA2z}`=XxeKAOU9O_F}W>{|D+ zR90_N$uO2VN77mR!NKgN*18^e;REq#rBWELnt%*+xa(XkuKIRtB~|lZYo`4KYAkF#1D~QLCNm! zKMj#EZLC9F;e^?_Lwuf+w5%H5j@z+hL?rb?-82XlD@8Dy;GHkx=CGu0$Tv{(hNX1l zS?CoFOFIo#9sV-XNEux>V9n4d9DE4E(Rl+gx~4{`&4~Vqrf*cd_!S5Qjee}yr@-MfcL1_%(rc&iF@&F0;pd<)d>O9LnyL0a{9&tRs{cF+ zS<~k~QVtpa39OoC>b)%)mHOb%{D>C@oN^7re0BJoD%ZH=J_s9OzTAt?OGe69nGvR! z16=WBgj?ghRRzWk13K6&Mwg6ykCC~Uf+JGc_%|_Do>pew!`M-xZE+&@e#VYXV}m~G z#l|lmi`b@Cv=S=g5Tg_29gip_C)Sd&P4QJ?_CPDjE_Ie%=0;D1@pBlJvS*u7_FQu# zq9rSF`+G!RZKbeFm18uM*Lw}eN6+fLeAb=nw>8D5_o(n zZb`D!b)oWHf)VeMO0~L1#xa_SDe~y3PWe|Iy1Y`MbIZ;%nDEIsg{80G=!1>PkB77;UVp^2r z6yHTBa3k{oRnLrbhNxc{+OC%4Hbp%>U zpkMSDhNqm?B^qK-9TIJXsl}=lGpRAW~Jc-X*K>n5(Jrc@|ie^yqk&ES`+;acXEg z6Ic(ep~SPU2Jy+5s}p15@wF`1Z#sVsNG(v2=gR{7M`K-F%!nu7g6KiIp2mCHMX^&^ zht7hr+>Gpn%gVZ&EEys-A^uAv5aO1!{YHZ98&30m#AX<-)gK}zO(fC`8exu8fyfH5 zUN<8aTqg1RC7AIDb2>q*DuS7#Ti2jUS09qzF!|bj>c(fFffG@fwjzCxf!RYAa2t*_hiQZTb zfn*7!Mwg62AS!`)v=PS7mUshDbv^=eu#XEI;KfS)@~>a?RPrK^b5 zU}T!pfDaV;(U*{qZ!HPDpKj_UBuG<>PwG)$d93ryVz^Ju-7Oj1Tqr3cp5GtPR3&Sh zw>*qKBg`DfkCHG`$&CJOVM1o(`+*&oEG9o+sEDE&>-#UI_ydlN5l#5&QiLyT5K=WEwB0SdTxmLqPx^x3tne=*fyrZde-SfY?lLp- z99-5y^8^-~{w=UaGU$*!$c1F6ggrRnHR*KNHq#0vYsAui2fQzX4y9Lk(hNE9Yw3h3 z{Q_aHQyMYr9Hcj7&>{brC(SZB@RR9;DfGK1t>MynkUo+@htlagoB~U!jhMi1r_-Ty zeZmFOe&qzD|IDC6>8m{HM197D^LsiSO45W;t4MI-E!bUVD_LVc=qb^iu|2UDlq_v& z?RZgV+`1BkJxbQLCoVxqe!>qU-K{u<y&<&{^Pi=TGuVTgZ@#!!C$ZR5&GW@Kxg9;@)YLQ zHi&N;MQ7_E(|p-ppH|E5MC%s`;E1WHDOjS*-g zfz0SpDrhT#E27U)K|2X#MQcz&dkHj*E2@Hsqrna#X7#LkZZQ~>`$jI!E)k>SG za_7DW6)DSPSs@zNH^Ug;W_pQ(hz<`y-M^r2h0^eJw!o{!aH22VGlY`_>C1TWD%_B@ z4W*WQ5v^k11zWa=+&UQ1;qM`koWeUOJQRB4BtlW^S18}99*rp@r+RdJ{W;K87m{J# zR>?CO-a^PT8bnrufBXvEK!p3!x2_9(`S1zx7MB<^l6E5#?Rphs9zu){^Tw>}J-ZQG z%z6|NiVq=;%*u-qvqdJ}9bRnw$oq(m>!tkRMD(~5h%TX{zwn|n`K+kj8PV~N7aM*y>uTG3~OnbG)3%5~FEQu>e}Q#mIGN5i1*Aebu30!$!5 zR`Wa=@kUnzd(@OUayc>HJ{5TCA%%{YmCYMCa+X z!Tv&+z6@mczP?L)uy#p>XMXfH{0HS~;n(FIJ&#O4>`GmLz-~k*+AH~^7%r5vJkb(1 zIj{_Mv_Fo1SsKJF4rJ1M8zCg!JjDppDlx=}@ISTSYXx8OoyBnqmBcBXCjwdICG!;a zmB7i$!s#cRlB2aTdCsqc9g-m`oxljsq`vL-p>HXC{rCWC6Fj>Veb<{txFYx=MujKV zgASg;%Nio?RmSBsg6|-G3mEr4e94RpS89S24WUA38Al_yFrP?<{v?^fkZ%tF#)bKp zhY(+bB-0nB^;76F2DiYM%wY2OJpIEHt&)_id$2sd)sYge{VLubs#(C=r-ffqH`X@V$BNaPwFTARKHYBo3Z6@R zVqhzk*Q;O`EQQc*`P`J~T_-fFCTxPAL<0~rLMHh2mc2;f8um@DaGhC?7Z7gn;IRV2 zP22p52lePoMkt5ElO^R=_H(Xq`xPH(f~4H}9aKN*EtqnTD=;Ex;b|0}A;SIaA6(%< zkKbKDcxbC31%yXVMt{`V-U0qRH4%UBxUMXVj6Y&vhV%9yV{*pFem3Nyvf z350Ga$5dEqW9YB&4fUZWhZf^06Q?jOq(Zb{O1`igLE4gqXseV=Al#xWPJWDt$vkB- zm@IMi5e#?1Da3C=CLbq-!K4Z(Z->fyDe~2M>@t~EdLz^6g$l_$e*)lY8B-1-Qa>Ny zw;hel@Xg>hkVgmnn4^aH`9~u&nNYoA44fyVM=j$dbgf9EwAg1zY%*VeB=Z}KFRM3k zPO`e6f(rbuzx6xpPu@PYDhBe*hwg#DtK5k3tBHy)LgZv*&cw{tsb>mf#t`DkkZ&$# zc1Q)3C(t}XJQ?y?#>}>ao|R#XpIcONPo3GGvCm8F^Ni)m2^$&D}-g=v=6Pk0CP5Pao3dhYsm37q?1ei{tW>g;w4b5q_YMuF;!r)d)X6 zNSB`)wDPJ&_+df1{EVQLS3PovwuTI41tKCd->qc5Q?htY7 zMP@lJzg}nMWk>j_I=cKWU6>Eht-SgXeu*y32ki_*`q6C=xzcg-#BCTE>$vPCJ}zXjV`~|X5}@Fv~b)Z;^stVIWE7eX65BXwu##!!Y`&- zc`YK}I4-}1X65BZ_~A3U{K^?!e$vd!YZ>A9%joiBWpvkz+bY7(kXd=HBK+nUU4CH9 z%4;3r*Tm>%Ic_I$+eAhk7N$fZVPd*iVShwS>g_eta04Ej{CLareG?w@&-g|i90aT z)p19QJ18>Oao31@b!4aG9u;?RGq4wj26oPKxXGX8(>h>?h>knexz|W-)W}JM;nI0p| zSwF;ZCO_8M`7WW>LfDbvCqVBYwY?jsfy^h7cIPML!#KkTanRS_6>6z$yr-NWD4DK| z8HD71kAGD(VzIM;W|VGRTNiFQVL|q&Hd|0e6~=J(su~7ArMA1`M*I{elXlnW`TQ`W zxpc`hUQ=cN!p4(zp&Y+b+A-A1y{aW_zbZQMnBU~5R$hJ(&;I^GHwes@`yuo0vFZEX zFA%)esC*1r-8fTAVAgRYH$(E`t;vGiuFjmMQaE#(clQephcblA>TtKia&P~ zZ(o-C)0i_<6B^z%+~cIu+)1VO;KA1!=1f&=77{b>#&wW3XBM8LIyBUp{M5>lhc4PY zhzWZ85$SB5Q6+UYuGQH(qblj}5S^_vsu{u22NQ^2Jl|O+^FIsgSs@8_s)VP4=RkmR@y;Zokb!S?{1(|yWh%m zvZ#x2ztvcWy9N1H++1$O_}>}SY{};65axqcn*4(ub(i-0Ec~;~Ni9)zJ>UMnR9%u; zxayM3!c~`KCaR8G$<1-nso<6BZlrUuVPf#WYFu?;e_IX{Y~eI++*iSoPE`D_koGKN zy^1f+BD$Rn6|cjIir1~%{-TOc8-Xl-KV9c7Q59DozNjkLlo$6R-N1=nq{El!Mcn7^ zB`2LaURCTuIu~zXr%Scpit7e-wC}er*Wn?$f%jYWbpxZ1awEKMj`r(3?GCO zm0P3~DQ3E^a_16FF)Qk@Q+p|9mQJ_5QJFjEHFwe}=B3jg=}3c8PTCQh<(1V+(2m?K zFZrS>-g9y0*l3bDwwA60T&TJ!6IHCki7M7j+s~-X9ru2lrgK%o%iMW4b1Xz@{;dU_ z3*QNc+f~(cY7`$GgYZ5_xV9(EFLxEG!AtZ5ToQ%)0WOI`{h;6_!Oi;CI_XsK(s>N& zNDWfX`$vs;NpK#NOCtR?Jb`zl^F8ULi))L^SlZiHi;t4byPfXT z+n3{Xr_%FTId}8hw@9wOlU&qGt_72ObF2P$pX*Vv`}^HezRL#>9*;i|r2Q$uA>C5fWR!NhxRJaT!$D>49C+MGAkhJjNdmpb z%g%w&G6|asHDsz%X^%i=kt2gA4)Rkg8@$U*72P~g*VQmHTIiA(W|k>*NenZq=se<* z;3kBV9qox;HwoIkF|IVtvx^zPC&Rwue-#hfnHbW(m<~(bZMa1 zd6x!vGOTk^wWYo1WRh~y*|2$GSx2dnHVHy+VwJ}q7L@W+E9XPVoA|s|m3qT&c%^i` z=%EB*r=Ijsl77w#JM~tYn=YAmwWg-YPj+?jF4`%+TJ8l>ed`*-_!vsL9Xfxtw1cGn zMyyNUWhRp}43B>u$Al8-%zh^;DRQZ6Gl z&ny|Y5V6gT*gmu5{um;j*COmAACE_5@V_@9Q7)w!Tyo z{Z@w){Z?Q97^Gf6I;EX-5*Jn4v7*;M=WXx$=Qf(p-l(fHas4l#5I4eNA-r;X8)xc) zAk|mFDWfb-vGHaj9d-tSG+%KYZXcZ14^@)ptL_X4Mu`LHACDuEE>6#!?KY58;e-9t*#8XAkh2@BNrWrlG}Ck!e0OA`N}{u?CgJNim``h3S7eM!0#7-?Da zU|2m_6B0$93ZA#*^!^j$4SCKet4oR@Plppjp3@4Y`M!UJ{* zIRcympWoNms&nnpxulqz?TJ#%PFT+Wl~Irs@-Zm{=-2quz%o8=%Gi#g%U<6I!a<+z z9FU6k>H6%08%5U{saKBjY#q`1bsdB%Kd1%3t_T<|c zo|~r7N>2dxTE)-Vi$hKH?slt)cI%y`-}QLm zRd|=jg!;_9fPa|HcwP1{Aklgt*uUI+>|gFZ_OF?vHJ=XjybF~S>#98zdKjq;!Y>;T zo>Pmp4*k+C{M6l>_>yiSQ@Yt4(nw}uc{`0{mfLK}Oq&jWRu}DI9o-6}kA<2USD^tSwDyUgHc1?@m{Giv!1KJ3tZ?FiJcxA0}H zqT0U?(*HWHx9YZ)-~s*F2VZ;%kv#M&FeY-4uNXzz#^hq1*Tcrp&kP2f6q>z~v1X?= zpY}wk!jp4!{#huO{_KN`kjkLf8YJSYZ-jf4lFMi(#RPs#({C-8m+;mtNOkpMcMnA_ zryh^c&T?}4*z2d6QTP&sv%Q|xObBwTh<0uMNuLzB+Aa5YR4%C?Jiz2PBz`Td{F~E- zm2VSP{>=r#$~QGfqaARnuciH&QL$A-yE;Fri=OKiP3uBkDZwZ+VaIGg%1qeNtQ+eJ zhY94cp1l+0{hKatqFY`!l}ENRy)=bNr^>IfKL~O175fIE@o+YF>zk5Kk) z;NTZqh0oX}KLDGc*XRG&r8w^qx&EegMvq3mXWspUmWE|?_Q)TQ`mD}dp})vf3zWM(`dvhchc-`Q!= z0^&7P7WwY>=HdSOyybGg$*O2W^|#~UWB4#FP-TmWhH$vbDI`3sYAXBw^`Hw}H|v@` zq5n&yMyLpYEpj(sw_EeaZopLjQ78vG{~WiaWk}_2eG7#XsLQT89ZR2(ny2&5cJrQ= zmA4F5R1B$i^hl--H}4%LuSm^pVT!aXunJ}h2jA5Ah<@cv{R+ms*D44VM6N$g8e$dE zM&TFgY#v7{JO+>wEs*?kS(B@h2|sSL=Zkn0QG$Jj*U7zzlJYa`$(mznyBszZ?Kys$ zuFj*6^Qk)0qUe1?AG&O2sh|&Cv`ZgF*Mm0~>7qO~{ita#}Jr zU97UcPhrs~3c3#_BK^hX0_LNR>!DmB(t`N`j0M^wgH*dpce1)POc*T`YBnexe&A6&2ilo%{~>$GHNZyi+*3mxUt21Gr0?~JSl zUW-&N=e)0SX19U7UlJNv^m{aBl77$AjE>_y(TrZOr>1E}FW3vxG@}>nrZmmyJN6{4 z8ChlVH9)pkAyqDr4ucQ#pM9_zsobtBh4#5!1?SpRNc(1uh;}&mxPEV)`(8iZ8;ZNV znRjX$cY7+`9*(K%1zS z^OsSIs}0j(mS~Zy4a>c!4a>c!4bwU50EMd!&mVgcXzrH~g}RfJi;Y&Y+Uth}EA(>M>Q13Iq0d9JPA;sLmHa0O8G5H z@$?;|ehR0&bdIPat{o(|BicdlZ$giCO$*(=P5BkzO>(%nF0@YcLgKPIN7?eyJd)opj++5GW0V2fKww@Yrg<+8A|cT>{9I*a79qr18cBx1!}oW*L}X* zPFg$2Gpo1pAmOuAJ6i&|1V`xgjTls}+Y`Whz`LPAK|D(Bw zcGL1n#5~~5J9T-Ua`+}v8EUSpgbwWZu9lh4yKQ{pH+p0Vmt0lCJ$Qo$6bE(85>(sB z1d03Aa=#`_T72j}6`=to_7&c84kuL7{t3>3|JXO}{%<1TK@}oxoIS*$e^-;bQ7wAZ zSgISY6=Q4ivw%+MQB^D%wojgQ9_}AglQgPBxuBy$ZrA5Mq8tBPm=XB!$dai8Wix?D?Yw!s2i+guXou$_z42o*s? zJBhCtS~`KG8_b#husIn2VfG2!ez@aC!b=~+Sd~s#){j<@BOMCi4y&+YLMe?q0Tl@Y zR^hY>71ljeB zQc67sfN;A5x3lDSyLGL-9-?@WE~C&bV>TVJ@^-u2dqw{syXfQTMIU#Io;`02W+inI zo?=z_nvZ{Jm;6qB1sUzyfaV~}Q~JeOZj;)O%4FoZz@V#_TVI?8>hI;E>VLs|e%@@J~LF9F7|hFJefufQ&9sz?8nS)X>d)e~b-Y&BK&fwnJionN za$logvJZYA)ue-ldhfCxrrp9V)dCWs-NG#^Hn{GkA1`fpi^B63mLi+RA7VT!mz@P#Q+Y+P7Wm|H)-I_q*b+iA3 za_-aROqAl#;#a90@;y-IDO4)x&Z^jWDl{$JjDJHjI+CGabPzKq+w(qx8>^aL%}XK~ zdG_mq=eY&1L287GAV&8$zHYZ>p9L!G)p<+Yyo1Q=8h2Af@7bxZpcFc7Xt{pLgTPPe zC8Cr7)9}(cVhg$okKDQnk5rNE_@$i#$LX3Dxy_sUrWUbqeO7jTle@&)Hn~DSgIAcS z=qUD2y-!{O5%HgWu*^tVUqotzN+9UJpRa)aCjh<0I&X{H#6RINIPD%wT|Gh6t!=X?^hI48mRkh% zt;Cz-^_wTTZ`Qpv;+tiYlGyYe`R;nJyasUbpMCIsNM#!N0fTg-RYoVkUysyZzenHK+~VSXGLr;w?cKEvG9Ln*!)W-`1iZ2Bb zzYC;rP*+jxR`Cc|fzTGR+Sy(}XbaU#v^@XiM$7t7++3pHt90Lc38_2+-#Mc5+HlOi zjnwmX-YPfm_&;XkEgRT~`5&adsa0-oWE)Lh5q=oiWnh_|NL>M~jQ+fl{UcJ@fk2Oa zrX{_aHnMK)z|F`wh0M$Jk^R4n9rzUtp})YEr9W?E>Flv|^LQRoqz~@MdQ&GEu>-Dw zJmGim$H=BIvcJ?-cq4lQSAmfwh0KgB)k`B=MB9*mUcXZ(tpiK{0Uk^Bzq6~;s{ft6 zn6?53yAt;GJA1Xv)f)hK-uoxwY&FZm_5GmiHI!H9$)xGHZ{ct`Jp>h;YyV*|pUrYe%;@7&x(?N3SluY?#uUf8F4ER8&7p)g# zr`LpgXte1NyFZ^JC3~ZN30Hv8rrc(w!0dZ80qj6Yx9Ve81fTq`-sD$gZ#wvf4mxcBMRT2 z)#Y}iGVE>yy>mA!4q{SU=iB5q?FQrnL}EAyXBC;yn%Sru2G3WXJKEyIV!v(}EF z;V-tQl6yf^rN#DAQI)8Q?FYbCaXnu*K%0i7H6k@a<$=*hrtx)CWG-JfT17u?1N+`8 zjlN1Qc;`VpW+E1k3mU5&L{EVhQ4+LC9I;Ccc83a z;QBRPbfH`H>qw2zTRa?3f_6Ws^Pt=OXCGYiS53PmsLC}Ogmy7oBXd~ZY>nJQMAA;H zr|Hr>PH@98rGXQql?G1Wmi9KVc)TucsoS<+Q)%P?BeYCMUYy-n?MGhRHyPw*hs1xX ziEil0;$|p=e**xwNYNfLPDUyttzZ|7BRYz38B+UoUeBsppOyC)4VeE&>Uy1bzT5JC zllQ`B1o{;>A@BQ396iph`7{NE$|F3;OceoRMbZMVvbFNWO43)j9&-X8$g z)1Q6tbfhwLD!CUM#fOj>TPjNnFlW~dZQ!4f>qAtbnU~`35ee2)cwE7ULX*iPspqhU z4~1&zMyTqB&`d&btC}i;(Q7@9>u>ew9OOn&Gk)YRJVMoh|3>0`T@x9=l_W%DAOC=t zqKJ;>{F*Mt1IkRx_G}Xa6m6myplEH)Dx#A+Kdg)J*y;^bM3$w(m`Mto%T~om@uuJ8 z-kW}tYPRVZF^H=0h2VcEe4DOvncMkqB9+JBKOhM)^uj9q^A!7c;UJu|8b zPFA2ZqP53xea&_sod$ZXSmZ=#bY}`zDWHJK8#-< zLl=yL_cr{ts_CU|_rcnwt1i;xCHWy6ybzCwe7??CkWV8r)aksl-Rk!uFApkNO=(qH8T zrpgnkaM}nJb{?<57N3qyG}n&<-t6hLX-WN_PhwX57Q2R~lVZqV%V(>?+$x^;%G*LuqSOc-x(piJ|hM?^HPNAbDdz8=SJ-?baOHqVB$ zLVAJn`OiK`=h3pQLXR`7P{{60CB0L%!3Kh?dE*j5r5#-<(FJ*mUL5Z;s?Z@3qUi06 z&~NHd*`XC+jmWX{45|3D=m!1S2WzltlzZAVqxz4I5FfjHpZJ2u7u1R`_>O&HI|Md7 zp`h$%oCB_0_U#rHO#I+-s%OpQd#58qQ9&N9wj@^A__VI?cT^ev;EUR06;3HAmNz!y z9`T4%3d-ev)8wfb2;5JT`)!lUfDnZz6->T~YuJt@aZf-ntwN(?_%H!Jbp(j>XeIdm z*9*$YsHrb~k#FYGjkSt;_-i2i6}UF&_Mmlxn-5%M(R|w%d&P0Sa zZmw^W{NBLPDZxB&^f<%FGy^C07!BO>G;nn8@LpYzH*hnsV-^qG#4mdTN56UCu33W~ zAjca09>BnV_Q4B~%HwsVVPPZAvHp;Q@bkOhf2PRn{VU8Wu1*ySgR=0 z&5yv3iR<55<=r~Bi2p%qgx;be=HGo69LaD~|61qsKyortxoiLQj0VH^K|ouOTBmhv z&)7eTR2~O<>@%E(cH>-zj8n)QN;mfZFWopdbU_+y6gU8I{AV9LEleYig#sk9xew(? zkv_159M+8^<{wPpvIQ3+{s(V9p=8|XYk>1y$meG zT15rjT#i`@T(8yDc;os4QX}*hk89|5j6ZJn=zQL|{uQa*90|by8Z~|brq&po<%$ni z*ZNh~$z=A65As??Z~f<|pxh$QIl9a$7l`jhYJ`eF-H{T$Vpi>kr@i#+~Sw<3iIP;5w<)t0qBz9&1|wMi5 z`3_$ zCvy&n4i*(Rjdeu@BtgGbc+1#AQR&xArckxQkBlu4V+vL)oyk5?H)4_7h<(%u6Pv(% zl(;@Cz&Lr`*c$9tz`Zdx^kn}wYyKBkTh?tT<1a9`=+DE}&mxsUp&6`IamK|s_7$ne zsLnJagY1&}g+NsGaOn&-GJ1Xn8T3dguW_}isjRc0F%*rrfyh!5JO}(|ADoX=x4a0| zKz7A9`MM_ZJzNP1tqM9o?y=PzbI+(e`kaThrx8 zjZhIpE!eFTS16x!n*BpMuLs%hwk;<(gm7QNA&JOsv^Iu{Bc=KO$Pw>i`{}O*3 zTvdfPAO=_0w8X9HF{;VfRH9d2J6#HQ=fC6@w(6|Cmi1qF;Sybp$8%psDz~!?<3VzF zzCvCbn;&%Qyr6&nvky*0sxL1X;;#U-sYtEEhliLrw=faRl08YxxSHO2v&^>Mjcb!G zbDmpfCsHF+1P$>lzJejr31vy#T!{~tOO8dK?5DRb{-I^vgX;oarYHM9htvqYPTZs7 z<0$J(xOo~Mw=8QFWqPI;Q!Tho%PQh6q(vjVA7PX$Pdo}1^jxJV{cFnqR$}9}o^JgJH;ZC4 zCVp@H4H#&0Di$pRzWwo3Dc-}k*%6Iz^uED2DcZ$1x!rEHRzvvK9elT6KybspQUOfJ=KMP8MId-UgBbRa&N;!zfclone z6+b8iQ6lNTO!7?BpL`T(H|9=$lTF|;cP=>RFxs+#-fo-##S+&);L}F$wmm^#PvOgI zJ%pAx*h_T+K5l=kiqOrl!;rMlB-f)j4^1~v_ID#`HLmONX`{?m#nU%oMi9T=gAbQR zuUQ)?$BGKe>c({dpEk;4wH`#>`|#@;d^q<;^u;QBEQzo?Bz+}oq`r<+#sgtJjxLcW3r zMuC&xhU}xi9=V{k-@#+%ffUr>N>fJ8@mJ22NC!dA@mDUB+wJAwzZZ^#E7y_SC4N^{ z(qdV^M?tsh;ysj~2!dfi-t%S3>jClwz6T7JtpWc-u0{AT3`qET2vAKWOsU0a<9fO- zU%Ly@{PU3-q1TDYRD5hD7LeoSVtlwPQj~mUQSOb;BP<5j*}ANmE-3CoYJ^_rvi=8Z z`@^{T0zO>UPLyR;Q>NRW#%ds3|5t1F^W7qTfz$}SMMcaX_ZjFVrEm-Ad_->aXCIt| zR0hjGF)ASMHsozU>JgoHmSjcVwI(mgek!-<%)2e?13I5Z0_6KJ@(nc=_VK(mX;Wbb z^On0)VIKh%Jb-sYy2O2M&Ci&c)2IMT@Qy;1FarPJ0-SGxT))DHfkeW~2XHFkyIa8< zCqesdl7hX#D@SUCUT1(G1e2bHltuV(S>$K4swvZr==r;Fy+Rk^0sMTVM(8anV#4X0 z;cf50T@R%v@v-TL)w%@_F2k>X!H3H({T7(nCjrNK-Ls;UrSl^ok1yeuDjf@Mb1!tc zJ%7YY3N-k_zaig!p?MWwLxVcMf{eeWjPCP$pj6Lm4=tkSklabSSxb!E>iiWlS3q)S zWFGHkZnx%*53Qj3tk&IVn8|8u?H6S%YuQPGXy9D@wlwN#X!+{H> z>ctTGaVbZJ)w3b;lhO*ZN~~%s=LoR)UvYg>*HY)!^02?W2-Se?O z5`A1L1cm-Q5S@$E2))iAdLPQ_z|Gb8xMhJHyRCwYLi1^(Ink;ILepsy!m6g%9|3?r zi))Q8{Bv9dvFNWOHA3Z)W!8f$VO8W}PFQ1AG<55W?^!rO!Ele)ZlZh!AXYJ`d)1h{~&kj{spGe3@--{8aLu12}c z45`J+oU3onH-8R|Ff#8*w=py|Ho96tSbf6;XkZlLTZG{XP?Vg z_y?f;9RIj`-#6_a;a3wfJ!AhEzpQU@!r8hU&9AI)^Fva+F)q`v{s}LcwT`|8)ddCuET4yaa-em&DuaYeu9x)i|Yn_ z+9(gU^f-Wa>xOvx+z0RslL7sfbNBSOfq%eWtVm5*&b=HQVMzj?Cs1PFf^ zZz64_Q8kXOq&%0r^=r> zp2St&f&YGB->hli!}*mu;Z-Coc@PQJI^iWGtfYjKbi!*$xc1{nI9VtB>4AOC107cW z{K>QvdESAC{(ax9S3Zpl3yS|4gykGKvTfF{p2PjZGTLS`@4%4<_sx3wDI_d9nYNA0 zJMhv&`V#X7Fde9q->nnwK*Cp3Na)uIcO&7_5EAy9&Ofv-zJ9)p$T#F-J%ljp z=3XnmmUoWMJMj4j_r2>FAoi6n6F4rz-7~LP7RAQp9YCYrwFfGh+#P`+jbDc*(ci^# zvBqGSn-f<4iiv~eAT50Z%r)=8)w-n=pXs$!?x>}WXVpka_v!+vl>@q{uc4Li z)z7aot$dJRnVdyi*GnrIxT%O>??Vrwl~z&dhe4^DTvqBg?StbmG3eS$u2Y{4#qjMm zZ)*=;fcw1`?#l>Np#vS$==9_8C+)Rw--VJYrowA783k42!%T-%1go0Le&tP&7_Jn@ zPJbS+ISZ)~dW(6@!c(CU;wFv{7jY#QL76`JOPsQY>vyw?IDpg$y+uW&Zh;a~aM>NW zeHb4ugp3`JVO3N9$JSuyNL(MuD($C8jnM1dpf7eqKgP`;@ZqvZrd!pN>E>hTa}^kG zRuR=mjnG?M#PbQr6{IZ3hl?Py!m6fByDJg)fom$Oh&WOs^cMGN8Hy;lEQQ;v@Zmzp zp78aF^3Q@eycgH4S*1OU)Cj#!rG3c0;PYsCI03{X)OZPGOn-5?fO)=&oF{?ADkjl$ zymQi-xS1(8+fl&J!Li1x`G1xJof5O<&D|hf`oj{IY7iB%xe1wUZej+TEA%K`*j&V8 zb3%4Sh9?=aD>gg{L~?_D9ys*vrQ>cyji1JcVMAJ^4>r`A_W|Xf#I+#{HqRk7La!5S zZm=%~W4Nbu;!8+)10ODr+~dCT=#39N2$#!Aww0<P$5i-)ABV^1lz4XLaFTHW|1(5c*KB>#|2rUJ}fR9_2RZW?Slx4kuYo0EGD2)E>gFi%Sgx;bsW9vDach`NO>d7|QJ@>ch z3;mVJ1usmQ1$RchEjU7QI`4tCw9hWP<)`PvEw5hzP4b_8Fo9RVN0OFvjXm=?OXh9Q z+m!m0&Wq;ppL4xk5qUozP=~A+?9;)yoa=D!8nvvtIn(Vqte(xj02yx6g%s;T?1TRy z6=EOU*PWA0`2Mx_${R6or&Yd$?#AaGyIUO0~ludU#J69vnu_ioBmX}i9D=kNUImw zwI#h1)BAOj?z`KsS-M|t!pUxF+yPW;3Y_i1AC?yyJSRP?$#+T(kKQ!&VD44>ZS;~d z&s)rhG2ahsDP{rVDB4aqy3j3?J41aG3|%w}`vk8Z=Rim-_75P!J5Do*REy4}jci?d zX@V5>dTjMLG=wt7VM+Q+41sptilzKa>ZmGU8u9?NY>}nuOOJgMD6nyyO*o4MPj0d9 zQ|Z|XMuaMxQL<`00c)kN8Xr10xyf!3lzUbBNDEX~V-!GuGzzC``r-}~eXY?At$NA= zZ>UmkKgh1ZFf~?zqnwuBUV+^@7g%a})i|nreR|=9x6OJO&`2SQ(?h@r0>%c@QhIZv z9~Tk7Ee)PgK}~KIG@)#5ME}@Q0>ovVsar?2oFy!428un~Z7NzdL0Y=$YM`DF7yOlk z<%Xeb_CYag47X^ofs1d|KOqO+?W+Le(NuArU1iJYo#T5%r7^mAkI!8W?DA-Qn{Br+ z!#&S^O%G+pd*{pZ-iZwrL;+AM{Y(;SSNi)+6$V4!%VQf}QKeiiPZ)}63jIb^0Unrs zhXh#B65DX1UZ&RVRX~HqfO3qhty-~?5(sy8G*}zZoOT9pRmsY#&pOMime4?TNK*02 zs>|}0SB-~8Ca6!(I%z!VM^_0(VjLqoFmJ47?WAGEUQ(uYV^>x^U~~I4>wybF4@A{v z_=_OMBE9cd*#Hrh-Ho=Q<4Z{1Nn?8^X>j+tq{&1;@aS`sI6EcvQ{(8zMO*{Q`Zf~? z3XvKH5DZ`?HUHq(VD?kjc!aCKY_&WXT#k}fR81pLPq4^Ur?G(Uc59qKQ?9YO<$KCq z_)|yrPSC)N$Ei>ES;cNa+D)FkNeF26c&7Hf4Ul>4+ji4~b+H#JyC@A4Zfa z!drS_pD7)~_%=osuMj{kvrT$|E=aKQ1GZr$1uLtbKz`AgnO}ApEkA|=~q!Ypw3*)mwvTQk5J*| zq@`SgaxrLCh149CE+Vf*V~n10F-pBozs(RVZ7Jzyt>k)WS_tYi?W@X1+03c^3d#+- z8XhSZH$Du3aPq{Gan8)CGvAGU;UeYO5!1%FY0*UxIbf5*g)J2YGWv-O9~3`34;}5P zSUqkWx@nl)Ev7N7@X5G+BqNQqk?ZVnf&u?x=h^-usN#>>r=VzJ!M94kbzv79SIHT%%_AGZmAF_Dccqdn6cX8O#%rcdJHw`DYtC=C{osT*%n zr*++`yP^{B++oV$avL!apY%%MH#~OuDes9MAnJu-mY)uMO6>MdES%&4!CN3wY~RlK z%v=&x)N#k}@?O^sb>WL`;Y=TNy{CdpVT#+ADt*1j)Py3qrhDxbq_pFf6r#`4W36%X zv1sYEG6+va1{m9){+&j&LzN#Bc z`h#@gYslgN!iLtdIV1A;Q>eX9B8?>jx@lO9=w{zANPs7Xp*)2$H1Kb`gzd;Zzu zpvhB-&)^B^Lf_&PQ7gaAX=Hjl>j4&hZb`Feo=ba1BqeQ^_B?M-M-7y+ZQOb4T(sc@ zZhIwTx%JUSFc5JZ>~|piY}@`b>@{3)V@bkH$a?uZg3I^u`3*h@%(fQe(}GVoK6~-` z6h6=36S8N93eS27x$L8K`xbrW!T%B}#+Oq@zv!tolYT9rv^x5AD}Ak{uTAvzKKj~2 zU)RvrE%?g26JO4wbo({>dXBy(J9zLS{d$eQXcLYQWyzyW$V0R7bO1IC_ukX^=59#YwN_(BY zUPa{vRvygh0(^~$(60)7jXjCJ7T~L31^qe$U)H(wYdd}Ips!x~+D%{m^z~zWg+EBY z4&bZc4!XUEzCK53U!Y%K$Je+Q@l|k)ZhuQ(RJrpOr76c66Edy@2kVT~)ctBkWhjI} z&I_qi@YHxEoZlDNs`ijt+A2>SRe-0)N#b1X*lLmUv3=o`3OT>DwyB0T)p$r%)Trr) zR6&)zlLx#Q6EeOS=Ksqtqyzs1w(Z>Xw6(mJIkQvKR1 z=G;Bkem#T*V^rukJTUGz=Qes!NDuPWBs?%aL}#2GT2QPeA5$}qsmi0OHoQu041L5d zQ5B)(C2Csudum+hq|)&HYCJx6ml_{hSfuR5syg%`yHpj0&r=nh>ZI_Cs;Ehw65g-u zK{b9C6*=?QYD1{LSWOKrE=C!1O4a1>t7)}dhguq_mhs`sRmowcLMw_@3E<-_QWNMB zzFn2^bx=*^>uvlv^dxTV{G+NkKl}$ZJ$#> z7C6P>*U|C&)Cx*^T@{C`_;#gtI}cA!^={|lc2(eQMR<-XKc>oF=MII!S6~cLU1$S= z=oNL!8)`M)T^`=1X0-}P$A^!riBC{hTh3F{Lvu=0VQ5XM?&wPxY3^v*b87N&ReqbA zOvM4%1c12GV)Gygg7=`m0Wvgj# zsluP5g*QuAC5H*zaPG|q)aD#hkyf?%sH$rfKuIPO3F16qGVND2M^(Mf1fm4|O}vTo zqq(-q3-1CXm?26LCgvrmCGx%rzj5xG2Uq}BQ_&KDi{*qAVxoJTo5HrLcuQ5M)SUgQ zV3pymBrQz1kn`uccDPf`JgycVrg6hqP3J2Z{zCfkRDO6ruAxQYMY!a*GVy@X7v!Vm zup5b7s6Z2|G%SQn@Y4_w8pkMZVy>Kj9b<#Lo~foDQl~W0_uMA6pfi+Dm5$>|O&FJh zbvG*S2^C7IvG=QjHtDJ4F=1iO0puwP z-%<#vEd4DPRq&&=wt(2|J&4WK0xXgU%oOu(!2Ie=m&5%WUQCD!Zb{*uk&i5t;U3J zQq|$7aBY*Cgjh@@vU5+wM=U8RM)1}IItMj(0yozLtz)XmR#o9OYWm~gx;27D6B!Q| ztRXEKs@%72;)K<|Q1giM+4-&bc5cI09+WX$^1%bAwW;N=K=eT!I76YM6LzYi&^)Ln z;d;oq>I#5lF*LWm5Qvd0RQ_QV`Vf+qh*nj|O&VCM>-!4OazS{lDtug(>{bQ)nRuNV z=CjUzRY=tzR$;mj6+3Ne9$k(}(jiqtcV|fU$I%tsITs&NEFib3@y?jrlsYC5jc`xR zng-`t$d|>M56dI7V#4`vJgU);1jtRN>Gs}<_KpEgOg0R@h)Xq#LRjyeb4b-{8kMJ) zn766Ud0Nx#TjAiKZA@P@>8Y zsrkE(u7NtR zIQ#^ZZFG1(42#)bSIuHY=WbR$RvlL>TGc9TqSU}zVbFa^&7|wgY6@LK^@LFPaiv=2 zTnzdu2tON|=ZO=uurhOSM39)JoX+zYy2xQQO%J?amRS($yaXi8JFFu2k-3$3ScX?R zX4a-UKL+ZAfE=ZRs-%_ZU2+vOj+!;H&fi$Y+p9vM>N3et!sBGt|2p?LG)@zpu}3i= z_usEp99H$O11A=#1#L*_Qq!(grO?VAC!sYB>fOU?&eiJFpR4LaDjdF9o$?-4$2X-; zHBf(28|ew9A5b%ntC{z!C5J&Fih+<66%Zau8d)Z-w)F^kllU*l;hv z{c9rqdP)JnlWzj@!AxGH8uKBr7QF~D0fqFiD!fg>BE$QYuc!#ftoEo1LlEAs3T_wR zOV7=Q2f;lz`zqwv^GOU;v(tm~Q3$#6!)nTYk#A-E)NC5z{02|gAC^bLbj{Wj&d&hv z@;?!}uqrA-+H9@i+=LfP|3@vloFMMYV7B`R$RKoO_6~8bLJ4IM9eLsJ$$*G(Fx!`9at5>6;>P(VUOzef zfI1C4k6SdEpPOBDoJRo*%)x^RyW&NlWwz^au7|OENKH5n&ReU>9|yPDDHe|?5N3BF z=clDMI#vD(<7!G3odG^ureGbxY(5LuQzyX{@!zWa18QcdVG;pp=If~R_Rw_dwKU7@ zcoftup)0e0l5-Clp7#crqYR-uH5)cLhwyavAJEoSet~QDesUfrvuYvRUQ3Ru#x&c@ zY$oM=-DKLYmL65hb*2!*&+KXCyf6+GIb%V2I|az1j-R$w6@@KEl${Y$xd44&+$`=ThDwHFlB8YgJ80{a9pnHFSOmYKG8+=jf;^I;5s_D)@{* z%rl-)bC;Ad%UX(HRbj zWCYCSkk0em{fD3q3<~rGJZ2-xp}=D{x6A~OC=+IP%^{TuvvcVGTV+DJZgx0z{tyOb zPkcocy$)=KLUdS^MPUzS&s66*2<35yRoRO&uJY9EzUn+9PfMSYr-D0XPuF1Jm`!De z1diD-_x}&z-1S~fb;AP3Y#z+w5vuZdcvlaokQQVDBC|EIKTl|JiJMDwaVH&e$gVoZ61FI{SSp7WdCSrv0*cL#BD$aB&-op5fRLWW4Ws(`oQrpr~) z2M?%{r+vN}5;4wE_PM}i!&5|B#DwM+tFiQyrq`VBvBv29rzn-%)P%jN`WVIxmUxpI z`yMs%S@Mwa+?yDz=9G*~b5<00b7V&#AxKZn=_Jm*<7g=7{SpJYQx(^!N%s?2CPL}R zgHaVe<8qSv6Zfm}pTzW2icHdpDR&k@8e>jG$u=CxEn?1J8J@WaqcZ2Z1TiXd>6+tY zvMmO|A#v7c$X@)sXDySKvahdb1w8piIHLe?3<1$=M zsxpUb{l8JU%;8`spmLe>$8t8)q+gRR)LbM>V-r+2$F4cgglYN~M7lVo7PhL$i)rjq zplQy48(M#rLjPnc9jQ6%X%Z9HIkU4rW+k}u2F^4`nZ%-gU|7v&vR0K0H@apa+ zQ8$Bx&b)MP#k}E3p!+c}7*c+DY0l$x zhO-c*FmukQ^A!|^d8%@4=EzfXf~fNlo`%pvzka z9Kail@a8DrG)fVqGba!`He2*Y7He$|B0G&pDH?_CIMm2RnvB6L-ur=J`-_JK;UL{{J85cD}M#*Zl;zQRy419KmF*Y8GZG^mqyoes8k< z5!p@(U(EC2q3Tl66ae_*l%Ix&B3o{AGQNTn8`yAMoc^-^H*LU|7Zss@WH)QmAO4F^En>U}DLC#$>;CELiKClwoRcJe+F)o->4W+ z*w3?6h$P|Ik??ttO%A*?blIvX63pJF#$9Y&h|%-UYTJ^kUA7~ZOteRnsewdqS9Dh* zzPqIz$+hh}V*}CDKrE3;wzM}lH*_X?JDRuDVJH9S`CC$riDYlzKu-(~leF7-`faB* z5bx>R6^|wdJ3AA5_~G(IvTGn7OT`D`l>01Hwlvn=-PayV^|>`}iBYAEIz8UJc}oq| z98K*U=-VCL5$lM?1_ok#qrLIn(e8L}S8As&Dx=*E?S1`wn>V#@YHO#4qq3#D;_axY zC4nju&CTl?nm4zh@QkM6u%PJHz5UXi+S)|2JDyC&FB*(>)03Pax1@a_4$$oitiE0z z0s5)F4vQ}+zvb-cj=|0-o=H+SdOi?O@^>n*9O*_ax)EiV>5*$nraD%vaG~2ogSvV_ zC0~%WKQ<84U|ELa820R`t*x!|<3kWC$j~esi1&BL+T+bVJ%C?Bv+tPgY7D8esuv}4c33D+5)tONS`oLg& zicwyV0Z_!nh$z@iysK|uuR%ABKehGfXGdR8v?IPN(H;kom~fZ7ovp1Wp5tO5a0#@> zdA6i-ZSiunRJd1jkJY{--j(Rpeb1mAj3@fEGY-r~{^lOAGmY-G9f>3uOe!A55Ag6E zgQ-McFF4z}x|Xwitwz%_=&WT^!lMe!4M7*pTccYr)x*OB{EEi+w8#6Y%xHgVpte5k zwjsGY*3Z0oltU&`g_v^&ch(32&>Dou9lA?n{r$vVNx*n$I}q&#pdekWzJ6gil^yYJ z01#b3&Ia&7h>R#ptypc#89Qp4H?<`;C7QR^Mz_{P!RofuMBvgePqsAj;r?11P6?HYy z=wPom@*O;~7}471=GuDmOcF-|K@h2If*1itfL>0EZdq%%RtD?UgjHML6;F9w0}R8( zz8!si-Bxxx|8c;b7Yw^}64Of1Iw%NRnGzV3r0i&swtFDf-$YzpmzFD1_MZVdVy-m; zS88jAmX>SjEYCAJHE7wd47IT2?`USJ+1n?oB+)suZy*meV6Xv_w^2 zc0hg6O%Hzp7o?HfKp$7tP7orLSZ27 zfXBU|J)Ygsz)w)Xad40l6TLkhscOZ3KDdd}#nuWLS|2Z(_0 z`sK^$yB1${OO`HcXslmay9772l+sYQykYs$Wp&Fbh4R%ctzWvlu5oEY4P~L!hMKy% zW%V`7mQazkjr>(x*HB+yx1=71VI4*vLISX96n5YdVy1OmTN}R!nsF+cg2@Q2x`&9L zVHw@km*|N0_Ys5#1e|q4s%*72Y>;s&P=zr((1nehSa@Rg#Hg^-u$-QDi_Cl&Km)MO zfRSLJ9UZVdlYO0HN~T$3WWU6c?Wsgh+}hoqO!dK-kv?YNTkWzef^2Es+y?WzdDqC2 zmvoQy{bz3_#*j(YfU9U2SOmpg9~!#t-LL}R8MxKloY+j=A%(LJClwOA7E2APCMn>= z1c|Bj4t94N?D1JL+*cnu1_-)DbD|jvPyj_5o{%#OTMF=JYB8fiH<6MgADKn;$6)S9 zcPCOiVRWTpiEeUq`0QwRj9K*n$Z9(K+q+3hcJ3ATlRri4@xDAjW40#^QfkGgp(B=x zX<(4INhnT6r7^l5{)vIUy)cpz&ATunwb9K`AE53*tez>(CmJFQ9QiCfYm!8wXKwm! zT%!rXfQWYVc_ur|usRxXa&ZmIjNQt_E64aiAc?|!=}AU+#5?;2;#QhR#ijAV7c?LB_EE*r?W*F0n=H;&C-jZl#2C->tl&Bvrx>Qee zXWyV^qqWPma+7BFvNhg8SV8_LI5h;L8l!7FV*TXyd#A8~j^=vEKtqces7bPCb6W?? zXX*+XJ*3cB!ZHKGf|Wp@1OcL+KN52trLNu6(hMENkKBf)$oa;df;!mU*Hx=MsPdZ# z5iSR~gfANG>+IYF|C_%IO(2Y=1MwXYLUfuuOos+5VED}TPzM&s*@MuROBgB%|$X=s@H^fXEy~B*`(Njc_dFRBs2je{b!V^h?e}v;FILBAJ zl(m1TRd$N*?Y@kXZ0bPRFeG*hvO{8tMq*+gBvVg;~b5Oy0+ot+8k%UTq{#p@Cb zxj@(R4w7L}P;aK&qGc<2Ug3cBoNOo9qov8g9cTe2sVr!&@m|b3^+fk}#P(W@SkTq1 z&Qu(L3eY87mqA+NGflq+b|ASEi~x4MZvrY#3Wq@+EhC912TxLMjl!1>rwJyxlsG*oB!I7b!AKGu@in`s7ady)KNV z`e62@SfY%ARK)%t4Uu_{3axT$Cu5+WMic_EtTSEkkPYmxvZ6h)feYb50OJx@8rc^@ znj=kU)YgC&F_{*R!7a}2MBk*GhS;)pSKXx<)Q%-mbjB#JYdC@Fm#A@I!w%LHFFu_w zLlH0omgaW>n>?FmuUV#&DCmfH#s<4F_32L3Q7YMOTl+l+G?4?t%hK9;n*Tl1Z3u)6 zROZbDMPs55_6K0r(1Kb;O!AbvkLv3?61$rBXil8bHLXdx3e9q``4};73K4)+vpY6m zbirs(JSLN5K1v8+8Q`R&K;!1-4n6Mg6ve3?Q^1Ug;4BSZ#_ z_8L4HR_W2UghBjV6&FyKZp%Hqt;@T8||mt-jH5I>kR=ty*GokP5Qm?WinQX?HtnJW&mAzYW) z&dvpu^>x~%4M!&K;Mn%unDBGs-g9Cus6-aeg^9;Y@Yr==;=YkS#(gP z=5YGRCmZjI59rC|T=7{L8FdnU<>{Pkhyt7Y2a`L|_x209`uf<8qqu_niMz@pX4XCdsM)k9v4^!J()3hv zZf)w|aUg{>+cs!#_7|I7sScEiuIuZ8!-K&}1)ZQCSX-aw*Cw?#+S02-l{_z=cC6(t z3$td%fOs72vY?VC0JLv9S1d4|1>&LP2}S@0SzNID-~xat7mW?_5CvM)OS9~02u!i3 zeYQ5(W@hP#YRfjDdd@^6qsja7QBrJ*q@g{ zcRbOxGnKSRIiTu%Xrjdjrk6~tT`uU6ZTO(ACMIQQ-<#iHbz=}}0cV%$Oq5XzIrfJX zF3Ym=)8vm#Adkc}N2liWcZ&zlr$hxzBD6QRH?ub-36;1V1|eobDV`FI<4{BG7uco! z0x}{wW4ULeVcHXOq_9Pp1ucoS_a)u=Wcm$>MV>Dj`cZiNWF~mzXqR@#HK-I)OE9km zMv_b*9e0a1GUyiphntSKTnB$N*0QOCeES@CC;=lp&%IeY#B%S-P!1LZH39c}Q%f6! zPjn|RwImI~=$atGXe?UW($PWaxIEs=lP`(RmTk!a=)A~=X{Q|tns{}?3MmVepk2*N z*t&1tgxQMb2A=B#sN}zYc0?Oc44dxVvAxMCN6r#Jb0ErP?ZWD{5}E3X_4LHhKc3bH z(~`jH)}XT#2cvQaxRxoPYIi#gv0xG$%oG4BiVX!%xs3yQ4-q3rR7x?{z*f)- zrf+s8l2%tg+)AAske1=y)g3=k-KHjbHcylK;#^544Izoi4Tx|~?E?uWYIKXtXT~q~ zttBV`KsxGo291hd0fEeLp4tG8%hR^xzfKFJ;5KNroBXludt$!0OmVgWlZkrM1IaoQ zm_P1i4%7pR=Xp$Upv`SyJxsA6WRwRr6H&c=z1Bs^J|Ys*qHBO*gFS=YfW(NlRFEl! z+Bi0@F}h_L&<{!r0t@;&vCyDzAl3!aTTAgUs65lz;G03!gGn7mX!<`gQVBLIV zI<=lo;e+_8&7uq((X^udT)n${BvOKXr4%Ruka7IjD2*yn_(ip%xRd`wRf?^9pWM%w zg5_zBU2wGL65tBL)05tM$hO6USK z7e)#c>rk3Uii%5Y8h8{R=;V1C{c~7^gnFhqpf@i_z8;Anfg_oGnXW>R?i9=jkt3T0 z^a%DW`hyAYM;f!3G{5!`;XnjzxWLn5=xKff?ndYiWNq|7*s=2dPVulcB;)Z8(46M` z?i!@PwKL@LgpUi(`MB6i!x56fIM30fE$9ZbB1n`O6J(jOSck@AL8XjJPMQ-3E)piy z0rk=af=H4P8G4{|Y!gWk=ILw6^~Lf7v00X}MhQRC<>b(olkibYSIdGRtQ`{GM<#6( z1$PPy2+}l0GBOic;BIdAB23}6Yh-OG2Te3!UX1iSVNyHy_V=Ya$QQeIpo{ejl$@oN zngJ*BFb_2{fPyo_+FB&?W#pdvLgO;IfUpu8@6nF7f3Q(ncFXHxDUnqp*{A_S;`!O% z(Lp+xlGx0=l=<3;>86JD17PoraKmM=f7&sH(!3Yz40z%PES&;d>+7K13o~m+cz~X5 z98vceoy$Q)9QzG0^R$C7%Evr2)@{1R9|#SO5TUiD65So=xFJ8zWvDO--%My$UbrVR zG|s@;Xm%dyl^PNi4#A;+@T(efojT$wR~HQ;Qm~v73nf@H^*ESuy6I(LJhpvs55{9XIt0Ma zHFWOW799x?N8Mm3yXjL>3=Xoq#I9qzyG~oM9iEtgTf;c~(fN!392(UTR>qN4mE24C z+8s^OQU)=j|BeN>P+4h7>xsIr0+n3$4;h=#Q@R6|T6oCAE}L|PZW(kR#QD=Q-XO7n z06$ixz0i@WRbFM;i+XibC@m`YPa})lAafcy$Y}0p#-biFn*FM|=cWw6!O@2+H1xt) z#^};IGr}#s44ToZzQ1pGO9%YCe!d3ldZ4eT57T3H630Sun#iD2TOeK7^+sj_TyNmY zG-E}{&A@tbxHZGBVRzeEa3Zt-GwBVi_rb4#Om1$JAy^#XC^xd38I&*DI*=J|jrzM3 zz(LV0Xok&%^;n^V*b^OU;Bo=zM7h#%fY!x2S2j;Iek_;Mk}2d3vC+45HZ!Y25w?QA zL$K&t46o}90_Wq+2H@@Ewc%%q>FPJA0`RQ1&aWJ|v?9Q+d2@#>W^m&lsS!D7qX_Q9 zRHvc6jJ5}Y0+Kg_QgycF?$jmhRSk?>hsp3I@`vkf0DLn&~Spik~4&UY7fW|VRKpf2u0ws*6uDJ^hzdAd&}mI=Cg^7 zP$)WS0B$%bg?h-uhImjgQa&IDFuqNr(}jByn0_M-JlYBGOaR7bjHlsQo3Uz;e5P)Q zMebA8JT0wpaJ19sV*Rpzs3X2(ki!x@IQ1j~g$U-Gh6(P>4zK|~f$#V<80*o#!Iagx z8!IQN-59rYb;N{7LD7R!!lCh26cNyf9>Y}D;3z$^2IPTMOo|kc(~CA5c6v8Eb_nx- zP%lUFIB6w}d``YKVt@a_a1_X{RgDEXbE2SyV5y#dD3(IA8S1s!L?K(fM&No%D4tX& z_Qzv*GvqZmDai)5sxcVBF<@BIKg!;?mZonbo6#}otR?;gWZFiC79wf?7Tmws3W(=n z+!@pK6dn`eyOxPm3!2xRYP;}_vMfY%6tbeXeR9DS446tl8TLoUE8o@h34H|T^k z05+sVS5b&}QqKuykD7UJi!99cJbj&D^iZK0EK6lQh8xJZG?OA)WYXNXD6E5Zs9hXS zJqEZBUdZFNu?oZy(0}CzLnaQS}>&(Qq0JKooMC21_-YISzcflA)L@#6^dc$1Q zCa8DOo!Fbo;u%}G4*I0wxstY61z2Q5bV*C^5eYygv3km;Nx&-c_FX$zAK8-XP9oer zGkyr7n1kYJm$5!^4z#pG&cc9!96{-BcYx46Sdg>4ewiEe>rn$?uAVOP6Hyxmk^4$B z%{qXXn>)n1o~5uqJL0>j!Myhlz3Yjt%$WLwZ#@h`S+y3OD^#JQlWfA$dfJf)p+MN$ zjCcUV8bmSf_CEk_nuGEo2qfFY#qOWcV5rL^4$K3KdUVL3nv zFF?<8m%44qm>kxE5vsf^SS0)jctG}oY||wZ7hABSk;U4hC9jEtB@0iWx5LFCJ0}j% zbiH3P2C3+CPtWa&~}-0#YdhQ zW%3>gXfI9I1o$iss~vIhWmmYfJFH#1`zeHyxEjT54$*NFC!W>3A;RE5?pw?*LeL?h z{OB1Ojtg?*g2~2W6W{BwmbbW2c%-|994aOnCNkmOVn~%hOsH^X{>kNJ;Rln2@#7*s zVPvv!Ap>-#Sv((QM{6~0`?(7-vOuIoEP3|YJ%g$SjWw6|IdegfyE@%LVV6m8@!7MG zT36M66k@`NB%)|kthrCo4g)EKhV6zHBDj+)xnNRX_salYq-EA06I>F1^g}@9pu(PV5oL<`8|Relm&Ca zhvmE_62S?h3mo^jJHoHAs|*JH{~-LDE2V9hv-W({XyR>q11~~nPpp&N2tMP3cYGcm zvcid7%_Dn8FDvHHl~x3PSrOB7A@3U%#DO>>#;jx2E8}VYr6bt~E4P=&V?(qPUIY?k z@9s^&gzDMM+qRxH*s~)(utB!N5Fd0l5B4Jc!0)yB)k51*osGymqQz{#FpyC@hMBv0 zye3fp3{b0dybB7)yKdCBw>*Ty@q@LQ;ME}%;K#m+tQaqmmwKN|FhS8Y#dhw6&ewxk zC|IBMG-bz;zyK{p6zh3zO_b>jLr)liI5c7S1&7A0;9+z7sux$KANGZ6>FvWN!L;QFZAGTVr!PQJNDFk_ zAv2wzDRJnqg7SYfWz^48zE~;(mdEl?8a9NRYY7VgqbZ~ZRv3*kcV(AiEJ%g&ZKxj@ zm>sm6kJj>b)28oO0-*692zsJRIG6dBaC*Cw01BiTpI{+g;H?|}V^-(rJvLdG>G0)% zH8!hxbB@k|SUXJ7F6Jg?rir$d2DXq(FUYnR#><|6AKxX1w*iSpwG3lAeS;CR6_2;# z4xJBJD^z>pYlRThzG*95u@DH@;Td!I)Q%irny~`PjnNnaGvT8Ze?O|om4~{XBt2In z5Hl=a%P4<*#3<^h4Zt&SNQ5>}Z9c)DrTfvWbJ~`jr_2SZas&_N+oBf@Ca|=TcY9^h z&9(CoAhN=cC-#$|L3q&JrCk|7$kB)c65$QAv%lW1i9!|hwt4TUy$y^4&u$KKFul9Q zUCIrgFX@EPWs=wgMN?GZv=Y$XH?5@i8qAnhqNxe3O|jaPLA|5$h8j7)o+yh z*O-Ofxet`P?VO*<1-A^`5W8_LkAekZOD?ko%KZ7>PwZt#p^UQnNbjGVdy}Ah(?RFRIf;8o(lQsqHg(Zb5yK%5c`gA%){*VKgRN)~cl7AJymQG?!uH`khEoSdI zSV^&7HlwIK-|%Hf?7H|x?7u*p4QLiF#3U7>_IS0Jm%7UP2}=k&lVR;L$|jKxO_t7C zAx&?@^&0_J0*U|NO~xQG%&`R$y9FrH1O*(iz9l3UEsC-bL`H+?E-=mTzz?&d!4M%Y zBYEI?n9`$rjNjG=?+nS?VK%l!=~>1w>v^#eK^SD5cIkZE?UqGd!7r-i1+5OQHcjFO;4S^_fC$^aVYlsBG+C6B{6o zh;}Dq2$W;LHV}0;ZJ{SbHL`t4(FuNcf!5P9!5-YO5EKOVAhgTDsGEXfTSty{Ut(h28R$c46YN#dhZimB-;4P_ zH_T}WIrNU&puS@>tx^u$Q~DodR7rRT!7x{(!Z5D&4%09KVie7C-2ou(2C(Grp!4p6 z;+JGYQlh-96=1_gNnb|usNC&47_9goLT0$JuU_zJ0~v`I*Sbb}`~J=O^UTjVS*ZdMCFcbkVG23R*lU9_7lMUj48R1vEIxV>F6v905PZBVbKB3i?9$C z+f$1{fMxl2g@;&OJ!VP@_;$huUiRK$7?EJ40Kx?8LUpvb!_0Vjm`3X@0|SNpTV@Oy z4&n2Yj0PLbDRQ7nmfx9cC0I!m+|QLeq%&|LBYheYQ&O&_k)F~sNR!jDRTRU16dYqo zT6EoLK<1jzyzi-Lhhe~Gf<_K{1SW7af>3}QUo)CUd#B4{J{P*4sH*gfZ3z^aQNJhj z(q<|$w5AT<8fsY@<}<)BLjRy(NyK^aF8MhSoH^1LDk&TO6ma6&RoEhtP}0}dtbVy} zTJ})X(-QbpANIO}(;td*+PYvfHvqm3z9l1N!Ul51QrOP!YEgrym`WLdeSzad2fFZy zV|z1ky^ml$(8-3`dq6R70pr5#i^oFrp@)8m1dU#>{i`G7-90lru*NU?`+^63XqoM{ z_cQX*G<@id7PH+FJgaCyAuu6K=gLj%MKXcFTlfro)<)5N(uk#FTHXz_8}DAZ&(x;T_UTQFwabAi}k~ zkWFb50y1>Gn#Vf=omv3^5#IsT2&XF!q?5sQ0ghnRA!BOk^g=$t5YyAxgQ1-wvO7pq zPd_dj)*H!SfYTf&B0OH4Najd616|!m(=4%85Eh36X+TLDF1b=J6E0a}Cv>QDnyZ>) zaWaEAbt6wymG>q_Mi`#}0b!N|0He}fwt6@AQLt_l8LS`+&?zD>bFU&tMA zA-;J?eBH{@1Uv@pt?e;`tx3rYw&0$5Xt15)rFni(@6Cvr3g#@nN&|vhX;=!cJ`LGR2GP{A=ngmV(Bl%HmQdK6|H+pO#%rp*ajKH2m~YTaPU^cEolh5XzH? zCk3%`&@(d~2*#>I5xEliQdi|CF>QP=R!6+Oo90$d(VKhECF}-1#W~0X=ci^I+cZ+N z*eItAc`-V3euG{HziGjl8_+8Jj_^s&R}qrPkOLms$gw1Z9SAbrW7hWO3_0&$q){^1 zpm+`v-(sElC^dsUB$^@7VOYlY@M!{>e93@_Sb(2&$>Tech#dt6`HUVh5po4&z-}sH z*ptZv32Dh>Dk-5*r+P^;$_Xq4_MjlIx@8n>N5`_kLy@)DJl-I!H|^}UOm7iQ&3e-{ zImI0LO!X1bP^(akhO%UO6!7;i+h8K?B}PxIZ-={rfPPXeHSOylJ7|t*h_bNDfhYMG zNlx&}h|x0YYYsIJO-7fdO}NW&;^zPBI%fp4)(1PC?zkQMDQ z&){pQ&9|M|Xs{uTD_~-fx1ouH$?-}%%eBN@uX>hV31&Jb_|Dj%(mlQ@Ex=?% zUJzh2<`hv5BOCvR-{z?kCsIIdM$AJZ*`Wh`Yikq9LD>3qKAAhKn;v7mu2y^Fmg(>s z84`2HAX-i5fZ#f0*>}G2kf7Isd;NtYg&aZH5p(F~Co+rpdd(6d~4A8$usTwz0V{1ZA1 z(e+|!fr5q6t^@Fl8+%MwqGe_J*p*wmqT*(J!$_=zt~@zU4!#48w;v0|IG5 zktSH{DYA5ZYdv$^Xgiofv>huu$&V%*wE|GGaW+*x8kHz};U>KOslE$o`V5D>%gE=7 zx4ubuD4>|33z)Oz2@KS(pYhD}h?o;NytF=1=9SjTj*24X17%Zf);4xoY(%=8Ay1$| z1WF97BBIr*5-<#l)VC9!-UyG18+!C%_NES^?x?w+U!9HoS}uA87T zM1-oJi#5Uw!XKzLycm?|3jZzwNYUGr@8|cu)m7aId32{!A(b>q(cQri z#G6~UZdG4Wx2jUF?#7rPK2X#V1xE%E5fD*uCL`#Gf`fvLehP!5Ag>Qw#s?#)=zwGp zW&X9+zxUZ^-+k*o0^is5C4Kf?XP)~Xulu;^yl?VL)ZhDlA7aiG$$GHoGS4pLKPPH zN_{~hBOyeHCPK+uFn~TX8n#xuPpH)U#z4)U0I8xDSKqve!u+Vyp5}d1>qbde2I6sX zqs?G^X~3mP3)^mynQ)j!U!KDUL#mlAfJKaLBv5z`bqx_I9MgCxvy(db-;Bt(um?T1 z0?uJDVxp98deF7!b8tjb3}Uzev6$d0!Me8j>Anw9&C*62F5pN|SXW8sK%cg+u{zsa zXbFiYQLu!l7AZj4$1Xnf+4cP^%VKI$MAS<$VSKMU!+b_LL$$g%LwP~Zi(ew^rsFV# zc-T&`XhS8u?Ob%2$Uuj%B*5K_NP;sUh=@=IjfC)PaLNr!RSt=TTwG?!x7gz(BNYt~ zKS(3nl{PXx6G`}KD@2w=U&2tU%Y_|6R>momrr#+qn=KC_`K+@13lMSuF~aEAaxk(? z>mi>|c5QAB27oqJ(M;t~Uj}^?CTrceCe;#TJ?XN7T{V1FyNZ?N#a82#hb zD_~Qvkxqg1qe+;@BzUK3tT|@7E}WW0eiMS~NDq6_TA6S3!ua`lXo=vPugZNWPjvp# zovc)^u+H!~)+&&t;JDeqOa>8}^e9^X!NNKY&yq2%#%VBC@iAwtjieW(4GO4a=rY1f z4Mw!vCDRE+V^q5sGzZ%dyg@$CN+vt*@}cEdgivSn(-$lv$Fz@+{Aj!#1f%10LB2DH z=B8tzqv|aYT;rfQLYNVMMC5t#h*-d?`EaoVH1=pk(vaIY4vO!FV6(vVEH%Nv1l5}? zOW?a|R+NV<3qIdYO#Jyz3Kr3Qs^LrvCjnQn>6o|co52gIu26`G;f4__B#u^K@$Mv# z{ldx`PAvHsj?u-w4tP?R7f@BX}&6)+Y!J6nk%(1X_Yl(HMtoSar zfE=UK*}dmC1}1voB_(6Fzp&C&!JT^|5qquH%d3kZ?i2A8td+nyU$T2FA`5{6Z0|Oq3 z6oZxDhGB4Reo5o7iI<|Xk-Wc!&9IEg5X*6|XThW6Lnw%3u?a5l0Tc#Z@etjpP#h;m zRwM}VT;WQhjFhE{0a-f_BTrCf&|4}&fff?ys%o`)zshUG5dcJZ%V@h{Mk40eOVn6~ z3lQ-Y{Nf<{T0BudwN_JIhq6F8W6@ilwkXMI%MUT@=^j*Bj?A-@-rGrKWEHC7mBSer zF+pGcWa$i5j#lxA;AvTLB!32-+fGd1gN~J;i)wRhY2-UJY}N4+SEg7JJ3w~^qN=xz zx)mi9&VG2c0fnw3RShvhmzZ6_Hj1Mmp(ixMVQX!v4u)OG4{4#t+zb~v3h%-=Pc1~9!-g6Vp(w$ zhRufx5t9Xy2zv`-rw$CDXECDE2Z@WG#qnZG=!V!S+YZ(tu$?ucb}ArA6J3@?P6W<@ zHKrcS17l>t`Gq~XG%`dVi*U}yE7yGjm9j>1n3gTxi{SVom70BOvX7z|w)F7bigAl# zuLD~$i=w&b_+Lg|`CmBvg#?r^sewK=*{}7cTO`kLjCiU*b&Tr3QYRoTW)lZ7m{}$U@+PcA4IIk@9Z~qNPcDzd}aaSI12_Rjny^O6(Qzu z*hLi*_+oXA3JUPSiJWwW(!NX<=%7PUQlMt+LZKN1vM8wp^)wR2f2S2`FB_0uzGRG6kP^ANVJR+&zpG( zlE{dW5ajiY(nrrhAKlNF4r!_3H4L@sB{&ZWZ>jbJBK-*zX;~1L;K)3 zM38~TGQuNl>b{QVGogaKA+4G2WR3&i{7xyYY5=kD%QCL%Sv9y80AEojE80 zSG^fY=dK=Xm?d)WaQM35Xi8^ypZVKihz#|f=OX&2H znXb%Ek7b){vfYvTIBT(y;gP)u&~Pus`ZPmvNpuPl8s{Law}UOZSPj#e?3NRA0iO*; z;6Oa9TWo7t;g8yw23HQ?J|?+KA|L6ix0hXavX2$;2;{KSjK z(Yn1-N_e5zooMtWGmg|sn2tzZFf9tb8bhLqkcNgW;4UoJ-8AC-rDOo)L6!rcjAqpOOBG zy-_be_71L0zAD-&c{MvovOA8}vKS_ZoTgN4KMOuhQC?}-GW{0+drjWr&3Z!$+Ct2% zi(;=tmV=Jx!D%Az-s6$gyhz}urDe>Icy5bLmr^Ju*T=%>Lirp)Sb>~RoguZj6ir<9``pywlDICyodjhxjjE(IZ-?MK54OREc|K9oh z2BbY-6y4x$;zoP2650?Ptf@q;5@Z@P^WpcDxXK6fiib=mEh5)&rK z8=|GzCoSs(^a7PZNvAQVErf)ucxIJ5AdAaiN1J4+F- z^q8!M#zh?6A^2IvR&&y0#niS`vbCaqTOtpomtQM&Y?*^;R6sj-XF*BevCs9 zji+a#k<|gJ+E5%LCmQ&CL_5&EW!o-4J)L6!W=Nzhx)7p;lUv`p@Ab^C1ew5em|gYY z8*vz|R8Ftc5Y7mT2`5sg4N*&k9cDrV10@=PPJk~5VZ@ElWfg+s@~+s!pqaw1*JE1l ziGXQ~-NN;)F)=dOT5)C^I+iVYi=?bg^kheXIiA?D*=lVKVIt}fqrx{k4o(|_a48K_ zEWJR+$j}ulM?zcY7RuDDs6VsxhNT0UI*Kr4%9cTZx;VSI)D&GA$X1_XUSe|2&*;H7 z1gcNSa7f$y(FGYTG3|)6M zvF#W*ptY7)TkEGP^G$C?;=9eQWxF@VC$UUD=+U729Cp6%1Z~afu8AS=uvpY5#~j9x z9XnX|_6cMDH=4kSb9Rzrvn3-EJJ-tU3`n8Ox#g_7YPU=u791_By3bSEbI3tY>w6O@ z%2f!3&{v6Cd_paMvskdhGo%vD$)W|)?uM-l_d>D=X8(6O~%n51H z`4LV`$U;a1G|u9@*rClY))&^qrVi6EZrEx;bCs=1nk{urfSKZ8^JJ8SJTn0ClXLer zQHFL=`l3SD)s4ow1?HC*M3a$7foRWR4l2u#K{V^_K78Aw1{0FmhmQ3`5(aF{2jP$o zb!Ib%gklqd4VB4bnfujBY=U_V(KEqwfcD7Eg1Doo)sckCMA*TQ8*iACuQSDtevDAM zIP&%NK^eQHDz-@0&{~5SSCR+FY)6BaBO5a!emb*uEIu=l>=-kwEL8101n1<1+_Yqgw4e^OieNI2{9MMFOgLci2f=ZOd=yVpgBgb z?p*zzOx0Z!ld+ye=rqB@c7xpFM194~=GAUfR^8xp;TbKoXDZafaU{|S7ix^luNQDK z1%Rk_*5gQtdVnF2)e-H3ZW6JK&G3Wh%iMAs#%-G|<3lhw2@;BBu!bFFEqcttvBNHr zIA*#f&_te}rtS#$%SMXP+0<)4=N8WJd6P?dvXuL7h-X-E?E$isoq0m_K1w!p(d;ne zNiOT6G7%~mRD30alk;Hg81|{cOsry_5V9cXNfC&if(c(+Td|W?Y-N}Vh!z7%j~lF33?YUO1Hs)p?GA3QAq|yjC?` zz16We2@PVeRt8H;nMD#EtsCMP z8QP5kUvdZd1W}@_ZEE&pWXz3}|3a49nwv#-8(p0osr)(vYgf{4=mPTwNL>^u**Q1o zR(xJCaoI(gL4rDq@zv#~$TOh%J z7+;`HUI1T+7ERm)M5pM>LihOce8q=s5afbgUDiPr+l9xSC>`}E>vFJlpl0nD z8pix8eNr8ZkykF~s!E$pAsKD_E@u+L=Ow1AMHrSL_GsbatAmjv+Ddz}R^Nn8w-`Cf z@I~Ft;i(KMN!7P#NJ5B2Evld>YA-ob#}?Ny-wh?xRm!h^Ryb)Qi)LG}#@P2d6*FD) zhayHXS?eVc#h~*#u+I$+9`m_D_)BEW6NW>`I?e2?OJ0OF^+Clf-DQ`U-$009K#`)a zj$I+KvUGQFgeCvG>44D(Wc?6EIl^qVnFbvjPfaj+n*>Bx7vZH^9U1r9j3^HcCh`VI zrjfBpQePm;C5o_Dy3`oyxpV3$4H9{``GN={fX2PLhe$!oCZ&v4U&5v~%7IIIF8mzL zr7IsX@HWlT3QBmSijgb|kg=%Dv@0@F6?j4XTEv^el&O2S=gOpsMt`0;R+G@qpfh|t zml342km(x&d&GpU5KHCQ6UD;qO`K%0t?C5S`xa|Xh&u0|Df%Vw;HVj5 z?wNFMt3mQEB^{_7XPgCiBi8^7G!$Y7+rA8CcaV$(89k3!+dLlW_#-HnkH~~IWnKUX zCJs(v1e6)|$=FqDcUh#TXb2MITCJJ_UPn>TY{euoLcf8w&#NU#zWdv>%;7LDf4s1+?iL$^QfzPPL9}t2zzc6x79xs%$)3 zFS)~gNORjFTG62Mr-F*TBGte~Mdv!KJE60mok4;bVMiriYo&HbLSrhDFa)9TAS(Z`CJC&tMLbP+A*^!ndQ8xylR8l0HaGhN3@PL)2{XQf;P&&qx^-dJVB zokU@4DyAEYg(5NTGL+R2A?_dxhkg+ZQZo)#FB6})Snp&aw;=Aj=j|MPr2EZ18B#gv z`o)kbp;ND7z~-i6LK>M>!`U@`_u4AH86ZT-6uoDCbs9(a6t)iJ{Tt1x%_-Z!RQI4yq`oVa&mk|hb zEFe$N*j~`>uNuSnY957|w+esUom#cCFDm=7^7A6K9nu^Ay|U#+*+*QS+= zW}Jug8#1_{cumCo^wy4KDf^bBbqCF$iHgOq92(AgyNSp~i*RyP#mj?%RF%)bg6l&TWX{W9HJ^Ow0J}VHf4ONuG9D@ z$)I=gMf|R&Wc0;qiG1%Zf6XzS9UjpZfA=3INN z@|rr5v#q%nA{UDfKj^3u2gvB`vZHQ*jTu%fmMy*j(gumzWgMRt=Vd{!%&y*7dEOm& zjU2lA>gqmNgO2VU-7~VQy}q&3yk3cfRs%olpqj2fxqoukuaZ$jHKUK z+qJQT0F`sQ)bDc*HzB-k+_wvxV;y~5Ufl&sTJ%%?h6FY^?r-B0aHBCF{g&|-j4$8d z)$>T8+q_?;AIbwomQsHHAGK|>->+CXAlMgss$f&mrR>tk-?p?4#M8IDb(2+;u&I=w z7mVs)8z!+F65VOuv~@sieW!}S`!iKQE!h{PgrI{7sb&5>E75&pkXVfti|v;VX|`?& z5oVL1TwYw8nz`l3(dDDHsY>m6hwr@U;9+dBjoI3Ct#(g!ycA1UpG45;Z|P(dT*1qYT}qes)t>YzdA|tBpZF zCMZYKpd5J}Xvcy8HukF_n%Y#M&qK1>C3at{qQXMm-w>;vdL!Uo`A1dajbZj#FaL%^+>U1j$GniBjMD^dByyka;6UmNELO!N(}hY+!v_{%H$Ji|eT1ViQ1(DJ~Ea^b;^tSQvT zDX-px$BM}IZCKNm`bpDO^Wha?GR1U-hS+G5TW;AS50PVfGIR<=XwVW`_5KvYD&#C= z;KGp_27*eZO#*2t~WF42_y%ierKuyTE<;0SbXe;msBHXIed0&& z!+~`$_!&Zd80I++kk$`l-Rah-j0n?z3F{Xa6VH|i2gy^pyWUP^&BHOoLfgv;xFm={ zUoX^8!U?Z$)*zK>V9mDg-&n@MvOI_AY@(KENx+9>Z;2yp-TS8wid+K17t{idHx0kj zkHkOpzMBtfkf11Ed>ZJ7MMp$ilYJUSIZvQ@=8sx@Nxtvo2n)Yp2%MoBG!1 zh)EDwa1Q~+hG^KN)BF+b57NQHP7LkhUgncLZU&<7^Tg31Y=}d-A^SmhQD7w7a7JD~ zzPzypYaWQdo94CpcVuq4!+Iyuir5 zJa8l@)kqL`l}k2p&h%|+HPDOl@5mWF=%i-?$trOX1m9ryLUeDeuuhX@?h@~QLPw4u zqW7PeCA)fkUh8N?`kKE0HsclqS_ip@E`w5U8M&;UFO7<>DWCTY6LNHY5n}8Pf(o&3 zVg76EE@yALajZ6l*u0+D8FaK6zf8|hAq7^-9?5uL_i>kjMNIVOd>yI7YW0;BIZDOZ zZ@6tCHi~NEF(XH2$ufPo216(~$;2uLztTwwiWrmlx&9j>wxSK9pqyEXCk&2Fb#6oe zn@|H;1b`@joX`?>6%D~5RdV&#Dt z$SJ#<*@q3E1G?l{Xd~zw%PbaItiV8>api*3O6SAqCtY69{L%GmB%@P(9(`=>qmD^#7bIelu`y^>vq5d;1{2`Db=z0h7~F0d?LY@N(308;3Oo8 zyq&|J-QS&OelfMCeVJH9c&2qZW8+aX#3Rge`Mi#a9f-JV$5u>NE+OskorT97+C&#) z26{_XBC30(RN-I)J%VR0y;F5Ebp`3$YmeES1yprr5l?ewkj1yq|u5U_~5;~54bPqXQvI1^Lz*GDf^~tX z=35J>pld)Lg=7_zT4|h+LDipf42per9d1o%MHcU73u7!*TgwE^pP0kbB@WeItD`0j z)5)G4(Q!hr@Em;3*8JCjON40{T>?xv$e5^jSq;)Zv?Or`*6mIBB~ywEZexj90sTio zP0DNQC|MX1yN8e2h5wiImj+_+*$M%&&Blf@$oL5PMjNbMItk$?3es6zr z4NI50vnTBKZnu}E%iOV0S`VeyhSIx3>CZyx%b|49q_y{4cLz()bn7g&-RD@k%x&Li z^*(@Zv3QmH5=)o43-;UX%iJE8er=ok9E-QQtFE!zhutPiGwwqyjk!lyy44-H*6QtY zODtXCeu|~fY;#M`_09YiOEd1=>kM|IyN#tQ+!9MqbU(n-)$U=IUf{N0Z%;hrzK^9F z-TPU(!u=IXPjp{n>1qd&z5ZS1Zei&K?sY6pxDT_`cGuo$^=90wSlZ`)kEIFs)lk}b z!0P?}cDH)aiod+gJ?$ndp6_;s(se9d<>py>qI-a)YuvB1G~xb^rFU&}Z#-npV0p1L z>ORZT<*stG-Tl{X?&~b>aOX`KaMWGL(igV5XWwGL4&zt$>-VapWp6Y zc&imJcPCle;a0rxL2^W!@ZWJ3HOIAjk$jfchCDyd-kB4Vd)>Yxf|~`;34-4mL}bA zvNY!Yj-?&$>nvUGu6>a`fo1UJd#pI`?s>75E_V;GG~(XC(hm2ZS-ReRktIC*wwL&a zAOGD}dWPH0(zH9t(pB!wEVbO@YF2O5!SYA{CfpKB7r9rkbd`H2OXs=Y3iZCk6873# z@3n`Y<37yNk8E=qlMx%+vRCfuK~^igzZ-fr)3zrj+=jVu`KDt8-8lkVj#-QzyR(u6zz zxYgU`u48G!t%lOuS-R4Fgr#S>udp=fcDC%<2{+5qZSI{cVQKvAOYQa{_gR+qxhLLd zut|5ArIz~*mJYf{0&I5C>Rseu_ojcBy4SLFiF+qYO?P42?pEDREIr5F$I^s*6H9aM z>?NyrrMrryXSpLRUF9BN=|=ZnmUg(0u(Zehdw^ZAY_0svHup;`p67m@rRTWMvUG!c z+KN@Y#=VfGE8NRiy41anrHkAxF2O{)V+tLN%tj|E_LUv z+7oxWm#{S9eu||X?yW365lh#*b52@4?CIY-WyRg@pIExp zUGp;E%o zS-RYPh^4CgDoYo;Cw#9xQFS-4w8PD?wB&w=r7`!VQ19{w?TLo_0hTUzzsOS6eVnC3 z?#U1NdJnKvb-&6Ik*HP3{JRaXvn&7fjr7)I0oaB+KX#Vg8DWKsaLv`f6!7hp3n~vk zlNEUxA^da#A18d|N>=1$8rN-=r&ebE(g4yw`MV4MZ>v11vi~#sGyEgNEAPEGY3GNv z{>7DNC-r{`@Ld1@o7Ue^x#ZO-XxXkG)AEkWlN0#=CHyG~{7LBWw#tsmQxo_;g+I0O zg5M;J4+jU~e?oY`=7b+T+xi&@ zL&6^-JRA;$znk!IY!Ut$!ULy7`2Qh1(ENly;W7DfxDs#~w}1;-e}nMA@euwN!UNYs z_=gA&L@?o3eVer(h;_nWN_aR12>(sO1Hnl6(;dgn<54hFO;24{E20+e}4~nZolt%9M{jZ z)f4;GBj*?R*S#%HR82NIU>Il=>_ zMEI)-4}uuNf0^*W#S#9uga_V<@W-8R{YlsJ4TJ|766@bic#ydeemCGduwSO0V}QTF zdX>MIDBQ~Nzi(wbL5jnh|BLVx5B~+>fmLSxvoEmz2kMRRJ%k4WnebD9=jP=ttRLi1 ztp5SRznrYM&k&yC^K&n>{sg9-?MwrH;r6Fg&N)p0FE3>Mz>N|95aEGyBmBP*9^?{) z{|~|glR)@c_*lVX?@sz(B|L~$SbvW2z!DPvyMzZ(C*hwWJcug@|0>~uog@4b90byz zz|9gqM|cn!5&jy$(NxFZXIMYT2Ux>>yR{z#T!ddsxM%bo@zSpl9z<}g|9QfL9Fg#I zpJ?rWXs-c0z4Q#gFUR~|aN6KFR`l;i)(;X3eU!#M<{# znM*k@4ZwG7zp!%7%h@n5E!Gd>aKe9*@E}Me{I>}Yf^EV-PIwSJ5dICq1Gh?e8;n5i zyIuvjtmhzgXZ@$(2p4!@ya~UJ@E}nl{9eL?IF|6AAUsIG3I9XF1LsNjmkCelnI}9o z-~R)EOFx5NgYCSC@E~C${8L@p`9c@?!KdZlI|I19H^r+h!h?*G?|mKNL0Uri2MG_N zZ^HkY@E`~xeB(Rpy+H#&_!VHJbMw0nxb!pSr`|?*5HGWxj}ac^yoCQh!h=49@I%=6 z(tZ#e68;LpgZ9F=Pk4}J5dMr2YbWTj2)~W+AeAQk7YGl^0mA=+@Sv?B{K=PF`$4-w z_;U#lG8n>t9Pr$DzK!*RpqusojPRhJBK(}E+k1nmi|`r3gH)dIuMxgC!K;@(!`cZ_ zKGuH`;X%no_$uJJ{=bR!gB*(W|B>(@^C$fISMa^J8UUZEe?LlidQQD6QsJV|7ya6?3VC%5gwGagntI`TtC0k1upcojB^mZvz?a{9z^4W{|4bfN=f*W zuCjK544m*^B|ONy3I8VXYWG&?O^6c2;k*hz@>i5r#y-9^jzCRc+eEHof*P|rjGERB|KekA0|8~8d<+O zYIOc3rwQQYdcdWhDSz=2!h`;h^-lqw8|U9<{h)hb{eL7pXc!28+-`esP|OiNO?XhF z5dHw+L4Hp7&k-Kf{e=Hd!h_<7@UIab)Chzx@3H;_6%pY-Pk2x&68fRs;(C8BWB%Hg_elSQO{3V13WfI{(2e_Pfr-A?EuW6Uc+gU&5vwoNGprc{^ zCr#RWgM|d)pC&wLSqc9F;X%_%_|tIyO8OkxzX0px?!PRz^WCf;>=$@@6L8;$_=&f%ey~{J%?}bD z>^unHevS1f9k(5X2dx_G-#~cKbrSwk!h<@Q@c%@3O1~Yt*4`Twy{!M^gn#&61N;c# zUnV@5jSznGbFH0VFGTo5fak{Nb*!J#?e8T#l@EN4@RV-6=sJ7vYq3t{59GT3?Ie6X zfgc83<~Kbr?q>a99l>^v6CRZ4g#R1iK^sf>)2`2d?*YJNod=5q)_;ibpb{qh4TJ~# z0mA>B@L&@}_`edK>O)^}gS|IsR$2eega@4};g1j=w7rB2T`2tzR$GLBFX6#+E3};I^n^Hi1j}Kcwl8)V7pED*9Z?r zYJ~qFzE9{+Zwh{5yWM#99r^XV4{#aJcPHm~lkoJs-XJ`f>+-#?0X(44 zU^}V&=QQEL_>&J^e5ds@7PCJ6yxZ5;`KM;q`5S#2)B;|d`@5Geq@6iaZ>snzC|YYU5TyFu0;cuTHH z(nxp}BYI_Xy*W1u@BUm3IHoSOYW3CC`YAYjuCF3L?J6Pw*XB0b?Nj0oQT)>Q0i~*` zzZCr5a$!afk0USil(?Pc@2=EWyWhPAcj4!`WeXGG{?YZrh@aJ37Ox(>a4!Ooi-SlX z!4Fz+w(T8Gw06spgU_F;P2F*G4Q_rl#Ne$>-AdrCHy=Udx)G77LKzTS$hl-K0}JiGt>K2y&{Wl$8k{#sC-P6)}-tm z>>a8l1_nLL5xyBNXz=2hKk&T6(>EQejg5|tPLw?`y;E@#%2ndS9GSCFt`b~pv9pDu zU)o#mOU|j;${D`MNo?Vz#VHl_y)zp!IKcmWdG%CJKhs?NzA5A-Sg%fm#>`o58lhF- z*q+Ajl7#`iwT^y>Er-;a_~PmI;r8U%-l@awD*lJ}yZEpA_%nmVltAQTdBIi#Vvf6P zTw;0qS>Ea)Uq?fv%MY8PyYH@zkM6}Ab#v6(^3CeYHsok(3IZFUWXAo93+s@ZO zm`MpWE}q`r|C*aNj%m5ok~>u3-R!6WYjj3-wn#AABZe;RBV}{ci)_@6OoUkr$$?Kt ztc^`wQt_Vax0R{Ism&uelf;X@X_=PLy0zP;k8iuhW70pwqWP+>3B0QWW7${N9m zQ;v4WqgaqgJaBk+55oMkX0WcRGF%9TD{;4T9gViW##`TFA83ncQdhOM7_I7IvRuzK zb@b4G1R#>VtSK;RNYSDn(2`AR{RcYH(Fx;;G~9iUr{7Q>CuReZ$tKjrvsD~e#7hzX zs;*lZqy|KHAd02NHrSjrzs_Nxk-k#p{UTxDOf+0jnztjIF3$zZ>~~ zwg|6Q?0LyJl#3y8$I+T(SWScY=ysi|b{rBo+%4mfjAF>HE}01KJXSlBpIfW}ZWfTR zjg$47#*7q_q;dSfp}X%sc++&PIy!FaJlRDY`e@5Uk*AugnUGU598sM>0?C%uJThfe zo=evlqjPp3Lg!fb!{jB;4SqPz5F~GZexqZL4Us-pV_NE1gWswzB0XJ+*o5moqB)m9 zTar_AQyugrrn<{GcN~RNNM&ZhdGZLOKa6Jqc{SEyw}UbwKjthPV@iC;0u8iPiN-E5 zH2FF?RPGNFrX96YMN$_iDcP2cK(gNUBCye7E~RZQW})r9qm#8xjMSxL;gd?_qEfvD zc@Zj=zPlO%qobS2{EYELnkz7RbRu;UUKU#y4`KO9L@|a-B3Sd33dJ-oXPYJ})v=Ld z-f%J2V!R6N?C_2veg0 zyF})(wp=@o@E?}<7ZInDK4Aud$B#D=z6+l#$$&KQVu7fUQzQ-dwsjAyqGEsw&py0=(i^VF+5iU6* zrz8tVH)Kpnt5g9WRL&c#sQl*d97QngQAB+^d9sEK^=pzJ~&iDO6<}%Ev4i>!E+Ge$4+1?6$rf_h9?R3r@!m^!(*%y+<|<-^)#?b1iZF#US-CZ6JKztb~0B(yR%E zXp0b%QW8zKaqMAXXbv0us)CFtVL?gC zJ!hfRA)`j#8+~bc_EYXOhvd6486;veQVEQ-Umc#3^heqlXq!krpz10i%M5QMXY4in zzVfMo;Um+7Z|RVd4~P5Ycpg9u4@9wc|LS^JUqMqb6yDUJWfp=w8GtGRnk^J>;duD5 z^~88MAN&nZT5Of~2pFC0`azV7hoTPN=d|qJuS_DpZfKNC)Qfg7>1% z5;P_`>U8$V?ORI8rg;1nEoBMQ9P4G2DP^S9J@rOoqrI^RJlGRIr zb_dlAfM-0U6nW8l-+LAFAtCR#Bo#9WjL_;3b{fk`BkMUHi8Tdkx+ zkAmG*bBe)}-gNSUOD9SkuMM`x5gwyt^=v(m7YOnJ6aVxQRAx|UThqtiqjA_Hz0qi% z-i-7Gft-jX-v#Lr3xBaGyHI4n7+x$_Ji0}Lu|grvA|2B~HUWbYRb_;We$6zncg9QV z0+al8J-i}y7SP9|>p(D?3EY%lN#J|M2GFzBV6}}O6s-&fI-e9Hq+?6gWhAHTH2+B? z36qrXP`Ga9Jc(>n#(s$GLxH00;DO4b$%Ni)m2G1lRZ^Ye?1Fp(CX+45MWB2a#1wB+ z@J)&ELRcvXFC+^ai?fa=gL zTQ+2%(aG*WO~?hqCo>ERn#W+0K{jm_n6oUT|^u!(Fg zh(;dT{;;gVs=5Q~X&N|6o|w>5rc$UaXhNibA|!*Nta1Fl+I+oL7)(-5mP~73M{IOV zl~XgTxv?%T)#V1lA|cYS`Ao^1@~#PWSCBx>`@0ZWz4^+U^7N3$ui;!v*ksH}ylcfq zrYn)yxd;0)1FRi;{vmIc++AzrkA_YyTf{vLoXaoXXvE^liR|SFLdtZJ*qaezHyv0O zyQBt=io`P(2HkX7>G?QS7*b&i83SqND8l|KIqbE%TTzzPaqP%h*zH3d)oQM7y*xEV zPh`t%@@A}-P7_M%@u69w9=|WM%{ zcnPGQVoYYDk*!w886`+;1wmqWmiy7Dp=ft5s!@-pqlHGP6%Hb?;q^i*3{V$NH_sO1 zAcN`&`?HV1C;n5D=M4&Tf-$+QX@7zdVHL!So-y4QMM6&IvNT2?-npduevuBOq9TuJ zbJC;8phD>ZTD->Gkr1u)7_p7vxdK(T!2%d3)VD&}CWlinR6%Au^Fqkjsfg8*S}uVQ z27%l#<=5cM5vUOC|0x*q8duhXUd?Up^h}vpIR)>Dz4oWo|w1zEjUQ)FN{FJ+=5eFiUdc1FXNT=_%pukntX(R}h}d ztMvs{Ttkd5Sl{q8HOvPDzc;3AB?DG;T#i=DmRA6tsknWo!S)Tn%q4uVzwgs!S-Iz$yie zQ6|4UmSn^zFUOu{Xp_Byqew95GEuROEEB_0VL#RC-WoDzpC7-ugPci_ZGrXuh*^S#7GtK_uBM4{GNr4k33+C-nJRJB_`#JwYa( zYbzG2S04oxeja^Ue`>SP2C8+7E?;ufM84QnF>4yFnXINDvtze#M(pHeRfV|q38)JJ zX)Pf{TT;9&s>cFt>o=??IdF5L#A5Ylza%FbE07O{1uS6XSSUO@`jKv|&NWb?A39ls zs8?9bG{@Zfmc2|Q*Ro17dbM13VTx@Y zhY>L0v!RWep)AdJk|!cIM&mxkZJA|c^P}5#7_-;hMvUxU)$Ox9Cw}A-e{LDHBdy4# ztDEL1CP;yJjgANN*H8UPO=h`?v1m8j;)7^JQS5f!1s4Z?OAi;&VO<=q&I}_XjEfl? z77LbZVSl5(Qg6W0x=f{E;bcs)2Rl4HU#t9iA1=um45lkb?bCz7bSGPn8Or&56rai! zRxEqL$z{S=wyjt=fs4k?K}B0rC0aUo1t3>9Y+=FfH0n#sOD(Xy({qR06XSyV$C3AT zt+}*>WT!B76^RLKrjd77ocPDb;ND@L{NvZ`LwQ^r`o|_F_wC(3K3Sa*=MRAdHd`Q4 zZ)|dW@|v;zlY93_6@l*EGd8wwe9yiKX|lRs|EZ4c9UmV%}1I5Q1=Gf2_yn(>4@d%H7)x5J>VGa+K<%Iri$#y!95vipLY7_6{ zJp`^e2r}bvD%~WQgTzr73d0oC|DoDZud__>2Pj%-&AS-t>OcfL5s{y@FsWD;ps|c` z*GK|K{GLvUS|DdMk&{ek@O38-RWQ7LtM2edFZSq#OENNvg7K4szKdS#j1sTTL37hh zyn2Sv3gUKRG~!l=eA$_{!`UQZl0g)h%mdRjjMIPiKo%5Ga%n{4z&mR|n6>p~Z%DBv zN;7K2NDVe!#EZZW@jEu#VaS$p$4X_fc)3y}V??9SKO5(fpHmDKN46412+m z3WI`(H7Cw(wpRkFFGu%W`Am@0D}Q!LUlN=X5p*D#=a*Mc)K}-GMOoHgunHQ`7n&-J zui>R2?${bHL9TMN@Qw<&2vd?h*3fF^Sc_J3j#SAlG5c`36@(ApGDZhX&n=)0XEobF zpySg1QAL&Qp)-YJ*t^zj&M7Y$P5G7+o_zVB6o48l1Rga*0>npZ2YQLLcV*heQ+T>r zyqdq;Q2}%iqzZlyc%D+w3R&kwj4AIf?XJq`+Nt(>eHPdCRl6SdB{A<>U8#&N!60mO zVQFI&MkjECUOyFqW;a@kbGuq|1R<`=uJ!stMXMjLuN|+9&YfDqE9|j%Tw{Zgt%qc*UBYl zS%d!iw4{B8!wt}9pycqse||ro_gAE^DE*yN`c02DcXsJlrGl`+ zrRRO#Xn!3^>Zi|tC+`2tH@>m#`~NWC@2|f9-^O;*{?`G29RByupXT%a`UqbrVzKOwS{q;*6PkH{y z_&gHCe*^sv@Ac6Co;-if%k7T8KEYSy zH66d-2VA~Cbo14$$m{3jX7rc7|HHT!KkxH``|AUK!r4ap{!b^*AAh}7^w&S;c=GYE ze*EvhPM+WUKD*m|4! zKVLa*&s9EZSHI5*?HGT_cPVZ8_a8XT=lt`@`w!Ud@b5GD{yhO=g-iJS)d}1;=dU~Y zd{V7)h|jGO3ypN`-6-(=6fS0*_6^S}IcvCH!}zSw4T+hd}KQS{IG>jQkgT&q$! zaIZc8(sRpq{Bs^Ezq!OcNUsmS)Smx?XBt>8x%1<(fcv#)HSOP%uQsSV5<`prd#D_D Sx#u7HoI!sq>2UJ1^8W!Z^CG(d literal 249600 zcmeFad3+Sb7B<{HnWQu6K*DNd9b}Q6u!!u0B{(2xWKl#ggd`9&gcuS)t|(pz5ZR)l zBDkQU21Nx$L}UqzOjOk1f~Y7_Q3p|pxW$dU&pB1yQ!|-?d++;xe|*0m12d;jJ*TQp zojP@D>CVg@$s>n3bX~Jv5!wKaICpE2k|cqo*CXVWrX^{;v|9MQRBNL}A=Qa@l0<{) zQHKC58ZG6hG|HDCiw&ktq?|=94T(~|aIans1Y%JwUhtGJk}lo!ftQ;1x)Hm=AwL)WxmNWpGDo$o))$2NjlQI zmn=7!CIX|EMT7HY$$Y_dsK};Slls!GCU~Z?my?S=)*`xEUnVq{aPI|fV zrtZ7qs&N{+rIgZSahhX+;H~lqt1oeqfBv5@U%S0@!gp7-&Utd-ii>W4Vq@|LBtv>r z9+IIKl_$I0<~!qxWY`}1-MDsZlt!;EcpuJuXGV{E`Y&p*CUyuXhWPjpiq{R1o);#) z8cKwc?;IxmiZJQB!j%6ebO}{HjgwI6F)&uB^xwjyKN61w-sUZ*%zk0Q^Ta+ zA4Z=?!_+%BOnYO)l%Er(d>XHAyn|nJ!^p1)Q*T-r`P;+j1G9y!cXk+i(lq4`RuX)> zF!Bw<=(z-XUJ|05=TXijh+b#=3NRTwz3zkk>u8O&q;kQ>%XBR@b=r)XIjOVq)AI6D zQ?=CLV@IWCWaec~n?5T)GjHsuA=xu?GRLM($<7p5Xk@}wWAZOgO--LWw`aVT-iMl&nFE6rq~{NZ zHIkEOk4+uZD|JkMx5TM4^X8=GWu#6=Z>QzYL@%XH6N>bjK66$ojGftIc+T{EsUSK4 z^$QzMNy|u0%g&ye4$aZ^X{l4-H92T+etK5OwvauiPS2T6ElHg=cW!EKX5OrsIceFj zPU`GL+ZaQHF`!eM$Xj5m*%*fVK z$K}kKj%JO{oK-Lbp_MxkV*_JhUZyr9bH&yj-Y`?=HeHH>J) zIix`#{bq#Gn^UKzP0!YH5qR^bYREe)KO?kK(t#|C8sJVu2Z{pwldIV=gaKm z9`;rD9+;jSSZzD;FA`TytgfT*X=u?%jnZ6rJG2<2n4C^%EK9{e-U%!c|42^9-q^|V zI;hUl4p2;lcwtR#ZAu-BdfBN)V8Z0qirfuc?hPEUizr)UN?SrlTCyo&Kl_K}KR{9W9 z2Cwl!>7}hjdUUy@f@l_B{;o(s_4b~KQjRL=FsS{iP|{o3shZ|f(%UKNl}dUCCA~^X z@1&&1OFe1X(?UtN)m2|S5^(s@+Nhj-7uB2OiM%Ym$9gbtaDwOmXI~8_T(qonMN+lf*X1}VG^xAeR zE~NcQ$2cWDT1k&r(&Lr%I!bzilCJKn+)8>qMZT?)PWyZ7m8hi4BPoV@Dd`O@VbCNc z{URmZqogM&=_yM3#Y*~kCB2c7K3Pd`tfXft>DE~r!MRF$Q$>ERlHN>7U!bHnSJIa% z>24*xSV>p+6Kj<8mWup(C0&L9MoW}*8A>>Pvyy(PQqFcIy{(d7s-(A9(#w=|+CyD< zU9i9f3tX_k1q)oTzy%9ju)qZiT(H3ZpDplnT(dtt3%`%{EQ|d31>CMKEX{XRmwOf- zh~Cf5s=jQ>^O|<1x^+58Tyu@&vj{nJ@{8)~>SE?;qk87#VVkE7>Y0;!ZJsu!XHIUh zdD@VkIr*5)(?;~n$-8ZyHlSxt-f8o+sXKG>7MrIH=b4jfHcuPPGbgXHdD>u}IXTGY zX~Tc!WLKM~jpmt?Eo`1Pm}gGbv3c59o;j)8d>r#XoweFa8%ea^=4k_o_S-yd9MOK8 zrwt?8Z}YTKMEh-?Hi&4y&C|vZ?YDW_5TgAyPa8qB-{xrpi1yn&ZT!%Fo2LyQ+Hdo; z(L?)fo;G-Bzs=Le4(+#j+R&Xj`O`mE``yfcVe@pbf%e-xZRpT`o2QK&+Hdo8(1P~c zJZkVG#dz5dV4*zblA;If#EQh<`GOe>jN0 zFNj|e#1{tf^Mm+;Abv&=pBcnY3gX8F@uPzHc;u{3l>aG{hvZut8Q>FB!8LOIj;F4I4uI`ivD|%;#m>7gGleH{00cEv*{Y4)m2>) z*L(rV?UxktceDIucM)lK)>BmJ+56)_&)%vCkABc|_-uZC6p$v#fs`Wb?iHcXhQd1HtTIB)N?~33=`MDgVhi0O?{J z@(mg{XzUozo!`@Gvu9y!D=p}{1i?7Nv&`9=PER~V$w#}EdR7#c9<8qS6nTCBib0~E zy~@Oi@;)S_d{6ih5^03!>MdN43^Z+c3pe13CID|?39gVISDSD}LDyTj8CMi8y@gwG zMS%{bQRd-A2L|n;i2{5scq;lN0=Z|!eZ-C|`etO&>5)ZWj4V3kDLPInu+U*o(VrxG zmPPHH?+RAPcztb9xu?}vc#7Vkaz>Kmiu<^ImLlBD=KvHHdQj;y z{`91m+r_cK4hSrR$VgkH=pfu?$#|;ByB#gle6|0g>?Fb1Y!y56C$NX90$VAsuY<6^ z)s8nsv#j2E6cc69QO~k*M>9Mf>T?g~=boBQT`yWomZMgcVun0*dCl}gDBzUgPq*rs zf_l_+tHREZ_n<};IflIOd9=rK=YbNO$lWk#;-E>B_FHa;HHiC6T%F`9e2l96EV=U2 z`4yifSK-35BBNF1r~O)4)aOFOu|RPH`+RS8fv>ut!p461Lt>LEJj;?Rrh4LXO5d<6 zIj?VHVG-opXX4@ub3dxCJ`*>wa4slHyuB2Ok#Ak6X;b6cmT?unOf(Fd7kXGUzHkAF z#L+PkY^bat`2T8`&!{9 zG=_ZNRsr{qy5BG?6!r~_*rK38cpv=a|D!>e!7dnP5SCL*imX9+tMFFK>qZDx$asB^ zA$SP4v{Hs}O3gv&rSuhrl~lMG{xa6ggC9?gJB<#jQ<%l55GpEMBTUK!-r0!;N>O1V z`TsHjA~jv4l9!*l2^BDm^lGG|Gx4rdScZbgNvL>qqvU0E%b2zLtb7Ai;`J>>*Y0+s z8rG9=Ulb$JWN zLOEp7PTt8GLxiidD6*(DjCoaT z2(X2$h`w+a>l3#!4{bp!pC2;8^s+~S^N`3La`$NWNE})QzrOXsnnXSJ7kRxL| zguI0l@yR~25}#zZcBtI5>^?$a)f9A+74P;@Z#mg&mMak~2VGywCRE7xsMN|<>Z^^= zO$w8_N~zpsOe_tLUZa?+E;L-oTA_DIIal1uOyMwAzvzh9ivJuFagW0Q6#NQt4`{CR zu6QihzzUc4`d$bOl8azvcH)59F>cXoFviI(`0!79R)Oo#8>jB@r(0UxjC$3{FkULq zA2q7!mY#isZyBA(2C);meJKrFD&}55+TFuEezG(j6MFmw0 z=l`u2^u2R_74>~VH^h{Fk5MU@uPOJ6$Pzn*DHiZ7!bvKo< zhh6<%^pk&XFZN%0isn~&mL*pyDVX??>O-mz%gHM4ghi$KwMBy0w}#A6%i>0!38<6H zD=Mf2Tsdh!pGMFkb_|viB}s>yq(aYvxJXT`WZ;E`6#xSATt>$&Zy4M-^p zERp_vD+@yq8GrbRGKxaBkSe4X7E@w5oZshEciSIChMmZube70D2RUU=^+Vyl2Z&!b zsp<`X3($ag%UC?xM7!-42IGr>`@13lU09kxCD7yL(6)-M%W#dJ3tQS&^xwJg^{~>p z@L%BS=fV%1r~K6z66ebAIS($&R~DD?h^om|Me~0VL9c!CFJudUWZHm!;>g6YNU$NX#b*bWSuy-PQ3(IQ%#;6MJ=1s1oka{Z8voN_*KbU+PJunUn zaI9)|jH%?)9!!*&MpnWe3oG?Sr3FVATsE%Cze11n&8ei$4clAMrvrP7yx#+L%Ah#B zcHDMVEgA*OCY7NYz+PWA^3uL$S@L!o<}?V7`@EF6aDJ&qn^)n-qp*C3?xh~R{8Z$2 z8sr$P6-dE*6iTGhcmQprXx7Xc1+tdGXrFZWE72B+D}yG|_W;!w#{b#&<7j}RA9%W6 zfv6AXP&-#0DGAtfoXdBjgK)A|FX}wnc~cE%&@wU`S~RM>hUt=N|5PqjIm8o?un-=a zf=#ez6zr!2v0+iLwObqk8Pzy|yuP1lViKFA&TNQ4i5K&SljhoFcPx-3NX6)Dk5 zd40l^cTcGDs(9=bK_PAw(NR#0TUHMR1-2$$^@B>P2QD4bDqjmFP`uZ7MGdQna)jr> zl&Fyn$hCfqoa$Iq;)7=y#|O{e3I~RXe~P066%inKM5^ZI(I^}y8!K>HZD5t3-y8Ni zPP*-(L>g_hmMR&}3r7sQ6{C)0lETnSF54}}qSv<-qNnQd80AsNW2H4#u8Tg+PqfPG zOOxp(hY7#GQUHDIsJ$3mu2LpolPP_`{cM&H)^Qu$`fYY|b7e`A42I2Nsmm)K@b`A=&H8 zL@tDJ*+-{7SHRs=F|#bKk+VkmWs*Z0LYD~nk>fve5;PpBN1$Jfr6=g7Q?LI^VfpWIv{2;=HJ;XxB zKY!$vQTJ```2DOBH2<8U5l@pxMa;E}Q!AF<>m^~bj$es=NIHl2`W=CL{ZZj{F!dx< zCtN0<-HqZQx`w5eQ#G_4Kkjo0!=ketEYI`0Pbf@T0C1dUZ)ndY(Fz)cV;~nuhxhva zV8yZCFB%*TuM6}QX}20PX_bG)6R_(20)?ro9m;RTch(PVyxOPdAJeeLisWy}v&O?e zFcQD@8;yey&(jthmQamR?R#R9n&q>-$Q-$>u}Us2lsopoPBk1N(C+l|Li-VPIQ zMm#L384pXW#%@LH5ffuL1fE<54p!WZmX=A!Dk5)U*6Uk`YmV9&*X3x4UCN&%gx!OZ zM6!I#iNYtQ4IDVW>$`+PIqtftf_W@R%R(#(SCHA+p*wNZA4j&5_j)3IoxZGTt1x?4 zc5|;UO%z^<3b{Wc1&^tcr$=k_M2N})wymXK1g-Akc`~M<49AE^4s}gIHg9W(&mtN& zqhO**7`E7N@p6ru^{q4u&nhqrmJY{#*Nf_57M@O^6|X2tkgV>vknZ(ehoyydr`^y{ zxQ-Qo#4RGBNf~;-RPA}X*D3bSrBo1|KU2@FNd8Egd?TwN*7LLJ8j}*EmY!Qkc}~Fz zq;PT6;`I%|>SB1&>u4sTM*;{}K)V#I(=C>EVk3)AVmpbuo0RKe(Q1^y0VWye57tT4 zkW>BqV-D(heM$aN9?9Mb<80 z8L#D03f5h{_vQCPu@z*Ym)Wz#oFMkmKIuo#5yF#o61K7_PQETmi9VHR<)y#k65|(n zyuPpLl!I0zG`(26{|#0t5ExCq!$He#^M7w8}OY_;f`Ry)CC#9kKsOsA{CR*Sbvfz@`?UHBSStGVK)^*8$&FTcSgMF)DcQV=G)`8B_$xvH>PV^suM-=Nqn+ce)2SVvyAdD`|s1#`nfl4+9&e< zg67*Ya*x%Dz%Jr!Bu)m<}qSR@$vo3+wRigqo~d z3i19%&R=NFO7xJu6)8v7arme+ZawmsP-}~UqY26Dk(vxBKAG=Yk)Z?Ti(;XMddHr} z^TPR68lShSLq!P|>Qbmfz~foBSdrcUQ{W!f;Ft`59LKPL(3S>Cghp=RpbrG6wcPKLr}3VS*I7ggsmeFZ3E_P zal%FoER||LK$clSiz-I_jZoxhx+k-+N{_q0RBo%e_>16ACrx;)P|552gdd-xILY`O%wnR79CaBF zy&SZS??*eJqcxIYW+6@wCy8YQ=Ux$5ST|<9ut)`B??^o5R`j`VH`@i-SBy`vig}XH zsd;12Rye%9;O~jJtklpUu!eG+%87ExjMs7uSBjP^{$W)7LZ2@8V3*_ZD1?g0mwFK8 zXdYnhblef9r+|V_Bg6TPiSiV`;lL8GyQR&O9bhb9X9w3v?JJSr4sxaH3Gjb(0@{oo zrwefc`p}V}H8Qyi8X9yWk4ZG}6#X5j6RNzCp~|bW)=|Fcy#B8-`i`J9|LCi^VnX{D zas$X2;3i&QKC>|PQBS*aepoTU^+Ohs6j(%8X8GuKb!p(pq25ut~O7(AXWHL$)ZfD!mc9u_yWQ{ng*#SOw9jHek+YKJ5> zkRYqq7eyOZv7ha4SE9}{x4OXrh7N38$k;Ti)=F^nLn1o6i@b-WpZ-+Z1{dcqPCMYb|Vk*;jokAODutlXmcl)M7Pp8Mo}`33HYc0rL((?ArG=n29}N6E|YJ? z0Y8$DBKJ{Ha#?q!jqDc1oX5(I)xL1jq zaZiLD7ke3Y=~7S8$CT<4%HW_jxx#5F-Y+m`W6nw52&HiHC33zij6izA2;=Y`9q;LY z33%_H4wxJjux7QzF%gNNS@BZ30*7nSxZdtrQD12iZOfp0N_;Uc0%n5i52G!n@c~p^aK{Il8`}pL?@(|Iw%8IU#_62#=3Ka7H z&_VM>adxcu4?VQ9qvE0SL_5#tp^Za(Xot`qdYwqF;h_-$9{PG{53LO0p<-1+OIP;L zNBPEhu!kln9!f65zFmb7ulRN*=M47H&xH{}d1!>uDhvi5@S>7lClqLoans_t| zomuT^L2Lei7^{fDb{G!0ZRvA*cC@JVo}2!Ae#e@!+;iCHnO;tJB1iy>26@v%smoe* z)!bpdi$$Y4j>4Q-vW8HyIonPyf1jcSXA#|T!A=DuUIx`#ku<(*3~>{;Dii|-s3ax} z^;XrLC_6x!!VYQ>>w|;I)j9{az*EUBftlo7A9Ruv&wUrLLggvqG4be=y;4Q)Fcy@z zPu`zYH<7C7>se!21S6>Lwi3s)}GS{caVG#BtukT&H zX3w%TxD83TRlJTG9pD^p+c|hdd3|fCg}sw2;vS&=A8pK2FC}Ni`uYv(HFDM(2fj`m1_N3FHAm`M3+#;&W&$PD(l4vZk8i+Bu{D-pvVebkV`qlLGt zlno;cZn|$)6!r2cS_>*MhwppUEKp<>SV~>$j79~CB)K4t?HJfZkN4r_m;+OE2TgDtA*sqc&W4y^iRh%_rAgA=R3Q0 z|5%}qBASdyzwi(a2=a8}HDF96sUbdiOo)4IaB&_JceCyAyv$5k)#o{k5e|Rnz)iak zj&|@(mfb9>F2mGc0d>4`asLsLF|67k7bG!wu=odDaARTt2tK>*G7yHP-}x@KdfBT7lu^_XC0BO6`EanROCc z9T?T({i86TdtM+D^OTGS1@Pd>f0paClLkI*^=W4H&wLzZC5yiwwI*7~g^IFBhU>`5 z5XB)p2ke8N;b$B}`deUgzoV5q^a${?L^bw?Spv=H8vKz;K09UWMPBFM{y|rEwdVT+ z`XSVL%uxyf-($_scTp*R?t#fP-&^nEPl*zWgZ7D3f(PoBq2f{)WV<>n#10>j*JnN3 zD<5aR2-oWzPNj6{>ES2A|OHhmAz~h&U%WU1E!-}W{)vT!vWi2|GoO% z{B#AL?t%Wizh~hWNEpk5yt-EQIWlE7{dok-WFmz_GL1{x7u%cFLHkGxI>WbmlA4=f z_YT<@%8sWPYgxava+8U9nxo6Cppw)?c8ll60WUjIFQ z&*Nuy`H>QKly7)nT*LE*(%BLw=s?eVm4pL4?=)@PkmC2e&yW(@^SrEu>NX)g@6F>> zbpq^#aq9KG#;o7-un|{_fad{|=b|C+KYfNB-G6xhsiwoyA0Mh-BWIKI`e#H~|9k`M zNA`sv|J=Ac(5FJIz^taq!9+hspz20B?5%FVm~z_|qUbKOWA>uXti&!uEJyIDGs0CP zyNrQ^&W`jA+=VAU-rOnGrm=@^S&PKL$tkFk8q>#7L|kR;TaDr63Z^dq2+qL0(g4B0 zl0zR7zY$zIWkMvwmYcUDNzqtZV5foaPoNzT-8|0k#t<6wDc!g$qCF_A!w)M|$o0zm z@|GT=36fIiAl(X^w&zKE);~#wczyrIgG7pyT#^gJv8H$hYw3hf6*E`FT^C z{dht-EsC+>6&^YS0dyBViprPEoLHCB@&)g`KC`IQe(H5^h0%J!wH+T;65?8G+QHNQ z1Yce2I#AI7CH>7@5#VwOSZXQR7N>NA$zvh z_a4L$^P?#z%?i8~c%U?R1XJT-f4Z;7julTNL?amV`tAwz`;bv1(H;ue_J&z{Wd)W~ zV@9hnoJ9t8ttN~s^;(1SXf#a5)TCI}KN>{ylzUIg!woe|7-l(<9IUjzf929uJ(YVP zSlS&B7Q@tWkaLA?=j~Xc`P)Zhv#n}vbROKt>-(0?K@&E65ye7r@`9BeoSq-z{E!lZ zC%6Bk?_zi&u;Y@naR{HGSWEpQ9(4m1kGgdgiPqnU(a7h+oUd3Rl1KEk9TLyCUBVgA ztnr5^=HZkMdAQ>_pAY#kApAC?r>d}D$I52`D9+BR?*J_WubrBYjN4H_89(xlK@Ax` zlPW`%2oVH2%Ug3ESD74&z>4WNVgy{joGZska#xDsRkVS}?%LRXd~@`Ja_aYVEf>X# zx{6})ZDz@3I-ZL!`x14=Ev9c!fKugOsY;<>XSqjFsyvKR)O=vYO*uS}&a6}=9dENz zmFHCo`ms{wq*QqhmQhkEHo=0q6eXo5)JjyLNvj|ygYPagm|C@kk_{*u-3TLKjqI*AGT0;htqWDLJb9rXa8fKgJh0L}VEvB@4PcNCTM<0j7bk_R|NL`U zU*z+9S50>m!J2;2j#q~Pry*%bRg6lmnT4(^f#0l$->j*5W>A8s0&c_2I{V&o6y51Q z|5E`^A7ru3K~Dv|B63sgD?$9+E^YCZNIr^Wn1@dd){wJ4LhCOK298s)uhT$hk@G$k zu$yjEVrjqO8cJ*xXH>X znt`T_ww?;WR&Nw4;5ntUc%Xz@ie|-g6>?3EYkDd`X%e*(8iaT%V8|BIo;HwyW6_=& zspP<;GD-}D;aBqdpk(h0&ps!ChVF@G@Z~Kpej~pJQ=q+V+lxI-ue*oSn*w6<0W4#escUa{^k2RYs8R!dEK& zaV_k$w2GD}{(f4(Y|ykcpO-NKM;dm|_r@M_&KJf3MU58(oX( zNQoQl;{3Gg6rFa{#+kni5b-S8M-zQKPj%D&zX8Tfb;<*Ae(TR2*jmF)@D!RK^rQPuXp_BHba9U@< zCjeUC%8bMduL~BqV1Wx3xL|<`7Wlug0R8@-`pU?hnpTia-;SVZ_?^hixqaNN@r|zd z8Q6kMafzSH%umZnCvIwtHYaoXw5}+?=%zQU0ot{C$c%`T1P?GrlQ8#{GvQMAcnd$i5 zSa)_>-n7g-cYan{j(bMh+|*h4A11$q>h^@8{v?pjZ^cV-)7PJ^N zA9Ne&YS30MR#$HY9SZsZXf#f%{s!#^+61SWqe1(D=7G`^ZmsY&go{A4LFq5~w}X~} zM!$^uK>L73;|a=tgLVYn3_23@1JG>Zx1nCpzd^Txj(i36f-VRBg>caNcog;^Xb;dc zpkqOY;@;|9(0QP1K%WBL4tfyuC}_f~&>M6VXcHXs>;UZt8iSqKM9@K?bo?_L^dZol zuT@tc0G+zCy7~mAgF5l(`eM*lpqoL5f*u6T0IddH1lj|K3mZUvpk<(cg8D$);s$bb z9Zeen+7@)!p6cop(D9(Tpo>9^LG$qN!dB2vKtBNe6Z99*1$aQB34WtuJv|@-x(_r9 z^aIePpiy|trUY~#Xc_2eP#@@@ps_fd?ubLmj-dTOM}iiBW`iyTT@IS~dUf??&{9s+Fz>Uan32Bl~1vq5KpE(bjTx(W0M=pj%O&m4UZ+8;DF zLDQ}V?FhOYbR_7o!)Q0?CeUKg&p|hXR)Us;c76}-2KBuUKfM@w;xE;DfaZdZ1uX{6 z2Ym^2HR#`wc6f+pZMM;ym6 zPC#3NP6QnfdK+ll&oE9v`+)8Q-2i$F^c~Q@L7kt&U-26yH-h#9y%%&MXesDzpud4W z1lsX9@`L7p9s`|(`%fBv%Va&M8}tZh5~vS!GU(_ps;d`(W`V8;eFU_WaL@|SkG{k> zZLVpJzCyo)UIRK5bSY>C=o!#OpphpqPC;9N9sunJdIIz@P^Vkd-UDp~`WNU>(8RBi zA9OY7QqUcsC7@q|mVw6NX>A|qNYLmOXg6qE(3PMb(Dk5Mp!Bs@OF@%COF(l#%Ro1Q z`ar({jlKkN$%p))Z9zSteL=H8b3vDaJ`P#}S_WDMdK%OR+WI8&x74&Tplw0#0`-8F zfM$XI4!Rt)BhCUgfervY1iBmad(gSx!|z+6e9(@d+d)Ty9s$h;HGV*T&}%_AgJyx2 zgO-E-0_p>;-x_h^NBAx1R?zXF2SMk8_Bf4x2c+PHGhTOKwE%jfsO`U3Yr000{R~4AyDUUup8)Qpt0>R z--C7peHC;h=y#ympq+k)-9U>$H-YX2Jp@WGgh_ts^G0j>+<3iltPx$Ti*yVnEpc6S zHJXS)Y+xpV&*I$!?}Ym?796;!9Y3sg!iYF?PV@q8V52_mySIWTi2M^lbJrjSQ-XX^ zeffB2A)WrV$9hp+%klpE$?9rM@i1!b_{EMPwW0b*e^mtPT#FQ|E!X<%nhP6eKn7vMkB{@?Yk*Gy-bKZy`tj|+^JE>t<-;Yk za=a(4t*)K}8#^1j{dHulh*<7i7#T6b!G)1soscPcsJc26*LGQsi8kH}c$+YFQU0Ol z!86W-FFFst;XL?(^WZ0dw}$?G)%N8HTavB*hAnHM{m}+&Q4hUl^_OLv4D&joJzhFy>J3-Yg}(3SB0xOVP^cUZcRkG(8(CYx_Z zInJl6tJ|yfr1|lqz-t31AGFI*{IBX9IO##(eoy&d#I^IvAU!sSdfdQzL2eD?JS3N> z$lc-Bg>IAXgba-fTNlR=7NE8)0`3Ez5`bS};~Rh{lvG!DQ}OA39d<&8_P|+(&6vn7 zn<+ZblP6a}rjuHR=oap`=t#^1z+0*K4WbT8b0hy`;Ky+7Oi}8%VtK?ur{fSwQd?3` zPW_GH+nNhJ33#}+76Z=(K2X&IeSZropz=2ZF9se;Pr}QAuLh1~tlthJMLP(u1b!Fr z4k|uH;BKUm9qtEy4X&NDk;Ag3!^1*UMvo}0T_JNBu5CQqU&mPBpMu?l!JK*8QVHNP%z{B-J0%E~az%PeBcKtd2HueI( zD@^^=Hz_FpJ>bcREzZl8HlQyfF4t{aE&yuJZ=4Dils8JYh42W0*hDn4G|)ECEKgGR{z7p|S}V}oP)6UEdY{N=>D zH0{T8=+O~)MHoHYD0`&Le+t(Db$sTpgU(O3J&$#rD&t6H0kUT?@Uy@}jSXr`3EE2d zVq7~L2eoCcsHZJ3I>(v#0?Hx(i%{f-%lW^S-v^yIi%G%ROep)2POX5C1|DwRH5B+z z;GyC(<;QuTb}jG#AIkOHWD)S0Vaj(S{|4YwfS2Gpz^-fkWzf0OH|NlS&YP-$<2c1% zhBA)m9LfhgoQ`xprEdvs12>BF0RQDYI%Y#=F3Ol* zjv{;$@QYpwzkWRgycTdAHTm-=`^*0x_+KwpS7VFr$FK3@v9X%=EATcdKFN=F1Wx(G z;Uj@NP=8M~{|tZrY~Ts!(0@7b+UL-J6Y#%Lf2cLH8+9H6{wMGyYW+0EZ}sa?37H#F zN4U67-yT>1JXAcRK1c+97x4CK9dg}8_G* zQ~R3N5)o6V!>O)^Aam`@q3a@iC-BL@L)nAyW590&-T~LP9&)ZH{BPhl0UxR2%DSux z9O-`G;pWJGzz+fs*WVL?9|Jx_Eg$_sTQaKuHsIC3!>x550^V#}=rQX?{++;U0T0*T z)E`ID#$3o`;@a69yHB-0uJijvGy=o(kQ)v;TgH*Z0;FqO;75U9s^T~L^Lv0F2OiE= zS-|682^~ME{H4Ghz{B}n3Gj=6hl{agz}uapd>`<}!27HE=L`MaNQ;igS|0eTsz0Ky zBA)fn6CEM*4$icvs%1DtfS@*v1YRF!+u?M~2HpmExOrqba5^gwr{gBzJ%OJ~$8yLV z+7VvIO5k;Iz8-F_i^q9)ec)sh+Yb~!NtAd?6`$bugB0KwA%8eO$_1VTJXHK38x{i} z0erezzGJfOhns=l3%s+6D{G;0;Ew?h=SP*mw*klTy1#uR{QAeEbDjYnPQOIpTY+Qf z`SUAtObYPF!_@CamR#W5fuCzVxEeB^oz>Ot)H;L-c%Iw}{2JgzD(+Zd+vo$}JAgM+ zeL13mJ&*oEI_wG`_v*tqCxFwvHQNUqXYKNP06(-l{2pv9@N(cF{``uK^8xG!-bKZg zvz^tz-vf>z>(8&ORki}(8z#RSSv~+x_19JPr?KqxkL4=J?8becaN{5Wp>hxKaDLPa z_y@qtRUI8(+eYJoFDeZ`*5?AB4LqEmuK`{PJe(hH2mU7TaC6U5;1$3p1n4IgJ2cL! zfH&G3zI_Rpy1M}Hq~=%73wi^Oh`fkzf8rIbAsD|9|1l>#T|pVfo`Nd1YFyHZX3{jx3?e@&IWWp?nmI^)_ZiHF7iNl z8@Yiu0Upic=YJVTE2c80))-V28>}3)cg*ynCJEbe;RnWIWYtHeZa%@!6M*~03V>1uiUrT0DLF#-YTx_pAP^(0-V;n zcKhVnCFyqp_$R=_`JfXU!lS^$`EV=XZvhYGBiw%A6~M#!UgCXsgQQ~De@I$~u#Y;D`R06N_#<}aLkK_HZkO`+}58%Uq=cqaeJ$Xk+dX9%o zF=Rs7i}1O?9|PWBEkoIltpUCp___8v^z6b|Jd@HzEkjvH(lZU|z&$Fi+!Og5_%h(( z+SvroFdz82+L;6yZ3 z1wI>iz&dlDe+}UQ{@^+4&jNnz9OW+s{sZvw0s4!;#_b1w%cAP)YXflMsDzgRe;PQZ zdVl*;Mlla4(3})=b`<>d4dgNab+BQezvrg?@$JBeB z+Ht24?0Hn&L>dQxPDHebj@_lX>&O%T_j@C%<8EO5aB7c6kW0v9ZB!2%a7aKQo> zEO5aB7c6kW0v9ZB!2W^U$PA`i;6~zA<#79I4c|3k4 zUT#6~_z%A}+$t!akKodCNbooo=NBFe;TMh!_%&YQbhbh-dPa|4zn-n0Npy1red6As zAR7JsExn`~T7|@M$BbY1NC1!E@r%!|amDBHGL4ALrY(3!B;wBj_*EhSoWk(SkQBG) z_(ji+(925Cl?}4=c1uILgc#lS;};#j(#w+jt6H=V;+%9=^0{$Bu3GX=!D^L~kCFHv zLAVtAe?}(DehDrx(JfMvBu$ZYvZT3^E|9cX()E&Vmb6sTa!D&Bt&~)2q46tTQn#du zk|s%-BI#sFb0u9MX|bg1CEYA(siftSR!CYYsdkC1UsAWEiIOHsnj-0BNpmG#AZf9r zqO|}1GrBx5&lN+4^l`TxH>DsazrfwKYv&%F6FYS+V7BY+-MV#7?9ompYq4-m2j><} z=aQjdj2tTy6GhS1P?;uqK3)cNtKzNA-cL9_vqpCS28lDG6Z zB>DXkFYX~O_;xxjcSzon|0Ib2Q}QobY^0JwlqmKYA`OcEJ?01#qt^DgHZ{`0`@>YKhmK|&9e~;v4v$Z!QZ{AGwzFcYOx|095 z+1{9i%*CBp?Ehp9GR@>cmd zlDEpgP4dlTd21!VMDmx65Eqs|UoUyfpH@oV^2hCxe@NyZd!@MGN8xdKP!4=czEbj5 z{k2C4d24+3k-QZz7E9h5Z$~6=wKw)EkzcxvcD3ZC+iEK%Z}sQHlDFF1>S~ccQxNSg z$xE|nA4vXEiT@>eOP`VQ!t#e3C2!g5Uddbj^?H!}N0OJrUaKzy5kD$`I^P*BDxNCq z?=ePPSmjNXyjA~P$y?=Zle|@4?zq76j!51bUsaNK%lZfh%j zKV8aSbe*{9Ecs-~TlSeJ`FavxDS4~B?UJu8@qr7ukmCd*h$KJ zByZuj2k~1aKS;{|Ci&Bn|2j=vSmU$p6v12i+$edgJ-L#%+VhFz8_4o1C2#4|CS3p{ zB%UjItNzps0a*1vF8Rx){Kt~F^of^&z^Z?qBzdd9S4)1Nl>b2TmVLjGe4@k~W{C?6 zZ!7r+B)&)T*7$o{@|OO;Nq&Ho?;#Cm&6hcnZzb`2ByZVov*a!N?w7n}k1EMq_G^EW zD9Ex$isUbq< zN#2srle`rlUzWU;KjBu9-;y6L`SG&;U@{ATqa3N}(UiVQU;8T_swVxGZg@6+guCRaAuhb|x#g=p*X7O0UrHdmuU2BfCW<_kQ|ekI^0`)?7o zU7`oomb{s3>jDZM+3qvo>9ec@>#mzx|9tuXRz)P2)^_ zB(20m8C zA$3;Ob@*$|ZvF1Y>cBBa@9e-?=u236J8sh*Pjti=bnL+cd`L7>hY#0=AE1k?hjXe< zocJIie0?DthU~4ijYLMi;>t-^Eu#4y=3#VoMDqovb0g8k=5;V@MDrrEfa!9xnCS}h zDW)sUolIAm?=ijG{DObL{9g^@nE$)s2%_#J^B<-w%ympxna{mI>BZ&&rgxhaOz$yuxM76*Ub89F z)n;#|_nG6E-f!kHeZahz=^FDHrVpC0FkNeY#&n$-v4zTc$ZXE^VRHo2N6e{A*PHX1 zK5jnB^a-<+=?3!{)2B?wie}Ksiec0zGr4iS_In8ZR!o5@5m~y?{x>m9Kc);MD>C%K z_rgYG>&DgB3Aic{j?$_7@^#~<&+r{~Posh;+wa9Na zX;B>zcOvf9jSNI{$}!1;bP^OgM7?($`5)7bODE$G{vh;k5~2&Wk{jDY=sDdeM~#F% z9ZHBz^Qvy>{|KQ&wh&iG2GOFb$VRX0#tRj~e&3Q%a}=pH-I4|92E7F}HHOloo~M+z zbmK9^XG*A#9*}BxMaYkMS2s3d2vG#=K@gQA3cE+ooHO#7I(GVN;?GVN#H&2)g7Oq#bCXm(;c$n4MQgU#VghnVA-4mH!54m1B@ zdWGp?d5_tE>2R|J(<{w~86RnGWID=xndw#LUZyGLH7s|H*&Fm;{gsO`vqaOh=)Asm z({b;@?icG#E`Ay&pAd~nbnre*Yh$P`t^2fTFlWqdCjDCPsPT7$X&KWTf)5$7?`Ybi z5PuSH$G=EeAdebPC*bcHkV@YBY}Rl_uD{`O#K&4n^q5B z6Jn)1$PuM^h#GS2z_^9(B4a$pTNHe=A>LfHPOyF#q=iLWZZeif>RKI?*%>muZ8@%`S+|E!)h)Fe z0@j<+YOiH>E%I|cW*8(J-Sjn5wivT-7CH4>kT{2mXiPe$WaeaOEnkiqCD4@sR@-2s zB^b>uUp0;t%Dm43ddUy}vlH+xW6EO^J_P7J8*WzK6!5HC^kukuqm792E%zEDy+TB< zg4|hKw$Tk(s58;-us-6#Mo*$;*+VUe~8ionO_X2v*508N-wfxk$yN)j47XfYe!%r>& z{H3vLod{9-VL%_*aI>G50?w`Frrv3^>IpDDcFw6lip!B?|e&Sdk+^LRyo35oHxQx zS{k}>OOcS#S3&STTR3(H)(9H|}{KN%Yk-9|Z~Y zp`N=~H~u^Vfgb=?*#hLynv-UomaTMyHgIhIy0tXzQoOl6`V{hHPNxridr51EC+fzb z#`v==>dZk9y~Y+-Bxz!8*-JORxJ68?`puAYM04+s*ow7w$(}w2tt`_bYp%8Dby4K-E1MhGK%;( z-SFWzby%5^5SIT{_ti1s8#daRHs4z53-lH2cR!YfdAhpAm#A#YRyhVrG;+nHPDf^Ia)b&cqPLS$vODf8; zV8|&u3ak2;!o+u=ZmEHW{8&76xW=!;^A)3 z=*HkXrQ|1&`p%YAlx4~1b>joLGWV$yS?l9144^2>k}vAUam%uuAvMI73|5xKx1n>B zWxPmwxpsgOYXr^ZnBiz0;#>Wq@pZK?$?crf0vS< zLW;g=Ca7PfWm(*-8?_fp@t8W8t?&*K*PJiYK*j>`2Pg3(kOOeob*L z>g9ITUP?F*6Y$zNE=vq1vt&ofa;63m(y4MfzY`i5&|*Q zxM5fHL11e&#eD1qqUq){i1HDwGR;z^Q_c67PBVQ>v&?Fy)6IrhOhmN0$?VAVW^)MB zY%_!D46~5wE#_lP^Gq+(eACCYz;x}R{IkvWOy`<|nBHoRXL`Gt$#kJPhv_171=B*a zgy|A<2h*kIVW!K>-{JS2hb{FmC*ZALhAes|uC%5zPXd2LuSKie7y_HpDzolOIxjOt_Rn-<+7^-h5>(*N zt`n;@rI=RtIlWfIGnf?~d>G7W-5B^K7IC&TRV`|aqGe0nmJZ_}f+*>5GYR#9Mq1P? z+@!19&0#G4Kq$J{hMLm)vF>9!FCd%JQlakCdM)bkrcn<7*{4VIGk*ESpCYNVJ}4p) ztLJ8aX`0(L&itnfZ7asWJ6w;{_B7D6K_uLUQd}Dx_vhnFNKn&RydA^IG$bN+4npQ> zN25Pb2~sb?Tag(YQ5r5zBWA5zfiLc5_)BOnhNAAW(o z4-%XW(ZVdU0$m9!H2L8hY(rejYY#xu4aB%snlo$ZT5Ir$lwmDp;PPtgQvt7vWk#$0 z{VH(J*Dr%@wc1_CP%qRawWDWK!{giB04H_rFgC~NS{@3TPla*qY|S?Fmjm8y(BFpM z4T!#TM!;;1-kf`%(dT)rG*R4Ez&l7J59(;W7k`J$2aR`c5a@eAj#>q1yxw$WUiK1M zQizrt1MU+d|3EAPdqz=E8`oPX=o90;t@!pZq+UV@E6G~48Fn$?&y6px*0i301_i>s zOR=zYeQn$}SS-Y^2b@YGLP-aF)b*V)CtD~v2gnk;fZNEdq7oMdm+J>(K337|fInu* zXl?d32J(w>13dm^q|$fJDB87X^)cWW-T3xaP5Tho*8#Xra}WMDo3v<&(~}~6Nh1Ve zu#xr`B7~YztZ=2aYywP=Aqm&QAMi0gp%OOi;Cv9*ZFFNU=9D|3_aF#dVHG3c_PP;; zV7(adWI$61W;1kn8qwJ`KsVOU$G0A#EAIfb%7WPhy!+HzeAgF(9^L5H0$)7}fmZ{C zD6f$0a0&}}7gnt=9uh^q2gxsMN^2bk-vziW z16{imm{|W)022Mv?Om)IT{r8-y*HvGLkV0%CEz@*>7)29CR>2@w>N6xSb0x^U+AAf|+65M5VOT#Mz<^@?sJ zjDap&An}SNrS)K}R5$j)9SRT-+Y-{* zb%f9shhbhPg&u;y)3y-%rx4odFgjtS!X@p6z#&_RhnNt0+hH_8++v|`An=nd#AXsg zbs~(rF<@E9#JFpSw=e>k3bW*|P`piqvF05yq3Vec=t)8x&zy9+n7)<% zTEc1K&;;Hq!uZz-Iec@0%_f}lUq;7YuB3=2M@06OKvvti1?q`7k}fiD0`j7rx7iU~ zx^7CWqCR!f`IhUN2xAzgG?LLj#>a6IW<~fg%r*V8fBeD|B8=h#LPn2j2EV~uwu(-} zTicA2ZGd$oT(pYu>M%DzI!nP6v0c`4Pq& zn{=YZxVA(X-d$+>V5E;G z%w8&pc~nU4jxcl+H-57qF)Khyi;a5<)f|j4Uct?0y$IkcOF(nR(pscE!nmSPs<08* z3xu=d#JXuR^Fp{Je310$u-#}GJS3yEk(4+*<=IgL%9OQEw6a9v^< zUxZ;6ddF$>#SG5XwS+*g03k6c@=WJs@lTw_LxvO|4bdsKxIKGmLh@UuQTlHwc^jmb z1V~DuDyQ-1H&W;^2yC&1co895%oRH#jVGd{TX+-%M?cEGVhHt8Vr(>&qC_;nv$wfInOgu##R54d5%M#ewEB0 zU6j?Qlf`#M8Mk3R;V!G)8Y^nNgTyr<`C*hX1e-sW>;|dKp&cr>}eRC@?-^Nkb2*iqza_a zaKm`=v=sUQ$^Qfh=`0z$;VV=;(J=D&K(Tu8vy1U&BWTXy1ArAksUoRVcVHe1_gi0v zG!|cG7%qntp90Z4!-)HH%X&5#Mh+%*Ht{-SdO1W!WoU3^yA0zCY~?u5yO5_}gHt+? zttKKVi+^Ys6HiI;vk*o^pmU$*aeqM+?{{60~XF;?v=5Lv2HRPWU zk;lL56?q)DcAm4Lz{T*$17s|!mVo0qcNnYY` zA8_Z<2R3xH9FB4st;#Suw?J&CT_{zfId@`>6V&nnah}Rx0HJr%B0}PPqSvcMUgS$qg}vZjII+kQ#1F1}n?r zFUA;qb7aBk5S>+1T-;c69f&b{;L#4Y!U{+|Y)dN2(k(UD`!PoJB3b4ukn-A+ie*{y zw;1F1`m)R~AoZIq8LTXeJ58hOC$ix9&bXI?cMUgS$%dveW1y7m1E~?Vq@pZ6BH?Od z8j}!UUaOCBmjS7KTasH!AL8i;S8vledljPG(=5mL=t&3HX4ClK3Mu|2MD;FKivq>jzoe6K#(k#os!wKYj7)9pjAS{f%qOPNtXc{s zL13IMmdTTw%no!n1Xhxdb226TE?(f}bj@ zbEUBiuEu410ljU*{8U+;tLw(=jGh4SoedhP$>KT87+M<)JN`R9Zm5SjAqmrV>#JLk zEn*y9F#$gM3o5=SEB0+L_1fbv|1QdQy&nyQ5Mr-IT4eWqI5B@heFTs=oj*uOt5<-T z6S)rGCvq*fa((r%nu|D{KSZuJ*pE;y+sc4zcvx~ zHFT|sCxtZsBeqpH=+M%M(*AK>H$mudG1Ba379+Qg)--xhlmFtOJB>k7L8l~r6g8pk zu6b6mbH4fvLq5tis|QA@zO-KC!l=k4C~d8t5Lp;yng!1q2S%~G=u64tOs$);B02_ z>QJyR@;4f>Q(Z)TOZM5^5}y%@^!^w}PXoF=KU_A3sV+D>6zPh!-$r2DJzR=ccEFFo z=Y%59UVs@auoDIFn->GWHWVp_#6Ac1rHdQY*SrsCZm4j7M6u)+nllN1o$u;vSaH{f z3g3>QN4OlIDn7iB)iN&>8}_BHmNtMo5SCie`Cbr;+_n}~is*?hr(Ok$CCAJ<5Q{;^ z-Z|&7-T2mat6=h;Mi_C=j6^>PZj4uLh(5QMz5Ow>AL{;LNO_Wy?mmKsSdWWwE!%I~ zz=Y1lD*%s^V3WqsmOC0NB@K55@fSQyUNZ{rHCKJ_G%J#_@fXp?{c13Je(=Spq+tce zJcS)<{3?MzIIF!Z=8#YOX z8QxwRAsz+aDDfFpe!;^p*=ntF+nerK%UBW9De&MAH-#%6(<$t}G=&~+3RBJh=QL8U z+Xi!lUiJ#?maM%Gn|v%Nbs7V~zffX&e9gd+@-LzuQk%a9+LiXdSL&=?3mL+}V&}b61@mH0z;DQ$qf=U# zcK>CXL#+eBCYQ)4+Yk%6;9@iO0w$wp5&eP(WgUZn;1aX&aTW!ph!_XxlZ83p7NiD; zj?#6DzA;OBT_)OQviPQ&UNhasUO8Q2%k*>`?2{+L_aOQjiH;)rO7YS51kqPZz(({) z@h#|E<9*XZHxcZkuE7)o=+wnI7EsI&z<~VtNV2 zB6mSpED0Sac-pr6!CYPq1n+S2+nh!l2zJ4?8z=A>0MUzGNYN)3XZG7`r!$cV<2BoN zw!LN(o`4}@x5rkPVq=f?N0PtUcAudTavb1WE`bq{0{>&%j~&t_Qr`gkiFh&c2BgHn zu>BC~U+O8j8FUT)4nC^|WXHmGv@CAVSy?rK@fAmn#{^G=?PQEP)d}&viLtm!GS`qQ zI#@D%eQ{mfiGZhj>p1u5U)AG~vb*4{c#ROvcn!V;_&Hp?AwSW?j2O5%SR z79*H)ovt4vvJ{!Ae@92i!5b?(K;LE28U)-oR^IpnIuEh^@Hcz1j@>s_Hk`zU2x4ct zh#E}TePiYPdxkLr5z7JJlb=N1SlNIiA9my2H&&`4qQ&C&*vGq1mBJ#$vk2r0&a(*I zIR~Hb0_FGkt1&>7iJJ8-0x2az@bVUc*Q9Iq24M2p6@&j_5!k;XHjzAPCaqKSECQdM zirN7I9~P*qSPh;3!dPacEbiFN0Q1pM5`Q9hcZD6p6^_eRDxJEB1 zl8+EmQ>G}LZCTbzcy1|7-gk5=$Phyn)|Anmhau%0vS(!6i+Q=Y-8=SKYXsha^y2oQ z`0HSZUyY@@JtXoD{6@UWT@X4{0^#`7+Dt(LDV4}$k1+qJfe`@G+4!5+vgjHaV{XG* z=vKt8b`iBm;J4a=agtf`f?;d{^t1=xO!)eXS3sL=#S-%+4_HpXh*U#F5{(h<0ZE@BxuZ1RO$Ic@gCFtX)nDGSg4@z)H!K7#VMGnKt@G-?si9SBKMWd*9J>}>-v|08;= z3#miq^dO8@kk%^u>mlLdaNu!jEfO}PK z_WlTIwSZS)$2M0B_%1)Mh!O#klhCL~k=`519tQ2@;h)g2%a1mis- zN)aO6begh@X=g*;JW#E?45hS@PI;JV7sa-k+6=O1E+uvHHw{!DA)OPT_{5{SfL^Zi z7b~?L`Fq&3KRJo0UqE5Bb&9D+Y6_etKGvE-l z0zoH_Na{-yeQ4TCpgTpszncD&B?D3YNVV?bns`GJIBt*kJ zyPIX_ysc@}bP&$=M3v!Ns`kUG;Tey(zh&=8)ii1y2se3>12nv|M_6{xR~=#dfgSRM zX?%iZe~V2orlCH;`vCJlV#gBk zGgyYkaQ1_$UO)C&n$Ov(0ej^;nounV^*seR_y(`NK{X!baa0W0+34dWR4?Fij2z6J zQwe*X2S=@deFt3gGk{;`C!qD5-8S&;8#-01BNQM0d9o=KeFI-(c3~fDumKb3xGE6{GFz?1=&U=xisa6M#*1g&6XlusthaKVQ`0Uj~e~R!%$6zRq44 zu=n?J_#XrIgwM}chwVE8_PVe1wzfJ7>~-QYMCF;cy((ajD}rgCb@L^#?}j0;2>i zixLZiC0019Xe^*vF04f1NGf7jWG4sh6Xa45e3)t~t(eJv}tME2c5du(%uJdumZ8-HCJ%&eh_o($S&ZHK5S2s-5> zl45CV1^aN&ZVGW~7$_!qRGbd9^{M?~(0;W#2o?am$t5sity`l`n}+O7Taf%(#6Rw0 z(zl)Q`z6$mofEPTV@+Zn1jX@uR7Pz5aa6xjL4L{AJOl72kASNRN6c?*q>Cyz`*Be5 zNT<^H>q1Kf`*jq%2ha2qqs(9rC@!-B$g(_AQ9OYdR7zsI8JrBw%tfC$00hHaA|vqp zufTh&;BR|%{h4!s-R$DJN9cBbtr80NZpi)=I*{2gxjnP3BJCO*b=O~+sSHI-~&7w=H8*%6MSxgLo*%t!hAGJ2+OXjfz;A$ z`{P$|8w`R+JR(^_$--9?m9y=0SQ0!3f>-ks>4j4W&7OEn+4XNnc7FhcLP2C#fC0TL zkf)uyNVlvIK=M^XW^254Xl8<;A^!59jL-8lx&L@iKY4vCrV|>tdl-wKR*2||zZrc2 zWuZ@z#(T;ua^0uA&wh?=0HD{n4Bk`T-|J#mkIc()Sw%Pn^1P?KoBq|QsI7o@da(19 zw=;SIQ$C9S>mJCbyt0`Sp-ybilY83VJq6n!e^)>{#omn7>xTW2!AJ4R$J^DGKqtsS zb;aJPPNt;M-4Xw8bvdktw`s-RtIqwSB+lN&-ml(@9j4C@&08iLo%)->dZ2s+GMx+%g#j4ahB^`|jPumiV z7+VoKu2T1Kr51)!8-QY@(f)l*C=rG?s$qTW88y2n<~Mx|+7~gKRJmiIt32I|s`n6H zAmN#226msOAbbt}=9A3s0#z22v&`#;VlF`JDi_g(?M*qAuQdllVLS?GrwgmS^@(KmowReD7aiQ8KrTUTXp^t6OWM=y#yE?WE` z>BdKE!JR+o1MKDY#CYzH$-HWZ+C|}4B}!a}z)Ac1E3vXdnN(ZEcEjK7$dHV>ORY_e zq&`rR)ov?G8IP!U9>#`y%ObDCVFHh;2M-}4H=X&ls<(*t+f27*bdi#>>PrQ|A(2ViO?4HI6^gUj3tb#58|0cjYb)@Qc)ey zC1U_zPG``T($yK$Fwl*R1B=LUDz=dvqJ2Km+DA0bXL&Tv>FPAS(cEXM&m?#A5hJfQ zYK^rHK!weR=zS2P=y8xfR;7xlM0CUViO}O9-K?v@QyHr5Mjp?Ne}uwyGKG3 zy>&eh^8D)a7#)z#D(lbMI-R0eb4lKu3<`XQwZ5)StN~$4aO!E)l&g*Kb5@y|n!BsZ zZ8R5Tk5v^2>BqT@MzgE&Of0-rS-V$hrW-vb4Q*D|0YKz>z~`DV0$gX6Rq}}DddBAx z=(Msb0wUMj9#`r@jK}Z^D>gwhed{r4IaA%LtR!Qv}z?%8n3Je z&uOkX9+!qjD{Ctta;@^Yws2K3S6NjTXs)MRF17L{=2h_7%BuF3W_{abRqKg2n>uBd z5nigSTRUj}pFMu&+`$(q>p9c~lTP$^%gT@u`l~u}{g$$hqT`UGHgRFq&X}v@2RiBt>;m-`?t^UHr3HTB3lylkY2AmX<6IsYcuM8uP@s;c^@IbJ zB*bzXp^G~qaH?tDiVY8PH6ovtEmHR@C6Dq&$Q5qh3k1=V1>>Qc)w}gwpT;%`vL{J$F$}<&`-WVf$l(!?A2F>LGc~@gfPBFZp$0KUGyT^J$o~);A$-oX_U3B*+XC_hKVw=8q2+pYDK>l)UkcS&uR>@m6e;iA@ zy!jWru4OI1MdP)I=V@QTYg*O;hrcWFJoR$}2lc^#^=MVCWyZVmjgUb50@hQ2$g#*} zHA0QkQLAqUthO=Dwa(`f==Ffr9T2&m^|?l47=_OUtObsie#hq$=ybrk)zQ-5`&@&M zfa~{wwPLYOD~fv%r*jMRbHG{)h-p_TnjmdvxC;$Uo_V@K9@kPg4Pm1%lc9XcaxCxrVx24y)iJgVrdRbdze|Q7x`bo`S zg?OHkE%*aLYs3zniH-&M54U0c+1BbMntxJ0ey2KwsJm^oYozZm?j(^nyc``WL|53> zM2vA3cXz&&oa_qG(?P2*1~hZ|UcTgvkl;Il)?wfj@>@P3=vtGI-J?P4;lp}5FEYYw zZh>A7T00!5CLzi&LQ`?~7(NxWKC*SH9epl=J_uUp0g-r=&oyijxV}Txk2U1(X`as| z&{sjLqXXUJbFCZ)E)}w#y+w09<#P#i5ruQ06F!%57r0VG)(1s(GkocD2~;R#eF2C$ z436~5wGoXTt`xHF&Cy($gmmW@s9ea}1c+SCeXbs?!zLjsc%A0z>vIXzAY?swP;*W5 zxrVbgazj?38v2g$R-a3t_95#Sv?%W(AMv?Xu{H*WtXkN&A#~8^5~zR3YVJU%e6I2r z!8JK#RVt=)_`A;~(1eiH2oTGaI?Ah!^HagK0GY>R#7d}7D9=z3d~V2k57{JZFPGKn zB~LsJ{#7AMJ*rc^x&Xi6cZ95)HtVEUdi=V|C$okg4q02vX#SlA_yyk(vKExp{BL>u z%#9K1%BAkJA?tUiU4GBU@7xaw(bFO82d6iby3#4X6v81I!JNDnvI0?^lO`n6nH1<~ z$m;Ga(0jT3M(8fK)u$nA3nl{+Yqv8`-0X8b_7Avz3|XmI!jNmT%cZvy zLV|xAvTg*pJp!&NX&h>NEn+v|Z{Bzq&FPwwF2zjuG-409h`NoiYf3t?reWNPhz|gNo}WZa zNx!OV7(cl2dY{pVFiS1Uzb>Yvwa3CFj+@>*T#|1Vd8VZGHe#VT216fzwHj%tF7WxL zq?8gNczILOgYRng`T5utga2VldJe0MtsXU#)+u_Xq~q>Ky&?KAp|z|A&y=(zs)>0y z<3XM&DcjjIC1s}PuI!07Q7}5hgp{y6S1FB}s41O7msZ}o8i9tP5h$ve7NI{)V4#t< z2t5r3*CO;B{GLT91D-`F1D-|b_q(tHM8q=u%`Gf}YY{pc{qq6DZgvs1OJK($bZ1|~ zcplJU4}O-gwg~#$hK<{x^EoJ7+DW(Na9+AUYUb^Umz9m zH(#O%jVv|mG{L(fh|O^k^_magZXT-u3ur(iJ@_pjUTJ=q2{ULwH+b;-KD^poi;AUo z*pv@eB0?-eW81I`;DSyEb}d5BqF50Y$Fm6SjcPh|7&`!n{FYp&5%4WSm(In#6JqS~ zhLMcF`88qBB2;=b<2{Sej!BxZ2_jp044y@3X^fX%h#o*llG4VOun0~22^tX5b6iOM z%Cs~Ni_j-u#10s+dptb9MQDv`unGjWFCVUjcov~EBg%LS1Rr}ufBA{PBJ>~Z!T$v8 z9}kzx_bfu^A(N@-(&h1&{44V3%_%HGr?f%)gP@~F#F7Z5ZxQ-P7{|bYV4O>&o655Y z{Rv&ow+Icl#sg}^+z#q{U5)}4p?{!fYzMaA!^u&=B6Rv`Wc(daeCkp87NH!=ViC%A z#p4^W=iK~>wg|m#79MKQB6KDg#lw7vheZ$%JCJxzxSleo$1arPTZI0F{dC?k555YS zlZV!xMJN>rp;?6FQMFiv-u;Y@_AEkKF3%$L(<0CiV0eK{^yIl1N8B_#i%|Cd2x&cw z(05TK!Z$G=uSAIe$%$tXx&!ksvFiUp?pcJkIDz>LMD6f5gUE?*5&9zn0}(yig;XKp zo<*pPD}tUy=q*cO|Bi^Y9tV96TRw|W#%t3^ScLAu!+P}+Vm`>vmte){G+m2OHhzR; zni&?M{PvwvlMsWylt863o32Huc_&uffU0|NX~LQx7NIk6)2G@1Vw85W`I&qBgpkR7{})VBz&xdv39f#L^`>Q3}> zoj=baR24&%JsI;o{!$7(QeBJCB_*H^nB(fe8@V*PraX(#9?Kn~?jRWC5lMY{7NIX< zdqX5$1A+w}5%c6*gg(ja+zs$yk3f0?ThzA*9ef9)sd*CKQpIt>$T3M7lD^nBMMbi2dc56BRY z*Ru#+G8+lG7NPwIYZ|o(gv&fpo<-=b9x*IJLwhuhdJ=@YJ;|O$=!6E2us49c=Lz#H zLhH|T_Kluoh?pLlw=yf|mm6!&52K;r?dKRHWOeYHsfHfm79V6gcgs$(d z)wt>nY@mm`7NL!nVE#w!93p-OJ&Vu-Si5)@p#k(*5~}sMY$?FuT7(|=IA9Sv_nanF zZ-V+1IhZ@A5?qVW=`SGuCxHLtCvYr6>o(S@7M%{ohku@IIu@a;U)8BJ2AWL@KM~I& z^xof{yblJ!NLP$+5&APW#aSdZ7uZ5qh;I?P9mSHeuLZWj=XWhae^~33^f_P$eSX&> zbX$K|CSs;lCxM;z`2~kX=tkT$K1k_LZ8Quk698Fbv!C5qF+azMd+IY zA*VgadU&Lwcsz^H@S9pKm{);dnoHzcgdXXs>(9Ie*nKXpdxUOh*CMn6wiKBSa~G%% zU5@h54bbMW2we`X&Rm$Efa*I^dgC;oMQC<$O_z+>L06}&nH-DIp$j!yiD+YKDc2&j zBDR#w7KrbFzph5E89j^8rlXxg4F`UeN5kBE7NN8861x;<5%5*{Xp|6o7NIBK#%(YN zp7Dre36^oAR8D+hv)^AqWXlUZLIYR+ne>{?iGq~b3(`3&frd|eEttmG!YL?&hm z7+vmm^;vU}ws-j$$jc`zvDv5405Bpw@-NaE4U%i|7b8+?9G!yb9=VLbS^|3x_>e0X zr(&q7?@WHj9Y_6Rk7Azy$MGzjjT>>k>4M{Ugv~Y7TnE{gH`IIvh-aud8@l!!B7Vc) zY=LG}^eNK#hMLHoat$>rpt_4QQT&C$Gt|7W6^%gV#(-K9Zo_Wj9>??Iw>lNo7tml2 zb__M+oiutifH@vWLrs?6h)`9vpZOUsW$Qvi??Q>|1lJ{=L06N50P1W`9GinBnY`@3 zEnyY~>3+yLL|L7g4-M@}m^*jl`~*aQ;X+C*<9i9~frRX(hQ@J*w6LwCeiRn@H5;h(ZF9YT~7^! z;G2ZKgy&`t*QW}^i`o^70$Ydp$A~fGx{>sG9uFsqv)AY&28tFPfi6or3Vnz4 zl9oPVAfsrH$2Iy5ke@tMA2D!E(IU)+p^p(*7O{_E@}?+N0UfUa{{EQ&l8No79+M{4P>24m>ZWv_zj@qxhsD2ig3@s+}J8#s~h$XXg7jxJN{A$ zx{-rLE1`{L*sMVAGtL$R9V`+523bC<=F38CS&~jIH*l9&K1< z6F4NNk2M^-5tUM<1oki3$us^QNb*y$cRcd{HkhQfxoa>fHvKIYV4}}x8T#GJb*nrD zlj>`6&#gjI5*k659VA}C=rMB24T3g}E;Wl`In?D|=xo)tH72|0t!ApcYh*U4^csTq znD#3>aTYuz4Z+_$%#I?jyvQAJ6rVOYxED{T89fUG3q2zJDiE!CqtBRjZ9F3uqO~A+ z#3NEKATI%a-6r}XKFIK*Bk2GLUU7+xz}wjFjvg`X;+BJd2JBn`{Df&AHeo4>Xr)l7 z82&oDQYXPb$LgVLv^aMKYUl27QxNFdSshMg|B+^=$7pfnULhHrmxRXhLPC#`u>uQi zw)uR}XgmAO4foyev@_q`G&0`puSvF%L=0meZ5UkdcZ;^`9CE(BX|(8#tfM==;U$V5 z+sy5by6v~&gn4tF>Ng)Qb|I^oeUS4@>zk^PzO*e<=M1wdGf6kxHkr-^~LCjmAa*Hs#%Npt?I-4X(xM2N15; zWMgkTgxG9r$0yhX_F_X^MVMz*u?;is46aBxxMry+)Q*{C2FG9$A=VXa|9{d9*-xSyMuR~+OIP7_OqZjYbte6bOB|Wa zjL=Hl?6QP^HrJ^=cWG*D9sgVP1sbg0O;|6Ohppi3&RFd-r3UB!uM)nFe3*sI;6n{H zWgX1r1xiQ-MxgWBE7xV6YL34g9 zG@Uxh^zq-VS306A_El`8vgXrnMCxw;R12x18Eu62?9&w+wl!gY5Ekes|GNp(i$FkA z6+HMDDi)1B*G)-O2rovdr5B*h?hi-XL7jyf_Crhu;F0>zq*^k*eL#shkp!%rL{f1&F&rz76?d|n28@3CNa)Ir2 z6Y&U*(2QP4WOg99dz4P(FDXQ~PXBM+(FlF=kj`YAnz|q@7GIJ{w$pzP)0rD|CjZ4c zkd(tAKx%>k8PrB-P){^#N+382&C1r;M4I{sb-+`}!B#IJ272)F?K^*h7BUTrg%$jz zD}(_NA|49ijimJ9JQv+=cP62@7&2!X>BP(4#Ij+?{LhxiKKwYQk8Qzs+u#W&ID!w4 z)h!ZScS4)us27hQNgCxiBfKQ4BeiaDaWTA8lfkVr-NB^?YhAbxmO9XdNvrS> z48-e6OkF4>8J}^qok8`abymSa<8|i0aC4Basyszepw5)&ht%iWN~Yc(jO7T{#I!4y zO!`_K`>wmC0_H=OH-G*_6%OO&|i;?|sDWUnbBTl?< zX{eZeRcwTIK^n{OStnhAyGY34m9GLNAD6l9P@>9HLzsf0WS&J&8H9E^O&L@&l#!?I z^?1&`N*Z-o6}+tp;vgDV8dZoJ{mZ(aR9@uG?tvE!p)Bi>g!1?*qCUV^d|KXqtZbmP zBG2QTV-WXoOL71h;au@QbZgW`J1b&734WjEZ%(`3_ z%xfk1&jH3YMy^mB|v9j^ozPxIc=i zag0z!OfFSpX7F1)E9r#Z@C4c1Ph2a;=nn^l22I7L#5xu1(F*5GY(m?E&=c#~v1y}f zb|51ZK=G|oDmdU9{XinL9HOHUyqEqcq%!-)LN)FfM#Ybo^(9Iv3XB)L{}He^pggsd zIX?+owKQUxQ@%cyu60!O6e#-i&w`AK(enUCZNz<^s+@7^b~vhGCG|IeV%`Ss`c<^VjaG6L~E{2u)S9I%cG+kyuMURLlsG?uOlW|uU z5Lsvb;Z0za#CvY<`ZWa)?~ZI7aIK`Kbp$z2S8ekjp;Bsl&x^kId~36}=nOTj~2Ye#S&1`X+Zxrmr!>GV_I`~=+lf>{~h z2F)ze(33ZXq18b1eQ@aqn&!UC(MXN_72Jc)Pxk#DjXb$yMHs2SvuYOE2eWmpeL$Kf zAa<&JNYgPOi!eHM8{1&1eb1M$8bUb0-X-;$S{J3UZnY~G(lu6|2!&`#PpHvT#u(Ne zcDRS;Og)9SVXRg5q(5}Ht4p7!ZR?LhkQl8k6)#@qgVzMHOXmc2R^Cf_;pTrQgwuKH4R1oOB6lM#vENN^+VII#_&>!Qk>0G~N`Of;kxOsh@O#Gd zl#=vT4YT&aPg{}ntcGpj&lvLy>tI$qv)`QuvD>05_X^or@ppC=PudQ}i z=(KI#0Bg(dtio(y!;D>nxahxDiKM3>FdNc3;%_$Pl;1!wD`1ywifwR2k8>f_iny4& zM1QyH4d~_WW)}(AQ~uI~>UL1yMUEUHrWtzl5361m5~qwqAT3~jHAK^>=RkPSBi38r z83B7yH)IIx>Ljq!#3g4MuMn^w?23MaX!SQP_FWFHWReVghv6En7O=}raD2r@%J6wd^f#+X8pF$lB_ z*w@c=l3fFuhseRaYmUIlVj#*6*xRc(X+IBw!zA*>27;`m4gq^UhJw_>X%Kup7Dmcx=s*7Q?C`1Am<}ujlOh8tYiFsYbxsxOjn{ zvkR+O5i$q_BU~cC=kxIX1ePr2QKS&^~#@dOc@YQKuF%Kv0=Pc_g_#ha1cysSOCOC?Lu0IXrWQ zZKuY7V4_Q;dk#B9o}NQl^>6J6TFjO6?saFxZg$xq_R7Gzh3qBwqx^an?P)*K8*2f? z9(55_QDA4TY&;&eAb>8oaQ?Yc?ik#;a?vZAP8GTb^A7%I1Bg=ed2^-Qv$%7mJb`fM z%I-5!PasuYaOv-H)91~VvK`^hmG$TA`&Km%B+JRbf+_m`$6Wa?s%Se%_InIc26B0G z<<5t+K=nRiKPDjy;?0$(muUD`Ab)#kd7h-6vfe!TEA~B6^-b{iHk!pqhOy4EX_8Y( zSeDu4OMNN4)6N^lm7tn&2`^)v)5(0^{6~}-5gwzT@mw>MA9FMBi8x0WYN6fNn`^g? z6XxmiZFVEloueObiTXtN1d`GR>$`LGiKEygWh}Ro^u3`wM}LX)%ks|A@7|Jsj&AvR z{yBQ{sr+;FF(?c2yK^+ptdBH9*4;UpN8h`1@l+)5&c)ZjpRp1J=3IOy8JxLz6C`-I zaQa0BIkzomo~bqJ$M@&asBD8gbMe8yA@DUwdmDfA8jL(&qdqqm-5b$AyO4gq;%U^1 zm@)N}Wz5CL2WUc7axE-s@HZDxn5R+GN$k$WFMX(KR7VhY^@u%%* za^`8&AF;@iTi~U@R=RirjXDb|M1*Vw!A_UR*Qkwvi;&~M-gof=8nxJ9r&vFN;3A1w zEJdHMQIlCVcP>77+)1_qs=YS;l6TGFY1Er=cO_|e0zq#Q`C>hd`Zci{6?HA~7 zRB?TtZbVI%ryEW97nM@<0c;`SZ$5SeptqzOeH*p{5#8K{)KkR0ZghBVo^DhgqmG1X zBrfB~@r)3=OFH&RuNyVOjTC9r?YP|K5qsUJ+-B^Vf?aI~wu`vr%PE}{wIKa z=;8&s(L*mgLVgCppDvN#jcNfGA&GS;6#kM(fo{YhB*kh90vaVqu@rrNH+q6)bGy-w z6Hc;Mfo3K-n0L+Lb)%^tJ89nmg8N9s+H#28CEXY297(%C@InDeZZ~@PCr8qUAo!wy zB)1#g_PSxP?bN>@2(EXMGs@8LBKnKfbR!C&A7Jgz*Ns>`^?Rp+5wrC92i>{2n|&PS zL7gF|2W5>uY`92IdwmaV z!wiU0^m((iY#VyB^k%^BEPW3aNXJ2{e!}G+{53ay-Yne~TMXVE?VFwT&aA3{f;PZk z3a04$AG7otRBIoQjP@9$4CL}=X`{ausOBMd5eZokZ7P;k zuOaqh{JniXnWY))n541^^lmfv(Dke$H#m`M>oNP>)BrGMSnlU@rX7fNA>ERWd#mGa zh1xugGk<;X?dtaMu}o9>#X?SWN>EM z@4+B5t<;JCN?=ZfKedYNhtzGxQITywg}^4LxmNg_v(etZik!F`dtrzk>Ox{m z;H${*uFIn$J2%#ZYB8v9A;%I5^JdyJBz9-oV|z4>+5y5n9jk@P+Y z&J>X3s>tT|Ig&1dAdHsIE6G)nFKx!nDHA9M0vaefjpM4wV<>>ANcIkyX=%}9$dGFP z8(u@mcmv&56@4Xk2bhy;);ElzN91%_Z;9uPUhg4jaMhPku#Z4a=E;|-`1a&&8_8>-U7mn)Ov13$SKq3joQ zt`5JcbJgGF$ZsaZN7jlLBlJKaoyLLndcIute{rN{Kphla6MP4A4YkBpGGr<|WI``- zA5)BJ390u5g8Q(ELZbg!Gk9zfKAVG$YSW$q8MVUp{U4#FxCsyc8u)9e(0L&UK7>kq zQU!wJC(ke<)DE@6!LoQ!0Zs;;lt2=;6C*qiqE0$@rY{J!ZjQHNk`;GYJ|PJawuS+8z&~vUlCPb zr%9^FukbhgO%qEP|9L(5o29O#|NPJJH&3jiU;P4q$0Cw$X)N&TbkgaL8wLLwou72{ z=Q{V46q*OB!oODgQ{RPueF?_zP~jxrs?|AEmcghzw%~>lYWq9Xc7zeNGOZ(MXw>V0 zvq<_O=-;{z72@Fpq*TTgGKvG_y7^;=ledf@zPu*WwP$AD>>Bzk<@ z^wE=yR^ksBNz*}6KP&hcsD`H0Z)?@Yvy1=+wPtA-XPyjUX)pe;kyHmH^*aPlX_l^5 z8>l-z?9nXUQu(|`vve0fSh7Jj9$(} z!wBzG(Wf9VS`GuQR*GH3W}gq{qLj6uSxO=2--Oj+HAQ7I*%U zROx2LUk0-g<@2`0^~p$jpc!KWO=fz$pn`DSr9$RNpu@}}bV+fCN0GURjAIJ1^&e)e zY#?Ud%-HcF?KwYoIb$alW{bY*#U{2*Kx_*u-V3#HkoaH)!!fbc-(X2T$Ga?& zppm#5qpSW_s}Pf4Mocc0sR^R2;KVT8KGol(B|LE%s%~kuLD1fMgBVMwi{qDRx8k`@ z^=F#NUywuw$oLjD5%sc?e0A&434y~Z@Hk-V8zb{pv|Ig|Qs-qDE19Cth_djR4-bY$`T#L^Xrk{Lmit2%ZNOZ(`hs_~AFy z#CnMJKD_HP?F$Tl3nQPc86N)LF6~P(l0xWBO%rLP9U5*HSHJefEB%mgO`us}>s@#T zJ}}xaniWYU#lX3kL7JsTs3VNHiSs_16|$xEk)*K{)E4I zs3?U-E;8aLsHzsh^b*^!fZqER7L+aPh9BGxfu%mci(mB}fv0~$pivT=D;)plO9UEA zASE82i$D_z6ps%rk3driWX4OPge{v%ph}#_khE+rfjaRrxD{;KLIO?Ve9fX|O9`}& zKRp3~))MF#Z?ph`HWKI_UvLP4Yzg#_e+Tu{vTd=kdr_tFXQ7x{wogn%U|f9oF$6kF zuBXPYeIJ2N5||NxqzeMM(efz5?0CcV2y`jJnR!9{#^(^|T8LBm!gvgWwq>{QG)TKK zKIR7mdK9_=fu->+6fhvUHU!)e-+mB*L20)DSreZ@WN`Xj2&|8v9EQLU$9NHnPlq$r2 z^b(rI(NrJcfne5oQ=&g&G%rRpj#f-`e-A7{tFUMr%m-TSh?*0sMA;G`_*FBPA_0e% zmXN4NET+d^Q(`hWHQx>tChH2V;rkGil%>Zd9z(y%>ZP&i9!BQQMreCFz!hffVYnn; zS%4t%A&YZC=jbsPG{z^&fbTmUof!2m0u7XC)Avc^DN@Ct5oLEy3_Ag;s+!7r5>)wh zt|m=fZ-J_!){Z4e#fuS5V)fm9J+PiyLOV}__(bRG#F%)Z94qTLoxd?8%~O#H%q3YD zHFmv=8Hpit5IscK(>hPO2zDxK>;+J)F=IpFva((vm9&B;Nc`Re1PM#p{v<*64X61w zvl&Kf@fV3n6A3qiMwEIg#OD=Rub8oJaG6Bq9hXuj1~aGAwJ08et!vWDsSE%`vC3x6+)+8-zxksP{^r;H$m>IhQE(L7Mk0)|p2VP4z#|dIGWk^L! zOJt5d3xW~S+rK0(4bB|kM3?UYO^`V-xHE6QjLf&+26Ur9nFSydx-P4q2y9L$kHEd( z0(wrmVBh>)iN9Y4)LTz&b3Hb{x)^6fOJm9PjG8gYXwupaGZ1f$8_3p4j+*T;7$@yV zBoK(xP@#2H0^#`6cOwv!KrB9|J_5-SNQsvmhd^8ciTF#!`8%t>ZtDFckfs)&)T17G zY}(8%pMdlQ$>1mXk}?uC`UARF$=c>G52MeBGRKJrNibi@jGlqHS7%WOGH<#I*oTtE z7KHpF3ZA%)_*Nwgqapct9mPEMFA(fdvND=?8G_6|e+0o2$@v5MQ;z{;w1kgs5Ts~=rXGQe zG)=ID%EejX_aFh2hkEZh9PxLVu}*L~geUn}Y7}!>)`n7aNPVjdiK;X-ygrREt9lDz zsdFZ4q~7@pxL+XEi@QXXJTr5=x`^3fdF2tI1@TcpY2eT>sCG>8?=Ed-r)H@7ck1>qw z>czL9TO75;qB+}>V-4B!Wowffsrl0J7n)g-u2kLkWeJ*=+(I^yKQYIQOdrYx3_@gvIi_jh} znPz}u3z*EC^yI6F(%>p`9Z~H67|9G~974kk3N=UL1K7w~v2M=!07cmTKLIeKXw zj=zj0Voobr|E9#BfM(BWD}mziD5^fEodh!DUr<1M2~>$26wpBeb>aspprZtu#LuHG zb2>?&bvy?hG$&UA9pkTJ`I^%?%sh9Gzs|rF66g^hhoU%W4+4U<6s_()0{A%Ow$Qj|7I0t4e; zQ`%?=42qATw22ZJ93MbwlO!<2$lN>!p=;&N{d-iT3;d(2p*x!hb-u?^@ zR9A08X!Lrvz>7t2p)cAif{O&{%UC)98!&AnDP8uWRfgS$9nF~BIvDYCZy}Ieh<8xf z6G&IN;YYD3n7~{h#Ua_RgdEaB6<^j)4ITS z2Yf>Km`j*yB;A5cwCi1jd5ADR${Vw8+xH>1i1j8S)LvYS%z3vUW`|6?=e^j(@^=uM z&`bG${pf1wt?i2G=wi=#GE6Akc4tLK4KFrPc|Ky5Ub*G?(bslD^zS-)m>aF=Gos9B zq9*ye>z$OvB#^0`lY`E3qDprVm@3W!JV*jr>X;UK3JAh@UrDtZL;8PTU%ic%RMc+HgAzKu&@ zB&x7*rsnJKMUTG|JDu&qI=b7*s}QJQ%_1zN$~?rFHB!O1`LW+Y@3gyDVjp#5HAA;R zKR|Dp&w43zJ8=(UI;uC^7^zhwk$E1`SLn6DZ}~7i3}p76(4zyWo|6jC+A3(s&_In{>&%L<7ZevFhOR6E4Z|y4=59g4tmoc%>H@(QOpC zrx66c2wz|BKz#zwbBewxrV*_G`Us<do1Db)A}>hV-1ESMBR#fQTzsK=X5 z=$4vzNV65qM$CxR1AYA+d&ykWe#B+2_v)rR%#HiKmxsBt%DnTWJyal#(oiG8U@~FT>2CGBd@{HwaBD%~X_u--t@^jcCA2 zHZR?AiPCZ?LW`*6+Gv6(?Ykn27$gvF)eRS`2ZFrRW-wXe8Xy?um+~U~j9@Z9GMLO@ zQVo>1LnXZyY4|q`fa{bv#dH>;KW6TQitn&al*&a!>J5TJ@EMtdW`VY`>>cp?e;T6o zrja>>P=g{2)FPzS*7KBgUtw~K&4k1z^8rXQzwftS&Bry#>hT7Pj?bc|d<|QQjw$`1 z$uobw1O9GuC&sV$DLx93i;yBg0_X~Xo+iYLA)g1#Y)NRR z=q-NsPsvSnW)@?2OYAwu@?u1%FbDXIp3!MhDwE)M0X3AlV*z59N-Vz)sACgTuSD$C zT8%bfv|MDWkdFyQX+NDj7CkOXQ~6{DqqJsC?un$LG=ffM(8{eOU;U%Iua^$L@3=oY zE{buE4O-# z->sv|57b$?HDdf69o-wntr_Eo=B(VBF@9Cf%B>aSC*-w{C2P|F0v?zDbt=vYjRSa;aoq?x>qH*kP$NgE{CNX}y%*t&N<2TBz+@>*pkc{q?;x>!% zV`Elsvlu@uX5}`I@k3&C`PDEhw?&Mf2%{TD7qoJ-VpSYB$8m>>+d9TCcUifuWBg1P zU4E0x%54+l2e|0+Yg=^rX)P-^J66(h`Oz$f`GqViHzzjHarx~lhBt`YHpZ`7S-EXv z{Dc) zcHH;G9US}3af^%~|BzTs$L%QY(AX%)<;PvD++i_($%XDy;tr4T8!cAu@Yt8);`_cM z86FYir&g@okuiQ(g>GMQN5%NX6f1XBjGsrba<7c>TPSo7iaR>Subf!9qhtJ}iIqDh zmO4ti^~D_<>*csti#sm1(s6f+J3jW7}JQ^EbgS(5y!nC?&KIhr(xwzj#UtMN{rvguyUuw_(6qv`tH<@t{}`Mrit$ zOr;U!krfes>mr%o!$@W@x%n7eI`Xn{11?YC5^XUSbX!1Io4#azbs?F)D9@CSyhH&< z#{p%qHqS#(<|WEw+9N!ZKgy3bM0nDFa*6REA&|@?)1x%uiSWeN5gvya<#}=up4OMl^9qw0jM5k7QEd^P^A_cyhLOqi z(WEItbEo94FCo}*6M{<^BoJNP0KvN%;{G`Zt`1S_&mX)T&eAj-o4 zB8M5I?*(-o^bzlrI$VPVLg+4h0T$Tb_!pUr#lq7E3_ybbZMX$2NAXTN{ysF3pSv8# z)opde>kl(cr*e**7@f^(_7?qq$(|Y`mn#{f=z_$m1_vJJ>Nhq?Tg?{+rr50=)85Ydal- zX;KW87wRv!LFS5yMQ?m3PjH-3@dIS26Iz?U{@Q`Wcfon-SzX~j=VA#mR~6!XX|CuW zE(c)N;duikE**dE#>hN%#t+T4G&Q^aT<nU7<- z+EY15E~BWE=b?W1^D90Bn;f2ft6%XfqT9(>@e=kcUbk+?ODaC)x&_#ycM|cdVi6K4 zP!()S?<^;sE_#t}V80jX@MU_@b4X{PlMe3J<)_x3MmoU;82W6w0^RAbmCz09NIz_q z*Wuy1fe%}abOWQ0eh2Aa&(u;UYX<`}7bB`bDOkA$N>Rv6(^c*a(L!bg9d>H3kXc8k z+tH}VqvSqx(kbGlGauyGEWst z*so&UwEc~WcOjjXPCCWB%vE^Z$s7w&a{dA7T=+^g+-|CtQ=>)-kDnWPNhWUvbAcMX zOh3So$kz`rB=YrxyhGw&q|?Spr>vLBqi!b2=e^tF4GGSEG9-9(-KW=RwhK8M z-)Ge6n(PyB^u@ShqD%V(YI6h0T;X)5K7lN!JC$6b7;hLAry)6>bHZO-JLpzpn4I;L z?zC==8fkp#?tVZ^9fn+w;bp|;f9Z~N`lY+VoT@WXYLu_Suwhg28bD#EQTnBAMX;WWPtN2rlAGIDDnZz(C#_1-zO$lEy_Muki{^^f>9pcX`@t$a(47f+CSdPN zvU=LhD*3&vYGF_@zk=zTt92gztoDD~$tsuNo<+KsRi}1j`eash*w3mCcPz=bJ}#S8 zo+$W{ld4~AkFKVaO_v5}f2P`KtOCFcnZV9Q2o}YOM-JjwjYrpBeHOMKsk9IZN+dS?bRy`<1bKEo2HqbfwJOH zt-bYKL!Wz3IFEMu0A0pfv1WcahIA5JRJmPk8F9z_Nmalh8pc|&biR?^e-!YYDs6Q( z@ki&Uf4>G1yHug+Z5Z*y{Pd`Wh^O6%J@eDsr6OXtW?>(ha23LPGy#`h^;;wSj2rH5 zr0i&co;p=>Y_!x4vi>D9;*BMF;b}i&bQw?uBa9;ds*Eu*WT?KUGMufed-!BuN2X*# zi9F{>_w`A;_t5C|4`MC<5IpXBvM3kmX%j0s^K?lF#e6S_t|r zPo;ckimpz7{115FDK`t@mD@XqQY(U#Kv}1ZS`nlKn(DBl2nq*^>Tt(!hkmG%!h!0J z?lRIwW6GP2M5a1PP}#!@Q}^#ords>e8mS&ky)QoWbwGCW_m@|)$OQh6j_J; zBI~eUWJd=Y)%cybtB}aYPSSo8%|@&g`3KRLXcZpedAmc`%`3{gpu6-;POU^R@#a%- zn0WIkxI7bY%7^ISLmlaUUvKtd-ll%4r#|Y-o3M1JzgSH-DOVhmjkJqRos|%RvyHTW z3b~3Zjpq>zfW+2LI;Fi*j6tlF)@_h#9dZA%7_rqH+M*uqoi6P@t<;PZo=a*tbk#h% zv!IhR=~!m(hBW$MPjVM)FRM+BVeq|71tTBfVHP%U_969e?>{+~>*| z4k+#Wj(F)EId~Zwm%sVi!B{DL(kUqwKWYpLbGBhW6exd2!o!VD!l^w6~jiWLPx)1*yymMUomW)0S%q?AZAI( zD&nNzcj=~xl^!z39l-N3?|n2u7q*dC=KDb>!__{dN^@%D(w4Ia!nJi+-<=_xrNjM2 zciJzj;wPj&yO-ocN#0|m@C1ylP8zkmG(JEYdg42wGX05fvQgxOs%^F)?{Fh!17Km#(_ue~ex!pR%fPV!T0_aL?qS-g^Nh7G$C+wpC9*fJ6}Qg}r3aYuAjPc&aj^`;M*=#ocP%G+gEQ19O zRQt6?p<^obL+B5(SK|jg9tTx1hu7D?&$ztDk7(L7erx1?#GW0i6R6{*^Gg9**%HHN zNSe4hzS<+;O`OJ=F%GYv4qqvjJi6&5(>Ni8?=r7)h_k$eW`J1w0f&XZGcyE)c!jw& zWpUqeY5?I|15I_fyHUI)lD`4q8vJD}FtNIviSRL%Dsn=2Im&(_2X=IDCpalr^HP2l zv4toC)mCVkxWkQV;SN~QAdv0QSN7 zUnBhh$(K%^-dasBRy(WedfwD?49*qK(P6E_)2>j(9gXGeDc~lH2Z;0B2mbu=(c*I? z_b}>${Oco_jqtt%IJLc9z~o zTJ%9Yq=KNAoZAM+fs#0fSZSUKhouHZAK>nRCvE)q-2+eC2z`OkTcvaWDndWSc8D>VVnNj2rfjM9X1O#yc1E>Tr zVv@D#neG`n&SiJc0B#}%jaSr&nwzLG+5B>N0F` zb@@PZ{AVBSLMpfGGqSX}T@{zurxDl7oCt+50FvgvO>)6JejM+Oggkyzc5WW>_-$F6 zK_1ng+=h6cc$Z{w`g>6>D3OATaZ6~C6TdA@`F{C4T5P1FKtk5SL5a)B49HpxQfpNF zxO@hwH6llLSj)*ySxu49wxhH&bsbyXI);#%uZ*C466cKT9z|VC?E^kU`R|43bSLh9 z-6;io%l?ZYC=#b6P0qP^j!2m`2)#`iS5B)z%`;@K& zE0zE3qmLuiRll-!i}Fc0AFf-_9I-vD{}&9ogZ2N^K41crzY*o1#NAc8d=H?e{ip7O zhb~dhwbfFN3s8bRp~{+Z1N{C9O1ToHjKq3hwNMx*SCo_6F-5sIfrFi`Yl5AF|Lmh5 zLQTvu%xH>i5)O8+HEj!8bt*1-yuQu*Ia)O`*Y1W_5n}l+d%3J45_-YDzsp`P?E7Ba zL$&d4yHfL~F0rh>e*?DSqL!O=-LI7<0NP%QRGyzawAW+T8MIe31B`7Ca=i&3CJpZb zTG~Pi%ZeKoybr&v1}fxf2m6F^eT}ZdTQMI;YK%%C3Ngsny;jX7kO{wln{VU8#a?2H zop^V{>$zBZ@oSgk)JSC9;Esy>J#Zn1W>{s}T5&q*gFs_$LrnH-PH}Yb1(Bxm2 zFD`$S!L9Zx09wUw%VQgCy5Cd#*jc#$y}1V;cJgk^%Hqw3ba@`KxEiTEYOc2D9hli4 z{ex8aO}E}Hztl5Ju;em5?s*?Pp*SDp3<0$*V&(ssS}*q-q9kub?o-ofLTTYf=UvPR zbrhV!Ir7;cB~K49LfHKRgJ1EA@kTA<8Ih)lGBdC1HW4+_X||F|)Jp0!xe+9>j-dmV`2} z#c6m0mo1^VZPq#}uR8=wye^yj*9tk4^$IXYiqw4iuWOB7do*o@0P;+lkvVfyB;+tnaLB5OCc zYmMBB_!8S)CAWL3UULiJdbd`0fW>$N(8sl?;2~Y@Vz=5ONcHs&T$+6WHiaYgPe3vB z_er^cu6(_g6M8RdV(JRTZQVPGAhAMT6uB4R6<$wMh9MHZMqWz0@BYfXOO%-oX(x;7Sd_Wu z-V_YPcys!1^zh$+TA3#S^T2T(8>rxmPeJX6EZ6F4z0q$+YK%&t(J#XdHF3fF06ORB zyd7>658*M8>;X&NFhw}6JqyXVNZk~bTX;>LgEwpRo2R>Pes1hHm;9s+`Y+`B!^QGi zo%{Alr1J8J0G!ZHYl#irW!Y~n>sg(*-pxB5sd;&;2e-h&fYd>q7t_Fh_R)1FuVCFR zR`p7()yt9knO%~{v$y{Vsm#sOW1o0PuZG*(--V2`Nksg=v$y|zEf@pc^mT4G={T-@ z5qCLKqz?kEquJYCA$Lj{sKo+0AFNwfF~hCm4z2<|NyG^NMA#>Z>ZRG5M)AH|^gB)N zJ3qu@ss2T~!Lxe6-2bAzoMLVR67d|1=S6$HSV2Hn4rdVb6>mPhQws8CbJFki%ukfX zV^#lP81a^nTKQ_p>&@m@k;=14kA1Qky_z?hU+Jd=cu#aA!Pz9KFwc8}1l>IE z2}$sIPlzDtc~6LF?0HYfJrsL?M&F*>Ax-yYbI~94Y?2(xefYE62X{6-+#}u-S~%?I z9st{c$@=jdF`GAHHvdIe;mu}(tH5kh6=pW6UY^aH(X2c4JKk*GkH_w8=2ef`q`0pB z*%VX=YDI^_U8c)g=|aYw|JDebIBA!ka!I#He^8ZbzMH8dsY*5D&0fu6s?sIjUk|i~ z!nYT6c?(h*Z9J+`%(PEKW%S33q)j?INOl(aFd_+@D6@`aGtvkwNxcfD8$9^7&c4v? z$=#+{S51B0R!DnDy-DZwu^Z2V|{(#p?2NMC-rDs=5ALU`xC;=YR5P zFIa-*_H2?{g%B^dR|z4eDjt3t{QdF58M*-=ApB<^-GkH^l?MQc*|@Giv!ERGw@NMmm1n3l;_e76^MMz~6*l;R7x!xo z@Uo=)uWG6>tyQ1h4!t7Ex=z>N0pp*M%0Mg71?>3Z`GAH$LFmzWJ$8LDQuFh^&;m{Y zsZ(`c2>twLAHCS*eJ^8DaCx^QZzoa@;KLJ0PrzpMSn8vd_u#j+j$XR175hDL{k5)l zo?GO7NR3emn9SJad1az-WT!MUG>bS)qG~Y*7Pu&R`VI{wY1l&-g*!{ z_%rxRfG7QB0QK}|A3Y1H+~XbGi!CCYrYBa)&H$LL-hiHOM6L`zu4#t5M@z7cT*fMH ziPR9o+r}pUTOupyMpo6Wk@*DRRs&VE=P!u$kL$x&-t>1=E@;MM{=#Ea9T>aVR=#eC zU4kny^syxWfcQI&PNTe47vl{|87go&Uo$A00XBo8vAi{n4y(LW7vZ7REEQ2;$6?4M zMDLRR@b zUsJXq?*ck@vtO4t)h%xyl}CaPy)>IjCxoxb`qNu6g#kD~f>EV)}BQ-`P(DL~xU$K1Jkl~M8q~0^# z>MyfwPet--QrQr5J{ajBv`jy3{OaOgnw!7Fcs;dF(luA=(r&b?j$nSoX$qZ~b|tF( zw}L9a;jgmWR5_jsPwKKps_-WJR4rO;+qCEgtqFJ9b2~qb<@n{hu`T^hdj;8j+Mbk~ z^XbM~pl*hdSr>bnJ1W~z1VaU7GEhOkF`@=4+uz7AFl*RSI9R{O1R z6hF2GoBVM1i&sf6KIWpfwg`DQWQSnH^V`>}>!!1ZC>f3%PPU>QP`wXdW#%i*6(2$_|HE24W#mXk(LB`fzt-9ip%V||F(|qMc%>vVlg^^$NMT+ zr|;vf7xCedBi3ogUvGm{!vjSnzT*WXA@bFybbTHVH5;ihdY#%;a~UdGgp?+HxU54c z%UVa7p85oo1h^j7MR<(;Wk`+DTii7Y0(diSz6(Z!{=BiJLw|W}>2W}$GGm)SLuG6! zuIvIjM))hbAa87ci1&GHuX@58Tl&oncn@gJUy$Qg{hl|rXJMORfY!*^J`Xqw9os=X zXv16Q;ltzc5Nbh)C)`e}M$k80U$3k2#-kspF?x%dvxLs~xdk^{3%cjn4kJ%gbG-9yE*9l(M{10UU{)lGI}%~7 znxiQBQrz8y54TvC3;|9U$d@HcEzlZoYL$%;)cy?NrSi#Z2SE~D7nC%PyW72|S4O06u zw-Ix&f5_#G^F<0Al5KcomWOd~m}G7Jgmb~?*F*kA8Bgnyy+yYLseZ&{)m(d!qEut% zs7~S_W%sI2#Z&^>_bx6YNuLsH>C`{)z? z@?um2@xwiQ-4M&+NoI$XKrjtDC_K7wTd>oO=kV+)iP2F%avJ z_b#Ni>AYC~{AVBiSbkn0#7olX>3y+uV_Z=c=@;lchC?$6g*F>Cy1AFZ0K zM^O8aMy;i2OuIcxd`Ne+Uansm)UN<{q^;OivwvW3>yXZHiI)NF+IF*l0Dx&#(^0PL zP}5(4PU)}RmaBdAYNRUl6=7z1D*L`bAhxCI{ea7<->4H_bwkyZ>6n0TG}Emg;1=Fx^bqGf4U#u0O_SD`mE7Qh4oG`1J>T zxHNjr+DthEIj_Rk2d2lIEJf20^=KGDi zldo$v#@*R~!O7QcB1r?x2mJm!5M2%h-J^^5z;*zsyeK@KEV!yqmd&#t)nl+~19T9` z^)`HXe2KI7a7_c1Fn0y?oVZ@7%h%=z4EAxP#^`m%HSfldJb|0<;lpJSv*Rm^a@Rf$ z{ukF}x~%y!5-6);8p@*AxvW0`D^wz79zI+aIV)KWl<6U?_KmnkbP;E{MQlZCjNYOm zs!z{aRvI^7!$i`bH!Rm7)kmI4jFDk!GN7>qZ2BF@^&xz?dP42Ku22bg?*gX4^-5j7 zH!R;mYK&gzu1o|9`yp;#z=z8s?TOVunG&dPG7!^+x(Kf;RY;A|TU5kN_Vs|CO-NGz z{TnzlC_v_YkaQMLjx6f{QUcBCqMJ1o7uT9HZzudiDE!^TEqG=7S@;#lk0E@x{tNH} zD4^R~{QX)MSC`n(_uYxqHr)=wF7#&~eLqrpsBV0WSCO@ZPFH;tsg*kK8Il!wzi#r9 zU_kAjMrUSyyG=5j>*kvcr=O8LZQmPk(?9CD=~u_lI^fn{a2j^H5{|w=y z8>wwN?{>HLY(d_RE1~~G>gzQY`M#U?9+NkViDH>z$#qv?{Zqj@v)BFao6N%W5LAg1 zj3@xXh_w78%)T>iYodPlY`3C%q~>ESV$U&#g0&V_d06X*5Py~-`$l|tI%#eDK$D94 zIaW^+*MD9mHEeM!>O*RbUT4tkM1!uu&HuwEpGl_bg-QO8N_OLDV$Rp*2YLtx)9sc0V>F zB9**l=+B$b^MiS7{tF29)ksa^!$U+f;u|7*qv@UCD{;L~m*)-9ZAgvL>pVnHp{)1e z<}rNSvasNKt%@rmXHmp0;rKF&8tC;e;d26?|Is?1PjHiIJ^cl#F)ELwh7aLN zP!;M%&T+j> zm*;V~Cy^SXA_xFJz*kV-@HZv0wZ&e!=N>w9X}&atcyAnRxF;entAd-JlHYFsuK>L6Udj?Y%gYz;04BAsy8 z_woBheE3D;#k?0ADDyNdgBjHTMcol^LT4j2Mz8a1JRgPr3n}N|!)0BKvGK~R> zpc&4QNB1mz$XvIT^+6S%j<+Z0a@GT0=4)s~( zD|8M2jw-j@h!@uD60Uye(84cJPtVt{+=GOHOOUWxzj7Pu_#Nh?e49>q7ZNVUESGQB z3HKm@f_{|m&9`$Q#ZL7WCDsSZAwq-{ie(=y0pFv;9yRq!Z4Y*65 zM4U8`$g(47!xh(Kamn4IP@8q0&}_*2baCIO;?h=m+fjNYOm2Jcu8MdsC;ar;_)xDaBQJ@n8(`9Ft>-h}H_1*Khw)EK?a4LYkA{4Z|a zhYy!U6x3>0Q|k+uvUE`)ezU!N%dY!IJU<2tXPwAUgvMz2$8x7hc72JXSp-}E8) zHYW1wMKT$nlKf{MeJ^sJfn`%$r6>N33ve@EZuX*p<-iY<)&4)=8wE@_Q(oL3F$J7C z7w}9-Wl9jKObsBFm_aH4S4Jw+JftE^X}X*rdgNi`;H5M}Cp>~BdaHc|oZH=%lUh;Z zR(yDDh-dSS4Yei#?xqjdzcfl4G4T9nA00+&j9#a)xz+x}LBxHloO(SH-h&U9M~YHk zdGyBT?njtET%XqEfsX6)9!F}7UZ?V^8?i!8;^rZpZ=Rd)C8RQEcLIcv^45G4^Y&My z&VY|K*Go@)_0k*j08A_K{I-IAtVe2$UgxszL|NOAaYv;y;X6O8Uzp{-@EG#4e-i3ss#x~GMhf&vWN_Nta?3iX zU%{H>Kd44wtpFa$TF#C3{Hlj3@1AeklzK$xMf3R2x!JCboq-3`A?q3YC%{}z6YkZd ziHHb~YM4=S=GqIH8Cp<&EB5v1LT2bf?4y@Sg$Ts?l5;wl&8fH>?B|gA^*Zw;H?w6c zt79he(50mo6-KQ!lg^p6dQuHi%a+;a);d#>pjJ=npV~3AY0}zSh!=RImRk-IfPjN} z*4EPV3OtX}bBw+zp<`yG2CHY5B%ls@KJiR$z$Bc^P|q(+&M(lba>_K5W$F}P5pC#A zOj(Uw__SsA=9$y&85J99-pK8kPSsP_sOlN!2Jy4pTF?&anl!u8O-7GRVwLU!x0uSA zg@mY#iu9?Ps!irqTq8+!^${8lu$cLyaGG0@uHWnDY?=$IX3k98nL25b%mpL#cur`1ep!!o;ZX8+XuZk+Ds<#wV_ll=@m2=1sX z@W%d19{V%%-!(5T)MMekxM&5>(H!((F@qnPMc}u@KdMsXS#FWsbn217Cz2Z$R%^}s0S<+oSH zZj(E9YIXf2s{H)?!U=BM^{luM@u~2e^8t{t0Zq%U290Vr}hP?Rs10 zXt(bXmBujQJ-&D~K+0R#ud(e8Myr?H05Fzxcxbt0=m`xJa;ZG;pW0GO%K*_7{CE+e z0P^2oTWetS^*o)?HTB9x>;$8h^$+@u`U*TSgAkGNxooCwa8W<6vv@sbemMqqFIQXN zb`B*FxFlMv&1g=i05;7-*Gx?4BnCpj56D@PCIdEWQ{lvO>L0MVN{wQm#nS^_e>MK5 zfz;)9=Xx8xrn2{;di154sFu{9c9$7LF!k&WZW8CBq|2#I^rM#xMiEajbYm){;69#= z`pR?aKjy5iUrBZKOVW&U>aT`=axyd&FpgP+1aLfS^+2B*P~86g{x}c{SDFuuxAOJv?BBP){b0-%YkgM+d#K zDf5-4tBUH52;mcm{YOo07%1uqVCjW7n$pqbzhV^d3JuwtOmc-TM*#3DgC{D^sec5y z8UIoKL)35?)vImu?m`V@ddBPOEvoU&wkc#emF@IT<(Y=@+q~$qBUJJ=c9mW`*V>Fm z1V=IPo-?r*Io?9)7<|TEzVz#K`ZTJhns|}xQ3EEjK1K~w`GoKWG|R9SSEAG#_1ip< zl^rvCnZvk=OQ3GN6`U0r-x#OYPe2{08a_9s6ZPekL=)g=S8mlU;JI``>1`ko3#QJT za4$vt{`76PaL$baolWps#lQq)BLoK`?ik#xTbx zGyC>H8u2A>wI>OTyu&WD{Y6m4@3a@8Xu`qok|EKBb<8}smR_C%%Jyy>0Ig6hK%Cxr zkFAl3zJISx5DxESTs=Ms`d4$Wmo}mCy8;cQ)e4cw)Qu9U)4FceTU&>B?lI-yDNqDv z=KWqN{Dy}d@AaPO38G#Y)cJwXr-Xbzh`n7rA$SYR*s}h~_R+pcP2BMhd9Uk+y5kEU zE7J#E@3}y5@Kp1qN?$)>YC;iQ(?{(!#I@s=*rt!sW6iYlpyO5HVmNo2^&m4X5*7K3DBRCMk6mZ`qK!lf$eKj zw#%Uj#`vsPBf99~{f7ZWhCe2t`W)Ry4UM9dWA-^133%1o9;a;KOg1K50D{lc8q#DK zyIahPLX&vhzKD_E%$)e6JO>0-L~7}{2fbqU(=47a_Gq1;N6p#bMlJ^|tg zALu_qV8aDB@VBO4^FcY~?@?U7gU>JVfoGPr9G?z+dht1k&%O9Og-^tuABk;$2)XPN zbo*QSDuV(hG6P@EEc!)Ht@-q8DWx^huXoYcM*7-8UzgF>0s6X;zV5_V*$46Ee41{* zOkYpYSB--Q&(g17(^na8Bb24Al75|uFK0P@or5p68DHfW(d{Mlbs2qi(^o%zT}fYW z##iJP`g$LIeVEb~($_=u^;!D*JbitczMjEXGgMje0)9n*jjsv+O}`>#5Sk~` zR~5c0PN!ch@nvnGUmf(djlM3Suf6njDSbVTuV_F0x)NU%H`49x^z~j!`w;zl0AG{7 zh_8yL>GnDLqRO2gP?~bA2@#_~aJ~x7!R*6oUR@-D2`!7LMR;nI5zc>A*sAfETD4W4 zI;sLsjc&xb!Lijc=iP^*ITdmK)7qn2wyCybs&<8%drVc-%R6O&h6xd)f^iMHcJ^s zvE)2A*;Z3uRx^%89Pg=7V>!RV)44CJ`eV{MrKVE-S}Emxc(MIbWWKyM2@j0c&AE#n z#OOh}s=@=KI)o=zWa$i5b5hMasp?Ls=IA=LCGvKArmBsso~hnSX(Xp= z->#}ps#!0o#r)Q_Y7$)|o2hBft3@xX_0jv(>gXPI##ZUd8@agCa=Tur}3Rc%$%@59`^ zR;g`~Sybc%9tdNDbl!(I1Y{@hKo~2lb7z?iK$~z<&510iRIM`BbLesmUy<_L)HGaG z`5u&q>jkPJ+5=Y|)S$Q^V-e&v;3lsaK*rHAZg- zdrs6s-9nkF|Izka=htO67QdQt3PrC_6_FK{Qom#~27l+Dl&$9cR>gjb7TzIUl^n*! z!1-u7Ms49qHEpX}enK^Em4T8>#%IBK#AG_GR$v9|Oju4Bf8!b9e1Ea6%A&&<3C1c? zgz?S@Yl*yX97UWDEx}k|tY)Jn7%oP(Qi$z7Y3`V#}S@~98JiwL};(R3I$D+k&YHS;%^ks<$l7)LJWYZ1KsTXptfb$U+4 z-Us-&)(;=Xq0IRN+B}~i_=H+`!jwc68P~LeiUf#_^IHfI8y~x|+F*SB!rCyIN7gtS zI&VQ|E21|Dc3rL((gYt<6X>#4)zjtQ7}49ufDiU5b+@1xS*^y+(fL`-RuiJPtA^+k zxNei)3X~crOy?uhd{CN`Vy19oj7Kf3AGWHGZcuYS2V}NFCTA*7ukr15zHSqOX?Q^` zA%tR=Z^gHB7rx5CDBw~K)G}wATKzo814z|&g>FpQr=~}ifNVyaK?@pc(c$IbDh`5Z zOuJTW`}^U1)JQ z+td=eoRp+vY6abGm+YTIS8(TCc}y|g*`p>q6Yf&#q>R@z?x}IOcAf^>UarxbJTmUw z&cEZ)3jIjdobeuaK8W^C0MykOyg8jqH6H8ClPx@^8a3$4Q{(&2buPhrZ$6>UKBii> zs@Ao#$Yi37t9|H1RWMRBe*eyg!3-^ozC~4H8fv$z^S7$n6RJFVn`#+S>vHOh`&8|9 zs{SWnV^S(|oq&V%#cVTh?m%B=9ar-;KR1JC#%ynJzE*ClSad%iWx0%>EON6|!ol7S zHQ{A7`&k2xWmtRPf{B|6^Cy7p4y*E0m=JJ-3ug$dmmd=@CbD#r@pWaNAg zw>`Zv8zOjmGul<>dyrgQjsj~ND7*?P+V9mCvGa_rN@Ov#o ziyd8FenKEqM#t>*aeh?+`UB3e3PrqxmA6a?kRTDWZzxD7rHsSpnRbB6E{{F}Mi3o7 z3rz2sURTXdD(AyY)7PC+YqqL&ntfgYPMU}Ai)ubyf1*yKOQe|q3O}w>>zpgGzABUC!;19)@-DA9!LFW9#hNm z8s6Wbp{B6mCIkRCyy_3C`Y`e2J{Hf!7jRBZv7=j6%_*R)WoqIvRRe;E?`>+rDdK}p z^H#PAW#BxERWbvTLj%o9j!~e!Rjr{rNN}`{m+^8|mr9M*Jj^Eeg7a0pz99O5IuD40 zTU5i(O?(IE(-;fbR)NV}94(_|0!cVGD;v{1>}6mWnL>GLLWwxX@bt{zp{?uuRLevqaXv{b|Jf`TtURIG^5g;&=EV6I zlj*QpbwaJynIb%XCfbVg%p_FgOvEayy9B-2Cxa}ku?g_vyzH^Y3z;=ubelSBt6_~v z&NGo^oSVF?1zfbCCKIS8kNFVPYQp0b0cR!(kMjTkWdallr-ARP2chy&851hVc^Ldc zZS;Vu|0%MiRK;6l?4@!Oe8_n_ltzn=tMd-4rkuLqE*X(pFl7@WCY}+|2Y}qBlj>Ed z$_Mr)Fp~35G{?tR2vlFTL$ARCsGh-O!9;~}eg$#6IywaW)-6pGqGBRVIbXvHKjXMs z=yEN@^P5mt&Rv$}8C?@@%=ujupgZ+>HT@+_7s%#uVJTz)OpvpY2EYVP3m*UzxoyM&Fj49L z{}=!hJ#VA|5CmZ2@j2fBZJcym&3e|zLNvoBvY+#mJgt1f|I|bcWcmPxYclj$M^r>( zaw*@$B=qNrET8G-63)&n=qfFh#Ds5=-(h}m=LGVcYtbZURF)fJ<@*Rbxhz@=UeE1 zB>EsLuOiD;Es;j>o^-)FAypP`NzD~`n-QU>;|@ae1PIMW3qeZA36aiAHKKV8h0X`{ z#q3l-3%X6!Vp;R=1=p(j-$P@%PtE+Pn(j=A-lb-2Q*rw(jfreXE z98uGebW)wYLY;L?O@2bDOI6u1;=8B*Sk;_>KA>4mJBB`?qw64~u(}W%hU%Sa zpkKg(F?sxOBNWiYFLq7>q+-8U70;>(m#V2fF6$#)nTdYvd=z5LH0Y_ddQ%E9@s*uF zk5Gv47$(-VbH{1K?pLc?$gHR~nc{i@Q*5tW&mb5*=re7;Q2 zT!9Qmsy!2PeRSj^h|0ur4?|RhFii;gLY7%z$V9PsPJvu6jjjiGuuLr(Qm5rq(>3ax zoNBla8f$@iL02Z`zVl9?vxQ(x*BZuD(B164x^EvRcmcWtr!0(;yuZaf4@Y;xB3)%N zT?4S1iM0s@X!HYu5T~&U;ldMz!QiOW>kR<$;7k^Ii&!yafN`QY47sOiVl zY27Mv7cuVh9#KtD#Jog2lbW$s%^HH%M-d!Gx(yB@X5G*<01LXY;U- zWHu*(1XZ#!*5vLq@C`kHPH^94M;44ye6%lYdR(oL_2Sgxi)+XG$Yej>f| zh#mQ)1j-_WC*^)48hP6r;E zfK{FI)9*V?j?qLmDeT)O>p!C~7&WT3+#yd-nWqS-1P*3Bjr+utE=MAn%mHrB6Zu65 zfiy?MIgbGwOad{!PffW-&HKEXd!L$l;y79OCoLoXl78&T`!NYvZM#dfh37M;(}nPS z<{-Sn>6GdI9kx8spYtT3Y$G_Qwrf-s7!a-9V=>K~|L1%OATteO+AQcmj;Z;Yuayp) zqXol_MFQ~VxWaINHwPc)trP*eFJU(dxAHa;Go4Bhi0K!4OtV0?IWMvhvIUIHxsxNp znK{HVTq2f2%z>Kl7_lK#Kj`6c>7qHTvylCl_sxN!h3^ZxFb9u1@5X%0ep$`ejt|0> zn1fH9p8#W2I1@nPRAj|WKfyh8xgM%;f-8cxIo{P-0d3Q9wMfIaG|`+H>mU*lxVQB_ zWi3>;(AAzIU2Vk|Rn^(B^)}3uMJ9l4PS$m9Br^8}@Q>FLyLZ|ORR?+L2r)`E0N_j1 zX~U}OKDFqus?Vtz>%f43&f4X~?2(m`iLThQ%b>TQ+s`nU7{Oxr!DuC}III?ryF@Z8 zp~SgAPz&!<(~qbsfYl{x&agWBK6U0OrI5cv**R)5T^?X&y-eGiWKo&Ji`m>*?o0y7 zHVaCdR+seaSqhj<1qe2nrvV@kI5)>SJAVR*%moH-G8kNd#2hLe3M4Yc=6vdKwT(GA z+j$#o26Lj{2aKIt6`4S4KWU#ifjgWune)DjB26U4nKQ~m>OGCcJah87^B}-~>Ty-6 z;a2)>&R=(K#nbuGd(iByv!vNFaOUjyLIg2`nM`x?{D}ILC0FQK`#)7E34T41(RDw9 zNvV8URp-!sbq2Kkd4oV(ap}+bJ+hr1y^`&|k%mg)9b_0^XYzy&W1o3iIE*sR-!mBy zK$Eryp10iZ3-{YsI$bGp@`MRuE~#T5B< z^HQKlsqly9=?#FDB_L^=^ViU{A>E*-sgEzidq)OP-agYj4MW3%VTVkXfa+4jnH$X0 zky&h^?B6mO{Z{JVd3q9ve;z0kgkYo75~%yG$q@>5zc5cng1Xo4*X{ob;HnBU z)`%Hn-yRu`o6Yl(21Iyyf8ONy0GimqO{_eu%C1qXhX^QX)Ucvvfmd}UGr~%B2gVq< zjV8kg1D7$+-+`8sQ(486;&8W|DO=<#;taA!se9mK3M4Dd{j_;)yv>zys5z*cJK{KW zm>houY?HEV21em9+os@z!EP7POF`NksHW($Taj;)y+=*D(&$a&uf1^Fu3TelXCj;K zif40~bbn8LIGx(x(S_v3u6>D2JeNtNbJ>or_V$+UbbqpaR}&&j$6vcE*Ot!q4`lih zy~+IBRQ_$Zl}Yst45#ARq3-VV0e-kTo$bk_61h|+MY%6TWvddsy#rl|+<;r-t^`%u zrqfgHJ9n+1n&Y{BnSuTB&O|bv$Yc@+RBEH>{ zg`pb`t-e_vVf1qYNsBKizvH5K=TLVX&m^fAJaXndrJap6<`4GC8-*4zCGGG&|Ye-aa^p&=~QHhH_|Whprlp8R$*M0paPa zhNEK21!g zME?*0%bGQXlbG%g_8BR9p5mE(0Ac?c)D2ARYQJa~!7i_>Vj*!QBQF}N3*tQJnW3&6 zL%N;=fQSnbabTHL&p_s&0XGdljm_w1a-c7sObw^IQWzwZ_u30ryPa)pCRF1>AYchg zj`Qrw72D#~XsIBr_CBktGu4ys*L@Ex7|bX7v@Zq7M*j9bU@;lMrp9DC3%rs`#qk5E zyK^X)9_R-`+tk$IZ#9}0SZ5tO(%!1jND%9yeRq7Ofa&kjjh?<}!`V zdABXu{fR+F$t6yi5EH`50i>(}0z+#6qWIBWl^7f(tV(pn1KUiz7Xt;NVhs!m!l_H9 zdNF|L0&=zh{ee=%nOG$nJGOVOXy36dy(8VeyD`3dMI0DzS92WHY&ey{!gG<93m;*N zp+t;ka9XioWjfBZZhv2@FPjPw3q8CmF#y?A`&e+YEr~_h-o9%UQI+0-{e<8KhWeAE zV*u&&=;&{0o#a|tmp6U`gINqCVP$}OHX9#K^qS@AqA)_ShIXGXD{xn?rMqt+X}F0d z1j`-j_hvrHGm9B*Y;SLDHqRt+tRV46Y@tu1hNxC$Y#?${Xl#zT!J@Tz{Xe^Kv8)s19e^qz7@Ull4-`;Y3i6Y z_plW4dxjO!eBPQhem;-MrRK6Ivtb{ZQ7quTI92mryK*ZbKlJYtJSx8dJ)1O{9R<6l zv5+)!ZH_~*0R0|FuI(M@@2MN=r=dtC>o7A*>sB?jEUjx?TDM|pT`n_}l5c?H1@Uwi zc&RJVYi04(2_g!1B_(q&oS>%i>#eIo>7~q6fas8Bvy@_!t z7BGMnHj-!)-*!=GDSaIQqq&%vn91{*Puhi18W>FU zpi^-$48$Gqytj0v(!By0{IlEYOZOMfu5PZ-Adn$_-b0Ys|+%!^3OVjF>)vH>YR#OV)Yg*O3YIRfFs+JX$ zg;HBqG&Qw0uV`IKMK-qaS7TF4b92+mX2^q0n0*ilj7^)M18*S)h2qA>)D_^2bMYJ` zMR3)9wD@@}#|6? zhX9nx=Hh@zAkbtI0%vxhTO`OlX^iBTM7ArJ?n_zwyRx|f2s2~#v8xxd*ehd(+uPGS zcN2=m5@^D)RZQlXtpLMEY%rlBLM{D6y}f1*eewi@s}Cqb$W6LE-3~S+WL=n*Su`S9 z1>6?oB}$rfp;bhsc%cp^Aauv~r*r!t`s5PnUeYoM>1Syc5bTLjG-NBf2fKQSR&^f~ z-H$&-bJM;&04A2|3@Xy>M@ur1OX$HMRgb{E%t~AQ{1jxGfrAiL((S{Tk;eE=5OFYF zAZ{0k=7**TYl}1oo=iuC$=BLKZ4Zd(u6T056PzIoHPMWderZ&c=vF2wF@^`?iQ*6< z`m*uPRQEt8W#!3;#5M_TqaJEzwFDw!xQp-$NOw*pPd@a;YgISNI?|AkwDW zSG)3aM|vxiW9`E`cE`^jya*$2<@)0L28J{;Yh0~aj6CU+W#S}31u1`^S`dh8i*HOO z21)1kNIxb?qO`q|F*i^)vtm9x4nWP*9$>u(n6eJA z#U%hkdwX9;J2-_9HA)Mqz_?Rj%6bQS8nyaTe$zsP;17N56+;8v-8-NK^OvCo7KYMH zsuSeEfbXu{>i$$B(|HguBWUpoHWO;EcAOR6il26!1|0 zKz|ynXh(8;ADD?(3b=!)?F6SyJzNE)Z#LJvI&~n`#VVtw;l{=`@Y~RBr~1L^g5dS0 zyAC!YBQetZSx4O4o9ab(LF}QXW@=Bec_;uiwgSV7%8EpA(Obz{@+r~jRWd$|fJXG{ z1fYsQM)*^(Aa`P96ozaxFT_mi<`qk5eR^$@TcKiOi-W8G0_Ov1hsY2sQRoNMELxq% z0I{+=lR7Y%!U6-V#Ru_tFy47Eo`ve0mJil^xV-~vg@C8pRYU4ltrKL`7}`1-1U0TmiVTS*4SB6kn_xiJUX$n@ zO0ju^4K)H{1jggEp*5~zHXGa%gv$ZqwA)dTE=0Wh#UPb_)l$@@G)Zn3a!D%OJy4u*$>F3%fyawbTZYQ80v*( z(6wVxDhX7(2R;2PEe9SiOS8>+>gfOj$1|dJV|iS*(cibF2Ot<=%vw57tI#htH2cs` zb22^Len8_-uM;eeY8J=kG**LmOAxvx!#Tu_{fUfW(&BxogxHXLE8*|Rb0+n?zfw4w zW>`oW5`kG-JbwbR&x`zlbXQU3A51Sb4^BqqMl_Re0KZs{0;|hs#Dk{-@UE!D!CAXg zDsBY@%^n%NNlT%zegVxOJ>H7;_AX-Dh(~QBF)ac1Zp_sOn@@0MLkuLIWo3Yq?f_nH zT$xOFcLN?#v?#$~LnJezp=pa2i~eW?&0e7{aA{q0lh*h`&xbqceLXE7)WEp+bbL$e zkj2yR;qgj5cJ+I>Z=;XV?ui6k2r_Irg3JW%a(`E;B8^tx15=4J1bjI5XE0`r0f33j z6!<#*35JW<2X2=>CmnmmBuUp+A!V)kChXEWxq3klnIjp z^GI&v3A@T8M%F$8sL`}Xu}5X`^SDdWI_*gEJP`X<$h3F0`-?5CRJ#wwHx2Yb6T!nu z1&x;%UZ+{P<1}oFe=tA*X^trm?)G{NNCcyVq{I2Uwm}! z@{Jf=cc~fA8}vOrGDT@E$WI0lF{+M*DNEC*4fcvY&4-3VRQg@*UG1#f$bt{ z3&ae3gwzs_U;&Y2_9n)5mzFH(7Yzd;PgpErJ|+(=hZ%gD|_saW0;SH+CeG1dgjy{cH+JcX#Z`X29qo8;n4mX);E- zu6C3KoX>FkN*2W1cffYg-oo}j43+%%+bXow#ADODKXEV{XD3n`&>|LPYnR}6%{k_J z5`BFM^p8#5Ksqu%0a1V+x zLBHmwq;<-yG1Wdgre)(PX_51s3V4t;k4;+9t^*05kD}lSmzgclO`YYX<^hla_p1x;0Zyu5|dR zWuO4U*K0&8wfgt>iPr$DGs$THL&m;TB}!1j-3v=aJ{Wm$^7mz-Sd{lcVZac|#)e_& z{)=(;#DWWTdK`HniU$?+ivZAs5kZW*4>8B&TSc=Zx`A=>vtfoCgMN$+nn+Kfu#s$U z@jIP|TPa`_Zf^DSK>ctUfc;C5glj*>N+Q;X)m@BieeQ(d0mvdnZZ72MVj3r`E!_i- zQkibHmgt|O0wmZnjrlz594P?Bj{{m`Qe3)>K)wbr;4X&ABAY(YvhWSY)g5V!V)B&O zBe=#;f1vNq^Cu@01aynw89+>+Z0`f2;e4+Qmzb7pDwV{VV}62NDzwZOwta-un^0&$ z6Q5$;f*+k1EF=SQo>obV%PnS8j4(0A;V@7k&BxL@nU$hACU)W@NNNK6nNJXel8lMa zLp5PLh=MRq-$;5crXTQ;wv6aW@R3g^N0yibkHTmydt$JCMsOd=uWQNCQBXh_hv6Uc zFwB@P81D9V&)X6zx;9>RMR1@YrYqv_1WD~XI5?0?lHzq^riTqGD7kf*u92fS?kZ?^0*mKiRTi11)b#n7_Jp^PZ#VZ?FZp=&sH9wbaL`+ZUR>?$gB%SdTm-9llLf1 z)gUB}XkHvFves6Kr*n$Ecl_LLp-guVW`bB*H z8}^)nWu@(%<5gRQGP$f5GBTmZbcbv^@PLO^HTeu(D|jFHyz@?0{{(B;hMOI;(w=um z{W`C*!VRw4H<77JM|{ScNh zyR_$uU`y`=X0U1=9N6EHgnrkL*C1VI2KokI3u}Vz4Ez&$OCp0#?ErOQl^dxFp>hLO zCi4^}x1(*MXlsXD!)mq*p=9d-WYQbh`+{E~ncUncL!dZBL2hWbUp`@5ao7&Y-En`H z(5!&W-hpPJXYB;_*sTLc6YW>vVgc|(#g23c*Tp;+t-gFhtS8k=B~i$8KQUa3&Sp#~ zaAUx2t*yLL**t9mesohE~qNDr=e!uu>kp8QfUYZ_Y!TR>Vo zkPjlC@V;ctzHbo~(07-YVD1}G2an$-a?ge;8~7nPT)Mp`b;_L}-K@!b#(vNohY0^6LNO}Gg#oMLX2CZSRR9m@7zpNihraFh%2f+izzI6CD`wMr)!>qx)*h0K%fKQ-1 zK9A&ufuWq$y&t;>soj{je0Ie6LxIr)Q^F4FRvdoFaLs`UYp6txtQqpqRZNT&fYWm= z8r7^@=qLocAK1&WG)|fcBb}3Pr`F%TNg4&RYE?r)(U>S~J65i55R9d)*#LWO0tyte z*Ki-t$%-e|iS_ZA-T=J@CMDXyQZ*)H)Qy`Zuo5Ju38iFp^?oNYDAysHQkk)TO z{flTgY=?0zrTP1&e4ID4wyrR><`UhL8qsQ_DDXkF4aba((zNz9(IXcDqxx@)+T`4P8S z0L(sYZ&}^k>U!#WP)!i1%|8Ccunm*JZ6-^x_WI>&N7yB^3UXvJHB1$AJQ;e|BSFD{ zHEG}O68N8LZn)Udft)}z2HV9c$_}|P!AToy8Dt9n``Rfv&lE4S5I|_)fmF}N-3|>$;EtN;> zqhMKns2VXA1;bM@B3y=?MU0b(CuJg9i)#?^R~*JRmDno@0ag-$b15ZDdZodtD=lK% zecssqeY;rd0wIhBuZeO^Td)HD;T8qz2@QJ# z%<7uY@msq_dz_G#npQ%YAo1h;z=0SMz#&1dslC0EHs+4PakuOEJwB`%kUE;l+mm-b zLar-qzJZ$rTEGJjvs@26ffz-`A)JvY;f`^7*fZk{Y&(kklWR-#bdG-N(;^aJdfXBq z6D(2q0|8(PDI|yMhQEqJXyAh#2jX4>knkMrf=w_R(_KDCXCM`*OIXBx32;Dszl5F= z1H>*w>9Lp#w4_I(DDmdrNY^a@V;v1JLuU7}5ahNr80_};i%K*PfI}a)uJQ+aArjLy z7>Mws*M>&iOY25gI|C+MC4pZpXY_hNw*k89Z2<>B6-z{oxTkTO4nj#46W|wC<`3t{ zc9{S=D^OV(X8N0&SG$n}hr^&+e+gmKQAawvC}|DvA0!t@ z!fNDmIYP&cpLap?LNxQ_&W7c_%S6V3S_aIIwydy!kL%Yd_XMC^OGNYSx5{xj0|2RYn*Ro#~bz1^&8pcnOav=WWxfmq!@zs`Ry}a_5z6a)5+gf&ZNq}Jl$hD|o0^Gi8Kes$ESa0Qq z!2)+#K5svFbV8i|MgtLPw*d;>Cf7PF+lZiGfG%jL9}#_%O}e9FkVmZS^ZP*p`r|!d z$p;a+Tiz>{Q)d7XjW1&>gaS4FLt|H{uD4UTyOyu_11Sw+h7>oL&d%hVRD>t(h zPIAz$gZ8n@$cG!oB592@g21D5Ala#Ri}0oF{XjNNUqn!2#^VFt7za+MX@;4)d^|q ziHw**`I<)gJr+u+qcH@|fFa>*K(%?|LZQ-^?7(>eB^NEmQe~eSSis^}45hKjkYkbZ z(k-_0ARw~Wk4^1afCQX!+)Y-2K`2rj0}vIeQ^|Qihm(6ng%&WZI4dkjRdjKOyOSE) zTjK7(%VZIQM6ak&Ll3~-XXw!}_yUF=EN1M{rA#{iNprkDACWt z6P4$iz5tzWN?pPF2ejD?&Dm$e$OP{>-nHeWuJe9E{y{h}>>WngM99Iv(%B!x-;KGC zB1Fg}q8}dF3v|MS(ia~pj3OBrph)$3hFi2b$$~Q%O`^NeGoV2qC8EFxt|wz@(0Q8j zy=;u$)i>S&tx3{^c}3|3A~17zi7|&TOeFF49r5NJ*HjNnABhAKrC)26HHeLhQnBpa z_%vd?ga*+IF~C0qn#jMSb*itA7;T>xN!v4h0+44NKq8q25Hu!{A&iK2XA^K(W4$y0 zbw9^9-mGavhuf?6Bmixi>Oea3AkZ1)*wuR7l9e(QX?Q#6rfu zST>V%$2jhWA~NnYu}F$7LzD{QpX=vYLm>hRv0bpDi%X|bcao1mxbGEAUsf7!n!znS z0rcRyb)X=i2U)vp+1U~1V>-6a`AXw+&VxP@H^I6TeW1?D!GmCQTz8`p=+G-FTzeAE z$RqH8eVcZ!uI|BNbl=DDUJev?@U#3RYZHLfmpoQ-YLo2l^a=@2_Sy9L8N zn6Lx61mc-yWal4q{v}LMV@R+pqxcxk=BYly*P(ar8Zm%{k}Z$}@t72GBZNdj37YS4 z1g|Ml`-BFIHM@t4AvLZVgN#-2S4ntDkKrt3ag3LENR%OB(=~raOnD#Yd65#dlH~DB-J$=S51b7>_lvWsk3o{Z96abiThNg*j zN*Jq$w?T(CFNS*S_~TEE=#$`6ag+iL=6Eu!N+!a=jR!7{`CG9tEhBx*4zHwQaSbsW zeM4j+mUv4%_9bA9m3c01r3{%X2Xn+w(+-1xjcr9v5CkN!OMt8Z_6nfoUu@@nrx00E<*uLrlAx5?J1^?|p6w`8V_?Y`KFf&lDp zy)4BEknvdUu&j*%;8h1Y;FQwrlM=LDUEwDk*0z+W@h+abh+nJiQYWHY( zcOzWIPUZrFNU#HTY`y)8VzXU<8HN5M$0k}Tg*?7oJ|2Assm8V@CBWsywhLF6^`-{w$5joHEkQkY0SeNp_-|X0TBfN)d~;j2V67{jSIQ)($lG(kd>z0uWu zG|due1-@xGV+AWok4v#DmlrNcW8*q4I8WcqP8UH>%98Xz)b=svCxk#4zkC2gzTQ>G zF)yvia0XchoqUFZfro-qMw_*8J|4b#N_^ca-~_zmTf7Z6fu&?7TVT&TG|*1onQYqA zfevAAV9esHG{nP{Len-C1WaT=bOR!Yz5@hUnKooRUCq*Gauya;oR)6FBOKrm7riYRuGuX0&_BGX3qVkJ{uy<{L+ zq{Cvv($CYGV*d~v%o#X|$j`2aF>xi@{di|LvnmF>41CkBFW0M7@EyUEoJ=B1B0vZ9 z++x|tfgS`M@bo-jHp&(~a^68eR9^{WALfcdcAm5*qd}|E#7~@{^;J#-O1n zh|-QXi0jQejx4AxBKxXma}lm$oNLo3s*eeVnuTI8l>NsgjK6>H1TWHlLiB|CI$bw@ z`biGW6eK~yQRY$A0DQ6Whk**s881%qA(EoTE8t#b*w-Rz9(fsEm1i}V=_q!YyNZ*s zcn0|9YX^c0VZ7>q7XjZQl#>D0;kkX^m%KKNzhZ&V0(=8mMFTa@`zi@JFF>Gg z00Pi4r?YRsp*e_6;srA&3G$T@_0c^5DbHJEOq>uRI~L^>4q+SrN8h2@jpH4_KEr__ zolR;V-Nwdrb_g;*o$%$FX!G5qH#KUlT&wn#kts2Eyexe@NQktMgkEJVX@Qn{USoiX zR`r_gtEF&Fu64<1vN>V_4#VPjSH|8W9#RGHD98>zAU+{xEurE-E14Q24Fllv2JU8- zv1UC)ART4W!?(XsSY3oO>Oy>X{E!eIW7Qj``VuM8-AvOw!tq(O3%8k0u@|339GHdQ z&E&f19hrrjMoMva>#oEN<@1isqAZl^9h^leZTw}9&T7XVM%gsSaSbhmBf?pc-Z10L z1;M8V0ctD`=MwFBz)GHRvSXqlGAgl=G5@%Z6Lhs%x=GljOgoKmN|_sd%5YbNo(m1L zUHNg*O%ILC92UD6q2y4@@K|#%f~byO%(~rt#RsBdnYiHymYB+AWc8C0IA2|6#3Vkt znrUVSxrM>to|Th&fvFLSXRvoDOJ`Z&3}2e9Fg85&Fkmbw;l6#Gxhww$#zRNmE+pv2 zgdaM_IGxrkS#j$Q0Wh)L7JdhqGCdZq>lBtD1a@fUD3}Y*Kk4ok6$1PTAvO*DasWuc6<&(908)Qq?}!uZfH zkwxf)BjbPN1FV41W6lu=^Gsu{&13mI*7=NO<6S@m@h)u0BpsSWJjFmsSZb=gl(k*B z-x8Ys+`#2zI>VXeGV{g4tVyEN z_weVRB#Y@Mn&hLRe!8IXr2)Bc)*i5E7Y=*j^?Arg|pHK@~QQJah6Q?>Tjbq4HqodHo2L^|Ta_|!K@QF#k+ z^se}6b*LT1N73O#0xtmy^l3cSitI@kO)Ai6hcN+RID*3p^mURM(==loK;R2!7Y4Fq z;1W{@si&|g`;C4m7~xF@4nu;e4|R{^UA5~4=i&g-Jh_sMV;p)-Gf^ay=Eb8EvXsSal)xTYSvf{51UYZ5`-ww44-a6>7Z2tv^A%(sf}9YL%!o3 z79C^`izQ$BA;F5~nm1n2QYHIa$#odjxFIzfiRDF13OpM(Lnyl+nCHhx#0TSDS(4Yf zQrL@64Mx{O6{Xnj8T3|0H$4iar#a9pqZx$bYHnZ%OaqAe<^2Qu`{T?><<9`(>60}O z$_QEwnGOor*tvsF%KpLQOU6ZpF%_dzy}jO6q*Q; zJ@`bCfR#`Squ`Ig5Rd{memQZemp6f%-49lUy{-O!6GcRm0Gba_W6wr9_Y2Hp?@*tP zh8J}1Staq$B{UL@lvG#!VqBslY=u zL{04Zg6K%Z%~}3^Q8>==dDJ_|#4_6RON* zr&so=7#!$LcO4|tNT?25c^34%9aKdi&z0CyJ%Esn~?UM z<9(ohV-yPw9Tet|r-C#S;Nq}5xVOy&E9rQp*hD2{CYs6v*0_SU$3arV*?1(LhQrb5 zzBw8?OvE4pVKFz*IyQS}t?WLWt6b+EM}kGErEh(b7S-(oxv&)zM&EgP2I-Z%m1v9t zLxeQhK*DlI=`F$t#50Ee2aum@mw*>N2N(sa_f0}KCc*4=2F&S$qP@Myq_uG);7|+4 z;;=&cXjJgs-LMB?OFf(MVJ6}EM{`1Td7eLpIik#R)n(KUAJDs=)c#m1AuiOw{7se# z3nOI&>eh7LOXah2yq%QX*gV&WZ8+0_{9jNUd_YhGbxMATo_K`rAo3ID>9O%=cv%6&+ zi^Xy!h*S`8`cn{AT+Bd}a!sM-!Jq&cJ}OuOTHK9AGPCRR3zZi=O*54#$jFBqRX zjctL%FqAfofDnIZ0f~@Chrjm>W?*K?Q(nf#y zrb+Y}EVhw{+0Pk_uANTj8@9bAKyUhYteYW+ ze`tf!Li0))3BPon$Ag8i{iLdbofdko-u;P#**M!ZSZD!_MQb&+#V?|^x+CHxJq9lp z#@vZI#rQ#m=q1>kOT?K3=1{f;?7J_P6nnv-RJ=lXnjlUyJ;ly#A*LULd!@LD>{~2n zuNUY#8k_SZFvgNt0lYF0!ko{1S#K4D8`T(LgaBKv?~|6iDZ~UH3z*LKCm@^?`#~j) zF*l`odY~?hb9;Xe8|&jk8AK_TjjS*v@TB>w9SPRLBIoBxip0LkZhaYwq9>AeWtcN( z1jCkqO#%+_?7GGv>C;=3W^X5URzL>LGMu2%e`y?c6`@Cc-gG9_BLT8_|9AIbS1*~6 zyG@L&{6%7De8?i<$>Y5TqW+Z=8r@?ItgBK7x>AF=G&I$ElRWx6f&qu3_Y}=9v|Aji z$kMt)j^iSNYH1T)0*k8$-WzwljEdcAHjX70BBs$=)mna0CP=@>$NAx9%txUnS9=7| z5o12)FaTGpTy?F4EHz>GN)a|W3S?I*O?E0{IwYc=>KVwCc6Q<&iTk#>MN@b9n|>RAFxlR^N29A!9QoRV0EKrC>n zWa?Wq+9ky94@O!N6X%6h*8677ktE>a40~T1d#JrI36Xn;lSx+ti^UgJR&UoGO*-?% zKnF_H=L^bS8*?W-l(_@g5T8eZOI;>dl(`xmjFxzNc5H*9l9mgWVNi$3OB=iBO5-YO+J&k@eSNI+P z9Uj&V_Cc=TqlEi_%2-ZYrjhhfc>l~Gl1xuZoL`7R!H#t=p|lBb2Lkd*UT6m?E`*Mg z3nb7E>2{zh){PynpOkMgl>#oTbU^eta5NdPt9~U(ZT% zdJ$nLjc#zf>;OAy5-!DAz6tmMX#3`%Id+!DE}&BJDnny7QrJ`D3*vDUW>ptA%oIPj zG<@xeDtUClkcGbu)vb5+n`_tB$-bm8cTn0<#g2)7A*6u4FW7AjnC3{<%!(lPWCr04 zpg2RE79G7go`%z&clz`Qh{!lk6BpB}O(A0<&M<9TJA6EVM__1R?HGp@q58?!mS$%R zunj8`k-mcgY{C$52pTurcuK1j@G0KjbX+LdX3#;nV7m_GxX8&c)Z@i zo{PR6aN`}9fD%oQEbY0$vY-fUfN=Q@if}&s(h~h$DUR4y+|0R~k-?M^cE>ItHu#In z8{ML!W|S^f(l1m3=#6uLtOFEC*SJ%&u!4)M^X*G2{j zI!n~^4{qN=3Q zO)f;tVTi&V$YKP}WhX+{c3C6r_%4h{vb3(bX=xoCE%0M?E4~_+)_J?Xm)14@f6aXf zm|RzNW=VFq#$a1+FL(jD4aUZ@)lzR-Y%EKb+g2M{5|WIC0hg<*t6PP;y4$@;B8;uD zgeAuCnJ|z*AP|y341*_e1~3i~_Atg{7(>`X_>urK1O_shkFc8g&prP=@4Z{My1UBw z`_!MUy7kw6_q}(QbI*3q!T0R!_odyalAZj<&x81ReP7?k{`DIN(NOOu`9GZchP^@K zKo|J?ka1SR`RfW9kRp~yg5N3}PK)W09B*#2dKAQ9t{3xe?Ldzu%G!xK+y@aQwfKl^ ze9()QUZ>_+o_19BiJi-PalquSG^t(HNbsKq1uukR!@;-d$%?FY42jB1a);d1Ol_E+fA`>ndrYX60XMfIf_lbY>^1?2}sN9;NHPi(Q$Tx*daKhrslz=JQ8U<#2F z=1|r(um$7}KrPb^GB^BTgDV|s)Eescwd8oGc(5?wZ7?X|Pz+rxG2xge)m!-u^=@|9 zG7eSost76I*O4x<P(inNeX6mAwXg)l3SzI7`H znf3ySL9WB$B=%&O?O{&0Fa4BZJNJBiJG9dW$YI~Kw$)J%QuNNKD#m1dxH z_2%hGUgvGvSQsFEM|LpYyTM0uxXa>=+bIhm?w#8KU~(e+^< zNo?|`S!H(Gev}J`E+;FA^E`@ottwwLyi;g&8|y4cvt~yPPh;HU3=}wcRtXV&$h+Sr zsbJGljAkO(g6Ws%%_v-QZ%nYE%G%L|SlBr|G^o5@+ZMY{c1R6{kCm z8EkB#GCnJgZ5Y0OrB>rUyVr~)rV1gC+8Zb3B;=Yl7HjH!wW=NbBg(UQ1?kLubxxz; z%MEga5ov7bRH0`>rl2pVRT|4UOrC2nVvj?d*1#m8!}>zh3wfaCtlyaV3s6FM{W+$2 zn5|qp7)J|L3HbuNM`{%0B#3wYk+_tI?PuBKI@$S}1I7B65v~?nzQ4U0OBXejW|v5I?H2_l7!~M zCH8P{FI?mhj;bjMkGyL8cR_d{%mk$3eGU`iAba>c4kd%Dd2Ei?nR5lYCUvAbzerNU zl4R1%bf@V+<(2&b49}C0axE1l2xN|-qMK)bU{n1n%CoV7MQHYe!*YX;;!tJUyN;^! zq|CbZ$07(-Xiv?Z*@Vj3Z?TOB`X?a-5b{k%J~zi(X|@thxwqp!qf-qWMO&z=jDZ)A z2uxlVs+3RWS)dy17pwpY3g)Lfnn=sVwBg|Qq8DIp-&ty{rY1$_S%eD-r@Rzhl>=9H zb_Rq{R^1^@fQq+nW$I<>kW>yrFCcgYpQlCAIZFI<#|3dPu&LXJG8e6q9yO3TK)bs! zG?{=sJ3FnrsQ9TgnToKy#bgtd1h`$2DMI9?Tz2u%>lmd_v>ki)mn95gpk_-gGCv`- za&Bs-)_ICE2}-8ez8KUp68J;2eL|w~C*Xp0GoHP@efexIpvT_Y)XCyp9@m~fTZ2CE zN;|1GNL6ME*E6ra&3K@>$j>izLWN`!C99Q@dHn~o?T`WK`V35@djBT!SUS>lH; zw!Kgmo+gyXN+JFMn>DLZUiXqX;m~5!0$nJQX8&M#GmNk2J$n1{#4AO&yp~uEgSmy@ zVoyRWy2x!bi)qrq8qH45digEIkQLTsxw3#0*y3O)-IsgZ6rD*GCw59e<%wfE%o(1>XdVi1!I}I4f5W+wwtP1T*?TU#<3!5T(F`DZGc|z9ixVC+$ z1sjhy!bvPiq@ELDLRdDR=h#nqQOH!beF)vSSCu*! zh9l>Sq$7a-#Op(aSxOQkf3_-PY&CpL=2DbfG|^*^7FiP?J~?Abf~R3Oazn`QbwEAx zjIJiO-XHYU}m=5@T6Nz37TUIKYq^*qFL-08;EkkgrkG0@$hMZLv-Y zXEvHhIrcb>mPV-okI@lfhe$pJqqS*0O#jX;Ru@koI)P(LCH7H8OmV{jf$`D}V?HPY zrOtKIcctMm4{KYtarlw3zhP! zh)yO}j+4i3J~h+uA$2?GeABTt8X8+TBkt^H^P7k3Sf*fa#*UX!vOs~;VO9%J0R8F6;T4?`>KayFt~*`1ptsU5vTU)L<& zPrEyW*E|fU6-mUjCf7zBSrVa15DNfG)lE~WMG0o{^sP{S51bw?b>r-Gvk_>}q6VZ6K zGR0?tgm9)(pPL=_Vg%eBMXw3j+IvTff=d3OUke08UsX;NDMeP;ha?8st{tgx}A%2GhEy!+@6LOZe za3neSy5vCzo8UA1$^mUyDJzW{LIh3VAgMQ=+-@wXyap!pa_O+K(v60)x_M`p;CYXp zk3tOwAuR;G5y7c0o>n3-^30C+jM?iWA0^H%J=+Hoi8?(JBq0Cry=syI7qcaIh+PxC z?DsQFSoFy`wQ#`;5z)y++6nxU1~j2wwF*)klL>21;-@Udm zH$Pds!t(|7D!x|0C|z-Q(}uMh2D;adcds3*%pRFk)_s0b~%Y*Y4bX)wZ2jE%PJg;d1$= z-u^-?Sy3fp)0ZhEKBJ;#NbFp)J1_SW-xm6G-lRBP5# zi$}fOqFwGE`{6b@5>-A}NB%ajs(Y%tMFr>`{GtgNEv1d3JBI%c))VrIL+>Jy1pGr} zn`}YjYb+$UUhYbGY?@0KN?79(9GtFD?Y@lJD&r%UVv!2-WJ$Y~7Y=em8{5~p-?fTo zS1)<}o?p(;gw0INPmWR(=F3#JxBG77j%AewGn0}NANd^b=ap|w1i#(6FKxmjNVyb= z(!TUY-dUI(J;;}HRPnd!WCCZ#49rC#WCgnFxg+>pK&|QB6|iXgq4U)dky3}_VQP;& zCzWJTEmy0A=+?ABIp!;MNkZ21CIShs#T6E<#liv7NgO#JIf5zi_>CTvz8$X7u%Ael zRF$MV(2A<^D%j?NU`E*jT@_NWa(~I?f5Qo^nlKVaf<+F8MMNF1-5R&FoHSMC5ONS6 zO#TqXX7xBI(L=V_av&a}dJG&T&O?DA#eZVh)9S4~F!SQM*Gpzn}86*5Kfa8Hq8-Zd7HBp9R?DQ1;Yfw&Kib_}X~M!d=YxhVM@DWw zQRrm~roR#?&SZ=rVTdruUAeWX&1;Hf3AI0=!wxtpgu&lF=clD{Hnx=J7RpetR5528 zx6MzL#&Apk5zEA=P?uN<(b|$Tq?K?qwB61%f-j^6!YjitEHjvvYT8XC_v-nC65f;{ zUW}p)PD^K?^p`ffCkA2daa7DN^DKFXYJapY`Nu@VgzW?#ui}Ev7xo7pJsobL=?x2R z*F1%XRw`ko>E%P}5r8aY|D*?HOC4?0fh*f*b4`$J;2iMW!KwLKIN(5&UDH$G z;!a>u>eC#DSXzU;iLGn7s#OT|v$Y9mU?jN@Y(q#7fNUyC*38@r^^4xLUE+|1B;+Q% zLF0`md(JNy`SM789LoHu`Ed=pJFm=b`~Bz*&bb{Nr)y!goWi)k=e^i*WGCUM1lQM^ z*UnLUGkl#l^e@HvH|0rgw|5f3RYk^+#Ou8NHSmwoDha1ST7_m8GforRwbbj?_vKh$ zFu$;yU@GW>#7Iv2T`hO!Vh`BFd+NpCZJVs(&NFU8E#=J?sD{otNY7C zh*uk!opyVh;lBL-DXhSB@i6eB{Vp9VDbU6$NS#%#Oi#;JDrfIHTNX0qyjR8^*)p?` zjux`C-FLIdX_ARlHh#}1MYE(&V#M|VN!4`^QOzP)YER1ARG`bF1Pd%W&H!z+4{d0F}V&*bwRNdWW_S58L zC-sM+36}8kV&3u|p{63vNx|Gaj3ZLYl2}UBkjA)hR!@5{T9lZhHd$n{f?za9RkNca z%@^Z2dC&yS!zn@16II3_>WEzc_DnIS2g7u@n(yH`67RyWOq+Kwc}q8fCxXZ}D`75! zhhs4-xaT`NqrIt9hETal&=g_9B%p`fo!y^Y-_6^0HneI$8Js|HqB+?n^S!2oN913# z85ArDE!#VSTaum3I+gou1{!LrpOhH<%lza7{5eCZ3>P<5vaFkh+rO}B!3$lq~URlN`Ij0Mt zklq@Y5OT>IPq!^?d_|9-3VTA4~fRVhPGRyRJT2otPi3#rWgZ?z%ZJw318@ z`H*_5)6=DO^RqMd5YXY+_*N#uluUn$k zb)&VB`SB&%XnG{AKT#i9H(sr-Yq}@if<3#8hS$kJC*OG8^z7UO4iCvRfXZN0Qit^% zgoSqkR+;fBq38ITGs@$e_{pnMlr>e=C-oYYxr2q2=d2O*iTny1eQl;*jehhAIQ_YC zd4#-?v}djgEhy;URKpkX1nSTwo{Xq#at(AIl2f*%dH@Y9gx_W1;DgU8jmZm!htm7{ zEwMYklTs3vA=6nw|L@@`JFJpe)8I#o_cGlWZ+7r1JyK8^~04#=fYj$%+t)kD&$ z{;O<*;vikYVIs5=GC}HZQ-sD2jpFKpkg2!zPcIGg*gBpBbxV-w;E_d-dsXBy^d}ym z3{4#_kt6zZ+9bZo*x>^|V=ia`4~l|!-Y(Cfq!B#yH$3%P{6Fcx`4|Qv+a8c-kIZBF z$UhK zH_lR*JHpZy_d%Ax zR{95)E_Y}3Yb(!mTUcti_px-Idyu71;;{y_;u?29OXs<-Tj}R4{pAYxzCo?H!~H*& zcDk(_6x-w8z*3+41WP;Ii5vCTwQdtj7q}O)^vxA+(2qfKW1sreVL_(yXtbiVvoCPXvh?Yd?&>SF;(J%P|HI-b?olh9yhVRr<2JE`XJu)#dlgHA?g5tmYK5D=QZMOp zFJr04-OJMX?n^BFVugEXYpD2bmU`UD+Z6lP74GLO9&{sDDR`cH8B4#r!kw^P!FQ~5 z&$?QR=ez4z>T)k+sn6ZT(q{Kr`}ONAy=R4c*^pk`=k8=_29@?wLF*mSJOMPyPr7m}vr7PTjV+of`-w-bO z3QOm^pR&~L&U&8y`V4nDOT+FJEUj_>g{8WC%8gpD#|^PG=w8CoY3?qTFaRu_>^@`l ze#sJ6#=Qr$nTy@mSbEJ0H}ZT1-@eivy-ABZ-GeN>YNdPR1qxo^e#+8m?ny6HY@NG| zrBmFnVTW0|d!>8ri?rhT?jDu~-M3kK7!P!_{@mq0!BX8_T2^e0dmc+0+?_1l#t+&?gU}@0ZZl(KJ+U9=3(vMcS?^H_uZ@YWeh?X|En_22|(=659*I7El{g|ae zcVShpxXw+pga*r_p}}{tw9$Qyr44RXO@FOBxIp;7)7Yh5T^)7T*v2>ApF-vRQ@3VBJdxWJf_g$9OyE6~!wO#I6EWLS! z`xuKSyDzYGvHJ;2TiifhFWKxSS-Qa8&C+UjFH5JnPqH-Ve#%m>Tl3=ZsC!tt$Q@#7 zgL^+qJ?$N%sxIe#p|e+dmg>H^$Pq`+{Nr$WpIcHLvx~bQiL; z+s(7oaK&)vyV zulpO8s;>KRXn7k;y>5o3?e4Exs=Bj|XuV!H%+dh`6929Mc6{mIejWexL;x%B%bmyR zFWszg8a`9?R|8*JT2+b(PLOD&I2v z-+j5Obk0#hGyEyIQ0kw1)Wg=!MvtFcdT#Vy*8rF2|KU2V|2+LDEfC+nUV*cTx9b15 z`1VgP-FFWw<~~yI`)8l=&5A8%_>|K+T2 zatiDJ331y{h<}l|QF-F~j@RcjmXP=z#BI|cejjn$&WL}LxCuAJ|2J`C=ZT;6Tj_qd z5V-W4QAXCECvHLt@joGMY%X#41Z~HNJnW5kWB68|P~6Q_v(jJOFb#GmH$ zzQ!FA-$UG3HsW^>x7~sG{lsktCjNvIO6Z+)N@qPxfFCCTmwq#OhjLwpqou{@7$kHjx0Zh|H87ZEp^g7~KfOQmkSZz+1;H?h8n zudM$taocH#|AM#)Q^ePvsLyG_Bk|t`eyXh0qY7Xe`@h!$Pp#h%u$>^*4v{`QB35*YDkovi&} z0uu3^#N&B;2XRx^u>PIIP5D9m4}f=Jo`2_A3Y>s-D}QfieN&q#TzZgrOeeoa+=N)x zf0VfKRm9hvqVHwwEb&?3ss8^X);HA->;Db$k4E$AE5u`ZdpuYcS=S~`vz_h0PhELV z>4a#V?qPkCm{|V^ag(lyzn8da42b_NabxL;|BCqS(eqz&sy?SFJy`!{;wH8c{|Ir@ z9uj|qxG55d{~K`=!-#jG^QC{zy+whw#BU~UdK==e1CIZi{=UNcChW7u3NTXAzUh{T z4-gMhyCeO1H*wQ`vHm|1H^m+C<4@Q2O`l5qX~56N_^x_b0g!$Fx0&@#$w+)Z@zs3_ z1bX!{;wJ2~{$CJ}*VhM$o29F}ymGw=-%pZP__?veqfZO@Mzb0GygCaG7tW$Y%Z1!PpCKVlwfoiJN+e_)Wx36H5Fw#7*`i zejo9e5BUP{RR0T$AkSka0k(5CaZ`&C|3l!ZcJ66`uQ)ede-&`KZ%jWgCT?0L-uD1; z(_s*Q1##0Z6aUlD&OrsSU_O`AacpNX3Zi1>*hAkx0+g^5>)oBo~nJBXX1 zgZS5on*o9NFNm8Kg!uK{>HZu8?%#K}Rvc#i-zRRS9paxOZdM}VtIpSUOfOFSe&S}i zBK|GnriCMZHkdJa9j%@xd8CJLC2p!t)<6CNy{}ooh>rkIz1JM;o64K@e?Z(6vcxaK^QGE( zHgM@rQ+>1k4a8%tWb>BgBl-$=$U9A6n;_>`>CvnrAvi^^V zn}(El*G1aC*)54*4m|Zd`&;1eW;^%Yq77_gJO4=BRMEuG0Dmm+WqLp23&c(5O#I0g zYkku(6TghO*)fRU2t4)t_p!cNn^^w^YqWi{=@S15@KigeUZVBQzQy`g;9V;rBy|(u zN1gR!Ibwl$yidKJxS3Sh&IgE_?Th%&iO2Km(o6L@&2-25ZvZa*d8{{h8|%k%!2`t2 zBFA>V3Ov<6=YY|b@ikRC>+d3NdVJz9CT>PH;_o4DW((rqAZ{9I;=d$rmT%%cJ^DOm zlp+3n;-;)8{t$69$q;{(xEbt-uV0t$hnEAFelSBB>;ENj)2$Q#7ID+f6F+yowqsU) z;tvv!>EW7Qtv_;=R>XGZ|27gg`wj885Rdnl2Y{anJ@!`e`Kw5uzr^}x%V9hJPTUME z#Lw%~=P}C=@oR~jxtaKjiN|vKUBt~6!ur1?Zst?soBQ>?=7T}}4&r8-A^tJovQHfa z9g@GAew04X`mr4J&&18T!TOsA^uFdiK>Sz4&7?{EBD>Z zUr*dT9*BPexabLEz1ja@eKSmPd@tFc&tt}aw)5M-Ah@0h*_?^VfBuo4w#ACjzwn^`622|Gn z0CBUL6F+ma);EU>;$y_kj!gWWz*GHmKkLW*_P2<~^7~US)BDE!-XQUtu|DK4&;i+3 zWWH^Q@JZk@zVW{B64p0Y1Z}SLTHK~iEja(dfyS&H}gO1zmvEbSc!j> zxY^)||BSdf&Jcgvv-NpmOX4hXvq`f4r-++1lK44SXgg*nCH_L<=Fmj^9mLK5gX`;O z#Lbn2_`WULzPT~6o&QYSoZX1Oowzxb5Wk)%V!N zH^O$_54@Y@{Kwz5X#d-6CpewWu%DlH4c}|4wgPs}|7`)D8m}8!-`uTO|CPia+Nwaf zR@O-W00&s5gG0eEU2-U_^%b@CstWIM4Q=3T_i z)rl89Oxzq2iT{+id2tcH@OpjzSRYs;Za$N&{|Cg)5tI0X#LY*TczKt$Z|<7J-v~U_ z58q?`*bm`JyS1HopIS#e*5~XcZk}ws?-cOVeM|e0PPw;76316Y>T=o#0cGZ9=aA;L zr;0NQGqrIXpTH>!96*QL|0E8Ll*^-2*dPKOyvj;AkNJo3+W7E#Fj_r8;v94xu1RW$I=T`<1;)sioroN5?pi4)oEMK#C+x0`` zp*|)x9`G z=nuC=$2P-BS3At<13+d+_2l4Pe~ZxY!;PJd{=T7|4J2vDzx|sx%D=t%r*Ck>#(_=! z8+r%vrB@J(v@eL%>)X)3VRPT64Fl_?il77Q`}#KauirQ*P4;f`|Md0^^!N7-_9L#Q zL_o-$h+Ou||#FJ1(3G46#R| z2%!>oWbdd(2$h&k6U{9|T^|m^b7&SjpdAMwmV=V0Z)cg15vMjjHFIRivyZ9B&O-=R zKi4~Gjp+fZVMOe}Ve2>~6e5Z;P+~4**&t5&OpVHP(3v0ujuY8(rm{Co(>CH9AbzfN z`C=V{GnxKew;vjb_8dlev5P_-f0A9k=nx$^Q10&;KuhQaL`P`IJNxrh9rmUVQm=C+ z8u2jWY#ws4>3M5O05l3hTtS>D1lFsz9+pAL^r8W!G%h~E!peV3r3gZ>1PNBq*?Tpm z(!}l1U4>I~8hfbH=?#$bXnolq#Kj!ji(x|8ZlUEmFmjHb10!JvQBNX8%hBLyX{IwZ zAV_fj0HLIm%7|hz+yRz!b2ML#{^6g9;VPGrH8(dalVKhbQAIU|1701$85aDM$S;WH zwlXv^w6GT&h6Ep~X+j({xhX{2M7Z?2j}C+g3DVujx}ZJ!n+W<5P5wacB*|T2)VM0R zMPZK0!Oh{l^`YHDmk=JO7(z`5(|{bfL|BM00n)chjaqs=pu|JUsdD;CL7E~Zu$skm+2>s+)EcPb?Y~XBZeX=}1i=38zDP!)&xgR4! zjOT3kkUM5TE?}`IpZ?j9Rb`Q|SJ}FhJT8gMqK_eu3*Ld@P=_TT{O>g}pg;c%5uP&q#^%`@M59^}* zRtRAiO~SwtH|M&>WlHRs!7+RpRer4@Nmo3HZPB7VOO8>}bdW6tny}6ETBPY_YS~9} zKbn!t9Jz1iYJ3QwNnC_^Bk`RWyoRvP)hO&pzib>nS)(U(vWGIUa&2;a?x3E;2V>Vv z?V{H&?uZ!DXc6Za7we&dNMoq)w`KvOMZ_{}nEMcdE(U!z6l3ccuiEytT6@C|xZC5WZs4yObgZkDnn ztV8mXIzy$KvKeKem@~P?#MccXmd4^u_L7fJIDCFOa;aLI2dEg{X)!v{zcD`t zT80&ssbLhMMI75gXr8_yALIwOZg+Q=vB|HRo<2!p-(sgB8<+81GGUwMKwxcJ5-nWO z3vJOH0)j~H!X;&z1P|YOvqiY6kf3PWGBXb(Hpqe$921E=o9g9hyijo>d3pHi8+#C) zxCb$~4j(QfOZTi~9IDS9DKGfIkWI9w5F@d;tU{L>T3l8U5raY}%W9UJOOkNJWPuc$ zzLXr4=%}HL(C1i*Wvb4?9=6;FRJ}`1mDCd!B2cxvK76(Tqfs~? zcO+YS91@J19m0+x2Od(#Vb2nkw@{dD6Nobmgv3@VPv+`jn33{u5=nJJRNY~yeUQ>~ zf126Nuf2FR4MP5@%~X(zt%B4)2pYGC;uiM$kj+AZwGB%qMg(4q(l7R*8lD9KsSefA z2CtA*=a9D-h6XhgNe0yvR-+(( zN4g>KCZZL#SeMG4_an#4a08?Y6T>G3S#)EO#KfZ-n;P0#Boa~nCKBAqiY5ei^j8?; zzz-@VLO+5-$%)Y3+#<>?UH#EcxtUK{r2XW~b+t8Vc{`(EvdOlgM#gfVy=`XBW{GLq zJEDF*K9ojgjyj+hv7^SbyRbh(-v)WXsC@V#>}HFlgTV{KCd6DGQ)9!~kg?ezEakmT zillH)FQbg+*r;P;fdmFqCI>^($~G`lAMru9us>HP@T$kg!wwCNLcytXyxobDi{+iz zF!B1u{W8o5Ln&S51~8sHKK7y)io}Mfl95%G=_-Sst3hRzflIv_isDq zmL%H*TI^fP?Y|J)5YSKrb#F01N{d;^Bpj41y~t}Qh6Ks}w&aVXx<%eZxE1_|y+B2v zC3-i}AKJMp-L`)Ht&|5Eb<0t?=B2<8E=Hp3h^Tu+eh zF#k#6S|#G6JQ8YiVPVeWX;W`wOQwC%5o>r`mPIikAV*MPy|>B#by&Dcb-FO1Fe2!3>OHriYzBGhbsL?bM2zqKA@bUCFE$bo1sW+^J;< zNDp!AJylHY{&Io=k|6IXYMe9nV0AyX z2QZ%u6L!KoL%0+dvmm=do>iesY!-O1bRGapA{9-&oHDH0yChE7NhJz3*y=43DIjHj zqkGzYcVjr4M3kZeAz}yXdDBhZCnH{fU?I*%K>^#ssMkc^#p!`t3zPux$g4y70Q0fX zjr>Z4SQBXoMACtVKvHK`X1uEa-d@!L3qx?l^Co%E7hyj6^r0A~yh}^Id0g6@>>{x+ z7x7JMc7g%L!+%RT!N`Wx%H1Q=k>@y$Xetd>Cy>N7I5D(41E8tf#|&MF1U;)U*}=gk zmS4`n>R9AaC?z5T-1O9;;n8|LeUKf#f&B30J}8hdO?P40V!ja_##%lwJA*FQgs9p?69sEj_28}Lu}VGj$D=YT8rEg) zfVrKhm{8Vxv-(ZXTRLsuk9a67J~e^Hq9uu5V7@XArFL5j{%2{i@2WJr66kBZNrf37 zty=N&XvxDhufb(GqLuewzdd-pwl>X#t)bbJl@o5-&Onx5Xr$uNrW?fkMbzTzM%T*F zl%y{3mC4!PNyHQO_hl1uS~qnGseGr-8X}!yFrl}i>2xv1ueTp7as+PSu=&($vx`qp zuN2L>%BoTqG``shkj8R&SjU_ z^g3}w!cAh{p`}=GOzHXRrsrEkj(H5W9?ky_c5l=?Lvs_2N+oPW;)NP?O6Z^#%D1%C zij55R9jwocackN6q<`LNcb>Wy^Hr8P9d?nCZA&%&egS}(R^jyi}Ye0@1j($$@rOB&O7ah6ELGo;#v zaudAc)J$dE8+f6pmUPUqU;`oKX7yM=y4`oQv0Rku3|1+Oe0W(geq?_J}`YwL^d)_LsxV;&$)HsZpGP5rpv4A z3!A9dGv=ut-#o93$dkO3gqdJ3^2zD_H1Wz6nI=l5Y(14L!D}$(B%Z%>6Gsve+l+9B z!7G{=b9xRPYa?IBq8KP<3`kt^q}eVaQcFsjUs`Ah4j1;$Lex}M059Do%{8f;Lb?Xm zlUIs92R`yT!Y!uyB4=+}PxYcl!7}Hca`E1#GE?(5{ha=>*s0CCIQrgi^;yR!721hu zpWoD*=3@}NvLAwh#*E}?@}iR_S9kM;R*{`fAx*>cE`k6E^T%k2xdpGCrCVI8w?Jfv5CRa`B>Pu zi{rnH$&)$Bf#+*mS)vncIs3UE-5ixoF81PXjbLv>hqNbZPO7}Z-nZA(le9Us4Jp-s&=UY_Dw>NQdeG3Os@?zqi87oGT( zPTN}#{UNJp89D|KUghIOlv+mp4L&p90{Ws+Ysf)3Ws33#lUvYYFSd!iu=ofX$%etL&VN_grj(g87-_UCq6{RTguz zWR4MnV9|6oB70S?&1~AsY$`IwvTVhN2*NmiY*#xqRN$q}dmiWM;WG+xr&^hunyf?Y z9Uk4;z;Sy}y<_6kKi2wQW!5@)X*m8iN#d>dLw_DP%m~~qB1zzF8W5;ZA(-5vb;s#y zTAOTF=!hbxbDZBgT=ZKwy~F-h+nLrxXQAc5`^Y_zj1cEU=VFM3(*HiCrq+FnOpB zLcX_#11Z=Ewr@w|0v^+7t)|KALok|3Ml{VWx7hrdt8nNlbL$4@RT-{&ooJql=zL4- zwXij2AuB|i)7jwvy))(%fMb#S|cPxJ|@(iz&@D7dKD z86q&=c{Y`58@^upfn(q95EQ_qR#P3U59zTdR$FsSWZ-2z7y|Eg(cfHJbysU_c9R-tJzGF~(*dq`|~y zz9^x{*~x6~=lyqO$H+1FEr>p9nfxARbCBMIKu}1H6ozu|!a6DS%pPgXRYveRH=~~i zLrHw0W~NI$lklGE8K0c*frkbT=FT0-K_m0^iP5$7Q9=k2vR1$5(&ov1ew= zhZO3m9b{y`gQI9Ie8X+3IK6qeTAQ9j&_Q8feXAPuPumD(+`Q7Lqj_x*8st(Bq760> zL=aeQWPThqE0g00O~|kH$+4+Wu8fS#)E2_GiTWh&q!*!2Ls4K*M*BW9IX;0?O|uN1 z_!vIU#kCSrlwmeYXC0@Fg-@izDf~&@{NFS1#o_;O{U%-?J`rxe@OMJtTd9Qb<%R1H z^7``w|RZ|d<$d9GVID37@y)_eXQrPxJcl8Ez=gFRv1wpUswDM?ADQy-I%xpWU1=;r`+J@cwV+ z^;faMH=L@4@cAD0r(AzF{*SMJCos81Xus5rFY?#z|3zf>;$J-eZ^O^|>$|(Pe)v2Z zUX0D~^$?*}|Na~w`Ro7q>57NXP>2eh5|eZ&33 z=W%FXmRz_#q9+lEt~%VKLyvz+z;1>{LQ!U`fhfttY7&H*M;Yj*OgZc*M~gM zM?WgHk-jy0|8RZyJPW_)ueW>|ANQA+!aCP)+5N+J$>%3+h5LuRDQA6LYe@U~zpeQ% zC_jVuUmxM&`b#1_G#5TE<@Hgu()N!lvMO{GD}?Jp{mWZizwcqKaVR9{YH|IwEw2Ck zkMvH@lgX9)i|>C!i|e}|)tUz{&0UOQe0_!2$Nl%}H9B$r`x(V6!ng1_(c=1jTXjUg zA1#=0UHE({uP;7jsdUAVUjK{}i@${H0xI7F?Fg8B-m+V-|M&%pJ`*3Q{o{$i!`#!F g`fvA~qHjc8>il1Pf7z~5*ZaMAo^PR{~IIQsQ>@~ diff --git a/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps.cpp b/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps.cpp index ec6d9f81..16c94004 100644 --- a/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps.cpp +++ b/autonav_ws/src/autonav_filters/include/autonav_filters/testing_gps.cpp @@ -12,7 +12,7 @@ int num_generator() { std::random_device rd; std::mt19937 generator(rd()); - std::vector range = {1, 5, 10, 15, 20, 25}; + std::vector range = {1, 1, 1, 1, 1, 100}; std::discrete_distribution discrete(range.begin(), range.end()); int index = discrete(generator); int value = range[index]; @@ -42,7 +42,7 @@ int main() { std::random_device rd; std::mt19937 generator(rd()); - std::vector range = {1, 5, 10, 15, 20, 25}; + std::vector range = {10, 30, 20, 25, 15}; std::discrete_distribution discrete(range.begin(), range.end()); std::vector p = discrete.probabilities(); double sum = 0.0; @@ -50,20 +50,52 @@ int main() { sum = sum + n; std::cout << n << ' '; } + std::cout << "sum: " << sum << std::endl; + std::vector indices; std::cout << '\n'; std::cout << sum; - for (int i = 0; i < 1; i++) { + for (int i = 0; i < 1000; i++) { int index = discrete(generator); int value = range[index]; - printf("index: %d\n", index); - printf("value: %d\n", value); + indices.push_back(index); + //printf("index: %d\n", index); + //printf("value: %d\n", value); } - std::vector indexes; - for (int i = 0; i < 10; i++) { - indexes.push_back(num_generator()); + + int one_count; + int twos_count; + int threes_count; + int fours_count; + int fives_count; + for (int idx : indices) { + if (idx == 0) { + one_count++; + } + else if (idx == 1) { + twos_count++; + } + else if (idx == 2) { + threes_count++; + } + else if (idx == 3) { + fours_count++; + } + else if (idx == 4) { + fives_count++; + } } + std::cout << "number of ones: " << one_count << std::endl; + std::cout << "number of twos: " << twos_count << std::endl; + std::cout << "number of threes: " << threes_count << std::endl; + std::cout << "number of fours: " << fours_count << std::endl; + std::cout << "number of fives: " << fives_count << std::endl; + //std::vector indexes; + //for (int i = 0; i < 10; i++) { + // indexes.push_back(num_generator()); + // } + // accumulate std::vector weights; weights.push_back(0.993333); @@ -85,4 +117,13 @@ int main() { //theta = 2.0; printf("theta: %f\n", theta); } + + std::vector test_vec; + + test_vec.push_back(1); + test_vec.push_back(2); + + std::cout << test_vec[0] << std::endl; + std::cout << test_vec[1] << std::endl; + } \ No newline at end of file diff --git a/autonav_ws/src/autonav_filters/tests/particle_filter_test.cpp b/autonav_ws/src/autonav_filters/tests/particle_filter_test.cpp index a0dd4db7..5a75cbe3 100644 --- a/autonav_ws/src/autonav_filters/tests/particle_filter_test.cpp +++ b/autonav_ws/src/autonav_filters/tests/particle_filter_test.cpp @@ -10,6 +10,7 @@ #include "autonav_filters/rapidcsv.h" TEST(ParticleFilterTests, initialization_test) { + //GTEST_SKIP() << "skipping init test"; double latitudeLength = 111086.2; double longitudeLength = 81978.2; ParticleFilter particle_filter = ParticleFilter(latitudeLength, longitudeLength); @@ -33,6 +34,7 @@ TEST(ParticleFilterTests, initialization_test) { } TEST(ParticleFilterTests, feedback_test) { + //GTEST_SKIP() << "skipping feedback test"; rapidcsv::Document motor_feedback_sheet("/home/tony/autonav_software_2024/autonav_ws/src/autonav_filters/tests/ENTRY_FEEDBACK.csv"); std::vector delta_xs = motor_feedback_sheet.GetColumn(2); @@ -129,7 +131,7 @@ TEST(ParticleFilterTests, complete_test) { // cut down the deltas until they are the same length as the gps values int n = latitudes.size(); - //n = 5; + //n = 1; std::vector sliced_delta_xs(delta_xs.begin(), delta_xs.begin() + n); std::vector sliced_delta_ys(delta_ys.begin(), delta_ys.begin() + n);