From cf658638f4958fab4d9ca85744e7dca48aba019c Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 12 Oct 2016 01:46:54 -0400 Subject: [PATCH] LPE flow improvements. --- .../BlockLocalPositionEstimator.cpp | 4 +- .../BlockLocalPositionEstimator.hpp | 4 +- src/modules/local_position_estimator/params.c | 50 +++++------------- .../sensors/Flow+Noise+Modelling.pdf | Bin 0 -> 131728 bytes .../local_position_estimator/sensors/flow.cpp | 46 ++++++++++++---- 5 files changed, 52 insertions(+), 52 deletions(-) create mode 100644 src/modules/local_position_estimator/sensors/Flow+Noise+Modelling.pdf diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 5622c1199b..3f768b4067 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -82,9 +82,7 @@ BlockLocalPositionEstimator::BlockLocalPositionEstimator() : _mocap_p_stddev(this, "VIC_P"), _flow_gyro_comp(this, "FLW_GYRO_CMP"), _flow_z_offset(this, "FLW_OFF_Z"), - _flow_vxy_stddev(this, "FLW_VXY"), - _flow_vxy_d_stddev(this, "FLW_VXY_D"), - _flow_vxy_r_stddev(this, "FLW_VXY_R"), + _flow_scale(this, "FLW_SCALE"), //_flow_board_x_offs(NULL, "SENS_FLW_XOFF"), //_flow_board_y_offs(NULL, "SENS_FLW_YOFF"), _flow_min_q(this, "FLW_QMIN"), diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp index 9fd0ecfcb1..cc7c0932bb 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp @@ -286,9 +286,7 @@ private: // flow parameters BlockParamInt _flow_gyro_comp; BlockParamFloat _flow_z_offset; - BlockParamFloat _flow_vxy_stddev; - BlockParamFloat _flow_vxy_d_stddev; - BlockParamFloat _flow_vxy_r_stddev; + BlockParamFloat _flow_scale; //BlockParamFloat _flow_board_x_offs; //BlockParamFloat _flow_board_y_offs; BlockParamInt _flow_min_q; diff --git a/src/modules/local_position_estimator/params.c b/src/modules/local_position_estimator/params.c index 3e7833ac3e..56bda8579f 100644 --- a/src/modules/local_position_estimator/params.c +++ b/src/modules/local_position_estimator/params.c @@ -21,6 +21,17 @@ PARAM_DEFINE_FLOAT(LPE_PUB_AGL_Z, 0); */ PARAM_DEFINE_FLOAT(LPE_FLW_OFF_Z, 0.0f); +/** + * Optical flow scale + * + * @group Local Position Estimator + * @unit m + * @min 0.1 + * @max 10.0 + * @decimal 3 + */ +PARAM_DEFINE_FLOAT(LPE_FLW_SCALE, 1.3f); + /** * Optical flow gyro compensation * @@ -32,39 +43,6 @@ PARAM_DEFINE_FLOAT(LPE_FLW_OFF_Z, 0.0f); */ PARAM_DEFINE_INT32(LPE_FLW_GYRO_CMP, 1); -/** - * Optical flow xy velocity standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_VXY, 0.04f); - -/** - * Optical flow xy velocity standard deviation linear factor on distance - * - * @group Local Position Estimator - * @unit m / m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_VXY_D, 0.04f); - -/** - * Optical flow xy velocity standard deviation linear factor on rotation rate - * - * @group Local Position Estimator - * @unit m / m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_VXY_R, 1.0f); - /** * Optical flow minimum quality threshold * @@ -132,7 +110,7 @@ PARAM_DEFINE_FLOAT(LPE_LDR_OFF_Z, 0.00f); * @max 2 * @decimal 4 */ -PARAM_DEFINE_FLOAT(LPE_ACC_XY, 0.0015f); +PARAM_DEFINE_FLOAT(LPE_ACC_XY, 0.012f); /** * Accelerometer z noise density @@ -145,7 +123,7 @@ PARAM_DEFINE_FLOAT(LPE_ACC_XY, 0.0015f); * @max 2 * @decimal 4 */ -PARAM_DEFINE_FLOAT(LPE_ACC_Z, 0.0015f); +PARAM_DEFINE_FLOAT(LPE_ACC_Z, 0.02f); /** * Barometric presssure altitude z standard deviation. @@ -412,7 +390,7 @@ PARAM_DEFINE_FLOAT(LPE_X_LP, 5.0f); * @max 1.0 * @decimal 3 */ -PARAM_DEFINE_FLOAT(LPE_VXY_PUB, 0.1f); +PARAM_DEFINE_FLOAT(LPE_VXY_PUB, 0.3f); /** * Required z standard deviation to publish altitude/ terrain diff --git a/src/modules/local_position_estimator/sensors/Flow+Noise+Modelling.pdf b/src/modules/local_position_estimator/sensors/Flow+Noise+Modelling.pdf new file mode 100644 index 0000000000000000000000000000000000000000..fb5c03530c14cd23e7182bf8a3b97150baa89c34 GIT binary patch literal 131728 zcmd41WmJ@J^fpSWfOI3JlF~4ABMn0hHH734N_Usiq0)?W3@I@n-5m|NX({lDD;UgSpUi$=jK^!DL|;j+QWN2?=ahHy4v$oHIv&p$a$$taC!bD$$^a{|F!cI2I>1E>tg z6e51UKCpuqT&P6{gV7WNeS3Tc;+`hrQNim(FUu#QQcBsm=B0WtC#6d%3!-?f&ZP#~ zRicKKBcIy;K~WA#DC!vhg0E-()q1G)4Z9vzLirUJXEZIvR`%yF`XIK9%BEF=EwVyE zSLg)wvykjTvIhdvNgr{ok@6Kairce*hPktI6fPgGruT|O*GBG|@jueYGHooEFF&%) zlbY6GPrgq$n(deoL2b{hW(?6LfH7dQiyon#R6R>U_ZuPDZ?bdGI?{?Sc9HTX-;qvF z)*Rk~H46~4n#lJ=jr`Kn(ece0i&K9qu79G%%mVk_NThNRF(vrHC5yH(3`kpv8`_j>=4E^O>SKHS5gkrYZTUWx8M$N>QH&@myTx# zrWkFJ+@x_DTq{=g_t2rJ}c$E1lJlz3h)TZ46;6jll$DeVu;~6Wqu*Zb}sP6 zl>B})yJR!5TTdp6P7|gDrjz*hO@}t^Z?;gQGFF9o50Q3|h_ z3c?{xk9FnHCi0s3Mb1X+x~h)Sr|J#{Oh{HEliiHb47*}oWduUXZ6?OXDjJObzEM&8+gz`y!NJLTzV;>Rj!>YStNQx;^1fy`L3U72?|kS}x9(32%eg^EQm{BB?u)Oz-eW#|6YG6hsl!o)yYC6U9UA#k zW4L7Rm<62;PTh;DQa+uYTcj;BC+!Su%#MMx|cXE<6(6n3tW!61@wpv^_Hq62D{{|`GfByiE=l=`o zc=`DLPm%7Ifr{h0072`P-gYX7`QIZjl?^`ToLn@TVU2Lj5mi`a09yH4KawDC=CPGT zX&|1FEuNjBbp{VMET}##=+#n;LQAwjuJ47Gh_B7{ zt7YKc;g%#2^~otco`fo0U>kZ?h^J4a?$Yd_N!G!c#B#uF&Q7T0!`&KRWKwgryf+|0Dh*mEVl|*GDpG{hI2!>@p8dVY}~tjrW_V zo=ZqP_1Ugmo}klaOg(3NTaUFBol?rc&~Z^Yqu$t0kwI$GR+hFYUBZ#~N9fikqN(w^ zkB?+)U5Q!n8(4BuX^aZ&n?IYB(MmziIvg~eHq>_SYWcYUl#kh&g!Cjl30s@H^DZ1|~-FFMJ($m2+IZBMx^id(}^?_Lo`lr;; z0|)#4-Zbnz!J2Pd*_cfkxVa1JVF>x{Us!L@*AfuC0Y5#>p1M@AKZiw>Avk9y* zaWvHIv&!d452o_)Y@KIO400$j+1MEIXsBod+Jqteua4fJjf!ALqMW`#D>OneYyOCf z?0v$4<}CF|mw=n)Cy7iAmP|E5?{&vBX~htRNkszXAd4LBrx9>P?l400C>Q7tnOC8V zdDQMfMOc_yMoy~rWt+r3Mp_72NaYCOdzlVWQUj8(lB^>7bfq$TTPkA^H(_gh{y3=n zM)fV%$Mhj$*XAt4Z4)kZ?~(#J^$`yWrEUa62Ygkb1Er8DcXFc+hq`B5 zto&G>(^$%rsvD|Plzp~b_&iSJ&BZUuj3v(+6!xkHFbjiXxJJ}3T3XBw;&+k8n^xb* zN2eDxU2;bwI+a=e7MvR5{i^xd>Ryc$wD$izkHD@1NfaK94;UJuJ?~e?@f>tFwoR=S zoZvZe+0lzy2N!#b>5ZRHWDLdIRC#7u&E9fsw=I6^@NmzF@NW(j`05fy!zEX?f)k!f z%fd>`XF5x_xjWCWIs5B!>#dl#y@lF2yj4s6QtO4k+uQXYdp4iH7DxbI+$*l#67=jCe@#$sjdr7MZP|j zpcYPNoZdJl)#HT5k=&CHPaPJh2lszHdF0worKcgndbWJxs19&Mj-M321s6> z|F2SzTj2i`AQu6EoEIW!-P7Ct{juoLZE~Bv0rKz~0bJ(&V_3(4Eq6+t-w#n?~w#*NOkEzLV^iDa^XV=OKGZASk5BH-RmXbbKrN+7}m%cvmpR{Ck~&MC+uRW$79DbpWS z=|yVK7LzMKx8iu8UG*QEE>w#;EATro;hi{>wMns-k9Kxf6*wGnos;R6Hrueg_kB`} z3V%7p*ea2dFr$24+jU0&RzdVUHW}~y$rHTH$& z`D%up6h9o+8(Ubz_2Vn+Pp86+YCYD+Jl0{War3jKGli0?$NkQVCxo~`^?W;;^e0sp zsH>M4GZqAf+(IyvX{PYEv zXcO8VduVgi!FH(Qyz>Jd%7Y?2pSy=xq(9@tqv|2JL}}cqle=Ui$g%&tPHB!Fwi_l( z+!<^tBU+`Q+5x9`Ek=_YpBneo1+{_c8^%c38I}?7S;-F(32^+Ug zCydJl8#Imz+yzBk7=WVW6EJ)&Qy;x&+;iM5QVn;Jcz)16pC|X(v z8B7zDVf+iByLw&`2Rqv--^bHyHI!tDT6sVE0;yW(^D>SW-C6r(IoVEY!>w?y(Ny(s zl=3~inJmZX%@-xd^7bk}_Sn}=Ltuy2Zzh>sb61LV%ofL?INZqwhBu;7gn2v)3`h& zl2NHOW+w?`=40^igv3~!MXp1nc=j5%z9B%vA@kf^HnWq>`r=pw_dP^Rw3dSi$&@Ap zGNV1Q^!&j`rlz2lgM?*Li-)Z={cOiL;*$)}VCbFV@}!l!_mpli!ClCZrMbz!1?|G9 zG%^Vojwy?hF|PC$-XPHo7FP?Z4Wzq}iv+_fCSc`1_lFH(pCs~|*!jZs`^vbT3C2>2 zFN`g$kTeQ@m6!dEb1tnPl0OEC6W`CkCO<<1eQr4AZoV1aI(_&JRuK;`PVaVeB%6Gs zijk)rilY3f`y~=prhcv2n_{8c zcl+;&lD(NV44X^O))Jtyg2EtdE=8EFwT&A+h+7bwOUBmCRRiYo*3sU{(E;Y*MlXcT z_14kO(FNjUW&x}x3-hqGfN3en04svcTtCqB@&Vt}`rq7GkWWxZ@c)n-?`L4966=wN zIg>#bW;@ZM=Q&9{oVnhWaga=h$~YI2gum)p#OYz}S;Qvs^z;nhwtV#%c(C-BTQz=w zfiI0==$e)`bJ31Bt)XGS-*vcQ`FiPJP(WxG;?xtj=gjB&kq)xTK#XyI1E6r!Ng*%f)eAVi=Jrmwm-H~(Z3xQ8z*z+ zq9=+W)<08^r%eJw=jp_KCbFf`DRSANNYzZSw5G>Wy^6Uy$1Gu2D=*$%?E$G08C)A4?+QjN=HXTpupjRj_>Yo&dux! z)iMmSrGkM2c5sls(GD_1u~{9K&#N-+2tg?ae({a}gKmLx(n=Md)z6hU-751Q*+?Sy z!zG$`al4bH<9bnf#lV+QV5F>CmcXfwcy-E+C?6Va$C>h3|M`9o818et7Pv8Z&*kZG z@;H=|DH*%J4zimeu-P3*U^a3>pZXAopa@%CrVM(+&K`3+DKXxMWPh9v$ESOOiHWM~ zzY01ZSC=%1O$F z;~f?4a!xFqUtraj;W&u@zAl^`gR$7?+gAG5@h zo7dad@Kn5`$vCbAr@k9bw>sY2<)vl@CwfVVP$x} z&M`bIFE1~FK`D1DV-Q%aL3O#w^Kd28qA$+BYrOyK>(yT1u3v)xLB|`sG3|qeES6^h z7y2i0r)xbp`f-4DhTE#tvm~g&_qT^_!2PRyeTAts58{HR`}J&GZoD?=*YwX8YV&ew7fus=#9vFUN@mQmbkWJ{q&>7;YMYwm~X z0UnjaXRY>N!e!jpJqq}J;kHfRqmk24C=U6*KuwhG=&SEB=b?%{>X|j==6-I$oA%R+ zZ{b;B=dtuPIrv(^PB|TMu+TtELPA1F_|Kg(L_H6d+p->ZR=dK7ZQh@4k2YB?gHJGec~njw)S!UU00Q?q9m0|7UfUrfxb);@y%h4!{cMOYC+m zA#8f((#cjJ0{#a2TpldmULNk?A2Cb7px<@#*%L=>b~jXDyNEwD;Z`?*vjfHgzLkhT zsAXVFIx*^GzkC~ZWQ$E9C8fN&x*DRWt*F?avY)#`2A(W~j!TR`jj6Hd!@Fv5-5L&2 zU2b&W6N3Ak?~>l#4RN&zi4ymjpn|`^l1!4O&~}S730K1kJ&73^~W}!^n-nr1g^Df{shiKVAdZ z@5-QhiSDAa%{>f6J;8pq-~A2$7!Z9f{hIA!D3U=^?P~3sBbnkKAJZs0`tV>3tt+R0 z0B~EVpoVpbFW&=Z)1-YnDC3U>a^D#%upEfr_?hMk#2Nq}0BWjuc?lI11HJ^nSdD&_ zdA0Qjtz>|ozCJ}IaTWqFPBOQdj28(?docRb2Xc!F3{RWs^2N?j9N)9;uM++~UL<3Q zvha|@kD=J4*x1->)I=*)?KKMuCf6q$!R}@=tE4%iS63iRhUe&bQv6;=rn?%Nbq>b$ z_zIAjLVO_iQi^v4^7cLp!nTR(#P_r8xa7SeeFy~J1|ZjF3O^w1MQ}DKH(m{T)T{_C zs+Wd5Mmry}>y(hV9~xDfqAs_%&ez&kQZuV(ig_L^v^_rDjuog}gD?-vfY1XFkjf#y zALH=%!~HD~bmDSRB&2M*V%{eV3&WpvUxHD=001gWL29rw!s12Tw!g4Kn0A*M{H|Rd z#8)9j;BNx90P=kk;Go_DK*0}=w%8U(=P;7Y@xt^-&&2=yZ{4!PLOr1cgoQ*|gA8+D zRygWf9VE~rO|mk+M}ex`;&mLdG^`{ACHW$j%`RDwUGn;o#d1~NlgFe5d{7SQUtOjad;4cwwRr+6$PTn&AliAY zH7>2pVOL>UomiwsGKaiS-~Zaab824qP;OD0upSwvtTdm`tK9vLQIf5tVl?nT4*L}; z3(fg>$e1*ehV|xv7`aBta-%LE2<}$O*mrSqSi{{RXoEym z3MV&Cp2>zuTsm6M(6?GVv8V3l*9eTgyv8VJN(n83Xg{bZv)uAT! zvFK%BiZdz9D1rhFmSw9m>SVc&8yuWEwL)UR1P@#>xiWCA?)XG?r~_piMAXMCu{|j< z8aB!lrU?D7CdQ(V;uCSwCzC@BV~Y;q*K>|o!+4G|RHp(b8p-IfhiffdWvD|F5i9Cz zf8866*7$_1*B$+zePKU~ zSR2ee<3V~x6P*RF4(6^5JK@}wpn*rV=m_EQNEJL=GIIM$5$-TCojRX6{EpD%%}*hKNbsPIYzR~J%*Z)F}6J7EW{d!y#)Ke zbcZa7nmJOmjT;lWHGRs~0rmc8Ax1e)U=P;>iE<4e+_IU#qjrRs%@;#OS{*==YZEaO zPTVM)8iKM%JKk~1Kx-*hnVi(LNOh5LtvSa6u@0b>3?-8=AR$BJ&Jj&FK7OO)p z@Rm4J)IKHDyLF-sx>((*eRvf6P+_4C^<#dT&kkH75Nw!qCzbWTERv#4rI0dLT>Ha&M7IkiYOr|1~g zpi3%3+|H%pfTxDL>Lw#GT)QOx0Z{Jcr#i6$c02P3z=_h+ljMZ=9y^odif2XDe;@Uf zhA^UYlG$S04lcST6On5LBlBOhLCA$t-r6s}Q;>ohmD>E<U$rZn*MaWP(FAFjsjrKD0C1eAJnS%H=l|YK1=iv>DYaYn_-nd@!NlfDWI2)v^>Lr zX;M+%o2&_dJGM3JFm9=g%iZw+f|D++8((k$EgCF7*8hS;+qNf51Z-TUN7< zB}1+7^H*`8I*!g}R}Oe2pS&Bu6wr8Mc_XxvpDb}P`5MHdd`ji;9a9ma2zhXw78_Lb=war6-Y*rtUtGC4Z|l+b@{&31|L_n~7fP~4 z)`OV`n4X&A=(epJR{u8CH zKdKg4uG#l#zNU8vs4!>nb2%1ZXR$yCUz;eV*yxj#j1%8VjLnBXZu|JAAe?}~bxYn_##6gqAVWTftVWSmxKz>LZ z8Op_Q&wtgq-&BuSKuV>0UvN!li!2CQ5LYR;w`f$>?sFd=%EzMnDTE;M{N6*!4!Y6=!p%2o9ANMU&2^z?$l1N&;~>30!GSUW%7$0Q<9a=UE@@hu36E~UI{v5S--s9TF9*{szl z@4qmlZaHmo``#b1#oXTxEnO{|nc^Nme!QOqw35{jVA*1J?4{3V;%r*G>%^`u6^&%| z?A9*NH2uQ0q*sQ&N04P9sC9FmYFGh8%Z5nfPg8AQ?}Q=*RTIz--%s~thYK+#kd+S zBoVD^TGV`Bl(bXF0{EM?SoQ#p!T(_@CN7Sa&q~$H>pwod>l7)QlWz&QIq84s;>^~V zi^xDA%P|j<`DQPv^9!y{e*LiFk!&V#&O|UEa0(JPmG>=P=-Iv@7;0bzWB$ItP~%=k z8(La^_+yJf@vvNNtqxeAv$HcKBxLQr5D;Gw217qPKnq2}Y| zJpt(Ph3C~)R^ZxcBE2-4m%=(#Y?LoRsTA}kYR0v@f3%~+b1B8kF=L+o+#v&Z@XZA} zjK}A5?M63egY=Zc`A5*8iV%v`uV@Sx%g$(2m{}73aFFfT+i<+^?^W;vN7A z;bdb-(B?P2r(QZ>gZ7+c4nvRo8+ReRN=j8VpfnF@1nBC}<0m%$H$ck5pcD^KC%(Qn z`L~BOgbf;AvMp!cQ=H%s@u!Og#Zt~6&MtC`z4S6r3W|f+w(#no#HHKh{X{8XwPpsm z6|9~1YKbFoF)}7*e>CrD-4obIrawRlfhb%Gt5?mtYh#Z(VE_1IhBg<2^-X!9k}0K> z_ol%L6o+D@q+cvRq}3ism3_hNaL&ZFKV6e8AJM)d(41Y3RyK#ws<>){5c}#6D;*yJ z2A|}(Gk~-MgbD%2rJsvq2=KQs+!rE0&j6Oo_F<}w|NVrJ&lwBn0!tf5bZ%Ca5l{6! zf)AbxRO=IF-gjZniZ^-WP(1m1G;T@U$Vj=2PEE~9s$I0Gw#pkG~ z__pUA9jFOv=|UZgyr%6ax38C*y&?L<8=;ZZG}ZIz|F*9vij zB?*A3ANx5WtWU5wquamD#M(eB|ndcDngt^JBcG2OjGD+0CsLW zj)=X}Q8GuUX9Mgtg~O0++AUFiFt`5U9}BstPx5}M8xa7CVLz{ zQKXrtl)zM9pEto3J=WL1v>kM?ur+;Mv{NuZDOLQ|;bMMS%&R`zv)U_Fg&)3VI5?gl z3qLvi5wAiX$d5UIcpHiFE*1Rql@dHs4Tz zW%_Qr-I{|I>s?z!}wLe?!y7`k5kg`Zg-EYop zeJlVyp;WtACNNXT*<4>=AD~uzmi-z4W&km}D)U+EWghby8RN6>&pZxF_f^XQ^Y?+| zs>Ur6v?gt$K6l{Rz6sLJ4T?@LO6dDKV+dCMFACegOPth|M;skHU6gq|_`P+jDYjHn ziD#(wI(|qIs^U{`@U*S(4n5n&>I{3P8a6~`kz@5o34U*vbd&dwk~yZ(53_ji7d z|HIk+4UbMq>Ue&YrV%zywSfJgTDpxKU51xseWcinV6nD;-l z0kM|&C6JFJ3vqTVvkN&K5;pX#@`H7T?uBQHR+F&%UH?Ql%z-RQbrCY5>{vu!P_&~+ zYEL$PiTlEnxde?`N=TdIpW^R!c5xi9&x^QmYu2OL9xh=U%Q4z?e#qh^sT;`Mk!fTm z?1QfPU4+qLK7Z_qo?}#bzSx-d>NSV7G)5K?Qw=GbmF@H}$hUU28!MyQ?I2G99!CRi z*L2#tzja@O^hmJ!0hk5obgX0f_@O5{P!j&xTCQj<2FZedK|q#5?WOU4%_aMU&nH+0 zg1S2S5ooI@fk;!vbi%6#v~o)EdK!ZASYaO?4j0GEO)BU>5yhHa>72%P51gQhxqK{9 zhjix=+Lj?BmS%})@)x`?Btq5ph2#=Tz`J3@;PHCjTN#-@f;(?>v^k^Kp5_5mU}4dD z)0GR{Th11Rox|-Qw_^C#OQ~cs=ePtTCOMQ#^nYV8dHtsZCt zJpdO^P!J6i+B_b{t0eo6xyaju_X21k#<53LWp?uTw!1im#q9(Y(C z={$P9)Af?nAWnV6%x=|Il=DCM07EOKe))5_*2nyq!fF2w+3j?kJM}RI&uY6pSQQAp z-x_-+fjf*6gV2@@y1+Zl?*{xvWtzbE1J`T@RRqxRJo(2e ze(oB<-|O7_*}eV8-q=@G3iKewZe~Gai9?F?MthT`a~ngrfR_!X2o@?5MyrQnLwBdG zaY!oLD_}!#e3~(DKfD)$yRKWcOlo#})1RH$Vs?M7e*jPh5F2}RUTi$VG;0LDZMN;# z{cQq?Jfpv4=1Swm@>9O16z9L>7$X}4$k@^|1q`Ff@)Qy$N|vlV{%M_X1Wr%W?r*o3 zu}2uMz{1pj!}0mQ3G4*kCly1&fwq`HAUTn_{qGnH9vwdQZ*aPe z-CQCrPIOPoK&VY|VicX`q2;eFI-QL;_pG z#WsH?y%G`m*WRp;%kz6j*3%#-%od#+8XW~NoSfSPtryFt5my|hvYnpq#}eQBGF+ny z=CkG(1J%w~R%r_eNSiT}^Njc#yH{z3aNak;k>5EVdBheHg?I**8I{c0pkqWd_Grz* zzPfB)qMg^AhE~sTe=w=q>@Cdx(e-XvDfT>=kdysFVs?9x6_Zc$(>(BU(X-m>SLY=4 z#wn5|+(EO3Ju12sg`yp#+dyyRf61IyFn5vh)cDENgj=u_;3j}x=A?U6x>N6#c);k)=qMZzG~hiZIeiqiGWo^EZ6^x{B*ixb^G{Vg?OkSc`pg8@_h&6mJ=6FM_oiUsxE2DAQ|Mduc3fWPB^TjzinfriugJV2 z5=oY3s|~!~wb#!5_$BPpEx{$Fog+i$L-h-uMl##GTFHzTqcfT-cX_z{c~5kZZZLPd zM8Sd_ujTVZ9b=)^`2D~~Hqz(tr(}j_7QzRkB=_B$=HEh|Kf_(_SiCFLR5Z#hZZC<$ zGlIvD7tby+4FTI+V8XH5SnX;ohQx9hBF)T_y^a-8-q>mxhGK8NYe|)S1Q|6k)o>Bm za$W7GAp!%LSo)J$6Wljd^QxnLkEE*on*us9#(0@ty_!0uet->_f7gu_JM0V%TkmrR z@`B9U@5PY$sq#tR^NeS8)g5%>ksN)5-Zzvwt<6i~{t3n>=~5gZyX9Eqa~ z4O+gQ&#pO4C)`-h-!x#|^=(_J zitO!!33tq8+ni7N=nnz}72qzZxLE9PqR8YcVQ_Im$rBA|otmU+P?Z6{fW1MvZ*+s% z+phLty0%-jEU^ZDnDU1#i8;f%cMYoKbIc*Zp;2Uvj9SZqBkvk=Lks7dp^^^iRo<>- zPAp19FRW8Fsu2y2CRPJPT|46<)@h>jKXkvVIz0;5s}3@yXTbEb#JuAH0;a$3w5R~k z;X&9Vd8C8p`!EfXWiw{UAoSN*S!#DNnOX+~RHQV@EwT=GlyX=JRyS9P8($FA0Y6f- z21^ycV*L|(`c8HQqP9kqNH1rqdV6DM(}gXLS^a(X1ea68pPLET{a$XX@V?XMvmxN& zRLoqMDot6P`d&u_;Oo8YS>$l$BpQ832LRwG$~xcQ52p)X?8GxxC$X5JzJd#l)?0)> zbf7C)2dswF>hr|keiNO}HV``kI%Yd&Zj~E6$~{PyxTi(I`Gyi|R3HyCL((Tx8}x3!y}(ypYCuc`E#KvJ|%% zLhL(|r{KQy!qqoqvCh%t;qJOhiEeNnrm1`!q;5Ar>HfX*x}OljeFSapQE?XLf2vE! zu-WJJo;T7~W^xAal{-e(3PVa4KC)SQ?Ij zWhWQ)#p!npr92AJt>Dw=WA)Cx&nXqvlhra*1sxkXm3+>l5{pMNKA;?wXb+@I_}gu> z2KcQR5YReM37>Q!z!i=QUI$0_uXv7d3g=46(Zj#%eI~7#JLyfWFm3{Joy#+HmWpIK zR{hm=VndhnOQKFimycF$RiiJoTuou|FP6b7eoh!5xindTp{>$kMlXE@RNeiJV1=ps zTX@^!)Z+;bq%>LBLY|GB@cl#t4PS4)YvH>;UPnG^aLb?Zp^0#G2h>R6k2QPKKlY}9 zrm-~~^iurXCKcylV-R+KVd(Lj-XfZ;F<;64h?z5lVdMUlR)^PZZLJI@pV;X3sC+m@JMda^98J%d^TQtzQxEeX%h4uR)pAmv>9zd93&gHCI2ZcgGXG z%6~8BUP|Q`3({Ub9ua~ulcke^p6rLYI(0#_kSZ&%0BlgdL@A+H_eY6$JBrm`gBJhz zVNEG{K8r9OhHf~0@ZUbVSsZc+-~MQF_{XR2K>gI@_L3%Qb>$4IRqzVh2^6T~g)dgA zx6_uI3cnkFqfm0+Hg$s*GR1TLflO`wI^?ykwH&luY&?H`ue;XrO5R$HDo;N4{c@}L z8tUL8k|lMf#$jP;8-=O5J=9Q|_9*fz0^1ks?}rmsmm;!INCILZ_T#A1M)0>}6*#gk z{vs)#q-A^vKT+NeltU+FN#x{_H>`UB^xzBCzSbCo<8?GEvQH7Lz;pM%a*T7t_UDBie!G3iDgzBI4GVuRXMF`(BVoDG+jj07=8On7U2=nI^@OGg-SP&(H0 z`npE}&V&|?a9H?VZlu(l`bHP@^l2Xw-0GK%P5P7M6E;cZ&u`XFdzh$i43XU^K^XX4 zdT|&?5f4xjtA$$9E+hyiZn+@Zc8YzBUS90?+074xp`bZbqaf<~<{Uq2#!@_>?E1ox zXmfX#Z|YAvz(x*B){hN)q4M>xp=4l6Nk&_$0jT0OQ{+0_LW*r1{TN2KrQ#+8$If~M zK)<#)4KI$0UDP1Iva?h)@}~|C8m;RW$ai88Xs`TxGfEN{!c$t4`n=)T*)m)xksO9+ zZFjlfjptMOKiFMEYVD?O&Swcc@EtF|m3sIBIHFCDoRc2&c z@BCJU^}_@UlL}e9KRR-*Nsk%xr^n$`*Vp+v!6Z)m9MM~w@TQ1ou5}KG23K5#xNWiM z`3{nAygd{ovS_f!htgXvUzX_^R5dJa{AalB>R)Fn6oGoL=M$UxpVmigU|gu!e!lkQ zo9uiNFcvT5tlD@M$-=6&tO%L4w;>uDnCO0y1Sz^O6ZBmN%Q2B=1+R;NBP+;vMO$8j z2LgKd0Y4|_1i2m9-Q4Wy^BqxiR=MpfKHEC8HGWRtXO-cwG;y&j7Xw<&w4X~I&UBBV ztPwpz!onWz(?r}QW?eeJ;*i(M%EN=TR_K9n{xcGCd->ytga>nrDS%cZt_oesc)pgw zVg|{$7t4`a6Jp#P@zr;Fq2Ad7NOHi0&%YuQ7${WB6pJhha$$|`=^RlV^%GymDR#^s zNV=&v?D^9n0HWIj>G+DoA#Av#Oau^ipT-%%qoNpt^1_(vI=SObiQVDY)}>V7YwE{? zh0${3(x=142Iu3$^-J2tU;W)2HR?S>l6zv}$rVpmR&mRIaB$vy9 zz=#hm?RLj|Q9z~q{rfjCY}nu54=GfOTsU10d<@-+jfjwv#VVU2X-7#(JJD$qlXu@^ z9w|w+kstYJZ{vrheBZ(`nHh)2RA=2`+^?Mus5GC}>?H^Ru|%ZhDK+@olBqp>a5y7K zz4z{#gOay9ERxr%W~u~6E0Q={KPtzS^xbfIszmPYO|{jJI9hwZlTUUXqVCFdmXSG* zCV*i4bGEvVmQRUj?5@t+)nh?uJ(=UC$@9k@{meqclb|})v@*^QU-F+V{a$S9BTE-O zyKuAOr8l_!4sF)QXQrfjFYc$mRjOp(=7<>}?y)}u=+A)MGzA#JvF*NA@#`yKg0C=Q zql2>z(4!f^aJN|`Y`Vhab6lJnFb?xPrOUUo3IFQ5?so&AA;6q4@TZ`}t}Z|BJi%H= zHKZlB65el%n&%Rlik*>R+ncb*_UEsQXg~m&tumf@gW;LlkP47kG53x}^BQ-?mGX-; za%N5ny^ig$i01%g&P0s>MYI_S21@( z37`=nI6V78F!<>oTfwKhafuh&lXE}a{6)g5vp=%6x+yie6|Zh(MYf=TYZw(xhvIvb zzd!HnWQQOqvLuqIhNyTy<$Sx+Dy%I~vtRXm`b6d%cSpT{Q~p7_lR2Li#VYlRO%P|4 z(N2x6yikJQH9LSvvLCX{IlcucbDB&!%;i7cd#`RW(hK#ipI(p*Dvn_ElDBYd`XPtM&lg96 zN~3y4gG{V}QtU9>-3R|)VYoLPAC<~u_ms$~-rFyv{+&xgwR(pA>c<)o{Rgvo zztZgQo6uEB+>)Fjdd_D}75D(vYZ8D|t`sU7taX3tScz)%WbWOWuibH6pyv_sYV+7v zj1PM)&;1~^Hrz~8Yd4Fg_!{U%t^f*{r1Khv=THzTdTwqmhG&!eo^CQb6qtBKmjp&L zM8L)S96PwxXu>c#Wq#+2QXgN;tl@%Vgb0YyG~f!=c97ZWRS!hdYP8AG78q6hwbatM z9KaWFN%M_Ok6oew{Gs&SqL>qXwL`|kuFl{6*|3ObIQCIb?b<7h)-dfs3ULH4PO}09 zbjs~E-xLGXVl?-xlH0uV`l@Q{tB%)G)l56pv@tRw^ZQ%JmREUouxN=7x@<;VdLHL1 z!B&p}i+9&ysOS`?{YOqX(-TYqeui<>$%9GY(NRPsacocqIoEp{s_o7se%nqaMbmFQ zUE9pW^Ro`!Kof7eNb~K(E4ENXneGQ*PI_}BOFfWA!cS;SyM4e;pvh3-Pq-B(@2SJP zxuHW1w;g~D#@iGXsP!}jA<}ygXg$?DPPWQoUkVgQo7N_K%6TQ=3C!-Un_mt%dZG=9 z7+)0;kXS~?)VTe9Z_qsBv?^nFJq`#5^_cq4Sk}HdMto%=R|pYZsF!X;M>j$ZBW1sW zdaeM4h4jZ%*wAxvA8x>bf3CzcW;Kv`Nd-CSlD4j#_Yun+5%{^lP#dO`J9^v z+Wu{aC0Syig7^3|8=0tvd*t$R#4m)-DbZB{h6`)RXEQvLvE2U@SdjBv-k_6m$i4UVM#T`(?+Yw4|fcJKv3D?WC2p3-UysdX|_+5D;NP+|1($$pXM z&x^l4;WbXD2#=$c8JXiFr=bx^zM~K8y>?5@WOF_g6zuFj=PF;`4srbiYWSfP8oRY7 zca_^k&-~|DEPFFN8P*v6JNrmgvNazJVeW{lY)#*B7bmPSm#g zrvdyLZ!w{MW%B0y2H*if)R9E9L9O-5IUrlRjiGO%o&o^97ju$gKB&R4xR`geEHw^$ zJ_S^tubO7^pYuwM&Q#@BsgxT{(TJW64^yL9%?sS0?ercjg57s3uTOdmDj<0!XqfEo zdq_Z(w))B4DIIhsU_Vxp3XwTp_#T-;TDE1Y;9I zLUDn|#r~|Y>*jN8?5LXc{$I&T7KgIL|gk(m;c!*nGfYDm9h-UOD# zc4NDv2f`$f6NVrFP@E^lG*b=N*&g;ueFeUj1S?@#Mv}L5fq)_0u7!q1wTu`-LZ&E! zpto)nlo}e}1emsRUJ|uHe++Vaad(Y)_k7A^k9|?y6`pY8x`Mmo-7oHYCKp9OT!KfV z${Cxq?QnlNTz8rw@tsX4iu$`@-HgA76Vv74hsy)T&;y|96-!km7j2-GA0h5q?-W$N zJNe7FF%^YX(1F33@3w0s(;mg>Q*GGD_ z(~-|DK09x8Ewu{P_HlkPDsv0F!Y#)1r>uUZg1^-`E(ehHqj{msrSXR9E6d9p6d97- zZQyYImJk^(5pL3XBUj1+v5Uh2a?)uWHgm!rSx7$OX z0wp2eX|+=yBkm*>;kTw#?v<&yMhiNBEf=%V&NpRRw^^6O|~*c}HNiS0N4Mw@yl5+uyUGF2n<$rs04CMjG&zo(-Oe*-4nyDAR{ zyGm`@$ORP!K5Qo2`z^#K1yTe{ID1;fo;ttI^&L^qoLm6l_VAoJEVJjk{-f!-eJ8sG zS_a@GB%)0TxHtzs;tK_;grKVTbmK5C8ubBON=ieJ>#^-mJh|M?;J4es$WJ4s4<2s< z%hmBWDNB?Gj+7n+NxKoZ-c!jWGiX%lih%!Lih~IU@?Mx_fp`s~91-TMLs5Pm?zc^t zOniq2pVyorc6jF6XWXx8=OSqr2y&es3o6RwoxU=<=>f9ZjTCD-mdCE)SOuP?778=j z{sdL}b0pk35z(AeolgVdS`snyq`X(okM73>QiA}lq?FN)r*3xAyQEWNeZEStAB?>9 zzU^xBe_gshoNRZS`E`&@n_xDA#pu&~xd?gA_II8AR%Rws+8F|^G?`7^g={i(u+lIE zy8lF6--AIY!8U0YOD@_=sEt9(AIGyCd0Ll=5*lM(WEQGR#T)nSdJDo$AfxzkeF-CB z!6V(0+#mLSM%xKXI`64KEqf>q?GcB18ZDo_tUUy|qGK+XwnaFqJFLIY^+BIQHzcqZO5@>rX07va+NAgvkWgUQE-s=FXYjt+&orB_(wnhg z%FE`RTdYhkHJ4+{;E`kaCDhXj1HTB`JU|Ir2Ep*=XyrK9qhWts<5KGKuc6gNht0I+ zWTjZxtffcZXSQTrz}C-gfysBdq2L(htV}enZ*eB%{pnJIYZPQ7 z`+VUgD&G7W_`TT7M*181C2|Xf6|}FVn3pgc0s^_}hT?Fpt2Huj1a9=4Ra+zg2}bJy z?+OuoyHI{SpLcab;8lZRh^gnaadYsT9CRJ}eyCWh)1sQ$_WZ2S=3I z8EtaG6)=_oI1LDIr-ot<&Bs}rY%J)suM(~)qvoK5BJoZBDrwBbO{7)*(ZIO3 zJk)PW$Oxq|o(2g;y>GFcYKKMCU+ZR`gAkuU&3ND1`wm9-=RnSkDACe3dA7c7p&Icg zWx6^p-<}Fp>!f^l(yZypK_Z$``0|)y0&HBsgD1={+)62AH7Dt!j1Kvt$X98Ig2y4S z*vb2AB9dzkwd)>3ZfX{FI#K8k7K4gLwRH+J*VT~~ox%E3Hby+79xwefkD2t!?M6Ml zIvxrCpQp!a`*r@$wDi%nTaWg^eqMFFTj`gyz4&O zF13Tb+4B~B-1_#@nMWS0E z>Mre$ek4GcyqHlaBH$PU1*SDerOvdVsl(`VlY;@m7u!3>ZM!VC;%h+0^4Z>(n&o!R zJU%~8YB&7pb8*{;a?n{2Kb^kbk3-;Qk-{8+k%UrueT<<+qs$M-F;gk5J6R_-q#1yR zJ$4}dWGprmP5chyKL_DXySlHg2)D)fcwxC1YCe_`p}m#5qz_)~d$ojZw;b~`IgU%F z7p%f2JiwDwuuS#4PONnsa5+&x)Z^) zT>;RENXMn7q|GNE`hOdw&BbL{xGs3I+0S5&J4{y|K3&6GjjXW4zh?4$u5<38rj+hi zXNN{gWUva0=48|~gkmBPTz#`CX2J(W_u5Jw7i9~8&4alRnUn_f^!eX^Y3y@XYqroD z{Q#B3?_A*212tWSHxX{rjA)U>R@`W<#+GsO4QUXK@Cuj7Qk?UTUdNa4zAfpk3ar)o zCWmY$85{uefeCuuS<2c%{1oOE;pg$HPLE)$+hzchiG(33J!)xCLLg~6Z&Jh2?}TdD zfdsK_u4Y!Z6Y?$dS0f#ZEka`Uq?@i6| za_TVsM`dWq-!HV#Y15FEB=Xy=E0GzP#uNIpuxg zT~@73<6)nbUc4BL&jN<-bP9r=Q_el=a>o zr`DrMY_Jz{>E^DjE$xLKr#~q9P(@GIQO9gT#ZQ69xZM>pP^DL$%;+uT*HL7l@O-<$ zwmS-oH?%zAl8)2;5Y7(wZR`2oVg_)rK-eUcf_Zoca3zhu2o8n9NVUj+!TxM%xeu8s z1~u+PIx|y?y@sp~I%-}TI7h4px4D58K%(oMij>1w=jwz$Z98vdmHG6CI?|=JdH8$T=QdKM>W+6XQ%ke+fB!r;-y;Xs_2~p%Blz3ItDw z^TlVt+7GEWtu2x=(P^8_QN3RUpAi%>;PFX#@=V=N|B&l_`GJk6R)Zn$7yA#QA{Rwq zo|A*m7I`+&;;Vz=({7yvE!?2NT<44V7F{!uP+8mUbxvb%x=;>{phxykG{LpeRGtT) zM^~pSWPCK`mq+hhxizB7;Pt4Mo6D!)s2J#3D?+^%%iHbvuo|_-ETvea32ivuoee$SW)DOrAw(}B|rShKPDvID;#KbFV=?kL&NYbcwXIrZb?hIIE005i9Y?Haf z#_x?o7!???P0&BwKn&ZEKV-Z5^Li6T94;6iOKjS7q1xv7Gv&zyBHsJW$>+zg^!-?J z2|NYQcY!=xgG^b@@8NMOn9eyK%S>8&!lX5QF+_?0dEUtqq_pa%l=$z~`>*D9HeWHLdZZ_nY3Vx&CD4w{TL@|2oXBkcj*<=->J094=`+1xzuj}A!BsYJjerUKdUMmzb~^Mz_-T*T zRW30>@1g}v%9OH^;aLeVelAuWrDSrYeI=~E3&&iHyo6{k{7w=oFz;>6x+lX=OE5PY zm{{U&Bzln;(1)TS<`e8qRwi`HADg^U0z{&TOfmdWMSPK^u$k>4%Sl=d!;ahEmvLAuydCRx|bpVK&>e&H@cnBCVZ~kvcaQyg>@!A(QChh*k@vqLGfT4`Yhu zJ6F4&Kd}7!`Ke!|K?D|u2~D4)>Puvo_18;nuzhej$V(3d+|F0dI4tE&CWNkDK7FlB z`AM|NXs1nhY&AUj(*?vd@^(HFn(?p|2>9GN0zU^Qwb{wgPk| z^bTdJ>S@KWmO!GICeY5|cA&8KZOZ_#;8b#&n$`Dc-^E=Y8qiBn@lbKj-H%=WO``lp zOFq3myxtiiY!t8r+L$AYRVShXmm?XQSHrvEs1UOjc^_xE9t1=2A5XP-yrGWa4U^f5Ie=QJNbVs5H_VCVEyEvkpeENBz>z=-NFc3% z%^1zzfZ16pOG1)x7)0FxRWF8gLBOk^Rx+N?t=xbH>r;y zF3%PojL$SpuTV=ZPCKAdMi~agOR13D30$BQ?=}P|2|)%+_Tx=Y-Euthi8dsjRtsq% zy)bauH57$z1 z6BSy6dhK8GV)fDfZ2!qcT_x9Gq9;-bgNrgh()>VFBMcq!#lX--59Xx4Yu1@^PC#eXM=)#tQSNNR_jEfmG~bi$D^qibCVt#h zPn}k10(bY}X)2CZfyfo@W{fXozrvEIE>-z)Ha4+aZV z&b!@O?M6+*k2$Op&U8ki+ZO0KbB*Oz7pBTa@UeTgjBD*0h&BSk8XH}a6qzN=2J^|x z4k6_)_ZA7<^sVA5D7XZMEnwCs;-lhdzkT9?X4wR*5?c4mi0i)an|eznnKsvKa+OHQ z1hk(`YV^i_92U{g5=UeBh%XuwBcAk3%r+4?3?17n-&f5rQ+0$2xI0I& zz||4j1C{}u2Ft+zyE)1k$Z&GoiF6t2LJ+F%<)JkqoPR=)xuY!q=|l_n6DF&XE|R|b z7!S9CPHzy#GO{%SCh7WML<2N}tMkL^)J;SBjpwkJSkR@+#}(EBjkdg>G+{keD)69l zW8WUel1DyQee&+jf4P@zwv2;DA7~8QdhxwZYIHW6mUI}yTf5kGFq%tl`HF&$5(9Gt zJ(v(pv%SSC9Jgt>9nj$0eu#&AJ(l9gC3iUgv3;R|)@E|Ehrd|i5J2O7DzGTf74s!V z2u-pHd-Y1v+3U!C=H?8-Elv`5^!(DI^_E-@(kcK;g5QTvgyFoD zcT}4xMEMGDWbgTQD^Ba`WE!I9H`QK0-u(<>OysM0aYMAoA$kW z)R{lv3aa$v0DiEU<);jY>-~mYIo}x)b*M&1Wm^a(HO5;j7kYE~UNBV*k z@R4R1p`gJi*l(U;Cr6~fxl5Y^c&mVLS;!m7u!4f($BG)*G4XofQBa}Wz>bwUuo{A4 zv8e=|o~!tlD}imi;6hc2<(jo?>uy0%l0y&l-xv4+eKf zK_#foO!E$o(U3oyuEa_cAYvnH51-!c$eoJ!`RGKME2v<(wcr&g&rmTyAr!3Y2?+w-+*1QDF$A$pL_>(OD>!$E{s|&Mb?rFV6 zwL+Fpw^yV4k>=;eo1&4V@&B6gfP5Hcf2a#63{RdPIAZAZmYo6S$`41r72a@tm~dID zw{jGiUHrLH-)=ZIFwqgVpjEt#NX`juFMzFBf%-TGnkoW|TnFoZ7Fo#RxAFJ5K$-p3 z)P_r)j>Q_A6q3OWMg=*~HbLJv;XP;4*&$3Qv3E4^)EKTF2Z_y!;SzID1Om}#B`PU2 z#rtciAGCl+3b3#-h5;AC6WZ5bSCD@<|0E|-a=INWBy{llK(I$WXX(nQ$d6~Hph85d ztWXb?SL%Js?(*-T`!!3`XGoRe{L-U9y47B9dP}|o9lr`S`ObWNF^3FBZ^LhNBD?za zkQo5i4-=VabLDKU&Z#_v6fFw5qPA;ogCqj3Z043t4zG@fIJBZ+Oa3B62=P>ugwFv> z{fJ{`Z(wK)FHB7wSxVn&cdh0OpY?G!Sexb9Qk``>b29|s>jt-G2>=|1fL;xg^Jo72 zA&+zHU#l$sC_~mqcjzq9Rr(WU}c+v!Y ze*)qLaD4!Gf=Al}lVu{)_yytE@k(*KA2GMVOnq_K-sZ>tz}0o=g$^Du?vB}$+;ZwkU9TFYlT6TJO;r|7a7VBZU)OsZdu zj$%V2l$`Vd(du!!G{Nf0(^$gwr9*who&~S``LWT!UryQk`Vf2|-N}m*LjZ^ODg<~o zwBlIGWSvclew>ldIYm>DfWO~pjtHt9i$+sLFoH{fj@ighfXaJck?qtNe+SKIPi{JR zFt?h!L#z8S`p<+zH$Jxi_0}dDLG0jnU}XXhMVT}p6jSMFp#&4s`Odm%DFA&~%2<}C zHw2vd|M}9VN$0fwioj*&w3%n1qoV`3&-u&$WyWFAC<3z!z^qPzu4+xq4fJ>rA15Lr z5*HT-2;#c#KA;QJ0Tx9N)kZCojGAS6FkAYA!ikI%-oc1zP?X+ZbzNsj0lW06V480U ziIdF>$6E=XpwqfU{JotnOSpPODZbq$qa1Xn?Rv%GR4}ygNc{H=obhCK+9fab%CxV; zZ+Ciw+k78gg`Q1=9(xR+ksfZ$_JfA!ZutG>QAtu5*-!}w*&XE5LVEIkZS( zdAVJ7d<_ANnfo9ls5(Ov% zv>1rqOK33rcSKBVgL&|bG`FG4TM%5D9c;w)jY1h0NrdKAD=b4&5C*l*e?!5&sYWN# z?Uxmn=i$n6^W?5IP&5rL_Yt~E{*`dgJqQjdnwYQ24R8Q6 z#kc!Y`TCt+@F+ML>{jtQ3Nbn0@(gvTv;lr1F6rL6BKi z^d-(11l&o_i3b0fSfkD(iD4hiJ0Do*4ckLqj~$hF4|gzEeNWJNWj(F@NyJq?6Ma;$ zfL4>eNP&ypTC6O~_~FtISpW!az7JHn+04XKBG}I?g}whcjyscl;t$L$&?QhLh7A)L zfXleD?v58(nz$ z3J5ipkebR>y0)FaYg7xqo=Xa3IGTP0iCBCV(ZZnYfn39iUfr9cY>uBO$aP@FtyJtq zeL~v*$;lW-Oe|Q@?!9n{-~yA@=BFo!N2-p1o+HGA2{Srvn@jNKH#j@P9kj43{ak&-3&wcUJ)Hln`Mos%onDH9Z(5tL z4j&Mn=nHU$)k^?_p2?Ta>&DuPA*`OE z!9!H}7=AMWHtsIj>q;(fx`Z0T~U&$j;`!citIXaM|m4yk3aO=n*XM-Wx>TU zFGSnhj4zg_6!;2_u~`Ozn#i>I65p?06p2qJz0`~%esvL03vLu~YH8S6b3B{e+~oSUe4roLqNrYT5vv`uLR`dXz1reSK7I#9P{GzQYOwS9((3Wh%okoIDWN*rQj)55L%iXV4zi%g|Zq6Ebyw84DT zWIx9jN&4qeQZgN6d0@Lbo)xc>3X1~8N?C~{#!MvsAP{wMImDMlJl}e0z7{KRnU6|{ zasggSL9i&T0wRt}q@ z(>WPn0(r!yUq9J+J$P`d(^*S}Y(L%-;Ng3Ema9{VZxbaJ?Q6ICwv#9#$`cN*q9i%@ zNAZ6~IP88M5ho74k&Gd=fpVTMsQoR}#irMq2S3Z8*t4zmDi(Ur`kKP#0Sp%I*i5>b zRC2v>AXw3VyC3NU$1uI5geKGj9SKP)jh*&SiZYc3EF${T<)qLSKB%UTz}DVuw}LYY z@fBAQT+$f|jN+Bsh2uNnd8Oz&FM87Fd3hU@0O1pH65s9;cQe!!R&j+SUhvRX7N~>8 z2xK)b9_cvNR4RRNU*``dGbz6ax#g(+rgDH8~bw5*Y5gBF3ohcC9VaV zhYwd!4*Ho<+Z0L~n*096TiqN{hr18>O8}3{!~$v-<=!Z$geW+%2rk5YX$P}LeSM5R z2?_*eFyEj=^U?MI)%fz<{PI^SlML6&q0Q1D8lG#t^Rdm#&ADu65Fe^8F^Zo-OLSW= zAkm(qJ7I$S%&S*bsXuCU-5P4}y&;LBbOCYhQ;W^XDqu~@ElMB^279m0IKBF<&SnGQ z*k)D5_EWRLh!~*J)L8=IA7rLlt6pMHrJg}1qI#1E#GY0&>9rX;wU1m>sAX&PN^mIo z#2a_u{~+gN7O zRw#q^Ih1ugtrqlVXC@*IMGdL6DVw(=$wHX z=*2`WW_PccdhszF5cF0D!bl6Wy>RUJoIis8KZ%fI z`&3Qn>xJBU#~%3Ff#2xedE-rF5l~IcB!61}k=cW1J}J-r_rlCfR3D}sx<}}zt-g3E zP!6yh)|uAoca&V;&AB!==VT8rp^tzslf!CSOmMm-9ReGL&sHQH2y@Z=j}*iOFu|1$ zl3Ggd{vxqR-%xwIwyXfltdAyf&jR<)eqDWY|0LP0oOhuRORl$BIUqX__CExjolB!A zvQ-kJ&c=3@#so-@+EijTA{bexr#pD~Z1L)CQ;kNjOqS|Ch9z@Vn@tb}TO4vko^AO1 z2Z+CqR;kVVx*^zlxVJa{5Ck7K;BmQEwASu+MsLT0CF){C7#>Aj%q(bSqY6NFpVS)YGBWmZSVCTgeqp7K>ixgE6Y%h>=3A7&r zq^!<=hk@DY_lDw4ABK?Wc$(YUW-r)2xl(0+aM8&amkV;BM0U~zo)?X%-IlpgxYIkJ zeCY9TU1)JwvNj0Zd!Lq{eM^N~(&@NB|GonHk$5C2y= zf-$#KlEVWejYQVMnqDH^=$ziw`%7)w_Gb6vX;@`*U?OUObk?DXK}o)+tWzsB_B#`1 zxFTPNT`)R)`?CW~db3*vQeF-W{ZO4fJn!BmKi(!W^lw)nWC_keH3IL6V@+4+V=qRJ!zDYvlz5kC&CGl! zY0OhCRfZn@?E{tqds$HN7pn9=NJQ>~Aec~e;yZHI#0U1>1Z&5^(Y-H`?|0eE!0Wqrc-%a;a-!cql&Dblm;BJ@%DE`&1V^0l1 z24TSQx$IJa*}ClO3TNk#NDOGU4WSN!Fh>`=#$gOqy{iDcvl#mUZWLU+kdPbV^XvkK z;@iyvF(en)2CG>b^C=1if-$5luQ5E6U*G=AH)yuE%53~`O#_k$7UO0!JWgyc$jZpq zdH){F{fmn$${|~cr~Ei(W^m4=0_>tH1!P9DJR#U15s(HO+w8wt1NF2KNUJ)%3K-uB zH>Q-uJQ++7Y_r=fyDm3ag;$h8$^3uCfVo1G89epCH9!lZX@S}3cRVGw6}l&I3W8jZ zUl@+SQ%gbwNI2l4gIrS5L;_T&lp~osf`SI49b!fet+7H4q6wnX6q_9fB5JklL?H)p{ zQg3cMo(32r#;+G|SJ3cY-43s$1D4u_AuLSs8oT8ng_d5u;>~IyQ4tr|R~>_{iOGjF z{&(9@)HRfWLgaQqxs_kGrZ^xPsr#>fsf~uk@|gkiyELztC*lgKxVVp$h;J`|X7+f+ zz7I&LmVv@_wloZbhb%S2*B$6djKpPr{z0&L_SlG1)SM}@U8<9<(!~)8ZmsU3fY%12 ztJ$bA;n-5Bli}1@X8PNOu~Z3o+y+2PKzUnD`>oQO5~jIJWYD zwg?(#JX@h+2NB&gFJF!&u1t*$6puiq?+XzQYQ5j}jbxE=8WI_8s&rE9fDwoWrCA}X zB9gE}$OA9srv^65SC9||)-_lUT7yPwY+X^XFn|fX*7wohM z(#*%&MLc=9pT|I;2egG$^6b+HE?^&>DY&oDL0&Md0%qq)p+jm}FzRRYo1&eO=ipWp zuy$g>Ep=+uM>@`JZQ=9^GT*Z|`gIDb(Zy?Yx=MZBC4yrgC=z7n}6dp1~g{sg} z?CYu4oZ@jl)43kt{E33WHIpM!D7_~h@g=yG&qJ^fSKx32njJ;~ z(PFV%C_iTggQ1I2JN8H)fa8yYHqMse$%egTvsK5~8^!P_UuH|Z+}N6H+S3Cu8>Zf= zcEk|fLx&W~5ef(=-xd8zVGdhC=s_hz3qadM6P5>pZy=07KwAvQ9v6>@e@1^zJwSN@ zaA+MCvwdJS6i^4B(On&n_Oy%xB{26!V+6O?T3g|D3pGgxF)-fvUPfv4ra4(OuD&pb z;+&iXfz@;y7(@cwqx&ScL6Eo+OdrNj3@Ir{5ig{by(y(lHd8Axh}U9e^p#1w>WO%; zFI;D8!iC%44?nxum2r3!DtYg+GlWSiC*XNzw90Lg#s3ix-e9p63r ze@WH^@UHwjVUp{Wnn<^JgHDxOxz?T}o17^iv%E+tW1cRwv8g^+l}Lta*NB>*d$-Pv z7yItRaMy4$qt**bl_~=A534gnSfXw_ot-Y<)A?%uX2afgr1yfTBu}+6xOVmC56g{F z;2S{3`Djk?6v?>Jgp$Kc@eA}X{E~JP$@eTQVGT?0)lLtwX`E)Fzh$4*Y|#7 zhG$W_{0DOP>XA?66jdf6m@_5?4bNbyLn{eK;1D{|JJi@?&m|;CS@$h<&Nbt8JWhN`+my7*(zyJMbBHfXA z2FL>0R_uDY{foK5RSpK@`%|Rm z<6h0i11rZX8$?1cV0PqUHfXEzM63%kk1QgsI()OlDV^5$$u44NwvERtcx{b=9Bh; z;>Bw8Gd+Q0VEgQTnI;vg3g%d-d^0ptT)Xo6;R7R+O4PKKH4yUL92HD^LX;_M;SiAS zpeJy+fBBbPKveGGFj&s{ljYymfgv)jpQ#1k&Xewh#N(gb&tEV8hRH~M zVwX7Mk-M)^%a++u1UeLP=6lUNb3$W>*-k#&nX%_2-Y-K@UNwgcse--_pTqt0*~z&<|5Y4Nq+K^%ZEdf59FC>~w?u6B0#j97jiT9lNf z7Ofpim6aN!f=}!n?zMc6u9`K+2Z+dAS;qt7bY&$eC5EdG~vgy=QK~iBVluI#bO%G;& zD;Gx>S}L&}Ck{Q!q~pYfRqC(JR%Jp`41Tt{gwf8VvhgzAz#L*%B-IR4$(R%JCMub7 zwD=pWG|&?Ed75ix?%FbJ9|CXk`8J#X@j zFi4z@P&2#z7PbFOp zx*j;m37EZ14u!-k>Meu@ujq_P1>#pEB*pmL_XBzO+}Xb($>_=(z9!Z){)aDC1MhB* z#cfMAc#xpoX=e~vJHT2BhXe+!f&Y}_&(qAt9T2;3m;WjwpiF#78RIG=%D&cm<&(%( zTi`I8&lKY_mDXTFOU{+_Hdy5ovhVL)K~5JcyXkZL?=8Kv(4S{n{y{!~20J#Qv6ZtKQu+8m{lKLUplnA4|0XY)8(40MCgQEU3*Rc-b22upujzasf{e>^Wv z+e>5dnLrbmC9XrzY`1=WJW;L6XjGwQGn_kFD?-6-0AiXQb9g(}?TX1a{%8Qo2AGg+ z5M2L-<)ONn^%szQFkjlI%(=5*|GR*eTXj4Q?jFF1v^sxL4m}&K&4p>9=)(Ap49B5w zgk1KnyL=s*ZKr?}_$TK$w-5JBekf8bQc1opj|)%*RA`0$Zi0&43=8ma-mOapbK}3~ z6TWGB#~!FXkc12;XWCet=}JAjzil}2w|E4kBo zcLY3!u&MDA6PH(XJ=a$HnA3| zSS^pB3WH=UfLLo(UDdFzf(HvsdX&>Y<*UW5llmNQD2)7?DQ>o37CY!C5pwS={ZCW4 z-Ou?bMo9FLVNAO$arYIxeB_B`u@Djm1pqlRkzkn`IFC@6fwk~ko?w)63|e~?-h(5OBQjyWa(2<&0=I?#rf{%IP^d>W+tF<1@&YmUauZY-0qj`pqU)Z6R$g$Hwo3y^GycI2nqI`%BN%>ig**@FfA%u2%=*%gf$v zaw@T}=kc#aauAK`Rfy5>T!lXbcB_rWqYA)!)nJ7L8hC1I5wRbllW4PmVw zZ9b2|EdKj}sl29tlTnm16yvXRA0@{t%jlhlw4nm_sGmh14 zWDkJT_N#a=vNH{cw(&4>5G1_CL#SfTNHku;&;x#Mg=hvjsZY{aZD@5$E$ZjL-{;wA z6tFRCC$80fXH9>#zedjN7xPt?WQP}ebN`OM4;B_*5*}^Krt3pL=0Tu|@wVU7)WJ?L z13m_^vNj*)G;l{0VN%BW@5NK96W)G=Ex1ePk}H5+O8b$igG$MmNbzv+MpHiYSAxdDO}wqK;p~%tbaK!X z$&8~t*b+Nab%v`*^^O}qHUaKYIp}=u+ae8*8nG~qt%*K8YDATLA zbP!C$X@ZAR_QSE`?5=Y}ifUL2WvZa^Pu3#3JkL>tMHhfq7OC#*MpuEOk`AEDi)7v5 zR`6LJ;gM^0M?Se7{MqpNd=2>=jc?+wOc<* zO=!VO@6)QAt5qDIuaLekP^7{{NnqazG$uG3)`C*(YT=%;oNmvv0K;RTrZ1g4FqS2RTkdJ zXeNSX0fs-orcC<0_k=2qQ`{p52Pfa>+qa*a;eEB-q8Mrj>%D5jndz1KnNAL=nfsK# zAbFxss4*%Ft)EkB+OgiD3rR*3{q~YL15h4#31~!NkjL-oE?+W+9~=TX5mT`D_QCuQ z+j6F+*>8u0yel<_25;YoKW*)4G~-bs3k<=Gc=$mPXgB5?EAI7n+;7a z*NfISGu!D6XiFsZJH5M^tkXXQ<9!M`nhFLH70BpC z(#Zvve~pM3tWBPuQ>Bx@Bt{D=M4^mH1XeEjB+PLM(;gZMn|kF46!p=D!~C|}%Lum0 zM8+`Qg+2R-SXw><4t;BOn8zd!adyjPL#z0`T&yI+e>9*@(lzy09MN!s76zm4YEL# z3m^xzu%ZFT+xkIa(7OsJ+H9NTO3FVKB+zrixP2fU3o zqE<0H>`~#YCcjbo9v;qyelb}}Mcx65d-rn)ncUrA6wWc`?Mib<0My{dMp%p9Ru3O{ zvimVji$eqy4%Pai+#X)$#~|hCWQs1YYdU~${Pu+>;{O&y%*ScB+yFARNVy%M zUJjts#gMif@zt!w?C~7v&W)uR?i&a_e^*~E49CnS7r7dW7cZa-Tix21snQnwuwO}T z^SQ70t}pw}ZpNO*Y0utE|8==x_3m6u430In!+Ce+e8)fxv<^N1A8VBU!eSf&&e)jN z!Kb{Y)z(-2+4(L3GSakNAngDd9LcbVe+rr&Z=<%h5V+C^^E{r^%C`fa%T&ohRAODZ zs#3f!S>fLJC=SzD8TYRG7ZqxSG&YO9fRE6Ujc>R+*V@IRw#U)? z1h=@`6@Vr?>0yGJ$5M0Ou_8}=BE9^QdmT@bpRagc#VfZI{txhV$wK}w{zI`{XJ=<% zknxPA3j327PY@@%BljG-ywAC-r5X9FSR)i6!#;`2Dvj4I92HrVNUa#%?a33>uN<3p zjF=SW{Dj!)l;rCPQL6*#^%fGZ@+1z%w&mmvVQe#)o6%BPhVG7H1`Pf3HWyjM1 zlBPPDWq{kbC1n?ikzz(}BCs-EOGk;B>L%OY*czd{RdCdZ*IwH*eJ4#`#HQQu21)HvAPVQyY~C z-;upmcV}#fN)IABtlLgKXcA2&&YTp?h<|r?aF(M*Is9Tba0ybq7{SYW-By2VsWCq# z#vHuYhHbU$D7{2ACSHzcD#zVw%}u8c20vf&cI^7lbf#$d9Jo-thNAKOnAi+8H1V7s zIln%zw|a9mnxk>}3ko<<2pB?L9yiNAKiCe0+vbX9fgN<%2!cC5-+YK9^|lB~b0igw733!=-qOQz$RsvVYk? zBPfaC{aNIG%GrnHuo$bpkgMl;fru(h(`cO}j(t;4=$LHy{&PrdTCxO{tngTeQE&xp z+)P>nAue;8k57w3ci|QDCC!vqXepMtqUXBo@XMAetFT@iNz;`Y0SenPq7Wfbp^j6aB_b-r3)L>~;sTRSc5q*8V zd&Fc7(wHtUcj(lN3E2(#Tn&L61-bWZTq4f2FFyv6n9nFQI^zAwZx zU@V!DHj1j=i2QwqkFfEs_u-GCn^UenCD#*Kt2P|FU1?Qj7<2Vn4l6=teLNH_LwYr1 zEOw+djPKgaTv(@7@^lS^(YF5pp+8+~B8h?EDVp>aEhSKAfp+ePrHJ{C#ETc#n&{e1 z-Wz5+H<7ll!mVwy@iRa#kRT0YH`zGw4fVKYPSw0!qG zL^}KOtor56*H=M&68YhN0mHH&_*B`{MKnShzuXc!-vpiJ$U_9Z_ut2}1DmPE;X=f3ZhN9vfJ*^-_#i@!5(aq3fTq$@kS zf|wwqs2s0Dt)}s($|r@Ft4DSC@+AxLs##iJn#&AE>V{#W9(5ex8|_F$G;?VbhA+wr zlgm9b^Wn9*i(7cF^OvvDB|B4|g=5br(zY_`RV?#xY z<#Hl7lL1I5?B}o&ZU6g@NlDfPF57Wxrf_E>ivu5%cC`ws{D&rHxQ8V8IrxR>B>bKa zSCIdH4xJHS8HOmF5--ESg1>c^b8YgBaUzZDWx%vc>c@cbmF81wg=mHJWP0Uqg6?Al z6VP40qX>uz@W>m#H9t6%mEg1O4-a>H_l{U0TbkZEs$yGhWGU;}!^NEaPIyP{dLXuB zPO{4mZezQ3JdJAL|2!8A zo%JWE=$qeXS*c!HeE0g(5*yHCI-?+(E9woQv_pME;1e`KFuLu--pkjhjs!I{ zmDLFp-nCId`FA!Ct|p?eQv~?;`uVdwE>wXEapBptd8G^0Q3K(%FE2-z{|Gn-C@B8a zbi=@Fwv;CBWQ!dwo5`nQ-UohU>TJZ_!hFV{_(@^zL(CXZbU7#J_X%FufJs>Xh*;tv4ucVsZB!PiP&^!gmZ0HYd>zTLxQWu+>E=%Iv~abnWxo zWj2_S7R`JJsuZ$6}w!&2B{V(fcJ8rDgTt8RM;FGx644ilUjpoEd-4MbVE6O4(B ze0q621(F9GBBBiNzAe^k1S&pjB9No{KHlgw+q-duR%zD$+Su4wS!oAU9tcZoehvYD zON4?@64#Efla0D8{iPr z7izLKAY`X)KhMC+syvPjM=c-Q)wMb|%kf%Nx@o9{u`G}V19!KDNTEhoWv{2bT(I29 z?N5SM11sO|*jpf84JSy-U1OB+!I%+Y{y5 zt0}&rc62|S&8;_`n*T_2)2+cgJsROMnJFtM_x(Hm(=*^o@S?`L*eQBGVn^Fb`S|*R z7e*g|P7f$~81y?lL22pX2T>bNw1L1V`2mbspx$_ay8t4E0{?7kNL&ekAzU92>tKHc zdkGJCdI8L$;1!C6K9X1IG}bqfT<0TRnZ1KKkF)$d#*Dd?rOvo-1oTkeTr+ftUDSA- z8Y80Rk&`39_eKbnZhOfF2jU53$*0Db>!te=KcJH#Yk9*;cX}6R6#eQ$tJKa#0K?cf zoVtVYbVflz-QAJMnXY(mc3|ZNxvl??tgniyvg^Vnq>(Nu>2B$k?nb(i?(S|Sr5iTg z-6-ANN=P?IH+t6hpK-3vrDNd5yT@8{%{iYcvR<~TK*^qhhQ*Krn{juIs5<-nwixXd z5$truTX@F2!ykSh@qevm2{`vvS%(a@9LEVZY(i~KNJ`{K?0lmg0_SYGCIhNbIfsKp z$Y!H+xy!xM`u3Q$@>52@>tcshqWif%C!EW+1Sga42u4F-V1utG=N4vMu?ji2G}>J+ ztXbg)*{foDY07wiKR*geN?e*55Vjjn%$KA!1y#VTT_^e^J(f)W!E%Zi-S_1ghUd2K zvgBiJG*$E}oGZf;mQGT|HcY`auh<@*VPOpM>0@uGd2h%F_whlV^>MsI~ZhH%K-~W+PFM*C=_poIxzx;P#YfpytT-YaW z%4HKM!@I-a7fJHQ&RADw`S0&mxn|FI zU=wy2-ZvdzZkSW95lycd6HHVk3eBy>!tH7?<$=+16KFl}a-q)W+VK55lOLL&?qG~U zvkf3)aCRy8xbt~TWaFg2sg(mNXZZ#QeWxdflLq+7w!90eeARIF_VxhZ<>OyQkaOa& z+EU&0sa>T&4B#g>b;Cbc$#^cQ@pC#=3t7?~+=--3nP>fo!@=FtwJc32@d|HOA;o(q z>-Hy3kPkF6d4l9c%fTIOe5QMHoL$Xc&Ua(DYD#)b0AUkeDW)I!y0M}Ecs0@Od;DV^ zR@nV8NX~G+WYpfET|)gL!;2b!CQgbP`ayeBlnld|yIF#xC92uan^@)JpA8zOVJv2g ze=mI83=DtI^vo3>FA6S~n0HbbOI!~WXqD2@NjYH&L2diI&Oh$>LnoD`c`DB_M<^?u zANS)_6y`1f@VkA#r6pk4r@-arM*3CJQ9XXaxA&`l$>#4CDj z_CYy| zYYgpw*7Y{nXTg!3jbL7bf%p1A5uE+=HFn_uJHNkz=RZGePH0E3?$3}H2}VvUP$-0u z44O4JPRz6xdHnnP3djZZOqEo=eYCJi;Smv6M!;3fR7E9WAf8FPjtoreE$gDnFDPQw zs{W&84x!>!P}IarU&q}l?)jSyEiEhSJ)5D287IPNp_Teu>_JR2AY-m&awVVXB(jP$ z#zr9)DiS3_BcK`=%_^fQMq3y{HHwymq64#(g+AwtM^`g&_2c7hLw)wG%TNCN=Gka70YjqO{@0@i=j*?(`#A!jWa%x{ zG*@Yx015PovWSl5Bn231hvKM>TMiO99Wno z5NuLX2RgMk?JRVhbuOGIVex6Ku}(wB%cbAYx_H+Qir&S^*?{devtd_TU$I}!+yVft zLEblF)?Lu>4-Px&+oMk+vTJACo_MRK$sU>Piz!=JTWX^+Wo-C0+o&j%-yh*;(b&*m zbPCdqaHQiB9^mj+Xyal9ehFRj5)Ddckw6HqpUis8tc@ zm0{?zAy&aer8A_UB*01}vr{7E!P5@>&U=e!JeFn&oTh9R3t?eZsY^wn@kWpzkm*pg zZP$1Q06=)X4;`%o;$3PD?e%{M|D6`u@i>2Ja5S2jg#cgR7~#ObJGUpZ_kRL??oQ`d zTb;7_+`5H*mk^gbfL?cg*8O4&Do>}u$@849+I3rpHg4q2cU0grO5G5kxR$VSKt%+8 zOF$$;Mnn6QE@W_gV-NhT#UoGw{(rAB92i{UHubEY zZ+4duuO1TA@`k&iU?h-__*pdVlE)P@j4F$WPdjr?pmt0c3WEqure;4uC;6^0au z;?m(R9zra$6iYPEWn1We-@^xoOozK`K6ay-px(x&*RZSgQR(cLTPVES-xnq)rEVX$ zKO4I}!MmWMJX{VmSr4F#U|b*QrLlznGY$N=4ua284LT$&*S_$V-*hEGy>?!47KHDD*K`SsUgG5h3k*oU&C)(!}A3 zfz5EwqKMZ_c2V8HtY0b>X&jjoFvS6;&T6@$k_OOrhtXx5ILQZ3HXSY975>gBXg!D11 zt)nh`37vg?;Z1%)xU)E)_7U@9ow|@%VIsh4VGJb91w7+X`^emT!0`nkbde#DA)vTG zQ9;qxks&}ql;1bV}l6GhBN6h-t4h(IMacY?xgh2w*gq4=n@-ocr#alH>J zlHKuwexn6W5FXwxl+R@dD7A(Ouw@b8?;L}ipj?7nq1>HhsmTzgh>1x~qu1f{bWz&+ z`cR$RK!feLQ3eU9|Ds)M^aCB0>Uz)Yd@UNQhR)4VutuV%9R7irCvGNFVRJvMGVf3- z=O1CFOVcVyssgHt_^US{4NmF(`}Z5<uKe*HQ zNTI*CoGEm$QJOlT`%MIcjF8R1Et4j`XZ&3_m z>G_C~{+OYIm{?Y;Tc6RS)5q)G=lg+^<*2pub;?>JT2_5B8X4Fk!=7+W!G&i+?Eyw2lQ*&n0}U^RlZJCXiz zBIj8%q0!>4O})v-saXg(?&lk?dI{LrW)Bx1E9Mb?L#>9W@8&MHPxO4j2z(qoj_}a> zPEjfKmR}mp{`Es}dWQ$~mRpYCyDwiR<}{gFF;7OZDHB|~eJaY+iHp5NRg8@A&O4~u zT&8B5Isxzi`c{yI-o?P@2GZ&R0s=NRHh>-ofG|BqZ!{{6K!pMS_g3xo!_(c_iAj8* z5iiMNnz`n@0}dptkjxIMxb((ASq=ANoQ#EID~0DZjZQN|7TKyrjS=nn8o9XmXadI7 z0MgZkiOV$U@w7;}`$^gF00>mf{xpbfC@EDcmX2*eBQSnC7bwwUEpfF3JcJT&*Al>A zv`}o3!)?*$Ymq=&nnrg=oiFP3+Q}rN6^AdX9!oolN;6o0WR9mN8JVlNZ=hqitf)xzym@`1wGIDqA>U&2JwyN$q!+bw}Xu zhtqeWXq&MgmG(m-FWa0E#c*oslhTP$cIP^{;3A;}OAK6~qe381`7Vys$qN3e!*N!^ zwRjQNeL83F#EBi_Cm_3Z{$tBU8P>VImWZ zR<-?)4Uo%NI;4_&5r&m1mkd3?;V$e@tI}wDR`cV(UvbZR%$x(sWUgj{^n0BjpDxXx zBypu0{p?y+tu{7n3{lOB0eHB2;CZQ-SqC0C5`MPz4t8MwC?3HEk)98QpY^`VkJAQ@ zh<1nfzsnV~%18vtUZ2a&hDSbFj>xBt5b=y4ppRHiNAWn$IAyG8i)nNB`^#>n;9B&A zB{C|UuYK*H)C#k97{O@jLYr&tiwEl%QMa>Ib*OCJbkj>{;|vaJ9;*b`e+tx`TqZDm zN@=P59hg1Y6A_b8;9cO8ENtn@-iE<{N@_OKcq@_IN%Jsy+sXR`si#{y0py1&qTC4vRQn4))FChuLBj8)Ns=kt#juvtN=V zf-8(XdASYOKo#kaaEFs4-vy;(syvlT9o+fy%J)FmiY{%17BP73 z*U(R?6@z0UCN5%g$r*tYn}e6iq-x@wZ;%-i%jI?yV&!r2=`GUkg~85vK&b@zmFM?eK4{G6J&GOZ2(E3%iY+?hOJw&W1q~4V@>Mt`~=O zs^`51z6=T`$e?2t7VgQz3xIDTiWTE?C*{Qm4CH1@kR788zdYSEmsa=iBx2D4`9m$>vDB~dfXMHI^U5eV-oj|%%7Cou>?vI24+RT zbFG$;uft@*!gP(-JancM9ipE_6Xus&5=N=jr0sO`*jQj7puwU0W211p(LhGM4oJlz zd+xSNR#9rLj+B`0ppW(2a0@M|G2;0=8WN;9FY8cWFH?q2)ZspUs9{}2ML~f&7*pWf zFDlfc$<#%nJV3wlZrVyYWpbKoLsAWqN&bz!ENFX=r^hI{R^x(NU!k%rQ{>FgY@KFVBLXs11 z^f>Z;)ye@et>5A`y3IE0-!=(#rw$m{ z3_)-GjhM>I;rBAhT%I+H+aP1_ea^5&pDC6i!-5<;-9{5wNS1$yWH8lH(a?KR zkc6!}e`7W5y12Yl`V&P^yOA0S+$Ed?`()RtvpA7Lh#e{I}V_i*-zbEd^3M^1mX zhrqRe!Ix!bdzg5~VX0K(WTGT{KQmh%ii(SO_g#^wiOqha%S$!4PpPO4EeLbGd)U#u zsKCRXUmRXhAtRn7uIk@L1CL6k`nB(;x-2^bCjQTM-9XnOwlr^2yKY(N zsuHE*VDU_D_j9LnQutb((4~jvnn@{%vMPjr{|U?KLYrkNDJkH@*n0&37ysF;-+jQY zTw>Bx6cPZ85ZJ*6=BAuoi={=01at!R>7}+>SoyEVi>!08eMLdqW8Ih7)WqvUU??qD zDF}%y5iFor#Ej;wn08P^JqdIw)F>uMq5E$o>*l(gPcfJL&I~T;IX1|@G{d7AZl|>Mqg||MP>1@j-yL0M3tDD zqApfKwm#MxTCX;QbsN;ftiu;BBD82$QH5yN93Ljh@Dh4=0reuF{`si=pw);kVyjTr zz{bWiu|pUwZyQlU(P>L^C^0D9oDN;-e>v0R<|R;UdW$9%q4KZF^s@Q8>w%1sk$HBpP5vG?ruLjZb-=UI(KZrhGGZ&T5Wc6 ztFQ?6{kzq#Tr4*WmN)n;1GZ@e`%{v9ZZBS9^TfO^R9LOGdX}o`LT1#o<)^>G`Ax+m ztSTRau@@l-3^KVwwk}`w@-)~}i3JJXx!c%pp*e4fxkaGr-=8P@#)_?WYS|7Xxr$Kr zI+>qzcwKG-C7joPABmnw!vA7QGgc=2vRYxyE~l>3Ho*}`9R5Sb1PxubQv?oUkSLil zzoGoL_k;VE*st*~u=_r@a^FII9%isGf|fkr3o9_t+L$24Er*7OVf<`tq?S{;|1;dj z+?%C%$wg-v6_Vv6XleqjsV^o&Ti)qu7K2v|@cpU0csv?zN&_s58kKw_?#)U}dl=PRlVN(9g#`Cpe5O6JE6A@=<{ z|0(|P0QGiGIWM3|5zi04_Z~G~yA2f%^Lo1Oi#9qb!RzbK5V)TLo?o@2!oT56&Dto= z8Z;wQpZtBDtlRljjBY0>Y!WiZUFde_cQugC`d+Ub3v#>G0*j#XXuB&zyT`i6>3)_8 z^3-a~q~#*N>--3?QoA1f;#?8f;1RXw=Ak@?`XXlI`xWeuLDY5Xe;@cohKVat7eFuGqff&T*jitpwz64jjQGSPmc-@%=j& zpb_36k$)?#C}b*A*a5(+K8^gFpS_p}k>wz3vV(O2zU~kA(+p63Jio~xN(Jp5QqF&JF}WAM3*o-Y7>RKp zH#Naakz$gT%mpKSOezqYueZCF(*F7Hoc5usokfYIOKoYTM8133uKmFrn)|7^k8ivO zog!Cb!!>OBd=)<<`~G;aE1-Jx*F^mLXyBOD6Iv{v_*hz*O4wJDdr{`hj$8vrhP?|U zRjTnW`wDaB9R2v=a0+%lW~rzT7$zTOH5B_o${H=rTz8GfQ^T=8Zx^@Jcp&BAL37(Z zfIhF;))EO_dUdcR)&{Bmq0I$O(H)5QKH1(x8f1pNo-N0R_47H2>WRErv1_#0zGNqy zU07?ENh?0;I{N3Hg9=cxi{tBa11y902MngvibhPOlJYAD4WGwz`CNy--3t{+9U+AYU3ES=}*JLELI&1ws6OX8fwYku%HQ@la&)Ih3)W93?0`L^OaO7QZ#>1kh zcZo|4#7d)@J!|>wbETEVk_;qX!XnYm7 zz-Mr02$Npj#rJOHGxw^_9LLUs^8yixQ05GIBRWw89%@8bdQw^;5hdOy7aDnGU4M|Ot;aTNn3E*fWAcU=q0yh*2=-7inpTKe6ph0P1U)n)fK%3NUk8O` zo9(hpY&Of^CzQuBe8!=TAIkg;ZSAuQ{lsvGFoB5ZJO~IMgoVNG0MA4nUHG?sTth52 zZPmLEE_DSXBee!%U$s3t!)lQ0FSIuE(1_Ve(ojU2S> z!UpNm_;vW7aYxE4%i2saDI<^NfE+klE@cIWUS+h**{nqp1wOsP-?v1aw!}9m}=9m#btgrY0i7{I-aaZHj44hJJWXr+=VD zIW0(~lP{dwKN*LI=cuvCKTRboGCNcOi`d?>>v8-rdqCZE+*qMqG{7O^=u>?H5t&*}8_!A`&-gZ;nKGUb z4BH_Cl9clReemDMq^r9K

fp*S+nly&Ytn&6n5NC0Lk*<4#k_5;@4&n0YR*O7!#t7$o2$EdE z((8OFYqc(>Q!YB`iz$x~JtxWDhrfWfhee%EA-Ph=W^cIS~UsyED4s=NwmsI!*Pj`Xo=5vs+}IHw#!3+!>Hdp*5qcr zRw!AIf=2*ojV#)tlR5I!xr+Y(gt)A+_#BA&T&Vc$2>7fp;L_jJ0eunN=0XdzDkK7T zPI0NqY5`bkA=X1RLA64`j3+-L2Sb@%c;wMeYavdgV?q<jm3CJ~a@) zn7lVuX3#KZ)cT7YT$lHjh(j@pgIRCReszw7e}q{K6Rl8m)42;j zQ+i1uWXEQ?r1A5P!|x@$Vq;IATZ*lP9N{yi`Vng2Y(vuC=6RT3pjvvlC(loZc%GY{ z)Z4BuF_|g((m0yVWIeWcoQD=g{Tdu+fdYsF5R1vo+@e27v3=dD{w;%a)G5?e%X6;b zBrJI4b3Wg6()!Vn_p${1(!;up+Bu%@s{8+_wlViq{A&JrbCjcSA6hviaua4?5M4rQ zSROgfMXNMmJ~aW4AfUm{$B0odh9%1Q;$==%!Q1T@eWMjms&l?Bep_a{%#_BW6Y!b> zMN_5ojn55Hv*zx+87$&$bh5ZHPnHUfm%vQ{_hnk-8wy_jujMM8-J7G`Wcr0Lq%sa} zKi-NY|9g_fR@QY0!g?`EU#Z7gP|o50BuE@p39t6Br(sJ7u6}rMDwbo1hE|v@Y|49Y zkPlVSx;rrn!_r3`8mNg66I?!5EY3B=q|-*s2gR!sBq}0OBp>NdXOKy6lv|?_U7;3^ zj7(v>NO8PGO~~EEZEb2l+xIldvxG)cWzeAw%(0&CsNvD5z}96(z=Mh1A^S5hw0pcl z_50fsJP-o61V%~VmVev&n~4C1$G*XC-R5Wee3xhKh9z+;OVS@2!%P#!G+u;VAlq_yIk3Dt|N)D`)UvjDDSWT$9 zaQQfa;pdj+Q3+$vZqp zcaS1cO6EzUY#XND;w>B>+EtsI>RS}|HTxhe;C2Z5eQ*)6lGwfn!v!X2m(yyzN76b5 z&*4aFY^83><3(?kfquJbFf8coWXo`Da8*_JUG`L<&t@U46oIOp7zFs1VS({cQEyS6 zuWqa-UY}=q9HoH6)aBJ){K0gfpeGCP{$Zt69{PK$^>VpW0+D8ZzR&Xf!|k|gLCA$1 zEM56&HwJgeD1aTf=Ge8IEs_Ba}pauY^XbfJPvCclIT- z)SyF!gkQyeHR+;pGBXi)Rk$A~aM>g*RwSk{e%l-W2If3yXpMT)rXM1(80qxbC`4lk z(ChF}!B8;_V#XC3`oEfp>-hb=`XVqez@{wQ>I?ob#)wA6Ku_;Rf>j|1vy zOhw??FI5r&HG@tyA>TsrP*`HN9!|Hi&l3cuzs?dacS^N^^X@* zgZ8-wpXSeJy7G$^O|3kwZsnh+Nw0%p_bH_(0$;<)*r*2Fj*{p(7XU9GNqlp@bO->+ zCMHJY7{-d4q2bH9tL0XLr*#?dRdWVk;$>^>x^+pc?%hqPJcE&-<}-E zKIP6tmJqW?)WPhy#pov)n3T#vOGjZlF+7C-n=6=sgJH9Oa%=LdH4+&rZ~ATT;(H%Q zXOugc7~1I)?&gM$NNtkdO;Wwk4}BoFf}&*ArfrNJ9IRko6p?Vf8BFczP-80jN!|EM zJdb$Ibb6wYD@|skO>>xbAF=aRpJjgBQnjoX%J9L@3z1IvssycZx0}sgWkbWYo?xlj zlYa-(^?AaBuqa`XL_wTEJVE@Vf@~Y@W^d4-3888DJg3}_lac7)wBe%Q$ef1JuJZzQ z0cibl8TomUVLS#m$|=Y-$fHD|-eN3_*JfK{Knx=N4;CgkjqMH0$Ny++TsC1N6(074 z0Fp+Ds?_JBfrd$Br}0w){O1~dCKY}s!kNqtjC2m_CsEYkI;0g0yST_6wc?qn9+ve{ z?a+Vk_~}NL?8&@mlPRIq)K+DYmNBCM6zX<3V=`AH8>9x{rVz)w|Heujtj}*_V^sNT z>(o*B!jN6{UsD4alG{X~giZ3UGd@`J5xK>$8Fq_}-F11lueQoYGi2A5M;gIC?w*&G z)9ROdo}^N1v7n_h3+juHct6f%C+vgwxSBiBDahIXi41$>Y*nQ4J5FM&ZIE)n<#yu_ z5rYbx+wDOF>NssB%#%e%vyCph#R_wc1=Q^WhzsQGvvx zXa4CI-|UYp!}mT(#S}M|i8{Kmo{z>Zvqi#avyAsXP`X~KE-P(!AYrht*0kow&^Yf0`crL&_20 zMS$c>wPHCgiwOdBvlq|4^D^NtgD~iN-wCK2VRk&q9C*tqT%vIHFG3v<_v_i_stE~a ztKRMG4Zi*rC?;ta@)mn|c7;Q6i6`Z&?YmSI`hNH(3)@1Qv|HjX%ky0OYIkca+2r^4 zMT}w!%1N*soa_BYixz=V(r9g*cs#`QPK)xOv42F~ zo-bYb)qJGizOvd1k@#9vctjWHeXX+Wvdq%Bl!E;*+#_0IrTQr{Q$+!FE-Qt;pLg!v z=%s_4+Lp{z&OpEF+dA*-eGuUQ96oAuLN*p zRAOE>y%xJVzS;XO?`w;j!&&ezBvjO!nT5cN5~sIvC#K0IjHe4?Xo-FLqoP9hg3Ul% z1p}KH@pxgPwl0o6)a_eT%Zl(0BtQQ^U#po8Eh`_^65IUM+xnB)^nwtm`V>WZi{-4f zSwo_t*_W$E&Buq<+X{r`kWN5w`f#bjXe^O*23K5xc%t_C3VS6(oc2q2qh!@AWD>w> zfIL6+<6+J~jNEjKFDp(#+8&dUY9N{BEsq~>x%hisk$7^Ix~$n|u>!1lF^fgCCIu^jeV@y&j3MpL$w{YiFO2kW{aQmIbj8 zLAq=VcRDHSroO2~(?o-=VAfw9Dhv{Gp(nYz=%fjM|BjF|a3(L*pn1IVXE5Sxb#RKt zwbe7;cqg>0q35w|z0vfO4vz?!$a~N1;d`-(eXhJkT?mnI^2x7;lU zdbOevknfALFUQJS3p~cIjE>ejJptcBh;t8#IDz`{O^j>d)RHm-AtD_UUVACqa-TXQ zRoFygD5Fl2|D8fV|4KNDIoO36lM!KF#={8{@ZZ-@xO`)uUO{dSwWSgZoy=-+2u4pBXkq=I=PJlb zRidZ~6}@hchbJqf>LE+x_pbFOe-o<|ZjVsQSo z1_%`t@{Zx*P*O}lLyyeMsvqGCI|3lO5}T+pC59A*(x}_VsD)|o&vcjHJ4*Ga&j~!Q z?KMCdtE6YSO04C5(nC(Y(zsrx&eflMxA?lehFYiQ1Gvs24Wf`s6_j`ES z9sTBedpsDp3d+x)wRZJlxfGDG-IE7Gw@=Aq|B)#kIlk_0B=PX@B9r!sg}3Kw@*Wi$ zY2c`~vY?dPpL~*gY>_aK+;TdGL)nH}@wqQ?-jeGmAI@XpQxq}@i-edkw!1h3H``TA zfq*q++G>Aa!u-)#mIC|gAxxjwON5Foz$UVZ1!i4(&}hT)T9aPAs=aS(67v9?z@5ox)xJ%dVj0^onl6FkO;sP?ueC4u5*ZwJfcAPcU!*(y#aix7g2>;f z0jmB8Xu0yW1#Bsauy#{PZc8Oa;=C~D#|CP3ni|kNd_3LnlDAr=+LotF$0Z@zHwx4N z2))luelzFM%dtZyHA-fG*_zi!#C|bWpMY1hMvIXY`M6v~lOCGQ{9i4_K@khMrd#-L zHthR@BJeUmB@Bj@Ex?d3Sz6cZgwOwKI=I51xm)v20Z&~wsk1mVsy@6Pd<-z~^_lCY zy(yyK+X>=I!fjVYOZt@FkH4j*44m~k+p~BQT`hV;)^Y@jbcy;5B&)n1jC`kf{rOYK zSYVRX+RJHC$+pK*5|#AIY?dg%fR1frtf#74!_{@+gCHC)&spk(go21r25~T`URpv@ zHi*Wu6NSpU_*4+0+4%-_I$O3xVf1X(a*?ojdwT*P#Q_0TRx}VXay&zriQi@EwHrU; z|6`!3hD3i|7;w|T>5nMb*qh9v2`4F|Qc@qa#VqWtmtF!Miqc;Rwq);fXZW#}pJd~z zMi!N^rw-hU*p}N%tvlOyhDRqd+L3WrmTMO^!Y?Jlps~<^&VozmxdyaNmZ#rRFE!D zfAZdkX=CYn&T2?J>;sP^C$zw)(PJ9~2JcyohDNspCwBrM3`ZAv*&Myio#~|_$DBl7 z(3Q8c-D9r)?}O-ntqsNE2)+<;n`?g5QdN)t!vLf3mN-hqW|pGQL4CTWGKmP2Bvz^e zirBC%-+qviq7Rh3lap~_e;em`_FZC1KV=OKzr_l-^R?4zy*v`G(uc8Vu>qK4nUoj- zubE?(ukY+6_dRxgelQmTk$7`7{lP?khTr2xPkIf6>|ph#B)G;AvqNo6WJ<0e z*V_?=W5sE==z2Z`V4D2^kJInGnoqGW7rk)vs?t8W=9X*83I-&aq8jGn)+ff37>wR9}-KKKt`SS4H~{p%D3?YpGnL6^YvVP z0K&k=AJ6}+5>5F|B&g+Vtu=zh5%|e6oM3}k#c(qpWG0S^ogM%oqwu};J77GIak!o}4r*h6>g_mUK@(luy>1cC%9;?sG{ z`Ydqw8r?n$xq{hANXu98_44@qt`_H8;@?)qn5+k|Jdol^xoE4Dn>x(-33D*o=F{}6 z2ERe>`El=Q#l=vUYa~Si zP@|tA2G5hNju0Yl3H1$t3Qma3dG|)2QLwhclGQky!5c2dzi+k4$?xW=gEYl;hE3-YT^&fD^zE+Vj9_NSYxD#>O1geSh|+0H7<(PT ztXw6gcC$?r24PvV&fsAwn88G8tf`Zas?Eo!-{^`4IilsNp)jJU7^b7k9Vm*@LY&3x z|NR6YLqHI0*}k0!6}ZoEo-I79wo0X|hx6sJ*Ne@aaS#g9-DpJhHa2RpqL^oJ+0t#i z2=Zro{mpK34i)rHTI>D~IM(e-&*hFK70y1N4Ygj+EH}tv){0}+P6%yv)Vm4!w|Nqd z?0g~AZ2JLhjRCU+79lAhfGKGBaCZ0ZY`;HpXF4~wJwWLA@fy8ru$YJ?%|k$%S$F1W z4hRHo9ngjScp32cu9|R;_crs1k?KD43l}R*z9p0>r{f;B)=ggO@7vHS7uz2NA>P-C z)74mFo&``7i)LNU{Yky1cZhxr(@R%^!Bpk ziB80@AU$q!E>w^2PEYqqrR>zq&xZNl57AD9G_}zVG;}U0h@Al2tupx`#ZmdgJsG}# zz~lo|33Z&k{|Y*PQeTn?{TJ5f4KSaMgwdEULn%6JPrdOjUJ7($zem`<%#jJAAPsYc_9c|BNELGBBiic zp>VkkR##=IpXH4%2DAAx3MG$vL_0phRu~9W7>U@NYTFExr<-`WUxHzs_xVar+r?l0^a*vib2?rTiYA|Ae`v%{VyV#suyf z>pkCbk`*p}%e-uXs)Jts%+lJ_Nv0~yIF%JSRj~Rh!M7)27J))R zn(1^dbvYGyA8TCC6ac2i1hbwlSynQu^3&riQaG!?&E8J`-sE^HF#D^W;2R_6z2EgIRFDl%ZU*oA9D}QD7fJftp#@f_F3xWa`!Yd{))B#{Wi+kys8~;)_Y){+CoaR zijgT&^?%TmDPkM8_2x_(Ai5zyi&8;Wn>b#?VF{P*C%SX=Y*JG;Eg=<*2H-+vY``nm zr<4?*xHq&;d=}H(v;^9Nz(QhcD7I|A6moy|^m% z1)45qji||_!S9DC95_%4pr@V8RQQ7Dwp??QK)wLr6aY+uD46@-5U%K0!ddk9x?n?g zp^qN}K|R)?fnMga9Rg~$k8w-OP__iW2zOb4j(QfjRD3)~`l@a~# z^QLk;2dAxf!$%Q&&b81}*ue0TYt}F_Ma3-HDl0Fly>sBoZT#C*RUy5!F3@woHUl@eT!}wOuhw#wlr;JYTfb{XXay79 zS87Ts@u9=v-#!r)Q^}b)aNbJTe3Sh0wPlPVHr2LRe%Sq(syR%q!;WHJlGqrc&E5iZ zlrN7!L2uUL82|WszXC9pe-D&=0fM*do*Kh(V0Qmc?Fl-2TJ(c6`^fKIU2WNXe4=S! zxe(xA;_utxXykKaWwXTOa-`|q1mLz#|Es^q5>!i|p6sb@`#$ux-UIsBW z6Vn$%zcnI7I_ZYir;~psG!uv4cL^{Y5XkY#s zXj)prpM7GzqPtynOophXpQ%`oHWg+0TvTCHD0170%ELvX6*oETuXTUX)d0_OO~vG1 zXVlKHv3_>BDkZ<|r@P}ttH&MVpkAYHj^E$y0UUu0faIHTR;r-+baot3oP3Q?c!j+& z)E-sY&Qu=pw+503mMZ1ftMglNsVHMoM-Y3dH>8-A=tee{%OGiJFRL z7t=Z5G6X>}YX)_d8G()1Y`D;7H5&U{i!h+YyZ9g z$oeaMwVePoKI2w+R6=m=xxO4YB@UiQXEy7S24Y>b49N9vMBa9tl|ZhQ$MHFacHCDi z4-m9xd!vv@Q3}Ha+ti9mKZJHbQp4%Eyy^&w!;0C$6@|9efB?K23Vyv~R+l!dj?Hze zPsY$;wNS0Fuc4Cr9q$YxRh_FP>ZhzS4#eq}PJ9x3pwr9b`=Hg#&}f^6n_zrt>hk2~ zGJsg2#oD1r)S*ODA_lkgJ8v=*mrrTsRwsPIumXqUjnzi>(OfvGV0tEJ^wSaTRqO94 z`_(9jbTvSI!5!_9?I%&o7r-Slj58fZYhqq`3wA**pRuKv%zIXxNH@`%Y<0xK$eZ-#q6u;v*dK4T`o7fC zDi?a2RO`;_W>NY-h3$9lO-%{~RB7VvXw@_8U}cHI!0TyNuZCU_FE#+Pm6sRuc3kMH z?}3g1R|77$6?+fPjGJSC*%1Nku@FG1DIhsvV==07Ur z>Pdcgg6cG`cc>#0bpAf)+mh8^{U0({6DjlNOZJ{_9wXm}+>i-st*ZImoJ3B1U^SQv zLl1WR-Tgtt%Q$%Ycjq!PMhXwBfO`e-$`{WQE^++P%xx`(0LNY|S5OO!wR)>FnVZ9? zpANTMsTFU%ntHyT1%ie%`M&8lgz2}&1;q=w4*6V{?Cr_RD@?)z+qLGw z=CfeQ;5Ko%Mf`~j1{N0NbDfV~<<8`lXf&ZEXkXQGt&Sk!c9TIB1E)GkI%=GVtz~Vy zUFsj@maYCEd=;$CYg|6lFvwj;-pv%?n0pwWK`I!Y|ESVmociC4Bna>{$VJ7v{|%iB zy~s|j`&3JVrCaZ#!S{4e+uhyXXbGW)f(>Bq>ze>*l$cl*0-83DJuu>adbft_Js9<>KN0DcEK+FNkN;6uQ*?P_!StFaF;J?Bhu-l^>ZOlOOLIUmba= zrMA-PFG(t|P;4)&xb=;MiE(m-qpcw*Iz+|w{12dEJ#2aD8U z*b>)4>|ys)wN+c7Jqni+V@x0T9qOT&)JvLJE0!sOB)1L?yRo!X_RujDY@(>uqrz+P z|Go6e!)aog%BII5`z9k}j?a$le0}!;*oiEC+Y>5KMvNS%(>aZZ979?xy((7-%wx=e zq~;VZ)R`Em$}KElBloi@_KIvt&xqJh6#uv7UO_|@T>yArfvMf9lqfQ=<5RhB?76T$9k(PFQsX1Z3O3+)64 z1x5VXm-r$D{r!Y;p01cUGZYmdiP#mu`L5=}aM`4F)d3 z#G+bv#F9&kg~d$D;lXMA^yj5~+7K|U^xTa?V)^}zHue6`q=%zn#@Ktk6VxDnR#t~o z?Hs%5OP}DkM2LEEYRezEXEEisT@ZZ_xIU%&T@%#&6B570EzHp8nqp zQ%AO@iG)qcV5wzNL%Z6BGnUirm8{$H6~`UgPV4yRlOFP!QFcvrM7DN0mRjiVAGLgP zIRciqcl%H-8mixA^!%pN3+8XILwgsh-d!2CxzbKqBaO$lBww&mQbH;<3SM7stdx4W zY*rG0mf!zgiKJLxBJ6RNlIn@yX90P6@Bc9MRZ&@X(bj-;cT0CS(t>nIcXvs53xae> zcXxx7APv$WE#2MS{QEoST>N7&xL|PczR$B`tvTnK6Wk;@{uHzd`LJk`!WBT=6M?PQ z9pu{KEB|Cg5;=7bEB0#(g%v%9k@C}y0Yx>)QmKw)zj|u0E zARM%LgO1EpPPm84&5gxqBFdauOlmDp4C#!yya}5+lP^2N@}P`qb63j|?i-Asv!0d* z8X4;;M7ZH!;7(9h=@jQBXJ=*vJHar$}PR1*?P(#G~q`wKpiC_Mj)S@%m!pb2gXt%a?$s+X}SSA7Y^^y+2=?Z0F;2f%@+! z>cinAxtR;Uc|@hC^Cj)>g56)Jg|29Jk7|-I&#U78r3@kt@g+%o1365RS7Ej|CXJ}@ z827gz$ox)U>khXO=Ub*rZT-${tzXy=l`$mIz8V`ArG_~O$l}5kF^e&d?X51H{Sm;B zBLRg_YpJmTIByXMEehHuoB!h&*&R#%6v_m4nZ3n>a0L-BMXh1;cy51spV=Q}P;EIA z*L}f|lbBY<0L1d-aoslx;k~w7GEvJxpomDtcTqxrSF;CNvE^O5W8xjx z;*$(s3lR~nWoCYztLuyFGHNMQF53mWf03>TkpbU(dBLGPn3iBSC5|Q@70um?z@+^n z1gS(BzRYuu$)#M4SSb#bfHVfaRQN+GkZ(Odx59KiZOa^;u0Y>vE1>(uue2pp>BKkM zfVn9Z7^Erf`dUokiXyoNZky+m27Vx8by!^!u7E>LZLlz3`dMeh@ELph-3y;mqC5<(Ocb2f`ZoN`RAUT*2cye(D_|%8v_D;ztpeq!lDF1-)B#*MJ=vrr2%0gfHJnZ(1Jt{)~8!P?atSc zAJlaX7X7gVru%DaGi3>l)~XyIQW^Bq>;9+M@w=e7HJniXwUO@w>UgBOU~sTvfrv)8 z>wRUiQjjq4@bHjCuL?^>D&VhL7mkCbEN; ziHQmLUtrP514}mg+?14*dGHTHRu^l?2>3FXb60nc{}mp}OwL`C39st4a-_3Y z>0`*_1O8d1WEY&k>Ur=89`zn)t0KPl#uu9l!OGuu1I%p|17e&bwCv&QGAVFx-O*8( zyV-$pEbtiKO44vxZHMfEoPiv6rsvZDObw6}`R;Vj&wF$S!Q`L)=V#OEymQ~_elS%8 z05y{8dx!5)cYXPA{^8H%ZZhg#Jp1DJ<1&y48jbXGgX#Rx3~=NjT%88Pk`{0 zIq24YJ+}W~G5+VKst14_+rJc3MJPiUQvU{~iVE#_(>#fXE_Z?%9;CguiMzYF9gX@fd!?yfEuydBj6&aFrmrmXK9?pt?P zuQ?{w+?%J!Y}Jj0#ya7lK^JS~;En#m4Aw7;Zod6B(!7~m(d{gO;#ku6JU43E>c9O2 zAU&sRNQ+if;{vp@_;FGIBwk;{P0{1kE&jP#j)Fv3oF)MT;_|1;NJ*wg;)383QxQLv zazf|y*mY9fMlsmMiEQmevgn_K!K@7Si)J$W@)+fgi9d-Ts|=Qv3oIvlo@9?J@UC*tsH3^> zJP*`V<1njjYaRj}-;XTCZ25t{)YG+QVgZYn7Y~yGJNtc*)7qJe(->gmRuQs zA6F45$Z6?rmz2E3?!(hVl=7W>DS5^0b$w@~6r))24D++;%cFdU@A1*R)8|lO0Sbe> zMFsv7gSPLoyjueYGh5#b8Cz_gZnYbw+nQ{6+gm?{Ru1!0sWI66x?UF%E&H47YMAnoSi za_6D*Kkvo@v9}3Wg=t?^#kXQ2)KQ*a-9!e{mI8=UEh-Lg{tYR3^KEzY#Tf;~2ChHB zDj3=5ol~y}JL{x{B^@*fXC&_v~hD4b7-^!PNVwnP#eiuDKq{#C% zx`5IP`bNN;u38N=#)Ac9QmCh^LXqMen-yH`ABM~3OIL3H1S2F?p|wgnU6R{xkfFw|t94*Ap(VdN)EioKmMid9Vw(&)Umyj7%X%u4-)*=T=WVR^{cMTlGz#2Y z>AupBO+y_gC^xfCuY(`drjpgxs)bh=GBrD$@BHtLI-Gjz13KOM5lx1%%PkeRZ}sw_ z88e-d`MFbgSu=Y?q6_%Xy36#iX!DQlQK zYs_+#Y@?~&^KZH0!0}`tY?Fr?jayk4om9s{4JnKR|M^o9EoSKg^|d2*$FhL?F&&ue z2a?z(`xQib`L<{HuiJZjdnYIFv9VpZ22h^+fiiif#xUnC8^o)?!NT_3VKZuc0f!Aq z>HWm_AIg3{#{kS0ACL0E;UjXeWt*X|_frWE}_A9QeD82wQJnZAqI2gKM z(Ub0J;xJne3W|$+_k#va$9g&+vcA!VJ&XS@IE>|zLrrsiV`kBt&Opyq96yZPeWVW2|56+d2e(E7^ih4RG5kMWyC)YMU+oD?Q(E&%27`a3N?tci)La%Fb2} zL1>7^V4*U-yDnD^J(!FB-q-wv0Ko{>6E=?KB22#{QyQODda($}tq70RFdZn`D%3>Z zC1&vyCXUE~MzlB=vq?Jtwg{80!{rZPVej5f^kMX{m++D?mFSBkprOUZvDuZ`mFn8M zJl#Ez+&9;}71gkD+K$qKOBYJ<>2ia~;7!PkzJ$JUMmZ3Bq?k8-*Kc1td+}{+=p7&b z?Q!~W%D3lldGAOfG+;i*bUar&-=56kO}3J5Y1w&ozW%G#si9#F3&*7p+fM`iY>m@q z4%_v3Fr|i(u6Q~j85tQ3O>}F(m(bmd4wITnvjB@V7WGe38>X@@3H6U|_#9v-S_kSV zpiy0Iw8cvqk!T_kT_IB~6UGr0|EAw6Dzsc227MFulhpZmYo(2Kbyd*C<@L7@sTtzo z5FDA@j7vn9M!Wx5i(91IHJwi{EO3EYhJ5GAtYd^q@cun{D^FTQMXsNZaO#spWXn=h z-9(nDkawS;FMfg#)SPHxV7wpRuyfl61nlfj`ecr*`0hgdxcpLX1`G_0W6Wr8R2=sU z3HE5%7Vg?Xx1%X#Gjw#EkfChV8K)!xJEtB`Z1%+*M)Xi0uhs5*Ln+h_IP1Rv1g?{`BdSF_e@BktpRt zV#Koel&Dp01w|=sU2(Q2&8N@fZ87h))yv^2C`C518E5SV$nz!46yuk_HoANBUk#wl z<$d~c-&3aA>i2Z%DEz4!wxWX3)ddSYeT;7HsjCB9`!^RRFnh<6 z91Mcd3(unPTO!=($$u>bcDWe+Z!d~X7m9wm`S2>LXc!*!(+A0 zqmy6aw1?Mxb6?r|Gh31Axskl~=FSMmv(IH65(YMo@jq=g*kSB_CE5PW9x+(-CmMxP z*cI#vLU1Wq+A-592Pk{6Mh^-~?tC7J!i>=DR;>`AMykNfS?%y!0*1iL%f29b!O>$- zp3(}MD*3Pg%k#ZsYte@yxSPV68A^*P7$ml&1O2vzdX~|h)La#n+7-(x-Dz^>kP7V} z<(ODj^nVHPxXkq71UUVR4WYkHU@V_K?VIfd6%|FJ3B@@62IVZ)=H>c$kYqxXoUDw* z#8^<%a#Gvpi1^@6(H8JBHwsK%bZJ`7$mgJM` z`q!W09_B^USn!COJt~{0`o%$6VuJKjFA<`m#4XF;;N%(BD(|y4TTg-dAy$fh^O*S$ z9eJ8m_%eNaN5GqZEQwILW=#hWWPQLQu!2T0S8e%BIQFG{l%uZ*=4KEwW-7>gllw;8 z{cz*p-$;r}sl3uQHxQQ0K0F|Mcmx&{kO^eKGQe0wLN>dfuUn?wQsH8=VPd7Fur_=( zV9_5Y5K2Efo2W4~gm4wptHRcJY0)`YY|La(4?bDEI4F~-w?Ns27H|rR)Y}=ojEym>&+0JVa?Jp zxKKUIgo#_~sqG{l2hGFiHGX#Q@D@Se^m!b{fAgjgxG`EOuVN+^F?gNwoWd#}DkeUb zOkqhap(7V<4CnpO_QCt-M>)9<4kVw#S<=x+YY8p!SZdvmjo{#1ULPaj+=s^$lp4#C zZHgi&84%^lfyz*K5tj$UAv~yPZg+eqxzKW&y!-lusK8FQqpFI|h0=jIPNw1aD1J^T zoW@)ntfDo7-Th)E!9;(^+ievW9C&$ptI_Gf6>tm^bWk322|GQdvVSx(GLa%mSs`Eb zcPe5H(hXYWmov4(feJZ!>cq(ub#fRl&Rdp>INJ8R>%{8n^Hrhr!GYbeg_ZukT3Oww zu#sqnALm#57`yJe^}*jf6C=c$)q=ec`jx{8Zh#vTKJZzos{=~Ph7D-57z_sF42BdH zKjbnTJMkdz5NdjXOR#`*gnb4omETqDQAkxc5;sgY*;W2f@I_X)VhM+D+S|eL^1gik z-a0~lBVld6P5A2CdTuSi1-vC#=yPAchtHoo%aRTcjBSdlbY6-zfLf+h zhhBaFeC;n^?k93OHTA%k#ON<9ghE0R4Mo+{N|`n~BN6Pfc~i(5riQJZYNq}HIfnEM z{9|eAFAi}uOpK1Ts{3Ndd{!gm$bOrAPAeux?RA6_R#XfpPV>apM){~}hEghyfDphc ztWk7T3Lvl;5~0PxK`W5w?B(S(h)$^n5f?eaHe8@)XpLhxC@PfC<&q{U^gXqu`QG{U z#uj$Lo|hLA-n0nVpBaI@yR2H!C>J&45 zmEL#X``i?kqPXIT{i#>kA~8;hID{oKHkS3?VIw^|TiE~Eb6pwWQ-ec87>FT*h?HuA zJnAe(kLM9QY`;rcN~H##?zHqZiHIPXlC4u+4BERgjqH{#N4Ru3PAHh7+3o-J*>uS%G;pke)zU%b`znRbLhr+Hh;&8O= z-v!0b{)WGQ0ck-pKb>xbT2=*wV1%qc_N&#p2RL+2K&N7DZ4J7(3ej({NsOBIfAjl6 z7F~UPy=;YsJkdHFaAaQqdGM2ywE)Vi(5MnigbYjAx{e>F`j zo6_NqBIn9lWs-G$vgdpp{mVBELB#)Gea$ttNt+*0o4_JwgtIgL?rx9&i|3}GY-=_z zg{y$?hmi%X^UeN090kf@QuIhg)-%0GEq5T(3OJ?LgV@5Gqj|Wg{E`yQGH6&>*sdBA z6O-YQ=PK=nfu0@;4h{|hfhREk18l_d^76uP$mqt4hbz=bNj@n{C@E4cqoa4d>u`GD zc>fxZDj?v#oskOP9mZ&GK@%~yK_zQ;_RwH?R#kb=tmC-)`$@d_2l2c(B8qv1tHo=L zZl~MPz`MxIH2Ra8uU5Z(huXc98XZV|W*Nr&!k4p!ybKI{k&yCQbgWZYp6g6o!Byve zHZUWbBVviUh}znkis}`K>w7q-_^YxAI}g?~K1uzH?TEuHVm1^%<`3g&D8UA0%5)Ro zuOPv+xVUG&MuIYx;n(zn7H(dHtodCaW{B6DJPCC@G_G~;^78V-)m}zwDhMK=;^QNT zJ-YC0kBW){7Jm-FXkxQ3Tro$One}QOIGF(u@4b_`_n`6p{dc%guk8k z56V(0AsP-#R9uF|&K#QeokIzASvTMg!p^A_|4|@rkGtys`V8>9?4%?z`m&GOVg)J? z%e{lr^)x?%c%<_??tpsp{&I%?K>#&%DiTj*RyI&Hn&=O(lQT@$DQj%ZbvEBP{+AgB z?=FwbNF73-^Yvp|p6>GE?LjXW&-a*uq4n{s$o~7%FiQp)w%0u4W(Uh*Wj#ey2nkmY z)=yUYZa6NlA4x*m2&ml|iP2C|dAPYxK)iy9Nxt{4R28r<{ri`lnHj}E#OHQ&aq)4X z&h)=m9-{D9wOo;^6z=PMJ?ssY1Izg6cJmi{N5`)LbxeD2wboct+C>+o5VR1wO?0k& z7!w(Z3(#!5`uZDkoV2uoDpLu4c5%|BM+d6KdF08xHTl_(*9c4N zUI$Z(jVgwQB(9lRD_|Sw=!h{g<~8$ndN`19-K2A8zJptsTr4Y-PphO}Wp(rrw;#Ga z386MCP%1{Tb>7-lkT^KSvs&EVU{g=psSZ>g7kzt z$cz=RwFiG<$ z8dFtOI>5ezL*16avr*EBZ=A@fV-jX%6-If*^aVDqeQa##tDSE$vuQ>j41V{N8@*dm zpJP^XGTw+q-Y|M|@x;!)rJ1UlRI;6~Zmg|6zq^Z#jn#a60r5=l8=9LzxT~3p%G5@0 zsO?Ot69@zlM?l|(6)Jixga(y3mVE1Gv7TTlt&pGE`ufLOdQTK76BDh+M=h-g68e!o z@llFq2iDjz3RR?tdjE@y)FT?QkJ-5y#EtN=?|W01iWP`KtzUE!lOsZU)waV(GaOC3u;!cE=Xp{{}+jnClAlC zYg+Pd4@1>{17=yxzy;lhdgESL;12{)zO`R&a;mOqV8XT0^bhLh2?&-rnym;0>tUG; zFQvPx)j3Oz9A<)W} zvWqr0>1g1_^WHqZ5@|in*RX>0atdrb&c)`vj5Gu+thAXuGw0Ptd7^<0@qmD1=b<5n zJD$YnK?(aD@4la%R5937 zW_yF?PD)D3dc%kT0Yrcr2jO!m;c&z<*lnm5JGT_K)XKWI__8p&VGS5)X{CPq_6gu^ z1^M~I`hv2kQQ&ISsL}x?o$Ww}hMsp%ZW zP*!R2)FQr$m*VQ90ZCIE-0s4)YkKiD0#cBSjL{@>!iPx_D z@#*HKmUA%t&>ZgP;vW)N=v|x~n8k%`*6akxY<*yTmi1FQH*5;4d%{%$vwXuLBcnL5 z6DXw?j^xTHN<+r8H)KyIf2HnLXY6_ zw4nZ{q@2s&b=`$*A=ASnB+IeQDU0h3oh~uMcB5p0SO(5=1Hv2i8(8R_OS=7iFikiQ zQb9quGaifHq&P{)JA0S8O6`yE6>4Rh$H(oi2P(DS|8G^Ol%t^?#(T72RaTB>d1GIN z6!r-Wa$@>QW$*}s6K(6yPYu_VUyaAoh;HBkd~kuS7-(~)S5RhaAzoftY$SdV3l@j# zmQss?VXp(k;Z$4-u|}{hX~<*`kdU(Q^td?eDk`b$ z?3H2gx5G)PI@Yly?UK>ZySts?R@SyiC@3LW0&gmezkSmlj{kXh$|Hc|Ej@XgiO|Wm z&5mdQ=Ky1{e<&jsZEaRveKvXsSsSOZgt}Um4%biPF_Pi63~t8@?6ri0 zt`ua_#;Wznhgb-Q-B)ymN{X#8Gy}1gTg8R4IKcH3pndp}xPD+N*LQC`v|W(8LR;7? zsA$>sP|Zdqf?`M+Q&s$M9`A#|bRse=?`$~^t}}y62@xNnlFnZP#GqtS-R50zWz{zv z4AKTNy6%5n(KpD>TqC1cR<@Xcl7nta$f{a=>Y0_Lq}2ZHbM;l><}9`>iN}hp)IeXY z3VQ+1u@(WVrR&e_v9Uqx<;lS`MQ(6WYi-yTrUMVBOQu!;$Z=KX~}xT&5qn|t4pQZ(Fb7EQk2_8 z6|0Nx=a<(e(5y(h+wNu9+l#cdDQsc+mK;PqedhI)tXvY4YaleVEEz#pv^*CuNk*d7 z7m8*bVFV0I>32!I>pgx$>1{)0*>hu(96Oz0l>GrTcgDd>E zGqvg6DJvc;uAuj|Fs+nMIa(aAoLrvD)I=$Sv~@J$u+z1&B7q8ASW7K-St_Lv0dlqT z>+=K1BIN(@0d(M@BRdo>;a@+-D~$UzT+^x^bEe6rfsXhb|l z|Fq#yC(UA5^^B4VmlLay7=+H!DNfh^Y&LLOI3`hZF}$azAGMhcrj)ug<2IwnxS@Of z`s^z?mL4>o^>8iDw!!dTz=R04Y>)MKz=X845ma;EtgKYjy4!x2huh9OAKEZnCEJ$B zVg)b1$68uNi%Pu*x4YAxkrWXjzekce8pod1--cF8Rj{3tGiuW1p1Jo7#~JBYbcZaJ z99Y|q+5jNJ_SH2rGXt&L@$qq!!y4+e07oJ`yt!Cm3$maGrrb?9)4z3Q(fnb?(h{=O zc4Kh~kkppJX^q*eFTm80BF*jOy8ZCfQ2hC&$<0>TY`f&z_3sYJ^3MKWt)Yf}tK`JV zSWFpHd1RWp&l&koNAt)?NaPEu^eaW;Q(8)2)wk>>KRQE25sMX=d$TSz_4jd>MG7%U z6Vl4BYg94#KK!65*#tN$&+)z zG*pR$;qLa(nnn%FYTKQQ+Dyr|nY_^FgVp{DO>OKuKQ&JhiN6<&)qUNhlMk`H{pDb_czH%?^>v3pH9ZMA%Z zy8<=606*fOP0{0{7#y6zNb>RP3&C`;pKj;tQ9NZouLG{7MNiSTlQ9mS>2jMkXU8U5 zT3DY)|GKi;ruRJ|bWVLTtD!-e3bmabcqX<2{QQK3gttfYXTwR1jux#IPMeCnsJUL} zlnyJuLMnNJ7K28Mji|#@4k_Vo94RTl5m|s#))_F-;)cW+E?|qBJbbi$ZENYB#PHGK zgXw@TAdBypTNPzwME2+&RB8)zOT+%Q^R3NkB zvEQb%XDSVb&k=f3X=Esp9o|+mYwev53DF8{FIIT?3DaC6ztOYqdn3EM*?9@Wo+H@J zg(x0D-`fJg;Qz#PbnnD-eLR|$`TEidU@s$eF%3p;F6<9{kdUTm1U>1Ta9S)|*VY5y z;A*Sm-7nNDY7YmxHqm2$^foZ4$fFAnkB@`V0gtr~Kajb1vazwTy)iv*ROq<{tI#%HkYCF{B`T^%U#x-J`gbZW zYpk{&)BU*gM=-?&y0QIfTQc*%Mw^SNsmmfz7!_-X?h*Z@I)_{2L0$em5`3!rJDpOM z5hIJy79H#J^;K`CGPN;9dG_cO7Y@k2xo77DWx72$s-MZvM53iIF1a^3tj-VqOUeP>4i*+oz7NhH5^CY; z>FM{zvyc!F2)J#qGc`^nBSv=8GctP5L~jX2vjRaY0GzL7^0|HLw;=id0hpZUlRH}CH|_}u#Hc050|I7Qj7q(&1uF)=@w zHBMn}czgMFPRZT9S_^^{q(ARqk=eMpQ4kS>=9FA0-8TCWgoK1V#o_^>bR|vd#VXR; zg3MPMn(-PzIFn$F!1{ZNn5(zJQcI#~XM_*zOF|xOe8ShCFtg8u*Cb>c${&dAhX%Ycw6|@_Gj^5jEw~@J)4cI_5H?ytj2>zkx)bv4j2!P z0VY+9?Bej0+JXw2@%q6Z`#{S(U&WYPvd;sd#ru<1LINrNLx->b;$owEn{vE#oX=Ya zh#2irujuGTv0pQwvsJ(il2X?ES&Gkz({ZJA#W*VXmW)N~85p`vHD!SR=OcW1K| zcpP)^HmHKtp>Q{0Dt?|yXcJM7oPc2%=an$4&-MC|kY+g!RR6okL<6={!476r&#Z3Z z3%QUr0ReM8A%=ISFTPK=p_#-{hDF8x_04;{HhoX$fyGm$6&g;CFVsb}X>#Hw6b&}& zY21j|8xg|7TJndzaNiTjXil}&hgo_+Y>G2c5gB8ov5ihsb(^%4kOaTSg~{igVUENH z4fJz4AwlS|j4NZFd^)R#Mrbp>ep3H}i%7iUYA@UtPHR#mp@&kM{TV+C4D{ zY@u)N6fnl=QhgmE6@4ild%tomArpa+E9ygNTU}gVCz`U8C6xu^V0W^N6+S>g-^#c+-v1@vFY>`%M?jT7I+s29sPxAzVevCQ!5rrLn`Un$t;J2 zgw7xQC1hqL>F>H$=b!;TUxJ7WGa0-N!}`}BHM-D%dxyJ{5_>gWi^Z-4qd=@Q3jZb38y?|20DfwaeSShak-sT^?b_OkwKAo?3Yarq!~?c#81_A(kzrJ_@JYfgl4Iss? zuE7@ps9(DOypIB;Wj%}HOt2JKjlf)| zm4=2UFfb4#(atE5gnZ3)`f7h& zK?=^yB;HKJk(o|Xkym(mP=A<1S0g4B;W%A3K3yHl<_ujbfSdTI{c-`DopslU_@c0-5+=KuO0_?Wa($a!0p!hJbEnz85TCdZF@<`y=i8-H;vULyMu0M}|G!bbmuap7xSdqI5AxVBk_%^mTx{BPeYEa0z`u2OaF(2WX!5_V(Me zwF#5Dz8B3eJOcFe2f#ZC!26_JR&fCD4Ge@7Y!?<523;~p9(e&|!1UA*8WhDt@};{GZs=SCyrvVT3?s1PmZgFQO7XYBm!|irLHi z#NIgD>|h<)$w|nK>FE<$94xbk^HWFz8=-d7t$6U2_u?r8=|5&>dAS|zIW%DGCWr`` zx7@wsTqY9kNRye9p6-3R%;%XLibAw|a-!d8qmG4@01Sbn@!6qJfeRQvA72`o+!RW1 zgtKcAl@xtldiLUF=~QBUhkySJlVYY(jaD}T{JNLdMTHv1tLDt7g;ETMNiq$`^Jc#% z;kDmS8z;IF2y9xtw7JKk88AtVNS5Qp08%Qyh7CtIw%C=@ z)%E`qQ`z2bh%Hw{^5bZpombh4&TnW>z{6yGbU`b*&zIay7cP9%;as3U>DF9f~RP$ltTAFkP-%s74yc+pj7Q`>rS9M~|RSa-%yl$c8Xzu<$kA z%6XPGG~D0lKAMmHZPeYo(uU-)`kb1@yaXjk6|AZ<6;j0iNfK9xj_w}nxz=8v;P4N9 zm~OLHJ?^0Dxqpd*DG?#!)|SY6V-pSrVbLu#d#(%-H|FH+zVCfkZ4)jsewS(hiFz@T zT*RD}wHV4dyxb7nH%f3(G&MHf+}!*IR#uzJ@bEau5kgyX+WD(!AB{n7OTI!PM8(>`oS%pyEjKni;|Z>w3K_n zYRJKzC?(@zoK(!spu(ggn1iKb1RM}=Z*M`QcT{+|C|H^su{)X&sq7}Era+NJtB^he zEY@soZH0uu20gqvn6?CGDj;J4%}kpTNLF)3Rs1zVH&jHSNuR3BKtg8lJV{$SRbxAu zITL_EfK9Hd^uJ^@Vs$$_Z*$)nO@&Nu{=jf(DhX>rSzmv-vg~3el??T$TpA54|Z z%=i`!-b-VsGO$>1eW5GWjP20royaz(KyI*bvR+qid9!Tu|1``r`~175_ds20w+O-dtXCu(Ow`LD|{a(bARx(0>e! zGR#-&v+)c&-G0Z|TwiCi7)=ch4(4@O1+!5=wSz^#4Gn#>p?Mw$bYBh=*+Oilu0Zwt z_ph>^2{sKWM<>*P+wLdgL9?j?*|>K_5_61*4-QqOaA| z6y$!=vh|0P_shNW>2k^Twr?7T@9=deaBm3B2+RC3SB$bYgn*?}LK~BoH3l$3eDp5W ze#am96j9MHrB%#&O~*(mDjS|wuTw=6Y-&6XEUyKg*d+5*-J zNO$E2Fx;hO{i~$~qG5P!jQLNiH&}%o9UX%f}_3M|ryF0k_ z_kqz;?{^gASunaH#KtdPt5_HpoGxcH#QV-Rc#|$Jy3Hfa=dONlZ0q)T$i?Y_n%%}a zTrR49uIkDA@p`YX@9v(4+c}2#8UqL8tIu8PuU|bdNc)i&A>U2@i344h+G79qhuts? zK~+^_4O~0Q6Q2qVL9j^uJMzT})Buw8UuQfJ-I|^4t3~`D*z*M^ez4%Hu$Q+t_>53_ zn^zB*w30j-`WR>nw1M1519piw~w^rfjO`6N*iKjWZ2F;S#7_VX2*Up?B>ovG_Z z4@|NzxflZ)hF1mrGZ9IQI$u3Ff(4;B^@8d~T)92$xEE&`274hW^Z*MR+*jJQl!1poXaL&cjouItrjUqF z-6pj=W_oalc(z(pvnf+!ASfqiY+rp@#t|<_IVF608bqUT|C4Z(5g4v0~uUiOT&x`6OI-BSSA zPp5u~_Y(U!Nmi>>X+DxHGeJP7Y63P*BL!wb)EiYTmFzjaGF0T_^^+7mcp4!<^$3oP zJuF&$&{uv(-SP6ds?c~Dswr2);Q2C0$^|fnXTP`Cd?6pG5%Kaq;{2?-7~>O1j{{_E~Om>RYO*>1Gz=H&(-^ykmu)6?e;KRzT}w%cR+n8>I5-RSZU zjs_&X!?Ftnp_t{{N;8d~HxUTX&X;D7Dm|E3?0MnqMlqOwI6Kf%;MF68;jyrg)=9u+ zYpq8@c>||S5eqCJB}0K{KTy8fEka9yR8|yZWGc(NiA=r*AZQt!BqMuHdzKXrSJtMk z-KNALj5n*kCd0e&WwTlYlA|KI%4j0KtpTT{pBot&Z#3+S4YZcy!~^45h9;&W8<+(V zcYjNj1x-zjz4=u!kdWq!4D@O&6|xwpWw)JK z@AOWp$(<~Py(k4W3m6dUUtSiZqJkEl?Rx;(08&6=WYFerCn-4)Pbme;QFlPYm}#J+ zqx&nx;p+px(q+toDQd!P8l3dDFPb6y`x(4Z`&M%zZ;mtyo0~U~2;s`Kw4(FXz`rsr zFV8SPA8~5>YRFGqLXwh0B~Q)Kd5T+ty=c0mj*&!A+AvV?IpR-DoqAtE-$bk1ktN1Q zm=MX?IH_(l+&yJBpm_M(J30!+hm#yT35AReI(!Lmv%xDrJw5fgJC(qNhJ+O5@Bg7_ zlDP0fwZejq2!X>rq{m;TS6ive(H-~xelP*?GYt-fL}}6bG_B;xB9w@TupQ;*l_jj>IO_XEM+pW&L=U#6 zFGE0$>WuNR=!~K;0j%HTjcIVvfG#90J)K3n9@?KXT?Yd^tIi*vOw=NvaqZ2x)u7~N z3&jrZ&jX#Fco+pUg?xCLb$Ln7;lxa424GY0&Fz-&Pu2pE5`OsqT|b!a)U0M|59pLG z#%78r%>Sw8=;ya_wRcTz!D=}EcNRz3t4EC@_6JE7Fq4!!=yVO2co|Vwj#Q$5r;8X1 zBF_KCk$;kxm&aw&f)GJd$b*MZ53*Zo;`{Ic*s^kgk`dHqD&y@gdok73)hQ`>He4_d zIPxo#Ge9MT7mt5)b(H~ZlYuR|sfmfRv$K&+NB|zI!SU8sLPiFXB%H-OA`QDNb&Wxl zzkw*^)~nxchu<;KI{;n`NagnTpSLx4cZ24tyj~vb8XH3(AwjaEFgm8z6r&TP=LiBq zD#^iS|22YqQL)LvDd-B5#2ALRm0K7`R}CP7HRzSMoDnc&OJdHgfr z!@=Dh%>&nS@2(nT6qLXnF}R!Ke^=ms+{7$6WDTUYH4q|iC=m6!k&uXzicJkgtqYt0 zg|LgqTYrtbLI?o0B%_P~v-EO*k^d)FZB~cIh0357|a&^F^Uj>}*0_us@e(%DCu7=-9=jlSz^Wlc%SrY2{NP1QB1y#>ZLK z9$Dex;V%P6b`B2@gOq7vo&lcc_jrvV!bw2^<(cx4?Bf^NSqQoEni|8B&shK~W0NlD zxRi-Xj)YE@zyEYg+hYgx=o6X7RR&`OJW>B;qiLL2MhKuYD=LDJlFW6Z-Paex(^cld zp}a#PKwui%vkwHB=OeuM8Gow_TEr>!chCxD2@_TG_6bxXM z1MP09a=|+He_csBlILjS&!3xHTj7*oEXm<-e#jt@Oj^&)%@Gg~oDZ)+&#=zob63C%+>5gk&NA3Y-FUpTpJ!77-JUr zJv#19Sf2j7;%2E{A0ry#@|>ZIsjFk7{MMnn&=OxzMBVNZDuWga^&jfbXumqD+`O7d zLP5okG|v+X7k%FgI6dtK3&_|YZj8}to1OwA`+15yuqv$>BtI%qWMIMr43K99C|F+I zfqpMcp^RCLft^9$K!%1$yktKx{iC;&5XCzN&IG3&M5NT-U<5rw!;YdIMgO7#N>?Y0 z>;3L5&QK5wd$ZWsGdg;Q$Lb#x3)r{fXxL7#UN&wVsJnttDGY66dwVGErAQ?P-S4^s zIb@ll8_jQbYXO?&YD3^T&Ci3b`4$|k=MH*$#G}=RoIVg4LE2Cj5be2WQ7VhYOk8f1 z&j|6tY`$GB*8nP%%dM)4?)E`xlJf)X~MbGhZy+Ar04=sx< zJ=VEc=-znUOnb^u`OSGv81DyqdTXHi0sH^@_7;pB!^#&X$r{<%AXdyP7f5cv{2R$q zNSc==kQ@P633t9PCzO~q`jA+2L&MYB+bgX}OoB|RpcjYMMq(m1O+vViq6>X8xXLi8 zYljo9lwAJ4ODe*DK{jWYhe^qq2#YiYfM1E?pZlb5y{zHN0s?_Kqz;#6x5>`M>M)YvVTd>Gqe?YF^(foYP%!LlNt>I#b7$p02dLv+cnm z3lz)*E`^|kqLhpRO6&t5XPpgH0A;`!cmYF0*87ure0+T6w^9huP*xFu1t7r3Z)t1m zm5A3Coz%{xp2`NFov(|p(6;Di? zG4$qYKx9IEprMTB&$xDMNGp};0$=o4RVoMGSk;sA(b*C{e*W%(*c2ks zQAbx7V2^~P%v=*3u@MpcKp_AP1$el=zP@1m;F`NS+w2<4yd8Jz`0y|hr`2ScUc=hY zhlhueB&O*rD1L+h_P_aUDQr!6Cf!DFp#gV{4Yv~xI%=49#wLA z59invv!3IVwMBNc^6g(%o3JArC8cYqUnA3JNJCav6ZH3YhhsOT4(4Wyayu+pnVL=m z5FCWSHcS3*8>s*W6&8k|aYjcP%VWRD$;zL>?*_$yOG+9;2EPNwnm*0XYjZwPl21Y~ zxa4*g1d5uQnfczK7cM8V6Gq5I9sC=J6f?A2Y2^c)WDtBVlFj2MV`+N^d-XkO5zz+G zyopu4Osw26=}({q(07NDL=Kw|#e#a>wAVB*VjNXEN!72FG>~;t`03a72bFNa77ZRy&NjYsfT@fY6?@g9n{8y5EEd|6ciNyvY3U%Cq2Yub)tRmr{WJ~F{%z@Y;D#wx@=Rf1qZ(El-WG$gzYu^3@Z$g^{14zJvB zVv3v;R-J>9akQ%|2k6SmQst5-?`kMgZS6v!k{E7ngLp;%bTS+Pq_h$KZ#ZJwA4M^Y z3E-zH;CivKv01rGiYU|54M%T$5vn}m=H>>=*6ef3Y{UN*Dk)v0u(ho%NE%c=bS+*2 zke^*9s`w)e7&sh}u4@RX+THGF+Uh$b=n+%rK(brW;R!6ig1o;BCqPX>VG6Tu?^4YV zUgi_feV{mEt2?XScEH0KREQN}#&%D?P+!myr1;z%IlH@m>IzuzhDF_0`LH|Q2KFzI zDx+=?zUJoV=VRG2ZwfU7@;0~!Jw3fkPr+cJu2F~@_-DMBU&R{87H(E%oE2ah&~Ub; z)YQ~^dU~=1y<9+77vMwyd>e2{aOyG-IxT8~8XxZO-?w>dP}k!daj+yrHr2dpfaorqqFRr`nH7 zVx~K-GEbbP7{D}BLMIj6+u7M!UxyrliN29WC1lS7nCxG+z2#b0h^1zMu+qDCfpc`1 zoY@(Z`oIP6TkTd`0!=jkQq4#0!R2mUvqM3N@m14fc1|-m2T%rMiTV+~ku;f^o>pt_ zE&NGSX?D9($g1`(+E25CdTITprn+7FpM(}?N z{)(unHnZrKltjVD7yWbd=yEF>@0Hl7Oz?PTIuOHUHJJ@?puZ7z4-K8My0)%v_s?tT z@RJ~%Tbx=;a8-Xmt5oF*Fb>4S!(-c`m5QAF9sG57u-RxD&&0q0d|l>ZFe4k-51KkO zQriigsv#j7dWa$z;iF~ofK~|vTCi`bNR3t-HK$;jH-d(e4ax6)!9T33&OPpWZs%K$ zFlm*pKetf;+--5M0_;fl<6#dMEGz3L`L61!E`23zT9^qf%~Hfje=E3(j&SmsAZ#qtrM8pWZxNeaWXSck@wli#a^o$ zk>*FVFw+?=wG2ds8BJtO9M4AX9xzN!-49iaj)j)#T@J)-gFOToq+kY#j)_u{Yt0W= zQdmdu1$uQhu!;Tvo3-P9^)_~+YwYaI2|%zQBf`F{2C6#z{r$tk!+V{h75T(PCY2NE zc^*1mo+cI+nn0BdkXrzNHF{mXwyBL6uE>*%>dy1KKG3M{rE}mx^w&s*!BcE|<|LKm z@L^;$6Z{wRVRU~rYxjit44~F}?4Q3-7UYzUWm4)GZwNAQbK{}E?O{j#Ds+GDLyhMB z1F#Lx61!~osL;{T85YzS@sL9=L9k~gnX+*Vf%X|22M2~x#n5ndYRVaKRSK84(st=( zqx@Nd!e-%^&u@u;hd}dQUmF{S^vO~k4jvw!%Cg3R zkKbYNHdMAt9wb+eWY~0KT6xq2@zE3k83*j|*%B?o8Vl5~(Jui+-90_gQBh)IVqkO> zT!@;U-m3}(=n2VOspwCjfvqyVr!VjXlw$~?pn`+5DOX4d2@x5Q5$C4*D~ufAA6!9j z3eJX3!ap-Kg!s*=LaTzbw7M&>yID^teCi^;^8wl`5yxNBPAV>$QTi&QafjjY7$mts zPa4#TO^|$_x%{Hv;E<7&1o*u*drj$$@Zo(Xb@spA4`zz)^sEj58UD}x{kkQokgv9u z)-7k)a zoj!bkCWYOBDD4C-W6Zu1FnJ&{-h1L0P)N3Us$0D7FqaGZ2>lp2E2!xn&*uu`|H}-3 zkHd3wc#T~kzySHYMUXZCa_osU>)x^eI65RGB(Jz^B%sr}^X1NdfkxFdpO4pybXwe* z)&oIVG=Hh|_uSloL@T8(wawF0rAH&}vTS}su<;@Szb{#V6QZD?fT$kvaAR=r9Xvd| zU;?&iJ_NEJc;;Yw%2G#w;Zh78GaCbz8y2P}13sGgj>^XH$~H2&ituwnQ8&U@)iwWquS*z%MX5y=ix=;GAK zm&HwHIB&3=$OQPhXiKGapgh)zS@={qHmzzRfkr5>yAV6%`6dKaI=QeQOZ&aTHXvF8==AqyO3QgbE&Br5^{#rfLBd z!xtgmy^RgAR=@iT8pZ?;c6MdxV!o{;g0Ff|C1MwJ8g~VQf=CbV(xrjv25lQ$F9U2E4$w&y;AfSYcbu1Iw+a ztxXK3vv+-j2P+oL0n#ZT193|B68bXuMKqB!G%zrmyfCcc^XJc6WxBYpy-enyBBOlO zh=wa<69|rf=0{3|t6(BB(m%>-hQleWs|bJjnxEK84;$-kqNZ|$BEUWi}y2J z7T*Vpgx3mTUMOJ1u4p*exM-IhZEa5=p{J^<>afy^STh%bh^;)WLEta>E@~X~O8VYg z=(;}4PE)zYOR6!0LYm(S%7%341rNs3cmUytm7DvMG`eRn9G|>VX#PK|l=PsoIq&p{ z93U5`2L@>A=ny7GLB};`&~J)^gCijEXcJ-sNgiFe1~_-1Q_Udu-zP(vNWX&iPC?;# zsfnZXB2W{Y9i6X$fxAOh!bH7U0vh54;hBl~ANdpiO)M`Q?MJYkQxO_e4M> zL4!6B;?2xp$0L|2PdUQZT(1jnZEpuH8-m!;hM(r*4Q9BCqvI)X?!ldL+RoVlW(&xu z_t8j2Mnm=G(iw9)E7^dvg=f)QkTvO%M_tLrnYx{EgegmGz8kEd@P2 zqNjQqw>`+-4uu4L@7)7~?s{pY_Cby%O?rI^{TX*x#uiYL`%G%YH^Dp8A zju2SJicuIHDnDjsX3sig7*wM7F7Kik=z?e(;sm;Kdtu4eroqmmrKJV82vRLMW~4wa zLxc%|{{7pF@an@IP3N!WyAD($&PJ#8UBLjb(r= zBG5nQN|M1=ykDU{e$UUp27X-e#x0Pt0XDn&O3(!9J85a$Ke7+iFiEb!K|+qy$B<5! z?jq|}DmLs8ddvj&=7#zKp9p&AWwm@ zk%3n0yVTUwdxwXhC^PEuZKW9PqZU$dguj4x8<1asgWzAUk#$$(y^D$=(?(Q`$!fz0G_#*66R-!;gv&lq2a@!`vG1BMxkq?7_ zT=DJ@Bz-~aDlTT`lf9{2fN^JV+2R?vz7`ZDCcvjSr=~$9jw0uiMS%G8x7#BUJ-S9g zh`<_1u!1dKs+u1W9X$sA?)<RYtXj*xySt-R%3SlgU7MK5 z5criRgAELf(W#S4oy}*kmXIHZfjL%E0%fV?py^y}{4T4chUrnI;VdI^^6??t~`WobeaBy%sZNaE4W_^TJBYXR|)<3DgBUoDx zg2e+}mO$|6pSYE-m7J7ExehXPz>^>$fA92XGLw{)^y$y7^hf3Jk2(@2I8uypZ}g=E z$jObs190k$tL~VU@(9 zlHGn_RNDCXc(0xnapjEFT~VT8*W~cfP*jIEN(v&iuE2nK~`vJsM(8# zuI?f*tjoX|1euAJ#zp{#=c*#Qy1A`atmy*@WTnQZf^rFcSqEGU z0DL*kG71X|*CAIufHZq3+knmPj5*shk}!fqtCxCI z;w45)j~bzZ=sN%w67$)JJ>?7xh;LZqQl=-DYaFH0-v(Z($mm*Ke*QLaSJq**nRy9I zA+)RL)e3+EKr}Z)RNN!;-t`KABEa=BYFU2-@IeqFAb!di2?4@Pk4GX< z1}I6LPJ(P~m`9kcu%?_~)^4`E@H6r{(Cj_ZA`C{`Xm%9b+?tQNB3YD_lxx1(1_1VX z0kAFD;B{t0@wK&_etv%XZjdkaz|U#aOfeBUSnK#cSP-9(09YUZse@r6#KztP&4N(F zK9ObI0qF(m&FDyD<`r;Msa!lM|87updOI+U@GS@kK-~aP14q9qR)M)%Ujv$Hojg+t z&DI#e0~>O{M1!S1^9wu$A8U_ zh;U%YJH)E|A3y$@dr;;vcYWp#nsfl0(22_h0y`T=M=~rdC=?s;1z^uK)@%cMPiNzq z1U-9Clk?`MoE(aFr87`N)j553+NJdI)OxX&{`m&n6#!j3dGcN^8XI|y%o*|I^3B4L z3g0z?CYZwHyQ5`c2Bf}tFYmW;$(ZgxY~WCop4{*I)Ki9u`E{i}FIl(EA& zupi$!JF}fn0oky(vn$ptJJ{HOO5iI$Lwu>XnlkAOguJ`y1a8e{)mPvv&jI)Xq`M3% zw5z@Yf%P26%@hKF0w365j}w3zaddk6B5wDJoDjtLj9R><{%9SjTspk zOy^3eoYuhun;|sHCVDDgoK`ym0zeA5r@I^AsX=s5ZW6jD2uM(KEI>xV0%>Y$0u?K! zjs$!IQG3WlDgIlC;KcOwD1k<&XE5*>*AYBLvaA#^7CQ6oE3Fz3Q~iY!Ra7urNda3H zJlcTAhUh2h@La_4fU7-BR!(wVPwo~R?rR_z0Na9s{N3*7V`4(->jkJae_0;#qcbxz z%gawdK(;PHG9Q{2x-MayU>gn>@fMgOFHcX1dl00)u4EMCAp7h70DlslRu?N4S`P9P z;Ks50-kkw}aQ&H1PHyCH_QJmyT#yH7o-k_P?*Ft1kSGxScpT25{xW4j<%Na%GzZ-A zwKb#1HNf`-xh|luv9Pd!nSiN9O*#;M{@}a4vjY{N2c)Q#nT{@yMsQMC0l!HVuduMO zhYx6I4o*(j4ew#F0QTw1D*w$ zKa81FajLVc(`OeRuN@z^fjZ+2CJZg0rl{XW{PX6}I+-p$qmwb~H&&VrVF5Cs$pneN zn4Mi|Qj(^uYy>ar9_Ui4{CXp-qvHk400>LYZfOy~fbgBjE-Crz-8ju9f~0#$4ybJg zBaD0Bst2&s9mK%F!Y(W>Zn$0n?`~27Bun1WBmYCdMExM(7C{mh^zsGj+>GJtw{JY) z)&ULm1>@4TYT*dvS|FsmS9f-I1$cSas#?ith|mBB5;VFy<7a38+1)MH3kjIjZ(aA4 zfh{X6r0XphHUl7+EocM`NFj5xvvoB!f02_)dVnYV<2xZmGyXDqXCQ;70VQ4hE)@tR z=taV8*siaxjswzHR#TLZcOVE?%o0+-r~!~g)GMA7bVmaafD`))k=-%X{w-+_4@V?Q z|L5wYqV0PLcshU`4-FfagdB`;VSz-a{0Pa7}{!mWfwg^iKfV84M~ zDNdz~WTejpyehi3{Ct|q>6sbznb-d~=K*^7@Ntdh1R$&9o?EM^Oo8QvLnj4T(lTJL zN=itq*&GM3gN^bdKc57Qzh5OtCNhA`cLy`E2U1KT83M3f-#ydMRQww78Mj`?z$+fcK~(YxKc7}^q4?(q{@?sdhxr2ksceHbK zQFAgj1?Q76cege*mv%AsLSm6Ocd!KKU}NLs{^$K5u}E3lxthC>vq;$)yP8Xwn>w1A zBMAv1{p&J47mufNP`j0JK2048KqHn{%R|78!7(cL;W5e8cCkXmqheU~7m{0df21YI zDSj*6+G_i<6$$arBe3ZnY8b*ikX?i@8$}t84muI?KVJU#?}87B|JTp{>rekrXZTMq z|I>N@)4PAa_5b6q`7gKqzwWL44;BXEKUVwyU#s#zxRpTm|EDsh?MpZ+%Ks>Q%pv?M zO_DsqCP8tQAyux|oA=vwBM(w9vtKpygO5;s?Cqfy_P;jF|NifP^aPTZ(B}?x5C0qO z%J-kN>pyiL8#x;{EBC)OAv-xAE6;zt0=oF$zaZ!1V`cxpt0K!>&DGQO61ZSIkckkY zTlAbzVGvF*pcJM>u(NZlmzWx{IlF>kJZQC@JP=aXPRhxeJSPp-*OtMveZNzbZP7T`5ad$!^Rdm1%Wayn69a4d{xlIy>voS^UWJfY$XC3VB6yb%j zp@k3mC<)&hKN!U9yfYb*v2%E_6&30(Ow7(2fe0g6bRc3hZ3iu#-psR0m1sF@Bjj*)7^+* z5-$71%mNw`az#wUNI;quxf2Qrdj8Q5A~4&1Cr&t@&qc^sMgS@hLfVHF;ldU52np)< zi*pt9Q5UOTSnlSuFvJEzWeDW)n$p`qaYzh-xafp?GAJc?*2)}7pv6J~{ zFi#MIMUU14f0Q1$Tm)Q(=s~UrxCn@4E+n@#RWjhkFxf>2{P-UH zJ|zfp2SeKDRrYVS6Ixauf-M#z#TX2MkpMO$_|DEGk>n=S`Kfcn9mGFM9?u%IYaJTs zwG9o*4CeYJDixkWC>Za z9#z1xy`&H((PD{wD9ng{)k$m@G?b4NDx43)`f{qi^LQKn=oojmN_o~Hx$=_M_%gHC z@pj|o(C3-9wlyI-nql(B8sgc2HSh;2G;AyE;{w}@A>$;T$>xo)#0!Tq`Xf)z3!(%j zny<~r+KlZ4oTc=ofL9bT7Z_TVP5dxu)lk|H_L<&S-`)?56Qk4w%?D-GK9)p7ppiP9 z1l-k@k!Pd32c$BeH6YtrJ}d1gT|D-s$!W@{DXD}XXZ^mapu47>U0-y#QR;opMZ+z; z4MU3JO`;j$3QC#$U z(AXUGjtJ1@aR80k1UV()i+Z@}tybM5L;N19t( z(PktU+i!#c8}A*km?IO|lF~h1EP_tQGcKmsSW?PFp{zt%lGVelG9SU~@%y@-z+`96 zxj;h1Nj4JeL3C=w_A5c8m=65}(~kxn1>bj{Xg4&h5Z_=2W7_CA!ow#GV=RpHTF572 zHDbyH9+%O{>hdCcOSk&Oa=FuL|2`SFV&L;E<=TB3hCIG{ero}fudpbL-O;RkMse3x zjwe_@ErRi(er%x~dmr^s%0u9?GsrkERV?WAbv!%j?bnTqdLeCEIKMW%S8F>TAo^Hu z3cs-E`p+)*UVSOfByZbr*t8s5Tl}yqZg42^&hn3QtyA30p99HQ+?KMuQzgv7O19Rb zVoua^@s6=C#1RVGG|$`4m>)dceyq@?L>>swTr2R$-=KB`2juN2nlv^mi zW~F>_ZIE>$aTVPNeWIfr#oZCCo3N`>N7odVbPJt|Y6=NGd#JM4q~;(_YBaHNcG6$H zre&q+uT4TW`(}S~kPuey&k@vw)hml3Rr<%^_xOMp=H%qc-Og4VrvHs(?3M?Ki`{&% z=a}lPnvWfe)|n*jN`jNKYi!2k0O5w`uNn9)5`%~7!|$Au=-$j+MZ?{kFLoYso}QN5Z{rrd!%HyRx{!fwb7U?^ z&0+_VVI}C&(qbJZdCZ|bE+N&pzHjjLk8NEC=8!UGkKa809rQ#o@Ikrf!NYt>VkBNT z-=`kL$tA2ayr{S1zTJ24WZZN(;$$L^yI0V=xl>RcFhyw~!Pk!M+%maKC``v=SeUx# zjSbIzk{{=C=l-18*E{(e?zwaBn}RsgTa(&~6sJBCN=yR%r=5l*TesiZVTWF>6E9~L z+f!XQ`5v(k8GqbXD@xFln2c*~M`1s!w4mTGEFsTr->AS&KxFp_)kvpK%^azoxMDnu zaFpp9Ni2O{oHWVvN12Mf$xXM%>li#LM(@_`ExGF!O9|aR_KZnr=+Sd3_d)FY=CRsZ z;5;eGm!m}Ssr+z7NZEV{y6=;dAHzO8AfD0hYlnEW3|8TB&VBQ|klY9g7Quopm!aBS>t@)PxRn@hAA;Vk4+{|7(CetGoR0a7p$T6n`>TkhGBSHU2<&UG)z1}abLh9C z%3!9fWYM2y1pVsWKvoxk`J`Qef4Qg?KgYsjJ6*>KproC$4xG$$X+V`_|$~ z04|XTR0)+Yey31KAz_N`kj~`X*5w@ zly2KOmOP%!`%2T5vE0?Cwm`UEHicGcZ zUk08wb8Ib`aCbtgt}U?YP9yldv{KG#_c z#?ufn%p)Z!2`9f*Qwuj+n%tb$;VYzh6x)9ps+Oi?AUEado4Zl)UV?Ha^v@o@E|x!B z9_vh*#~}mWcZ0(XpFJh(k=OU&f#`d6hE&+g77Tvvr^{bVk&f^tmo?jAbb418YIySI zilLDkm*)F*Hg$=*SbPzCc0;{e`2JA3_)g|>TIjv9GDaVh95q<+NrhBy5UDAsk+IShbqI~*in?X-0J7&pEO)+V>V!AWhzMdITR2>sg)4Wd96?H<;dF^ zo3u0bU+fY(zOlQHNnns!+h|9H%(wEJu!iw5ZqY6?eX4Kw3jd`UqH@jfE7Q(Xu=VF* zZNYBLJY3o&(z9+*Kh&c1GnJXK@S&^FEv!33<8Z*Ppbx>2j3?9i%ra~Stis2m^-NSm zz60y7$NG=(y(uFaWU(^`omd^nmED|!$601$U$4uE)!Ecru|TDcF8`NMC#boMXVFX|BGbc z+Tg+R+ts+@*Y25%yCzIyv&%21bXJ=;@KV#~NSq0tPupP^)`J79h0dNTUt#%4S#{8? zcsz~_%giPZy&h!Ssw>YsuR4YMhor9pGkn}$tF*Eemzk!8=Cpg}>->l^B3vbg<~;dX z8W6o*#A8U-*{Dchs6ViOo5ucv&BE4Y0FR2llBbdLu2*B7Lq>$RFlx3#bCX|0%=x3^2@=Qfj(m~>@IcHV3mOc8PgK-(6 z()&vk1?=w$32E_M<04`&s5HpE18z1~nD~lGXY;L}PAI>{V6-gs`42%c(nYpMaqzE1 z|M0%0%|vJ2Xl^35s7zqDhis^;J*sPbA0|(>yw4-A$WP>QvYA@8a!b4gXJ&~1abuq- zoy$nAE&i3XlP<+GyOyFlPi9gk#vjiM);!%{XSLD6f`L^LEp>)Vop#n@eRLv?q=PR% z=xH-B&IZ($b_nE!rVZuXoUZ$>Ovb;yA3zd4a&Y>Bd3-jObsx64JQ$*Y^C(x$X7rZ)H>G7@aNt3KU^XE#=TC4+R; zdne;+Ge7Bs`Lco3*>mnUZLvEyERYgrx-Aq6OT1=Zj5A(d<1zIjX-H8)-XxkS_5juJdek=jJm@{kzc6HmcO`=?9PjkQojX-oFj}>Naph zzkHz*A1)ZuL+xPdFrrq}xk+iSJ zKH~|Tr$;6Tz^>L57Ng!J{Awvd%7K37hcr>(bnY;5;Dsw!Ts^FJn z(~%OVAo-sd*EH&bpWYmIl_qD2;aKTyB_H7QE+jjYiTR@xB!PmCJ%_6#Wz(wA+q9hV@eANX#zUA(lO^EPjk zbGV<~Du2@K>}Xr5r3>J*>Bf?)*_uZaTagGCXTNyE?;aP#FRgc07+bbifU1V~w)#<6 z7q#6^Wn8{*X}K7>4rnJ*Qp%C`xDoidWCKakPNJ+b)OAxeh31>s=~ufo)7~|%hIM=p z>S@)p7S1-9E~~dj))L^ zN#u<1C{gQLenh#|ZX_aO!BRaIsG=^7jEc)os!6*cO>2JS99EXS=fos7c=mk~&~Nfm z=*BukMvUHOs3zVsPEtyekKbh%7ISJZB(CX{hWgRw1-*uXIKU$7wY)yLL|_j^SPRlWf`lHaHO1^j5=h zkE|icL4PFd=IYX!btY{)NeVBe()F(^ux~NHqhjj{% z;8jjT7w;Z^Ndya45tj9nCOeubclb!)_UG4hmI3}TgqD?1Xf$?N-b0%BB9+hgU|zwcQz4*iWWbO!kIf23?uwO1a5WPYUQCcz-#UY_Jm2 zG0Aiv-TQ5q<`=yg!R*H|BWv8JTt?KKyrA^N-hhs?Y7mIOKhS=tDT}56Gdg)vH2~$? z9-{QwSRu#{V{||xX#?$g{1283w4wz}l+1cxy~@&5)~g?I;csdq)P>WC2zm!Gt*{ZV z^BT2A1UHp`qZn`f&UV^zZiG1(xL#>5PFA+Qb~~hb&3m+BILH}WrO|%;`*10{*>YEJ zMx_1Q!1&rX_G3S}y_T*yJAd;{mOsc&BbN%@YoZzmyjB}7#glyy&23n)35(c8u6MLZ zToqd8pA0$Y&xEf8^-xsrpFRB_H%Wqqpy1l$c?Ll4PM3zL&O8!Q!|Bd1VZ(2$6h0X9 zo8ZGrqzB2pe7QNV#Q3%g*#}n48yza@(EFUK=I11ox;H(q?w0Lo_7`kTRR^kQgr=nW9NO(O~+^m-FhPbn3lB(dUD^ z$i{?A#^JCe^$duVi1(@H1vIp%7JP(}IcqHUAoF2y(T*MXGt29?m#iV=P}HrwP%JN^R2FwbL<;b0^j3 znZHiGgMfD<6;}C9PaVMCq5Pfv)?)eRFgE}6@6iMr%k64n7>CeYVWM7%KYi`A%wj^{ zzYT4D-AgVw{`mbDC-N8*Mruj1JREYR%z);SCErEf3`~^?OO3DktBXK$d)9S|9t9dd zr(OC8i_;?wo!5^D1nMq_nxl~?i3Y7EJd)b9)`%ud4fsoiSH-Hgmd%aRc~Z;Pu)gpk z?JM#dhib=S_rvz7rkWw|8dOM~-JZ|Fd7I>zg7F>avOA+CaHvHyd(NfU=tvXNSN=>+ zZEk!^d@nH2#14%)boO})T2vMDKtuDYy~tyd3VVdipqUEyF?RuSmw9+eW2(Dr@8_+s zVYhJXkzr}*k0f}P{(`&?I@$0x21>L4BGJj(8|HlyQmJYrw>EqnC;3(8 zb$$x6O!N&O*{5Vdw1Ey*n#muJZ3gAf%2_?)c&gkOFXmpK%MW=YvN|?*@0%2M*XKvD zd^8ZW=0oPcsHfcP;#;ZL2<>{SMQnc{6ob+H@FS7ry2YM_Dt2P{RJPRdh!ydEi5gE* zGKbT(T>CA;&quZOUSra2q`E)SangkJ%w`;;_k21@uSpRFG|A%M-yzJIeahQLUxEI1 zm!BtJ&1o;_0eK#nx+)6QOI1-Gw}sZkj-}_;S~@($faVzgaHHsHj>2MqE9bxR=vG=L z*Ojkc)o_u1dU%enr)=({)YeV6_4J`!C!7Q8lljZp@kGikJ|)sr&9naGH99t5d&)e~ zpWS|5JDR5C(Z^D|n{z`JubG)ncbRI;Mha-_Vi$DuKRu)((|Ls{(lpVDL^7$%f;P+7 zHgR73vN-Lkag)7_?Q>whR=sBtGv}|T``ctrOb3g_A@fMS)Iy%4rUt19p^H}BjwgH4 zI40~vHH0+UMgpt5i}RDZpFkTxvGt_L9HU<| z*9*1J4^AAFs0q1f$1~>RX{cBKXj7v))1`OgN$>4b8ctTh(E5$as8K5QMU*MQVl>Gv zIflort<{23o<87JIOH2`V~R|FreLN3kNt4L*awAGpS%%;@88vau+(m)9H^4uJ48LF zdc+JB3G=5t5`JbtEX5jg?-wOeiVC9C?q4SgLQ#tb6i59(`qwZ&5*c5}h6-yg%@1V9;d0j*9{rq@P_bbKNVA;c={4BGU zU5EEDX||o;cP<5RV%gE4t$zOY;I=X|iMgqwD6;#9{&#e!zX^i{2BM)O+8#Z<8f=tV z0%FtFX$(1sUsCu|?nwC=Nxz`aP~}{^aZ@>$8k*Xv)dn&HcqR=v}V{Y7y-!D3wMmnlGnAuunE;H9(FP7?= z|1?jL4b^ZHktre~|HKfRH=R}Hu=oxI#j0uIHL2$|b7d*w8#;IH-UrgETuy;o%G4BW z+%bRqY{&-`NBJ)@i6mO@Ex)?Uu@)=}s*E$W#L>qXSA0Bdsa#4XMA`cOuDXiNP-;+f z+n<#zrkY{0(a}XG>p90HInYX1XK->Y{|i%5OGs1!8}f=oS!!nmLu(G#@G3>=*+qDu z-Bqk0R7z&pg4&o@!#2vz}vmmp25x$M6piF)9SLZfT^d4 zclR#~5_qP-$*{~pOj^B5haaRV4BcZCM82np@r8liVTRhS!AbNMAu_B>{^@nbq;rO! zZ%5KP%UMF9Spv(aJ~4Nh5*aIBdqOR^W4|1>KM_=6d(759MKtmHLM4dl^ozl(eO~o| zrs{Q#qp*$~j$Q>?-2SzRIH@NQ7SH78q4OVw=3zfIR7-5RER^pF#OPP;{O41Cx1rR} z3;Kl(tIQucZR<4mbQZM><|%9IxlD~q6#E6<+12Z~ozJr_4aZkEhkbJmyuqGu+2<&2 z#&CaQwie~JC@YxB%C3s@Zd)FSvOeh-DXh3;@q-gA2ix$Wo~&rLSOf!cH>upX@fK>~ zpZZv82Aoe#$|)~phvVL7%(1R*y^U%FtHZX6XEiPe>X%g3bYsoaO!W*dehwD%@s;%N zv=+S1NMvMOpuDM0C}bxl{NSao)hNg3Xuft$JfRqO?NJmWm3wc-CTCi1s4;TtA{1qO z>!nF!V`rKx;B$qCp1o|Um>8twhe<5z|Akcey8l!e`M}!bRZnkAfd*~Xren9VcM7NA zfhiy4GQ`ZSg@0hMIm)oQ>nu1ZO;$E>_`2DfC z4Tmp6H%Aj>S0N-)3tnyORx4jP1#yO_RXq82?@!9nw{h;HRSP!7lOujje0gmFQ7{RK z=D&1bSeD{5BN3^m$b)q>pPJz_u)fgsIn?X>L60lDXO_)w+ScdWqR(`%gpEGn?Bdnv z6bV{}K6i?|7U;<;fdT&jCRUi?&zEd!9$VtR6jjHF1E(?#6(0#E-475xbHoPV z@;B*Ha&c^v_{@Nj&`Ch>o-#*;srN)Yv{Dz=Jw{m=AWTG^>SOz4< z=}XHmc&-Ul0%Y~?`6QrQW6CwcyzoXe6J24m4Kx|o9Zk^-TiNwN`qs|#Y`b6~`rq<`mo6U>XLkuhKYyMD5`nd;) zJ-QaolnNL@W(le9#%MoQ=d%+^DowCp!)x{Zy_gm%@nyZ4&!YLQPFw^_xcfRs2tS5; zOkR1_;7GZUf9Hu(RC{{YmzeDc*(;}darTK=p;d0BD%vK~XNox%>-O`p*9^%Vw3G=` z&v1&M>L)ewPhW{OJKYo?A~Sa5h%)ZIzp{(*Y`%+>?s-UGMeW~vUI>F_(f7bogZ)xu zxIDiAmzdQrPpkfA|NMjZ1H@Mvk~dIio^n-a+sejw6Bc;-V^z}5ZW0@2S6+OQ((^y$ zt=`rK(3HLiDi!JlFD_CQ~{e^*i(i-XHT%;J%UMy?e9cj zOYy1a?&?vmPYyNzmdlW?4!#wcTI46$fhuy)Shrw%Rj?N${FgQ~s|EB^eBCD!rE5B7q>giYiD zL^C#Bkv&xI(Hv?NVPIamB33vk^+4X4@&C5WbR0u3GMcFVkK{;rJOJnR?U@ zX{`HPkDogtD4yM0J!C3ZAlAySs;XuduI1U-4PV^$8AaXkWiD2aL>0}Zi zbCce?g%JMo!p8c`@|wF=^TubLkQ4{8y?A_fsC;}|sNyl)#p&y(bkSh;ttBZfHLYI9 z@=hBJHWuO-Mv2$)<*P2E>Av$=$}>d`+C_aq@e+4MDh=_)o9DKpip28Y8Z+@S%`CbG zzAqqr`GT-IY&@^9x5n$|X|A(pumR0@nMm%SHUM>cF@1%_DnNp%*KmgnU+*9z%{eBw zIbmvUK*uxtVRh1^q5Z&UN;MtfpiEyfx8byOsG=Ri=HS-Ts_P zoc4i@({~<69PFJH%1^^l=s!4{4Uy|d=qadjQ>w|b$4OZF!W&1^Y=IlQn*3pJDp7=K(?AK3&Z`vifE^UX*`a1hP`M&e`k3qN zeL4e+TI4Fb_y9H6w>HA%iW(j-!X_NVdj$>iHkvsZrNx!zx7c3yqPgpF=Bac>RaFUb z{U>Qz3|M&a0=AaHG9G_hmq8ejI@_u;O9@0Uq`jTB!!kGGqZrHJY(m+Js+;2qn`3-a z=Cd#C)-Q%rd&XwUN;@iu41G+^UG@x<&ta0N>nBUb@p&&Vl*$dWc_fT*!82PUBB_A( z7t1TRdd;v`Q;LxVhP7eQ4o?MUJ7d{%3mnfvDGNpKS>&j48~iRAVowZSMcN95&CJf6 z{_b)9XpuRsonHTD^7>UhYSyHMHD-qoRj`{i3y0FO+aCWXZehVc-$z zKjp2zP5;R0fE0oNFBg4(JbfLVP5^VkEQ(pKbslP?QbFEDO6n?@-EA@wukv!X-nD7S z%X^%I=MD7^lLVQhum7nDhHmy(w5pEVO5~EpLe5jve!Q<@C^WJbUV|#?ET*V#ELA3N zxy9Z*9A|{;D+TF_^n#-SC0~Jd72@|DS6|g%%6C4sao0|pI);84X4g~AI)^*QKIk&> z>P4)`k!`7H=5;+Yni0GYZ)BkPJE4-AAJyrmfnACX=#C1a`N!_JbnpE!EPE20|J^) zV>$W_H0mtIigj#{{R#)wxsrQFNfd&9#-K6F+l`h!LYUk7sA*Nk=YFJ2;Gg`7d-iKE z^qnLPBvfjnwgCUT)JBMVNPdwIfz*>Io#SXmo12^Bc~I|o`MrWmnacDbYIP6zT~Sb? zUaaqFVT=y$$uc_xy5^G5APzdv9Yh4AX??Ok{vQBIK(@cjUx@$fjT%58z{Ls(u&}lR z0wh#ab>)<00JJj7S^ycK0}y0l2T*l2wX-$@C|a8V9l$_3fQ2InVE69@z|7IX-1?u= zz|4QK#J~U(0N4p=X8m^?(8CPq^pA@X-~y?&x6W2`~p*AhIYs zy8KNEp#8s7nfbp@&|Gr=V ze{UE^fFj_ZJI2lg^#2JrvA4GK{6B2?uYo$if0O+G!I5(@`P&RJ2g|>Lurjm$+h`4z zw)Oy;t6IC5Sph6e?EZG@Uv@1Ab0Emh+5z}i(SJ1)z{JMN`d@sSR@P>=4*#^C>)$S* zgZY0Y|5v1cQD@QAl9!a1XZWvo>c65?|7!1|>FM;B*#9g=$%{*p_&?VF8gwAg189c0wCHFi5M+~@k>*l^moqdW zsn^%T1~nAyR9vrFkRMRx*zKPhw#ip+{8}B%+%U!e-s-t&?elqi*M6*b8JaEJjH?(TViFm{;6@{>sg&y|*=?rfyjD3QIE8&H;kIc%TcQ zaLW(Cro4AT^)pMUi^1tYZ-Bt8`FVUoopAVYPctw&JT%yS1=G7r#E>0>KqX*;=a+O$ zmgwSX47#m1dxv>;<8j{-Q2UNv0mXch*b?bG;zD|%J1ExZ4J|el7RZy|WP?wYHlyaB zJ>XKRk%P-VT9_9=x+vX9H`Uj`dNm0!y0}AVK%nBH+ib1}VH<3i!Z2pSH(LsEukJ+) zdz9>YL~!mnG)nX={@~vJ{+VJxw14laja=4@|J1cD$}Zc#XBn~@-rZC>JpiHLrj%Xm z`bH77!eMd%*#qP)V!JPykg09l@afKurJHA|RET{fUS&|cV?+p10s8oGIS26QBbft$ zIJ=;s--L_?P=naq5YuZCX{kxJsmUK5?altZO_oNV#lOd5E6{QK%~Bp`8>x*8b7sxp zi!&@o*lcX$Hv{r4H9@YS z(YDYRGT0%YDEeRvu@^=OT2_Wqio!oIR<$gu(rHhWMBPs?^zb1fb0l7^2?SF9_7A>s z{q&IPD?pbTc}4r09pQ-XVBw!G&zn6K0nwOo`TLE$JpeJe4nzmM^VCNvT*1~A(Si3f z-iiq1;Ptk2nk!l%p8Rd@GCG!yS{T7Kth}PKF;Ghy{!^q3wQH2+1iHT{_Z{JGXilyo zTmQNQJ8CUc-IBXC79Y))iu1}5+aN(;o?0uL8Ja-VK3mk0vMh>PS8uV>|x z5d5AMYgjZTbzv527o@z%^`rmsHgU*T!L2?_9dxX6TZWf-_(Zm;%>)u5mKJjoq5IP8 zoM)y63_;BDOcO^qakqgWgyP`!KjMA4<}4x1*iF_1)$?&rQK5NzWIkxt^V0)N!LTBp z=Wb0gX0$);3pcc@G1Ydf;4A%bDQ+z@ubUu7MUK2(4V6DVxRaG`=ZL*}VA-3Lc5)Id zCaADPBkEVq1}t=X(33kyDW56#=`<+LjVRJf;-}Ncirc~6I|;~Xlv*5d#txr3NdI|H z>BssbB#Rk$EjN`9zJz!H&WyV;LSDw}kE8+2L&!&a+rJy8oLI!iNZFj*3gMjQ_~_j> zP#;+*5h(qX=@}pWtUCSrj)#tsv(_|>uoFB-AK%%FFTeIkhnLFHa1F%-{Tt@N?ARoF}{BStUV^=ozOM_WNvOJo0MH z79Y8EL(C#N+?FLGS>+>KhP#zE&syp?wIOVT8OcB#R5b+WLU!;g8g_M#MizN^ZdYD$ zNt-p8O2bjr0+!q6eh(FD(bz~n^@kIHME>{e*p<6#3YV9->nfiFC7;03<5vxn9n_=V zB>iryD9|A4irDJPyX&+8sz^4RMrJ@^+Hjc%6{c8&wKuIL%%v-7x~-h)soH2AQwHde zzmv$R`H7R)e;p~5yCSV0vtw)AhXLk7lljmN^z-5eR5#~Smp$pQX^>BN)< zsomBbdAmI}0d<$#&{AgQm%NN~y6&xx_wy3M4pTLDR{QHAZE-;u`ln!tkA`N|p;4s0 zKuv|ms?N_mMz#j*G!`!Sgkg=ZNGXT!4NB_a)s@DadI_?(x0vtzBHc8W(0IXEaQGNo z7bX?%2%N_m>6c$8GE>bQqY1@*m7vP8es9S=<2meyz+TpCV5-`Ex++=-e?cGaBGEEi zlPL(0Ek{^)hEHn`VGBvZSOZdPmmMkki731B!Pdh^l*{u_G8eR9q_gR6I!cX*YVNbR zGE0RrIcj*ew#%7bn@ap~XNzNA6M!p%B-nVzrsBx5vn;F#s07AC zdTc$tHvhd*QO*RCDq1#)b3WKzGkD32bT*3M{ImEL&b-&=ybTi7$-t)mg9jV;wvr7^ zK+hs*voPj}ZZbN9!lo@tcS=0aIPJTgyY(iS$PmLeGr{tTBT>C#t|JZMMd z!gtfiVp(fFD+9aFsHE>OM7T6)yd~90r>UaB#T^BeGBBJ+G@kcC++lxl*}AlBU$?UpK6^G6_}(Av5Y9Ic&Ol9^|gct ztY{56*VDGa5`hQp?9slJ1cm2s6k1X{joKTW%X}}LpNip3y(H3Q$%2}p*~SN0o~Tjf z#20Xms+^xma!U{K77sNs{d_X?9L(kGijN8Hy1S6W$C`fI?54{GyE`^!z6jJyflFyw z*zqcYFUbogNv^$kqWm)-Ka*eAZsqX~`? zEom3nQSm7$A;ypy+MrY}!5Jzg)!zya__-0BRFez%<(h9yShp~3H?EJick$2tbQ+*G z(GUTW0!P~yG7}wOxCz73x|96okiGd=%Z)38VbJp;csgw_?RgpjXvFaXxpcpLyI2SY{OuX(HrwDEwiX}+Wc}?Ainpt7^lHt*t?(c zTVvhmD~0Um&PZVWe9p+}T6))N$`_bjL?(TAeo;WtUbO>L{qu#)`um0nUD|$CB5T(z zS#Fh-aPK0{fXack;tzD%+Ny@Ky_-ds%JOsVxN9KTd_grh&Z&W$jQh9Q7f$Y<4H`c0 zXuQGrI>QBba1>*zx_|iR*h1zR7ak-#>KT>I(T@e29iVUVaBKQR> z(OR$qn9VY3DzP}W@!WKSfda|XDbq1pQv&Gh5D>d93clw5px;kMy1lOAby3e^noO)&yf+^pgSCL zQRu?^rWIM&+!N-FKZge@vsb!ut#h;%cEnYNE!2iT&c}`!id}TX5=u3SB7i2QwPlMw ze)5pKKmCu}oawV26Iv(}PcyS!R}pkM{+;9RA*JIw2xHORznqt*#i}>O z990Ni4O6a|oT#}Ug+K;hBR7wPq`Lh#Z5V`3IXR!MMIU_w=gD1d5zrdS#Lt|@LjAks zIhZ{#!~23d?`OjCo!O8}y3lnb$>TxNIg!A#jV`W+-zf~#@Xg~|cAUgA;nbEA-H??PHz~rO zF9jJ`0hH7-#cndXygv7Iyed2BmTn0eAjQE#?(D6tfi^*>G)1qkL-s18+=|e!&t~82 zR2KLe{e|VOP66Y!Orh62e76L)M`EwM#e=_meaV@9uqK0avh)bowa}D5lcPJJs^z_4 z@}L?xlkKadjk>CY#N&FyMv}zQSKjFT`K|{#rj>Dai{uW)5vu-8!{hWi3H`CG#4?=D zB5TkJug-3N^aF3qM6))+7lv_)$2ngq(fJke$1kTv3G0X3gOT@!#s(v64%jDU}3OT z>7XsT?m`HA`|qHzfrt<{w8#^0s;cdh^nhFW)bp%l7p1raUowQqgob5ld%jfadPs$N zRjWapDB(%5D^px-#XV=OIMLsbkXTtG)CkWC~`ZH7hw!AC%ZiTNwgNFod zOLLd~TyvzTIAgr;wgb`8gw3Z0nVmx=pXXV=MQ#klb6gU}yPF@;qMy%h*)M)r%Dk+R z)+USg*8qMKZVtVzwbv}pe!$nEgO?YgRkigoPN#X?lAJ(}j=IL^~zuC zVkSr`Kgl4c?KCJ_|As33Tuec|DjNNL&e@v z4cDU*yzn-E$*LElihWyyJym1=EHsvchV)dG3(dupV>%4G4|*Pfgo1Df4va>Bymaj;+pO}A`j+b%u-!Drxi%>+856d5XkjmP66zR@) z@~H8WqG^z&p0PZ1Yt%ckhMc-nW3S(gGbgdiadfKSk@aA*gTZp`AJw!qeb1M*uFT@; z^VcbTTM3e4R7?*sf118DZ(=h|?YI4&PpD_7iR&6u3%>f1$xtUNimPOLrQfUX9D{gp zxOW<#*#Gz6lbo8AW(CgLcY%Gk-?Ehb>E=Qn*}Ex~=@PF##@mL@IvQl;O~1Lh_y_j= zk*G|GNzlpaz$np}xH54%PAOw6T@&Vb zC7&;Ixi2;|?u%p=L^chb9Lvhvv`V$(Bz=?~sVMvaf)uw%~e~XqgiGYFuKdHEOL+tJ; zcZ?g9dz)|d(~u_%ts3?N>d^UCNlVA&mA#0_!`<38$Y$^2$IkSYp3Y*}9~T0+PWRso zb9>QTIA4U6y+sQ8Njy}_eLlNL*@QjDxGM5Rc`Z!WKR$I?<`CdGySQL&_5@z#u0EK~^HdtOWYSS6Eg zW~Qi(*yxAxBM^AfIZvA`F88-S;*9t4A1-J?0NrSMKYYieC~bWQm9KAX z!w~x?WnLV2TqS+QNY!SMIVHcm+l>x`Wk{rE?>bSZL%!+0z3>92S)@@J8Pk*s6CV%M zD0~{2^}`iY^FEkuQCcTAFnV_YH%QB5<&i&rJ5#;EQ*)K)hu1A)WCCP_9ILuOvbJ2m z9%rh8Ud`cyUIURUY z+kpfBG9@Mm$NpT~;u=%hO141p^*K=_m$^An4T<$+RmhI~$E20DvBnXsv4Ngvs$Fd? zBJd>fJS6)w;E{a%%g8oScD6|5mZ(I~xRaB=%Ijv(;to|R_rg@eDPrP4_z{7@y_IM& z)iyd=3q#O1dy88W)T`JeJYL`o2S8d|mDzCTzToz3eX&uL`nsD+DR4@)QZ1^%7Nc)s z%6_-{8bBnp)s^T(PV<`^4OI3z7sa89)L-P&rP1jTLpCi6j7(4K ze$lQSkzRu!=g}C;d|7k|Z`R2d;5?~4=UKBoP>Ad^iovAQjA%n@n?#79)RMA=_!{*1s?Zs4rba#{=glhfECZnU z-oaheg|Mg04`1IBR9xTU*~-{TKrRJCrJAS=u9-SCh}R}Jlt8`o-3ff8b4lFHZEjlg_TFbjkwFh2$ae*&XqetY7vI9`P~_hkMWkKGMAkQK zS)}h!^iIoiAknVA+DpNV&=h)kfxtUw@kdF0FS!>IM20^+*VR|3XRFzwKXv)MANX9j z#e!UO6$g$DH&Oq*xOa)|Yt>(E3p1wG_3gVXNT^!gEi8;qc$^ZTRw0{0m-qckr*yQh zfM5pZ4uN1%cNrvv-a86CpQ9tSzgEhm=(E#jtBEwP-+~<4`?iX}yVB>MkfD>-D9)1V zOGSn7xM_U2W-8-2wxzg%V7fVH=rXScnop<)+uX7-pMBt z9P>ALc~Y$gS;H?t)XS)bvFl>*ZKCN8zSBb!EDc6qmqlxSiUbUgmpZ{qsK%T{7O|YO z&h1(VmZ@I^N4`+)#tRDLD>7Jho05ofL3}5Q9_Mo92wQ0Vlsi-0_oWFLxoc(};@YdB zk%`1P9x7Gx+|I~mk#I(^N#5PQF#Z*)Qw;vHnYc+?HbqHa{p~>L$(~<|t7vJpo1WzP z(apUSK|5>fEBSzDHl=CIavD$R-TKzSS;;T^Ip4>Hk}9TUt`elK7Y%(Idc~2B+u{xE z->}C;J*&t|2MBm7ola53Ezo-xdVL9VEAgVwEjC4&t&GVORwE}ordEmqEx*t`%=_mQ z=^is_rE{pOUJAT5^rhVHFC@ob8b9YQL*NLViACk==v~%2 z%CND*BM-lZexASb8k#>ZcAQ5eOT8J%(&3&(*HuM!H6$QbAVtJSH}mWHp2+jh z7HFC)9ZPS4+}p4{+&-|y`}dSNw?7<`Y9_tXBq{o5^PiZ7VP_|=Z;0vXpxiE1Ef&1Qml6yXLI67TwBAQtO9R`CU z6+N?;6t4$CEz;UGD76*~c$WNz))TJwaUD2;`bDA;JJbq%KGSescg89wl>A{YvqKa+RRfi0Mu!I|CP7bewn;rT-GiP4`ZH1 zHS~w)JVtD3S_xQOTRG_&stUDFsx!L2d1VrK>qGePRS z2xv4?@j0@V-L&~$ZT{k^d4YOgxri$E34Bjd9|1_0Htq$9C+!Nd;8N#Ki|*#hBjgEJ z2lPl_OVtO_Z4Mk`O>2a~q)O5bjqLgu5;JU9 zZLl|09+vr#ybcSDAxOn>v7^;ty3p0+zg4J?-!tHS{^ECr%v?$D1qeF4^azi#wDv7AmxHatcQE17PgE~8R8Wbi zyh}ZLdr_M-s1hfLd2^5t!xq^hhgRV}%~Nl(4HtG%qyASwt)Nv^3J*Bk>hK3o;JJ)h zX{C=j{8b{Z_@=;|QJnc}=9h+9WGh`%&>HiX$PYKjc3!FadF*3(+|UP8#N?{iV6smn zM7tul$7mvRg0~gg$x#C9T7!_LFQ&`o-l35&@uQp{^n*>h5~tfF>3aePFx@`+E1O%0 zJqVT{nLi}Ey}h3ocrPFAlwGBk6|br`Yb7cn-KTtPAP^8!crDV4=!JHv>P0E=KW?a* zr{LR{bOb#q^z?p>s|dz+w_a=C;3D#%w(+>$GRzU8sBe`__lhosB5O6LIm4PZybINw zuY$?@-;ZU78a6r`V*KCa+_`rEea9S;*Epwz!r-2MncM;2!;rkKhv*&CzS5fKIb!2R z;9ZBe%bO%y^TsH338NbV=f@lda(9fo4DBvW^r===P4KV%Qu9}q1$y7N;lLxA(6OZ^ zok0--fBQf^>h%L*Zlru^sG+`F#uyJZ=8t-`_>yaxWPj;hT`qxoA|En)`B+s$A48Ay<0(#*{tJog7*s#hE)PiM%)j62st$%^m?Q zb!`m~CZA&ZFmZ!PSi=eM6Kp>lsMkSt@})x1N(^;n@Z(K`tJt`LUp zvrPRO4a#BmewoOI_T%8SDfy&AFS*^IHy=2;k=GCDm7(ns&EvabBb8W4 zFeVN1K4qg!<6RDDPo%Ob_xTam@_mEBsU`?RA@ZlogwBnX`Ki)8drc||L#EwQ>0Z|g zGJJYzRaOo8VMl;Eq-iGvGU<2SJQCh0Gd-x37W!XbY+iqz%O1p2O|O@5@1T3~u#W5z zfS`LJr+j|!4!K@vp}fFT4#uvUu5$|B-kD0QL!4RnK3k3pO@U}(cB8h{%M2F?U&%pb zZA+A5->l{zirVFjDAMulWF9IskVJ_`nqv0(vZ7qInZP622Hz;@WdhU?8w{JaF9%pR98$S~>7Ebe3%1lhe$g<)~OZR`;6;TEm zH^aw*Uta8M^-r|RVIovoqBs(a+V-5qB^flOA!6WoV%#z7JDL0y*7VFbY#d_>$$EsZ z(&J1V3^2SqM>iHWnP@10N!q;GFp5eKhOD2@^^A2@O|arjrn!_6k3F{5933~oD_y_C zJ`rNOSN2^WRfA3|l>$pSsv(2;ox+S}qork$P?jL~(eOfFz*)qhsb;~NY*%@hYeaY@ z`;~=EA!lud+I7$8to+)HBzLE)5%Vh43WLrMbem1-Po%6sae`t}zIk2r%Gl^A;ETLC&-nLQ&V=z6(3=fO)-O433aS{t{4z&~t7)%yGB;|B$K`qNbpq<&K*@>3*SwFv^NIHSY!zPz;}iVi_jnd~ zr!6bI>5f+BER;~A%O$y0^+VA)!^pN0dC^zUZqS#-U_qtV3xDZfW~atKt96jEXAXG1 z)^mjLWeT(MXD)Kgh<}bbG3UNsE6~4Mxs_5$OvR>f9gD3O(-F;;_`RrJ&pH$%O)g5- z6!CI%4Xm9B4zeWQ3s9~Wm0lTA;^16&s<^4doNRB#!R7f=d-6p=M4c!~Y}X1gW`aD> zj>#4_q7l;-aoYegs1h1d{5;-gZyzd5G)j#Ej_<31$586%~-D zwyJPx-4VHEdp`XkSrX*#5*UvWoZ3NyRxGKNErV*d;xOA{)D^Sw=HYo2yu6t#9pqhD zdgF*!lcz%OPN-B}+R-)d zF8(&Uw$P0L{4Xg@EV#O$eKg@q3c)I4cv?(PX3u-vHitkZ*ZEI`tD^pOAPnCeT<(Yd zR~(u-@|fUkTT?h02p383Zc=RnoIrI;9$m5uH5G}^HnaEA5tG!o?A1-G2(f3UHE>Z9XKl;T{SS30Q{tX^=Sb|*ggl`|QeiIK~8^T12zR=VF)n@S8u`Si= zrKg^jAHauHo8tUBKjrd2s3bKD;CiBlC1c(}B6z$cxb7>9tw0EdU3SQ5-uv?4 zcTkiu)nGJ+e2d_Ttkj&mc7!h=BD)x-iW@&HEwPc1+nH4m3*dk=9k!*GbfulO#_m*}3~UC+F4UEhbRMh{Y1t{<_sT?swXGs6^OM%sdNZLQ-!}KV zvJ=OEKoV*S{%Pg%MiW1f-)qtleI!2I*7RyXhi)ss$*XKt&>@BD+av+wi0XWDc=Y`V zIWwkcrY&CZ4n-y52*Ym8O7f|cLfy^AGulHTV~)rcF6}}X*N3VS+LsfZb!0k8VO|gooJBnXLXDNY(l{RwNedWuwU=^UJi73r*FuLthgwgcF9*od#BQS zL%OfSMx8X`9OSuGm>w2f9zw_}qD8hD(Sh^Kh(Kh7FN{!x=Z^H*3Ekj809&>8Er}{- z?>EjY!p83)X$b`_@5vxv)P8FQFI`caONCPOa`Q2+j!W%Qe=<7PFJsPrIiTsTm02O} z&euMf@a)^(=NvXX6Z;ZKndEO=dPpBI3Q(hRhK`5WqRSGoZTNgsc!gG!=33!GP4y@O z+?4~C;OtH6=9}DV`fF=8!6zY8_0>ltUxGujxLT@pxnusIsXMmKp`o63i=vf97F-~z zF2@~sLUS*s&ZUz>@tRPr;z3ShXmhoJ>l+~NHd2Lin19Y$28ticnIBCvs?*~IZi2uN zUGO!zE7;{x=tpXu6KXZfIbQT;Cd#{zfWSjaJW^BB#iudC28K){!E=dURF;2kX=}4F zz~jBpzc{Ijhe9r|DsC-Lz`+Ehdt7&)qZQUFp<#N`uQ$DzN$jefTgM6!>U%Wx3ktU> zY4qpQ8K>_qu<&N)gyF`^Z6tgSOlZYO9Zi=v`QAtekjx1vR8_)=>%h zF9`H_mldt_Kk5bvMKWE~SAMNu6#YBN4>sWI>TDbT&FaT+u%zs{$8T+ z`bAAH3r7&n!%Yi@N|hS%h(Fz7evZhv-^5k=3%jmVkCKFfZx}+dxmOJ7kKZ4dI+ZyD zSsR{{-wJWkC>RB)#}SQDUiMFSXA-!3Av=6961m25&%yhSj6PI!7;(4InJLpEg)-Dj zldc-HBPFC(XC3bTXxZd+l-Xjbc(eiYRiE}`l(=+DG`;RbQYjY^-VV&3zLDZlQTYVZ z&01GaK@B#h@U$=XF+Yjfx$Dv@KUJj;Q5KY~O9|2QuEr@=#NQn-TMm&HOF4v}h`|=0 zEJ|-ZhVkbsrs5Qn3&}l-#1cr!WMAdc{~vy?K&ZIj>TWrp7V(-p|er;KvP#k8O7jC85h-F z_(r=}*5rS~qKEjoDRvviy$gveRpzQa zfhTripTb)Vbr2tEe+;osLq~E@oZ*McS#!0gR|^Wu5>1!DGNu4w=atKDe*~v2AV|3% z7O7Ag!mBBX;^+;mxcUjidl^v+2%_eykqB1+)oJ@-J7cD)SkYxGepPUQU$inV=cI@_ zMImI`ME4Ti+@bve^kWfVRQo!;rxT8td^G@FPPxKZm6T~l_5HL5BA(T5c?pD$5lB#` z06`X+p%Ix*Ue{UqjnDFwsHyotjY_Zi{cNY;>AMWqZ2nF*jktmhZ1Q9VvEsf3^f$W6 z??}5(!#i0gKUja!-2o{QCUER#_!ww?_!zk9rZjggvc|=85odZXdlUyt%|ZhsZmO<( z@d(bUd8w>tF`97GtOd75UFmX2r-wtWdQ*6tF{1DndnA1BlTpV(A;~h~m%1|B1n!@> zd{a%WbnmIc=%F~x!wsWU^(u1!c$eBpN}jQ1u8!R8aoN~z8bPbtbYFm|-{Ym(OwOK7 z@pGc&2JtIQE-6qDXg^BcV!bLzXM@nZv0=Tz?F>J8DaL-L1x2R9O?LW+ z{SHj4eJ)ox=+DzU+^dy9c*OG=&8NP~4UF%EN-RMjdv-gQ^Fruj=z<<%U)BgKMvsTI zud7sQ9(3M%6IpO&kVbMM!}V23NdEj5cU&4x5eJjxzWpUnFUREk58b#>kK(VZAP?3a z75+j^^b@&ztKK+<-5MGg!b3Kq*D^6?otXkQPapYq%j%UMSMK7}Xgfd9J3v|ii`I03=es}uf(ymu)Kugg@Q&}1v&-PE-$x$EYzC0C;7fLL8WEc7A6FVm2p$Ly)m zR|Z(|l?&mHi?~)Ar*vn9F0$aw#Yz}-ptwa`D8fk7mCU|xT;`%dO$%*W)Ij+rU$-4% zK@o{vmd(*{aa^)r;YrufglkNgm&CuD;;tP9)hPy4X%B>5U$&WZ-XQNOJGL93%9ueEWI+F-^|%b6~HIsJ%)78fxL~!I=)bqcR;)i zk9OZOqU!M4YI|aB+phn2O6~(=dp$VdE_u*C+4{#l0AkHlEL&OcWdI?Dk*u#n!jJsZ zdqnC+S!li!-V35)=q58US^Lfm!4|&|S))Kxf^RL*H+ZIuH>_>5(3uJFd9zQ;)U!fg zC)*-qmH$oZBwCH*1!uHQdT6{XrV=@4*61uvefkI`h1r3UB~`Vy(4#c_h)R4zfsR`Kb!Z6+xSfVex*Q zO4uPf_)FCu7DZe}S-)quTl^1i$@bi(%WC1y2nt~rZzD!v+1J(xvMGbCah5l*^-NQt zRd&ipxJyg;^=;Jq_;P!76MIdF7n}S2rb(tJ;Ws61ac%F>2S%;SPu}8XDZ5l)2OMtQ ztB|(%Rk#*wT@t6hy+_nvSC62^i?q|i8iMa*VId?fzG2sf8L9JJ;O(DHmG*m&9i7PA zrO$SgXSj*ZPJGqES}NU!l17sg=h?W)L>XF}QgdR---aHc2uzV?8SdLI!tI;Yzyuqw|SEy zM=mZSF^{FWy53*6p<3sMsyV;*5PtG3Z$!+a2Upu%f!XKtND;ODeJKRx*o3EN zjo>qn^@1Fsg@2_HS~;k~DG;lBED-~*5!M3|9QJryZ_h&)q(}20VlPL|m=hH*=ov=sXknP&Fqv1ryTG@>v%dhv#ZEpQk z!>zvCg>DpG2*ta`l?=alBdSgzv2PJB`+^4)%EO6tOF;!tzXReMSdY2M+IAp3IG13A$Ba$(~zZ zvzyw1{Jf(o&JnfXS%ZKua&rt?P%!Yl;4J%{NW^|Yobl)*SFE|RZPz$j@p!l;9-jS^ zRr>sZV66zJ4fpl2uU{k1Qr^EEk|FN22sTd+cif9j-Qj#TgDGr3yeMo97n=Y2y>-&C z!dMXP6JLF=5Tiun(%7ly$Sf2!v{Ibe`_cBWSUth(6I9Gjd~5^5T33^w1;@1AqhXh3 z)l_`nWiELTa>K@@P`}q}k>@I1!=iE~Ds@9(#IW)81B!Us7e-B7G@$BXnn2RWAZt+B zq`4QlmRijl#=mlj_}wV2mn z%y&dok%0z)29woI??O3xqQ{F9x&dKPU!2F=Q5{M!8Je5c0Lf7#b8t;Kk();fjouvO zNZH-#)-?R_gSmU%vw9@rPN5^cr0qvYqtLYb z+{2+LID|OorcV#$J8$g1*U&X(xcO!ew$fSgm82=Zp_lF}Cgf%|&*9We%`WV_H}?p2v4gmmH1@j<`Rn4dKp?-V$pfY;?t&ZPp0CMr5X@ z&m+waTNQb`e^-K0vuNs`10I@)9x{CF44#Qbq822>4mJxl&WLf{&cs1kA}mZA5gZ%S zSg;yI+7pw5>RNtfUfhu>`APhubFtyKoPRh9^N-N!G~^MRA%wGHKxPn6IFY00`I0Z{`m9_C@|0H;(mUD0Uz%1ZK zXO32JpdKsxL}&y2-HM)q4i9a#2!(ajk#9{|hP0t|0p&ZhC?!l8OWe==1`23ego15< zS(mTh36$&eYBB=PFMAWC3cCjC02DAS9=-~5S5zLPr{5EzPiI+;)nTZFojO-m-t&@6A$|oPdB(x_qJbAnHu_#R}e$mMP?Q z8QSEgz=}szoedkvCl%*H>C(HtX4Qme&A)nKU~RB~Fh0wEsaDwD0$S0=`>I0Cz<$WGI-!Mp#uU3amUJE;T{eu1!Bx2~cfY%n zaD5usAoq<6DcLlHw`*r>l=5?s#U}ZJoj{G^)}Jf67$)ky*tYV`lxOL4^Hh*FlXKjQ zK5>v&mN~n8$CVPKhcfS$n>dvJTMTjN5fIs;I12rI61JhRPJQVQIVo<~T99b;sVpn+ zJy+^blO#7g^uqc7yNbNexZ%9IF%xSmS4TWQH{MPzFcOT9zVmK z>S#1)Q%BPtgPSPc05{U!EMo)Lg5oQaair_ zlo`#C$kDRL$$dFyr$5LRVPfuzbkOW|`z<9blHN&CS(1PJ;?ZVShWx(3ko)Y;g1qO- znzU8Mj~-KE+~}G$UmI;v68lIm3Xvy~ha(rdw`u|L4XrnqY*sr&$H& zM#`bG&hhhjDbZP9-Tczx%p8N8&J07mv!QPiOK<@J&0n$mr8_sX>m9Y6s!EUq%v5r9 z*`y2X%@wtnfUV*_L=&kWiAW|QR>n(gN*RDZvK64IDhPBTEf7EmFu)x&e zF{$hE24Ek)HNiN!U*~_~-4-BZ2#7pC$)nHNAiHSvt&Hmm5dj>6aO^1bAu=9Y8FV<)cSp?`m=P30t)SXQ%+yvZdAlSNLTX?u)et>pXgevz~2`t zADtaTYDP@k($Om!oOGpI=BOFBP0l2xJ|7tNPgHL7Mt+2F^R07onukiSE9&EXF=UUN z;VDqaKR3h%E`8l7D3r_S_tv1xumo!n!#%YtcI+UvWm%#-b;Y7V6@Nkw zak2s8-A0P-dSwgg!C94Rhxn*!lXmfK(v2p9uSY@B3?AV-fmwNVrfLDCEzlT7|_5lB@)gJ|eU3ayU(x*n?N2i*qdS zOO5fJh$n@qEGw&;4H5ltRXcW<3VB2% zYjx#>T;~-o{Pz0cWB`d7^mWDWS+}#$kGQU+WJ0pA*KO_Y0>GEyIdU(~1FpEQWlWcb-_IfHbjD*omUtNduOC0UDfvMYtGg|K%fo$@LA+u+5Phdrrh=>fyb z+a+bm;*lP zw=bP@_96YlUHp%v$dAgQAS33H;ae5N*!9UE1)Xad5~c+zD7|yu#!E{)eSfeAfS13NoC>;D-taxzlYv`A*|<7x#45BfzTf&Dvxp^#g?(qApa=x;q7p;m-7;gTc-0`kT$*O!tY}23X~Ki*a4&u@XCf(vO|+W&;C&d zGW0_Qu(k$BiH(Klz~KcoKRE`dZ}tO3cVc=6ub z(z!wY_yw(o;e3IYtI%fjo60uBv4T3UuhR!#wcj-u!U0LcqJ+lLJ;>*8)b1e6P1 z55SM@Cka4V`Ul|i1yC0-NY($l@p$xmlK2SxcVxc~NX$p9;MVTafQ6e9o}5CciA`Dr4HOWOQu02T&gXnB7o5 zG5(`PIysE}Oxi+tiUG=7mCZ$+hbrx({to3)>?W*tj2}t}0O}a@HTHxHUJJ~=?l-lS z?ZA_;#_sz~F))SzT=%U4QV9T-+te07jDC9hD)}(^Wy0}uj&!@z&f3!Or{fC+=4;|2 zhuK#*nzt5(lLPI=K^kh+!P){IIO|}ho{YaT7l3BE=PFs+`KLG257q}J^loOFjtfoC z8Y0Md3m}=7(h*jP?2?_>_s*w;;loGz@W*%X2f^=$@cw&e@XICYdqd*W$1CS2OMM#x zTABIhwG+Tchr#zm0~Asg^s~*R_ZZff$0e!@>GlVT@dq5J;|tF3=eiW^vt#vV|HDNU z!T9?hGI{7z1D&Pj=4GZ&24D0&zDjNp2e`4`pIQbmo|#M94%k7&Qvgst-1m&VMk`*_=2)J;w_h-T1j#?z-wm2RC^LC^#f*0E;y)psz0gEpKeZ#D&l3D;ms7&osp`9at=7Z)ieRLITw7 z=TFT4lZ}K4!Rma~zt^y-Q`raa-PXR%UjJyYv9tZN_+0t;*?i=g_Nn56KZR`M)yWJ{ z4+ZuV6_W{4LNs}b8pU*SvL$!~Sw~qm^%;924{7!hhggHBVD=~lH>|-y^0u_k;Hv%T zsv7KMoaF;HHkAR&K8*F4qjNgmubyuKuf2S=OGVZ%!aWyq&73ByA;i3QIKQ@xHZ@I0 z{)ev+*>ua6o4rliJwI}@qsjOP{rvLOoI~Jb zols{eTrd}wisV6xD@)wFIf+eUL4_N4odu%FBEq5-c%pj3ijaONp^C0kviON&ORet)?rW z!Yn(U(B+h=nkX1JkvM|BE0PNnhY1&1Y<|^@xoohyMiD{m6&RnF9zK}l{;ZMNl_)yr z*!j3xLF^sjagWZ0FiJ^vFI%-X)Dz}>t?|(gdjtg1`>&|s$nz0O+o&MQRd^t6VmLh= zGdJTHjULq2WL=HE)ntFhy(H^+8eIrswuQ>9>eV@zbEMYLqS9T|@%)6Dl|9oAr~k`X z#AWAt)N`vhks~ub_X_z1WL9p~`47HWs%WCcDmpOB%=W5i#+kxme?K~FcliH10b z&5zi6cpw5>-|8%w6DWXjWI_W}9tS!~Nj?X&bByt*Zw8zT)xwJ=+p4?w#o*ji)!?$E z-ttWhlhqpLpYD;9r5=Mg?g5@P270Q|B!(|wPc6~QB_oj5J56N)8Gy2c+S-An57@@Y ze2YQi*iD0KCvE0j$D~eEx_-DCGFa)8l)bP}oyZOg*i!|!6VjYnYW+23`F7wC>-7Y! zLGt|7S`#<=8=7J&91yJn*Sc{3m=@2I6oz+px{9RZXt2KSb z-TQp|wca4%9a}hZP;;89sV|?k#t`z=a`5-wT;*aZQ7t-Gj_%fOi7^Qmc56rDes1YL zBp|VliBStcanmSg~c`?YTzc2u^oKV-_$q`V9tzJdmcMKOS0cDKu?Vs6xY z9RKXfm_Fbp_8}kHHdM%{&p#B#7lg^l z%)}!U#95wl&M?BRt&@@=VjOf9Mo6N?`bA@Z&}EY6?D+5j<$!qIVliP88fNgvCuuL` zY==`N_zj3h8l(Nbir*C;Cfq%l!Li}RTPF$A$HwhfJb`U-rm?gu>-ozb_O+2(SI#&B z#GV5pMe9xNo0jmJrB<^Rp&r4nlwYu!$o>^BPI z)~g0+ERP|vUS=UN=dvwoXFs=C&CabLu=0y6Ra>`8{Y}aXk4^O=yTBt!cFW78W$5Td z_-P!g8mH-GG#U5luWll2UgOn*iemObxMFz_b-ZowGfV-hq*C%X%8@=$KMhLfk#RbE zVd>5;qG(|FuRxQ_t;G#pLCZm1D2Vs6 z+nNH-C1|5H&1`oAiV;K-JaF!)6{$dv&tZO6F>;NOMMTIjZ5VCKQJaK$27|o$#oZV| z!rny8Xkw$#XoIU`pT6(}3Te0GIjkl^At!tiU}z~9AgWMIcNl6ZHQp+iwU`;EnT>i| zY9JhZ`WF*_uc6h+)HyjJiH-|OLZE8A(xFN01TB8snTtWW)z&2C8ukF|h!BV#R0BD^ z&a1}B=+tRtwQL9JaAc~w`)Z<1E0~pinMjN?$VT`^iD|B)Y3E>l>SU2!%Qp(OwhF2u z%L{FJbu{fLVaU^IWYRq-wMJ}+^5TwdEca(8xH@XGZyFbORgd^udOSQOHE%H(5Q!8y z1G>TQ2mPA^$Aa1ytt4!)C}m%;^b)>LnDv6bqX zscSfX7eKp@`ze*MoPY(P)cE&68|JTxV<37SjXOTgAQ$ydv2aIdUU1mD5tm{J2CAi# z;7BRBtt2`Qx*2u&zcsDl<(Q<{j1x9s;xdv@IOjkYrMf9QLvF{+)JkY@y>p2(+R0_k z5Y`Am&M2#QL|;lEYxaR9Eu>`;{bqa$i6$%CaUxF#I~SkMxRnRv*G)Hq{8%DD#8jw_ z5Q%Q%@=2OH%9A%9?`^K#^e>Y*6|3rTh)(rr0C9!{W#<&>-8!+{0PDYUo1%Ft%Czzg zt_~Kq#VB<&bTch@-J}&x-e}=Gw`HrtP!3ZDM-6n!L1(IXmb8gMxRz+0M(vtI3cc50 z9g@HN2`P#z7#<%K2AUKdV_(-{z{U}u179(Ns1n|if`dh*yuWR~qa7Z*C1O)tV$>Cl7}Twm9gKM{9~-#toM1d7d|T37qatKZFQ zd6)$Vy8N>gaUPXpF176zwLl=Ip+BTO3>$7$?<)m&+~a0q)|j|yrCenSUaUUYlp(`V z=d-~NJb^HMrj>Cr*TuwAWa{p>07xYG2y*rW%~Ype2klsNu!2l7ogcvxCMzjHB)Joq zXAPjJkg0&u#6g(W_&jNCjOKvh9^MYb%@_9N6wr?;KMo*&(Rc0S)1GhHHq=dHe7YNe z+$7Kv#UMdHb(BbU@-6!#i(AANNBJ7PlHO%?kqVO@DL^|uXdqgU!YBjhlNjC&%Zl{N3Zzt!A?7Ln!$FyoTj+&HPGKEUV^RWqG!9pck~r z1i{Nw90YvF?`Zd|L@uj=UHT^c`>`C+P&1DDwQ;k4rgb3YhoQTr*^Ciix1BJbaJ<9Z z9u+!KvwiRa!bUBW#RJv{REID@+HE{0Ol7k(0>#OL$;OpSvLCx1I^hlX>ErE)RSY7;$CT@eBOit#!es*RnmF2hHL()YCI`WnF`l)x-` zrmdzh9Ki*ZrB@VggJG^E&)x|{&!f=IXlf**9LsIap+i+oIJUxiMAu)h-|_!~Q#yE= zLQt?oS#uhhy1Oz@y^{y(8sUtAfiaJG&|Eee;VXk2z+BX%$mAsCE{X?LE&{|5m|IMl zLzc5i^LZ9ncS5KLUE9QoT>&snjXKrKz3a5*ms+y}!=yHmQP5kW3i2V-!|4p(-Garo z)kr52I}@BZi+X*5pVCgWJ+p%y8&ST;%rX4h0?A>D8rh_>^LQ~cj}iwIe!5b|cledG znJNTQoW$kY=yvZfoRF{F$mKF9QR9TMYn!?`L_XC`1uDuHgsQd&d^NjTLM{jy2?Mn! zDT+X2)4+x3EOYw1>!<2a@OqmFL&q9yA*wG8kuqHup^TeC4MXj_5Y; zlRTZx3bd{m#JfD-qdOgV$&`eRm8ZeCrpFq?Z<_c%xsJP|Zp6wx|NXoJJs)s$f>rBzKhYI4@UrNO}2PlCu`d2XD zoLgmTnkO>-PHNnWvR2=B(YEp`)^LM#MyJ9&ogvp?1A@@(8Ac0=w+l{PNmYSwsx>@F zI#%ZK{A&VayI9m-NmSUb5LN9wyA7Hex^8GIh??v>#5K2U zX`njNX|$pCa2Nq=ZO%$^^1t{86B;xw53B)?SS1u7+|x6JoM5sJ(K|DP z&+TJ~Wrm903|HaC@!GK+Xwd{80ugg!*pHuNq#7zu+^Uj*;La>h;P^(k>CpThD=1>? znL3a7-?t}pe8uKV6?169k}~fjde>Y7*ww=YBbT%BucJVh^hE_Nb zmtjmLz}a#vbtiY>s-EW?dfq!Sz%@Oy5{bNX5c z+3k*ZY}xaZ%b596y7jKocEBIvEW~&v62T*ObOpDdtvLhU=c9 zsA7}~KTos=kQF~Az?&Jzuc}5#DMv7AYdB!}h8UaJH5>Q4}|^^@XOHHk?e86 zT!D?(-@#xQ#XX1bv-uOdbUGD8P7H+#9&yC~x>eI+C8hr!k?FW+3mUSPvV`!ur`k5E z29Ar)|7neFGLxy}rzYk{{?R8Ecf($y%4r!r=gkAzNOObWTzGNsWe8Y8Gdy6Kd)pV# zkTX`QKI$UaA||X#;fw;eEWCFEjnoxh&D)e9STaoqPj>s7izx2~Q(UojnEtgoZN)qd z<@^2!juvF4!?|% z0=f*C$?(7PrpIaNl@qFTseQK~3+E&VbM8d<_=bYZ9J{EdCQcDu-F4=4PDIB&QaY~x zhOSX0tY-?a9_r2|D=mijKv`GG{TsHlj^G6f)fq5)1vZ8 zo_GwOr?$utX|lL`zS_ zPCLBy=}5Ns4lUqCM+tmQUy-WLv&w)rxP}fQTS*BPphXZE?C@5$N(YZY0rcpWfRj8Z zOrQiD>&cz$NN`Y$)@BZ#<8X726(>r9v5me1_eclp$Lc-;8x}m9tO-ZLaYhs&AL)m(*Q#e7MutL)$`J#=K3Vs(ZN| zcs1$FqCT!O_oa?HXB&m?q_bJXYTdrVj}o4s7ekxsbIN%$Z~G#X1QSC@DBAl=x0*x1 zQo~ZjeN>BVuas%Ch7!Zb#5Es#XClM-=yU4N;{~8Z5^pPsdEkPr)T^QMurxOB9AKNY z7=}HpXD5@%GW$(yBPRszbI^%+j(%OcN!^|+{IQ)!Pvs`I4;IwUSQ}jzQ>P|9(Rg9B zF$jE`byyYoKi}kA#zEp4e&+quGoqnq2N_-mNA58!NSXRZ z!dRkv*Icn94<#9OV2tB`!f0LrgKRDB*T#h;d*?NYcQ0_JqJ-v#w2jv+UD%htho>p> zERCeS^Gu#vW7A!Z^iir6=C2ppDXiAIY~^f)_tHN}ru7Lvm2*dW8>e??(cQlNa@39R zM#j_Ph~5p8eQ)tes62}KCTkxj z3!1LNL%{AO+t@N34l3Rzm3`DbDwBJMm)qG?S6-Fmh-B_`$-w?jW7VYFb(j^sUfXL@ zLZg&N)jeU#t8oa~1g=grE@-^BoZUQ4qwmEi! zx(&H3m!#%TfDnRT3UF+^yrcqoZ|dw}t@*9R9|oA4-o>dG@eBCOkh)CYn{jak8~k%Xvnh9qxP`Kxjf zf@zqU0x8BYDi?2d!-U3G`R*gP<;sjF2VpQX{DU=^NuT&<9@ z3?`a3fzCb(qYBG(rlV8PUs7=0+~{+=vWSVw<^5ltsrt%Vf7XhRlOLnUz8+8R_3m1^ zbjar{t{rR&i@UNVgoUGvmWVqh=mgV98 zbh7jSelR|~Hok_qEriIG#NVgwJ#f9dCGEK&F9t^F;hn^bW;CAmN_ zZ&9_^%*QGaOv=N1&q#LfG9P*D&j*X7drBJYuL_KUhn`Iqasi);A^T78ReTf%qSvd}V zkW$n6$fl7VIw`J}B4EiBzZzwPPNw^jaV~$0C(a>tY=Fig81QPfaQ=4S;fEzL5qYx6 zkaNTf3(>K`MeW=nD{9`fy!0~(AO*@$;-ruhhF8MhWU3~R%|*r9rGv2Ex*c9zgThh3 z818N1L+E#QJM|ahw|J(J4~u#s;YZrb2I}Yee06LXKGl8=z{v3qVjFI&AI055Ha#(W zuA1Eo0e2l{dQ@G>Mg!II@S?*EdF4`4;h{Es*ue0QDyWd-q2}^hu2<%u#>{9w+UYnn}BLV$0CZ?rvqQKX&f$K+NY7L3sbq>w{(r+I*2owU|#$ zPiK3jSMu_70z^g&O`R$S(pRbh5GFdZ<`huu=T$fuif!e|IOY6#uKXG1)dCLJK!txtGR36h5eX>DWkht3qwqAF!xy2&Q@R z7?vvS&@m=gIXJ#7GzJNsWvL;G=d7C06Pw;M!Naum6p4}av=mEo!rV$^mk_3NX=g~B zt&^;`QZ&PVp*Kq7^}X1{#XX}9?PuMmuQA=9Q&Xg6>yO0Zn~8dSI$Mb@7}6O_^?`~d zGV%Qc+YTMJm*Sp){Twby`=?02R%6FtmR1TCh*%fGaiD!*k#LBcn1t4yp*+)vpCNrn zBHO+~whbBS6M}6Z(kcWx>#b0!i_F7Q8^uKC_u#Ccn?L7EpMmOnYj6wNS^7ViFOp90 z)J4<2s#7PP6Pf1JJbJzcu%Kf)=Vp9H8g<=@p1)!=P`W)5ret} z^1ik#=W+~d7?SS55Nm8sn**NwTq9aI=Gg*VU`=$ZgGF197T8)8RSk=07)mO0`D z*;$3Vzv%af6$A<2n*^w0`y~(NKblf!dAA0ZJlXWs(iFT($wu*MLO7V349*OOE$OSs zUPjO>&hLb>s+C>|Ec3p!Va^|U1;9!Uz1~%uEz-d^np!GC>_qxPa!XSz$}(=z?1IMa zWS1o=|M2(n*fYo)yN3$Ry?o1~{fW)nendp~qFskYy&T%)?AB*rV^L z*MH$kx~pacMyEF$_NseE5 zAxsq@(>FYO)peHpbV>T|J$c_DSd&99)*GYs>vA@a8JOrXT2NDco2un1VzyD^WnZ9iq#uSOA96<8!?s#qs#XLed z_%sSiq+}0Kv7ro4tJ}8Gf*d7P(e~MZ#qGe(;FXy{^E`&DN!#v<(>g*?<9<)GU$Lv3 z9s(d$91P5s4r@mHlsK#WFrk|A7t-<5{=R>j``}9p?e?>?EnL**`mQOA)X*20!HK_~ zp~}O%H!;c8ceCA@M$6`?xN)KCAB{ zTg=3g0^&r_f+>&k%CqFeapqd3e=GE76@_$Ec+>I;hAx(s)6639G}_dP1+Av|Ipk<+ zyf}z@4%Xvy(=^D57s-OuPTAy^1&RTL*tr$Ez)pZE|2u!tuFVq^HnlL zEK_+Fu?d14-Kf#_JHG!LH8T0SKP+Hmz;hx#Fi3^THX1P0azm1EX4?5VD#mf34XM9f zXWTj~+Wkr4hzR}L4&p8&pdTu;`88yYZ>#(yr*Dj5%9M*uaaV=a(#|dBt;FrP7)RI5 za&ZYw@SOn!bm2T%bL^rP;FrJB#QUO&T-aLiAXzZD3i_VsYHhjfC^zX6D$8b1a~I@7 z%Id10wX$rpGyqZN5H(hdm%>fmYibgq{ABjN?wrXVg$S zc=hgzJMUQde{_wiT#Xbn zx8j+vaX05%e;K0=;1E#E3*i7xKz|Ke7-`#-T|_2V+m_vGK<@3A=}pdy>CbcuGiyvpCu&p(%32Uv)XT%+{=RV<@Y%UV1y&bZx)vb6BsHeK=wn}2MmR{A zs6?pQO&DP3covsGkU)>V$^d4$#J&kgy#)C9zWje;fdo1=d0CpR0p3}mK}krCebl}o z0aabUN=~dwC`X4Oct4(Z0UZGZu>GX1ZQy@pBlTa|XbKg)7L*+TP~Q9;6tdhNz@1$Q z#}|7R;#B_{K-Q(j7C;RskuRB-R0aP}FXknX?du4TE`)PE(3es=MD8 z_YK#P#Cgc$h0B}LgC+R0GD+7N_j@6n?5=>7zRP5m<+?2`i2(0ES>u&IE`NXUL_dB0 z-u{Gj{`l;FcL@I+!T^8O_f3D>a9e4_7IiJ?M4h~aK%E*s-E8g27rx>Vmjl%Ja=1eaFC@rr^4jtG^ZIFF^l3xKAf2pR(NiomF||2%Zq@snm7B0SyWYPqzSuGOt~&kE z{NXz1%_W^hG_u3BBu6$+Nlv>~7Kr6!Bl*f}$@t?;2Q4pOqooS33UUo88nFsrO823F zGrUem@H&6a>;mq#EoZp-H5YZmyYd9$nl5uLGBm5;+ac3}`rj8b};96#I8=YGU%Jefu8ddoF`U{OZD6sUV1gw0L#W zLhaj)fB1|!>`ENZ{e;8TgsDf4%mwLa&qsO6E^A#KtCtexAGb^`Oxq^0^T3A3$b^;n z)cDFQx?-Ui6Ga{b6xAu+sLa`4ov9a+67>{B>j{M~F!olLA})PkJ2pUiR-8 z3EOs)pfrBKZUFB79a>^jK9~@?4@7$eReKofWzCpJ|8_)+){uq{dC^I?M5yq8NO!nu>)aV! z*;K%z%`cOW!I`9@l<8UPvDN^2Owy5w7RPa#$u%bZZV7;UD+;UA9Fv`G9)_QMUYe}R zc(@!4^8R;sE&PYB$@()rSAFIiCsly<%~=p`4KW}CT_Dz^7eiw!dzz2B;)L7KL^m2F zI-K`SgRFj)oYFp%Pf>Vf;{)-rR!yWafr{4G^98?VP@V%WrtvWK_Y#D zG=>E%;aQI4feJ-6VBA-&Dn}FN{Tjrn0T_kN^Eq29WjQ0EO@J_36&UMj@`RN`$lE=G z+(kvHTMG*ZH>+{ruo0(?e0xPzW`nAWQUHDwEmQ+-KrvGX43W7Yaz?}tGm~uZT zTsf%hHLp0-#)Rq~W9%WOABVk+f;LTo;YQwD_0ZCQ_+BxfJBaGg0;r2umdUHYG5;C4 zD3c;8*uxNw1@;3K;RaJ92UUonB9@whc4hX!LTF95|L0Xnm$pg$^bDIsgzhEQvGuS} z>T1k;Oj(SV({DoBJk!OA1gN6#ETOGyCdf-VU#6Ox=LZKLw<+Q57aMU<6kFPb+_!>o z5D}=T-5CWECo}ln1ir#LwO`6-05Uc#+z)_LkxJ<4PINkzJgc9LIM)ZT{$0~N_Qht} zyx2iD;`7{}rO1>270y8_y8N2g%-lE4exs;EEYW?*sc4$JqGu?Rc#7#H3$YMLD9qTE zf%)g><8YG{)lxhB;6c5*naab6ifG4O-6~l$#-(GCd(8L&B~gYu;3uIqg^xKhBLYj! z;dH%-MC)eH1Ua`8Yh=M)9+q>JCVm&Hj%H|2leD0>VT2A}cUy zrtziEcwZ(eT~3Gxu0M5|5vzjQ`c=pXF0ks+Zx1nJ zO;GAgt*9^!%Cn%HWsS@-SA_{avPi)W4&ByL=c>;&bcJYANtHgm|5TE($0bBVdw#w< zDTxO8%)}ISE51dxmPN&dp7J5!{S|ro!j4IL=mBW!w0k}{PZcN{hd|65qtreFLbGl< z4iJrK2>|`ScRZ@`zr;NSyAScis*uV60ky~%zOwlZ$Ji_Vbhi`~K)3iB+IYk7YQnm2eODV!S7RZr<(@HxErMz7uawU6iNCIbx8%anTIevEt+B{=$Jpuh)9Nb?0JklPqA)B?phE_hRj}` zHfLPZu@t1_b_s&ERi@7S?TeG6!kZ1bp(`g8d8AXJG7KuHkL*S7oN{|;R~2%3u*~ZV zqgj;m^h7Cush@bv2MP`aip!7eIc&>-kg&^xn}qg+gJJ=Ds|QyywnsUjag@`zr?8jSX`IG*t;^!Qi+;^@Bu-;v(wtr()ZlrK*=CxxTz ze*K@93s-pq}82{l0ylkPp|-o=Zp3@9w`3{@q~F52L0G(oIc^{0-22PKX5+$N!|DaRkV@y40DRIHc6Q`Ymb!emGEb!LNd!eV@* zfn;-vJ>S1LBm(q6&QCYYv>dUcq` zdU6RXE6RXrYF4c18Lj_5^lf~CosUjY4;~RtAU*p1-R(BB6 zvtT=jvJ4^>U1eCP?MGL4t@&VsA?#^i zMfsI`&E4*C=(lZM`OTkUJX&qo(oaZR@w9*it zu0pHoyJI7@CfVGbd#lJ?3o)Z*v;U{oE%FH^#yz7xEy`4fEM0p^XZd7mmTCaw=(HiTW)yw82B_w% zwYrHNJ7xG-=MunJTrh9s$=5U)aDeChRc7)&sa26mLI$8rqeWn4&!LQPrR!hR%c1X1 zfw~c1k?k?%wGOi~94v+IuA-A>-Xc@uT&WnFIPNrQcQeEpd$xA`*p5u!- z^BhGvaH?q(w%klv!}-z@#`37huqPT8#TG7dhH#o*+PDZ=1b_|{VE+!@==!)6efTst zON-)JPi#s>BWxzxP9zE}O}6l$AbcpzRcyQT6?534)g3$zt{=ToOjXDmooObPm7g-o z-V*QoUR1Cp^<-7Jx48e!d+w+}IVb^)S#t5}U06cJ6b?6Q0-v$(qRPv~Ac+CdQ(B6b z90vADeXT&ZC@Vi)0(0t$(BJ5A**4v@V<^3u*7YWLXoBIUtV>gbI{7S<9K%!ez&zCb ztjDHPe(cP54UHM|j;>vsPNytaz1DJ`oE>Ik;t{#?s0Z$9$}M2pnceizcVdkb`4D3! z6>-y8t}HC$e2i#$PY7GKstqT{NiJTKIWAggC?J0iRawVSCxC7;p!d(tZMdUaW=R=- zIgMK1YJaOpAY<}88A;I9_{-TmM%_#LU?drN=z=5j7x*l3;Rt2i+2J@})oAzQ>bvT7 zcEQBq5Th!QrSGEvWxrSkTf-&7Sc@dAwz?x~Hbq?1j6m_C?DVwH@0L^e{xMAa5&s?R z%_@F0taEs2Z)2HGTpGB~uXQ~=#sVED9P2>82nGs8V1vBi zgZK}STkcP;OrIywzpq&SuQ9VG<~KrflL6Q5LHZn!Bbe)Y++gaAh71RQ-xk;duucPY z!@GZ|0g4PaIH2Y)U9y1j&5l$U1)FIgSAG;@$DygqDFw&QFyHmmZs9?hs4IXI+-9S2 zB<2$F+g|s3Q=?bLI(`|MSDhOk0U||O#^>41(Pf=L(5p^^)I9yO7Q_Vv_k;8HQx0v9 z-+3SDFVybtttinb;{vty&R3@>UA0Kr#{?jd(GQ#Z{T|zFJ*jJ1g)<%3URnU}oP#r?;2( zN7(c<7sPp**=lMUQt7UIcZb!vY8F7Vb-M`RuO+pAo`6t4G>BkJWJuC~`VA~G04OfV zK4g@M#C$w@gh5?&epxoayxU@>^P0^Wx9yahB~GN4(u9d|id+%UTxbD1n*&ddgxkr% zC>>U$RntXKyaB8twBz=fS~5Daj7ylB?)eFkDiTP|KP65~bUWSeeWl@y0$Dd>UQDzn zXW20M#z{`sjmoa*K4_g=n#pt|baUTT3vG0%CM{HcMOnC`!)SMvH&rTnXZW?N=Y|vT zjOhMjbts~fIJ&r9!obHV8J@FWPY8AyA6Y+Qhqw_DTdR8zp(o!+Q6Pg7l5uTfrP|7x zJ6hWqFA|jf&vU36>Z*&$O^5km;bN0FUn}3pxb+9UJc1YK9d&w!{ntopT|D-KV$gWX zB1RNYH4>65&v%~>yAQIy&;==w!jAi+mEBF8$UAJ(-Y-r=CG&RkJWa54$)0zw0gZAy zq9Q!w`i(sNE;;nR1M?SXCOOMpehH)7@sZdY?E~c?OD$fGmmhb0II~vBbpwg}Viw6L zBi6MhvOp;oi#SD$md#B1W}GdO&wu!eO}iX|9Pm@mA(BD!s5>Q^so362$~~3#qQ@UY z>G^S3b`?wY+a9vY3OG$OHX?{xtmM64>z}Vy`QQa2J2w*SeI{&v|2@lT(WK zg2tQKMG$R;QMSA46JRv8exM45K9p`=qhyX9^5+wIdOMo1ot=%cGFvU z4d@CY&M=%SoRtE|*a42@B#Ay#5jMP8dm=x(OszL=^3KZ~k(|Z$%v3uWIL!Reg`q6o zD+`&wQ91IWvQWcJFTjVWOeGJT$YZV3Nxx~&Qs~y}cuQroLfc>Zb$3s8^TP_d2;377 zjD;@{lx+a>VEw$OgaYEeTNm)Zm-F_&5e$?|+kz z9l(t-qu*2WV$(DmZ)W@9~wq>2r;XiC!1VcG^`CZKj#rgZ5#M4`$d`a{ zq2pmXF2=}$-#8$ey?Pw#SlmNnMm@fX*m5_e@8FsCq=O8WI(cP|j0jeO*Uw-IG|Roe@)nhE#Vks}S7eZ{ z8gG;T5;3DxC}$A;b~{#`Dx0b1dGKjo392lS1qOdp@yz;_zP(hxzok?OXRp;N zRWipM9=%sZMoo2Z=s{zZYmu(lfRGf$UW(>@Co%|VmN}FZOZlX-Xnh(8s|6{K zZx)H#`6%uW7O_=Q4Ic-$LMd8g?NLfXQwLbBMBPJlqHoCXiSw$+1U*>PlbKVW>2Kgw za56AOEWuA5QN`Jry?_K~`7cf{QoGOPu0>92%7~Ck;+g6@gDn@e@1D;)?qQ<8w4(tq z*79Et@7IWV!^yt9yqIoCA&^~ti8ixi`gWEEpBb*lKz`QOYtXql$!u6fv*g~^pEXTJ zcU(zZGkSw+RqoDM`(Eln|MB2#@YkR?rL4c6iEdScnkVWgi__Qe`S2uBZX>Ls$@(6p zYmX0vCI)p5zh{@{^X2Xjn-MN(-X>TW z8Kkl9C$3`?`EE%%CqG}8G_u1clqhSFcxuo~%+O;fS*j(p4`OBZZ6c%Hu%@tE(p74N z=}atd0Aj&Up*q>?AfeetBbv zA4PV5K~h`!G25$9NLGOsI(1n3kPqvG3G@rZE(?0e_N)F=%gbtv=FvfA8awsxPKnI+QG6EyGN1pR zw~DqBD{GNNx$|gBKxEP}ir1koai=nBQivX$sy6cbs{jv*aS8G*wjup-zbre+eZ2O9 z5K%Y%FdB8|h!m9f5nJiOU*M+K;!m+rLg!9VP8}$*_5`Gea;#PuELCZO*8@NVAPOd3 zdE3fe>ZselsVew@?{mP{7vd+~9Bb*HxyEHq7riB^ZKqCS%$Q~HPW#dEU-Ja>m3#=G z8AMyQ>qoA-L#t_XRygqm2qE%V>Iw#E_2`7o-I7GD0Ca_bhMD@ZLS=gTKwmLbO${DeA4TE6g+xu2({ z6XDH|Ckx!l`M~N?tb8Yi%vfFpXeeZp^dMVHv(Ix#s9;NDJR{&St$AE9*@B%TUw@+# z{2jk$i?Kk#ut1M#kSWBHWnDoCtFcpaK-!$_G4zC>$TvP>$O=3?Dyl6aGRLuU!>Oqt zV2U^UeggC;DOi6(Ywt#N$4|(UlSDt9J9=m`eSBI(^}W@&K}CvYLx!f7qiajiKX7Q5 z9t)0>j|t86dZ4fAZr0*fCFO9dZuakSTkz-lZ{cVJqWWLQT9C+vf-C`ibuwm4u=~q% z%fBXh?Kug}VkuO5sCn?yb9A4B@6O$9_e8t;%3c?L_`sSsUpmOVVGoF-Kxzw*BqDN( zgYMM65XK|Mnh(NfN*{~*7$xRur|;YuOD(#l3Q?|4+m&5a_D&^n;nDRYau@{Nk3WZQ z7V0?IMH&F+=Z=CN4nc&z;u&IsF8H^Xt*eD?qn1etuX<&3Q5q`h=evs!)5xS+CJ2=> zYwoBh?ipKb%)C|Q&fY1pJtfwAL{U8_55!?eqqR}3l9;qazs1kOJ%?#Lw1<=J1nf5d zcowcw@XWTDp1~5WNw%thYfx{6P&09x&}=hmw2%EHJQ*&yy+e440@WaOG9WkjJPaWA zf-Uu4XjL%c($n9e$7<`J=YCPg{dmD?HEUJ#A8W2}9|~)pPVel7cP>h0>DA_0QKyEE zxuOkrDw;y{2Ci>INqSN%Cu+pB7qjLR5=ZhkA#}tTMbI?G2>*zba{~3gCGsyhqZReZ z1sV9gc3d)b+>~8qI*nc$$l|%-k-^$BBezINO2YnRcdzFYEAk1UqUd5?9bDNR<%y3A zDY_Wra5|KTr79b26h%BjTc5u(uSSsgs~~MB<9Jh|UBRy)VNZLa`Q&Pw^Z1yL7L(zQ z!LOhd2AWZ0c>Ly2iu++Bu_{EkRW!Hh=MvZnrQ${t6Ya0Z3r`uOk|@BW%X(8T4vL`- z(fF)dfxLnSxiK6lt49)yw-Ongl?>@-ZZe?&Q z5j(hF!?J9XfQ*4_O%fG%_J>lYJ^|6W(@B`VXhckXGsU5qU zS%2m|3+V}bc8tf)F4~vHGC-!t9B>+c#L}T`cg-?9(n8~86M^nyAY`_ozbr|O+{S7z z|AL-W+)M4tdHTELVO=h%OzNr!aG5)I$@X2?fB$t-wj?&2jfmYG&)M0-923_>b{kcg z*i1ez0*MayGcr9o?ut{S7Hn#y-F4;0VAZrxP<8ZD;bfQ}bgbv|=X3K(|HtFzh8$fr z3$CdAyJ`JvJFi9@C`}u{V~=%hR9H}sNVSJ#&w_;SV zwguZcA#Hf5K+>o}4mJf`t-2J~kqOzb?);uWvohA-gfSatfYN#tJGwI;c5e0I$5KK1 z+FtU_iP}+dH6G0!8?Ece`v|>0e4ra0FJ=OR>WFGLe_b;te#4m5y^@-V0jCb6CRYuW zi|tl55CaZDI#lOzg2Ig=v-0we+CY;RUz-qU6O|{@qEVG7Cf5y-*?G71K*|&!JcfET zEo-HzO@(|a_u39iaN}}f= z0@WgzDN@Lz&Ev;3L$eZ|-n!=7h&^+Yr0!Uq>GzaR4u}MoKFjRAcQS)H39)b(NYJbg z2nAE~rTRl7& z^I_#fQqfw)%oN+YPt^5TV&w^=w?s?T`=XsponGkbi#O9%N%#j`=4VMbi9n@)xPDPa zbB?sZzlDA0 zSHa4#4f^3VU?kpz^nxL_aU;t5Q?pA9U2SJW530eufC8V~R6`L)VTui+UBya|=23A= zJ`D>P%~iOS6#Ge9X0&=Aw-R-ZNe{ncd9fdxSm6vWZ?W8X z9vg?eE{H-cVc~`zYrSLo<2FgZ*^7zGGV)h){GGOKbJkJ=;abQ9aa52JP#stAni5+XuC*TxWY(BF~K}4 z^4@u+-LdX62^s+t_2Y4Kp?*v$esrs4N>l=Ba31)t7xPs52YwtQr}XaoyO{C3UAV`= z9K8|=c!THUa5PSY9mU>8G&B{yP0RRSeff@DLt38zooqWVWs+|3jdqT zj{AuGym;3oz~eVs_I2v-axJRO2f3Bm`-f{GXJn4mn435n`d^)##Kuj0$&|P^ zEc~}~O2PAl>pc=0C#P~RnecE5V z@=S`OC>*@PgX5)exz|i3N_+A_H58iSi1ZF&63kDLAv#$5a4WH2-9oVP)9WnRw()`_ z@)lD!zZZT^G~g$8P^r*ThgT%=wBvXmsPiL#iB%F34|g5sFTj14lIf1nkTX0|tkhTT6?!U9dR{el zT;N>N61n60D);JsR-`Y&oy#8Qq|po!+4nxMXnImoa(qea#D%8A38!#$a0{i9lIrXA z&*zFdqPB<$jzFHlQIWs-UylAV4oZE*q={hU?Hu?N+4JOP*yXtI@Z$+NB4**P)bP4E zX~@^+zzs9?;=Zf-otH=+|A(0h2lTSeokmzp^mGVR3y@16evI|wu6(wR+3%tJ0Up>~ zjDS5exY3{d&afvbT-olV#4Bk8_l6>}*vOrv)1Kb+*^%}Sz10!du2_V`F(*Kg>L(sn z{H}N;G~r#_l`P{4mk1{6(p;uEiZNxF$ib(a@ino~sZqF?-xb5C=zoT*0G80{p-4Vh(v-j)W+;AIY+8~4KCTNDPQ0-od^b-+*sgiV6-L9F+7g*FGTE9 zZZ-K2amU61ktVj?CUxR#?4ne&_m#_;F~TMtd+kJ1c8-_;u}4N#Va9PnLsMR8j@2ft4{}IPj=lB=F3PSEAzJ!peVK4V{O8Vmc3)cMPz|O?-ckI;TbBl1-nm!p2g+{TCl%M~L3d^D z?quP^0Lt9BYcRa|T#4`|A9Pyj-5*i2S00|zHqE2o|2Sw*X?}&d zd-3h21dDP#p6Ni^3bkvQ(`#-T@l{#QP%!vhvGJ>jG80pASLApB=_YLHgAn2#pRQZ} zpFZC~8TwK*t3#}rQwHVG%OCLNPi(>g(RJM_v16s_0^EuF5sVCyMcNY?zXNJTYQ|!k z*frkI8<3<5{%T&kg?|P=%@ZetuTWm7KcVWA?LI5;lI zr3;LNGwL|M*Nr$=Ji|jvGytfk3ZeT=_@tfN^Ib|8`z0T6Rjjtcg3S30h@ML9VOWDoR8J|5A#MRr3HmaRybN(!r>zj2clqo4Y zyD}C}U9^X)%7ngN#cx6T-ifz?v_GvsK?a{FMk<5zz8q@m*jS=eC}4@}OjD3Bk{KN^ zz}ppyuvBP-tkJw5(B6*Gwx=LXqb0^}piN=oU2fK+9~;=wJSf|iHUclp!XCNv+CynH z%O+G+{teDRy?zeZoNT_YHMab~)t7{kuTVMLS!coHys$qv`R#sSLmL!Zn3-G|kAnQO zW+M5e#TEu_o9yq-7uT5qEK#*Q1O)YTk$s&(lj0BK0!aPD8D15(pr|nCF)9$9rmXoV zh#i#l)nw$FXl)D9WhygfNM002B{50jy0onLSRJL(B6e?z$3)Tjl4F+Fhm!N$>lPX@ z$;(U(u227iiCu6_gcxOz>;Kr4rvHm?jy{0U!wnL7v@MZ0K2VpK?9SC6;q!~lybnQE zwCyw*FjT8-7{XIyaO#u)sy>{bUmo#69oMbsQuAp$d1|o`iTlIpMeZE~>d=#NUmn1e z3nP7JsAC_F&4zsi&xm{Q#-!m?Z3gEH7gjTNt6f?8_$O~%A2gAJ4Fh@(+^?sEn-BOx z^0hQV-R6NHjO(4LUz_ezr8JJg0tw#Et+x4557_GQ&N$aS6odAGH2%8J%Asab4ZMm`|+;5056sV z05t4{n%casUsg;>EeUG2AtQv>3YSrznUU<<>lNO)d#P@Omy-4t%kX z3`r_(eHSZC0>cAUr2|+E*pAI2FpwkDMC2Shi9r({fagyuVBiX3q|V;gD_;o`9|$sp zzr}}&>=e7Qu6L#6JKhMK&*}_oL%x3w`Iquk>N(%%7PX-R$K9LWcMA$ID#ASs6}u z*z7C6W{0QPBH4?QCNxw+6V|}v-aQ%hF0`0+Lb{0=6J#5>GsRz|rD~n%RQHN(ImQ9( z+9RJ&n5ySTi{LU>ZT50%U01gzuDG-$)P|8NNK@J`$AJ9F)zhMmU?8bE@>IB+u{#N! zrKVB4`Ggnl;=td?4c!Xkf)~Z0%0IeGQoq@Lg!B5wS;~HB3hsPuAq1fJvLzZhSk^!g5?q)7t~Oey6CBeakQzzdT&{FN;fD z$Rvoze%{b@b$!`b%i?H40YbRiNS~J&r_R?Y`h}-_g7h-VHdOL2GdO^th-i^SOP_)` zd79(9obR*`Q7R%XVYFpQHV4Et$t~#0l6(CDd9xTf083sP9$&sQ&e|AY^xh|Vx8~gA zb!``sRdj8XyMGk3)_(Vn-u$yW|f%MV1+9-mxiwgTNzt6VMO5$Fp zfD9Gxwj`o6-TIe&1mu-F7RnwEhh6yJx4K1r^?s>8d^j&ZumzEbJ&eqauw{PpN*6tn zS!%gO%xV*jwdfs(9ah?bS-wW;6j$sC8A*1zmyeB2z z^+RPs4skR7-qGRqC;&t)C}lp!s$AL4JCcvSKp_ndm;3S9y01Bfoc2dWeZ63|`B7cj zN%(Wqcj1&(fs5ssmER9mt0)@o!EWkLE(PS|el=ue`q#wz7tRD#oC*vlC23{6)Qc&d zugxS|R}$*8?s(;o9kye7@OWYdmx9CF0l&2*<3rukLHWZjo8jQ`c+SVth(_c-9zDIh z>NiC}r(2#ld;3*u2GYzBo!P1RyWiiE_xpH)i}tOXDf{N^5 zrOH*^$CxBP-wqj5P%mAABQVMe8??v$IkDO30Plt@9Cl=u{BLIx7M`oVr(w?!leOn zHAx#+xItADCgI*og5o;=Yp0!K_RxK&T~U?!Tki{cNb>pmSFv&KqW%bm=WDgQ8QOY8HMS-OkmaZ8jT*}rlICt*>nG@3T4qVoQuMBw>25{%-DUG9KOlrm|RSw z-U#Z3A2G{Bo!Y7|4zH}Yq&ze9;Lml}F#XjWE~4pBlyRA~XA_mtX3g_x>#ltu-Sw2h z*n z_gzI??ElBEA~9!}g*}vkkxkPQW&?R^HJnYXAf~W4O9Bc3!`_}Lf;Az!Kvzqc1<=CX z0Rn|W%z+MIQ)}=y2qT*+)ZWb56ar;%Ff)IHv4B{)*jYh5jBE-JcUOC;nG*ve+JAYn zw6~K4!yrHgNdXRa5D$nQ#KF$V&c(^W!p=p{&QAY^Q?fVve?c^%U&Kn6_t=3E6@Lq z^9}#@Zi<#J5a3%-+-#B%6HBliBhcCb46|^8fPpUmYd8-p2P=pXO+@5B`Ls8&LgV;9 zlBoHX79g97iIoP-7L83A$ia`sCT$6Ig1tF?GyhBN90=m(cX2kzc0l+!fpQ3nxpANosDl%&iRRMOzvbE&d2ScYUlN&(giu>eyJ z!2TDQmAnfoqU*oN@llB(^COW`ej~Na5u=&R^0QAHYPL}#8d2ZX0NpyXs6Ntwe=*C(Ggxc~WTV?n`4r!)0=Z1FY1+i#k=(Cl`@Noa3tEZRWZN8p9X>a+0cn1{6^;U8$e9!DlCncaY~*Ey8zQ9t{r; zwu62}eImV{6Ns|TbBz2vre`Ts!`pJHyGlr+=!0&x?XJ-3*1Lb~-+#8327V_6P z6u16*3&^88dBF72E<}yP@`dW+6VR&$lu}mw&%^)WPx}U&{Z0F&M#Na8FK?m92;s^N z8``#!uJy4JQBVnBTn~U0sOMlKASGk&$_Ja?IiYHIbg1$;d&m zM{^59e$#k_r$42lZy5=jw&qhalxKEwl6Uz$%z83|1DFY8If98%9N>8)X@S-JW48!1 zFnazr$o6anBe@f&_8BCPF*HWZ_v&kmlbf!#g)$7sG54Rjk@-J>lW4%02(!k&SGB+< zQ8*jv160%`yL5dWFbUr1c+&VDStBb>+9C!k{X$18<0|w{_B30u!>A**S{7zY{!~3! zoF?Mhlwo3GQ78*-yIfhrC!~Im+!Xm6jt{e({d1KmWRQ zF9m5n;Q-=7B%3HIad>+0uxaF3IibS(LxOLCef+aE59UH((!QStjnFAdy2oyY<`|Le zjaRWm*?E83pG&O}b$iAQvPnu=z^vn>q_5>ey1I5eJkhbh#)6iplMdqpbyN*y+ee1& zBWqJZ$LojWI9C9Gv(?;cyD|zZgC(11arD%Ahih`h!p3%KajK`HzN&=u$r*p)!T?zt zV4_sD0M;)?&`h99(+{ztB9Gjz$^jg5vN#4$k_**Po~JzI$*Gj!)S}nNI1}Q|a=lh{ zow$*FfEm8aYj__SV_Gx>(L*?0zBY39_er{R5P%9=o>|RFZQ{@6RM?+L?5zE)V!v53 z_tr9Suzd{55%Ig(Ze#e#)?MyVN72A*U_2G!rn`=ROD(}7aPyvSb|&_UtfD^15;aLT znDzml*%ecv^IgR^r(ImGdiXIz-@Vb?X0~@HsgbqsNA*F4hw$6oWGSx*UB{H2RmD$e z>@h>H;UWFkobr!Lx%^fWLNi6Op>4}Ud1Esiqazse83{&8Rr91B-EHGP7po{*_U@no zs8ba(j~9Hb$w_JQW1@#C@Eq!u;v1N;g0*UuQ{daw+-`dP-ILY;8;ief>@r%ZK=9|a z{4lu<8AxOssJ!77p01dN^Z!EGp#R1;y6O;fG&VUqGl&~dpB>1>VTi`2Vd(*Rv(VUd zfchXHClK`3r*3Z#19I}ejaUB<+}s}cKl%SZHR76%`3(u z$uA|&58~t%=N9AT5CQ(bA#bz%Z;IpK`Y(n9{)Yf<~^oX &y) float d = agl() * cosf(_sub_att.get().roll) * cosf(_sub_att.get().pitch); // optical flow in x, y axis - float flow_x_rad = _sub_flow.get().pixel_flow_x_integral; - float flow_y_rad = _sub_flow.get().pixel_flow_y_integral; + // TODO consider making flow scale a states of the kalman filter + float flow_x_rad = _sub_flow.get().pixel_flow_x_integral * _flow_scale.get(); + float flow_y_rad = _sub_flow.get().pixel_flow_y_integral * _flow_scale.get(); float dt_flow = _sub_flow.get().integration_timespan / 1.0e6f; if (dt_flow > 0.5f || dt_flow < 1.0e-6f) { @@ -127,13 +128,38 @@ void BlockLocalPositionEstimator::flowCorrect() SquareMatrix R; R.setZero(); - float d = agl() * cosf(_sub_att.get().roll) * cosf(_sub_att.get().pitch); - float rot_rate_norm = sqrtf(_sub_att.get().rollspeed * _sub_att.get().rollspeed - + _sub_att.get().pitchspeed * _sub_att.get().pitchspeed - + _sub_att.get().yawspeed * _sub_att.get().yawspeed); - float flow_vxy_stddev = _flow_vxy_stddev.get() - + _flow_vxy_d_stddev.get() * d - + _flow_vxy_r_stddev.get() * rot_rate_norm; + + // polynomial noise model, found using least squares fit + // h, h**2, v, v*h, v*h**2 + const float p[5] = {0.04005232f, -0.00656446f, -0.26265873f, 0.13686658f, -0.00397357f}; + + // prevent extrapolation past end of polynomial fit by bounding independent variables + float h = agl(); + float v = y.norm(); + const float h_min = 2.0f; + const float h_max = 8.0f; + const float v_min = 0.5f; + const float v_max = 1.0f; + + if (h > h_max) { + h = h_max; + } + + if (h < h_min) { + h = h_min; + } + + if (v > v_max) { + v = v_max; + } + + if (v < v_min) { + v = v_min; + } + + // compute polynomial value + float flow_vxy_stddev = p[0] * h + p[1] * h * h + p[2] * v + p[3] * v * h + p[4] * v * h * h; + R(Y_flow_vx, Y_flow_vx) = flow_vxy_stddev * flow_vxy_stddev; R(Y_flow_vy, Y_flow_vy) = R(Y_flow_vx, Y_flow_vx);