From 8ffef3851866ad1c152e32c4918ba9734bc82add Mon Sep 17 00:00:00 2001 From: ZHAISHUI04 <3150778793@qq.com> Date: Sat, 24 May 2025 14:10:05 +0800 Subject: [PATCH] =?UTF-8?q?go=E5=92=8Cnuc=E4=B8=B2=E5=8F=A3=E6=9B=B4?= =?UTF-8?q?=E6=8D=A2=EF=BC=8C=E6=A0=B9=E6=8D=AE=E4=BD=8D=E7=BD=AE=E8=87=AA?= =?UTF-8?q?=E5=8A=A8=E5=8F=91go=E7=9A=84=E4=BD=8D=E7=BD=AE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Core/Src/usart.c | 4 +- MDK-ARM/R2.uvoptx | 75 +++++++++++++++++++++++-- MDK-ARM/R2/R2.axf | Bin 2846852 -> 2845372 bytes User/Module/Chassis.c | 107 ++++++++++++++++++++++++++---------- User/Module/Chassis.h | 1 + User/Module/config.c | 2 +- User/Module/up.c | 62 +++++++++++++++------ User/bsp/bsp_usart.c | 8 +-- User/bsp/bsp_usart.h | 1 + User/bsp/pwm.c | 6 +- User/device/cmd.c | 9 ++- User/device/cmd.h | 12 +++- User/device/nuc.c | 125 +++++++++++++++++++++++++----------------- User/device/nuc.h | 3 +- User/device/rc.c | 23 ++++++-- User/device/vofa.c | 11 ++-- User/task/nuc_task.c | 3 +- User/task/up_task.c | 5 +- 18 files changed, 330 insertions(+), 127 deletions(-) diff --git a/Core/Src/usart.c b/Core/Src/usart.c index f133fad..329c947 100644 --- a/Core/Src/usart.c +++ b/Core/Src/usart.c @@ -46,7 +46,7 @@ void MX_USART1_UART_Init(void) /* USER CODE END USART1_Init 1 */ huart1.Instance = USART1; - huart1.Init.BaudRate = 115200; + huart1.Init.BaudRate = 4000000; huart1.Init.WordLength = UART_WORDLENGTH_8B; huart1.Init.StopBits = UART_STOPBITS_1; huart1.Init.Parity = UART_PARITY_NONE; @@ -104,7 +104,7 @@ void MX_USART6_UART_Init(void) /* USER CODE END USART6_Init 1 */ huart6.Instance = USART6; - huart6.Init.BaudRate = 4000000; + huart6.Init.BaudRate = 115200; huart6.Init.WordLength = UART_WORDLENGTH_8B; huart6.Init.StopBits = UART_STOPBITS_1; huart6.Init.Parity = UART_PARITY_NONE; diff --git a/MDK-ARM/R2.uvoptx b/MDK-ARM/R2.uvoptx index 4e7b59f..58ce169 100644 --- a/MDK-ARM/R2.uvoptx +++ b/MDK-ARM/R2.uvoptx @@ -223,27 +223,92 @@ 13 1 - a + b 14 1 - b + count,0x0A 15 1 - count,0x0A + count 16 1 - count + raw_rx1,0x0A 17 1 - raw_rx1,0x0A + gyro_kp,0x0A + + + 18 + 1 + nucbuf,0x0A + + + 19 + 1 + vofa_send,0x0A + + + 20 + 1 + SendBuffer,0x10 + + + 21 + 1 + NUC_StartSending,0x0A + + + 22 + 1 + PIAN + + + 23 + 1 + pid + + + 24 + 1 + bmi088 + + + 25 + 1 + ist8310 + + + 26 + 1 + imu_eulr,0x0A + + + 27 + 1 + imu_temp,0x0A + + + 28 + 1 + htim10,0x0A + + + 29 + 1 + pulse + + + 30 + 1 + imu_temp diff --git a/MDK-ARM/R2/R2.axf b/MDK-ARM/R2/R2.axf index e2feb1df69d1d66749149a8c83148ef8c4115312..8272b1a95aac2cc54f761bd6465be606b29a0fb4 100644 GIT binary patch delta 141936 zcmeFZ33OCN*DhRDJ*3ka=*)A|odLoeMw#gZXgZ8x6d8knhB*QHdruRrM=|l$NVQQl3MNEW}Tw)+?Ncn5T)ImjbW4009zsiWN z5bw!mqFZ}z$JoT^+MYy5@b6tlbScm7IG>u@yEoAd1%K!n62xPA>^N^sybF>G@bJ>Y zV9E7og=pH9?LUN9!H$#a0?lrP!Q6xBy5q^m6H*s?uZ5CFf{Gq|oan}bXAYkG@Ekpa zs)QP9(dKofq^PTKgKkW$^0qy0s5cxZlED*W4LGj{qNO1|;ZgQH`=dqZsG64W!$mWGIfg( ztMAILcMrauZU$0Sg;&3`EFZOUHp z38&*Pu|7WGV8URUE;J>yPe158+cZI6(_E}qU$?GMU#(!4KbhHNrP5xXke8UucKU>o ziAFZrCoD`f77X|8Y?_=ZHRtPhHjPTH!CQSjx-?9B$5+#Ac~pHpeTDk^mgSZ|wX%wt zP+lY}zuK(Uo2*Rw$|Zc5xIXMtKl+ID62>GY4S(@5Vlvc^lL9@cS!arpoG1f+t-L$4 zk&-CsHQ>Ee#I&c0>PtuPd2nW^p`MzR(yE}Q{YlefU%f?>8k%163yH}_Ci#Uv$t85K zuqS!1rY|)05{9RIMqd;XQk`YI_GPiEg5I9(12J;uXq!qp<+2^6nFezN;7?pSvtG92 z-(G4C2j!4l8e`Q0e#@mctK`!6y}U)t!Yw6gW(l=O1v}g*E2~#qNlujXte0FX&m*}T z8qmVLD3x@tSJzDBmrl$k8{w>9n6Ya?st`7JZzplO~drt&?qnvAS6CVd*vI7lWnw}Hf&069TUSfz3j zS*R(L%C$sP_$%EEXbVHPtg0I>Y zUrRejHgfF-a~iZi9jqw@uprko{BBg06s+oHw^pty4pkkHtJ*75SY|XRIbN>L&=}_6 zBd3Fk4?%KNh zYFni1hg+`Sh?3d~zZ-`{o^z=k7_6j1rO-^usvo8$CNJZ@LT$}HO0e!UnbJ59 zR|O&#A7`Le+JQDQcu_E8n0E_4QyN_?q?ohx4JhA=Cq7KDnltCduf|F};lF68XErJk z*^i9Im?^l+$5r0MB^l>qs+3>41t+F}bCzFijTrU9)pSP8R7&@8+9cs4b4vTKT!!Oc z!^_w({o%JjAKc1I!Rz&MS})EUZU-;f3SOa0=5w)UeGgc}uYbIvaAa~1TOpMuwg~4k z*Trs^$)B!h2XYR`Q7uAA)=J~3AXyEv3gizx1ha&9PS(Z9t%4_OcXG2=V^v@ObcG5m z3@l4LrD!Ay4`%O+`P_fnRYgy`c8dYL!OK!6bR0HH*cdKmb zVq&Vk_%t@#Z}2F6MQWL#X?HJG2}|0|QAbF=fbe;{3G^i)r~Pc8{|wYsw71YQopd~) zE>zic(#rup6Qrjx#@mQV+7a?MW-Bj!Ho)*Z4?LyEdAXrpWsS5Fv(9Qb&aAOVxgRVY z(dY^%m2(1vq68P*`nVJmutI;31uB#i{lb)Wr-|VqCF`R z@;hdcRg?Agg)p%?4k&YcrVSx0Y=XcfxTEC?!30u+qcqib!0`Ek9XUBLGnW@S(G(HLYerQ^zH#M7r zoQr~-3uMkDhr)4BE60y~UTk2wca}94LO~la+IXzNO0|hl5*4J4X;r+ZX_Q`lbrOk?E_nAe*#J)kd>-&{z%u}U?JZeHbCVi( zqKQ8=<+s+b6HUF*On?izE{Ve<9ebL(2V2)oZq=TqE^;g7-o_%_)6_9o)r(NyK3G*1 z;Ot;k&j?9fGw6>(@2)**zObNcx1>LRCCb0@H-{6lZWtk+VV`_FTCjJu)1AVyZV6?N zv=o<+t9fua>g(rAwbCXTuaxojz}L!nwT$-$eqYNEO)(fkH1#?k!ux?o1@Vc%mjDkB z;?sf82d)X?bAiunA*Pq*&9kb&P~SyR<)uWQ^5tJijYx)LZzH|w6FTOlmUVF@W2v-} z_M<2*;<+XkG5(4nB3dd8P6NCaa4L9)22Q)S5JmoxzsYyF zO}>rvxc8>~T|xP*K!x6{8?Pu>AbgUSv~a~OY=eSqVS%l!Tw{XOC}!O>w>@}6=9z;4ECGs)8LGaDUkZHCi+5FCb1cbMG7`t9`Cm-E|Zr*|=tj>(utG=ouKIdhb z8VM=`H4M~9P|v#seb3y4VpoL8?=%ItCKWUl1R|w>3L|=UPrlzJA+A0PRea$|%_Vw^ zRVyuY36(u92=i?&;cU+%bCPx3oAGUIq?=o{rWG%c@oTNyR(~0vqzUo&kntm7A-toE zf88pdDdSUxrd~bSu}(r}?;C2LlemTSKGn3Y?%h74RJ5-U(|>k;-*94z9LOv@z%yAR zq`mO_e&;G|I5C-Fh@SejP*a3741VA5Tm-5iQw8eR9=-wX!j5-IsO_IXHwy3f|AlU^ zdv(BHVQjXi?w>=~Q?=ij@ z7Cs)|pLO;Mx(RpFZ-qq@{z1107boncbA(4GPK^3Fpmt=ghZ`)>NuqFh;BVMTZD$miTx(Glv{Oh z)3#b_)?UvmCch6iY%1oCS|#=H>m(h~<%T!v{-?4(g|<`v)!{D>4k1um-fe?ySgnUu zlALE8Y!`t}lDnee@*!T?QK4x{84C{xOYfXQuM6+qIW)P^w33*y4T^AbfO2Q~yzN;-8kHs==FzfCXMowEuTZH;)Pt$|K zxans4oN(Xt0dZe=OONyE7iH}rkE>Q{7EVkb(Bb2j+)VXV11+(7oDII6m)ejp=^3}F zmYKG=j;pEZtBb_UYhNp5&G@GOPx6B!R_sXaA-V2$A@av)_60m z_BfyP34Lb1)o#6)PbsaG1!F=JOe;;m3GgO1#Ve%F%FTT)z=N|bu48JxOEf{7+KSnf zuPB%a5#E}d5@GCwM4^0Ea@bvdUiCe~o>^&hTiu(p_EL7blQ65eN9I}V;G{m_yof+3 zyyVnh1>IF6$Im!pAy{3yzRYsAlW?ebR_0uf#v1L2v9&1-Z_C*#VyaqbDYa(e_|O-< zGtpDmW6ro-frN z=YCgR^t}aC!+p)9y2&MDDE+DKg$2E7nOh{fgk40}h&OK$*K*u-vj)3MsligB)bN^1 zsli$jtRZ-O;&OX$k$W~MM}n3KK{;*6GRSqg?5ewS(ITqb9njU9OvUpB@6yz|3ybxP zK2-O|(kE|P7X}M=+-4<{e)ff|WYYJ(U_Z!KGU-cSupj;>E1C5EEpn%Vau(T2CLImR zSrsc8I#6?84pRq&&i6^Ir@zj)d?}?aVcUw7yMD*oDKD{HE4P?SDvH}Xek)l}Vk%)$ zgTDwfmPx<*GFoZh_={!QIbU2W?U>&p(?0iwD@TD79c1|r>jEoIQ8vykynX+9`hc)^ zRTsKX_-s`-`k@d2{D;tG^?bIbMKCTOC^W3T8{tOJHJ8~PUctC_O8!ibRvyEaXO) zE5F{qUwC8vK-SAGxYiG2JA8G6H~h(Rreas)I~%bP3(+x4ZZWg)osz^;C}0-8OMWd( zE+3S%-u3%MX1a{XMzNDg@8XE25%!m7#oV->Nw3J%@5{OMbkhqd`(GwH`U($r|GHpKWP9%D1 zs5}2kO2nR~t#YWOm$m~>j?hawH$4PjMt%gJ0iHVHTlp;?vmJ7bu%~HL$3QbdZjPk> z&{U?^O7naMgkz@Sc*oy)?aid)4^8){?rB<;D$PectChwEnGd^TgX;0VP5nYyeQmQE z>K8(yw=7XCtG}IBQ9ldn=cMukpjK+@6Moy0UN#Y=JCQ}?73yX2s$$-5r9F7xR-sL< za8HvJ6^??$RWEOkL$2_4UZui;&|U!E{^0#C$cxJKBY!LuLH--l@JT50Of_cSFV>%qIfIH)B< zUv^U@L`=C&BvKZ+X-rIOX_xP-N-`WS1Wdzxfq-&6a12r2T~8zRG>nwDJx$674}@eDwd%k;BxoD3PE{=99IL9Q^=(%CpphDxKqcgS|n#u+O_ z;}RLNgadt3jXt}C{>ViOOE8Sdgh)x=+?9vj>40LrC4e#kMR}_M83Fatc`pHM2TNS#0NUE4l zQ-u{3b7SxF>S{gC+yKJgdBno=HbPZJpLV@vvYL}ih($@?Xl$B7U9ryE;!O5)q3eEO z*dvq5vRWcdUZ}dozBy+_))J}bn{H)Ae-0ugj-JQ<_`e871S7OKR^!)a~?}c zTI!-ERypokg+V3fX4w8tD4Q$ncr32VU9P;pm1U!BtZUpgQxQT!ld6&-o5S{}gE~}b zd@N;HA6c8KQeCM5Jr?vXF5UxLwC#$U|9%5oG-f@Z3vT|~DC0?h&bj&T2X3M3)(NH^ z^2kh-(`Y1*T6SZ|cni~!d~!OU@(ER2jd4XDK0v*EQ8*N7d>rm7G;U2ux?dJH`S@We z(HmBSIA<8O3=@1?)7V`;A$6N^L7Xh=^dj3`6kZv=KLM;s%a|!ddXC~?qiFllk^6v!(YT*e<55$wq?)!OfDM7iwNJq;^iY7$&4!GUo0leRav}|g?eBQ$fox5h8OZI zb%oq-J-lj^tdZf)&@vU-NS*}y81HJ~m+cep=!{P`PNx-3a3K^$x7~+)d5Knf4u^h? zv|FyZNX}s*W2?ybBw(@n`Tw$b(&4RaN}{doq6WQaNmq?D6!Qe*YV=ZPxbM+& zPcoC+X>hBpZ8Oz{e&;(ax}!LVALo26K|cArkty7v{=J;;Ko1}n3uqG{OS(GuukXAj zL!qv$l$va%%%pK_GG@4_A!20ABujd1uJb#eNmp30l2`LRBImeF4XUXM7*GxW*u*RH zprTPQh!44EIW_B;R{Gw9vtb!+q&%;VJUY)Uc%6&oT!6HfN7d2@e$HxFa)e7No#(*laKEk71h1fOc@3E_bq@5gm@s~r6n_FbSG)_2a2hjQV3dkZt4 z7(^3=XP;;re#52EnDEXM_t8;xy@eDty8RX*+J^} zpsHG_lY|{&0xc9?5@&Yn-`Ll&Q%=Ja>5G?EVpx7?N^9N1w4d+9hPI_?te&3&dyy=m z=dPYctH)5Ql5w>|Ex$=HgJqxon#^HM4_Ndo_*RfE(tUSk3jP$}|mpXS4kI z{G5scRYP|932EFdsJHfW)_U zJ``j;!@SW*0=`S|GDAI=dA*}oZB4;s@i`X+Zl5fQpc-d6YPP8~l3f`8bk7c-_>?p8 zzZT_Mea=b9dhipNg0*kqn8tcwQHwKQc=hS|Ne_YBWc50);biK*7%Ec<9iADlpCFg{ zoX>dbwmdVKM)Yx4{T@#4NNsU;7e0A5g=PyEpRMop4f4wr?&1?q3!2{IeBTu&+5I$^ zHiSuWeE!r6HF@T+>Ko1(KE9XTa8C6J4ZG**UV;a6JHPM>1D`YMCb>9r(ktBkTyD}g z9`5t_#~nTmea=Q1_tx!wuAi!Gw0DTj=~Q`nP%yY~FuHTHcQCfq!M1=i8IH^4{FiH? zLnGbMf_Pr)-_owBn2mb!y;+4hWdI&*(Sy0PB^|1D3pG-VClwIMO10`1CKqa? z_uYxWZ75ND;({f%g|UT^-8IrtcNV`x>89s3WM#xa0kyZ#TdsE83^J}C#U25w( z^hGt!ZyMLg=l7IguJ^Sm_1)v++w=5nt0cO02p*bdNOpGMm5G8b0FFV;xw-E9@|#hHZ$ zsOurT^v}6v%-4CC2@CpPfd}A-_VI6WWX`Y|>xgL$nl=^9NC#YuRl%p@bSNzhsHMw+ zX&B^bHjR|)nNm2fpRRZ+@TtH}o(aHh#Z!P!0iNs`3;ay+B;b>P8$2U9|C|ZHC)hM) zlFno00&|K$C;|iV6acT7GZy$*;4b%Iju(#xJ{q{>?hpLT93F6eejj|UG~Pw6y>0XQ z=Fh)L8v$A#Xq!MYm^s&AP&#wUybz@~C}r(IqODAwLCON<6qq7qu`E|xRHwT;gr~XE zxH+wOoGS^q4R~*}3e`lo;<$OhEi$fx#%NycT!o^RJOOIe^EyE3yZ}sU=_*JXZpd7< z^hiJ>EyR|jk-m0wucyN>kgimhzlZ3u@m^3xbYJ7$p&Fm*@Sgbs(JjV%{63Wt#(k!?_{LMaXCi&A0ZZ~o+?$%P3Jk~|5Dc?%OjKM#6bVH?ofx2UChe{|uQ zMQZ7VK%~O6C>%V~u)9=%x+|cSsTGTOW_?^hG4-17jX0ZytiRVL0DaS~P`c7OJH) zNYC;4b!H($g=M~fU*tX44d3s#;+co1EFC|XnrP)5d92maNVKoBZBJ8Yeg4wU@DaJb zaWG`3pSM=@=M+}l+a4Y<$3~^$UL0#VD7TDz+m9baq=G%=(gSEE;E=aHun3#VgN`jcB>2Y9g9R<_ zFbO?gv9emfuZK|7FtPV0j_VD{=BFW9((nwzKu`O|1X#D(7}@M#jZ_O=4f$F z6`TjNu>YmKW~LW~L9eCYo6ViC4WVzy@T-8$!soALsvh%f7M9hdunis|wx%yD_6VbE zOl+J-SXz_H@;$<%H7luA2-G~N{{|VnN07~XWWTVz_FFnzSa4{1+wQLE>8#Ti-@Q1W z$74F1+xfiDaW~*O8o;}RpAY4v8ER?n#>PdC+%fE~;G`Yo%T^&}TZCz51 z1&eDZKH&3ElPCLokU7FVY<;R==}{ryYXW zSpAoX0`lY!=&|^c9fr^B?Nd)SQ(VG}2fZBH;{nGCZ`Ng$9diYP))TpFXl`-?%QZHB zDSyW0cl;hIM(F6?0-d}z;)rwHUSpFx3^m?nFFsBX(>)i-iFt5(S8xM|82D1>|IXku zFh3g1l4CM{mNg8N2~%VOKctr8%F7LBY5>>YGNY01a60?o^Pk418awvW&Us@`4(zLv z-bEyO30wRDVff+4na3sk`|u3fUg%lhP4lCVn7as@jwA@{>vgQbCp=Vd(wqR%C=*ZC z7i4X1;oraWO3%8^W?EdC24XtxItDXKkB>l3!G@<$$a#Hs&Pg~5<(k80GtO?(QrJOp z$&W}2a1mt_E{zdsp0NM*wmE9ZggB!?9W8U>!jd#X<_rf^AT+(6bsHzwncJ!}t5v6w z>x|_(`P`4Tj=L6CN^!;#?y(!`_rinrPV^C>)}BLG318XsHIx0++>Z zBFh_~Tm854VwCVhg|PBiHkE{@kEPL-LjAG!fWJT1mR1P9V@ZG$jt{`^_~Y%vU+_~K z4~Di1n~o>YOhG)JlQb}($L&9Jh6&ee`rxxK|M(hks)a9(KTeMcbKlCL`-MmF`;_n+ zejgCNe5*ZOCivcJ-)6eMB>mk(S_fa_{FYeH6IrxCxbs9-o4ngfItY)P=p8ozqpfg; z%ic7=GjS(gqP4=>lWikD^@VEQExd5@OW3ydRF>N1{5Bv|ohpF&KcDJOzY-GO&Zj>K zcfOrLpA_zY`(b*g;CnkKCLjA&xWn@2K~w%reoLs2(DR);qE>mc9AQ!!<&=0~^*bA& z^!htPI+V2NYMsvc?s8mybUCB^mQ1WW87jy9PzFecX^8t*!pzf`@%?>3;n;}+&QIO^0Kc2@eIwv}U-;lm zMp`#FhwI%rj?}{NHN_I<~v@!TulRR@Pj= z+2T^=@addut;8xiCd~XG$$XzX+EHA=a>E*{DoE^ut}4bm@E+tnlq*EMlkVj2NxhB8!6CwZO+3i2XELQMcNC1!%A#BHO*rUSxACI9nA>orj12*GYnUd`o z0$By>ALLfBo-)?g%0C41dz`qS$uDOTZ{4;}{)lGZ_=SzM9*K7#rjfDt_Kbe-Xki+)D=v%Px#(RrqpwVK6Iq*RfwZQuiA5~_H#!YcNq`pg&;jss5__by7=HUHonnzhW8}xvX(Uf+_lkx?n zzR;tj$W+o+`T9~#^JrML7*-Xuz^XT3)f*G9q;?t)>s7e4vaD%**?4fKMf7d{uvOLu zN(Ndq2C_>a>-RwRL&$!}Z)=UmwJ4Qj_2z%h+ozJc%kur27q-gh{!RY;e<0t^YgXj@ zN-?%#GgJ|xEHBl z!|`20_p3AGT<-YBJxzV&kFewM0ahjbA?&@HQx@qC^(DVd$FF4toXm|o`TVw9+D)?= z=L_~*GR)>0)_auMkODjf_)6eyQG>A)E_nZ~-_oIzwBDEt_PZ;;Or9Hj5V?X$p3|5g z%AoQJMtj}`PENc4*QEU8p}F6g>NnIblQe3zgJdVv=Hepnoh>G7>2VjrdcQM5Db?U= zc@AzC;0_Mi)ho4Et)qTN+@WST5I+<&IO7*ee+0bG_+#HVBRNF`$G#j_}rES8Jzml*$ zJ^0rUrtu2z{bg)FKPZw6k?yic8;C?UhC_tmawg4HH83e#h`82;4iNfXOQQ>f$=7<) zXN5uK~o;g0JWZC~|Xs*SGI)W)M@*^~ zwg|Cq40JFFH;8ki8_906t9mHct;)=^lBaRMK{z{O-Cgh9@JxO}(T+4GLEu!0XCpEF${ zv95(2jXp}URSsA#bqj1kq*;2r%jLj`a_EeQysFagyjS?qxvBfufC??S_o%A+(4kS* z@mBb)A`5!b5a1bL&Z*ki=w6`N>L=1E;gowo+g-S-$ooZCPox!o)KqfmXbkG>X8K|oi&kVrDc(wpOi)Yf3<>UFPGt?(Kh}72~X**eRy2O-0 zq&IxrR*NwlnsI^v6b6V$MSdQ$&UW$7Z6xEk^c?PZ-?NH%Tokpy;lhuDb{pMI%?}7Pht6X=h=$_YS&C*x+rC zYd!z+X0cH|;Y07z@LI3>YBC|xt3tjne^eR%Y@~1J>tFCQ&RQ=&6RnbeS9oEwR4V^2 z!6!s+yV@py&Okr#p2UYTQzY7L!o#;qoA8NmFHI4a`BSDxdM)zC&-;h>6Q5K3j8wfy zca&xm_#q;V^78qll%%2L@}df)079h$@z=7);g+OHVg#k5=yvf=N{7&1qDW~@+;UHX15?@BQC@!hFXd{) z&nW$%tdnP_dw7w-QM?eXGof{+zDLzpvk8@Y!9fzK&`TUDM~QLxA=2f_IdUR^Kou9e zrG6e}WNnZ&KsFJdY>Cv#E6X{ka}6?JPr z_3ETBA{yeUNgSxAHg-P|A5zm^>=n0oOikOB4Rjad>Uc8aN9Qx8Zf7qUx5@Yg;GJbW zPsR!GY#FbV@s7aLWqgf{M+1+S@nRWI2OcToU(0wYaJ7t|l<~Vu-P4_37s-iq%qgK) ztJ%B1zpGMT?|UEp9oJRNZfCP=NxG_w^c_sR{?vWRnd<8sOC@KW>jzw>QEsn4RP1tI zbnSHIk>aDgArdw5JDx;xR=LCj8k*ita#p&OgbOuqaZNI)N2<)!bk(`ZfBXu2j34IC z6nt<<{7pj(=pSMiEyZ7KwZVrJalDqsX&PdPsk427mOf0|T=r=BYE4&Tc2KE74201^ ztk5qG*3oC^RPh@f9YGI@=5RVlQyrj^QJfo2-`5lXJR)|}(+4y~u7ERFwCm}3%%SiI zx`;j}-XDP(wLz?ppxsk8`;1Vnvyu{BtupaxXZ%r!G(ikR&~Egw*e#NFXHR>?yCdm` zv3$`P>K{c=Yr+S#Kb+lt;@~JcMXj$f9Jg0T(T+6zMVyTB7kb5iI6v@UEtgm%i-oV; zKai6ao1^KY^aF8i8=65^ieel3167Nw4YU)@7GE&XnNe?f_^d^2-? z#9+l#h+oFgAw8bN-R`g&MD!16b|oJTIJe<4?2U^@abr*2NUH7Q4G%asL4g^6 zjX2RGR>f0e))J3qKQ=Pylv_H=vs>x@s#-p1nx_NK1z6|-r%HS{mbQ)h3!Zkf@1cvF zsY$Ghr4Q1F#eQ+LH+@rF7DwNWn(lsSk+W9Gkqr{_<7t=fC2nfca-%jWMipa^ym9eJ zt5HQQFiMBxwmaaw))H{G6Zgc^wpkXpV$)8SV$)AvZd0~w(?Enre&@f%AHkUP9`=vP z-kq{dCjpOx!MH^tCMD46bfLH+fp($W#JvfaF>}NYiF90>=^jK<@B*e{niFu&5FbvY zIVs(c6rNH$0~zU#$WuqwwwtTQ#u{)=7vD{!ZNq-@aIIa%-xFzl*cJ~zn>C0pCDB3j z0r8h4x`BQy&P}Ffb-O^-LS=PVCsSjafq^3KXdfn|FWl@d@yle|kM0)Rq|j3|L2OK+ z=BQsPP7|tt?=e~MaNiSVtw0=*0aLe#Kc}G^?i6Fvv4*z!{7!U5I!swA z&P}H)=o8{s>9kACuU^_N4^E#eQtVC0pdF%Sc@r>KtB#s7{LZQ3s0mg(+YRbdIHz}pY zy+)drwAYu28XFK{X>ij=^|E@urrPg3BYt6|<5@kiw`)s#M6=!9?9;l?0>&>~xTLxSQBD4@@=P#Ao>XY&UTge^&?bGqO-~YGfY1)WRfO zRU@Y<(XH%Gb^O{|uUEwPy3@OLhu==M=>|-AN9^8%TFMf#^72!AT}UmL-YK^%VV%MT z^$qV@7I*!Pc-^2k({y9hscY4#N7bpP;!`!cxL6v`7)!J~ptjtZ!6;MB3`4es8cVi^W*f|9;~CKDlPo=;@HEZbrX-Ir+yO|=RP!Acf8K9DQ-i3 zny#N(llrbYwS#!M2b>nM=k}!8(XkVH5%F7zuCr{oW;DP&1*`zrRWan`I`Pq=)Hr`MZc6bUjKq@%!F^@7z* zPcq+LzUJKRcn$ua1m3$LLz2 zNl>!-5C?0EXuNuNE78=dLz8zCw6ubBjiR}NzmnDXUlfAcidtDT#W%syo8XZ{A>P!{ zV~B1nT806ayE+>%@9GJ6i8uwd(_EWQbR)(55j06NYaG!Ph_$0>oH)Zub((=Yi0*aq z$0C{>1tC*VaOdOVb}P-)xL{9z(Y%@_i64WT&6^7w6CQ#HGbh;FO6!;115 zqflNoP8>V}^xW}8H&yIDgC?c$iT4oL_=HRks@G2-x@qE^F*Hq64$enK^8}ct2iJOT zW!x-zwvG)o>K|J)52_zhJ*>~Dj|8U39&%SKaspZi)_WL%F6da@gD$KU!!sV6kYU;LKnO2n(^lhi8^#X+jI3O=*A z>6UNA^ER3o+xI)7!<}!$@d|y|XQH+c-M8x-v1=g~;<=BA?nB=AxJ)iq1B(a40=}x$ z52_yG?KK5Odz}+E7Sc>@^;xVumAL&*IM!o@=<;5T;(LYEXqLVrx+`GLkNZcfFz;`! z*b0-2d4DH`b2J({o)K#&(j->?g*bR5O96QNiCji`Sa1!Z6MxIxS#cE4NY&S;Zm3mEA(m{u`ak z^Qjbh2hnW@92)X{z^4JfWnjb;V`(@m?;|#kqKUmP^tstBT*0xw;WL1npdhpW<`tp> zd3}gQqp7;L7dY;F%iYH3U=eV>32=irei#mCIp9z?P6a+iygG`;#dd~jK5`+|`)uOD z(QxDIM~a`~ol`pcrYhdIJArexAywtTgI=(BB+(_yS~JVxXS#wb)FX$1zkEwAUaL53 z3~HIxQ`|TPqjPBl(LHfKz6$tY@yBA!r(H{lu9w&yvpV)LwDVaR8b2~d zJUA9so<>{y$PLUna7(xF5vu~ur%Xs>y$vHO`z3a8h-e%~Q`yP>V*hcpqo&37{dEA*t)t>WtbL6Iw&Jk;yOgW!6Zxb!ZX8pV5>chD2yG09tG>Y2GjcLwCp z;Pnc!n4S^O7tucEtxpr(Jh^;bt1AkrzEDDR2gSx2G)v>!h1D%~pMtHZbUZxS6AQ(4 z<7r3jrTKhiD=zLN3N#J4_?fHh5%G{&uYfL4qm>b=+$9<(V0^VGjTRBFCuxo?=A$C- zT%{ABW9q%UsQWZjR>|>rY|$?(JN}ksM0bxoQVFH2l%5YcqATFa6zA9=B~75}oV)M8 zePoJ*c&L*+E4eD}-q^hR#jX=+>X-xf-7c~`SVd@MU0b1)hg2K{|5NDiQ0Imw{++W&`JYQb@1#yf}6e zW_RKqaUtHCs#5p|rK3tm;OJX5iK-Jm#oFRCHqr0nR;N$efD(*iyx-_aYWTi88*LYFs^;D#tHu=SC4K zjhYIOOv*&~8X`6FsI&Cf#OBF}TP|(jQ4SAy*veI6*C`NK2X!W8l&`#o?eLa5S3*I& z_}o-*yIv8Wm_j?U#jC})rqFgv9M8gtpt*b}c?%JGY7pm+`D@_ZZG`++tcL1%Q}}3d ze|8?_e0hXMGsK6aQ|pe$SJ%mC3jZlbXeT|~acsID!O{6Bs&k07cOty96k~;Ki4qUq ziROJusBWXu_+~HB85O~HZUU+t+L@+;duki8<5c*ovtUUTe_V>WL1L)RD@S|cwy89N zd0pZ&Q!)7781Z$^IxmhQAi3#oNf?z!C*;0610ShWk#`pc_CO2KS(Q~(;p9QZ-ldrO zzj?%kcOlFfm>@oJ7drFnc=0W~6Q%}~ttvFt_rc&I#d%ljsIFQWu!dx@>og3Qlty*u zm6j3cUdp%2w1m@oDsNvVbSm$-v#{vQ&5cL12KWTU1q{1PbmekUs}nm5>0PqDa}K+R zZs08=6FPJ4Licm!{CpN_b|l1h-{j4YTf;`hZB#~`&w`p{Wfp`c@iE{Ac`HhofuZ7| zN2q9LI3|R6YCh&Spn=LDPDN8UisSF4NeQK(@(CB>&x=RZa#3sriujp0WYs*i*mVYW z_$|TO`P|~xR08MXAr*&Hd86gI6%X(!Wp23=VAw68y(vljbOz1}>oHr3ZXOWW;tVly zCg?{ncnBKrL?Uo2z+7d)mHWhvGchA0eewu#U%q}eCdLK7>M^XV>Q>rduC&T=3bKzIlRpW;N{wv1J9FNv3^VF&>M1ydC+tSWd(67#m9?~ zbaL=ss*zgte+m%M3s;t2j3NgNmb+V7`kM8B@yXok3N*ziU#|=Y{;L2C2M>IDY=v71 zxhvkLeZWI;B*&3gZw-t&9`6;;7b93n$E3eo**->7im)8pN1EmsoY_<2sWGt0Hiu5? zu@WOT5RC{qv0Y5@4xte)*3#QX_)>)U=^UDv(;0e32j%z#EeGBgcxWaR!OeA5db|QE z7RqhOJkkZ{gP>Feg8JWpPXHbouYp~~X?G)?OT-87rX!+5b7oB^I2k4y5xZzCd3+Xb z!uZoX(KweTPE)I>j^`3?iR267*2PpXE!!ElURx0g%dVipE!~N33n~n)qtP`)=K+3; zEaBtLJJOLSZl6ngXa+-On7CsuQib2lg)1D^S8Se3mun_H#Wzg(n0pv$hu8d8 zQZ2SADxRN@}xt{qyLw1Q&uR<1MwXMBvmzY+M7!fz7suqU(T6l+_mB zq*fw6>mmD$nP*Km_b{SA6YBaSz;8_z@u4hIvRdz})L_`CXY(TM0&VHwvQ>es`+Vi&n7 z)3cR%XEo8C{#&KFpiK?Zdg09{RLz5;b^-0f@*cDgUVvGy8QjFN6L8)y zT#yTVeOY{JA)OXG2{rRsSsbKS{UOFKqIYX%{LW7;SLaf*_{<`l+>ZS&zOjf-(d>GX z=#I#G6CL=}J{qVEqP!t|5nS6L4qlAu`OkCqDU0dnRC6JVN1FK~;S?-Osk-B(9A#PF z8sXrtk;pF0m`OoJ+&+D-xO6F8%`S{zU)dAWuf^vOl;9Iw{Zizli^T7j!n-DCik_vk z9Yxw{8BHrV*5PJCfvYLN@(u-DJRoa8`HQF~G;y!xDrb|>?DKXMH!g!KSk;l}9#SHe zl5M;vdFE8J1z<-REIYSd>CaF*Oi;=zBuIhXjTbhb&|zkg9xfn1;^t_VfQQePkSwp9 zuc9MRp9&qw$qa)GxmBhJWt=Z4BSsX^@ImDfRGxl8Vt(Ap`)=FtCN)6_tqxTbnr>@; zBf18~gTk{0y#qUQNIY1IB{T^`4{KT{=X#u+3`z&s0Ol%SB|xJB9tM~$&RIp{5+Y$H z_xYiD*{d9XzaoygkEUg;W^ro^;x@o(Y9E13tqWccmRx0NOK^Krm8JbC+#dF7zAc~J z$`}0Jl{gMud*f#QNX{p{dHczI4e(6GV~hqEuYlF?BZHNLPh`JVmvRIQu?oXUs11s# zWesw@)tDPfek13f0C|^${M#(x!)|HA$1<~RTUudzmk%lB=i!y_@ap7Dt$ZH-H(1-r@r))DTtTo#rpiYM z`ILO%ZN6CL&jSyg7B}8cjdY!O3P+PD6RP3MW8Y1^JOixh0f|_7@5yQS=;l)8S-Fpa z^LY~TtE*61e|d5k9Wa4=9lo`OLZ?utUU*-ewF-^PeNRyrTG8fD7W*ipv($1dZz%xr_N(KNs^nS*hV5S~pk$54_JuO^yn7LwK43HoPfk zM0lpX8eQjCs9gb0QxGqyMH?}62jz1Ed;W~LaV@&&W%NTI z<&3i&mGCYI4eSlzlay7z`Q}12+_cpKFqqJB!R%yZ8SDc!Rhil)GRPMa!`F%J>)^oE zhvC>|Ya%8b!KW__MM2yeaolX)BZsi5Dit29Ywh!|AyFhtu)g);;C~=wUtiC|Gakij zP6M>aXUd#hfIMBuhm`lY%MP0W^M~VIQC~LS@{%+LfJS+AS+(6By`Ji6fs}DG2kiSKPhd9Q4- z8SmI9vJoyrE+l_4TWnW`^1eCZ*fQE9v#KN2O+oo`<@2A7e@)nq^~V<&U$WQEiT^A^ zJ*M+wa~WO8K6Z%H%4sG`|4H0fj;%iLC-JFrI+*SIN&I&?{!?({&!Tn{%1<+~BY#i* zSsc5GJ`syQ1(0{fUeL?iVKj++q2k1g~at*d=3DZXNF*+M6%v;#ZD zlF?1}i4`=DYF&545>vDNkw>VXYQG*5OUj$=+a9Cu;Xgc^4w*m1O%JISh|jdJj`k}% z=sv1FFeer_(dAQ)>@zjU~O>+Mj=xzNgX-dmMUA_Jw<>hK8*d zW68eW)c(9qJ%HM4_tGaI`g|;j>?1aARawNrFVgn*ntxG|YI9$VC5!vm$GpT%aJ(Ih z|5!!r-oh5zA9$4>pkceuKvQ2T#(Yn+?bBYPpD^v=wQ)rEo7m+LeLbus#Yje9qhiGC zbd|lhj_zaHVR7N4>J_{Gb$Xs^s}3iS^?%u$?X)^e+xgW5a`sRA?(b+X8diB%95G#_ z;_RR3PWz(o5!{8vkBB4jKT^?rfu`EKjaB7S@!Ah`mo{==4C#AXgvKZB?SG`*srFbB z{)gE&?X!NO$EfyjS~y96+itpmD+FQd4ztt5@iybZzDS1hVU@{fBTi zifT{i#F8`L+VdjVvWT!!7*X{r^2p=aX#3coRc}!7Kr(w(dt_=n@iyCMr!b91TW*ab z-t+c_M)nca64-d!VIN>(_fcFcdezJxN#6>F(LYdvgY?{zIm?M!t-fdRvN+&zS=DRyd=1M|8%r0=T|{DEKv}wR1>o6p z=PX`8Vm}8VmlO>hGi>(ImCF}TT3b4Q_DT}_y_&|UWa^S-^JEIs&}_9#89R9>XZe-T zA*wjLN*vOT^-q;cCazwva&Ae{vK7319i>)P9PSIPZ^zn|6)m4Tdu34hr<9Im9Us)B z8t0bGUOamZiG7BftYB*uOwF<7p)#F<1Yo{zLp2Le3IKjAR z{#s&~)s6RuXlT#cs5+j|iX$^wVFBkg@bcM173LTj8Ll9)GGbMbI2jqCAn`I{10pV& zpz1R4vbMJ|*f0|7gi>Ohx4e5F602h@iyB7{!(W*IN>e&`g4}OIRCIM}$LcV7i;)ik?`{%%r>yGMK_RjEqA{CwNjRi4j6;(!Q;aKC&RKasdZE2qEY4<~%SxB6 z2#tTdamtzyoNSzeeo*E`x^c?t5Nt9+VD6kH^D(7@#o5NWOXkg1rpj6sW`>N9DIC_b zPacV_2BnwM6pZgzD!QAh;x_AP{Dh%%mn~f>J~c^|#(vR@X*tZOADcg=aCQ-&58|L4 z)=%|%M6$Rxhh^vTT0`|k-acy$#(NgextGK~fe}NP-JVry&tdKx9Cmwq)`5l11G4oz z7V!5p-aaH8Xr2o)cE_qy3|b5LQ74V0LoHRU}dQ(u(H$?__n2{kp2%ZwV27O&{9+CYh7vz z`X4N{O6+r!PT5z_U$j57h`k+wZEWUhwk^4O+<&sL{(B4i?=9^ApIcbtdRC*| zQbvg7W&6V$*kldsJI;Q7Gpk}@1Lww(>`T<%J%atL7fUMHHf>&893SP+x!t9G%DOzXw>oYD93V_#P)o_&_> z(q8C{vv;|OL)w!f4tP(CRnM{Q+Lg!@UwBf?`<4~jH$2ZW!nN_kV=HJ0il) zU~{c_n~23J>@)l757|0ZWO*GSD-r6iG<2LP=HH`g8#?dBL$LFS|76X_e13ZrI(6nP zQRw8)+5he5y;QkB#PTnK=e;*R{oixm8~z#lFP``K$nhYQzyFtl(CrP%c`pJ@`rCQ0 zp&=B6D&wyNp$e=7p$e=7p$dFk5UP;=4+o)_8(YtNN`0+CsDj=egzor)JsWl{J{*7W zcw5{#_e=IR)4E=WAs@eE@ANebP;EJ)(_U}bvB=jkcJdRkri!KT_v{WT+>!i5e0+&2 z-E{I3zA{vDwu2ZHOl_RMbS{qAIPspexBZ^2)`rz2AfNO)5%<2ty0Ho0il6?>##4`I zy1;Unr%@bL&9Z5uSX#{z#7!4iLXxMEt1UK;owI7el-09K=PaMIgcv;Hs~1=@7x<`} zrHGCTY<0}uv$r{!vqW4xKvl)+KNq84X8qXbM7;WdDnnHdAZCjyh1QE@zp^x5UiC6d zqo0e%US_GBt$d3r8Kq6Xvd>tD2Jx+nm`0})!^wI(u~!{nkyJI|TOz(TL{$L8n=eBL z>}Ye4nP7OH@*0nqxa2pGJmU7>SUVM(A=j?EN zizyrZy?C`i6-a@hXgM)X89s67?B02Ode0uy1Ajyd17BUMN`iqI%`8Q3&W~$V3g82P zf@RIj9L2>|Sq)4jMj7hG=bBjoN*v9sJr}V@4_C#(*`AZ#DsN@JRW(r6?Q3E$x2mS9 z#IujmI&FMuEONX&nb=iLzq226u?K0!Fr>`LPm~l*oWEpFY00wX^KEmM&Rfj0R)(YE zED!rc>sk>K~Mk915RrmOZD`Qnfh zs-MLB6IJhx8*!a?R_NqwP|#4CDTsy=O+hr2Y6_yEWRr}FODCv0iSsg3RgdNv{h|mE60i^lPX>HG@;@UlggCv2s0bU-aq%A zWy@zHmAGQX0;FO-5LcR1*)gOjnApS3zBHuj0Wg1u}S~QW>lN4x-I$G&_kXf zO7ih~_W$+C$0y|e5KZk=O7d}7~kGu5El)A2kRY8#WpXqJ6P{%QF=gS}X&q!{#KH{P8RMB)9?15dQ~t?*dk3wS|p-x4Bp@QI~*- z2#9zCMMWbsL&O`Qp`xN9nTUXbA}nEHXe8RUvNCU(!&_d8%nFs-CRS$Fwziq6mAkCW ztZijxYUOrYnf~vX-})A7VgGZU|2gMB=RfOtCd@JBm}882pL5L17gej>Cu*=fO{m|P zthZ2cpm4_keK0oXe;%v{H}y#lId^DLGTFW0;S3p_qPLTX(sQ1W<>$1H95Q*1ZsyQe zJG5?$sGFn5^Z!$G^gA)@HislN{kcnnbTtg>{>6v{m22nfVN&IG7qr%#hSPH~Gr<3A z_%8!yU(njM;P}>%#7WG-B!8&d~&VSzhWaqeqF+kp-A zV6hvpuTA~e>3Vl{b%t(e5%VzHQQPvC*oSJs60j+(mR9oq-YuwjY*Zfm+y7(~_}^uQ z2)JnrDxmQeRKWkm7F59hbPFor|GO=y{}ap*0p=dm|L+as0spIeQ2%R&@mI&|Yi(yy z`70OKXHC$rYPRCru`9oXjd zKXX8f%F8WLoTnn`+9Z9vdW6Q_qaU>$Uxg{?kM*&W^)s4!D>cj2PXt6v!g+@0J?4Vf zr|M&jmaZ-#%GvX(()DpYK57KkFqHDD7FmDCbTeA?41KpPAC`l_{c^w}3`{lj-c0?H zI-FiB)_daLxnjMuI;_6sEPaozC8^Zzv=&x>G+zHuqh00tBLRD`__|!H5Y`l5k#oLo zqqqvai+6FMcO9qFr5`Xlut#?4?2(;%*Kua2&IsA5vqyI72$7vSBV?xzgzVJupF4FO z_p4~Zk6MTNyYAJ~RDI1Dl`fpu!e~dO{$1F&1#a-HCGE?ebsnRp` zTNY#8c*8*wraeW|-cwTGnY?*GRz%+|>NvH3RW7@#^ zCZ`R^T{&&Qe>rX706A@7kDNBJM@}0+!qWx~|4Tm6k8pM-f2!X}FFmLqvemwTwfw<) zoJ2|0Y$-Ssl73tL2aEMVnr%U7kh0`6YW0{tLhFAo zV4}~fgycu@9Ll9f)VuZRfJQ#5CRpgP6tPs_Zgc-VSULS;{n4d*WfL^4v^DxkTS`Y* z=+4)7U8~=s+J;OBQ5IjQ&s(RjS8ZW0;`rR9dSip0t=jVM3{jjH>hqt{zff)N{vpbw zpX!HhLR+%!+7qHIzeIOz(I3%{%&UKQi~g7zfAuWR$T?@uSMm31HUH&3`WSimAja8S zhCX#a&i&v?8(Q(37EZ38Y`tmw2&1U!5UjNh;~+0$QvVwL-R9d`FtC3Svw3C_wR~1T zoD_z6R>hpsB0M@D^ak)FB+LJP&y*&6KIZ@y5^oCs0)G7V)0bQIHqfv4VC#r$41t-9h8F>4$Gw zkiwGzEoV?^X))q|`~++JJdQTCbl%VYpsj$V&-vRG1=#0TQRee{U8k@+VFh?mb;@-_ z3lQyD%TbrF{SKuoPB!DQt2>fj`aZ6kO~sUS|Sk=ZQPeCOTqC6Ov1_e>6hqj~#jw;Kfe;xa~Ad?X|A@uXgI6i;zM9 zfiBLP(FZ*`oHSE(`W3ypc^GDhwQeg# z|9C(=Vl9}6FgiMRFV0&3yUe^`#C?dapT^`ER^ zv?G204?XIC?^xQZe)~HZY5q?fOSMg->Yq5IU(|0~gB&{Wkkt=a%_C?din}W;-YuO$ zpK`@`MbQtb(yyYI^t8&=M|44v4&jdNi}@Jd{rC1}Pa-1sV|tw`x4KkxulR*f?os^_ zTNdPlaEuo5A~ny*M&!SmCNK{FMHzX{opsWlQ&HMs)K^|7q)A689#Yz45W>vMVlm)-w;3Rk0 z^z~_UqRYP2FW8o2#-2v>w^RDlwi@_j*HX8y^a3@WR(z!|X}Xt#*C|Ty0*zu%>nTa& zN2Lx_n(85g#%AP<8#pF2XXLmMN>if&9y(@>(o`rJUILttds0zD^x&2CPn^cQQUs}L zN1e8RtuOCf2lkiND#|Dx_&|oSHV6heKZtzsE3UO9xQo^h{G{;UBh4I$P(!EkNUf|SRB6% zIY_nV_3VIa2#0l>Mn9_ep()4Xno!1`fR=R6PkK>AVO>il9h)!Kyyb0hGG{vL0_wl{ zNsm!&Q(6ZpRiD>8F6tq|7XMO9CH_0132`W}&oa387kDz1VaCbSK zy{vy5IAvE$1<&v(U7yzsQm^W*>M#69e?G_--z!Mj^Hcp(cH>wh+yh^HWW~{Xhc|SSqG&gR=Bs9K-vG>+V2uM%k zfZeS)KhA~nUvu{5XvzM2gZS@}TbU+@Z(b8i6m@h%MpZV;Sn@sp z47yykO&$ZP(EtWpicy zogqe7)pi*H&Puwsm9aJO}C{&E9?yG+dM>uL(1J*;4?p?+}_690qF(7%3&NzlIQx{j`Q@_m6=7e3PzO- zEpZo=6_rd^xUw%uG=7!qu5%7!ke-4CSkI%O4RZ!_A%9&+tAV|ida&JLdVx49l6d^{(D(oWi3 zw!T1DeM?<$H{Q2x!|j+~>gkW$jjpXsKOR=augH~OFh_Cj#BGm$Mtku}w5Hrb8}2aP za`2@YzC)9#(exyvW2^<|`^M6geG;5nF%A2EZz1-JG~*5pYoRbNZ&34}2*CELGPyy`x1woYit!HzUtltJEA|Zr-8s;R zt7aY+PC+~KCY5=_0O7|2jWZ)j&2kNO4W5-hq@Wz>{Qz|8I49#qRk(d{#Ii5im2O2w?@CB>=aOt#lkP#zwvQR0Fb(;EDI;H$Su9KrL^r?iqCg{ds zqrFth!Yyd5)YE^Z)c^gA>gbbEn}!%W9DF&AOT5-b6NVZc`&;mSR>*2enqoulHmahh zLE&3Pf7KLPez%cCbx-RH9eZ*AjjzgO1`xgk7JZim^94*FzK=3k;3}!W@d>W?#W%}I z1L^_vhyjjh6?U?Ch+>lD%uc>Pd=eV(haD!#Y;G7}3?%ZJ|SS2z`i*TF2Mr&gjf@%MJ(XPR?=HM%weEYL9kfKK#?YnXI zS-67@30>D-Q_cbO>6|uG@krzCCVU-qADlwBjWXKF_!f$<^La9g<97w<7k}X>j5>U? zl<%A_Zbs=DM${-)z`~{ZGuSFYj1-Dwz2bAq?c{3S8)8cWCX|n+1M=NIX7^)p_ycx{5p!xE83ap<4HfZY3 z02_^N8Q1z&)d~r0g7~uciF{O5hBM^K=ggIQ!~@Rq%u&Ge&;;YH>Wv3+B^Vd3Pl9Li zCz|?`YL?7ccmB|fG3dusXW=4MvB(NdmOS^G4h?_zlXnu3PtkKcHRGD0X1fYt2$%)> zzq1AfuAJQbd>qU}b0^0{qj{@G8C}LZ=Q7Sj*sT@31TftgYGxNJ$QSxAh0sqE4SdoU zoGn}!ZtHrQCu=mGL2nN91$2`}FQ}>|j54x~qt$%(oD+Du74qPDO`Yb=f*}QS8uGv* zbNfqt*-zrCzmiznAQ4$IURDQw7zjfR*NcsJ8{32VLOkET-vztvfR{D(1-%*l?2HQ@ zqgWxw{N?t6k*p!5VSpxjhY@W>VKx`ES?&U1*|40L9qca->N!tDle2kTH<`VYd*E6= zKX9-p45IPQ(hH)QY!_n-+~}4uV=c$EbPr7?OErfL&hD*#N-SnU=q4Jz8B+AwpqahNPcTd?Q)F0!}*m0&fR>xvNvFnrtYwr2}g%usbZ0&vDk)mKjf!H zVIYl8wuMrQ>Bem`OPlah2;7$h()lSycoz$-@#pf5AD07-xuo;k3TNOBw1s{TYWS9f zw_s8Wa3!>?08EaaqN-M=Wm*N*wcXyb{7w2!P1Zg z@oWb_Zeq}dLZjpDJTQ7u7(qQ1F%SGZ1N7m~lxjvtPY1V|?kY0&1>3-hqpyiZi(9Fw zUj&5EmZ5R2x|>6;6+FbBb9N)nGhn;r`hzZE!%PLO;IsY$`e7LN6%YZqk$@&Z@jSrJ zgUPORelCTdSjmimoJTbEhRy8h)6;Xtj!N~+KrEsxW^cB5&ggjneKVTgm}TrA#SgM@ zg!9aCiKbp?;5Y^={aFPbrWV~Af2KPcGd)~lyp_SPzRZJjcL3AJHTA0oreiD0U6?R= zxLSmV{keYAnCq9N#{OJR_(O14nd?SPJ?6s|6ChVXfyLIMR9gDwKvxDK9(2x!P5gyR31QeXRpLf`1>}wD5{@!p_2Vk& zg1Jm7Nd67j98`0eZ)n+zW!5OA} zo>y^YYmN-Nvh<`IRDGrntL6 zyQegDwY`ZsFUQ&X)S{C7VcaNqRb~;!vtkX6VmyPOEAXs22h+I< z*bdF`u(b%?{%kikV*6MyHNDq3QeBIB#Scgo$3oqmn!3vHmOSPv6)xX`w`lkJv+jXS z`XU$VA@5CbNjrh?t;Mp&xz&ceI|&BnkFqL_SAy9Hz{6%(oT^(ceBlak`Uk{j-==?ms!O~#Wlo(9##(OvV5c5+o|;kNnn|E@9rgMY<8%Hq$d z98a^a2svrl+9VcIc#4-u^Y1ev`*4l6PzGkjJ_!j2cvF5E4V|omCoDWwuIoz6s*F&% zmbP$x{dr|K;zh@*V6NmP4hv7Db@v z{eI*9YJLEWUmQEp4aJ7}^(3?E3@a(Jx+II@tiO;Mn2>Y&c{TSp$Vg`x=W}Gc=mDUS zz_vj7R3G_R724a7YGbv77cocRj(4Xs)kdcf3tlW`;NcDBsZi>5C#I649xxtm!jGDL z0vAvJSYUK(V}W%{U0yT~OHsBNycUpTP!wrvUV=L3GdGjMzXHpiV^3#FqDg4;W86cnIW$?WCTRu*iszDpOrG@GHYhxT#~I< z?hXb4`7C&r1Lc>x_KS_!0GYZ8ffTjC*wCaFrNeWYzO?fpBW8pJ9`@(m8S5keGzA0W zQ`xv*{t0nll9T4jXrxo2sE3UW4zB3@=w4j{9eCJ??$6>a+z{s5Pj3cW%deQ{Cf6yIxFU;S#{4s4%xU z$MeRJ^YDZCgi9mNtCt!f(7Dx8WEgiX+u$;9q5VsZFu69daQV!vLBWR_v4L1MV=507 z_?@QqOVP;rT}l2-(B)gGZkf?3+=6SQUfz2BZd-*0RHI+wCn@=j%dA9NwcLmav*0uS z^fo%O+}IGzZ&~uwmU|PiV7;QM8#Ehz*fcIWLA63UMsWJQa;7rqvuGIt7{9Ah*(S_t z3|utLTxrC|S>OVH9{U>c*c?IoR~j1~{M;tL$+_rODty9dA8x@X{i9!x@FbOA>MVgf zixaJ@jF>hS9D&uhkIKoB)OIOyhTr&PmRWr$_DLhUqXkd$C!Y^6%bLYg@ssHASgBgL zlYJ;`wGq|Ef;afb+!slsRvYV^aP}v_rO>adjV^H(c+#Ib949M%bMjgw9bFDJIc5f2 z&24m+j4r(`xG&Q;6vUiH(X#-XKeOUA;pb2JQ&V>OYK_r3+yYnmv)LVmdHBP|`f7en zH4Eg$eNhu&fF5c~86886}3h*Z4M7;N-0~6A_qS>dxqWZ^y5=TRA&p`;K%!OKi+%WQO}Lo zOXSCE`9a(Ce)RoDBdV_jUu9}}aEr&K-qC=};g{8H#~`eeayOj2#lUFlzsaa`FsH3> z_}tBZHyM#$I3t>(HXA#8@GH9e;ll1f5Ba&Ou2Ea?-X9l2PU=`#3PZrmBFd*88;v#; zvc=dM@EP(SSxawiFjA#pVnhb~XE|s3Hd3E9)&=u}y`ACGlE5G9_kU~1qJMR1 zm!dk)KyNE}5$kU?8gyfC`=;j{2y1}w>5I>FqGr#a$?u1;>>IecBzol;qf0XLv~Z^z z@r-KklSj-`0m7eWcn#)v{POT2xUl~8R*lhRF!QuE$uFR4@B`P^;noZw@uJaDRyPZm)rjW7UfAx-fqb20dtu*;Z6XJfNDFrRMU;8|WM^8o%UJ2) zy5fSHluF%RG1_*q;B7ZYd5@*ZJ`;y4Kdd*xWjQzKG~V#b{o$I zWuiH`^5p9JHI%E+uhQw=#%2e3b?ixh-lne){8JbE7BSaW2 zf6Z7FbPz{vF2My3Loa<%Rj1hKgF$iOVX772gfTCxup+n2-A8d&ccI!nMqM(00H7b- z0*>{Ws*bnaIVxvF--KQXIpwfZ=g7@x{s4=lN&pLUj!+H-#&n^5dyI|A{5^p*=zW=a ze5$Iq+pslKmYe7H#J0j+9D7!&8wbF#xxz_U2@G9-(`Zj$?J@4ZgFjeMd=Ujd9E?6u z@eOKRZ!4NM*TcsOu4~|fMH*}JQ5PEZy758)-%t|zg4KJC(AySE|C%M-@0nZZd~-?Y zwGvZSnS%nD#?Q+Xf`QP_G8$z`>Q0oS_b!uTK~vR!7A|%KeZAM{(At78u@aJR&}OA; zEVX^ZIBf42%dDm>p^I-A%UbeB8~F1P#TjTSXH+b}mhCgb6D@RFtd*I+BHDaFKJ9{= z-b|p(>ebQI%6osx!QYDb2;ZPMot7+WAS4F}e53e$CU1SVS9G5N4Px=G@I< zK4mduS85^pZ)(tLMKzRmc9tdG z^VmeW4p{_BSFQtm6XSd2K_5WAMFGMN^vK)Bircup&WGCuh67$#)xc(4v4-K19z0-C zJT(_jQ!5rtCb*ctvo!i2#+rcNz*^|(bm<>PSoaL>N^@8ae;y`nJaX=ws;1ca5odE+kcS$?tSp-IEYT}J z83t%M4!;Biq5=5iB*$t7lxG}fNm;xIitsEkTH0D+7x3EOk&1fF{^#W z{Ox8jF1r4%u_}i@X~RjqGy&YdQ`McSWRDTuWNwA;@?(C%m-!brGd~CvH_U_7>mB2f zJ7h*7vyNw>Rvc8-q-LC1WAf5V%iZav(~I)(c?Hf(xWIVdM6{2mmIU5-0?-^lTEiln9#$-T^GW0H5@g6Kq{W{}}0rK)7-g!A>M2xWDDjA=z>lby!nJW*J zQ-&?AJRpwwGvr3G2`Dw&v+c$6h?nDO?IDN=i&5;SJ7A@AH}!qr=vZyRf!&d)>1Cz7 z=ag8ZDu)=xEX2i6g4_ckwTzHY2CxoG0r{kXMfLF(@FpFOPz^H9<0$*fuBAX`B^dm;R!vgpApr77{xHSkq z2Df)IB^@=odf}5j$aNH|a{;o&A(~noGh(}1;5C*%4Lj4ahjEr76MG?#isa1uK0r~F zd(8OR!QY8G4_A{zlRh*e;w^Xx6F0Jvr-J~G-4 zu)qcWT<4Jx1|n5gR>r`>}im5dQ*c%OT@&2Y>1+9jdLFLJ1!mkz+0RBu8pcjgxk3 zf^X7d0A(YgIR$whIV~(qUPW110j@*K3UjR|ZT{HUJdE!n<3!YBJh9`!6;JkyWc^3i;X3s$yn(v+5+S6abo;hcN| z94O_Kv4Tc?V%Tw=Z~P}lV(@{+vOi0pr#><2v;~DU>Qf`O)A_~(G1$duq+AQy@Tu`0 z9vql1FP`jr`KE(aFz@C!0pkK!j7Um1uUl=gTf(h``;zUhp~scc2&5 zd~R&V^~W(^7(KN!zVSDFf%wNf@mC@K?4EI9EzI~4h}#3spuCgD4mFnW{f91EM|^^j zH~t`gy|!Q`{rIJk(0&MpqN3?@%SsjJeJI8ffDJi?(z=_HP8m;WXJ^tEr;HALmoT|+ zxu0T09)Ehmd8C!9?DvZ=6SEyCm9BqfJP|wuI%UG0DaHWtj;g+<2H*v*xYkWoE96>l zrd+Qk(Yn*PQHJAdUm2@{?T8Z!w`!Id?`1V$wHDVJUr_Y~B+=tv8ymFqv#8rQMyxjJ z7V16%9oBm(yYst zrxP+ro~kWH;A;$e%~Bg~QA`mTUm5f0)W3}Y?Q{u!|8JvHLI^e?yey|N;ANQxs3CXd z&ho8^bovKeiE@5s%ypcAMkAx3RVjUO#%LeE$d}bOeyk42AgLWIyETzwzcrq_>t$#v z^aM02b)vhl3~9~DEiS+olXJGt%{-BtTM^8vINcNUI1qh-aG3>)E<(=2-jF=DQuueq z6Fr|kiSt@;t7a?8us78^dTWY>Qf^h0(g{Gs!IPH*Pw1^QrJoT>8-FsKl>D7hT77v1 zcB!94w^4?QUazSmY#GCb@TW?6^2G0FSp-SoQRLz-^wwK&J&B<*eyovcUSo*Q6iMi5 zKt7qs1djrxhOW{AS7EjWY1z5Ou0ouKF7ArJG6X8AyR{N17>~d{aOwh8FMSw@90V3D zg9r2OuZ-~3mkftg{5Jk(;VO3Js6Fq(fT5b27xULOR4Y{J3M9*^Cv4`gX>GKAB|QN_mdGi%);&UQJ!Vz-|p3o!6XKK zR0{#@r-w?5f5O(+=8ISu;nTZo=1}(wM)zt9Uc&KZX7BC?9|prs$}09@ipU?vd0v@g zK?r+Z$pVy}JGGp{wkv}z2w~fm9t`1AG24|k?8E1Bwkw9jp=}}KwksDQjekyB@sqK# zi3#vnq6L0f(K+v%U%3MsUN@tv#|08%!iBtjSPO(1I+bCSn7!|H|G|M#~h$iuWLJ? z0$ie3YvoBiPZDINI=GYbnL%Ie04^H#t%c|-(dtV%FW9w zR-8`&JjtLrTX_oLJ_cvyPDe352XHgMM#=kl04J}kAg{=kQ&L(si$5{77-ZSy`2Nv4 zWt#M&V_K(-l-_D|O6!z(=|_LGPI0hzc20gNcVFw2i%`!5CE@2@P!hl61rwRLj=@3{ z>N@2twiU7q(R9}-@3J?i_w0mOGNi@}a%i>kfEUILd7U!F1NJhhlTC1{jM~`)NW$h4 zNHjyv4`dmMQ)S2@2|yt8+vWjeY98_cGA;QGR6{YDltEUc*)lNNqBKLVr+{{Lg30ov z2aqfecmNrz)&oe6k4m7|Y)Mw;0VG+52LM_1I;F3KdVA!00LkGx3Nw55Ev5?JF<@rO z>(VPT_ZjJx$$pHz++@}%<6HW%q<3Dm)RO)F4d)Ofc^b~k(kqK{o%G6rd_a0-So#bWe*_Ztdl@rlUt<+kRjt4 zkaap9QWGWQsjU$b@Ki}d0-jp<%}{E3-FPk_0t2O@q?`35`9EEo&{x-S0)sc!YT>3V zq%k*)p4Aqd#6^hNZQCSG`4{`mDxw5!P__eXs2xB&351Fb`QqHUIR(W9v#`?7K~vtK z+>d~4k9i5tZH)n#dPqyY0|!JP(gmj`>!lL_&p=Q?&K=q+vBpsc{GNxf=l8&qPm6Ao zE$}QzEREhB=GDkkX*Vbv8JAb#E}b^bi<<*n_Ovnu!Y8x0v=II4vq~!a^Vrvex~bwx zN9;BjYvJk^(IHi|ZEL}2m?x%&xIcjvKOTzuZP;o}tRL`ve;(N)q?H1O&K%yx{Q%En z2)(DoS$nNFBwfA-r#SzW%<-1c=bBhKnm>x3^*k(%4>i0nvql;4v#NHtW#*R8%z>3o z^%4zlq)B@qa9N1++|3_abS@h}Z|LIXLHvvkwt@b}x1cj}1`iyWgA!2WYd8@7AX{6; zWhl-jX{^d&30Jssq`8(~$q_mpUNgjJ1NdX^$G^w1{KZ&be5k5#;*CQ2+)++pY3WQw zwZaowGj}PDO7K@B#slJCKJ^Mf#$K&a?5m%{O!E;cw2An(7VP#<&Q9f#;k45xLbF0p zP5qM9A{{$~;~iOMBKesvbzG0oZ#3q#3Y;gJFEL?)my?g93dj#r5rOBJmFUo~J%kh) zAf9*dNA3Gys(1WRIu;;8+gR`hnFj30D)J$)bHnLIfan^;!M#Ba)4NREr^D$EyQsCd zgHBkOK0p`kBGm4L92Fm!rLQ&YVe%7UW9pz-7>aku;|)c-RvGZCswDCJPVhxl>Sjr8=~?sd%D$ z&l427ubHUr)&3r?seP+ux^qj+Dt0S(oK> zy18iI)`A!K3*M}3xr-uNh)uVSso`|2na?b-w_43ueLI{>lapRH`Y`DWbIKp48td)-)-EHVef=!C7aE?vJ%bRr=3U4lbK+>gZA%Ct|pUAq%0t_sb^7}AW>5t zF@b|??&Uam5v|Nz|2vnCWAw@Hs@;S3c`eNhQ+jyAyl<|VAsu}}cuT{?ruks`X*Cm@ zTik$_mDfZsZ@~J$wq^$JY6#};*F>IZK=K}kiM-Z>o(e{VuR%VCqUtSLO}B-J$hH=I z(m%7;E7$L$(h#v)J53bOO7!dzkysZ_D3>OZQp98$`i7I>T z8oC%Nx^xN|0nz1nf(~m=snLxIm3@}}jV4CQg|vaNg92ucbQVV#}^T_!l?!>L_bmc9mf3n)tuz_S#d zf)6HX)H02?%en}Is{V+z)8;TyVLt-`RH$wg*+#5#Bw%}GB;2-j^m-c++t-4xvQ$3a zp*XMIgVPx!0h$Nfo9AfC00v<~F!yk=w;fMy!$r8Q4e&UnbR$x%bQs_o1Ls^%pN5Ob zgf9@!!nrtp1NU_R8zwVOrhIs$Y4A*GE9M6Ey%#6r;i}eS6vU?IXdBi29^1NyY6a|J ze)2SmB4b|woISPNmD3>Oi;-LKv_49-?{2}z8gaB` z+@#X4qo`#BiqTz-)8ud+pQ4A`iB3JeFrxToO!mzz?gUEe5tIT3C2-51LN>!17-l2& zkJzxDsufV#h}({vxvkGos7Fr`MF|n2V)XtO@kwvEYv7ptm8#l<1IPf=AgmaCyQ%V~#oBGEHr}HD!7aRyg&nag;A=I*uXw3>3w7i2T zbyP;dv;a3{6a5?`diD$%jZBeSSbL{nFM}boY8Ot`l)KG9t7`v_`$wZX2z*3hG~IX? zt2iOD-DE9e1LVx!>ej%!0s0Y@+;i1InB*u`{onM=Ro;b-#9AYI-xiB;B5HmSW)iS z11?A4GM}b<;zUHK1v|(3aPCc8Vnv88gcGxd7KWjILEq9)m#dvd!;c5cL3Od2eXXy5>qRaTR9yo)Um%A{f{V*R-=rCkf!8Z#uqSX$Ff zENiknPqDuZ7f1>5BD$Le8kvY+C>bzyKY+4x^s?-dNu?b`B<+twgPT%-o)j;Oe*Ps&O>skEku=uJ6=P-br&7GTX3yEmv3(3augUdOJbo!HeBCl z>FXXMrmF=j zi=(4e@n&c61iFxb$`t>D?xM@L3THs$v0HBne1JL@FL#Rw`@j7 zE+={5TQmzsao(NZ2*9T#WZMHu&E_?6jtf^HN->va%Ey3~SWnDKz~*lc{^`>T0$>Uh=lpWkfnx__PGcg#nEC5SFAWik!*<~ie)z2*+1a2YUh&vL z-IGLEM=R9D!aZue&3><1HCeQQ>c`lhb^*aR~3-n>OQypT z?yr#*!NuY{8YQEidNhh=uSX+|{U#5uMrZuBjB>J?&ok1aCT^`@%HZTrl?D&P0-4OzEc!)JB=93TucY9yml&ft=BnH60gsWvN# zMRtv)da`3Fl2nBAU^(v69G_H91G-V0j|EE2&f|ks+y#sUm~F;rEi>j0Mxcj6os_Wi z9@?2CmO2bwwI>>?ebp`+JXCb~*=;F^j-zPyRUQ_*y)1Z^t6ISu{8;RpOwKg%l(zp*+L;Y2&1p#VQFgFla z4JD0vZHCOOBE=!Cq3ZZUIxe-g5pC#LnwS@)^hC2l%C5eH%vp!06>W61cU)MqY6TQa z$)*;4ray%pH8l`V7P-^HljagppLC$os(QyvxWH|7jv?pD38f?MN z+y-&OrJrqElOg;zK#dr81WLt~T#nqY2Stw%PdoO&&+wXm(%}&zYJdgfERZ)HPfNeI zfR^3Nxr#X}isGW5M~gQci*2g?7r2!7=+a0L*UWLyy ztIR0HZH2kznV5)}_rGxT$fC1Pg{)M>}KaXX_AxueqMoWj^jex3Vv?oIx zax4(4eGgpN`?O@Vh!||aNz7}BZUYUDbXF)K<8Z)Rj7y@O9|X z98A?$G@qQ>A;V&U@5^DkeZvmPuo=M5fY~FO)4q#c+BC)GEi+{QR8q%_cO2-e?09O?9(I(DjThbeEP%!q?l_WF ztThEOMKV1S%F$M~Fy$OqT9Lh=ZFmcJ*7;C(oXfVH<$2<*@H$ z7%j{aU*c1n^;0H_ma4YoSbcf6n5jDUqH>Hux)VR5vv-TA91HF%6Ea5$I;_lxH`~Sg zBAGMsEUSbn(~C-wFj zuKCE=H6K&bJ)%Rj1#e)Xl@oIDl77Bv5xlJ%y45_Yz6ZMyU(TdW_lVZvEEN59maB4P z!M%fuOY>%0%FwZUL`2L=aDN(3CDqoT#j`qVh}SIaHjSE37NNF$XyDeU>tu1*5%D{2 z;J~f=*XkS*>IF~cQFM-IWr`d`7`_>hD-Gg|>?x5}PDcPTf3>8h<9=Mq zQ*@B7YU3EGKjDAO#;0;eD-R^lrXrk7MU&^TB@!c&~$- zbdq)zh}dciK7hDIF60buKXD5HgF&8qODs|?@DG-4&mv$wF39*5#a4VtU{)qp?F&|o z!+bS!w@~QrX(G}%)&f?x1v%mlik=?OoSw=P6%OSxjE-<;PSTL+qC>a^hp;BIX6NuB z+cVg9?o&Vur;8}{RoXmVeB_w&3$B2`E&7tG3Prb37M$5A+7SttPtS4T@k_L}Ixmcs zvf@mE&MO(^cLmoiWd&1{BGD8ApPC`MP*Rb2%~AC$jL2~Lr&iApJx5yL`9?zV{RUpK zdxRcS(!8(~%2t7{jPes2NDHQmkiaT6t8jEh0Y5h&C4cQWjbzS)&>>&Z;+djXiUlvS zxO(m&@S^{^g==_L>NKNxCl4E-NbTFx=(m}o9g@|iSVZVG)3B6%%&$a_TvF`X&#=Xu zUOh`hgj-<5bg6OPOpiSwc{&$JFb$g}esa_y4ijEGO(`YlL@anxqe%0o)9e!QwIks_ zFcQM8`kE${iuTDCyn*TYq^C#7_(H&?E_YFBi3ih{F@6~rUTEGFI8rKZkN+JEvfQXM zF>&Z0?{;Ln<$RW*lL*Q#!$D2O`DZNpz3H^{hZof}_*gFDElY5@SXR-EL zp{cKHO-jq}Dkv){C>~eBLnmw|EZ?HLI)jp`@BxSLnKZdd>~}0;E#MaXK(Y6W2rt}s zCXKuwba&6>M~UBdFimsFi9JV2^HB&EylAFb#B=70;9KUQbsq=eRX99h5Rm#$E$%_= zBLlp`sK4VD!B8Mxor(R~40yJJ`+1zAzn(8@9R^4e;Ua#d#nmFZy9FNxwa+BA1EqhR$a$NomCP7SToWIb$4~dQ)EO?KMgb7@^dqQsc z&{-}w*0KvVMLAMT`yLWs1fRK%2mf!tnEwlAqwj0#L8BQpzYyEDsbYnkFQ%wRL|FIa zS&-j|Q~zd|eE^>=KZ`W76l>$DKsB31trv@rf&>4=SOJ&+E0`bF)IacG`x`&Swr;9e zA(LiF=B?IA=A1#2$wX*aHH+?gM0B%dfWeeMsp=8&M(_goPeJ3#%V7AnuAUNj0sbe} z)(Y7(i^?7q)2eMHD1x7~C5Z4jB4GA4*xEaCt^oI6Ay7$uM9vdeg6L^D^=Ba(&msFD zaw?o!YqK|my(Qz#2YxAs9k4abJ;62!dzlj+6I&fikg>bq3a?PW5_I7f+_8juEfMXt z)Dp^EB7Sh}0nHc``QEmLCEeK&T3Vrps*cV)k`ga~K@hTd5ov!|g zj}{NS+@;kR)ybt{1usJSi)5)_q-|}W(Er*!$CY92+%f%IS5}jNj zBJtYJ?<+(GCJ%S56cJjlhp1?!_)qSB-8l1YVvp)4#3J>{PN}s z$CY`5tl+#k;mL~h)nZt3V5n-3fKy-TK2mVYbeY{${ z(KIAnwZ8zDctfG}B%FZ5H6LHR2zRU67XER<#=ng{~D{Vl4P9b97aXsBjllrs0kiSM82SvZKt5 zT((wpjrj;5~;k0ip=JU%@Lfhabsr0})(b)^fdYHYlPQ2+@ z1cFE5PO7wYJ(g+~oCKov;$ufXmRS$MrD?QrgXk7+!5L-HRF-y6hlw=Qmi zJcm1`smcJnZ}CXDO&TLc6qT13D9lSz8Z-4D=wjqQoAQqoRdSLe*zaRXvP*1+s=YB%-BQc;P^F< zu8MO!^eLm4)`<{$XN%}<%SSACTl#a0cs=+qItulan8I-9X$jWm9Y|r8exo5;{!K>gu2-i0NB4Ad!+SN!xy@?idZka!A);HhhFl6 zAg*!Hzqg6J4q5OQ!l^e}=y}`)J3s@=t*krC5wO`oMbC@Z9cwU++5>mZK|Nl;pl!hk z6_oV?X34vF!UwmYDaE`fx^}YQAuMx|wi`hg;4tHm=8(U&z3ICBmq*NL{hPI=hQDi~IhS0-<7D3b4f1ejA!o{Y>yUE>w?!=|*3ZW%hZ zu(YBWUs9CE?zv8E2Rif*Ed>JC;A0o)Rf5(5g?Gzj6*vQBE(g%1IuRO!_Y&+OaO%Y- zK4a8TNf!%zUpvLVgvM|H<#`Ow-I6Z6B*L3o@U=PEeYzW~dD(^V3b_RCbW1w)GJ0$a zcHS!+cfUFJa_$YzEs>VPVfa+QGJa8UXVYSuK>fU!8!Q~b4)!U3+y_W zHIJZIcA;q;L*qQ#1`RZX=DmW|lm#F3Fn;wFG01irL}%K_4DR_S7=`|#od@bT;&Gdh zC(c)+QJj-%r!JGZdL0za+fdqW+srjf_RrTuY}i={?gPQdBiS1(&XX+_#Wt7vzm7hLRk{MVs103tT@3cZd*({D z`ad+!Ppv`*D~ctfAq6fR@pA5iz~Pdrk(TlEq?T>l$iNCyx@E3Cj99jL^wwTXt$u~N z>(T4~xL3s8vmDA?g2O6Vo(ujQgxZQsC3TUU*G@uEF`RnL@M(*iWmpyPOE~O9->|(h ztOod9t!VZesJG|Po!9<>E=OgMaLqh3%`5NoOS7B7o6|gAQZ-6*-}_{mt2@cS zn@gspiO1%JcQm-p*@NL~x@kuI9qBy>6jy1V4JIzL1B}K_G@Fn5j9w;&ho%S$-!D2uT5#RXN_=!5W$za|ZslzG1rFv9WdM$qQUvct z4Z|x7c)b<}__>bp{05T_i}ccc_5I%xTQqeIef1Bl!miSv_@@Onr-%dCABb+wdlYo> z``9qM^Plb6%#lcw55QQSM)w~;4U9)mI|pt_H1&B$#I?0xXBFp*$3D`zt)i4vnX{ja zDxUp>YrU&z`#YEdD~Q|~F1|g@c~|u4X~9bxGuX`tSDs{PwzK`pGgb8QyD+=u2jd(C zTFU8`SkE15z{Oj zgrRHoIYFv@aH8%3i-RcqeRR9m zP@g-a8?Na@r`{LcyIXLT)XAzYf3#MV*BWcNVLtUeEb1Hz(#dH{=uE#H7X1<}_yk9= zIBx~RLP=dA%QFa6F>vbM0G~|QF2ni(KfEPPJ|aT1r@~*xbo+eiE=!w174XYB z>|X&s^`JMT$a*l;6eoD?e+gt)nDisNSr4wxrz1x&J{^aR<^o)7EIo8ow2QFdW1QUo z!Pob|)qMT`-}kxqzTfYA6;VA7x$$uln*g}%YpAqtRNh35fHEY()pO9W=p_!5Y zvACgOX4d>0n_0{(KFy3qEQIiTp7;B{tDAj)Jsz*#_w_oj^E$8dIsnr*SLJSLck4+i5hH=ZIB2v0Alx!mv*lk( zSO(~udD!jhVIL@VJ`DQVI#hHX&UOR8AJ(CY^B8(4js|D*X+_6=G6we5@Cqd}noYQ~ zjeP&*>>bv1=Ts~`nT6()PZjyYdRVyqBi;#L|JiuS%8oC<(^&Ex1aU>5gW~=Xy9gQeAfw7Z z`C{GM2-LZM$#}?XN~qRE@z6pZiq2SFPyejJOs8wmDP(Utw-8>~L+o5VWD%g%}xY z_!_%FzYqRHp!@;F6&gJn-r}h#LmW)4+k1^#u-s{Tf(I7T{z7A$H|HRMg8*%O(EvPb zMYOJ8zTzg&p+jv13kR``p>k@jPzh@cdK(^gxO!Nb5*7k_cx~!+3GWNz@p~rc`?fmY z4#m|LgTA&ly>kiUkfRuf@Uh60Ke4`3`J1s>+e)0r)trpCcWqKQ0b>)pEMCi8Qq)%M z;cv!9;%P{_QkxoFFI0 z1)atf##2yMKA=UlbGY1F%yi=sQ0+qwk0XTp;nGJ%md@p$#n`AfA7{+J7-Fq7s$a@WGQ*$x3a01f7EZz^o}(pe3MtF#Yp~(W94!U#OYtv;QO2TlQ4d zYvJxKrhY{bTZp{z4CDoqaLwr5T*F;HtTdvkbPEuaKb#6%gzpT85s5QfJJ7vrMo(`I z@2p0wvcfVRd?OlW>b?U5{)jnBo;G_vN+hHzOou6Hz653Z1-dRM#pGMcH zNjxBC`Z$~sGJ7JQisN&=LqT-E&B7CLW))zh@}->zgdhMdqCOwgD}c)TNY+CSoUfyE zUu)p>weL{upGNPb)?CmjJ$naR(g0P08Y+VR)cb(i-62F$LSE>5fEwcvQpQWp{Zj+J zH6VfN(ys9ko%_c|PVNWejf@+QQ{~2vP}VUkJ6Fzv#r=XI2Mnhj;vQ0@-Z7j7wag(T zTM0=uJ_OZ^3#~N6>JMq$4dXs@Id&qJ?!cOBtUdV4*d(bEM;@w|&>Q%)TCK;%@eDdM z|N4qsys;X;^LV9HQenbApsK`n9aZWwPy<1AKh4sSQa+$c4{rqM+;6hOpx)V`bE;k* zbn-7_o;hJFZnXjwy+TWF8k@Ax@C3x1ItAsfbJ>IxGJvXwufqYB(7Bt&{pOP0_zsnW zLg+zhe;a+eYj~~_Row^6-R}D1f=(*{M*KWBn=O%5$QU|6*jBzG22!@H;G+@CP_a|kE{RF%SX#G=n@i+yQ*88$%O zd=D!`7T~Qggu4G@^bON+-N%l(oXPQO3P*ChO5u(`Ybf0OW7_c#OyY%-DFT#-Q0yI} zUuO+ZtC2$O#W)SSS_-(fyIKOJAFEdW{f^NTy$u!<-UxF4g^hvWWI&C~N9)}0vW1|p z2UO+#cO;35r_Ta4-y!6r60%W$7}P7fso!1W@uWiTjoUD#+6!&lEhZE-a8|bOh7Rnd zo-RJIPkbyUq&2<(WT2Xt?gBcpTEq7laQDyH9Y{4pYL!;02++CjV@{x2t3tZM4`wSt zKeCn}M^ptNWV{mcH;V*ykweJf#X9=&FXLBcu6s5hwKpZ-!wz%}KaHr>^kknn>Uoz- z#$P0jE5l4fI-DaoiC?rqDff*nk~G{0(WNM2Fq;Vm~!qo@Q-8N+@|eFnYJp@IWL~E!_y9 z)mo{M575Bz#*Mp+p)YwoG3?;mzQy^5~gBg8M~C}yqD3Xr$(Fk99SpK zzyihrw6?<7VX}q?I1cP6rhtG`7y)?Xlr&guw??83bOE2b_v*IyV`ZjiUy-s(Z z8~r^sytFFDz-3q=x18F&FgAE)E`EnCe@R6@kR1D^E}%H7=(?QVeh>2qca7qDSN9Fr zq5}vGL$mq=6V7zO%AP;0o(*+cNGb$OjT|r#^PwLj(La~3P7)h7!D9|8!u}5h% z$RIZIEat&|6B8mMUag+7^J%ou0I3gWVcSsxylM~)Hj4h^HQc(QvS4{JZR6-H&7a1C zvV>ExCo2xC0##eZfl|Z6`h(zc`iC(QW+-0SMh`t=H zAtGp{B4Vg7qNf9HhO4?A>1fxjeRbV5t|&*rOaDXgJXNqc6GCqQ@`g}PGj!ANEJqQ) z{D+8RD=F2C?CnC83PqX4M9|z?a2^f6$>XRMk(ZZw6+c*~FD?JwDpIryj=?KKBwo0s zL+LFiv8AVmTUR+md}S5wauUBX&&05f4=+bY(p%1AvxXWT?#MoI6_%4dG4`W3T@0~i zUf;Pw1(7tNw%Ec`!xJ4NEnUTjh`HvN*%)^qjo@K4wvO0zh=yl5vWw}^(81Ggf}w_| z9Ro>e%c`2LUsloiI!K1QcQlgf{01#|5q$zQ+?UI(GTBI=HH5yJPQST``^`M|ctFJ) z^jTf8aYGGHbd<0(T^SqU60b_D^H@AvQ-;&>dSXCB4bO6nxeqZ14y|5ZQ%W*14&c>& zIGpfHCM@qJ@(R+YPomuveQ>;#pm7y&c~upp?&_K*d(Ii`G4Tpeh@6S*=rTnu3n#7T_rO>x)eTH5`X>SLa^{w1!P*fP{68 zrQ5{b)$HVk+#Uv`jG*t`Meo)cp2g)=WDUQ`)UbWKpUXz|yh zMj-OPWNOz$++og-#n=G-W58%^7ZqD2X?QA^UX}PD;)zEls;_1|`9OsdQH@fMQ>qjy zds(5gibCk7$ExR(^McFiB$8j4@b;3e3X{LLSnf}>KpP{=)4SQl$I$fZ7A+Dry+hhpbUGK8;LEt zYxoYwnD>E>)M7H-9~{N3>szz1iPb*ea+>&H81o6FlX?0%W9UaOv8lg?yR320B?xGx zE_iPnCepoaVy~*~#qg|gbppmBd#ljX)OY5mgVcP_(%8Zs#r|+DSFU<3C{!rbYr#QI zsZuzTqYesx3`z}!2Z6*d3sSy0kBv;EmMz3ONdl-!&8Vs@ZW;-G$6G>PSF8%nF|*wi zS|S#F&zQ@<9&tm>=Cm4hY8+_p|LRvF>jwe$>4LE{=3o@bMl7fIn~8a5UOi9@a{n0W z(_Hi&so`#)IT&XVM;&rHMWr~@lGi}1k^4>{;T2YguPjQFRE)Ne7l6k^n(Hh2Bx(32 zF0QIDrey-H<|$zuuQGfajykC00!odfZ}FsSddjaLRx_09DbGG5?-rt$?{NgWuhU0E zzche@#YVt?`TQx>oh`mX;nBE4rLwUya|@ON3MWwmKhdwHhNp5pt8(?^CAF{6isqtg zGjuXFwciesc6EUZN-NV3uI#fG>lpw`CetX3*g8qWJ=Qs-^N^$cu(L~bjzW&wyVuFX z@hO?(4%W+5DGr7CF=#a`8V*u5otOu=h~mWw)obmXb=1Tvy0Z!EsLtzRpDH^=6yTVt zv=~g!Ou?J*2TZW3Z^FFgtM($Sak;H`$kl5=YbexdJ$3WPP-rDiQ`-wDn@Ugp#YSy4 ze2OALIZ4qw4I4XOmhcHkxNNNp-VLK)!8oxeW|H5c7cE8aBn{73h42#xu0hE74Gtcp zRKLNTHWhn)XU?1*ug&Op=fvp_v;O{^l;A+Z3mkUJO$x03aX`;$zB4Dat4_q*9X!_| z?(ggANGox#c@eUn3do&K?*@piJvBTTa_lF;am`n6;KT1+a|&2Fi%%RSwH8}8)bMOa z_OCbSRPl?!yMzPy+d#aApL68@Qx)&ZHQ_Afap+;53BuaC&Kb<=<0(`IIL33PZ(57F zuFDW54G=Q}(UP&m*TtDObo6iTDQF=+Sq|ChKt}^mC%9&urcd209?$4EP~_{&PD znvgFv^8>iOO-aF`PeTnq>KNx2B&3uLw*dFv^Bv&NJ?F5!U^%%l&)+y zsD+l$q(i%Gau4oyVIB?w5*zq$kIbwvOM?kD$o>?HF6Ph_LZWiu7nXYm3 zK6}wdowu^hl6Uspay!7wTL;w+pKhc--VuB9uEt1r>lxzA+>dx&)y<~4-9+yJ8Xmy4 ztx|p_&>C8Vf%H;WI2J_ZZ!~?=6>kgNE>}@#IkRb1chNUg!_yqa2W>)Xv(#A|ZK~rh zSjY|Z8p#%XK~KAjp3Q%QgpoKMY3x*dZ~6zk0(iAujXdXfzNnGc$-E(M)(eF-2R#Kb z?6FklO!=vl)p`nz3rA>Iw?M|rs(b*_OBTRkh2cHKJ)P(G$FvW?=N&XXAL2wRy)&Pn zwXXx$LUVZ{_9fT6{4Q>yE7jHounpTUM9H#<4i$~LL{ zUSAIpceUDqSor|2c}N#`x#lq?U91OJV`|~@mpU5VQ`{MF9L!GuOAvt{f3{9gtWwP) z8i&`H>bE18-r^p!ZXm9~1-QLSr+SNCm3a3r>0WQKe*KwWzEpH$zobTe#6#@CN-FFl zwqbrNNe&hBoADdJ4g;d*3%UV?LZ^*Pr;*YiWqkBTx)CZKG_S#HC!adbn@`*Nip?5p z_$Dx6?17QSpxM*MtDb)OOT{KlgM@y2SlE~7rxEca0EdAXW=sX)d&HVJ`%7xv51oA$ za&i@r{2pEHCpPY&;pJTPfQTXJr$=_d@{i3}NR`G28g2&n6#&kS($ClnLZi*p?p4t? zu^2?dAWZ8oKmnvN;ea6Wq8s$afIegU#_^B;kf#$gwlIjSmcksK!gBUD1m1)o20=Kj zUq9m$5GEi@{aZr!LdD%?o=h^pkVN7Dv5BXKr#s3VzlC}X5IsCXw;-vZv&UEMli*(D zw}s*ch+acaeZh2I5SGA`+=(Rr0l^hfW(b>@PRD;Vz>j|*d!j#nOz47tmw`*u)69?{lweO5uA zryv|e*n~Q;1+ELwO=yB2TeeWI33$stI$kzW(yQWB^KrORF(5mc&b}^s2WfZ_Pp_&h z>t_SSj`JBaab~LOGz=vC1=5g#;*O;JP|PFtgPiwKkb4+b%qazl*Xgm4Qh7v@#)f+) z&|WAX*B5Vw>OlE07E3f#;R8UhUmNB!4Gj1$ix-J%FQzki417vKznI3uM`zP>H}v_- z28uJx=}?BJwCMwq28llHG(5{O)ssMLG?+G!&|^{7Ct?rv9fJ!@x`{@g3kgm^wco;o z_YF$5=eg@O9w$Mejp4ID8rx0Bbb4=nDIF6?{PH7B|F*zuzA1Turv6dtU~#AU=BxOQ zhDOrsL+TlhH#ZHB246K>x^DwIbmoL!)sJm2=RBda5*&z^6(W{bgiVZ_%$MGChsp=B zhEYBM$#J@VD=4+Ash_d+C6kS5k3lG)_(M1Z&X#*2J9BeYo5j~Sg1N#~zOeMa^q%zL}N{6C1PqROT)diD0UGe zG`vd1ew>7K?Qhl(JejWj4*NP2u60s8#^)ek_bwzQDP7Q$-_QG78H=8gD589R;6Z^o1(*Cc#C%-afct3g*19gIbOf!(78&$FKrYD;J`S*+L(W62CTYLNn2S z0Q%ge6h2yPI!(h}cEV!uefb3mN~$jHvYBo%Ck|EaQc!0gT{?jp3u=vapgl;A?Z607 zs$aw1ZztW27W>n=bC{j^ZIt+yIiRCXegjajj56O88&=}kJL%|~VttSEJn`P+;^bfdNRl4Aj^-^G_X*vzAmS=>b`PgzMqjOg7;!*#oBrsB^jYAXC_CimUy zynmHJ@*$=OP`r{%6UC;jG`#yuq9#^};_JsEcJsl-e%E3|mOH_!tKjP?Oh~~g8s~qs zx(4X9ki?fneO@JsH>=BD(kdB3aV4sJWfgf(7MllXc@Ut#vTMQVV2=fR`J1o@ zAeJEgi6HEh%o*MM-Nq7S~q z$G*i|8TG>)ZV%duL+tk;tX~+W*W)JG$B|wj)$sG%|7G6iAXc0Et+b0d6q&pM2>z6M z&JZmo4UeM0w?sGkV21e6T!!$}2{6W|^g+DXv=UF;L%ZTdcaLXi@x;9^DYAp!pCY;q z{~aohjK`(56YMJsxQ`wI(ft`~ISzAqkUTPe?o6!ZnSiAalleyhKF|9pXQ^Oa!7_4u zwPsomOJGDxcROKvVbE-GW|GU#7~26Ztb_G&PR`0&uEU1*9@{rOa4b#_KnGVj#?&}{ zq3u-gpqsb?al1IGjHh|6PU9HPGDzTe0o_6HdoSlL6eM9JmoT<>lU_sns?E|gP)AN4 zIw*YTR2<^M^En(8y84c|H+08oCNKPFIYpkacxtf;O z_o|KRhFNGYOD~~Oy^PtE4HTCkTKy~WuN>lZum(g~P_=~v!dRzg>SyX$j*veDGvmIp|w#QkYD7K{KbH$ym zJQ7zrB@6bz*fP^>rgpWg-c8gQ2QB!Dqn!IyaxR*=?)|t8KBoomh|N4S+$Gn+27WYT zE?oKaJNTgO^COme01`f@we!TLo*EwN7-eLxV(N_fq6fX0hu4RSvzT8&ywcBU|GQ#i zPYq9WjJK>Z-f?s7->^Ia5WA7i&PP|E;X53o+~R2EEm6FTPOCzw^?Ty?=4AMF?F)FN z-AK>h6Mg(NT;Au9$9^202!Fi^f3@yY9cB0e6cCS`4OsI9bxaZ)`)PQLqkxUo1*F&o zEKL%BHFFDZ283*)xMb0B1_`13kb#zU1Wp?L3hZ6BRX#yrfOt@I>W zd}1#B6<$+_#UGpK`TI~x!vndHs(Lwzqgt+p?pJcuCbv6gR$8c2BJA@;Z;+j#fg>c5w6tUPGjH!b}KzKG?{ZMT3hKA2~l=hsXv-o{l z+^|I)!<7LOaq%y|o|=2i8BVJ-_HK?=bXWMet2|QHjV#C z^z+kjuRO%8GXF@9YT4+Xr#jU)AHfb+PQfS8nB{Jzjj5uqpN1zo3fNy=z#6-N7pd^d zHK_TA0a4rN>c^N*((nt80v_g(`(p9AnO9ja6msb{YW#`VsJVu_9dJ;15YQ>g3F`fd zY4j&znVDC>*8od)(8wiX6Mqelb&Qz7Q5^fv`yOu44-TlA-M0i)Fa&z00}MN9(NeL= zs~Vo`DB}r7l_KE{|6jmrbj%k(s_wcaOYvS?f?CiW!t;01wq;_I9vbd(&@pE~Yl!Ox zQZ;eBQ%t16L+zcSnO9lfUQTBjPX}KD)ei0R zgSfv7FJ`>sHS-eW4SvXOx|N1?ks4m=n1*;r?R46$z#=$b6k`w|cQ@TxA^Li1xbGo{ z40k=GmOzh{7%cIo;ugS~Lr+#>si=lWImU^riX+nCRcN-uU;ro7u*@71)5R8@HGGL< z#H$>gQn{G;6i2Ih!%n;0IqBkw{=5&5MEyCp2W<_`s~@T~HGO8xR9_0!W=3PGa7?FT zel`D0SuI|e7zIf?0BL(64O0VO)oRE`1zcRjL<~W&=a0{gX>5@YP_2S423o@_=7RK+ zSJZtSCH6c6C6_@1p8)^Q*~WC|If`RxbuLLsg6?oWAHsx? z&q=E@)mejyPc9-C5S~j5*NDxm8eZ%uruNs|kd-&eJBOitZg>h>! zDa`Gf2?)%ikJgJVT4{JB7h09-f|pW#>jaOX)zJzgal>rNqb(c6X8koh(@~21 z(VDuKJL-O!qm{bnAK|(;WJ%kpbru!{Wx=a>VTT@|yIG=7goX!mu~oWmekqkyP-+y# zaFD8sVj3{~MXDvi?ZIfj190x+vkD>HLUa9&Z{a zM@*cIeZneXI0*QQS4z$mTMXo&6&Ri$K}&HTAI|DFq_=;tHf*b!Rtv5`q-y5s`YllV zyA)5v>sz(X%-<}^N?wHFa+ErHnzfzMH;ez6(~;19K+IA4WDDM~G(3unsw#+#8j=(3 zl1sOUCI(qgx8QB9I~2YTaQlY-&Bn)n4bOFyHSf5imZO2!@T6ymp}xGTh13x&_IKIJ zLTb)wS|Pb`q_V!-g>R}KBkHqnjO^4r_sk7e+0+@>U_9;5BsMeh&|FLRXE^}Cm{?*>x! z>|21N`cyV{NfB`Kypd?^zJ+_NW5T=2SC8;Mq18X$YfMpyU0wT^)BCnYdO5(k%kz4^ z4!`+dIY6)cG8n017xvbN^EG;1+ZblN88#4;VSsbTF&Xw)5JHr%2Lortt8?F4a2Z6o zUlGE=83(AG)^5E+85-)`%Y}H**Eohz<6Yv~puD}fL=n*cJ0$U~Abh76hYjr&5!un< z`=iF?b^_+=u}{n}#|L5N1(5X}E#56QtHgs(DB-Tr2%82d=W>4#gsu2^vZuYjM=e1M ziL`TugKH!p{DjK+893{nu!2(yNjO1+_8`p^)Td>D>=QWHP4sfo@N}+~!jak(tB?S? z?`i*D%t~u`u3bVR!WIIezNZCWAzZ^R*mVhk93c`A*@_8?R+@_+1q<>F? z_lT>5`eS}S0&tXb9v6f(Ciabr9MENK2Zz$u*m9wwV%8}z*-U`PNjiBzY;4l-3yO-a zQ3x6jh(8Ij-w8sQAkvWUtZrsO3n^1=;Q~7}1QeX4k%wRl4R3XzT1_=e5JM-9pFMftjJUCtpWrp7^a90}?fL8bd_W411Y52U#9_0>O`h0q-0awd zs%RQpb^(e@Q8yBn;&v%KP0x=&T@BAy)ot5E&UR5LNTz)`<)DOfFl^^i5 zN$&ml9Ee@W?jNv1B=8VW*^2$Bv|`cNamdQ&A&U*){jb17%nNjR{(pu2%FLh#{Abv| ztPSWmlI%YcT&~Xp{bKd7#+BM^*B2sSGfYuUQ>uSlOmCOE1QG#R=U}6+1zc)0Flwy5 zRjsypR%46#ff^ncm$wT;l=%R+^J=s{mC@Q)-*c<6rP!mnAxa1!)gH~SGFrRp(KNPA zKhVe%;+nSaT;&(SED`a=BwpG1-X6m;g?6rrhOw4PbEBr;i|!*k@HkPD5(o24V`tAo z>9)gx7&@1;N?2Zvu=dr$JY>gs9jk>U(hA5I6&Z!J^LufbYsn0}9LHlY{}arCl@O?v z6nNZPKS|I+j&uLQ@|LmV@nKf;vB^7`?gj$f?+H&J!3Pp53urpR_+W&ah1N`p3|-#&EGX{YdRl(!g@Q=i~-&QBObiVa$5xZxyx+`hkaa37t^1ZSRZ zG_Q2J({!ysT-2ig(VS3f$v-1^rvzN41RufHtWNfkh8Esk5#_i6*<6?2J}Itj=?fW$ z0fq~Zfp1Sfb{S|cm6Kw$@X;r!^(hfo0lRQDVn@{2&up%%)ICRqDgKnW+|2hz76DFQ zAk%5Fagv6oLo06i>PA1yHT^#;b_yE}Iaz=jrGbi_#WsR|<-fwX#f}2h5fVMQj+??x ze=pAH7(WHc2kTt+*XJMpa*c{>fz(MORaBDN1!}ZV8gWKkX67sTPh+P~!7p_0jOdx9 z;Uzp**z}|2O4`MAey9F_xq2aFL)HmEWv-kNiI+8wk0=2B)_;cCSPAF_&;jveb#J@# zE?RLGr5X>X!g&;O@kNwsuDw*T)1aNbRJHKXQ#9~LF{9g(zj&q0G*nhD6-~3;j4ct20gzbK`hR+a5qv`pebIY1;@Y=?q`KWaN|&ystj*YGMuP$ zza^{z-4~K7jj?4H$>+sYBXY42tO&5C5J~(c2M#*%_$ref!VRtP`AN)R=^oVoXK_`MZ!gTA zU?F_gC8&WLT*s+uU~O)t8X8NXqQKMj-s5uo~5NEV>fdDI$3z38D zj--VLo~CzxLA5x(2u%t21An8s7e)626VJgOfZ`%KfqpBJLQ^Kq;eKTd1O|ER|$v1@A$&*Ks7$LW8a!*tg;9*^U& zX1%4JG`dB1R>@5hiv3QmML%8=-(zp=!`~w-as|979&r) z^g>IXr^@C{CureiNaFu$_NL&f?`e>e3aBhwm;Fj}t8@R5Ee3t_e};XY#Ig}^{67P~ zW+y<$u|)qN^b#uu9VY_)N7w_#KyUn?VJq}Lpm(nf^TP~qrKUUeJrEE9Yt+mIh3pf( zsQ(o)KHx$LdfR_cxyppf3%_yY?Q2GC9>5y6dg(fiBj5}bUlFs+d{BN7(ER}|`(5;Q z*6@%sFe&Yc7hPFE6FT#|=-KU16Qx#z^I{j za6RItgS73AxQLY>prE@*F61EXzl-Eu4pP5T;0q7hPL_(N1orSS(S1mtd661s|Ps}ghHnv{syZuCL zCa`mds7{5rnPna(TLtvn@jcCWh79aFKy{vr8=3VWef3;SVdZOWU0#T71lH{E>Z#H} zmU@_42+|_vbc}Wi(n=;Cqh3s!#{#~kubH%-6(6HF^?1HI>nRvW-S={xc^ zN(KmINOAQ5f{{VTLz)^C5KIP9H$Em(q+QwEM zpl{65VwQS>2G){LI49`$S_m)xo<=x9a?yA6yOXq$%{gLw-&wjMu+yh-MuPMP!z-b! zjx^E~bWE}QuLc_AF1b^ni`18G`j+OpNO5f5ck~y3E;>%b>q^tuj$`y~U1<)>IYQm) zNz>$J-zjnbq+a!;82RE61^b3$O{lXg1SNb+Nv;sk|2w+t3IVSjp;2zoD)bor;Rbtz z52mF0(s&aatVG?;D9%F~rA)cP8`jYtcWE>W8A03KrSU9n6xC^fXUJ%p)c``HN74Tp zK-l_GG}!}mm%((3KLZC-TTeW%kD^ulnK#n*$Wy8-2sg>pNNOU);A5WDM>tLYG?FF@ zV`!L{G)ve>KX^&Qg=||>Z>crxeu%;wOOx2qgOtagd56fS31m5Sp_C>_J3EQWnxFu~ z4$*ucX$(s|L|1&k*ZmNMHkC%QvV)Y>R2s#OF0nmpDm7rr!e-+u`X}V&E5*vC8OU$A z{v@UOO35a3GO+IY6h@vcq)x&T8iEH4PNu~zq}iQ~g1At0H5x@9(N$cEUxJug9Tz`( znP$|BIEc(o>fV3}qE5gliOo+zB8~M61;N-s>_kKSq<&2Fqg{B)PI${Tw$-no3O^~C zn}V;QQS?>>x&!e;!;J4l0!|$Z zmOA@P!IT_~dK9V|^={z8qzyD$VCPz+a7F7lR|~z5qJKTTi6`u8G;#jM`XuocV*{Qa zz1V=KhF{Leq8?e`xoHStEsXUl8IX-eU<)w{^^p+IIb$RQOWoxw%aDqmv1MI6gJIi}aq*oBX;;gN1zCoUYOqLFj60++AueFpp-oKCeg}1tFZ~^^oQYK6Jl_ zbVMkmy*;I|IO4rth%|wjtu!}8S_t$>2x{+5it8mM3B|TMy`Vpx)-+CV4oT&(XIjeK_!}yHqw@Dj?qxQg0S{ zgQkpt;}`x-7e*k^=N}3liD!?0Z0RGVLoy5ekcLb^GnVtA?cM}5y3Cqwn?4CmjF3z1 zCQ1IZf3j4UrDxL*lclagBQi{p{9MJ3+!$gb)d6JvP%MGyjM`h00J zGc=`(^O5DwbE)@xct$UvUHn--hZ-(G`xmf)7AydskVLoeltVBpW$Xf{D_tOY(%JW< zT9lk5g|MUBZO4)%D`Pi%Q_1_Ve0Fb&TqsS#+5CqVN?!_zH0}ebTdxLMy=f@6;O-_i zGfMD!alBFQ1soOAXyUk^5$E{ZtF~x03T|lDc)Nyb_<+ ze9dN9EM@9h$_?AbrBYW01EEz$Tee)P?-#iTLIiy>v$sf1jV`=Bx}}54`p=Sh{V|CC z)HO}&=iUI#hS9_;EwaNiA?hWu31y^7?fWym1)1W-Xb`Q)W?zNXqOkHRV?h2T-t3?q zLTqoNK|hx#R2wPiMbKSwM;2Q5D%IrN_KIq|D0`)JTu7rKzILVMNZ#iN`p4w4QtIq2 zdU3tbRvHZr^s!v1r)zz?RkPJt%U4NW!q2p0m9$9??W{!JOi}4lrre{Qf-R$pbTlil+#U(J@r3O-fHP>p$)ankb280YJ^*qkRe42N2|1A20hg#X`rz)a?{N= znxrs^LZj7oq=q zfhUD-kuqx88+v_1n7n>AdVMb%kuCLat81$WKo7zr7{u4PG4y7UphkfmaukVXaW^y2 zxooKy>)wW3w_+@Ht2NoSqS44}ZR@j5!tLj&BCb!8p0jXgYPnOo$dZl3c1c%RfRV26 zl5Vk^wQOg1qv2)IB2C_dm}?mQyGQzxCFpEx_ew_@%QxCa?~}%(r4npM_e7yFr<8vF7K6{g2e!A4OYQwNv1&DC{0sU2gftJ%l+gm?KegccQN2^Xs3s~oSW_$OdR1Zo%vn~Hs$`tgttCHGWl77?Ua!Q-iW$6`x#d_20 zze&g0{0dv$E2#3!r-3c*s^rdCd41cWA}L;AZVhea*CZc-BDDdn?3H(SIF9wXjF34ft*q8iyc-sEHO(aMfF^h4vT{OrC1y)hlwo;TY;72)4k>x8)SJ&3hByWO> z6;xuD3t3bh+lgAT7h`^psn}WmiQTE7yxQ_2c2;K#sUsr~DbBWyE;!wvU3IqYuPY}A z?C28;a7EmswQZuC{H?&c8|YMhc^SKEpi%DfMpn;AFWlvMtk6L3Hjv}kVT0{<1G$@l z6@6y2ddaXu>|9%rw>*hacnevwZD=B!1eUOsw)w~lS;=l{(^THZ=543TO@SxOp)t+m zW9;U8)T}vj>9w1VHJ4Aa!mYH-7xdI^6wyLn%+eRo)fUJ>_BPt8wTG%hqnEg;r=)dpkY1B0Ov!t@TIz(jB%jE#+{yL>%R`g1YD8$R|L)%Ff1Rw3c76 ztazKy2KVbR_YLIS773NEr%&6$M84~&X&@K4j@AVtp@*}`yPbT8bzVo#L0pk_bS+3e z%Y4`4lQEu|>*@VqWNg>lw$>fw#R4mvMF%>{)08vT(B3_xBOT=!w&QJD(Mg6c&$d15 zBr}0MNg$z%e9XiTm;>9=T6DCdJb{g$P3^jZuOyS!bw%>=bI7|J@RS+!aW~}4Ez>rz zJ5MHRvhC6*7l$Wu3})~8tN4S&C}M<*CFyjR!;OzFW_!#=s_=-_8ieSy^+J4 z6KwW@sN4~CaShdd6?rM1V!QUL4F6s7DSbWw*7aFS!(Nl0u!0G;A+O8R z5T%dp>o6G&O!Oy!hhRZSXCd>~4`$fT6ac_EiD0qGQ(C>Jf_%R&_#hqk|sN!z4FA~8aU8w0W zBz>cs?Z7Zu6xg&bwr}3xKm7X855whM>}XfpJ5e$k)?GbqACHhnGB&?I{W%JyoE1iI zkA^qwK!?Sj$HQpIo3M#)pzYF|xSxRKUZL7!(rwKos1kRhU(w~zdX-s?C zIR*5JezsSp%9zT?4We<=xTql8fVbo(u<2_wEf#enIgIYa%5zwH7)_dv0*nu%>(k*2 z^Ix-#kCXc`wy8gDi$HUgqLko!#JJGTR!m?>{y;R9&$EO{oY7(lmM5mX_`%QeYGyLwEp2n`0 zgXrrt`8~GzGId{pN_6-V$t$6z?|GWfpH~X0lt06Mv&F2EgU|+_rZwqEE$WOdYBe`e z_8{7k0ax2Lh`b1?liW>U=5RW{202I`LQ6k|gP0>|*jnhfD4ZUzg-GiVn*JG@ z#;n2QoQa%ghSPyesIX%ceYj3u$zmdGp6lfsdRD&NCTx^j!u6I@>n~vQ?kni`FW?_z z2Gb9lVDqw3G~`RzEMkQ1@t5)9eM+akZg;)5tG8_(z<+QgsXK~#aK z%onl15=&`YHryeVwr`b(n-ZHU#CwdkXUl_GNDz(QCck0gOG|iNwv&B=$Z0#se8mXJ z2khkRy_C<%eDw#&>+R(J9Vm7O$b9hz$O~06E)Z$76Djhg7@*z|)D(Mkpwl~{WpD@b z-G!&eXEcA8Jf7vWr=nf*AeMNA0(Z+1Ccbz9W5z`S{jpnqo%LTzg&?y{NfeNSXV_9o z&XGT3N9WnR_sD+C#J_nXnIavv&z0NIyszX}SlALe@RdAM=3l50=0``rlHDl!E4d+! z%av1D$qf1{7lo9!m_FKv{-@v*YQ7(J*!L6KvLA&SI*Vr5(1NDL*xt(H&2>B&56CB- z`IjpQwD9*UcPcs|d(zy4s7bkfsM{fV42%4TK073Dmiady@Li*~^JEVimoJyf{M!gf zJ-IH8DB)}QO__fl0jY^XvXy-;FP2z9DkXmhN#@U}=sV;$-$219;P<0bZKqGjb6nVk z5(@nlItPH^S2$us2g)pz|F%85B)4ipAsHqEg}61T5mSh!kyLBdH$wcACC^l)o7KPXQn+R7W&5qQDnemv?lcsTPg93M;1-$+d(Ylv6Bw)7F*H zy)?)aPsy*CJgDfATnASJWnGoMS%!{Yv^V)tV^@>OHm|+uEkn~bYDymb8CWCLETs6H z#LiF=izn+sY)EHQE&NW4GI_H=fi_%`o6xRaCTaB!lZlF+L8q$n-rCtTUT(>h()6GW ziq>o3W6_K7ul99WVpc}WN1MF(bH!uXOR(D3cQLt7qp~lcx8jNyzA*XFFJGFlRY{Ln z=Za*r&3%(;S%cbw)1YB}e5`?qft~$z2HJecG_nTG#_~-U%}&)BDeWhdx9!0RQ*+N6 z%pWx@G6BqhS^y`2GoUu04#36Mu&D0!tN$U)^GLlP1?TFC;Piq!Ud=yp`lcSh72pP_ z4{!%G0C)gA0Sy6-Y);>J^>1B68@hACT%>JOHd%fviJ&RbnTQSfVo|uI;SnoSnMy<{kPzNOUUIc#PE~%vVOEQVP21M3le@;zomiMc)}fZ~Tf9^`WF+Ek3}qezo{v2I>1> zElmZP{{9vADQQi03SpNkZKz8j$}O)g#S~hadWE;s>#(g)$@hfu*nh(R)XE~`Lq5!3 z8boIbEp1qFdwN!g5}_^(M28}-H-zu;#F~%olDs& zIu!RUPmP-ll1|qGz;vTup~VnBFt~?acLfwpsIs_inu+7m56?1rPN)WvI{le|t?^(w~0+ zjl1*!lCB`m=z-*S1r`knr@>b&?VWsv=ym)q7qu$=VsKUBs%01zK|8OYxWk81;T5>$ zlt_BPpXtNM?{`Zpmhc7*{To==?cctPgjw|>41zsEIZl! z3AFnUqVAkZ%&!6*BOxYY@{?XF@DC_>Eq(@Q!Am^IK9$)ZvX`$V<*M84^n~~;y-R@ zoT0~xEL;y|59T{r_+Nbh9D&ANvv@F{V0!l&+&G5TUPD`blfJ%&TGgHYxCZ5pcgVPI z`NC<+JiXGGZACm#_y2&U(2W0CBARbX z*6S`HDlfnoT(UhOVeFI{Gu{HG)A<6JE|H4=XR)9=aVkc4l~3J^EgrSnD?zy*>UHO6 zY_X+@8}>8mX2GZN&@7Nb9~VRU`IKF3X^j@=BFDPZgJQHW@?x_5i7XYvdkR zBMP6A+xa(A3SX_Dx(xc_FKAvur~X2hR!HT4p~)+tmNzYd=z&JvL_#_A@l6o3=n%)e z=u=UH)* z>fA*Re5vzYBppuC980E;?;>}x^wnJy;1s%k7gzq0Hhpv-ZCUX> z%Ds;vMA>~RypMh~l^)->_&cRPs7io@ca3V(+*Hv%=OGRL7h|pCk0{|^)SW`iHvS89 z`O?9EA-_9a`xok4$y^3gL{i5xOUqgpoDI4ZhTYt}r4RRSq_h=kZHb~4W#I2m2g}gn z9e1T`WiWam)qa3Sck1>4?h;0CJwR(#9C} zx)A7C{2vLfAperh{5tB=qZ?l5Ni1ZMqENepFovJN_>I>iKWk;pmt=^*B}~m zMj3RaBq#Tfej zsU?UNPo}3Fb)yy)D5e04s6b%{(1Hp}^ID;E47v)$#mIvebjOAtF08X6EQHQgSh_(a zr)SW54Rw2l(%nRFJ%dfklPH~26X{!^f)Cw(hAg>}+jC0?JYIW_n(0J|&(XxlwDmby zI@9^*@VHPae-5ARywsrdiwBSrMPIcxqropwt-9057vPPdg)d;}7~0RVc)I!m!c$jE zR)1r`DmdrrrPjvO(^E7m+Nv#3+Ug0`7Od>E)r+kGMxPA^T^6|1Zr(m{%3O_fkO4uk zHgn4U(xAgJt~y15J%v_RMN|hR!xYxRcH>s|T$Q5^F08 z@QDtl3!u}?+752{oLO7JxGnY84tPZCfqBppy)_7Kb3|`#iQL@c4Nii)W#Gd63<;?OP;<%JhWnlb=^^y4WVPVM;tR>@hl+4gvNmT^w$NS4+K821Bq!PG z=M;7cbqOWJH?Y&5F``;RzKVh3X|xOhQIsNEc@^4<2xu(NfymBXr^m9jEh{djmL|yC z@h81%vidvixB=U1CC*RdQVP^hk+nP|?B?He&t&CQrLh?jca+epW@N46 zABrxtl6lusw&gl18}xjU~Q`zZFINVDDyS+ zW^KinQftFbIkkE3Lj!7l4SU zQWW3Czq)<%-DzhXtF_k621Z?fJIi^nC_b;g0tIHcz`MgKzy)?%L&IEPlA~Vqo(pW@ zK^r->Go9iOA1Xs2a@MFW%oR&L>sp&NUt%>X?bzoi1%A+^wiq9%y{Ap3l)5O)@RoF~ zp0z$5t7~n*yjrP9DMxPFk;e6aY-4g$jJ>U`cOwV@RoF>iEb#}oKCa^Pa%Q!@<(SXbc2B^{$Fc%9M*zHfA=WnXQ2EV0;|6LWfSANSntt#;iz5Etc^V{na z1f<)Gs?vuMehQsgwQo-G8`>-NgbKaFCAOijf2=C2Jm0Tgjmhor=buw8*hEKEqyBjR z_G+w@M*cJWDU&-WCpd{bO>KY0>zot*s>T8=qi!A;z>`p&)Nbd=ocPqH89h$;&(V!e6eH2 zmpWE_hhxR}I4;NZy>fM;2`ZtgV>Ph9ZhHJ1$BOr^mmcruIOw3`po5NiP^{sm zu(DSC(Z-Qgf0JXy|7?;T*Y#CS{iOE<7m3*dHL%&S8u*W6#dT4c%~w2^AL*P$ zKnW8atASe_D?Z(^;u_SMKfJ<~tihnI6|c@M9@eU_d&8}hK?6>K5;VlEO;B9J-&!lK zfq1PI*Py)CifhDJYsIHJR$K$Fns_oeQfM?*TR{mLC)QdG?02lV27h(q8Y0$OagBs( zt@;`~)mrhD#b!JwC1~_kHzAj+8m$#S%dr~JRgZ4Gb-T!l>oF{DT#w?gR$NbY37lk| zX#%)z|Ry%I6>yc0dE}tH5qV8phmO4QSwV z>!1P0iZAbx9$)ELaSb8u*4J3cSO>wd0~$ElP0*0X)@ne*AzP~h8b{e$agC{Lt#~uX zieKzlagA3VPTzDu!scDsit9NW){5&%7+U_k!d0M$MOZ6A!=YKL zfgzVfR(ynG#V1^v9@i+oZhejLYpwbW1)MA{Py-q?*iF#D!q$pw3}S0FP|vaA8q(N} zYxrJk#Wl3Awdx-o&Qk?yrjNUb4`!;;%baeLek5*>(x*4r^=0 z4<(%fHK50fx(Pf=q1cK);aCmms&$*M_!o{9|HiT6dV;9US3H^T6e!_h$4bye^0tEF ziybSjXTi8}JwM!9aXq%xTJ<%0fi>}@r>Az?0ww6ydTTYHrwCgsuE+UWE3W6rS}R^O zIkMty9V&){5)CWNXEB4|8bF|4PvK0d9iE8n9MegIHLr0S$0rt++;&uvT0nP*^Ljkt?hf z*C-c(b^cd^uJdveGIf znC4gw%yO*wvyK(ly?FfL6>el7-xXPL-Gml|P5jT$+Wx~1=w3KCVU%MvpgZc^xCXtl zR$PP0S*wE@XwF)34P$4mxJJAyKL0C0BgnZ4-IhdFoCi;*#qV{j_)^E3K)?H)c;zF7swDWIHJ z*u%;XL{sV>a94r2a_7!RIq_@&3P(tO$(h|H&9V>p$%JewT&`ayUA;;>#amT8E-;+^( za8g|76eywUDmQ`4JRB=N-LWQcuVclBtWK{#$+6 zb>K(Gil4hay}s_$qnKB?t>5=tw)p0O~jurpvrS$qo9V`B~wLK|jzZ_LiLIcN|KzqlEpX*rh-i{R? z;aKr0jun5vnC&l|!%eY-cO9#N9gfvNr_E7^74P9#aYm?4TLlXpE57RWAg=8{?7*6^ zAg~gicq_euHI5Z;@^*T>tz*SMc`rS#k?JYt6|UkZ-j{=ug6Tj|5G81=?;ziFP(yKB zYXTa*+geLNW9eHfu5tFQ71xs^tQFU=_Gu@@dMXHBVGs3S18X&)XP8*40X_M|T5&xg z!dh`XufSSyJ!`>Qag9D7%)ea)8sFYc(Af9ZYCvQ4TdM&Lux_om9%EpwxE{D^t+<|& zXs!4+`(h`>A7cr>e;!p(19@LWRs+}XkF5Cnj)MstNRQX}Dzf4ad~;b;payn*6Ilu0 zJ68O#W5xe;thjeDy?%RtdmB!&E5D73mA1jLn%VW=^!OgfinsnQJ>Jc+;@cdn{XLF} zC%qm&q&G0gu^JfSSPfk2Sn&^kOs}t@d?@A>ZmQ#diLCm|9S7e$uR5Hbu+Fh2P;?|c z-qx|=(;RC8vm7ga>aXebYd8+RdEVy~sDb^C)xgQ$(i`xOMpnGwSY*|2=2-Cwf27Cn za2$N|T<3UtLMO*+;4a6Szy`;PA9k$xNymy;{WHD&8j-_qo~K0x!AW(gV>PhJu_my^ zvEsk}FMR?PPexXJl4I4MT5R*p^ZUgG;Q@D-V>NKgUr~cPlTgQrj@ppQC zZln%3Qv1zwuYb}LxMetPE1v0C6X0&^wD<fyRr!Uo5R zPs>biV5wupUv;brY;&x55o4n9hgZ0S+lLNMvP!r;mN4J3;tx311Xem$e1l`fHSijL zc!kG-DLIi9pB~tpWYxf?Si)wVFMKy zE1{8NHSn%u#dkSYe3`$!14s0JrP7<3=vZmf90&b$toTC5ir?#4@wXi-{=Q@4Ngi~N z-hncX)xavpYG9jV#dkPXe3xUz$Dfkk{&dH|5xqs(^n`wn)xb2zn!qf_iVrv~z5Wo# zik~c(9{0*e4vy#}PLB#SfzgiD!21=`<9i${-mP+ayq9CePpy(3&vP6c(dRh@>cB$B zYG8cT^af@*R(zi0puS_pS2^_Zd+IB@A(_20n4D_+iJ2e^?{E{!zz@4>>bEKHl0M(SNiB=74wDanL}` z^ad_G92u74Mdp9`9jXd_>Bl^OE^amr`GjKb3EpcA5uKAt58gsF>^3Rw3CEfBbtD~VR zm6k=KZrRbWnAU6g2lo_L?w;R-n~eQ)`P;?*BA|R-!>7?xZGJ~=&(VrshL_TRU5Y7R zg_kw;U+A8HPIKJ`ZR?nH_y#)Qd^@d+xUaT?e7n^nPq;Z^YWYa*Pz}u?I39yYTEjL*#0b`YNupHKSRjX zvHjV>HoL)JLbIJU7QJm|G->w72c>aiP4SNn@y;S@QX+vs9 z&E~Mm?e$)YpMmY=U2=15FXxia!}iJ@c_g-1>d61X_QD)_Nj96iy%I+SYe}$I-pKD@ zd!>#1HMSSl$bVryzQ8Vrayjgk&PG-j>j4Tj-WuyE4A$r8u)En`*3{r-N>~sj+<^6< z09#=O*0=`NOR&cGwSE%Y@4waF>)3wZE$_niJ4yKvSEm+#38?}G_x2cq;LV=w1`M?D zJAadUsEnP!S0&iZ9UsGbFqDm-Qj)jAj_YDQ#L326VLjlbF%Y=6~JygW5e5I>9k zQ1QatiqWq+O6WpDhedwt^Yfe3vDY@J{9DTP%r-mWll+V8Hg6{{X}=*;o?nU%n=i!V zr|~YwFJb$InBwo^p?m>0$aHuQwqJ-TegxYuz~s!*o~OsE+J00n%@XY96x1WZej%m` zXJb9X(^lw)E!}9kCvRYkhH&0zHV=7TkpOU|Z`uu^z!{ zy$tKwj@Ik(sh>sOj`h?_8~+sRF^JZ`VEc`oX24(9C%@hRdm)QT=5YDAo?&fkJcR9a zDvEEw_PP}LJ#4Q-kq_dd!~F(*^ZO?4g>ouC&S`d7Yle%aVQsyqa5}XY$|>Fe&mbP& z%fk5E*j^{6_z?UG@p`8Iwb))Kr}!*<(24t}GEjxRP)-SJNGRKer#zSjUc>f6ImP#3 zbJbRGn*0gdi?kHaIE}5jXS85+I&A9?z97G8mm$u9^D)xw1%|4Y!uEnf`5oMteioQ+ z?8OW`^yUTmeY=F$Y=vj(zj+&CFVRxHQ_FLJ?;TCPHlFUdHD+X^3;VI$?G==&*Q)}{ zwFOUeGt(P|?G==YPsSUGKV{UhO?cc+Vgn2 zStGC#xc8autCTF+!*M4( z&+!DWIO~OTZ{{2x0CgKHn zw29Bb_A&-7ktcEO2mEgbvt;e1YAWwpgKc=o75U-6XVi628Ojuw51Z!>gS5Y1|=huba>W>*D%c2QksK z*9zO~CKT_9A0pn%#4k~Ty>LPaH{l~BG%yKwQNd26Ae9-ds#^u!gGQRZhGqUX6#C zcsJ}l9n~LNn^l}af!!O&lW?k&Faw{4$D0Q3#kV-|r|`dUo{7JTA8_LT#t&k<#=gb& zIu0$Nc=+dXG|)H(d=*MDtMtH^kG-d^W}Qmm}3b4{!Z5sy__dAAS_S7VqYVAdZH?a!A%= z)A`x_GNgosB>aNe1%iY}@P}SBW9#ro*mmGG9DM7~AJyND?U(%W@7R79Etjd!f-v7r z%lY*OG6$zd6X-yK{c>6f{jvQrS{{#2nlGp2sn~uOE$hwU5P$Hce2rj#w^ea@Z90EM z3$g{yz!NCe2GJke9}$De;JL&fF!9;g{zjXQa6*vBcb`{dUo z*xvxvz!7{uYbwt)@E86b!(c&HZ0LDE;MYw&f!F*mig&@!;B!rUD7L?_sr|_f*(Znc zlbLa-nKhMZIcdyEgR$OIlf0t3b zRg!``%nvCl=z;AIFY*X%e`t|sV*9&_ycFBtQRJtv{oO=<4L38tGRU7``>TVjJJ7uL zm7*RV$HyI)O?aODnL!m2*#2rDcgG9Om-zBM z!1h~x`9o~K#FxLr_Dg$N+w#&9;0xh5`is&zv~ z%%LE!xFE~xf{Pqqf_tPMzbyZ>jHLaAToZny(DOR8b@w&f#(sR%*}DJ0$1pp0uxdz)Gm=%8q zALIw;v8DsxVEg;A;(y=;Z2YY8pnh&+zS6>w<&@#o#4lpId$(xJ-eP|rRzhbIHnMlv z17%-qe=kvdEVjRo$XZpGvSh3BSF7q);<8;ecjJkUS71Ik=V=LP)jgk0!7jhmsQkN= z_PQLk`&<)FMEktl5@tqT!S-qn#oxjo9*$=06P$e{@^{!?-JyJaRX)IpSH?pe7dB;0 z*vmas;Vcq1I|;q8z1&0bOYn$aqX}M%?bRNN--f6D7R7yRul7*<8Jusf{*Yg9%9@z& z6znEpo#R8;UJjxPC-GOuq6w5~#>HTc>)|rLNAVVTo8xn_{b641jU7aR{Uu%nTD6l- z^YS*a4zz0L5SK4Ct8O9Qf!WZ=&hj3V%SZ9YaU*}p==_dJdzFZqE!W)h&g1|;%BvqsnxH3hL&y#I4n>$$aNDa7_Nz6Z+dbewFwGiS`a(`7iupW8H%r?!aY>I6Y$9@dmhklgO>G=MTOjziEX|&7$JF zDdyP@_g%qvGxq*oHUBf^dZdJHE~6E@qvHx#&$Y1edf48YsroIjz3g7@f_txv@-I|; zedNnqv0G(lMGJzp;W5yC9-qTmBAMPbRQLvSWT!bsyTXhQS?rnkN5^;K!;T-q_Lc1& z`DatiJ6f?@%`z9lsmJO7Lqg_h7S(~zsUTAvbl@9&+?l`+u?9240rG-rYJ!#V@|w{c z*NMg3CSwKX<9lmG6-MGu9N&bi=0)+v*xq`n8PIOo=q4|(Q!oQr-qXabwY|TH?Mod@ zei$p@-rwQ@4AkIJe8`#LX>B=xo&PV^ zK*hGUc}^lspa5U$tkZMw6vsoc9aum!bU8jzFPfpN@hbbZmo6f>n}S2O0BerdFvnL0 z9pWrV+*)(I1>2W8^jXZmVLP~lI*{9rZN&MpupT~cKA9(#(3t{z-=2IiZZyp735fjl8yfK!)Fy>X*-l-GR=jh=bqJe&<0i8Z*C$C)a zC)0aA*1)GRAIJ9IAT?N~11DJLbW|PN>#!Bi$9uUh+kOB@Y8|zm>E*5CuiXaPvPioG z9SDzY<>*i;)1e|7sEF+ewG*z2)o-0(2VncsA|D^~ZP?yxM2C{WvFgxmUS3hjumjpi zWV?|ph&AwJ%&%g5b5pQL=?Qmx=FOuQnxVI2`QN5FdE}prb2zw}8)nr&HEeI7m78Jv z(j4`Uc?{lDBHBnNVSf85evdO9_i%g{-c;Vivzfpne);Rz6Kj~Is&@^~l4Gr<`aHHT z_2I*qkH%c3qsp8iajN%XD za~!Y2_VRhfwO!{igLb=qnRq=j!u-0T*L7u zT;zBs?&di8Jq1IYf{f05apbrJgOxL&oWgER4=$VqRBDpZdW zp1}t({R)=A8@SmSQG6HfqwO%XEW)I+hWpKXPMqW+}?=~#+@8rgu6K& zitS5l`Nl4u|Hh>J^2w#n+n@C$-H&zZ)u!<=-s8lN;k{10a#xO#b)p$>jP1x&+SIz@ zgLR`{YA(WdWGcn4>B`=@lsACtnF?l-U`Ljc7hpS*l)M~&SD%Mnn+~qWXEliGZ^5PW zBk#qh;6Wx|Cxy){^@+jswA7Ov!^~pR@#!!XthJbrVf)fzE8EQ~JpR z3R=SL$d|J*OE?*9>HVSt?_5p5yflZG#e5^Sm%G~uj$nd$)X|^doJe`=M+&-{wa!Uj;GUsDW(H0h})NDpl8g(@I3onfj;G2 zPeJMFQG>H_k>h)?9Th=7iz~A9Arh#A%7cqxyRdyR$#T-@)+ROA-kZ)g_!PjH{8uLu`aM&d+vcD)OcR{p{ z&gjJ%(eYWhpW};glc7=m&A5}}Wq8xYQT$nK$BEMP-oy(paW$rtCyuYidX&AEiaKx`?v`{47E@sFvsS_rc+wkDg%n=tcn7|H zTNFQp^}KsKfj@B%$EADoE4t$|aq|85q6*C@*x@)>$1A+NMkT{_+@1KzCpgryRqJzZ zPi$XW$8%$T2QPjxYX3|8qvIpJ+5dla3bOhz2d_pID&jjFH^etNi?k&^>9{A(-Wt^( zflD|`crq^Icu^m=|8Javr%7n!EaEruF2|qXPR=6#FTT+6F+9z&ei2*a_)I+3Sp`j# z6zq2jy5amcqdB+;-{JTg{LNcY{1$9qS_PY9{u|rTP_#{zx`40T9*ExkCo53!tg{O0 z;kDQvI*V|=bLi}b?PvpPa4_EavX^@yz0iSWG;Xjt>fp_|AwJ0wQStfs`e>CVy$2|` zfdc!E-ItJDh>$up54cMQ+~}55k9?RWJrW{B|_QH{zPkUZl77n>jM_hkYhfm$nz1_n(>G z0t)O)>+r*vPwUS*bXO5B=d6;BxRc|7_)5oD`NW^H0CpSzimee z(GqElPdw-4Zlh9gvca35kCs3`{0i1NP4SU9dqWhz0q5Yi^)06oZll1CGNK7QfcKK1 z1)=y_oWC(@;8Scz9Z~)-xE=9MCO>B&?|_{AGx4q1o;_RQaMTfV{vSxecBg^supML7&RF30S9HPu6`c`ASA>7I>d$ij0DqFt#d6=pcVy^`q;SSR zj>W&mx=&DVRJ345@YlU>@RwNr-#C~121hyhGUUbnl{+~6r~a=QJp+#?L60D_6Oh9! zE^jA(tFgAd##nc??Q-&iyWD~bTw@=!;T*|f z62B=BKiyajj7e*NkLp-A9)_PU!usxwh|^>F3vp4sjNtB+EPcKh!IV^BC-`8j!qa#$ z@g^kLB_iAW7h?Hu;Vs174#_tE-%fr~i~MT}+Hz;(AZHQEw!+U&1?B&RbswP4DYirI zeSswvFfZj-$4B=?dz%yIS5y)TV-?~)Cl()o?PwJcxc`pD%U#4-!D%uc&m(SM zTBa>=&99>_bi0UynH};#eU4Y?9cy4X9^y0*k57o@&&EA6qX|A9i$8wRX|{jiLfquf zxPv3mTd}-7Sa%Y)cD6?M&f;%k`N#0DdFe+aIh+{pgNLL~wldazxXUPJISdH)zwpLf zCGs0wtU^)D=V6{Q5Pa0qf*e6DS+!Mvu-|+xE4zrIrOrIaHs$(Qle6*f>{0VcuuaM~ z|DIU>6L>y98|rjp^JSaAVMuW13aPE(Eh^k+5>#P#tiibd8;k!L^Ql9_w)KCt-w;oA zcJZ@^7H{lf!UZJQ@qyHVvG_mVL|e-=yx;MC*p3&Z{B_vAG{M(n-WBtIlPWkEP2e(C z#Z-P^%A;5f{z=?A183_EsCj7uamP3JD&)JHdmG%>+5D3inF4*}*90fy0ZxK%td*vC zd;%%rnm`E?|G)Pq(_8+i!?C#k&zV$SfJ&(E)0w#I5NZv=VzrXa%~ zIiL3jmHZj}NjA8|Ru88Vcbi!J|K)zM{86|)bIHl~|7$5E|Cvd`#ZE$OHvfrtDDLs@Rr@eOzgX_q=ncCxWu^7r8p#O($iUvqJ9 zB;UTYEyvvDpEqL(d+^NIQBn>Y;p&lCeulr|Znpdke=C2I2V>FrmK~dXygUEIH@x3z zuN$*lywqatSHH~8T(GAl|DRiSeEIzUYu*|EzZ#6sVH4)yTxW$3i20_NABg!?*V^*G zatm;Y5$O{sFt&@dFSajjAy?vUe3;QePaEmr_!KMtC+3=C z_)5WXvq?v4{!OR^3gh`VAKcvQ?c#XL9W zhg>IVaGhI#x5T_B=EE`P^6}H{P+rV!WA5iTsX4mRDUhefyfo$~V}3d29Wft>`Pay; zgGHEiW%?XcjJa;iE&TF6+wRa<@%WgNF)xn!@t8No{87w@(#^M;<6`}exiIFlV(uC9 z@R+ZUd1ji~b{D4=WO$Fp{9Md$$9y2>qcK;wDt!j)xYoAY!Y#mEVjd9l*qEosd{4~l zV}93hu6a0dL zXKVug$+(+o-~?W8<4ho9Ja@fXlV9F7@!H1vjY)Id6d$wsxE=0Tf_I?y+}fXl&MGh! zuEJd%--f&6(k8wTUx3RPFT=yIW>FJdYYYRw5%ZUL4Ee#Y%5|vliz!eAx#Trrf^}_t z4HbHs2HWBku3+2&zvFb^JiHsLzLxMM#=#8YN%+$e=2vYc+(W@$Dm2OnD=f#Qav2)P zH1HJeiN}`;<1gS>D$ya6|F-h0gm+4-y)W^ZIOrh$1GmEAIg7zZCa^@S@U6Eks87LA z5=xi}o`uIa4fe-3<4z`iIerD(3H%H1#qU3J#ls zEfh58YC7A%N4PVdZW{Os533p8t*$vdif_hsO#QOgdfp0rm2nk(O08%KHpbm?MHBCg zlS3(JZwfA?UuG@vXR8UN~-wI^g4;IM~hbWB5f}+0b`S z<-K)I?eMk+HTVk&%^jDT=y}|L9=vH+ygD9=gS`MZ!Q&iv!8bd;5YKgd73PNZ+_%jV zO-^M0>t8RL<9kTB9}hA;d;-_5@8xbbUW?Ce;N|Wx4Q$58xYpxs6W@+s;VL$}h(E+T z@e?M#8&BpUw%d)rN>cC_1?QTApK;H^Xc3>lH{$~K8!drS*KzZ5Zmm~M z{l++>DL+b^4tB?#xovB#iTA^=;F`wCODH%%fj$DO!ST2w_iF`5K71>ljc1wod|aNf zb?howiEBIFjGH^&g*!X`5%-VGuMXGq-ZLujYT)Y}7vVd(2&{qWzU^bIV5cHt#hiZ{ep;|tYco&VcYu=OncHWyByKR$SNIEOkNUxELN zZ!z(ycw`6eAvW8@-FR(BFL#oOFT?dab1|v$8vJ;dsJ*xGYTTL*Ce@?wDLCjPl$gYR zY7!LB$Mw5L4V;4;V!O@s#6=~#}se{Yp_l=$G_sc9ap-M z595wo;d^kNS;SrNM%>7F0R9fIF=p5nZ%McCre)30b@&y0md?K_m_@-~=X$w^Ooc^i z;5;vPvGJq$)*j&pAa!sJejKkf@mF#Gp3$NE13U)bW#V6AF54>Jh!5lDz1Sw~`M=~% ztWyf?p)n8Nir+NrunE470hr2}20P*zxS}zSSo42L;&~=sAD=QHIxe)sWAMAI11*u> zxarX7{la+Mncqf=-#{#&U?8?fvIp>s7kjzO%>{mr`KypcxAjfHq*noI58n=@KHR{@oV^g zTx6Eu$M^$mxAN~XZ{v!c^)KEJ;QLH|B1ysQYoqh?+4v`H4=nxgiizykrpH&|XReDH zoQ>Dw`%HW(?tX(8{G_T?xCS4?wnOjZKXA6mPku|m|0YEp_ydo;F{*INRGz5mxG^4s ze>QW_5nsoRpmqYo@C}Y{#5dxZCVw$Lf!l{pde2bMZgRBIZNt}KE_n`in?1PCEz#-s zTf7y2Z{mO8?{1Cu^D?(G7~!<2y?S`0<4$-9ULJIS^Z$hubmlnF#Po0iz7ZD~&%=*n z`~F}V{x7a);w$kf)1#BiM%)UYq=Ht#R@{7cbe#DVugAGs1v>x#NWu2oqYoA*aM?ML zOHAWkFs^JSSOMRNpEItB8{ZLqTh|m1!+)A}+#X*yFFJJh#4qB})DO=87g13E&Tz~Q z^>{RX2X`|QxDHpEADv!j<389Pi0;R8v0Z}C;H|j5slNr6T@d*r+!M2a!q5K)DCiRw z1dHq^+#gpp4g7;=W4lUpG4_kNx|zdD`18A>ceVLAajBh64dJPy||?e)a7u?A}m zCdk#z-myhoMwb}-@cd5ie!R&vFc}ZNFWQf1<0E*8i7&)G{b-wb2rt4l zP5e2$5!c{v(1ADk$0-jw$8uZ^+w(gcoYxpXW%B>T2b}zz>C6BwZQ?a?&a%i&a3yT( zcg8>AWF1psAO)vA6m4W<@M_GP*`R}yapyWIYrwvgQ=LLqfi3;C!6e7{#ws1F7h2c?Uj$ ztD5}BaCt6FwCi{iZi?%f_y_o&7o&~v0RAaSf!?EOj*n3Ao8yd`OaR*nRK(?9irg3{ z9G{IlV><(V@HkxEw0}9i4c9TAgp-du33Dje>Lfgdk72t}ZN@n-M-6<2J763C1NXsp zqpfxuA6}jO*7!wi-+&Cbjs36gtKrqFS^^_Un2T)#*W*9%Ak*U+`25$R1JM#Z8J}h1 zkKpyVf$;|XspD<o;Ansv&1#bLCy!CVxMkgY69bj-SCdnRv3)Y|pE^JxZvCdt$p4H^f(9yGq*Ne_`9<9{6e8+BA3> zK7j2UUyl=SMoaWIJQwGM`HbB`!NIqpPcDz*Blua z4tL@spL)4Jn*9Cv^F7f7kK&(jKNHWM!#1-w+KVdU`*8!}!TG-)1+P(H_v2>x9c$TQ@?XVI;w$a>ebDAn-IINQV<;ajohP~V21gO6dmoA<%Bzu;Rm`}v=@OWp_jIkcK} zcr`xrt7r+_jGN<0W&(5YoMjP2hcqHcYMz9->!w2vK#{a^%{uV9b1vulV zJvE8UX!Of3F@AD7guW=dE!0-4MY!B6C?&M_kd-Nu? zD&CIm+wcP1CnF=bg;`~7aPod0y=E6lA63BTXaa0x191*RYc(?!F2NnLGm1|(SK=|a zj_J@Wya1ny_4)o${5URWycNHKix1Uza{hmf0=v$BAz?4J>nv-&=Y5IoIzJ7c&Y)@b z9Z^l(822_EXpU!Kd;0B)U%~g8I3HTPktM>%#;Aj1=d=IKrQj-)Fq?#olF<^mA2-Im zOnei*8QX2-4ZIt_ZQ}pNs~Ng;mGPJOI!5Z$644tRp5gAz#kt01lM8rPOM#uky7&WZ z*I8Fwwsd%jv>LbwZ^va!16SbPc&YI%c*ZFiI_<_TrJjUUFd8B5e|Gn?=tY`2k* z@OmeH0KbB@QC7(0{Lf?Uy`8FH8Z3J^AC-7QnB8d3#2c|)#I5j99soAYbg(Zzg1;~x zhL7<8Fgrsx;A^-~XS#{sp?vdvui*1P4@e0Lf;nKfdl3I&6Ywfy8-Eu6McjG=&f-2C z>z8mTb6<|OnKz9`sROk49=^uJgY*9$QxGgt628E%aNWPH@GY)ouH#n&zZwS{Ddq_- z-X+9se&#~zJNc&>2k#NduY!Lg&MM;bKLrgaC~I!)QIA_1=X0b`yqy~0#vW!M*s6OP zPcd`UAGfL(#fKXYH}TQ<9w$E0xJmH&p9$PV!B!{Xc4Iq%yKvq5W&&9p*>F2+I=t4{ zF2Rj>fw{9mGw=pZG&H*{-ice`d)fYiIow0R2j<==ErEl^!4Hj8_yMmlw;?G0hw+7G z4o~7gh;w`i+AFhqWju(=2k44tdnko67Q;nclgWxyuXZFw;99 zGxx>u0l1>$VVEsEk2M_BzY^DQ;!|)Q%fGmR*%U0tT!bG~xD)d&XmNZ2-tYKsd=ir$ zP=i_b@{eTHfCgjJ_;@SX ziWDzHeBbnFf)#O%8PPgD19!unOnbHPEZoYtA>ND|g-&{f6dae zat(O}+lX1jjj+8>sXRxV4tQ#6@Yei8MX6rD=g%v>aew0ZoKgcPjl6!+z%dg>r{_X@6>^L@ED`-q{sXuUASesNrAMA~7#@v_;}zS*OCzPKk#zQ**i|E-ab) zZ?DAIQl%%}IR1t)-VJK4_n<_{%+hMO%Z+2lj=4TH;KIa+oUB$YNBc8s7JQVNb!nnj zPF9-sFm$M@lN8@RKNQYg&CQxTWETp`-raAD(Ia$xHR!~c2?_AK}SCKA9*N|lX~Xi z#2n_fMKHIY`+wh8qGalf#}o4?8yR-S@APG&w14yJL>INvBX!D}#EI;zR->AQ&0qUm zBFF!7ZQ`tO8ZaX#vrSundd-3_QvEh1{G9C8Ma_dw?(>s7^K<-HHz(Q$$pKSCUrXfX zWVLM>rIbjWw>@!Lw%=@G?y3H(?RNkHef1I})A34j%tFkwurg4^}4Q~d8X zC93ORB~wfGCiXI)ty_kxgh}1YLTT09nR3T(nfJ9{+j)l>IoU1Swhm_{mG@)fe%9OA zW=@qR-C4lPe@)EF$!g6kYvrqlWm8!v5;x^!HVe0hu+x42PLxOu|0i)9Tjxl#Hd9&J z@U%92mnisOb|zcQic1Q2gcZ&#ZG!%Y|Kw+Ba5Y1-07o=nx>+rX#%gQa zk!sSY;H5e&&ym4Qf0%mdf`a9xvRk(c*XM_+Mi&Jh>1$CIl zm|*TcN_AOSa26}~@?i0NlaGl(sU%B}3g+1ub(j zi^BO!b$_;?R(AHd3F9WI8;AX&&lePAwP|ib3ZxpoqB`>rd25 zZF@v3sCAogV^5v^N5L7n{?4w2W~rCEpfJb(cb7uutW_JWr5&jqT?=bxXN|f3GJi{- zf)h&y6c%MQA04d09jT!ig`+qoGz;5aP_nRnbWHd#^RSaVWgVTWKv1e@}0&6#Lc>#%FxXxg9~^2$IdJ4tUc@;zvJbFIjPCL z3g6DoYSU)4qMxLy_A9KLox1sAs$`B0*PG7~y+msArG?k$WVdO@p)R9q;lEQ`Miq`@ zrdtG!zA&!vXm*K7%^8;GOaISn3eU|f)6DNOp|DO)C%zrK(jPaWuvTfkw_Qa_(bN87 zLYb?Y`!7r=Y>+d)O@>#_KQN)NZi%Tgxo-Cozx1_*bxKV9qJ+2dcfW=HU2%7=x9|i1 zV*PvNqow%%%%91>b5?F^=vDJqUt3tW?3POTUfvVDx8SsYwZHe;!ZULAznt$~>YpH* b*}lJDb7EnG%pv{#bM<%175;>Yg_Zvgyl)=v delta 142255 zcmeFa33OD&)<0TRJ>;Y_HJRshXCj0E2{Xu$KxjIE5JnLh5+=hOCPk(MK}7`&9^{~+ zz}2g$z)c7kq9CZC=v7P*6|YmHTm~U{K%l#m9^S9c=?>uce{22M|J}FN_tyJxoj$d9 z?b@|#*REZ=h7%8evzM+rx0hBWc0NC^J<-l@PneeIx)KwiB#RhH7%~2XnA&NGaBCA0 z&aENBb-a6-iQxQc^YG}_LQqp!Yv3eDM8UH~*X*-4`YA z$HQ}<@a2qrMGU1K*@;@b25dg29Z>p;N-(J_5$54pg~!j%|DFUU^L&ghR}o<&XkNjy z7tc4fs7kD+`TE11DEYCIc$=<{p6O0GVmxR(LS$oe8;jR|%Nr^Oc*JMet8A}J%+^eZ z>WgZhrbIBlMNGWa#&_`4zNl$ohCREX5o`J2J-fwM^*^)rE^&3hL^iWU{4rn@Jzd*L zI7eBkOAI%3WCmC50E2$hh1lin4dS z`y)Q0>@$yeJn|A7;}Q2o^`nB=6xBBI3(uLRQHJVkB?j#+%VO>I^(_AeGn*__KI##3 zqhr~Ak2oYcnJxB+v!jy-O!I7M8XGTPD==(n8X8}XxAs*6e1r* z9^jjmdCW@6LgYsQn>56gc2H3tIIpyal(=#l=>sWoeq+~?f9MJ%67O0+EB-y#j<_z-y&2elTG5h71> zlbe;fBx_XzT9_N6kvqA?O$nXH>~a#5wz~X?_Ifb!+ON4e1x?+|ET~0vmZ3jpw(Mvs zG;D+xb~FvZo8g_0x5mJ8UufxQ^V;`$z4jY!uifPikzZ;NBNMIc!xnLJ;uz*>77rw5 zw$ExIsi?SA3$~$7Y9prE7oqyxhcA*umJi*MEHoeoPp+s-N~_SwR~EBdV0v537OkA;AxFQt$a%7Su98G>Er%LH zEEIIR9g#IOC%BPwH<}Z`z0Oxt9MUyPO@pSQsu*8Y+nsu)st8o|xl)y=U|4D>FazD3 zov|^%#(PcxizH!=m4*GXsu+~?Tf^8^KPNUz~l}iH1Z5z<>8>5qEya> z9PSK2oh&s7HLUdb1?DvbfNm(t__+^K${e{QuOTE+d?GnTSE41Rp5j}{Z4&d&}mt33rRCuV!nVV^brOJ#H?M5lW{y zp$$TgvB8+b8cfiW#%3^S$XRh^~~(M2#HdBZ%-3g!u@9 z9AZCH?}}Koj9Ly}J7&0k&Dg9t{Yz7rGTax|hhkJ5n@z4&865B}CD$qqu4^`f5%A;t zxe<|U-A{4#=#jDk(-hdGj%`A6_1qt5E$Q_HV@oHmXi@X|_~LogLfg?s21iNsCKtML zy%=XspyS1E<}|}$5Rd?3TBaALno}#tqX3V3E*cLqE0uE;U(pl&qQdEaffE&&_nVp@ zc^6DfUi(~+))F-Iwd;wDn5k^_aNJanz9_Mmb*jE7u#BX|TN)iZDFY@%-s?14j;w@x z=?c4t!vgWJRt6LdvS7qs`+)yj1{(Z7aKj=eifz|+hyM@4H@SiE|V)e6Pbo%yKmrG~S-a55d z0}=+37hB4qVPt-u{(76;-s5P`f}$6g{Z#D!aW= zL-b}2uXXX?MZhw&&eI%f(p6EDw#sWS^OZZ$!dqOblso4Yh6rX3KkVYa2oBhtmY~i^*91On%H04KlzVV>O5^N!6!D2kp;j&!7 z-4w|*SQ{LN7k%f5WX2k5;$tbByEc@}bZ{=;I`o!Y%MBPI=fN!D$@ScumJe=p1d`&? zMn?##!Y?Ha_|*}kSk&&bB92c{@M#LZEiq1QZ_1y@vRETA6_;ym9HLpIvADc=8O<^_ zcJSp=ld(M2#vuw?CeF(4PwT|DvitWBZ3xVYYut><;qj(m!)8nlk2i(jt-(9g5NzAr zq(v$a7#-dQy!Cho8C07%A$DrtKK;5!u$e7c2wNt2HMT4Zk+q6bBc@+3GIK#WAE4sO z_Br`w9jL%{)S-zz%k>mv$*Er;Q*z`gdzR}cN`dSb+gVItGS_*gDZm$D3@z8mo7|$U zeSF31hILIbn8N;scNE?`@s2j+*hZSjBn{g90t)@owB2C3X7W*P^HFY9C}V6Yh1g2* z0^0OT({nyJ%J2f(`b*QZJ~-M?ukeQE8dz3QMPm^dgo0q*T?|4DHP`Zit7t9s0@SJE zmbWtA(X`Bl7}5`}oO6j36P|1B=;(1mUm|K6cf%GL`+{a5+^AVQWG64G4wTaN~!PGIBi@&RNyOH!U2_RbbwjFBP~-f!hK;p}@NpxEtUj zEx$Cifi|sZJU7(e0EhTs-tZp)2m0WL0Dlcw$6)~lrUCI!v0bOOp=M9P)%c)T%yeOL zf=8U(DZb)4M=bg*Ob$d=LeMKsENJ9aV^FC4mbc()5@4eAN2vS@;6$Vo+K0;DBOMQ# z*WiiQ5w-kf_r2wxzNdVc{0I8iU%uW~eyw-C!7Pka8GI(v+!*uMcago~BYW7pp_OVc zsG=%D<)@J6XSc>jH`H4NI&JlltHICm8CebJOv`my+S9*WBCxq=!LGs&fQw`#5O%mdRnI7BhW%WCn5`2Z@e1*BCkA}tnuUlmBwJ5N) zMf9{573rY^BP?TE`8q6uxTEFsYxBp75zivaj}u}YK#VM(n>P=5jHzZzjMZbGiDsigZt~JWLGA%Zm+k$XK|Y0W0oC^7P^{_P zg;_g@7dqe8y6nGtMO&BMbW-ipU59FDy7*0xDG#Iv5>s#=md_2&WC@aoHd8cdNQ=(W zCN%)zc`w8kLGm^HdhGpyHKuBSJ=@Hco`uPInKH?DXfj~R!dmquH20YxIZJ%D=fCOl z+J(LT3}6M$+L;9_sn%_`d&LU_I)*EOJ7&G|gF4KMZu@s$F>_!?x~+EXz_xnGwW{bH z{I(nNFpaI{PshW{U3=@1h#<{*j|Yp73gIsViarWrEyG+&gkX!~us+4kKCh z=9StT#|LnHj@W6`*rJHLC_hCs!{^@)mpvnRO{99V!oku)vX(URGLt%9=YD0|2>ZETdF(hUiBFFm7(2r~FOhA_ z7g!aDvnpMJ&v5gV~t zOL>7bCmL0ZMoo!<1Of8sW{&;DVJji>$QDwSy24aOUKC`>$!8;%Q{_RxLoKfn_dbxq z{>0dNpdUjZ8ajS9eMNk1{EM_$jCjyY`-|Nkyf0#@tNe)S9@{D1u9vICwGZCcZhlKv zs`k2(mRXwZ`(0Zug^>WckJD7c-~x|msp-3m#LVSM5HCLXy`hJX!ik-e35k(su}?4( z>zOC3wU$UT-Q8?|)Fn1g_#iXc#Z8OPYIh7xFW+q8n<=W<>19WY`13TJETRLqL0{RHxdCiMuE(?jWX4?#xO$h~p+F^VcJjCkGC4 z>MWtQHr6ol$mAH-%~^YU^0(R!N1JsPO^2`s-sknr0Y&smzOiyv&l(QbG-Evi_{mw- zgZbDTFFL1vqjlP!_12!AK7i`DE6J~on|VK_i)tT!xErk)`yvq*;^}~g>yvZ2-*Kmg z!49>C{4%wM{tmSUOPQ|*-}0N6%e$*wdtW)?lPt|wPVbitetAK>t>j<=?E# zH0qvY*v}6jL9XQVptiIA8{wO;%0eD6x>{QL@REXCttx$bqA^|$fNC)@)K%5 zUicwpc@FW(#Xr*samJDkw5upC=|m@pA0u5MUSBc;n~V=E-2oqIUwS#X5nj2e-ZY0| zr6N}SBTm#k+NHpbJsjRKe>%yPV?=;yR1z}Vs+h`U1;^D?Np!P!59Yp&ujo~GtdYNW zYAssvu}9M=5np+<8~em5o_TZ~T`NAgEP;~RrOU2R`j}X{Ji^f3vG)Qw`p$)azb&p_ z-iMuXh=-RKvc;}iw&DiMD8%fiV%+M!G0~1I z7n$iYhKDKxlc!)wuNCL5PHS^VGA0jFu)9`s$xf_(EiP^kOc;;zZEnJRGGX#JZeDUt z#l0opSFi^wQc&`nim|kt*uJtG+vTjCTDhNAjCa%ha2=%d@ewyWm6NIiP9u4KX#S0Z zsV^q!VH#w=>G1>3Xkw7BI0~-DA=KZXgq8-myOW3h2D#dyaySP%BT@HfY|7k^@G0Ai z5Nb!$n)qLu))@41xSKCEOeF`L;VNYXLN*>I+#!7oq>q8r?c$^*AdUPlOn+%w2&M}` zxe%0>6v~~TjQ%f_YW1@~ISZ6uE0i`wLIk{jX_{fE(90Pus!Ry&6=Vqr6BJxY$xa{c zA>i65xSb_7A8s6Q0SfL8!%?jfTj)>zN`|-M_{wOYve+_}_-db*Y^B5BFRb-8(Oy;t-b^m zWkJR=C^eQ4xwk88$pL2~Qr%o-NTni`>)MS}GE(hbmypUtD$|v<^nlZZl-X6b)MUd} z8iJ%kx7SOQf42UFWEYZSU5=B=-i0JTtpG7A{^i$W752dZQu+QsQu*q~UAlDXk1h1~ z@!WU784q^NEtgu#-LTW|}{~e{ky^)&K!heS-@O?;)ZQ;KI6u1zn`&;;LZv`HN)Swpr z+gX7vNcC;uzu7GU+L7Cnd$?@IBW0baKwl$5I`&E) z-cI=Wm5CgDsyfolcH8Z;Tim|hRdLSAx03r>UG^WH%D#NTeMo-`Y#U22q#B(gZrX|& zcF{CdI3B2C*imC|hgPK^?h@0z;8ssA9t@gm~br^x=)Y>XenF-u$j@-XcrUSdp zG2*7F0;~y$nZh6u=#4;E=Bq3?mM9fQBd1cS(9bv=m`5F4(b$5ucW>suY0VrqAl0#% z|0XDK3{siR{5PUGpqltprye$lTb~(V`a$X7SCr!ul1uZ~WB%ugO2odS-To1FIiE?c zc&VB9^J;ep)-EI5JiW|aVj_@_Rxvb|q|U;5jK_XdVK&>%*El6ErM^O%&v%WkyS9--W7tz2d;7b=$Nvj$=}bai8)_1Fpz2v*t#SSugf z=+KaSYd+qL^s^GYDd}T9wrrz=5bVGh)?f+T(^|QFqa%QHx8~!mCta-sZyo7uJqCI$ z=qTuzp`*2O#YRUE$+70+Z6MiJf_EUvvL0JrvC$!bkbzKR=wnOsRc-cFo#LxH>7J^! zhB#lQ?OfSj)Lfxdt@rKh&b`Q$kE6FC#uC0WJ^f+> zP8517>gNhhbZ9LpsoElsy#-4{bjlG<)dH1sI^KQFi>O&(dil?0tk^1OBLxk?xeH&; zyX z?m0^+>{)tle-`}sF40-lmp(4`*qjomb*i}e;*`w`>4UY6o8z=GYg>%U&ibDhUqBxq z1c(=K!njPNTcbM6^X2`7JWXrfR3G*3TX2lEu4%Y|ugGvsLHufKm*|Pj#u|+R`xl&&}eXSe4yoppVezmgm1CiFMDU(bXdS^v4b_HrAtv+uMZuS z7`%3SM{Mb& zBetX!WmF*X9VRxd{7g$CSPQdta{K0Zr1-I)FgvzLC!cdh1GXY3xjDj@W1Ssd6r6|M zVrLjI>yc+{4)*1(pKU~`Pn_Pc9XX<9!GZf{OtvXIzEo(a8%jtd~OTkUr`~1 zx#j3l#9`~~9z~IWn;cyfSeV_VNC5nAM<)edKQ9*o{_JS4Kqu#P0Q4Ppq8@f+7iC!; z_O71nAz4M4NNsWHaHMZ8S|2%ACvSD8sKw`|78${Am^gITw2E+dPN4~-_NaF){L5T^ zG)qbg)0bntzYLc$(2Vns5t9tR!_Dy_Fs=9MWQ}72I(Y&Pf(JB@E1KR*C>alUJmB8V zqX1h=#sMA&xO4Mxz$Z(_03HK4yLkwwFC7JVlvP(Kr#4%7fzo0iia`+HJOJ?e(&2!I z0}gNQ$KjG;fQJD#H1`I4vXqBrrxzmllIMsE{}xeE>Y$cf>-3&$X7H;E96uhI9FCdp z$BY1`Eikl|#sW+lFdu>@SSi)lkplk0R6pF!k-+P3g*!N609yffGiy*wh9iQ@QvpOD z1(5`np}g8@eoQ1V23`p;CWR&l7#$a6nigjXI(Z!y%{uvpvm7I>0e!Fmf$A$eiBOIA ziCsjP4zpVI77@+>u78~f4!rmNod}7*hXB7mw}J|nk;n&P>>EVT$`M|EtD(B(`mJu( z{Q2Y-UDy?!7w6E*POO6`!w!dFm9LZUcXlW``LM>;u_y=mTYXl=Pt4n4tM*YZ$-3Ua zN8c82TG9G>I=LV0NwL~_Cgk7pCKp+O?NZ@LRM6IW2|)kujrG}D9H6n@too=SF-68+ z6ys)$r;U<#a&CB$DNid~kQ+KA47nQQ4)Pe3Twz`itW+!aK(2m>fLw;$?jF@zr+Iex ztknezwN(;RMKyl3@{1l!j!LUj(VCEEt-Kbk?Tgl)!KpAGCrL#gI@S}d{E8<*t!Pd> zMAUj?>tlN*6z~pDY<)yg81O5>>nl%a(aAYl`G_}IrI`~5nk8PLX#HfM z_j~mUdi@-}%RS4h${Ol9c2QVEOnhvu#JdoW7Ml?oGdkyXfZXJKU0FC0OvS6Pk+=(2 zYkHaVa$l!b&hY3g-OmNcKZuk5p2wK0w(9TQSw)@eQ-1!2Ny){)3vU~Es^RuIm@NqJZ<+&(1hgi} z6W~*j9<4d!^AnG`eyD)zxBD7&3~!J9d2d@Vzs>hoU|ns%d>xp-<4s21d*0ld(4oA8 z!@zu`H^62n3V}WYJwj0+rjtP~UD3(eTKNLD(70WloXt?(EADSEa)o^jSDOpxBj7oP zv{qi>su*#zROw=^T!waaw(e-^Y$%xD8P37teh7l>_wZI8^t3Np|8R#P9gEsq3Ci45g~1`RnDzK zxD*74V*kVJRL$g6%iok1bN9RC32ghKwN-0z(FExwPv3FDd*%eAzn`$JGg(}Gk^SCV z!&!`1G`#&r_G=zy>r3v?M zCRm+zt;aSM=~5li9&vF^#%Pi?r!i|;ZjC0ZZ-X{#e1k4)N@GV`XGC+wHT?9C2bf!$ zBJmz;z_mIIzAd* z-+MBZ^TclutmZ0LB8)hD*W+k2BL3Jls??H;TUP5(8)_Cu?oX=7aQXw)=Pr_?8!ukP z5cVH9;uhrqHH5#`%!4kzdQ{;H3e4Ar<+!wT+rAoOjiiQRqr-0BgDqU#r5ir{R8H>j zV|{vRWG^C1ezevHkN@7x8OO;*+FQBeeYLAtj#GTEb|QUHj5*Lr7vUl14kE3K5=#yU zItD01Jo;`_h}lY)@spP8ZY;r-{MQc*Nc*6LpXBG3pK+W?&3B|4u?g!qj3$&H>4H6i zu6VkMfd{8#?15KOtA5-Zf>E~<7n>+9ZxZ=s+$mav%Ya1QDsDWOk|Ezki3@7-YK1Zw zsmBz`K%|z4jR({2q2xR#wDKI=%CngB4Cg#~pdD%%aWkNt%3&?ykav^m2yxcC?RD>a zsQG@SLHphfrn|-W-z}g|iSBnZbW4!a9*vI?`_-k=v0`c61LguxfGs~wrzqnahc=bS zJw3!^xp=3!-`90Zh*qeycTt6a>JmIuFzHWtgi52xxrCS{%WQ`!$0&RL99kzgg;io`;%(_-gzGVTb;jQ)cOL(!vTud|3 zLp%k8)u4C2!F8#VFx?Y)2cz*3>EAev;RPjnpUB3}-#7#`&gmwZxt3qRkvCBMq<$Iw zr`Z3!n1r`67Sz>Ch@}#{2}E8B!{G0Q;==bb5_Vv9r5wbB#=W0FOT=#Pw?%r=`zdsZxa$2Fq+fXdKKwSm-!_nX zsg=h`SZ5xNqG@8x;f$ERUIQ+Dnv+bpC)ERoul!`wYuAaR4?jnbh`$}qpl^$TM>23= z*$Kbv#IZ-((sFUtk+xwIJ!Od}_UmnYKzr?D#o8ljbfEa%k+iV9dvdbHzz@1b^g%bP zlm^9@dhLbc$PeD6`$gvmDM4Sk{WZTLrXBqT@;Z;E;S{Z>Lo^*5K(C9_j^)v_;tR(L z=x^e8$CBt)@z$}Ya7l92hZ$`KU@8l=<=@z6DwxEtd-V`&KkO0ms4LADAXiY1i4yG} zt^(7gAN6ndNsCZpw}0%c#GO}%eU2wT6~j_VRi;uiLuw}M4>#?^pFX+_v-|YpPR!^P z9Up&7FNj|qe;LdAIVV!!X`ek&05QHi(JpR%b6Mr|#OaBA26?=BcWZj381~7EsLReM z+d9XqQ`OcRye zPm>aIaeC{uzw6Af#TNxGD=Aw)AgRIp7{{fFYd%dVC~>M#8y_dVQdV@TJf3qJeEJ{e zREH$4RXa2pd}L%e>Ez1>ip2>;%6uGs3^9ae7M~zM}%$J`uzGnHI+HK2FLo?dX+I?$3!`6&vwo^& zi(16wpJnE3t~LI0o3T|+QTTN=y&^vK>%(+__{Xm!nav>%_^ls1=BR!Aw`@wYYxkc2 znBvTR;f29QY9a0D4}zt9uyp{x6)YaQFq~ek4Y){Yqz$2?@!<0~GA~RWTSRwXx7*yc ziI?}IgU4yl0xaX*2k;G-(|!Q(Ry_0ZgaY?D zKAL#XMX)^peC^Ptp)9DQn-=YI;Jc(FS>mogCPmzKMmFwf>aLunj>I{tMs5<@$Qcz{ zr(c)++91C@<+V3E@NEXa}JOuy~RRo&S818Y7KFK;{Y!LoPrvX+cTLr`)<8Q zIya)*{TBs&dUq65D7L{nkuw<8d>rhOs{29wX@HVoO;HNI<&EzAUe#6LBe-a>5)WQ{J% z66nC>h^SHiQ0#lXi}@>eYz>p&!~PqyF}WIV6K+#uZva<^jR$c$BW}Ll-u#wZtv(zy zD_U^-E-SEsW$7EKji%%44SB8j)Abm-QM`4%KWk|byWdD|JIPlh7DYNKMZ!=dxG@k# znEb7aW@#FjoGPxk(Sddm-@1`N9~MvC=t5r}dnhVL ziqHO;Ko5&={+X2Wch{ww&>CG$B=n*YvTYdbRU~b;r5!GJQ~3??w?Dh#o^{;KG&)P{ zdoyn6Ft@5NuFY{SwK--i{7F7fYqSZFGZ9;Fa}YSU0S_jB<)B%ijbuC7wtFDwtx3(b zkQbT!vAFAIOj3JSEbkFQszOlmHg;&#lKhj9x5RI5c5170*=qP<7u`+pwM{zw?O{%-*>>V0kJ z9^kDPHTE>xAhxx)@4pVQP|y1AH4#=?7MK){*!zMf-nKF>42!D5lEVW6P6sPFh|0@| z{DCLfCMYofNQ=ntiks~TG2CTm5n{p#w5b>m4+V*QT>RKROZT{k$aP|#_2qc@Z#(f>M?ytyGe4FRETqg-6SRwe>P6(vULu!!_$lyo@V26^ ziTpvj1W!5A$MB4qw`e3Eb;g6yHX?WQ1Y3`l9WOH_5xLsUWzA2<-bV>m97qKqMP!SI zhpwF_VdlNI9dCct+$2(2Y2OX7A^3IYB+bT@osdG!pWc#l!ag#Hdopy=) zoIPWjVU|R;yW_EXe2`#JG;;V4(e13GvEsqz9tcO9n%mMQF{&kvt#ygLTjmG8>C#@0 zB}9HrtZ6A2y3{p2v1iV$ulbs2fs3!9<|@ClT##9wsr*jE5g?acYZdUz7mr+%=R5RnU9+@92&Hpsa= zXFcB$@a1+^avdlaW{HP>{JLBxj&`?0EvwuW*bs2LXRz(w7xHPMSm~KgSBU@im=m6N z@|%L={t-|u`?`#?!M7grInnHmLfGHK+cxQT3za8(igCzPS=irs( zQQ`{kP`W|<)Z3qCzYst(BFdVhY%pU>wlehi*OL2Q=ubbZFgI^;4k|X`&zLCiNUBsrbl_d|_PdZ%vksS3RXvM8|xl=Q4PNQrg%9>{R%UV&^h_aD5 zZ6*AU1}|sB@l$KrLX>TTy%lx&J3=qxBw2n(+DNHW|AkAC1Bg^CP?NNWQ7h9i={BQX z*>4UhM?*6!GMy!@_vKHPJMGB|Y-N1aeI9VM0_Q3)0UWBpRSKL9Sg*j#6gU*H$HDoP zC~zX++X{SEfy)73Q{ZC?Jhj|8)Q-;yGlFfUW%T-PcH+tjjrLa0h4jkDgqX1(;+U7H z=^+0AmbbPpj7`?aVI*dm%R8yiE8dQR#>ctTy<%18m zA*R^6CM|u6hW**B=OZ*x3zMMoS!u1F_GQnyrH}OVC0Zy=3ZR4OA?fb{w6AWzm&%#a z#Q^%LZWxlsq*{Tl)lG1C?VY9j0_jL}!^S{5hrTH}18INyl+?>W^WvUyCxbP2FhY%L z>@3)<8Q6haE7cM4{$|YMLyaHPB$z&Lv$i(9gs9m@^)H1~IJ(hiiY>7rUg7 zg6OzN4qdk&a`Su8vziUne0FghvZ-DYmdUie@B+ZJ2zwLj5}0PSM^brPm+q`STLrLGY& z4fNU{1HU+YvpTd{Di5H^X)~I2Z(*8~KXl6VoL#bKXASRX-HZIwF}{4$Ni9a25^@WE z_;L4>7dg=%QrkB430fiTZ9}`!Bhqhe=!uZg&Nt`SYxpt}SHh)(;j}~N5+^n3xln6V zp~hndy?yaet5DV!2qoZ4J*U@xwZ)4up$gU0sS35lp$c{0#f3^&gzAdu$zwk&jg6ow zF()y-jCE~Mg!%~S5s=tpKPEjJK_6mMozlKGG>QIW8)2c=gc>4>n=&4{+( zE=(mf!)qTSwM5d4xIAnwkE@x8j?BRxTyRb1G%Y4yuYI)CD~hHBoNwl=bEPR!^kBe~ z&3r+3T1tqfed!A6!DzaQ9+$q0re9Isecfa&bx9$p*2ymy&4b zP?nWfcd9)dz*u>nw7MfrWre=?_&jL>hl_o1zVeQi4t2!P?vp2lc0y)Jo`llTTRQ>Q z)rT9CCw1;buf=c6qsm>fo?1eVQzG2#Oa-J(XWy23=hCTx*&nA_KZ+j}94Eb=OY_YM z^H}?UzUhG-=R_<$oFE+0#($}ecWNVg9Z3)hg!m`4Qky)Qc;CjX1mP)d{6KAd4W}rG zFz7q8?EIY(8Fi6@`QR{NL49KUt>B2L0|~UC@r#YHJX zCW5UzNIJz!CO%CB*kV47(8X>bLO*E@lI)9_Qgi`LW|d2&?s#|q0$DF9Tq-uvf`~fCZq2l}Zi%HkNFVo++U5x~xS+cwO4OgvRI&gS4YGl2>*U$y_y=i@#}+ zqt@$MDH#UPAYMn|mj@ zvNcI3s*LBVj4$EOX!zvV&`P7*ekZx-PV$UWAJ=32`VmAJu4sQXdY2$zR4rrEL(=1g zG*g#5nFvFq4+lZ}FO4L^04Z-MjgWpUq=Ihe^F(-8Djh*%Lr}=%E9j__LI=@Q-NemA z=q+`4h^DZeW2A9|XePTfNm@M!J$iN&5jIF|mLTiLkA|@*)S?q7higmgtv`=cD;s&c40fHlP z0r>_W%m>kVz;}1**;7OqgM65}QqF`lryFxhdd~vy@x_nQ&lVcrZQ{Swfy9jqciqVA zr|*UP{h-$4H{{G8iBKlx-4DIx52o7qxhRjtQ)@l`A$9Cu(&WK3I{XmmaW7oy3f`{c z4bqc?p}yE3qUmO*WT*PlT(AEGt?IbEWgbpP(HjTZ&t}LFsc#iLga0Ju?}`RaruWzbW>nuZB67 zQz>}?jUL+-Xg!MZTDVmCfK^uqCv_LT zbT<=Fens#ij-L0z+W?!u!f)q0hk~Ut45Wr3RNJlRFd}3kpI6CEZ3FVTKlj5jyvZWK zeno8oJWg6Tghqsyfi>?NKWp0%spC+%gg7#-!K{<-e6IC%rBV3 zBF!E~lRFgttm?u)({N$9V23eGO-TDaQ$FC8Qqu!8L24LAg(z%9DEWTDe}qTtCzVct zv79N#A32a}M$(w@uHeoGzrVBkjF39s4*?0NyDM$WxOA6Bc-wvi%Am}Dwr=VmB1~31kup@?xQ};3k(DOsQ~MENIh8u{fx8muY^AOW6VPaz z(viHbFTmh#xa2Re=`XOY@Lu|pf64#+FYxhu;U46ZdlBT=U*L~?uwU!j`@^|1>DmJ{ zK7?zU3w;VSCS~f2*UluuNud3m*VRX|@?~lA2-@9z=_Oo%Qu3F#`WZiK(;On~lSV#7 z({y7%wneHLgV8OIfSWosS85(Xv-Rm^%CJ@ZSAH?(o}3q9MCvS1j^s);IR?p4wTG_0 zD7{*Y{++6z)?oh9JLaQTsPyU}I6;{+*)ofh*NjJP#*u)_G5Nl&PUXiI5@Dv&RZ)AE zsjB8?!0plcDiKnpa~AG_MpA9YtB>B>72AEVUrXHq&s3Zj+xe)pZzPSs|I*@ni|q4N z!A+hkHun)V-_PQA&~F9auU)@II(G2Mxski%${kY2QE0Cgs6`4&w*`WhNlnPrbp}H% zZ>j3aXCo*2P7}f_0rMHh&v)2P=@gi;MLVV6Iny5(!8fRik_S<(WExGiQ3j}po2*|i z!GO2kVHzd)^8MXhvXASnU@XRM6WYN$ux}HJI*v?ctqp9+gH)Ne_U!Y_AkPmS(fvk4gQ;(#&~%U?@D4=JN8Hqc=ir ze4f+lmd60*o`dIeli38Aw}tm7hbI8$BgEgIe!4?C+B%tW5r!ElyeAh}SM1`xg9l$* z$3c0s!*IMN<&C2;(y_@HD8?|U<2W>NGNZz3RROC#L`YT(zuQcJRU)^YD9z3rrMJh? zZ1Z%GaJlae9sJ$3A)E>>CAyPB9-u*NL$ef*!Ozx5NZlWR%abE1qL4doc%?v-`kB<|xTf<<)}u}=SLKn)xGRW5f)zdwLL=VY`LJ|60x9xe65JL(dl%2ehb z4qaQgIVc`J-9UxiYL`xom-dZEm#$2r!p~~Es~kj_&!^LbsQh56Om8MMm#elokP0W2 ziAi@8l8#a=MR(?RB2-Fkpzu~FSB!$&6uCm4&|HeEBNO-~9DKRM>up zwjg2|8yd0tj*0Y%S53rk;#R;$WvYt0N~scu__K^))zxRzNcK^a=M#BP=S`}~!o_hkMVE+VmO2!TUde;fy6q^1 zp5cz(H3`zt;<4+VRRtvu^_oXgIPkew0Yf-@3|V>YHU0 z!-CQmaGkfZxO4-4MOrfr>nx;lRTCQaCqeh~uuT_QmKe!4iE3H?ZRx@!Sm&Wz%0h=X zJZB6Q+8S>|5Tz+A*J++m7cBnqa143-kvAY>i4-=1MoA?Y>biW$;j3gal8A3Ov+X>q z{H7A3`@MoL7?oAt@e(>2jasSpNfolP6npC|z#I9!8E=>gus_J;@Z6v8#K|0f-7QU? zf^cRJI%ujozx;^4>C7jH1YOSnZZ1lIesT&O(^-qGK4^sB$7N|%KjH7@A3=Y2H!lg1 zhL_OjjNOo8n6DhSP#55yfc@t1V<^R5fTDIS2Jmd9Evf4|VtL>zwO&KWyMRXl_IH}l zN%~g_wrszUbft7~-yCG|CRMg4!UZ_y0TIjB>7UR&seMYb9(^$&Vp*H@Ot2V$*RN*- zg8Y@Q?9AtMzJO+q&eEn*8a-hP+GPT(yL>51p}3xHh**izKB=xks$*SnFO z(+v2ovVEyd-5#gT2lj#%Ge&6_hl08qJRy^D>O;E{UpV^JSJYkxoYt z?Mq&|gWaxR%@b%WogsCcPUFpoOm`+lKFNInm^aX`v+dHX=`_JS1gO@&PrtX;^N4D@ zE48xpLDC1)>42zQgaUjS<5$&6?BsM*1*=9fTTPZ>X78xFtFDjnfv0R0Y*(;KBbET$ zQT3LWAQx{cmy638iM^j>b#Yk?GssccY@JDw_nI_$CU)75?*aw7;_h9x?K`DS$m@3q zH~D`BC!Xh@5BB_>2;2UG3&zF%sXmI6ezzNH) zNWYiS38`l;s*Z^F4Igh>2*ABUiH|P#x-@PUovOQfl`nNlr&6=@^DM0NhBZl^S#+Gv zwUr2m6tn7R!-0D>Kr4#!_HdIQFJhX&yC6bcT>DKR_2;^mX4BJ@o|NXzr3r(+$WRCD z-Jww--0n)4$`~I%F7~yy{>_?It&4SzUy0sST{t}~otuk|H?8EHi@oTsl6f9YU@o)N zZyu(nOx%d$ep4E5lfccGuNHJCY_oOFOBUTG*t1Eg}qxx^7&fs{uL*Xy8yxbc~GHg zt>$-j8+Hd&abHI=OHE!yQk9$;Uz9ds6D8^ZB;xMfZ+GR7bI(}6fF>m6u!zS7M681A z(?1P0w(83Qk}P$w4gR|n(8=sr`G~Bn$$J4JBu6W)NOAg=Jz~k^?AMEc42jEnR z`y?$=k*aGr4=>SAT@YFCYjqesk6^{4667nT6fdz(NpczJ2B}~njmda2>&`|n@9P18 z3-4-6HQ-paEoYJJd{@Bx1>j(HTl(fiY2QLj{>hVhtx8|a9my9SYsw+3l2YQ2e@)_x z8zp}`lDTSBvJ$0yyWU^iAz1lPYYS#8Nrgi{Fbh>XYlA--ne(xK@qK5Tj_dF9V{mtO zHRj|eynB@;)6L^j$Hj=##(k*tia(6e{S74OrB*oCpYK~j=N#w5j~l2??^+~i|2=L6}lO))GVY(kB^m)CuS+NpGH zF-_L5L<xYjapKm5|9B270;4HOkr$a|p z>G~3yK&|SO^duC)}t$*u1LNQpnDrl ziB%0d7s-BV)1j)KDl!qQCaB3`jDc~|htr@M=*y!b_d%5t6oY1O9FgWf3hw17y-&6A zSHIv%|5`ww{5cUS8Q)P!)@7q$cXa`C)G^oDa-YwWjCqNcs_yzTKSV z3Rbb@Owh)ww){J=@v8RH>-ZLt65N;$!VxQi18nXJN*8&62*=er&mw76 z>%55)#cET=yvvWg?pX3RzzFzTE!(E#^R;6}A(DLWkoT<;F`zQuRs7-b5WwluhgPUR z2gzhr(CYX2M9KXMJASCH-*Rf816HQo*%zr@~of}*tS$@!byX0r-^eWV|^A{<3HJ#0d{VF}P8jHW}ze)R6 z!`9FX=1rSKwbgFLkd#{ur$^fxpk5msVHM=fkaLszg70mf-Dp+bpG4 z((d6Ge0aZn)>LVBCFEY6sxC+U_}DDzZybLhOI^k1`}iEolKxeR+i=qJT3!3Kbd*MaGb@~=|53O0Nt#Oos(XYJ#~(!6w?Wfi z+P9vztuw8s64h7r4=3a0x+721Pjvd-525&VY0{ILS(2fJW!EKE(buVddTBU0*;4n( zW?H1tlUV>Q2{Y0a8Z9*01x|d#|I;!s~g_D&%>dalVeQ4de z9rSsWd^Mb$?;-8opvjl!zYYm(uW<=%e-9^xJ?mEeolCIoqj2tccQv!wb+zx%Jv3m< zNigb7rGg)5dfhX7>6c7j@>m41U6CeL({}?Rou)s#CyMO3S@*^Fv?~qh^I!yVT%yu*HoB$m=K5$&L8Va0@;F~fJD^4 z4E1|PuwiwU-!$)0>BnfcS3iAxBsnA3Jr~1tI(<(_bjDWqQX=~&)$akY{nxrV$!sB| zOQdtfnx`WRflEI}iB_wfId?(n5|aH5lcuM#q5+2}OEV_Vneo_^fh3#*Z4_XT3WO_w zMFk=hV6X~ADu5M$^hYY|P~m0Wk{3;zvgEPy86^BG@FB_57v*&);kUIcjV2E(B;hX; zmX<(@2i{*eW#E!UbH{*m$`TSjSVO}#3U=Ot=?Z49hNfv1%@3sXvtQVNcxbU}Rf4y`mkjdftB)OT9FzE3ijg4ajF zUr>a-TPhM>A^k8$(;@0DopD4be9fRI$%~hiE?K&mgulw9xOA2?d)zW&Onnexc3Nce zxX1kI*yM4K`qPQY$H8P%pM@cl)FUApIz@D#?< za#j7Hal;vXo@yel>ZN02HEHa#0O?#hOV$<_4IC;`C=HA` zC}@*Q=RZ7mhQC7mL8q!fll1vWP1nrNG%QVD*Z)+>BmIBoSW* zN|Q!udTSzX2TC=gG?|mL|1`uWPb-@;cgivn{ybVsROm4k(sF2#KTl90UtX{R&4A8$ zIn?&(ltq5qL3%DX9m{A<3Z^P)a|Wx@uZNLdI#<^=leJ?3i2$bCs5J5i8d>*`1Wh8X zd#WA#Hw(DbFOa-`+&_Hsy0A|Y^(7c=+Yi^dM=*&6d=VQ+%8!w{mlN6NRG*8i^7rfJ zjJazxT#XJSRqtUjdG~18bWCF%sEmOB9}I_yux>sa`1}9qa7Y@fQHR6ZlkW@%HLVT@ zHGR);P*MN!;ZQVA;~NgVVRsJ)wZi{T4F@YG4cA9?Z71^K&;XM)y+`gD4pZ16ra%8| zI5}jJ22EvO>kkx1kizqI$rSmHrwR=V`KqKNm9#IjZTe$5I0#xJVIlE?g!RXZQp0w(DWDL$n`gI@ zy2ehLE4sSk*VuB6{)@s0vf*c`;SH8c!|Ujq>=_#N%d31&Cdo>d8*kOUw3~I(=xu`{ zNZBuSU%kUZC`f(_uVWQheZ&QlF(1|CA7Pt=0xB_UOZp-nbPpze<^YjGV<7qzyG&lufdH>S&9Tr`Y%h7ryG4sk@3j$ zFGbX}8hfefdtxsY^&gMD4xaWeMR>#Rj=j_heX&>fQ|$k2DN^zO?otG+u_(TzCB}F~ zmC?zIuypYOd`nHjS1&II9FGhnXZPI`hkbp9eZ=(D*a28_qVDDIn3w7cvFP~m{koms zv*nCceks{@usHr6F;5fE-*e_^5>1s~@-EXTt1x0zA#L)E`O^@9V8vKj_uP-{QGGyV zR3Nb)B2wcUtP?x^z0~hFHj=(4RsF^?H19PMsbP&KmA%&}?R=9(0)PEC7Ny|Lk82_T zC!J@p3S9iSCI)cvdG=`7jx%?Ag@e+!=h@%b($iAEw^&cj($hrxa;+vwNi?n1#L=bF zAOB_voS@+?7O&t7)@fpu#6%=OFzEvOie3In>UfcT7qA7vD*ks~bq(*ZV9I6gxKuL` zbx*zwE)ccypjFWWoE+5bD3o-5+6OTF>|ueeJn>ov^k+^uO#}P&{){b zAL`(*=2CtG+FZ@zq(`o@3vrNMad_hfjUG6qTWy}+(Q54m3hnUD4yReqUN+FmL8xnm5Xb+=_k;fWW7ld~y&v#O((K2(?EU{BB_87tbezfn>=dd9rc^0EbsW>`z- zPoK+oJdC}hQ%?4!{`JKXWbTzZ>}&OB`svwG#BrnUf{T5n)$gf9Xn$3DpK4x?`{XzH zfw89I;(>)z1{L#dl)@P^iShRNx&=(LOQVTwL!_azS!!K3y~Yv5*4wr(^1W@(!ZlLpNu$plk3aB$nFqxp@o&z(|ZyyjEQu%bI-XQYN^Ni;>Xk*yygRi$VWHQ#%Q^p6yc zDf$(bnml~zw3!PQO_^3!x_I#{48=eq6*OqlGO&fQWQuP)M%kWWX=YOF+bKFlXaaVM z?<{d1iIgL7Ksxp>6V6Wj??V0)dtdF-H2>}QzCJLii+%q7-RMdZb!da8yU+nXS-96!`75XL|X8v!w_q94z-TV47L$f(R zjv{2wg#U}XcY&(9+WtqskM-Sbwy0Y`L`6hI1<^#MG$q3q`9LK_MKlosWhcUxhoYHa zS(&M6nbQmv&3t7_Wx}t_w9L#*tvqFArXDLRQz}o#(=olDxxV`gdt?7`$GER?@7-f8 zSaYtq=A7%j)?ANo-F&W#j``dvbQrz=S$(pbe%VlaSHFFyK3DfEZG(wlmN^{gp9ZUR z??1H^?acr>c()$K|4%H`+v{%zsI+mb78D8(ifKsr$jsTUadR`=nT44%6(`6d9?^p( zS=)mmk$J zBp~3|@3>=y=acOi?GTc-S+2 zYYr7E(p{ysk|RYZRF!FLFj6$8fFnG%At6uyqP36-If7vu37UleGT{6#THB@^ziy}i zb<-UmeRAUUnRZM@JYG*hdqUe_FIb;tYkuQk6znD&>?QYbH6i_UA? z!c@#GEFAG=yKPYphKW2GVh^8|J=FpN!V603LY(0#UQlrOP%kJne2^Curtj34-Ribl zu#W%KqOJBml@8aRwH3$WFddGYCgZbwp{6FqxjDs|igSM`4Fxv9gT-8Fe`xi?$$D4J zco50{P<7P^{j%zp3m~;zT43*~+k)U@a{CrF=!XB_vljQeZ4bh);U0wF-|s>A-L?ne z*I*CA&)kFf|Dw^=?|**};{OjuS8SHzCv;l>I_|&k9jBMtYEWO@Pgci|*RN}~guAgr zyo`-c->VclNnh483=8o1)fi(gs{2HEiCb~@i!~cd-GrqwiaUryT6k7wzT!L^MyDs~ z(NFtbo`^1ShiC0fQ}xlp7S<_PIdG-=>NGt- z2iXmmzSl1d>+L-UF$7>>pqFOowdzn>ou_xhS6%7b?id9&4ypbnPp{F{zSaBh)PK@w zMUnobZ84TEXI`mpTdX&(o0RK6jZsN-?N3^Jdii~Q4ZSl*uhP=)r&*=?tZOs0XW3ffZM=*uY?O@F6`x^B+-t>mmJny=NL$ zQ=6;3i>=S}2E|q}#k<(PN~2@1=;NuNT;J_igLU1icYN1k8d5FCUi_D1FK3G!d*S(; zu@_`=>}4`J_5vZtUi`<{+lf{@qK|Tp8g6Q3+HG=%)73{XwdWMe@fRtU<1hZp@s|VS z_{$zS{vt$t4HFoxs zG~4xqI2dqu_4dX30L|7rBv8rzntolPkI?=qp~R>3LM@_*_B^HkZaXw1ND25^?%3;n z=BV`QVl|3zZeXI;X%5X=rgyinW9a%a{S{lp>p@D*FV!zE*Gv6Tr=!;BXKa_-!=QAf z+V;HOQ?=EO3s$DoR^Pi;e*sUn?Fd#*|5|;YRl(VZ`!CorFJR3geO;>u@9^GTeE=w@^)^dbF%#V+7Il1 zU_MS%;CWP1U(yFrTxP7Dx{emEM)=Z&G9M>2BAunwaxX8qWm zY+x>#UEsnS-+^xf|FL8_NB%Y0o1#obOyLvh%1e4>o4Bs^QP(3X>sRc|mztH*%Ukp< zID9&KtKK<;Bde;VyGilr3VLR%zE0bT)BM}?V?C?-qx({|i~$7&d0_VJGpwcSSygG~ zyoddPTL4R+vlc79W(cFW?Rr()C>*NMUsj!RuHO_yrE559%JclU9nr1r`l|44$zJ2O z{*oH_tfKmX>9d@32k6xu`m$a}MtafU)H%ArLQjJ9J*v5n9uA(F70kIBO7O3WW^L13 zQN|%r5PKR6wN%ReT3;5*km>KKDhoWd;d@#D* z%D;2BvHz2on2*f;z&8Ll+QQhu_$z<$^y{~{s}S*uKDTEIrq}UV-u*+rw;S{im3zJW zhqJq6{{Y(y%_`Ti5w}ZUY6Ren-5UCQmmZFD@&DSTpR(B^huRR)pHUygFRZTK4*_!4|~OW$tz@}v)sqd7nOkZFE7O5JPp6}B@lHs4rC zQ1fv0vj5SqineKBd#TKeZL`2Nh&JsQXW{!F(F^Zq#YoMCkq z1rw~ZD41ZKMZpB?ED9!AXHj6#v?$zvP~Tun#*iHPIQ?-@-%7Oyb)ipM4Exv1T3dSW zUHuo2p{WCX@tz+3f9t^3yn5aH7|H)%FsMCxRKKeC!li0u-xF4MVl|(@^(ffRFlIJ$ zPWuN}fj1QWs4D$xBUJp&W|gb`SU2e5>(Pzq*m2!uvty>SXesUfL~jo3jBFV06Z&jh zDDc;pN;8di{};5Yt={f$tuzb2kXD-Dzq8U%_DOx6u^F6B(ymYR5DNQ5UuN3_`0~>% zaf|H;{LW`+;-~tHeiz}t@r=)4+m~j2hN_Q|^8dmSw>4#-(kK2uKjQZLLO*1?-Ur9@ zR+0U*zSbuCqTN47+fM7dw2&{W)4s&btFpgJWcQ2curvPEU*-Id+87NDm$`CM9ER|Iw)#gGY~68VMz(4uL~Y&naq<9<;D}={Zc}3{_Rz z>y)@%52e~~bU_Es>m{~w@V&T}`d-jm*);S)AD^L#7xXo@i@=}SKsW<5g3rkf)@-MM z$=yIJzk{LT-{K8?1VB+W({8 zm`>bh6xk{;4L!A=s(#jkgE?BHbG*t~!Aw~Qo&H%rY&(Y?iOV0-=F56IEJUk+(f5Z% zR5eqgKC?QC$iR0I$()p2F{;1%MUPZ%p)CTH)HBuERXy0ST?D=OlESX(+rk`0%)Ig` zs1%ro*~kt*hzvXl4y_C6+%^3>Tj-u<%AT*PKl+z`DA0B>E>KxF6Qs#a+5eG~{~nJghf`FKi~#-o` zn#Muyx1b4_51QUHIP_8otqT-2w#C3q$)kxu;;b$2M4(bSuln9#(HVy~5pZcP6*L!H zY^%-%D&-GXw+<1j18sW-;LzzKR2?lwBl(UPv9HBxpe`<9wqM@IDmg+mo^a8tThIpY zZ7RCai4S8OL){SDP6A%dsM{d%=GTkTRnR%xe zs4H0QY$cp@2cqd+;tu|Q?_DB9M>kAoHmYB9)H{0#>Rbihi@(7ET-8?Onx3DN9UCL>2oGZRFC!$qkgb^!Sl6tf-S^o-si2S8;ow^ed}#q@nD%`| zRI&x1@#S?F66|tMEt!TrujXLb9&m#s{na2zPL)PIWJFM6@6H`5?ps?^s_G+L4i?5& zG%9qOm>{AauweAZ-g$;esE@!ZhVydrrx&9gam!hEy9V5?d1vYpl}?VcwJ;MJ44Is` z-h#H?BRco9V2lplayuf^UDFEO*!${)bOr%zkWK|CmAc(6_6PB8kdbgl1WIbVrhaDN z>8>U*9s8;>ldRxD%+u1nHMph&F}c1%aE7XQLlhaPOrp#_qQ=2jP9ku@f%>vr`*-XT)HL^C_rRIigK~;c$=b1uu};Q~Dk=8DjcdiYq4^eyuJjl0`STT+ zGjKO(YJU+a#apPFhT^~aJMoGCXT&@BM$Rg@oi=)FfM{37$+vLV8_I75qrq*t`F}L| z$ffa7To4Kji3&L5C#Y?{;cQru`2rD_@FYJ98YH3;EEpet^sZ0~05+&WX+U|`(-}H7 zog?m{xB+6JgRdy@Z6;x-zJoDL-P~Pbp2sl00orP&{Qxu>}D70Xi(XK&8 zmT_;e3w>TTCSU!oXzHuFv#!4zlT(c8wwXkWu7)+KS8M>T7`qB{W?@7B3Q7%71GP>! zQ0peEh32S8lTQ!9NVAizhu54Uj;L<9m8AHYA4!*!vgCWJ;h=vanZIUf`pKtU?+(Yt-E`Vr| z$g_yzo%g@eo?+r#*e~IlV(9$!9=DaJit{o|WrkiuRl`LK`*lfCtJ8_$qIpaHO3VZd zH0UD+yZdLOiOW)@sQ z;ZFtV)kq^KdW3j4i0}3BrQ52;$k>&d`Z7#6zrNoosH-XmDl53$m)E9-yzUt(4m$X{ zAYUZx-GuC;MEDR^#=;%&Wf1Pix?wa^oY$ZmzQZItRC8dt(2#rnC~?4_?RKkm-&1j=92;WWW%}?sLpEdfJ<&lx%Z3qBUyC|SL4e)#O|Z|bsz3u zHQ)|5YDx%w@|7)wuHG-U`g37%rk^h zh(nIqxZ8OYuA&)zGDfrWUENxqAZTq#b*@T$vX{xP6GK%QRL zQvS&hsu7Q2OnZ_NQ^h+DzE^68tVx07KUTC3wcr$HB@32`r}QjdAvzPY-(p#*fV{Gl99wKU}c(Rvz}X0!*Dz|88CwaJI~B0ydv1;?8VlsdtCG&1yUx)Nco513*W zDDcC(#bd-?2j30nEDUZ<8z+mF9WD3(3#ylUlR-HQb9FvP=O&AHhJ~StayPKAHS%bY zrk=E!d30Y+@fh=NpJI`OVF>VIm(E}vyM)GcezMr_=z=WZ%l^e-^y(DRs-p#$`bOUC z6L}5&Iz{Xs#&_WPwtsLN=<=ARKI>=dGBB?&DF^oq3v*DPJT#|#`2{xdR_2=I=g%EB z4*@lFV5(@@$pYh;wmw_(eWIo`S)C=`>BE=w`3>eo>}2&js;L|GR%6EZPZ=;FbucCp zynAI)Eam8Cy*Q6--9`V&68CH87gKV!c-z6XoO?cZTMEh%9m_2EnABllLH;yzR{wT8 zO>r~@Cpo5j>eyuv)i<)h576HvW72MRwHpvaO?9N1&`S)B3*d!<$?#=Hq&X+Ji@}Wb z)mCQXv~Ep~_#cNI<;{iKC4wHBCc=g>D+?FRN|+6cb($Vh`<@E~4(`vC=}#m;B@yRt<*heHk*PniA#d$s{z^hIci@ z5PExta6991V-e%p4C>i_Y21NA->Xy_w2F z3`TC0=ZXJG`Tj7T%YuuF0`p~>`fWY)F(pOrocwGLcZ+b4FZc8Y-0AszaUhd3zy_|{ znCp7(w(2thJ(oKt$6{+ymin^Y#300j&S`_jPd60vW`TGom){WKR7Z7y7>poG>%|~v zqX8he!YZWGr2_TXNib1=4_#qK%Xq%!Jt=- z#7hEPndCf(n{7Ve1~oJiD9>EwJy77W0xx^h5Qgez40i%TU-8D>wm@o|E4DaTDQ;)> zPIRl#qnU-n3j^Nu_;Hvby*0~a*h{lvfE#Fb2^_pM>jjE>OW1#XG;4w|XtpU|R6B~% zv-9d9Dw;BiMcZf#-fT+bNgOw<;|#j;vvWKPySHddu{h!2afV}5MpIddXd7d}mwjW0 zU>n^#wjN9$l!)VwE~tC_yiQmQZI~^>M{!wMINo~qYS~*Ph|0pdQd~HTfw--`6sz@V zP7S7jIhe5Vb2vQS9f?8h+pVdWb+eLVJRAsfbrBCAuIZlUV-X+nm9AmN>9aDu_;=D< zc~?qv;)ZMHM&ue%hliHd5=8Cq%IHeXYf|=L%VUrumN(ADzl!jZf$URpa^ylY* zcoKGz`pgq;dN6wnHQ$&0Gk?bomSJ^{5zg~4v(p{Uvk#ubPKiaXE!NcEHEW)mS;+QS zmSE9T`AYb-fdpFmkT@8`s}NS{A~QrW9K{m2nIk4>pvlV$=CjIPnK1yfY?nKW%Smzi z{SLba5DjX6vk=-lUwl;d2L@w)oM~|vNO(cvxOywdii|(Mx1)@W+1uHE$AxhvjrFje5n92*) z1>y;RegtY9+!-n>6R|BVFq)~0T=TGSs+vOE&&bp~_XUbFA{^v`m!+YyDXnfu;~Zd9>QL{8+QwQx1Q zJbHvSmBBBFWfI2~Tk3;DE0`Z)Khc;fD2E@_jM?{!Z z!NR3T33bUhdYcM6eN|Y_V13@X0p6y98bM1R6`LG9_;H6bKaP4Y67Bl2W)|*}WLqb< zBbGl{-FvTI>_GXj{^oHJ4b}%1iB0}pc*X*EiDo<|B2z7J5VJ8GI~U4&27LC^o4PL+8y&1U56``O(3!=e zwd8E!ihVi1b{pqa{|n9!JSjGo@eGx#@#Y?AC0Kmy_VoLh;f=zCX>f|C7qjS2`bryy zrJQd%x_B`185-F)H1S|&@-_-D4{GZbGI$FtLRNUB_2ngE!${6Ro}UHxghs10bxFNO zSS8kVs}@-;W0am`b*wjF#5*?1IvANOwMJt=RgXq&{9z`|`~KDn8Bb@!T% zJ*Fu88*l@?n$lTKD=C^UgsOS9)iec+tVn z^6{5cHpf%ma?zos1&4*PVs+KJUl=V|DJmTNpkFea{Z2}GT12+A;7PvZ3&QBubK(UD zKLyAy1LoaHaVtdUZWdhOOa2vuUX#6jfbqLdDmoy4X0ROYBz0OTy2M!EbzdHLVM*=H zBeV_8Un$lH@f(HwkYW5?SaN@(s{h63&MM<$TC`HFkW`LYpVZlH%%t)=hj=~2zUD3x z&x*)U3tr_*zL)wvD=LEcfkb9#?*%bGtLj0BSz(I_>7ZI6r+nl60Wi&)o>TNHu_=hv zyaczDd3>d+uY<=yTTF0-YJ~)2vF@enT>$Z`HS>wfB@eEac0VUN#aLjfZ=7cs^vdhv za9LDA9CImLYHtYtT~${@_?6?G+Qh0>NR=<6D-9T(3|DZe&uC6f7Kp|E{I(>2tfz)v zAki_x0{O89uLRrykbj=;^4cV9xgi6>?xylJqGh-RCvz;+Mf2XI;^dC@@wU|Ns4ci3 zAAZ2fKV-QUfS5zzCKS(f7v@Y?oby1Yt(>BS?9he*zv6GgXyskdIQ)6B){oEO8hSas z^SoH^;MX$w18zIzmfoMcGUl0#D_~phrK?TzCkT`G;=+PFPLJXYhOQQ!9kvOV zJc-7s9Ket{OW{22#vqKKa+94?7}k!ytPoY*S;7*yT9$G~RkxT@%)PIAAr{$`cJ$^t zvAf$+MA-~CBmvRTsMeU#c;;Cj$s#IlM{CxL{q4I#5!8j1_!O^uY*9{OYALc{T23L7 z;=J1oqq!SI8^1Sjw8qd^(Yg&{tz!{(HMYQ&-b4K>vAy3rN>eP{Do&Qw+|i+b>YdDf zAlw6l*AUV>indpxBJ$4ERJe2Z(ES@lr$Nlq!qqn5c}JvI)-g{f5I#I%F-wV1sj57%! zh32pC4H<|c|4mgdtM);oyWd4|`$Y3ZEAS*IQa*y{yaqKQVOn$XA>5k)1OTu8n!81O zUKEy9*c|Bm?;?n*c8ZcReuIr(sd20@7{s`>{$ zfqee}ZXBBBny+==Hwt?AtB zVo6{kT9Z3V?q4@Sp&I&Pn!iU>2J)Nim*Dmdg%aPXs;e25f7Ypa2i5s8$gI$SXrBV& zAT?$zIXEg#||-W?F6u)>?Nd&d)l~kiDYnUVbBf zHr&!-=)k{J)p54_MrDlX9oIcBqX>re3~3NnEviJYFeertKoTuU;8?g2WV-W}pNx z<4~OYz|qi4&AtfpHcubnM{RfLZU?`+U)UI5NmwP zdnry98hY(h^weA8>1O>%sI0E^7LL-teq?d11k%;aJ!HbK&fM% z(E{}UsDY~$Ra4sHLDE_UA4I{`Fx+QpOAFr?p>{Wq|F{T1E8h}Nj^Ym)@E1r!G4<^C z8Ez9u4aR4>iU-Zi9O%aKA6@7KT&hoE*qaj#s*G>|`(a2U?bOi>?N*q=Ke z6V%b{jIF@<2At3^$1*2c7=S*c@}QVKhQGZq4(=H9!Hl%2RL-jT^h}%3$vN z?TgdnkWD|SYNDN=>NSVJER-KJuxL_QPMy>(4DlHEE5t6oU2F-9<#A})Wd3-@X}G-c z5b}enJ|uTY`C?$C!xZ@yCSpAV$?H?b7aSv`AZTLvEZEJxkJ~|Wv;-6O@Ps04tegH0FGV=IQ zOAA598R*q|S4h9Ji%_U#X?|^gnIB3SZQEaFPXP{2a zMu7Mi;MD+*px(tn=desjgQ29Gls0JC&=GR}F(@aC&m$@p*&t@1=m}6nGN(u{eaG6?GyKG?b6L4qf*BUHl_y#o%`%E~7@_lJTpYjw>QkYd?De9_; zTwI4NMx*;g5>_#8!t}a!fMdBBB)~Y{Gc);2EW}<|k5eLkdKD`>b*3w>cW=e{MrTcF z(*3qdbqO@;1PtlVLyKsznt+!!+24iz^Gtsn`*B(fZ=J`zn ztLVXhi1?r`5aA=Ue|LKIAEHVVF3S2`M0ZGSNU-E~rRGr8=i)jqy3>EY5KVD=-~Y6z(2^gdt*6BuczS5$8RU5FY4M!8nI8XA#A#i6P|cU(74-&9 z`$}|E@d;$6sQOAgr=`xI`@RM)kLG+WcBwn5;~CKj848Nsn#iMDXGC1Po#=^O)8`fz z;1nma^>cvrZ56rq9;JLE)@gZpboCq2zV|gI_b!K|on3TT|oc6AUbrLFNr;Tj{ESb0_2ry zX1$I^{Zru6XKuRsPtmT+W$(zt?(|lo3qz(79I?rrlyFgO9sU~>GVq=qw~^x9LL@08 zGcO0bN6uF@Ze|f&kzFu7;!sZDG9d7Ap$NBGG-!Epp7odHfzM-qC!W0{@+@{P;6e)( zW#~KVLvcv32bBvI3J8dm@MLX(X91pT6sybl+h*HVW6gv(d=z(tEoJB+e(s-VO?dK2 ze*BCHHgh7}+6t8rAN`R(q4H!b!Cw{cM!@hVDw> z54Bx~3oSNI~C5PmmEy(-$&^P0imfZIcubAeaC8>$*> z=ZxU&M@C!>Q5B0|g%3Lo+b>uV^2u<1k?W!iG~Z7~0 z8e5cGkcYbYs&WNd)F%^ae+>lA?8=T8;RfDH!+~8aEO4nXGb@*C^akZfFNI!x7+WeB z=bh9oFgAdWUluNZ{!HI6q<0@hUly@LEimft`joLA#~3!#!63gF;H~C-z&<*;sNyoV z8RLG%CN(}j8a9Xe|024US@1QEFY`Pcn+7h7EE|*?*mdD~9e=xGyK>fo5Vl=804P0k zY7vLMqP%QD2zy0Y%@Dq6@rtsLeTD4HlQ^_2Wa2BzctHGf@<`aGKJip`1)l`1p~Y83 z*Jg>V$h5pnjAh($jO$B>uZZ@+PVN{`9I#PAM*~mvDfk@Q9??S9snOyRzNiHkUCK*r z`AP~eBHq>v*48v(sfcLN6|)q+mj&E<_ zcjafyWXk~~Zg3zYGCdR*8NtO|M{=wVW6|sZrm>eb5ihLx{U$b-u{vzs*$0)Z+{Ova z<~G)hU#Q`%wull~6lN6IP5gIVb3p0Jl-gTPlP3NP2}qbvH~uBMlquLM@o4-3Xm-G|?8?l_%7euZ;8F(7dCfNf z^BJ6(IUQyE1Hcr34U+e0A}6mfC(Gr|$S){FeP65e23dL$KC81<36Wm(h-;ObFr=p! zm7zCWtDKR3bcAb_H`zNYBfEh6&9%w~sAqzba7i5~iA(ChcqX30U@i)Gt+IyMGi69>9mt_&N{>1ibKA9w(*t%lsjm!>k*CV2pL+mFxL*SCW=MqxkRkI- zvRN|4X&ykP<}ME)(-O=;85EOA`K`Z4%ULq;qzCkb?qYCOoXK*j2aqg_J%Efg$pc7^ zeI(F*mL!Yx0Fq4c03a({t6V~nrO)c&k?R2@hg}lrX)3sy0W(u(NUzM?G14oO-Iu-G zbk-{ErB@O(l3q#hI~UJ%NpMzrLC|Ea@}cxgiaqq|b<7nb7EsE6MCYUWU1K!(^Dkkz*bq+aB#nB}RM$0XpXeS0L}sc_E# zz;83JkAn!;-j=JlS$6{#jnmkoN__%mt4CC*}o$Zx{lf?RZ@FDZYpYFX?%i^scR+-Xe_s$o1g!YE3dza6_sa21c$KPt0E zx%UK2?Y7j+q8S-5TB;V&Dwc`KDehTd@Wk^}+lM{Z#dsm<$G$wo9azGq2N-WTj`K7g zT`=^|B+lBzyf=aA?9v*+8-dO5VK|OqKKztu(8ac4-wGrz%O=!@tZ&G^zW2-B(TAF&(xBpuL=kWdT0$eI)vU}eGIbg&JlE4oqP z;16#9wha@oCA3NyU8Y!Y)Nr4C+pXLU#Dt=`Ma4NYp*U`>$Y;I`9fuwwe9|*&7+;oh zq?xJXx4_h~cZ6Kfm~-tmiZG0@#sZN-&ReLVhOzzbT&R5bC+ti-g~b;RH2kDCHXnpC z7fp&4p3I8XE3kGr#oCO{!5sW9qNn5WDNf%LAS3lFtOgd?jORLLKq*5%w~%wOAV1HQ zpM&S7ury~-tJ8OmCF6el-AhTFg0*9CwP*SgSBYyp51Z$=R=8HC6UuzGpFKgtT}$pn#k0fP3oB? z8Rj&2d^%%m>ab`UFyOyY!Pr9!XhIVsT-zB(bDJ1z{0~973!7lQrdCajc3mtm+gHCA zmAMTwrsqhS-qff{GP{SwQgjbq{ldk$GEb~0+G59WJ&T$rk+NXTt|5YT#0XPPss{7( z@-Osa`pIcDEz2Iu5%T761U%nXXf`(I=aNruH`VSzdp+%DhApiRt9u~M45{)8;T;qc zd&&!odh5Z4Uav>X_Fxi+#nFmpMvERMlo(g12KUk?GP@qhyCx=baU6Zw%vdo%c@fq@ zRM1kYubj^*_a0YOPvtbXBrLL}zJ>6DvMbqaj4MJ7JOCGD%yQuMOnVyKsWmh($mrJf zn2h4N<}7blbRK~!&PFtRax{Sb(k@s$K~t{Kh9G0D7X3W+4K_N)4dFn((#kiaWz;QJ zROiriY#RDResBb>3^vwimCsXbbE8v-LmXO!ck-~3m62}(F#(JEqTGy}!ptJ{%kx^& zoaV+3M+$b_=EIe)rPvUoWtjzsjr3^hOqi%COBkxtbq+&WoXu?B&IaVQMr9Nq22a|c z{RBlPfp;F9+NoKA22S^bx*!0ae(>ZphsXR?;-8M*xNp4Cj6R;@XUE56jS@!}5Ey!H zS4?$w--k+x%$^$e&WeWL)H zhwleJpea{56n2q3xrq~aQ#k{~sGBe=2L9S!Q~Cu?!BGQiz&1*$Y?8*8CbOthv(r!*JDC(nJ0I&{9n;w zcc@mtsRj%k_ur=2zf{Tt8^jV;|PsVSXocOPfFrM^tplV@K zMJpnV7qrw$>e|le*6k2;liOa`5F9=lkXhd=r)Wwe2J7qlpSZg4R6C=U-*+Z|J_iuW z8DOUat2*20%?QIac2YQs9A>-uNclo0&pExTxhoTm+(VgQN11utR-xiS$<{w6?Ki|UfKbu{mdwyW3Dad8k1p@P+- zjnpQ}i0y8{r+ry98Pkx}e?frX8G5yyu_XBnc0K=uySx#J{aRK10zC;unQ>yQ@Gjuv zrQtY$UTI{?fp|5&gYjb1DM)~!ubHhxuoyv^EpWcZ*~utqH6#L$@W370#O6ECcdvOb z9GCk#8ZCx$STW1V!ZU7RQ*q#nf$WlEn7rm@u`TymWeHGTy{>uAa0uQ3D9PjQUG~DG zso8F{<0c)^;3~lLHMoQq>B&w;ScnB5@RoCd-s*%-)*Wp;;W!53iyUDysWC>U-WIH+ zLYE>pX3+jwnlh3hvzq-IU|$C7tJxn)bSh1WFjx3e|HqRjIVx*CvIrZeHAkki?C+W%M%Zsx;XqwAfGh%OemhvVl; zt(p2KfU;iIrQ?fKc@`#=oOc*SjtVzSzHn(T(U-AC$F3G^AM3-WA3$F=vA~#ZN%Fb$ zAnN7}*lAy)gI$cMSPP!y%jcQf_>_$$XIJBCM>dpL4HvP6ws$omV=cJKm%;b9G5BmO zEr>CeIjW$+1-M09XxSY`#2pqa#`&bA4?y3PbOOe6@P?BzD)j}-mf$XJL79Dlqg#QV z@@tO~P=kY#DF?|c5 z@O^;$&_p3{zE-o1_V+O2+6@7|UeF^9)mQHym4flqv?r?fr18|br?JJ6myGg)>%E=6 z>S;vuwBSmPcwfrUQ5h+9N&^-0qskPk;CM;O`z`NL*LY(?<0(0u3!!G`VRjw0@y1+j z=XRQLrx7vw8Z(^fnHr8vyDdG4U!Wz{6EhmH`KzJ+VK`uW z{Z3<6bTEtq@o*=1VoR+lI zCWk4Lx3KDs3W^6GP0A2sE3oE?_Oby(2U8tmo{!2#w$uR;)R z*?q0qQ&`gmvMjRsUb5cwkyY_`vX-kj`98dtv3yJ|j`)x3g{21MSUW&lG%ul;{#}8f)Px)cN>vTrcMQSGbjHuftK_!$a(s;dRd$B-UoH> zYecpl!dyJrb=HUD0h8k+eU0GIR}i9vY}EEONByF>#5lH!$t3@Pv^Uu`V_V6XS7VSLN_y8t9qaY@aZb>Ph>A_t?f~7BiTQO zA2vZXMazo;PB6~gIL`1~Vd1Zjo|#C`^fTTn3xiyiu*gd`KG^sOZf^|B=$}6w1?su2 z=1IL3VLtQqsDnF%mO5S7>rtl(`%NBo>eTwG*hcF3hL?_+EK_l^jz_3nf7Fb>?llgT z?R!fKmzBsWJaOb=buZP-cH)McDyl<)C<+`hEk=5OsArXQSI} z?($HKshmY-p9~c|xwV%4IIfmaT#(_F357s6=!@ckQq!|wF_wK>2EcSPMjM%L_b~!J zCu*#O!vNzKLHGAE7CTnq0Qw$7wI}YSwgZihSr%LaDl4OgWx($_^LXOls?vpFPbD(9 zc%D-PaJOaIT1^evpfSr`5WzXNUio!$^|paVf3??jbc7+upwn-od;dUHPpCH3Ej(j_ z7KW{3D>#>h$un&qqm-6pP{d%YPv;}@1-OL$^v+$Kn-^i-1Z zLRmR10MqVJ>?wy)9(crOx_zK&jcQPmO~om1)NaO02zr%mknaG@X3v1B8r4z8U_w~~$4T3{B1jWAl>)gcR; zO`mGBbWQ0D@;-3tEkjIQ3Is0gC`ngjSQ_xT9QL$LM;PUeFpfITG*Ru2rjT)r5=R>0 z_gHXm=J~XYcMc@AaOw?R%VM4r5T+!(i0?^iih{UyIQ4O%Dg2Uk1f?vF=|LwZcec~V zBMg`0h7Gq`{J`QE<&HAK23RnTu_;MQr38WCU^sP`uGMS3UAvD{1biHay{790Q-D~Q zMQ0O4y9Q#WZG)I=a3?=TWySfE7j)a~l!C(I!TH5Gg#!z*&4C%IqFQ9DSo(4)eFtK_ z38${}q;I=S-wqjg76Df{aH}petv1Ct8dQvnI{T3$`;MbF{h+HmHGG%yYIJZn)tRH= z!F?+je7yP`4pLK&pwIb3I|7n@O~^UgXrblhQp{*0s%(C)rhJ1a6H2m1WR|92Its1l zjx#T_79vnv=~j}S(Yc(LApTl7^$pD{$9BoEJ-{F0u)W@4M`hR_z}vViPiUMRPyP6w z!<5}bnxJgKw>(ku6B za;f`RM>n zsa`p@Rfcr|K7qr&mtpk4IO7{_j#iy8-e{(3*`HRAN;77tWxbIV$Ke7_)tkZ(EBAha zS4K3mvLzMf;Bulxmun_V2|T9kf;ZjGn?XxmFiT6QG})Dp9BKZbro6y0xAf2 z5Dw1?=u;m9Lbl+O2(#mnH3Tg6qyFi}$Br{l7@r%kyZ=F<6OHx}7JQ7QmX6Ovz0Wo+ zjlE*g?`G4)iAH!&mWGZz&5a6%``QI1MFa8*xL{Q}GhL7nx#2D}htn`9iDu=Bt8`oIlXw!c7G9n#c~H7=_mIhlAP zp5M8)!UJ-!gXJzwaupU8a~685bpHStYqI+1$&W5@RL(+*eZaUHwD~Vsmv3Sbb{gzo z$5KjbOgAq_w;rNcAzi>26;Sd^Ef|`Q%juYga8mh&&UAO_P}H_eY5!+rhD2JWl$=8= zCL14hzl;*YA~OUh`$|!ZnZuV7g%m_gaF-6o!+?^fq0eVbDOEkGhgNUSFea;=^UlH` z05{|t9Q^%3P0iO73$+5$rp^RHO%XW{=TnzV<6TDt`kFYno!`*)O!WB{yg7$rry8wn z>)o1iK8J=+MUiZS|9B3~1U_je{BMEbgjDP&7iOdm9Dq-R6!KQzzGg~<{+H&w6pgxc zOSLG>_82%zMbZM52=wT9`;s>18hCXR@F!lyB5NuEV2rJ1#nHEo382^{9F=oGp$+i2^L=P{)=@uo5>{sq%2 z+`h9Ekz=%PWx<13!pvD2ymGj>825Ci(E~X~xOz9u&oMrA)c%fYcMZo8zooQkMr^(X zFKQ6&ri6>8XYli*XsGAvVD!I=vlPm{%P5~a!JC2c>Y9c@yqZ#~rsdvWlEW_#+)cku zGtN5#p!QO@gmZLey3uW<1&2-dReiODEgeoOrFF2>f$bgXjPlVTftt<0a${z$(FkdV zyiQb^YrN@jBhd~B4LeWSE~9&*1@Ez#dahiso#T#NRs@3UpYn1tigzz@0vu`oZ94tK zWwdR3_c2aT{+7M#o?*yiG~uH@%#4V+=9eG@^;G^Z|LRDE7kf3*b^6b<6j9azk9 z9$N%U8!*_FOC$1--v|CcTl+W4{h!o(rqQmS1s`L2KC9~y__zyjfxFmMknh3dGR7x+ zhq;Jm8p&NcBP6XDbu2OliJs_4FP4*Ph5`_jUWmi7iu12%^su@7sOmcoC$va}TXd05 z=Nl1q@Mafj1;#Z8S7xS(_-?h^h-_tnhrrES$?sj&32sAE9n9-ZxHI3;kXhL3vS9Hb z>ug?5;70HOa%ceKyiyuP>ReQk?X!$u9I4lFG6k;kd#Wrn+J#&2l)vHg$bfNx z0J&KKm+}K$Dl$5>vEa(TiSw>0t6#BkraPAc(_Z=kMTw_Wmx(3?MX6F(Y>Eu!7f)GT zi|pKkG`z(4*1@7!t-MPVKijyo%z~8}oUD?344;)HNu0)|#@j(hK)?aPKOrNq2YX9%&?kdqnmf&B z1g&6u9%*xpi;kV>wYaC+{1esAHNxxQ=sXIYXGG}3@-W99AtF{EkBOnm-}TvX!Jtlt zOZyoDu&}Ar{0oYP=M?7W3x)YGRs9DEeTO^J^f-P8l*e#Cgy zF$hzz$#8kUQ|zNgyLJ}52kcyKpZV-t%0Gal-HTv4U-T&E&5JNM+6H&&cN(+Eh^mKY z(n1hvH)qn?MaI_-m>TR~!4+Slvd55a3l7VtU5^=|arya>g{fpw@%YT5!86^(Sasji zSW!}dPcP*Zj4Z&~dn!=(05yS{Ey3PZ)5ndyjtb139Jeq&{fkaKZnUd|mzu1bAC;`@ zSm5}DvNNALJz>P!&LL{;O-g&hc-!Fw3!G1~r~E-}7ehk}zLZZR7aP-N+*N?g{Y47{ z*@Ga%tgC(-VW9EoOnOZ=Nm!LMz#zm|p#*gts5E~DV z*pGq3yZPmS+?0v8TZ>Z0sWdvZ#`w~54w)(SK1bf zhCiW9m5xbj069;z4yMYbhTl*tbPpJ~WNBgGZ6Oq8q?-`~3ueyD%+DS=2v@t1Q*jbG zN{(Ead7hOa7fYaoZkKd3&2U;sw%#wM=6VZZ^1;u#L1K0Bc@g^hVORVhS{(UE7a{6cSh_5&|1}Vz& zSu|^<(Lr<1;*1M7ik*t`05w~UTspDRc+hqTDx3L@`tIN1-1Wz3A#1qcE@q7X46U$Svf{&$_z1Lu0ysSWJ*7Ulw_SFL7#1 z(Fj`BPK!>%$%7>j!lh+s>>)^B^TD}G= z3n#)t;P&YB;PY6aS#Vwvt$W`1%yAB;WDTpQ2to7K8nLY`xSaKo#bQ>|O+|QD(D=`t zq7kwNZktf$Ymra3vPpBs2v<>2PWA*>4({=(7SRDP!EYO_e9_qE-(0n)g}`)X(E17^ zDtw;@K4qqy+t(;Q_RJ6X_bH}x6-I~_R!r9`(1HH}+HoQD&FeJ3(u>qV7~nc7K3Nw@HuzC zigO&4+*C}%2`wkaia ztI}xI>;fVseXMbXPX*8HM$~yD66%D15S-JWu52_Sk}NoZx%p_xGUnYbgL8Ni&`Db* z?^fW2^T4T_FiXJ!ExU$k1)iL4^`g&Gjm87=h3IFw@J0X=@|m_25h4QU zoh?RI`%~~=gi~)d)w8&d>;oEDg3Ue!T*Crr@KzLKG%QC$;7$dQV;iQ97CdD(#cwkX zI0j*+Rt}d2tIsy0a|a79W|@n$Bm^yh!+b+pLmq9aD9_F2Z{h4NOM#e6aMv26&0&V{ zN(-~inIk-JA@XNJREumIbKIysf*9Y!rI)Zt(=yPSYlLr@q_Um_lN_urJr$L!z)?=6 zlJqv0wx6;TY$^iiksZdH{ZIXbRnN~@5H>|YEY{VZ9F3)U1qFeUMk%Y#E2O4GFrE8QfjudnfS*YC5g;I2Y5G}dd1&suzFpFl>@(m!>)RVoseOhf#2g#VmI1e zA_^v%T@W4JZM3R`yOh$E-Nr5lub^+j)dbO&DkG+y1>-RJ-;G&YN~yLAN7omZ$~1}+ zkkPlVqa&VLN{O!;RgU@S`O+~*bO+O)uVQet;6tSp`I^!HjxdC!!KIg`U}HZgTeeG> zEx1X42X0EzX<0l=z-Mh6TKO7U&LlMJVvM?Yr)AvhSWH>)^-_A|bz`h858>|CG6TDH zor^sEO)CXz3Zigpkw@=Wqq(#~7z8{mb7=`E*0!RkJ;uJwD3tv%xI-;a{xH=nsV{%n z?-kVwPXq&NDuTMlVRDK#8+h+_nFTm$jZDWDu-)sR{%;s>4U5P6h}TJBEg|L+Jj@y1 z1k-Sn5w~f@B3Q+8yxRF*=C@Gt%SZeL|D~k8=(I0kl@N%|HM$i!s*R5AEcjFdb$$fQ zzhl&YwXxMd8)NJdxGHM4&*(rMYj6PE!rkyl#w@gcKjY{;Rwrwuw2vKCb~0E}B)jcF zIqqT{S3HN@T`sA7R*9b~1(LRI_s8s9CP~WDfoPvF>hsKw_SYCTZRk8YTx0Z&D28(H z!XZng5XE_>nWEfNa!C11?R(I2`*1b ze}yn@WvY_2NKT?JAr05z)RV%iiC4-nJEDcQpzd#BLKg>rVhbAa7FxqRj3EiwDmWEJ zf&0*+>fm}!>eKx$O!!_!w|PD-+-EfJ^0-7dNO&$I8zy}0eA-oGghcn3F?chjZuGf> zQ5YVln})|fk+fFxSHEpEZ+{J{q+{=#txbNQN;)r_+#YCt2u{6d( zqYoK(bhF@n4S9ag2zQp0Vz#&g%4ZML?nBtgs13%}E~ckz+Ed~CMvpEQEEY6S>|I8< zXM1X7;C^NE0y_D=5ve`CfUdo7OiD=um%VTp`$ym~T;}wgB3@s+^6>z~trnQ*fI-No z`c#nYWU{Q$rPBW9yc=oigFqDORavMCf}PE&@~{z-9u0qQIJLZq*R*=C@WZ-t0Py2D z?3pH7{jzfkSjlB)5%Wy?OfDaHfouxf&gcAj&NvAs-)xubyK1~*(97KDQ4X5x#TdQq10-7L;AvCyb~>J+Dy#d| zzp(zDs_N$o(du6c9m_`Jx41S2#^9}3>HHbfYpp8qBUqs%ism zVo@6tRz#dFETtDie^|kPHhp;x?*~P$FgA3a-;`#aH@(tI$3sO5J%MNsYRq|=u}fzQ z->XZ1pEuR1a}jCmCiBHh#k|?7Pu4q%pkWE>comm|PRF4~<)hZsvxT$zH_t$X9%og* zdIFWqwUGZiCOZ@Vu7>%8-ntg0U4U=)#_wSwUWt9Yb!t&e0ewy_D!71gqVP*G`X~#c zwRxuC9y%VR=19+@@XduU$>R}2oS-H+I#J&_;>#4Jid%+2ODC-X&9eIFf9ci=4y zer67ZT{PtO?u=9@fbALLS`p@Lw?CrKE}2?% zWf0#3ppRJUA_ZF(W9X5oI@dyIxCS5{#D0#7DZv6YY%AyoYm#)?g^-Tp;R;M{Y{gva`#)1Bt$;W%lnc+rzHwj>IM$9 z(*wr7I~hkjx&|)5$><2MTbvhZq=+W?nSdtWMmipNMUGC=YBDH z)zk4AG(DX&Cj$h*3FhE2H;JCIC`@Ja5n}LIU=rjxFyOFBqi~dA^ib_|MDYR9GnmjL->C!<6cM39lRreUdE9d{ zgBt7*f-_bSGT+o1)FBQbC+1PByQaP7SbPE+vjc0Po#|yC8|FKf*F4~M;{b8L z)@vZ)I!>Wr$SAdpvS7lgplZZc?KJ91P;thJ!6TPBK~fN)QujUxFnAQR7NCyUVW_24 zTsx$dM=Y(oXZqG$v=x0lV1E~iy=7|9SjRUa`S@6rKHj+@<|I(<@Oy*n=7p4T3mzGT zz4v1OeaBFW``zT%S;xh$C3}yozu<)&mLUqhPZCEVWP*D&#Gt+p@g8_5153BCTyZGP zFUGDY9q))3_B=-{pcBQW)8<_XSXV{Oi0g{e3{62vI-Xc1e(i-wA0H+@A8{4Nd?>=T zj#>SL3}}@?_zonTOs3ty?JA087bqTu>=8toA+oAH4IWQe9Tx-y11ihm%LN9?8_avq zy_;yB0+O*49uWLGdH!Jv7*v4^{p@P-hAR5b6?mn-?te9vh4;Kn>qb{&%rqyyrGJ zDIm2QmEJ|$r{huJV&|mSfey1X;#uGxU$7BKITKJReZMMwFG~by zkk8bR+bnw<>e3^Jprl2#_8y#9sOSj?jtQfvKTW>DI{p+%?bK|&*ip>}z{OvrR&IH4 zk9d57UJ^zzrKZM7Iv#;&_AYV;xL$7Gpd4_?m|eMLAhe2ytOlvP(p^OSc|fs*5e`w4 z0F~C6iU92|1P(<{Z(_aX$W2q4S>!Dqkky^`-#0ag*70H_u*=`;OC0mp61YbyYk`!# z0hNM$5Mc1w$HGCKBIVTjZEk{GHzTqab1Ez zj~0WJcDl>~TG?*FS@Eq$&F;LLS{plvhEMp?HNhL3j50kdc$aUu)?=hOvOT_p0v}@f z8%<%ahnSBMO_unqKjjT_`P=0CijEhm$+R;XMCa_h6d7K`ToAPdpwbkNmQd8+Xj4T_ zMVsf+lYAbTeBaS=A0)Id{P7y2WJFB`R5BWj0P$Y47St?j($6y7*lXTz!kpOzb4SXaK_Sb6rSro%mx2C)^iW3e0*EG@11qn9*g5Jc;0A2#O z*2KYTSFKHwB(=TQgK-mxJ+CVQo!Vz4MtM`pGvvAtGBQE0VwEi*sWoo&l-61fR)QjO zIQ8ApShiOORG{Fm3}94$Ihm+%IP|Q{q{yI9#wDCC{%dOFrQ>BtYM06CDOBSry7X&P zP{32M8M6A%+#orj_(%|BYXA14Dc~Xsk2N&qkDCWm>f4!dk-FM=<1};Yy zp8|aPBb)n}l-{(GCm~O>#IzPNTohnbX4??%J!PLctH}=x;bjNgu zm(%xy?e$E9mo9}2m$#@xb>6VQj^{b1YqtW~b?{41P^$Rl1Ef(~$I8agw1SS+wU;Mq zMJm8`2u-ZP{o3hxq!3VP&xJ2?e;*`mJd7h4mpStcH^FBuAb$vo?7k$;t5%)v|6_6Y zmh_NxN3Mrg(2kn?TeCaC=6wRn~}19lhX8#IilHn)1~c%(>HX^ZhI4ONVo zg}$Q+I)zn8=*Ani)$v5fgx>(IQbg-O(v0Z7LgE>b@tErHM%JQm0$&%*rI)o)8^zag zrkGuol=NtMLO^AXO#~D-AWk2RjWo#IDYRe@R?=N}o^4(}9)0lybX-w%s19!wqvM_; zjdpa)$4k&@3AFrWWfAa1m1V`bQzL*@$wCN7k~X(7TKzCjyu!Rm)Y$_iTQ&*z62;?d zs}c0C2XB_7<2azfUh1q>LTY4!_Wmg3#;BA5c9hozrSc6e0B99Wo~fFk^N-dJ?-ylT z0GjAi)qAtY`WRe4ERqa=2%k&SRiaS$m`AO~7#t80O-Y_SFhIvsg?R0KouJ_}U0@^`X!rZzTK^2M2sox4Jl92JZ^x<9R(ok)t5K#!f}NB}8&{C>BHS z)#n*W0kQZR0{%H<6vm0aFln>wCfa(zS-*rw8!_q;1HjJCX|D*>&S^6RUg;`p1uC{D zs$bv;11E!0={&*eXml88Xe}K};tde1ddj373^yC>B zbg^YiXt*EWZx$7y7~nUK8Z_hq!*o1MHDU8F=^uaY)94|T@c7c03e9r?4yIg&RtB@W6!W*~b&7sf z;S}M^C*VA5CHxDFNn(-F<4juY<4qBlt#z@SEZSXRauK{==v$e)rfaLJ@1jv0%zV!w zODeysB1h$Sez}g5t90*;uwhW)V?uqo}}aGknN>6SqHR-dgX=iDMg^= z-S0bZVGaHT<#J!5+yT%k?X4<@w+9F1f`z?Q=bvU@**7CvIn^P%pRc6`Bk{7U+jhL! zX&lM{5Ho=;G~qribv#UHTxrdjK&z!KL@~`_Qnc!h z-EeEGwr-*7uSZ&?vL7uD{2a6tU*^8Z{?IzAZ$)>S+6AM^uJ|Y_j;>m{Z<3CeXdJ|$ z6JDQUB`eL*<%HFf1PymrpfXR7*VifH1o2&mwTz*HG|hq3Ly)G73$|aocty|xri^Q4 zPxKSSu?}ggr_s7*{2TLe7$Y07crv}!lsEU%@m)w#e%_zZ{6v}4$A*zT{HksaT z#+!QTc!6W|yR^PJVxL6J9Ke`(dOHZrb={mi(arHLpyO7@=$+P! z0{zx}22pbX9p9tq7T~Vq5suNvYTVs~A|guqd*~wnlca66s?+fQEPmdS9+KdgaLIb@ z-Qjv5pKLC~af>$q?o()VFmK|e<7tj*_S&cMgEW5tK8uKMg)};zsQ9PHeDgDS|)uQT)l zWQ&AnqX)F%MIjXg?Ju0x2l5QF&{Wi?oN4q)J06gvb%ijhgOj3Cn$D0R99m}CiEFOK5o=x zOz?CM_iF^MQ@9KiRbq!zVZucpTc z-%LMs;n~AFB6cF6M5OpcoLlHElolx>F#s+14Lw%eW+*S{m0wASO11&yD(3ohGd&LF zhgkDvw5Ka?!A7J|QCFVXT-=t|84x^6GW05tCZ{ojPRat8QL8|ZA{4c{1(OuUcbfC@ zhAJkuQ)bb;Zrp#Mj_2#jOzk`U-BFrDn7?*duM^5i5v`>jyV=~YFoOtA9Gq}ijML=x zAUp<(vD?35Vo_wT`5Nrt9f77ai4KPG`fYXG3Z~;Rt%d%3*sI_Vv_}fN08MWog(p(r z6fxuEJ0QIIHLZ`tFeBw{#hE7ez|@u>fo!*ijknPCxvvlZZ{2d7i-H@HtP;|69J0y(>c65F9fV-UI_$>dk@BUt?ChabN9F?J+=jD8RQ%)my^ z$B)NQV)O?5DEb)!MJsWE86?fhWwcY8{p4=Rv2kt_0=&Bu#^oDlNuPD9$ zK*td}HDQJ$;BiH$^f^>|1%x|7rEq=U(AD7c2RZ)+WQ z-QrND-31z7E?#q`)*#_8m|FEm|5MfjGnBo+=OfzLoBIya@gX9iHt}$LBQtyhRE%b^ z14ZNV0SNjCeFGw3c^Pl9b}zf@L<-!Vi54vf;fuG>j_R1IoYbFB9-IfELQvwzTII}k zQmZrG=cBuh!Xa4Ey&}sis2(%VQJp71t5nS2w@}M)zRw&0z9N;&Jo+=7`$p)v=T?Ud zO#xbk!>b^PTfKCZqk&g_GY{WNQGHOQ0?;1r13a8Z_4;zZBppw2l+t4xgbtiCx~u(} z|5iZ^n>x*bXjX~X$e`~w6i!m|qLSaLN{XIfIxH(*zJ3D5%}(u;!0~5Q%QtCFTZ}pZ znV-N(x8g(xrMfV46S2S0`+svgnGE!tR zegXa7ACu`i9)&b^f~RDV{{a4*ITO+E0ER52nghATOUF|jqi@cjegnA|%iTy52J-r> zXLDLOkms6H!*O&aAYl>3MDj+yI-V_(zu|CL@U09=i-gN&qUXy4JVla0+_$-oJ8dsd zf`QY*P0aABj#r*H++;g#9mKQ7iR7ZEowgXojDtJY7}a$PRo+`zksB*cD3UbsRZ$Yx# zdLmLw5jCVCV)IkETlex@IRt|C!;G^aD1HfL4dI?Gbi7DsS}w$Yhi+PRK;W7JTRH6@ zK9q-h<4O%B5j-k3u&hKN8Y{Twu4kCyxNthqOs-LUg1HdBIrmKz-lr5aj5nO1~D*ov4eJ2$AmzICU3`v zU||!GmV&}u$RwLwy+?T0fjy(KIz3fY1Y1PP;}i%*22aLur0YhCe@gZz$hAba{KYIKXci1mJ_3e3@$kROVBJ{5S>PVvgQ*Sr{3P6bT+jFybx^(*lBowRoZKVuF- zxsL!8e?|+UxnBi7cPD)t%?r$FNZSJ8@t@O*7~Ze~U$v96Vz_&++Pk2hL+kobD6G92 z&1#7QCV*Bcr$Zn)mecv225L1LZnz3r*$)U^PCt+2zRh$z_ysXT1w|7h3Zcg?ZN;YL z;XqD)F?^z18QA!|it4i*hM&)*FHO~{;Tdb)AcGzf_X5)ul}yE+wmG{rt^B|y3=pz{ z?vI96I-dRlgYPRDi01Q%y;kv~c$_nodI;FFg8mu98@0+T$BSOzA^vQhr^ua6i}*^MmR_>yp%+1;)>{4 z8Fq447}eYpf-eCSqE_#4-)cIZvfCi80rQ~A@9-^hJs+_nH-H+%qDW(6u!;?cT1CIa z@_-6_<8G=xp68fD5jGf*hw$+T*YRwGPe6DZguMm`TTQ=A;EgKqqTS-9=7f3I2vjbF z?_W(yNFueQ*u-M23&aqVSFR7bpF@wk_Hw0i8YmV-YL)8jujZZsy=Aa_{&`%|#(2iHcS zr5aJDF1{mCe-lzi-80%WYC>yt6o((y*xjC z)0yGAK-HbCqV8o03M1G{S)uK{t`I|KVh3>+V( zQ9c1h`|}j@B=liC|JodM9!pYys5ENv9&hNS<4+OUPN~{^DE2)xS@Bn~4hkqpqux`v zHBiTc_c%l!C(yC+;tFN886UXE_Qez~NoJ8Y6A-hWHc#b&fjTZu7Pk|3uuA%`_fXkX zUTp4(q)~vv^>k+%Z|0@r1&+z@?V%Ra`5iYARcIKs0abYqlTyuQYQU|&4YXsx^kA30 z4#NHSiqxHG;|#o42xU(K3O3NN_c7?w@leM!gZI*k_xWXWS{@t|5dIa-NPszYe41nQ zg?njN0x#&Ah^Qh;&R0-yC6oSec1JN{N@51)TqdFWDt~>@O|c$0QIUh0_sbsO{=qkaw`DocPs)tkXY zms86|n`dFJqe(hln#G@(<9~u{T)~cu&2%M+*KeZZF(OrEURMfK&+A7vs-KKuvUfUl zPUe@)doE&D9+i3*D*0^g*G9+pIP$2y-;T#a5mr&dFWG3yY<|ZqtQH52veRkY9NwUf zjt7gRmD((|=M*oH3Qhy|(}6ksv3bwWcr683x6;9nc!RfeJj0PwivvhJRjiu`Q@IKZ zS3!)$RnU61{ZAyQFyAi@!gBXh@Lb+f7<1%Y{)0LA0(Qy5m2brnnH;bxu z1~6s^wOhy=1nPLIW9pLvEx$)WRIYCi(yWF2N>Ub_%^kX4+kwh~Px}gtYUSt=H+^bs zq&6w8)eb#kkt5%xhrm}Y9Wel^3#>{{-~>{|f}=M|l`Ts^laG&0)$8jXPvM))aZn-? zuzV-YTg)50s^dKc^U8vn^&5@Z$ESWeSAtM3n~8>~aAK_X`Ac24KxJBv~l4Zi1YSPxsRADGQhSKP|fN9>%@ z+H^gVpO9CXn|7J>WGO#s-iV_AMpW6|bmmhY;HBe{j?pJ%lAOX%xQW(b0>JPML}HwK zU2>z@&Q^DHAY#fw51#LsdTl1vUIt;gFw0`p!)f2pjb*%Xh>mAEMz3)gs>W9ABK}u| z+Bwh9nK%!P|I}0T()ob&Z=nmW1sJIMPPfTZwAVRJBRx`(;8~gdaX{_eIp16WPC=-$ zv3scVa_-w%$LBgGJP5Rkk9`eNRUe~bSdzU75JEK&Mu0t7>+H z(pO?MD^hmuj~;a&%_Q#MUdN*xQ|}PyICTX|RL(CPnSFSKejt9!++zTSdVoS3eYc7? z8mQyBmCQD6!9|fr!3=Gt=uEY-jvpvhOjaEvZ1O^PX+x4f!9o04Y4=7k!Wf9_Wg^ik z?WaFi^G4x19wj(yc@~1szaVJWi-Nv%5R`P3My$b-rQn_h7;}K?eZd=z*YOfZ3FES= zW~HZ~#N%`ZgX>|a&{UvmcOaS{7hrbtAEG`;5rd^6dN!p&KJ;mtSiFW6ao?Sy9Hh~y zym2!fpDWl^W^ji<9W41pmUxTtqTE!z-8=?n5~fK!NFRO4{d?+ot|ONo$EtF%3QA=r z%mS^*L`fFi{gQh#+ZJ+Oi;Xwe;69?HeGbvtwcKxjj*k(kDs{c|f|UKBR4MgOK&mYD zHNfzPuV_%{Nx~i?2RVmOnJ+QvqZ;bWaYVN;43(n$#gD}-m)gYW5g!VPl?r@w9H@h_ zmX}kod0)GCY(_ajyZ=sj`Vdew9WB%GQHsjn9W*gnT#j}JTH&ac<5~e056AJXcoSTn zNpG&_{+)F^Pe`cL$^Sc`4ueW3P^uW^{&Cv29yML~>w!s6ZA++j?&PYKMPPZEo{uKx=D-#Y{tOejcU~#OrpyX>55H$RlhNDMSG{TPW zsODF^j@KFyfD>cz39%ON2?+R$S4+<=Y8hVfKEt-(V<^1`Ogd1@o9=&S^&Y0#R1Xe< z@^*QdAkgxcBB4z<@E0l&_PDDxNMuHOOBtf)o#Hq0yKZGEc%O&xj>jSRCX=?*_NMg^ z+)@*)2hVpDe6ot*^lUn?3ETg-ZK2DX_&swPvNHH{tT7&^3!AYdtm8$FY_^_o)PFJX zDy7>TB<)Sq;3~>%9Pp~;HBiv>@(LA5MQ!v}vFc+dz0$gTy-+@(7Krl)2oZn5Y5@#d zgK8?OX2Ex`!)^=(YT8#Hb?v3R{^&7tz`(97_(?S{cFlJ230j-ZEiR&k#y5jPn7h_M z2gCJe0%Ef1lP%o0qmBm%9+j>-0caI-gn?vlj<-%y;TB9BE`{Sij6#ceg4S*2_4?`f zd`FJ_)C(N{s=~1lxbSyTz0cvd_$#AUJ2@^P9f1#tT5RK!htJ0<=p{h@gTndX_fZc>QWR?sU3bfsP350qB`allH@CIv#LZGg>$@JQ$Fc zOYIK8C^{Z?nsyxGD_hQla3QoT7r8zzNd*$`J|wbN8;5M`k;a^+orm~}mhng+Xc6bM zL}#=_!48S^NOQGB=4q)YIzak4T6lk?3KgE55VQqZOPM=Q8-wj-%EZbaXqmAB4b6!aTdq)0M*z zpyMUw3YIQKQvqa6T*nP()LgeMoQ>PH07EWlxgNuNj+`>4ig-Pe`x&)?$P^94 zr>z9rGC+n%nknJi)4qLrRqCtq24F1<=@~cZDWQRyW!e^KKP|! zhu9F%!)CoK-DTDT^w^h%{lzAL{y;={QQ)V>hoIL+R$dI-W^@PrhGQ7rKgO4vgJHZV zK*B}(^f>perQ^%XEvDMp-e3=x;LvX*D7i@ezC!{X-}C<^$V7rWfS4bsW;SY~j_04D zcG-MY(z$Ems+k0C@RQ=zFUwysxN5Y_N?JReh67MVJj@qGPoIj7Wv!y8Vb1w{8^I&& zg|I0VVH>N2y@CTO)O1cr=tTWba1Vc#$r!~^Ks!4D*|gvUUuw2a!4wg|C!ZRgpZc8Qb-i`G4HOt!{#j$cZg_>OMzc=wWu4NFmkCzQ$qA2W3;n`WN?{W86_3As9;Z$Vh8lXynp!%k<>!9OyVEZtdbcU~P zXLc8hS7|2IO(3GZ!Bry_SCCo->$G6u!YHN?t=&nO4r-`MFet)a)HQy}Bcs+T?t}oIr2#(l8sdg6;&V6?yHRLGR}B z&zgFo{00l3DS&DBl$ReqyuqMCHK`sxEtdk%@s$k=Z;HA$->IUSK;>3?Z9+&P6`ten zT&+x@^yD00V)j{p&KxlRCt7x%*XgX|%aLP`^O7HeIs+4>h8cbn&;Gltmr$QOAC=Y9Z;c-FQSzft>#41n^p zmY_j-0^M!&@Z@te`!a7pLHYbc_Ylo%V4Kzk*NLmexu7w0IG@|h`7nPeU{?{%`jLCr z((yFdQv4N&{=V+YANe%%IE;0~n8)=db-u&{>gjlvFni_QK5Gp>o}&*hp`1c++>|(G zYRpaYzRX{1uH(fbLHV)zf5Z5-&I6Cf*-%p_YNvsIZFr_?|25mqsA&QBueJSKb>&)| zC8erWKA!mSxFS=%5GQ;;KwtRMu%Fms(9_>}Y2e>%E9fU*8n(=s1A5U*!?qi5 zf&K*9t(pmn*};9N^a_tRkGY3Z1tdJ8wO6=j1s-*tvaawnvlzOz{t}A{k7>eHj1P1? z{yZ(a$~^`r`wFv!4}Hl}ea-sJU|hC8$>USD7F;p`6^i^0YZ{mBNfK8WA3;D1h_DN! z|E}`SgTx!cXMnuNaAF%?O)%aTM|4$=AoUm-=PC0VU&DOLY(swL79-2vPqPboHz|XL z|H{X8-*wQSm?Yy`&L!?<@nL>6>_n*WMsruP9l@he2SAE1#p_)-?OkM7^#b6DX%n*JN#!B*{~#zlBW?xP>Y z^Wk3l_$J@X3ieR*TYN2Z-$Una@gr=~0o#(_`2dOe?WJFf`92n4v#q|(zm?dXL)7;V zK94oYq)XyC^AL?FfrR6S=tc=&TI;hzYNj3-)Jz%iLO${jK9xCT+8*8IXC*cxi@y64 z5*{3-k4pJxtm!GLdmkFtKV$p$KCjK#+FUyI7r)1FsjclHzsNQpwk`UbpO@H4W1sRC z65DW;R{RGJN*48h2Hh8bM?XD-4)eaFcc1f_)J2wMy7!!~W@EBfERff-OD8B$l2@{< z6Ld_H=doKSsTY&yuxBUe9Fu3V$P?7dC?98u$86P|=&md;WJ(TwpvX&E`YCdDMmXN)K6VD@7~p1k1ACNZ+isSxNi6&v zEpm|uvxsx_n~OY*ee)f4sVhdJ^oRIe8BGgfnxN;s{#j4sNN#sb(E; zxiXwSuY*+Kn6^Ty%{0;jsp9(6+a8Ere*_&B&xcXAMs?*{l9WqrJ>>>cBHgbmcWYl@ zRTHho1t+KwwYi_kuMU0~xwl$ByunbQ#zZgFh$euBqDpY;=PCD+cF}52`5ozXlDy=p z(ma~(CBG#tww?2mo1>sI>8ZCoP6^FaCFIdkUs!E^J^6JOa+q@KL8qP_DA)%%DVj}b zJ}CU$OtSjQBUo7`&G(hZvCK>=^+kzH%cSu7^4lzSsclPrxh_-p>zXj9K~Wv6OTX%h%{ZOIpd1N|4an$5?}Iw~}KOSAhi> z&9m^?d7jA zBDKwURc<7)rwwgiye7Akq&9T1gZ#eaM7=x8N2N?Mcaoz~(q)Ioa`@8 z#$IyNMd}$R?_n96Y|rB4rV`t~k(y4DkFwM>+aHtU6O3iAw|(=T{DF}fzOpr+E^~)8uWqu4lDMfBOf5+(>|c4Gx1DKrj_E^<^y8?LpvIq4Ew!m45BY*$^n$} zKRHy{g?TWvH~xa;Mfd+FzsVA3Q|Cma3f^wpnkZYD5`gy@Q&*!W&He~+{+b077ll#B zBzc^4jlN2fH%W2SaE@%D_+;6=6|Upes)9FftlFxPNk+qqTb7N&cTFfVXMua0jP*^D zJ4PYLlI0L7m7XNa&*3~zX3K9&`)TkT`EBRiv5?%>_?>SKK9IQ-m2gvM5|qv=wEQVv<~1sbX#z%f*P^$jCdGoV3mfosg+5 z?}Yy*-UTe+U#buzoDJ6wXw4!oqCh^}%{jE`)_*+^GwK)@UOxy#BP(c)aNR8aX zf(I8G>rEcwhz76`=uC442X><|K*0ZcM)iT|8;$A4!rx`sVxBh0E&`>WI*_>b;HP+*^C~G|BiDmptllI6b*~b5D?e@xlJF&Ry z)chcZ2Y#G(9>g#QM@F5!LALA2We!E>_Ok1LK^qK=XbZeqj6Jj6A@JCD*4v&&xS1?;kpF0Rdr*hUcMwnENmNlqWAV zV#3ch?t8he#8RKxk}k@%q3?6s=Re4)k`ecFQtKb(t43V3X>+|Kcam6Hed>2v&Soyp zY;_7S$YU9vwkcO+560%!wJp3R$4e}&p6%(+vY*64eQfoAk)0%l(=`GLkq=jI+E|EI zxX?tdzrv(W)o9hPawf~HV;g)!q$n{{!fz<2A|KmpMdG!gXEhppQ+~o+tI>d4avCd< z=;1AxsHZn2{El37^rnZugTwr4wr`4MSBY7lQub{`2zx?3@5m)A!o}9^57G1F-?5D< z5nc5|#dhSb;2q&?yK)cpiiNsR$5N=3Qf5mpl@*C4`r5v^FMlSnC~sSjzvLql3ozUG z-|}FIwfUDuJd*btad#1UJ(fRaV>~GBvHXGsJgo>S&i)_|2$}}tU*a&6|tEM0it~G6&U2wY+n^4nsu(~o0 z*?UUCHIX*l)n;~8zC+(@q6@W@rED0d=-RkzU@0e~n}U}%PDyUcB=#D&{pqH3aAF<5 zv;}!8utWL>wsv01IL2bP+t$`o;NwMGX@`$8hehqC*1pPCb|-_b`vTvUK%?p_$5}u! zHEE#W9cdSxY@nQBJ-5+kexR3aqrnZ8g)A?bZZw4co*A^yUs=QAGiX2~Wfm*jN*5a` z-!Subnil|_W@Qj-jPUu1w6-zQ$Lz3;YNA9)OnHy?SfH%SdlX<*t~2v{u-)HnznC#=Oe43N}%1~qK1++)kvQmq!y#AzMfY@wWI z$?IruOFYZg(Z|6eXH#vhS}6-97CeIvw^k;w9SIcp3ZBJNX@z*Ey>FA+C`@AQ-X~LA z<+!sro(+xal4=zEiZZ&oIDQT2FF{?+EovR@1SL%0U*nnm+6VJbpF((+LI+T1_W9 zBbx!Swmw~yr4l=rL1J^cz2o|E)?uecg6E$cN*G9ncytW_&}aE)S{R^%4l|` zJGJVI;GFLCC7#aWm<ZVwm$DD4Pef2niPx5k=d6X#40mbUSFCp9%Yx&mu`)R8|)9ajhmqK zV63n=?TAzEu-Fh<^DY9Gway6DKQESV%biG8wr`dz0RYMkO6u~2HClZtejCCAqi};_?S7Isol$Hpcg3eRKhma9}m2y9X zE*q{=8|7>Nev-ki2 zKJ!?iqq7wcnmq?nPhKULkKpX_KT*y{xc6kwMcc-?qH(icvhDv^LHE7qXY%<3ZCLOH z%KAh(!lKSm@_gW)S1Ditd?`E6mbpM#gGTQf4Os-+XI-JZMan)FcZKFJ#k3ngR(0=WS8Tgo%nGXxC?OwObM7_c=J1 zM%Y$;u5^%Cj{)@Ka%i17ke020gY<}`p(~-&@d5PTO0XO=klrJ-jo129tyO4Y3I@>O zRZyXLI4xMMe8$ouZN6)iTSgYO%w}4vG=&eQP^)#YdD>_6>pJ+yn*MYy4K@!RL4(#S zo7vL0ZU3!T=Aj4aM<0KsyvOptrLwP-!7QT`zDgDiH0fILSdOC71f7DyD^JV3oAX%c6)r@SptGQK@ox8gZ1m6EqA zqgY8>D%z^_RX<_C@Noq#-KK;~A@s>MWgshEO4qh216bi~3eLdu;ZmBLp?txfCfXWq zSDG+qu?P<#g$8QBOKCx~b}F6N!zFZhCrTo73ANg#xYN457~GB7sd&@aUCLZ$okD-? zLIK4rrbW9&=d^?@-=O~HE~ahYpg@zS)6{R#aORG)P2M9~X-`DlixTu%KyU3s%`fdv zU2M3L{^@*LXG8hKbhEv&U$k3$=F?jT;Pi3xZI=%y+hmr%faV@U%yFqybPVc;a0)pN zzjaz@%R8>jaAjleQO_Sl2Z#tiz^RtDr?hwb5JllX zD!#NL!MUz2`A4Nq11jn7T$8oNl?CIR8@h=o!2rqd7XGV$^ks=smv;OKBXoYnnbYz> zXJ7icL~*0M8%mVT^=~D?`>|pVnLEkTM_M*_sii!H)hNRHO&edr0e@dhjN~Iq=`%`EmXH3ujt5lOZQ;lcJ zK=N(m>`I-UDfL9$+SKB?GEtgEYo05w;)SNr-`N+B^P`>Xt*GvNR9Z!?yqudz%PII4 z@_qjeXE(ZLa<tiMn7WEWQKkavg5^0clkDj%5_Luyq;VaJm z%uk|E3x%nL(LZPalcWrGu0so6ah@5ZAhzHno}SuoKk@V_r;Fz;rj<5b^>(gDk9^=j zMU1*cIM>#I;05X@^{+Yu%z$bD7eIAD4M0tRtF8XkS~srisjLTU z=Sk#uuy(*F*38-fH-I~!4!{FY7vKr-0(b-J*{qp9J(~+bvu^tUd;#?V4FG*$xS5I1k*!&;J`IN<<73Nd(Q_}Bgd;sDettUZp~gjgbaf}fEo7R7sLQo@PHnjwpd_>`e!VG$Z$_Q*tAD9^$gg~ zeN1c4SQ_B%iw>Q!Sp2j9!BIn+)|$oD#dE>6k;=8~2|1lbx`KbH*;!buu-R2JFN%3MnmR=~)b3xyOKkPB0{p#<@W zp|!bCIzy)HT;w)eq2gSNwQ;_)(I6TD!B2IBaP9OZpaw&80FJjYQ`>WvmMpy*jXNhw z%Y~Mov$SE!)#=PROIwy$gQWA&Fp8R=hq*h_+X4%sPtL1K>^^U4#h%v2)(ku!x>4N= z;8oyGJukok6ngi9rE%{Re`Y9zFnq>oh#fR_6uuB0KYDDBfk1Vu7uGeZ4aIs;?432b zJXSx@nIVVvU9b$moRV{%r442%JLg$iNd**-hfAryQT zFmr88HNLk5GoL0D`aN7Vz(SM1w@hMTR{G_86o_jeDHkmbG4I^;qQ&aJr>W84f`V89 zZaBFyV&s&mV+V8tq8DfuO}l7mg5{|%M51S%<(nYUyc}EWRaG z{{apZ9!w!WAVm=k`@w?Kv1$4baD%z8(E1-NEm%Su`u+!K6WNxYAQlU5N51(MKc=*& zF8P+;Y|j!}lyAYhcnEFHN4V3gbS~dgAG3HR`AC-X8rAs`%=c6KA1w`PH-@&%kkZj; zD8R3kfEB+6x~WRlQ-fkV(T*Q2bsKxBm{S*{As@f+3728g^wFd6<&5}i0APlKF7yvr zv!YP)xde^!x?&FoG|7COhF`MOWAR}$Q{dstP z9^gv>qj3}I)ba03vM=6PntKgQOX%xs@SjjR zeGU3KwV^xLEMGy?(w|WTnRM`HOVb9$iJF^;Hbv~1iN;5`;;#(=wnU+M*CTEwErJ{slGr=>qaDL>>yLQ=w%%D_cbAg>b~O#dNk1k@M-F zLd%whLq0Vc@*qSs6ROmThFU8lD}DDX8a6+=`zyK{SMt1poV!xk4T~Q*kG+A`?coYq zc?0<2lxPfLUlYD=(1f%Np{SDGKQsQqQE~gy=bERv)p~tdPwIaB>YZ}EB zSv)D}AV{QIf9@jEIhSt4}mOK`-~G zW}q@d6q#dQ=;K5sB2MvE^0|e;aO!yr*=s{n zZlU}3q%Urvr*A`NZ^5~7uEsyN;LJJSkk{{)24Nld7!6jmfvFHSC_T7^I3Nat zFMt`w?A5$oG?LvWM@LMVJQ~*=i*SPogazKf^cuf$WM+vpw_Q?J`7hje=XHasMs*4#$HU87UC(a}YmrT=cj z7zxzm4iwr*eeVFvr}yu`P+7G84oWVQ^6tQT1@!a|1P2w6?;mij;&=+hvzp5LePH*>42;(c(W)s2hp?Km*t22Ic+%hH>=wA7Ecfz9o1hPBgnDHL`+lfZrv$#>edzM;_JYB&(obQ{E3p7OHaikg#t_Aj%hTs6m_SV z7L{U1l;c9rrL^w>)beXdKa0>rlKw(- z?b@1}{e@W8w$uktB%1UWsRr3tj`F+8wlnZ*koLtq(-ri_M` zA?xAEG^Y$1$feytrD^n2nZ@c7`w8B#A?Se6Bf`x6sQEvr2eB0L54gtAxPQhRPOVoFSh zw$$aR#fv%z2iBl<2*dUR>iE=BkJ5qzYu7|J4B}HdW=P&z9@mqSg9B@7ag(=cacAaR z?c>hPsE9l1KUi)q&HoSHoJ85M}f zG%`L%nWT{Ax#~^>o}(7K9Hbe~(L`ed+REo}NvBNOk0-426UZo!GQ^S!R@Ae;#zK~@ zc+1*Q+PLBas}-aT)8N z`cSeqHo2a0G6YewI9BtJWUa#0F4 z5X=lN51b4kMaW*4LP7NVMp%WR$n?guZ;i6QO zZYs4^6y1_aMX8}ubR$a9Id>|FZaV8oslKoGzSf$(uKoQz9^e0dSC2>Ixjvt@_S)y` zu=m<0{K5Q5@A8+=)gFy`^YpO(?DKc%PpSXiNzBG_o~jfpps+_ab5Xy7KOsAo%jxr9 zkZo*MEEVtt>|HhxlYyl4{4_CbFV3F$ef`jacgYWZs`#cHH?tmAL1#DwPh z-&Kkga%`%1GWy0p=Va!v=4t+wCo^l~{Y5HW;BVBQsr~_i^s{1R=6gVLR==Psi*BCZzbc*R z-`2mbDmCl#jWp({v!^P14x_K=&s0DE6oOsO@Gm@tb&=WLzn;HoJN)JPv%uee3JakB znf`aD&{UnX{8Mu%-shj4Lrcs3(fTvWzauA>m!98=ryCJ`&;KBYh8N#kjsFky3;2^> zvztGtT5J)A(J!m90vG$$sTF8=d;5PXo_(I5TO-zyH!wqMu#9)`+bNS~Z08{aQ0c#n50t9Yy)MW9#mEnD{a z{ueb^eKY**noO=}fZwcUurc+kNqs&8*JRnx_8;I+Op@i9grBW!ff~@y zSk`JlcQRWmu3NaR71!^6LUdM_rb*%U* z$BM6UtoZYe6@STbLJ1m1m_NLdi%266TPr@8+d!<0lkqfn(L* zQIZO`r301*vBl(UM*Wm0ynD*2`4V!JPcy8~| zifbft{^%f>?0_EK00JvP;~EDvagBLwt++<#wbleQQm?h*8hzJVagD@lt++<-O-|oT zKtuVu3F95BfqNaR0gae#^A%t3SaA&l?Z!1kw6)?Ii#nKpy9D(32{+-eV@*I$o^a!O zmV~w9dh&#|CZMNASSvomvEmvSM9ZI7ausM05o;yr0Swk^Ko4iIRy^0S;`)9jm?uwNt@r`QiYE>`1xl!QWmrK8dLkTucqKca=T%xOKFYD`-|JX$ zT>@|O6@SYy@r0+xiMR=RB(}90(Bnd_)qqA9uvT2pm$p`1x58U1u4ma=E3W6qT36Bj zrw5tZ0wqkkF0>k$>R9oI9V@=tvEp-Qq}JDS%qixTT!I=>!@7$0zx>%@ff~5iu_mz8 zvEr{gR(y|R#V5@P+f#goW5pkLoKV7Ar$7n+b*%V)$BIwm4lMrgN^Zp)94kKX*3|gL zjukJRR~}CUyMbE>x`bwGDmTdM)xjcu*C?n1X#TsN#+E3TXBtrgb|_epd9 zSAuS-b`x~FwYB29RoPk%1h+8<1ncWT)z{Ek){0MZta!Z# z{lSH?stG+K+vcfUkEFL&Jv}|%T5&yD-db@z1m0S4JvQE2aXsPPTJdhnLlaMUeVhU% ztXz?j;B9rR_<@I0z@rB#2u@?MraGt&GAh`=2PO$W?La7lSVat`-7)*SA4tOjz+Yy-(7IHR%K zISOWA!-mko5^}8iRX3WrJqgyd1!fUfeKECxnvT`Lh?i31QynWl%dt8z*RkTOjLT1g zjNF_u2iqO1fnAQ(z<$SyA9JjDy-i_zinn*Hc<-dclVJZy!e+;6V25KhQ0e8=3FJ6d zJhnA8-psM$O?E0CoP?6=uvt(*#H@m+9IFEx9IJuBZ>CN_L%XZCt>5IW(5kQJPXuAp zzDB%GISFc@YBxcHSX-+BjXQ6x4rokzYsK{_1#87M7`(OO8WG%DaSiSt%)ff91UnsA!1&aYphmcN6EwuQwHnZH|JG_i zk8`wET#wkZR$PzYvsQe(W5uU^HY_z^`DdY(@Z;y9)j*#Ep@Rv05nA!3juo%xKi7tz z8?N{=HEoh(rCsk>&CGVJ_)Gswt^b~5#fuK7#!DO%Pk5t_q$Z4YtOmA!l^TD~vEl>2 zPK}RstoTRYq{a_A4!&tV>=bAYzj3SvF8?mI0SymCF|XtS`NR*QRln8I(5m15$Iyy* zaU6WpywxdC!Vbr3pz2Sl4b*h3_=ApBUpKDuhgY(L<9`mV_$0@{H_Z!vNljSfSQB{R z*VOoC$BO@TEHz%|cxc6+ajXvP37!0=`Sjnz3Q8z(tOjN~R(yeD#aI84T7QjW#jBo3 zjmOGuzG?1RUXVQ8^mnWVZu~Q~ft8LG&-^PjUfHqYLmX=cMp@f$nk)UC+CYwDH89?> z8kpu-aYimLU+0Q*qj9+v|F2`kxuZ6S2Pau2R8I>lD1p0?QyM67tT;C*r^F99R{R^s zYQIZ*n6G$A(#eyo5~^mVCd3>o-p{cb80c8>^;xO)H#k2@E@t zl920I@m7x2fCgpb53l5I_OoNfPdHZnqLae>puU_u$t4?jE0VC!u^QkS%kl}TflSAW zPjsyK49AK;>{#*D*k9c~Ryon5Vrt9%9jj)YN~!UD$BOTAtd_rVtoZMagPxxpwnseS zRdx!LkmFbllsHzrr(?zEI#zt1W5x3;hZ9u1i{s!V(8noILVw3<;IL!GPdHZm<*KO@ z*ymXBN~fg8a~uaJflqT%6An671M{k<#uqqN{F|Do@gE#3esS&8_$bH0Nnp>ZsROsu*b0)c+auoV;iQ{AMaT4#rdi6 zB}s=Tfz6SGp4^i~JzmK}b;u``xCxQJ<$BNf)mRdj8vEp1U zm(qb|xF6-bl8bn3Bw@T`HSnEdb>K(GTt(&OH}{|K6l>8n=Ls*@}y0ns8cUN_ewcuV}{{#MZv%eWA zzZw0}SgSU_Gqz`K#fRa1Mn=siLB0aVTKhe^#5%Rs(73i9&wldkk0HwAIUwafe#md* z_WpBSV&_-apuVS+2wxYZn2hKHCDWBW)x}m_X(w4kL~Xf@*-@1 zez46<_wS*ZguUcU#ov?GF)wU3i&btfIaB-}c!(2kjqMd>il3|eqOksO!^XJNwC-E$UCvU7DxU9+iP#+Kd~MtV3$Kq7K_W-$Qofi(ZI&rVLcYX`n)W5 zSNq$W8XQK#5B~}iuErY1-&UA|H5P#NJy@dwTR)2JSLkZ*Rcya9m*2yBn1szgT#Ewx zy`>UP;A5ZogG<;A7@Oc0{wDMU7F*#!1%8ip{0r`JK^Q;zB+t|1p=^F5tS2B@7h^p( z$+|bzL!qoov7T;aJ?$h`ksd8%3vMStPg}9RAM0^O)=y(S-^KbBY=0Qi41SD{vji_E zf#<|{zhL{jkmA*-IrL5*s>^<;cwu(U@P{EKbR%KKUH@m}HsO@}|i_A4^Qk7E0kn4DgT z{_Y9et6hmDsD~ul3FMPtzavwHv#=g|Y2*E{{fbQS;n;p9CQrp0`@`nnjPegn^TdYsIS7lDI?O7AN3AZ=#&e&c`r}`J;cxcm?lw8rX;JbzRE;7TfE%{VQH)oL8z`-RiV!!J2*hZzj$OWH}; zi!4>IcXgI4XO@P4plsrH&Pu#=i=N>q1)qz zj?c$SJBRU6_^Ym=ug3OLOil03Q#st)YcEysGzs=nOZhcC!g*)+A>QoxIDXaf>2)|| zJMMzFJ06X9IKH(GtKfB~U=0b3+_k+Qr}VeF`@ixxVJ|vUhj!IvQyCl1(WiLvxX?di zdySa#PpZdHpX0-L9zHfPbZ6Y`zR>+}a~w09z-9GVLIa(IsU!@-914PM^iy??9_kNXUS^xI$O|?dz66mawjR^|I7EOru(;CrxL6@OrR>4he6%IP%tP&k1`cn+Rq+AGHP zQVZqx!pDjCHu1}p&}Vtrz%<+!CvV+K^A_SMPW*9v^>Tmk1-zTfo*dS@umRt*Ii83a zxo{PEiM7rWYnsbr_$w#=IQ|;j4!n#jnM*sg1m49bW4p$_#P-q; z#g7f5U>pg@%mj32ed$x-9Mr|bF$1mya~Q+++7LC+728We7&55@MkAjPl3qyOTeKc;>npG{{L1$F|9 zNJwCIfnY&BgfBNgt*C*uco?=Fcm>wACO-mlnx7p-{Z#vCoochhpL@rCT1 z=DTPWoK1rLZdx9I?RU}gcs#F0IDr}1eiyB{-W-GJ6QQVys(b2?T!$p6D?SIgO1zSvk-6y{w!Tv0$ z29Dx5Ybw_?@F%_=!(dIfY1zCN3fA-+c)$5gOYtN4XLn6v`@4G^5xk6C?HS4_D2Bu4s5^l#|iIY3hbBsN?4EW zm-_Ns*nWvGAHnuZds*A^+=^cA)=X^^8Q$;2+jlTphb&fJa@iJ`pzNyXFTkKELYT!;1s{PG3GAsdoW?h5rPtJ<( z#MiKKk1-uMi0v=RivNaBW8-Fx2lca?v#Ky;Ii-20<6hYA-ffz*x0s)dgM_Xmbmur{ z50w3|{kcR9jKTKj5m~FMCrh>tf3>P+5|{0&S%`-?UV$fJEg`MCXEQ0->~9+qTbQty z>ZsjkS}GpcL=-=Pr~DR9pmHnTdpOR=OC7ht1D!KL51jn1KDlX(8AyTsZC(@5sx3Xm z%iX{_(5k(axIDzHx<&XU%!WpGhWCJ6EsQ^c>-dd_#X2YKbt7svr?uxj$v!l~tXb}e z_3ULIig&<|aDXp0@qu`sb0!{%+nZnTZ8z)GrW;gHH?JaYt!`b*cTQgni)~3{I*qJt z!xQJQJ&kR__QD7?x)-l@-nV>*?R5u=r?;h3PA5*o_Ob!RJK?ES!u@VwTYAEP|4oL+ zCJwMS6)W*;675aI@}KzT7CZ;d%zc$2-Uwkx3u#^xoZT{XG2Z1L8Xjv|-QFs!w1pJ& zG=(N3_-;newXoF>Q*LhwR^A_24|K5cs>N(%jvHV-AHv34V|zEJ>UYNWLVo#t{L;EG ze`GPcmA#f&36n@zoEa_{)(&fz<3})m>E89k4`Pn=WT$)c@nOdc@i&f_;2#`6j_oVc zJNoywVsOylX6^N9v#Muu)Wbv9q5bgeRc8`*xo0H6W+}f*c;=NuoByw zE99r}pa;VD-kPI}ojH1*xV7f!KiIxBLmx%_74BI+0}0*$QLwbUfVXh%ZS~|j%ZvC7 zJj7Xt=i%v&$6!0Sfo5P5{vp<2JInkwtUVDH6Zb&l?-7kr>ZXe2+{m#9$$`Ov^4|VW^6JS1)Rv zmfbao^XWU%#9a|Th3&mHs;|wk%XBZdzB$8hA}+6_Tq|kIS*$(#(mZ?;Y4BIPba}Xz z)Zma=UheXsL&*-WX_b~;CvciqLFZfZQhRw3cfj`Mon!}@{s|ha9IW;XuOw1oSj5+2 zdvlMS!|XX;?qVjYC3s^be_6!OVS95=P@kiRx0D7-Oaq%E6%Iz6bvDPgRpAn;i|wV^ zYOpD`S7OV>cpO(|+c*4Lg8T@cyOzJ|a6;>RD~qsO(1GOn>ICPbihdOwo?Q^Zv}@tf~0b_ufln^0iysa1n#WBbw^T@vvWHBiAekmk+7{MJ)` ze!Bzrbo>C`P%VtF!5i`K863;}O;^TFN@SY_tTzZRsySmV;LX^+)SZtbPU~!=$>TtN z#N8tviS5Pyn%ya#*$Fe9cPz6=uovSiVLrCk*30+eKHoa?gZ0>5bwlwo{FdV_*j`(& zxZV*}W(ISD{B-ZV&Ivx5ICK0d6>2&@i0e513OBqloZ!#czO;l+>0*^!B2DqdcZd0H zu)V!h9qN>zz}`=)f?l{G9}YcU@@2RYu8wu~xf0u#CU{H458~`o!}?{ozT>xXk>kWy z6qGmx8C~hI<9e7M!^%6<7EgD4E`G`JaQvR*>+wOy^KgFM^7azm0~8z%3%sXPpI!nHj~jfACty9OZUd(m=m9fn>n6@ zTREQM55I~NB(;N=R`jE!%y8ZZy^d#MorASue2rgn;#JS#r)nqO5}$D5J+K`mOB>n{ zyt7gGlg*@a*f;GkSxUHtgc-aORFC8bupQ+}UWM(bR`N#tW@9h=0@K0Q@##&%`g`$r zO+){PzsCbj{@c90_DWgklY$8*7kZIdNIF_o8%bA!Znh3UQhE%r&ULO+dOLH_j;v2BN%-v4#2PT+HB~9?QNdDT0-^F&sCEg&U zd50;mx6`V@%pM%xz6lpm4Q%huQoKNRP5_$YoCRL)bkl+M#O+HnaDK!i@pk*AfIi+# zr$7%sRwYf~c09@Peb|nep!nms&yp~|46k&&9oyUcmH!#uOI&9pt>Ry?y}dv9cvIzE z=HR}tLCw)T=BRGaq2ylC#n~%#D6-aG(TMu?r8({v@o;R1giwdn{z}^Cn~UVfn`w~> ziz9vp_dF}?;H$V7wx5^w;Dd9*_-FVK)_V!f@i(~3OJTfHPd?8DX8%`@8dG3z_?3HL zdw;Jy3h#0nn1}8CyNW-G?fts4=5Y2xFPEv)esT$xumtn0~MX{-B`K zfUv<@z1hkgx5eWfUw{`lz6xJ)Sy=y0Jj3yN{PU17z8xV4I%e!&@ zwy^$TTw!}?uMgKMIJb;E4aDo;4vR^v>2Y&dKFy0JjJBzq8{?+k$c!slx zhvT`ghV`f8Tbw1lurJ%+0;k|H5=J?T_&<1!<4^HGXOVx0H#`0tf8e+ZJN#dcbpUAQ zF7X5fUpfWn;?mc`9uL8*9bbjBcZBhq@u;1l@51(_Rq$TKwa;e;mWKI>JPHO;VBh=~ z;8xBmU|cw_HMWP+KKOAbJ_Or=2((To-~pSw?7{Rx2bvjp6;`JdzY{--PjG}Jp72&u z@T0SipTR$2`-bFYT;Ey8yYXrGQZs>1@iZs?JuYyTn0`%s$}!{8c~9eHea`;{6vUiG zdKQl3zsv-BV>{A;=3oeJ&LX$(ipS$g&MKIRPk%j}<2&$!yF%-Y{c4Vk{P8jpEQAM1 zumw7uK7#E_>yS&q%U^QS0sQLVtb&gCF2@()R~=u8zjAyN&NL^p;QW6t1x-wW=I{w@ zUz*_e5x3?2wjE$Z`Q34?^ihKH?=De}V?j zqri?>qJ%5)=S~Cju^q8Q@%wP&GA{E=ZpGfCcz6y6S6DY)MUkDq}Mzn^F=(eDKy4Rh!TnTF%8i9YneBcRuHEx?3ep;M` zi*Q_9p(@-)L9vr?FSajj0}uGaXT}<&J>}2gPqn8a(O3L+ioW8%t>`QNS2S%_5Y0>e z>8d~P_`~^=I2g%2f#;>^8>i%g$sA;Rk$j_63+o0#y^+y^E9I|yLt$PdzZG6g{s<>u zhP*iboEfRm7at>`KTF0=KsFV;i-}jvOpdu{MuF*!%Fo!|oE4;iZgKcxXawPW3onEd>atnc2S_)H}KRlJ$}%b5Vj zpJW9U*a^NFsqhIty-8YdMY>%gvdupn$v=+!5O+Hy+x#q@8_X-AZL1aqTS*w`EJ8V% zljh|*6_no+>jps;+YZS#ze6Oy51#6L;pN2nZjc6tMk+)-DH5NH?Z7AMKs0`DBtPm$ z%i~RxTlGc?>_{nUFic3sclw{t;maC3Sc+1Y3J?II3V`3J)ZL=!HER2YpPbn>TRJ34}9AeuibQhyQt$f-Z;BF^mgr8!z2sZfS{ zriUH;FcOdYD?jZfjzGsFX_YRfnY^^@cFxx5-f>);xP7S`P4O)D&pH%pzDoHkCv!O2 zMDlxL-JiQOnO{Aq;NGx1*gtwxL;QF(apUV72M5z9Pa0A{_~CXm4GJr7{0)X z?=;prQ#{gso4=2cpb1nk3DN!M|FS>%79J>3@iOwwOA8_|;tXb{lmXf9~ z3)=dhQ#0*cKkZg_$crNtq8=BC|G#`=B!4mP$b50W{r{Tr#NX>lxYS9A&SfqW&NG_N8q(;%}ox@V*pog=<=SI9b z;$0E{;96UL&C=8c+ebXa*e=r9*uJ#N?#EmC{KBy_*tb_<`%?U6yoh)ah1#%pV*3i- z3?HB%mpQ6WsS>`&_LY-<^zWyKTk)km-h%nS6ujg;$#`(Esg|DR{Wlp8wm|tXo^L*2 zRmb1sJ24F;JQe(D3Yt+OpE9C6A#gMNP_jbc&UhQv94o(%v3ew5iu242$&>NfW|dWE z1{1h*;6$>*T@;*S6R7Z5#4ktue#Bo#{CC9lMy9sk#+vB|J?>=-j4zM)x`^+J_^F6@ zM*Mli$Bi}ppaWG$rS`B<#Aim_KjJHKce?~x#53`^)-2I`B7Q1q|F?g|>L$L31W!bK z>gd$QT1VU;_i`q7S;P|~o`KH~^Ap}}sRiDH_`)#3dn)2r@nts7+;X+0H`JQB-5c@O zc(@b)9goA>k;pb z_}hrn$Ch`vNwA1&gav`~BQEy0+{p=ZP^5TN#M2|bJ>mx=UKjD!h(Anq!uu+qT4?agT_HMm#>^8&b@+x+tZ9tAit6AMw_R-;4NQ#J@*e;|ga6wXHUB3vfxq z10x<4@zjXtM!Y2AXB-FH>Ncl9+v*n)pNP21mChWHe|p5NBJLLP1-N^1Z%&>tucTm{ z*}b*<&oKT@hX;;FH{**k!^6b_%5&9Q>q>(_jPR5>vkrud{L5Z;OvwlYfqNaKa?vLQ|k0 zo7AD<_!nCNUx_!s$d=K7)ZTnB+_Y)M@32dd{ z5N=|6xCb|`>t(-S8u%O^!9N)Ph+F?7tees|WPfy;yu5G3Xz797u^*iIl z3JR_;1-&RZxk0!HhvDwHriovTFTov+=iz&BH{+%FL&s0!y1B`LRMdf;xEBt#3H<(5 zykTBOL2c8(7bI-NRgHhaZ{j+}RVT3o@ae{RxK>{1vv3ETY2tnG*|?H%Demid>Lm8R zp-#a(5+*q2t`YA~yu&Qgb+|Y`oa1eHCe}|dn!}H9R%0*wCF9R=gC<_~9#j82yf>D- zyGr?gB`B!IJhP1#+yJTumf_>ru9DT5 zo6&;bMik$OZ@|Hk5xDxZO`@Iq`i z!ejUztX~_nL{7e%_A$j?b)ElDqu}!n;m5!BxciymMsgmWgSVRoF2XaRo1mDITdU@H0P5e{U@9kyZW&Azfi1T&+R|k$$@Hqu5O~T33*s9M9kL~sF z3j8kf||w;;kR*R z<8}BGth1duya^w{sxR-vY3GOQ_#J#U?qcGf;rX~9);9Mw{^Wel|D8<1-xTCAm{qQE z^=mns;TgtF@g^r;f)8Qsw(7uT_lSSxbJ{OIKeUsCXiq| z@E*Rysqj610CzJT@}@Hf_zL4{_}mM^4mZaC!L?2NEW8&lFg_2DPFxtitG%3pP53sG zFa@7GFgz~Yf>+?zSqEB#_u(rq3*S&|#4{cL7ca#2K=wcU%MdSnxoQ75oLDy0%Wh=~ zs$9ozf$bv7#~(XxkB{JXCjUI#;PS8oV{mKS+r+uy&zp%`7%#x<@FcSlF29cRe{pH} z7HT~SU9nwcJMnPGpW-?AVH(sr{}s0$&P5~~Yvt_gnSs&ak@Iw%H6}c}7AlTAnhu?;g)?n4VlkFW}=7!$b22 zc=V*Oz3&qgEOQDf-@uzfTx1qm16*-(xRsxQPj=iNSHbt1{AqX#9%DQY$ESqHm1X!7 zT-kIuQAPpB_wwE79sD)E*CZUmbFT4%-&(cN9mlPwh52>aKilF=liwDfac$Uv61)tv zK!R0tF@7j?!n>Y=6%>4Ddb|KXIX$fKIDXpkt9Tv0(d2)Ii?0jcl>Uyd!FHpoHq-MS z!~4uCX^iL3FsEOASJjq+KPmXiB$VLBv%~%T5!6!qe~XcpUC%8mz)@ z`<&zY_$Uq*DIIEoe{p;!K91{{`h9Tog<2*2Lvt{Qzr!i$V&-rJer!?ruJ#)ICbmoD zW_$!!G7b9plDoOQE+g6Aa=h-|{i_U`7r-U)!z`F z9k=3IiH+e_`56Vxv0cYMXb`EpK8KI0@(BH?iG{C*b2w{%yF!rtl5OD*W$Pl2^HE2|R}@ZVu~j$JgS4W(MBB ziQVW83hev*BP9HW&ol`?;nrKix7qsGdXeKgcqX=o-e&mbS2=m5C09XLeCvP0RWcag zft#52CnhL(mV)Z0U@qQSDGx4GL-%fl2-ihr-eFOd< zHmfw@-A=(D6xbdw#f4m5-p(}mEFO;S9B;>uVY`)oh%4?0-?o2^NACw}_OV=vm{9l8DhjxVt4RK%Y*&rV5Ms4u`T*0^p9*SQ#z6>{iD_mj|@E|X5cvhC zy&ry7tZ*xz1MvN(L$z@H15U>o=KSB7g2{Vz%U*Jhi}29@h7;_GC*b}j&du=N7HoH; zvAFKX;WjZHcgA)Gn|QN5{|}|$xlh7(C=>8;oM{@EjsL_=WG~IT z3t#hTxSy}UD?a0EwP2%4^VZ?M2RPK4Rrm^C_C>e^-o)$hRE|HvM)olUjSmJNU;-b( z4`F*CI)?Y+Zl=Ks^V!J0G#e!y`Uk$uacevr2TP3jxp=bUVR#Ns1RsS+m_)(*{|k4+ znKvbZ{Qg(rR=)<1`b^?Hqe@aVLyf+y*lB0ustxHk9T6bQI5i2;0mTg)A11;Y$I%hx8qtrg@^7XxG%oI zNqSm#8?(yp!Ewgg zvPOAO&o;O2cJ{w}D6kvRMiMqM6sDb{?f7%t&`j_Eu2>;0_<};8_q_#t{Kh%N zncRCcY5=iQ5~mz#SNd z?Ox+2@FzGQt3z9HR(4wXcSK*{nbR)c8d_hbM&DIeHr($FoiROXZvU zZPbCEjDs0qw>yq+GVz4=!wQR%1va5Fo=<{xb-d7V9ej^7fqdf;>HzJ<@o^{K&Nx`2 z#5>|%+#f(b=YI-HD0qSb>Id#`9Bie;FT(#zRtVyyYQWqep!ySx+nM^;;DouMK=HZw zKAX=Hxzjkt=m|lCz8Ww$@Mw`eYCPRE_%z<)#9uPL+{9nS4Vsu4p#EFNElm79+}DX8 zG@c%u|LNg36g+JcGT2h?i?9Z+8#7xu_4Dv^xU!jGOS}ay)<#FX9lpfe zL!}u!$2bxEGD$)&3Yv5O0`-Hfc98L4)8M7}CgL2gf(FOpQ_N+$n!sdys<}*8o)__> zxUQ4`9Oib0@&M`mF0)HKNWJApnM3IV)an|36EtgG97B=Kk)*`l{uiS zbzB#}=eQw0)-n+`P)I?22D-8h7U3?Ad*D%y`{8+x2V*?8`p0FaTtbMK zIKB(({bz1wFbC=0N(#u%P0nGu_ZVjG%j0V?Z=uWmBIY2J%PM9Gq=AV87#U@d<1va12-GmPp&-Kd=Va(dkwVrr*uQ(wI&Ju7pc* zb>q|URHuIPyP5y#6zKe{20D{qhdhu6;|;{yoA@x?KGVyM1(+wW%iFQ=fVNw|}Q!;XF2szMll5KqS?CjSxqlH)blJ1LAmi%W2+$$u5E zbo_RLg3RnNVLu+__lUYuPb&*06thM7Paeiz#gy^OONKF7|$ zHrxs)H|h*;2e!jfX$icKHDXebpP=9q3V7>W-oPQe7TY=e2HOFF)WA>Jj@Kjqi8Xu< z$AVxHXWzr^__&&J9o!My89EJ5$6BQcHPDoTc@)$&6`J9dSU;I4-T~XOSmYk^onEev zR`MYEzR;uO6>Jk`iB839R-297%kXZ-404#up$hHk)yA^y6lA? zVs})kIDEv_!=?=%f6eH!l0Rb4XO&e+i%-q0GOoorCFcwqIA!?6t0#;rn~@d2wo=`3 zEe2iKtz?)JnA(5%$SX%rE&K75_!IT3h83m`>v5s~K(qLQ?DC1_H;*5#Qg+%|@q5#& zIfTa|6OGyYpLz13(X?$PdwRTnT6%FS|MOo-dF6Vgv~ANW z+58i;+x1; zbZd;0^Y0UQX8yV_Vup#sVutoZu0m4%+B&Z-eZ!>=yWw^solurLilWNJiF|Y zz46<#GTXIln_Oi6`TOHp{wtrv&kWlyqwJ5&jH1?UlJ#;ArYwc$zSL4ERs(DjT6m|F z`QOBsWMvi=v+A~-T<}R*&QI~%Sdk`FFLwQO1Cf?KlE+qEfgx2k_Ury#kG%4XLn zs7S}!4NtCxVW*lvu=4!UIy8BrZo%=)^pQnoJvC+B?Q2jlFw;M?X?E4Jv-1m@r)3ni zYMY$zPWc60oIZ7FTu`y>vnB;UX0p2kv$3aaWwU}88m6}y?f>vsd{0@c{sqe`W)_XK zJI}+H77W!o50?M#vbReM+G{Hb7VGY^kH-|m*;vQ4*VJ~GeK5YDQC4Q#(XGwy^2U^c zv$N7Wv<{YX*+(`o=XcF7IO^|ywxA%rsJ-9%M>_Gw z`hw<6W<=ZMT)h55L2u@<4ZDAEbop{~!JsUE@<#>llvRGMpnj&G_hvzfpL1P&y`Q(M zpk;b%vur5ttc{kfC8*ctU7S%gDp(7<%g)(bFd!=}*wuHJjrpvgB$Kfb9z0~5T5+(T zIcvf6;h{qX)icYUIZ}|%t~Tb3WXD#2T~L&j*=7_6l3)T)9W7{$M~^XH_gld~vNJ|c z8RoN&yC-{iph96$M!VK$Bp1rzlL|-DrQ*>^o>sN6BQsuPCR$jtkmXrq_Uy8}dW9^( z(Ib-!zj1D1OJojnjhhtygGJxAIN4D3W`()TdXZh+nQaQs#%HuQJ*&~aa70%68D>SD z+o|x6jIyrX3JW>L7AMz1r;@^EnPt2GX4AqW&i45*eJ8?zA5pBG(N^J)iItx zNoLs-0}Gp{rH>q$T$qmyE}S0h{J|mqry+$LlgF^?g6Xy$S$I6N%FleYwt7D|e{+J( z_PdTPY~=SJTbS+dsTIrg$Br$`Nng_1zkY0C!>nDc8E3~|F}AQlrQjWNTP{w0+<%== zdaSMg-Ppn=S>Loz^Gf}?;|d#9=rflQG>7=z#uYZKuy}t3Z^kkI3jI50Z??DjE&ne4 zd(Wd4y)}9M3;a84#?GeRh5qMMt+J^%aGU(lame c2VYUxBt7>ce-?l1beT}-tt8XF(#${p4||P1hyVZp diff --git a/User/Module/Chassis.c b/User/Module/Chassis.c index bbcc4ec..d1ea42d 100644 --- a/User/Module/Chassis.c +++ b/User/Module/Chassis.c @@ -81,13 +81,17 @@ int8_t Chassis_init(Chassis_t *c,const Chassis_Param_t *param,float target_freq) return CHASSIS_OK; } - +fp32 gyro_kp=1.0f; +fp32 PIAN=0; void Chassis_speed_calculate(Chassis_t *c,fp32 Vx,fp32 Vy,fp32 Vw) //底盘逆运动学的解算, { fp64 Nor_Vx,Nor_Vy;//归一化后的数据 normalize_vector(Vx,Vy,&Nor_Vx,&Nor_Vy); - +// c->hopemotorout.OmniSpeedOut[0] = -Vx+Vy+Vw;//右前 +// c->hopemotorout.OmniSpeedOut[1] = -Vx-Vy+Vw;//右后 +// c->hopemotorout.OmniSpeedOut[2] = Vx-Vy+Vw;//左后 +// c->hopemotorout.OmniSpeedOut[3] = Vx+Vy+Vw;//左前 // c->hopemotorout.OmniSpeedOut[0] = -Nor_Vx+Nor_Vy+Vw + c->pos088 .bmi088.gyro.z;//右前 // c->hopemotorout.OmniSpeedOut[1] = -Nor_Vx-Nor_Vy+Vw + c->pos088 .bmi088.gyro.z;//右后 // c->hopemotorout.OmniSpeedOut[2] = Nor_Vx-Nor_Vy+Vw + c->pos088 .bmi088.gyro.z;//左后 @@ -96,6 +100,14 @@ void Chassis_speed_calculate(Chassis_t *c,fp32 Vx,fp32 Vy,fp32 Vw) //底盘逆 c->hopemotorout.OmniSpeedOut[1] = -Nor_Vx-Nor_Vy+Vw ;//右后 c->hopemotorout.OmniSpeedOut[2] = Nor_Vx-Nor_Vy+Vw ;//左后 c->hopemotorout.OmniSpeedOut[3] = Nor_Vx+Nor_Vy+Vw ;//左前 + +// if(!Vw){ +// PIAN = jiuzheng(c->pos088 .imu_eulr .yaw ); +// } +// c->hopemotorout.OmniSpeedOut[0] += PIAN ;//右前 +// c->hopemotorout.OmniSpeedOut[1] += PIAN ;//右后 +// c->hopemotorout.OmniSpeedOut[2] += PIAN ;//左后 +// c->hopemotorout.OmniSpeedOut[3] += PIAN ;//左前 } @@ -173,32 +185,32 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) break; - case AUTO_PICK: //自动视觉 + case AUTO_NAVI_Pitch: //自动视觉 - c->move_vec.Vx =ctrl->Vx*6000 ; - c->move_vec.Vy =ctrl->Vy *6000; - c->move_vec .Vw = -ctrl->cmd_pick .posx; + c->move_vec.Vw =0; + c->move_vec.Vy =0; + c->move_vec.Vx =0 ; - if(abs_value(ctrl ->cmd_pick .posx )>20) - { - c->move_vec.Vw =PID_calc(&(c->pid.chassis_PICKWzPID_HIGN),(c->move_vec .Vw) ,0); - - } - else if(abs_value(ctrl ->cmd_pick .posx )<0.1) - { - c->move_vec.Vw =0; - } - else - c->move_vec.Vw =PID_calc(&(c->pid.chassis_PICKWzPID_LOW),(c->move_vec .Vw) ,0); +// if(abs_value(ctrl ->cmd_pick .posx )>20) +// { +// c->move_vec.Vw =PID_calc(&(c->pid.chassis_PICKWzPID_HIGN),(c->move_vec .Vw) ,0); +// +// } +// else if(abs_value(ctrl ->cmd_pick .posx )<0.1) +// { +// c->move_vec.Vw =0; +// } +// else +// c->move_vec.Vw =PID_calc(&(c->pid.chassis_PICKWzPID_LOW),(c->move_vec .Vw) ,0); - c->move_vec.Vw =LowPassFilter2p_Apply(&(c->filled[1]),c->move_vec.Vw); +// c->move_vec.Vw =LowPassFilter2p_Apply(&(c->filled[1]),c->move_vec.Vw); - - c->vofa_send[0]=c->move_vec.Vw; - c->vofa_send[1]=-ctrl->cmd_pick .posx; - +// +// c->vofa_send[0]=c->move_vec.Vw; +// c->vofa_send[1]=-ctrl->cmd_pick .posx; +// @@ -232,17 +244,54 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) } -// c->vofa_send[0]=c->pos088.bmi088.gyro.x; -// c->vofa_send[1]=c->pos088.bmi088.gyro.y; -// c->vofa_send[2]=c->pos088.bmi088.gyro.z; -// c->vofa_send[3]=c->pos088.bmi088.accl.x; -// c->vofa_send[4]=c->pos088.bmi088.accl.y; -// c->vofa_send[5]=c->pos088.bmi088.accl.z; + +// c->vofa_send[0]=c->pos088.bmi088.gyro.z; + +// c->vofa_send[1]=c->motorfeedback .rotor_rpm3508 [0]; +// c->vofa_send[2]=c->motorfeedback .rotor_rpm3508 [1]; +// c->vofa_send[3]=c->motorfeedback .rotor_rpm3508 [2]; +// c->vofa_send[4]=c->motorfeedback .rotor_rpm3508 [3]; +// +// c->vofa_send[0]=c->hopemotorout .OmniSpeedOut [0]; +// c->vofa_send[1]=c->hopemotorout .OmniSpeedOut [0]; +//// c->vofa_send[2]=c->hopemotorout .OmniSpeedOut [2]; +// c->vofa_send[3]=c->hopemotorout .OmniSpeedOut [3]; + +//// c->vofa_send[4]=c->motorfeedback .rotor_rpm3508 [0]; +// c->vofa_send[0]=c->motorfeedback .rotor_rpm3508 [0]; +//// c->vofa_send[6]=c->motorfeedback .rotor_rpm3508 [2]; +// c->vofa_send[2]=c->motorfeedback .rotor_rpm3508 [3]; +// +// c->vofa_send[5]=c->pos088 .imu_eulr .yaw ; return CHASSIS_OK; } + pid_type_def pid; + pid_param_t pid_param={ + .p = 0.50f, + .i = 0.0f, + .d = 0.0f, + .i_limit = 50.0f, + .out_limit = 100.0f + }; +fp32 jiuzheng(fp32 yaw) +{ + static fp32 pian_yaw=0; + static fp32 shang_yaw=0; + static int is=0; - + + if(is==0) + { + PID_init (&pid,PID_POSITION ,&pid_param); + is=1; + } + + pian_yaw+= (yaw - shang_yaw); + shang_yaw=yaw ; + + return PID_calc(&pid,pian_yaw,0); +} diff --git a/User/Module/Chassis.h b/User/Module/Chassis.h index a6c3e11..919bb3e 100644 --- a/User/Module/Chassis.h +++ b/User/Module/Chassis.h @@ -190,6 +190,7 @@ int8_t Chassis_UpdateFeedback(Chassis_t *c, const CAN_t *can); int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out); +fp32 jiuzheng(fp32 yaw); diff --git a/User/Module/config.c b/User/Module/config.c index 9c56d78..65a65cd 100644 --- a/User/Module/config.c +++ b/User/Module/config.c @@ -110,7 +110,7 @@ static const ConfigParam_t param ={ }, /*投球*/ .PitchConfig_Config = { - .m2006_init_angle =-170, + .m2006_init_angle =-90, .m2006_trigger_angle =0, .go1_init_position = -50, .go1_Receive_ball = -5, //偏下 diff --git a/User/Module/up.c b/User/Module/up.c index 5bd5c88..df7dcd1 100644 --- a/User/Module/up.c +++ b/User/Module/up.c @@ -49,6 +49,8 @@ int8_t up_init(UP_t *u,const UP_Param_t *param,float target_freq) } u->go_cmd =u->param ->go_cmd ; + LowPassFilter2p_Init(&(u->filled[0]),target_freq,100.0f); + // 初始化上层状态机 if (!u->DribbleContext .is_initialized) { //检查是否为第一次运行状态机,运球 @@ -97,6 +99,7 @@ int8_t UP_UpdateFeedback(UP_t *u, const CAN_t *can, CMD_t *c) { u->DribbleContext .DribbleConfig .light_ball_flag =HAL_GPIO_ReadPin(LIGHT_C_GPIO_Port ,LIGHT_C_Pin); u->DribbleContext .DribbleConfig .light_3508_flag =HAL_GPIO_ReadPin(LIGHT_B_GPIO_Port ,LIGHT_B_Pin); + return 0; } @@ -257,7 +260,7 @@ int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c) static int is_pitch=1; - + switch (c->CMD_CtrlType ) { case RCcontrol: //在手动模式下 @@ -283,29 +286,31 @@ int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c) } u->motor_target .Dribble_translate_M3508_angle =u->DribbleContext .DribbleConfig .m3508_translate_angle; u->DribbleContext .DribbleState = DRIBBLE_PREPARE; //重置最初状态 + + break; case Pitch : -// if (u->PitchContext .PitchState ==PITCH_PREPARE) -// { -// u->PitchContext .PitchState=PITCH_START;//置标志位用于启动投篮 -// } - -// Pitch_Process(u,out); if (u->PitchContext .PitchState ==PITCH_PREPARE) { - u->CoContext .CoState =CoTRANSLATE_OUT; - } - Co_Process(u,out); + u->PitchContext .PitchState=PITCH_START;//置标志位用于启动投篮 + } + + Pitch_Process(u,out); +// if (u->PitchContext .PitchState ==PITCH_PREPARE) +// { +// u->CoContext .CoState =CoTRANSLATE_OUT; +// } +// Co_Process(u,out); break ; case UP_Adjust: //测试用 - u->PitchContext.PitchConfig.go1_init_position += c->Vx ; + u->PitchContext.PitchConfig.go1_Receive_ball += c->Vx ; u->PitchContext.PitchConfig.Pitch_angle += c->Vy/100; - u->motor_target .go_shoot=u->PitchContext.PitchConfig.go1_init_position; + u->motor_target .go_shoot=u->PitchContext.PitchConfig.go1_Receive_ball; u->motor_target .Shoot_Pitch_angle=u->PitchContext.PitchConfig.Pitch_angle; break ; case Dribble: @@ -323,7 +328,32 @@ int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c) default: break; } + case AUTO: + switch(c-> CMD_mode) + { + case AUTO_NAVI_Pitch: + u->PitchContext .PitchConfig .go1_Receive_ball=LowPassFilter2p_Apply(&u->filled[0],c->pos); + if (u->PitchContext .PitchState ==PITCH_PREPARE) + { + u->PitchContext .PitchState=PITCH_START;//置标志位用于启动投篮 + } + /*根据距离实时计算所需pos*/ + +// u->PitchContext .PitchConfig .go1_release_threshold=c->pos; + Pitch_Process(u,out); + break ; + + case AUTO_NAVI: + u->motor_target .Shoot_M2006_angle =u->PitchContext .PitchConfig .m2006_init_angle ; + + u->PitchContext .PitchState = PITCH_PREPARE; + + + + break ; + + } return 0; @@ -372,14 +402,14 @@ int8_t Pitch_Process(UP_t *u, CAN_Output_t *out) u->PitchContext .PitchState=PITCH_LAUNCHING; } } - - - break ; - case PITCH_LAUNCHING: //等待发射 + case PITCH_LAUNCHING: //等待发射 + u->PitchContext .PitchState=PITCH_COMPLETE; break ; case PITCH_COMPLETE: //发射完成 + + break ; diff --git a/User/bsp/bsp_usart.c b/User/bsp/bsp_usart.c index 4843fac..e40ddb8 100644 --- a/User/bsp/bsp_usart.c +++ b/User/bsp/bsp_usart.c @@ -9,9 +9,9 @@ static BSP_UART_t UART_Get(UART_HandleTypeDef *huart) { if (huart->Instance == USART3) return BSP_UART_REMOTE; else if (huart->Instance == USART1) - return BSP_UART_NUC; - else if (huart->Instance == USART6) return BSP_UART_RS485; + else if (huart->Instance == USART6) + return BSP_UART_NUC; /* else if (huart->Instance == USARTX) return BSP_UART_XXX; @@ -95,9 +95,9 @@ UART_HandleTypeDef *BSP_UART_GetHandle(BSP_UART_t uart) { case BSP_UART_REMOTE: return &huart3; case BSP_UART_RS485: - return &huart6; - case BSP_UART_NUC: return &huart1; + case BSP_UART_NUC: + return &huart6; /* case BSP_UART_XXX: return &huartX; diff --git a/User/bsp/bsp_usart.h b/User/bsp/bsp_usart.h index 4974127..bff764a 100644 --- a/User/bsp/bsp_usart.h +++ b/User/bsp/bsp_usart.h @@ -13,6 +13,7 @@ typedef enum { BSP_UART_REMOTE, BSP_UART_RS485, BSP_UART_NUC, + BSP_UART_VOFA, /* BSP_UART_XXX, */ BSP_UART_NUM, BSP_UART_ERR, diff --git a/User/bsp/pwm.c b/User/bsp/pwm.c index d2bd484..eba9c86 100644 --- a/User/bsp/pwm.c +++ b/User/bsp/pwm.c @@ -19,11 +19,11 @@ int8_t BSP_PWM_Start(BSP_PWM_Channel_t ch) { return BSP_OK; } + uint16_t pulse; int8_t BSP_PWM_Set(BSP_PWM_Channel_t ch, float duty_cycle) { if (duty_cycle < 0.0f) duty_cycle = 0.f; - uint16_t pulse; /* 通过PWM通道对应定时器重载值和给定占空比,计算PWM周期值 */ switch (ch) { case BSP_PWM_IMU_HEAT: @@ -38,7 +38,9 @@ int8_t BSP_PWM_Set(BSP_PWM_Channel_t ch, float duty_cycle) { break; } } else { -// BSP_PWM_Stop(ch); + pulse =0; + __HAL_TIM_SET_COMPARE(&htim10, TIM_CHANNEL_1, pulse); + //BSP_PWM_Stop(ch); } return BSP_OK; } diff --git a/User/device/cmd.c b/User/device/cmd.c index 899aad9..eec5297 100644 --- a/User/device/cmd.c +++ b/User/device/cmd.c @@ -102,6 +102,8 @@ int8_t CMD_ParseNuc(CMD_t *cmd,CMD_NUC_t *n){ cmd->cmd_MID360.posx = n->navi.vx; cmd->cmd_MID360.posy = n->navi.vy; cmd->cmd_MID360.posw = n->navi.wz; + + cmd->pos =n->navi .pos ; break; case PICK : @@ -155,7 +157,7 @@ int8_t CMD_DR16(CMD_t *cmd,const CMD_RC_t *rc) { if(rc->dr16.sw_r ==CMD_SW_MID) cmd ->CMD_mode =Normal; //左中,右中,无模式 - if(rc->dr16.sw_r ==CMD_SW_DOWN) cmd ->CMD_mode =AUTO_PICK; //左中,右下,视觉 + if(rc->dr16.sw_r ==CMD_SW_DOWN) cmd ->CMD_mode =AUTO_NAVI_Pitch; //左中,右下,视觉 } else if(rc->dr16.sw_l==CMD_SW_DOWN) @@ -189,8 +191,9 @@ int8_t CMD_LD(CMD_t *cmd,const CMD_RC_t *rc){ if(cmd ->CMD_CtrlType ==AUTO){ /*自动下的*/ - if(rc->LD.key_E ==CMD_SW_DOWN ) cmd ->CMD_mode =AUTO_NAVI; - else if(rc->LD.key_E ==CMD_SW_UP) cmd ->CMD_mode =AUTO_PICK; + if(rc->LD.key_E ==CMD_SW_DOWN ) cmd ->CMD_mode =Normal; + else if(rc->LD.key_E ==CMD_SW_UP) cmd ->CMD_mode =AUTO_NAVI_Pitch; + else if(rc->LD .key_E ==CMD_SW_MID ) cmd ->CMD_mode =AUTO_NAVI; else cmd ->CMD_mode =Normal ; } diff --git a/User/device/cmd.h b/User/device/cmd.h index c5082ab..52d5703 100644 --- a/User/device/cmd.h +++ b/User/device/cmd.h @@ -9,6 +9,7 @@ #define MID (0x09) #define PICK (0x06) +#define NUC (0x08) typedef enum{ RCcontrol,//遥控器控制,左按键上,控制上层 @@ -23,7 +24,7 @@ typedef enum{ Normal, //无模式 AUTO_NAVI, - AUTO_PICK, + AUTO_NAVI_Pitch, UP_Adjust,//上层调整 @@ -41,6 +42,11 @@ typedef struct { fp32 vx; fp32 vy; fp32 wz; + + fp32 pos; + fp32 angle; + char flag; + }navi; struct { @@ -52,6 +58,8 @@ typedef struct { { fp32 angle; }sick_cali; + + } CMD_NUC_t; /* 拨杆位置 */ typedef enum { @@ -122,6 +130,8 @@ typedef struct { fp32 key_ctrl_l; fp32 key_ctrl_r; + fp32 pos;//雷达反馈go位置 + fp32 Vx; fp32 Vy; fp32 Vw; diff --git a/User/device/nuc.c b/User/device/nuc.c index 05bc64a..57fce4c 100644 --- a/User/device/nuc.c +++ b/User/device/nuc.c @@ -8,6 +8,7 @@ static osThreadId_t thread_alert; uint8_t nucbuf[31]; + static void NUC_IdleCallback(void) { osThreadFlagsSet(thread_alert,SIGNAL_NUC_RAW_REDY); detect_hook(NUC_TOE); @@ -26,6 +27,35 @@ int8_t NUC_StartReceiving() { sizeof(nucbuf)) == HAL_OK) return DEVICE_OK; return DEVICE_ERR; +} + char SendBuffer[19]; + +int8_t NUC_StartSending(fp32 *data) { + + union + { + float x[4]; + char data[16]; + }instance; + + + for (int i = 0; i < 4; i++) { + instance.x[i] = data[i]; + } + + SendBuffer[0] = 0xFC; //发送ID + SendBuffer[1] = 0x01; //控制帧 + for(int i = 2; i < 18; i++) + { + SendBuffer[i] = instance.data[i-2]; + } + SendBuffer[18] = 0xFD; //结束符 + + if (HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_NUC), + (uint8_t *)SendBuffer, + sizeof(SendBuffer)) == HAL_OK) + return DEVICE_OK; + return DEVICE_ERR; } int8_t NUC_Restart(void) { __HAL_UART_DISABLE(BSP_UART_GetHandle(BSP_UART_NUC)); @@ -42,8 +72,8 @@ int8_t NUC_RawParse(CMD_NUC_t *n){ if(n ==NULL) return DEVICE_ERR_NULL; union { - float x[3]; - char data[12]; + float x[5]; + char data[20]; }instance; if(nucbuf[0]!=HEAD) goto error; //发送ID不是底盘 else{ @@ -51,7 +81,34 @@ int8_t NUC_RawParse(CMD_NUC_t *n){ n->ctrl_status =nucbuf[2]; switch (n->status_fromnuc) { - case MID://控制帧0x09 +// case MID://控制帧0x09 +// /* 协议格式 +// 0xFF HEAD +// 0x09 控制帧 +// 0x01 相机帧 +// vx fp32 +// vy fp32 +// wz fp32 +// 0xFE TAIL +// */ +//// if(nucbuf[15]!=TAIL)goto error; +// instance.data[3] = nucbuf[6]; +// instance.data[2] = nucbuf[5]; +// instance.data[1] = nucbuf[4]; +// instance.data[0] = nucbuf[3]; +// n->navi.vx = instance.x[0]; // +// instance.data[7] = nucbuf[10]; +// instance.data[6] = nucbuf[9]; +// instance.data[5] = nucbuf[8]; +// instance.data[4] = nucbuf[7]; +// n->navi.vy = instance.x[1];// +// instance.data[11] = nucbuf[14]; +// instance.data[10] = nucbuf[13]; +// instance.data[9] = nucbuf[12]; +// instance.data[8] = nucbuf[11]; +// n->navi.wz = instance.x[2];// +// break; + case MID ://控制帧0x08 /* 协议格式 0xFF HEAD 0x09 控制帧 @@ -61,7 +118,7 @@ int8_t NUC_RawParse(CMD_NUC_t *n){ wz fp32 0xFE TAIL */ - if(nucbuf[15]!=TAIL)goto error; + if(nucbuf[24]!=TAIL)goto error; instance.data[3] = nucbuf[6]; instance.data[2] = nucbuf[5]; instance.data[1] = nucbuf[4]; @@ -77,53 +134,21 @@ int8_t NUC_RawParse(CMD_NUC_t *n){ instance.data[9] = nucbuf[12]; instance.data[8] = nucbuf[11]; n->navi.wz = instance.x[2];// + instance.data[15] = nucbuf[18]; + instance.data[14] = nucbuf[17]; + instance.data[13] = nucbuf[16]; + instance.data[12] = nucbuf[15]; + n->navi.pos = instance.x[3];// + instance.data[19] = nucbuf[22]; + instance.data[18] = nucbuf[21]; + instance.data[17] = nucbuf[20]; + instance.data[16] = nucbuf[19]; + n->navi.angle = instance.x[4];// + + n->navi.flag = nucbuf[23];// break; - case PICK: - /* 协议格式 - 0xFF HEAD - 0x0X 控制帧 - 0x01 相机帧 - cmd 8位 - dis 相机深度值 - posx 相机yaw轴值 - posy 相机pitch轴值 - 0xFE TAIL - */ -// if(nucbuf[15]!=TAIL)goto error; - instance.data[3] = nucbuf[6]; - instance.data[2] = nucbuf[5]; - instance.data[1] = nucbuf[4]; - instance.data[0] = nucbuf[3]; - n->pick.posx = instance.x[0]; //距离球中心的角度值 - instance.data[7] = nucbuf[10]; - instance.data[6] = nucbuf[9]; - instance.data[5] = nucbuf[8]; - instance.data[4] = nucbuf[7]; - n->pick.posy = instance.x[1];// 相机yaw轴 - instance.data[11] = nucbuf[14]; - instance.data[10] = nucbuf[13]; - instance.data[9] = nucbuf[12]; - instance.data[8] = nucbuf[11]; - n->pick.posw= instance.x[2];// 暂未用到 - break; -// case SICK_CAIL: -// if(nucbuf[15]!=TAIL)goto error; -// instance.data[3] = nucbuf[14]; -// instance.data[2] = nucbuf[13]; -// instance.data[1] = nucbuf[12]; -// instance.data[0] = nucbuf[11]; -// n->sick_cali.angle = instance.x[0]; // -// instance.data[7] = nucbuf[10]; -// instance.data[6] = nucbuf[9]; -// instance.data[5] = nucbuf[8]; -// instance.data[4] = nucbuf[7]; -// n->sick_cali.isleft = instance.x[1];// -// instance.data[11] = nucbuf[14]; -// instance.data[10] = nucbuf[13]; -// instance.data[9] = nucbuf[12]; -// instance.data[8] = nucbuf[11]; -// n->pick.posw= instance.x[2];// 暂未用到 -// break; + + } return DEVICE_OK; } diff --git a/User/device/nuc.h b/User/device/nuc.h index 9b9cc4b..3f7c0d1 100644 --- a/User/device/nuc.h +++ b/User/device/nuc.h @@ -23,12 +23,13 @@ typedef struct { NUC_UpPackageMCU_t to_nuc; //发送的数据协议 uint8_t status;//控制状态 - uint8_t pit_status;//pit相机朝向 + } NUC_t; int8_t NUC_Init(NUC_t *nuc); int8_t NUC_StartReceiving(void); +int8_t NUC_StartSending(fp32 *data) ; bool_t NUC_WaitDmaCplt(void); int8_t NUC_RawParse(CMD_NUC_t *n); int8_t NUC_HandleOffline(CMD_NUC_t *cmd); diff --git a/User/device/rc.c b/User/device/rc.c index a8cffe5..bebd452 100644 --- a/User/device/rc.c +++ b/User/device/rc.c @@ -99,10 +99,25 @@ int8_t LD_ParseRaw( LD_raw_t *raw, LD_Data_t *LD) raw->ch[3] = 0.5*(raw->ch[3]); //w - raw->map_ch[0]=map_fp32(raw->ch[0],-719,680,-1,1); - raw->map_ch[1]=map_fp32(raw->ch[1],-653,746,-1,1); - raw->map_ch[2]=map_fp32(raw->ch[2],95,1482,0,1); - raw->map_ch[3]=map_fp32(raw->ch[3],-317,375,-1,1); +if (raw->ch[0] < 0) + raw->map_ch[0] = map_fp32(raw->ch[0], -696, 2, -1, 0); +else + raw->map_ch[0] = map_fp32(raw->ch[0], 2, 704, 0, 1); + +// ch[1] +if (raw->ch[1] < 0) + raw->map_ch[1] = map_fp32(raw->ch[1], -638, 5, -1, 0); +else + raw->map_ch[1] = map_fp32(raw->ch[1], 5, 762, 0, 1); + + raw->map_ch[2] = map_fp32(raw->ch[2], 2, 1377, 0, 1); + +// ch[3] +if (raw->ch[3] < 0) + raw->map_ch[3] = map_fp32(raw->ch[3], -344, 0, -1, 0); +else + raw->map_ch[3] = map_fp32(raw->ch[3], 0, 348, 0, 1); + /*非线性映射*/ raw->map_ch[0]=expo_map(raw->map_ch[0],0.7f); diff --git a/User/device/vofa.c b/User/device/vofa.c index 248e161..d1f8b7f 100644 --- a/User/device/vofa.c +++ b/User/device/vofa.c @@ -28,13 +28,14 @@ void vofa_tx_main(float *data) /*在下面使用对应的串口发送函数*/ +// CDC_Transmit_FS( ( uint8_t *)fdata, sizeof(fdata)); +// osDelay(1); +// CDC_Transmit_FS( tail, 4); // HAL_UART_Transmit_DMA(&huart1, ( uint8_t *)fdata, sizeof(fdata)); // osDelay(1); -// HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_VOFA), tail, 4); -// osDelay(1); - CDC_Transmit_FS( ( uint8_t *)fdata, sizeof(fdata)); - osDelay(1); -// CDC_Transmit_FS( tail, 4); +// HAL_UART_Transmit_DMA(&huart1, tail, 4); +// osDelay(1); + } diff --git a/User/task/nuc_task.c b/User/task/nuc_task.c index 98d9c81..cbe6d3d 100644 --- a/User/task/nuc_task.c +++ b/User/task/nuc_task.c @@ -11,7 +11,7 @@ static CMD_NUC_t cmd_fromnuc; #endif - +fp32 send[4]={11.0f,45.0,1.f,4.0f}; void Task_nuc(void *argument){ (void)argument; /**/ @@ -29,6 +29,7 @@ void Task_nuc(void *argument){ task_runtime.stack_water_mark.nuc= osThreadGetStackSpace(osThreadGetId()); #endif NUC_StartReceiving(); + NUC_StartSending(send); if (NUC_WaitDmaCplt()){ NUC_RawParse(&cmd_fromnuc); } diff --git a/User/task/up_task.c b/User/task/up_task.c index c784f32..6422d55 100644 --- a/User/task/up_task.c +++ b/User/task/up_task.c @@ -70,7 +70,6 @@ void Task_up(void *argument) ALL_Motor_Control(&UP,&UP_CAN_out); osDelay(1); - /*can上设备数据获取*/ osMessageQueueGet(task_runtime.msgq.can.feedback.UP_CAN_feedback, &can, NULL, 0); @@ -92,8 +91,8 @@ void Task_up(void *argument) osMessageQueuePut(task_runtime.msgq.can.output.shoot5065 ,&UP_CAN_out.chassis5065, 0, 0); - vofa_send [0]=UP.vofa_send [0]; - vofa_send [1]=UP.vofa_send [1]; +// vofa_send [0]=UP.vofa_send [0]; +// vofa_send [1]=UP.vofa_send [1]; vofa_tx_main (vofa_send); tick += delay_tick;