From 40ca2de03870e52768d55866c673821ce0bd9692 Mon Sep 17 00:00:00 2001 From: ZHAISHUI04 <3150778793@qq.com> Date: Wed, 2 Jul 2025 20:42:48 +0800 Subject: [PATCH] =?UTF-8?q?sick=E6=94=B9pid=EF=BC=8C=E8=BF=9C=E8=B7=9D?= =?UTF-8?q?=E7=A6=BB=E6=8A=96?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- MDK-ARM/.vscode/keil-assistant.log | 4 ++ MDK-ARM/R2.uvoptx | 30 ++++++++++ MDK-ARM/R2/R2.axf | Bin 2868232 -> 2871736 bytes User/Module/Chassis.c | 91 ++++++++++++++++++----------- User/Module/Chassis.h | 7 ++- User/Module/config.c | 83 +++++++++++++++++++++----- User/Module/up.c | 16 ++--- 7 files changed, 171 insertions(+), 60 deletions(-) diff --git a/MDK-ARM/.vscode/keil-assistant.log b/MDK-ARM/.vscode/keil-assistant.log index 7382f29..80658bb 100644 --- a/MDK-ARM/.vscode/keil-assistant.log +++ b/MDK-ARM/.vscode/keil-assistant.log @@ -481,3 +481,7 @@ [info] Log at : 2025/6/28|01:22:24|GMT+0800 +[info] Log at : 2025/6/30|18:03:06|GMT+0800 + +[info] Log at : 2025/7/1|14:01:22|GMT+0800 + diff --git a/MDK-ARM/R2.uvoptx b/MDK-ARM/R2.uvoptx index eb773dd..612ed0e 100644 --- a/MDK-ARM/R2.uvoptx +++ b/MDK-ARM/R2.uvoptx @@ -170,6 +170,36 @@ 1 error_code + + 3 + 1 + UP,0x0A + + + 4 + 1 + chassis,0x0A + + + 5 + 1 + \\R2\../User/task/chassis_task.c\chassis.sick_cali.sickparam + + + 6 + 1 + cmd,0x0A + + + 7 + 1 + nucbuf,0x0A + + + 8 + 1 + cmd_fromnuc + 0 diff --git a/MDK-ARM/R2/R2.axf b/MDK-ARM/R2/R2.axf index cf40bd0cbe9c9c547f60fd478d943675529fcf92..6593a1598d0c0c1b152345195c7b4d5f2c1d716e 100644 GIT binary patch delta 131023 zcmeFa33yb+wlG>%dw2IvCxp(NbdpXd1PEaY5FpGUK$9>g%rYhrAV7dH3Wy|Nz%Ux! zU?Curs3=i`0UBfqipo*+1VrU1NI(=&5;qF;kRINuy}Of$=iGb$_x|_(^S*oW+k4kq zwQAL>RaL82t*VYCCGX+muf2y$qdJEFy){aKhww<1jEo4Q1f)YvQC>MRw&IX5dNUHD zi;<88->g_9e0}T1VWIv{Q4*Uq?JK{&d_wYjToshYsuei6? ze4>|X`)aq=OxBmfmwyyippn|RbhWzKNu~hlsI%{Vz3-lyw!S0p>ssrijqbkpBYbtz zXtz+S)0Wq!Ly6{#_(yLqO#NLQYcyf$AL9JbNYbTF+!T6j@@yNl8kKO!s5=_ej2jdf z3yqP!wgU|K-J2MGxa97LV+EtXBmy4A2(sSsmp0idI)?v%@oq6d zZz*IV%n#(!I@`DOgf5EpPv@jMd-@3+r;GK4w5Cpo)q*fhq=jxA>jRkka&CZ04QZ>L zkLBdtX>QgalFGzIJW2I7i!(Nnwn1JYNQ9aZBX`WNmMWvH%PH}wHC~Otqi)!f~ z=Rk45DTfDX67AycsI;DfT~&?ZaBNdR5j#4I&YGkm9`T4NIQojlp?J=v{2*)45icjE_mz4*vT zlZn*b%0@yt&xSThCsM~J;6xd|TAv?h6)R(-@EGxWY>aAAo$hp%h~r=axkW>qK{XN( zR-hIF| z2Qs=Xa~*1EvX3ofkQ%0++p`@}+LeIKY7(rAh||x-7X|jrd#h zFkCBYTKq&d*NL?)j*yOZ6$e_T;Z7&)d#$9HrA@EG+qNq;8Za=~ zTK@MosVXVkQC#D%-BWW13{FvYQOzhVicS4}NG8r=a8=DYb zwzwutyA33|QS*@p4gpvV@L3NWs_jy}twsRM$tOyfpD0mLUn1I5;=TG3!PVVOtxQH! z6Dh{Y+J_3C!U^aSbhiY3G_Rx3HBo}3U+@fI!rU=;F|dbs!0Y}9t(AB+Q_GXN!!F%i=3 z-5H)r*8G!7o)rVy1&v+Sh~ZKXLqFiL2-1w78qx(Ge#ou&=wWsveoWUh>bWSoo+|#M zUG&(*eA-2e4@;74;-p(4|7IQ&frF6yvi{#xeNQ&m)=v;$0PTvu01t9 zJ#te>ck{^oqKnPJCe?dtlH~ERr=}fznF`y$H&m<4(LFV-J$#l!*#r-tMUZap;WO8D zr6vrP-yHpw;F?fak8`wFYC;%7YcwG#Pu$nO6A8D8-?VQ>B7YWzq`k9$m;U55wk>OGq_60ah zh7Zbc1i(#Y7?xou-x6RAgC7+yWN>GI-8ROrQqJ!OutkQi5>yBTS%CPBAs&^=1?&Ld zvE8U?1~VC)5ZOk253tb#4*{F;6~K`mI3M880S@!Pn*jdEW~oKm_iK5WQZvC4aE)MQ zG3u;JetSm1OvN8oCO}aERF_qCuW9Esb5irq-BWee=3K}@#z|nx_NF0}E>7qeU6>(z zO5wGo+NM%JNb7xPnaIKN+6?I5Staq-!7@0rY0;`9fMJu= zc?4mM-7ZGlz?jO68W^h}KMI&d0<%vcPY>w`NS}kW0T^$zmc$BKt!2Ld09w7TBJfvo zIWHf^zfh6ALQLOCzLryKEG;NjQ9 zS_=G(CU=yjvW_o5eP6dxcX}^ki!pD~#l@P!(p{EmVnA|qlEdT7ga1Sey~0jor(AM+1(CC3G{kj39q z69PKZfzGVr-;;YZy^aVrBvXn6&c-bkkNH^4Am#wRi=PA4Y*;Q>#)&R+6~LK z%hC$4x;PH7SM1CcSO#nH1$YXMwyn`_RGIut<+Z6hpvDcp(zAB8sb^dVQ-aB1X;txT z&yxafS**LyUF0o`$#6M7&Rgn5_+pxJfakK4k06B$RwNCWu!rO z$yNX!J8!yT6;v8&m|e^r*`35W#l0h^;wq6F^$cDi7LMB2bS$%!#?9z8z@yjQ6yN;na_lK=gD8p9Wf+?bJr1!-m@+DPyw zPT!SQx4q{Y&T2>HlVu(|94KM&C06Q+LpX8zuIq)=#{w#Ps`8H}#`9JO&vHH$_l=3b zABZQ%48%J{Zfpm$FEXXX0e6z7f$!|#b}#}#6?sCsHF{#Bgx zR6qQ=xbLYD(z8xH{!}^%s}sriHU!m)N#l)pftWS^ABFc_#=O*7z$`O14;GN>^c+^@ z({>Op6NH-*2JAJ`n{^DUw^wH)DXR{Z#yw-qL$3(ZuXeU#IBW_J1U!`TW9>*1kdPo; zV)?#yIUg|I{DF{Pgo+Zv#kVGOB`xjZtqHU7199lYSMUMx&cs+OiawKi1pUof;MrWY zlKWgO-4@4A>e1>$M?xI`K!@{8cFXpuDYvzrBNEnZWbKlav0T zjrLFstrK@ojtXj1hm2WwbVt{f^QPcfe9&&0Bz`gZY>S0XHmuZA1XSuBWNInh$u^0~ zkW))ToZ|aa5jTxZA&1WX2)4PQ)N>Uhv-e@Ly`%Uz zrz1JoQB0g_V4p!#C;POvs!aaX0qIS}7pI2d$cn#B{g#jZ8_X@PZPO~FiIYCEYclY! zsk)+BDTf(+QanBL4qj04dfqmIS61|x(-{}Ox)TW};8_As0SL?J#sXt6k1VUgBQ;Oq zkzwUzo~FF=fo$$pEmeGIR<1{*a-BWpkf-jpo^tA04dvS2vsV0;KL^7WqGIB_L_&(#eqYoPN514V=B>*!Nl&Zco1I+!^*s_aJI|O$q_tw7 zC1Gi^U70X+h*ac^uKp!&mYlQ5l`Z3zI)mzQV_c~+F5l^+Y>m#gl4*0D72B6oVjLzu z_4ExA?GU>!YeRZF#JpwgNUlTNzN`&w-9BD6odni_P`gRHI`QK2y9DO=u@z$s3&2pa zPMB*)zg8jvI;jYu+39k}PqT}O<!^yEy2XT+-7nmOoP*ZIh>7R?ZDoyC%V>*gG=Nvb zSI{f4uf7y$!L`&Ykr;$v4Fg9}0}s+0Yq6HOou$A7aQZ6XhihX2$7xF^u~&^&p9Dmu zH5?N}UkS{aw^<6`D#o<-rl$b&Qq{5$9pnl)4|5*yJTO$jm%tav--3anzBmrYRP-uV z;U;@+u*7ZHQxm6EOQXc$YbW3q;-R(EH1l1;;X2DeF=Sm|&0sm*Oq{eXOw-QF@WJ9U z>qZxLbNU$_mKIJFr;6XTAfgh)LI#j4Xa(o~yj5NaE%g5)HdDnrNyZy^~AOI}Ap zen%|4w;QpLrV$-|zC1XV9JE;WyTp~xI||>a!w`GvmF}<{tdpZaeS1K9KVSn)-5~WU zL{X|U3GD5;QUv>Z0{eXORubeCgBw9ghd(UQaq`Zeyww`8%k4VAGHSk*QMLfwe0$Op zl<|PgwGV%2ECkjFhzVo;RurJ00(4QT!h&IuTwy5W43R7JG7bbxKRZ*58dO3Y?EM=w zK^3col)a9<@5pc%q<*hs?;CZRa^z7RiXy29iA&d~Y2Jk1v|AR6XV-_3#ZK|+dPCGnug+LLGaFH*(ew7<7RGL8?p6<=D4evwIOD5E4h5A z8`_fTQ|j|p2;{#b1$oAp6{LF zmm89!s%7#oT+pedxOA3@hpd${?jx6I*w{vhw=sTixx^70lQn7?*eGt^*lF}V7_oNC zJQth5C>WDElU_7H_=j;8PEcK9z9fd_ftR+3F)w@?l<459yUk9SCG=0px%ocxf_sRz7kc3+ zv1@6J&+l~#P7tS*F2DmTE|o^`VGCTk6HJ~z?ra0Q1@Upc03p*EBHk9#c7iAGI^=Qn zd6^#UWx(?F*a2d{ZRv$m+SaHy@}~8sQWO6mRmDH(>B~RryA*aHn!d2$AlMjP1yjfD zHUDUIfy>g*4OPCKY4VYJdqVOp<$Z=A1wha~KS)R4d3kU7O{1*IE#G zrxhV}LYvDs?n3wSg_?-wi7l(KG3Dua2%~V?bs*t3FyzWvKr`5%_SFtDb(2L|VGXQK zDdZ9~msmR#N(^64tFESChu48U#^9+kKMUM)*zSO9zNeG?@1s7tqnwF*(32!W6ke4u zR1rX&`|`;FljSt8GIk#}X(Ae1U0ib>HbrbhpDo*e3ARisX|E&u@D;G=UhIvUc))Ih zkxq;WPxln((#VKN?UCAQ?SopKU3GaY$W;tMIu3H<#C`MdkiqgkQhO>rh1 zo6f1ELb1b+PKljdifjG)oCK58@`1H6w7HH!DpT20T?8-Z}V6`i%+ z@n+5veRgK~9QWj*ifKFhVBcM~y}$aPuKGF)72nwvfj5Ys?mC*>%8kxqBWSX&4t(!A zOIw>D4Yc9}T&0m-v%^F>DwZe3Y7RcOY^Y<)&ST5EI#&Oz{^Ba{*x7K^LSV)@->u{dl#MqV21v{-uBEtUax z0iga)m2||`5-5MNw}5y5y5@u92l;humJtv2%(pkoXkG}33Y!*)+c~3vwJ=*H{ll(@ z6l$h73A4lD9OMOiD8T8EbI~5;$w{9bnBmt!C9SqM1xyL#ow56Q@=9jwpwwd6seTBD z9#!D3u)%qw#!u@5hPF3UGS8_^RP1(F2c7G9)yf(DyfI~ z{r-rcS6wP8#>ShrfG!FkG_H~siJI417H+ro$Y7$T&+d^C3<8zfy2`LHyK9C3aEYyx z3}2X=3_`88B`LZ29RXTlQ%PD|yNtH!R*TKqZcy8dL`eNqr-Gxk78w`vRZ=&5yiz*9 zWrhy8{bn;}l*~~{ZS4jbU!tB92aIlu6|c=Ke9Af>jI96-LMW&I`4z}m4e5AjNHL^? z;hQSQ8&sw#P|eeBm9*138M=CMx=Q-aK0YI_n~*&b;E4cVwvPcgJ$pRB;{pE6J_6ti z+2a5n2k?jXVT?X!48UUm{=hz{kQK-o1&C3Ac;9XUxFlx;z#{;D+n&bY>`Z_&0p4%# z4KT#z;C$@z0`PrcRm0#H<)y5i-hi`Nu_+mF=K!aJl}#l{fJtJQTrcJhU|IvFux~xl z4}fY3C=3`sx!Bj%W>B3l)eC=NjbY-{!yj8C0Zs?Fb1VndoVJEB@c>Sh;iJGYkX1X) zizx$)KdS=-NnkXE(rbY7VJINd$;Ea6Mg^GF(^PQMq>_Tb>aalz_5!-*3b>I!?MH$Y zzD*7wp$x{}q%tH#!ME3&NJxcmhl5DSh3`9ukWdBRpCG>kzK;OUORs?&v|>Sd-GfJ+ z(+i8{p+~_BlG$`~@zQ!XZ<+#w^*cBgR7uxuZ8OeUix5}cHlqzt%0d&c_7q@~D zq_(1j2UX1>XOgQ~#)Y{m=?iPDGW6yeA-~ufolyeV4?$0CxR=b;19rJJT%pO2$lwd5 z+wO!DA%j9QblosauV`n0oGHu=%rJJ~rLQ5k$)Ki?%R#Qc(?`xtpR0wD%}bv^u6mFL zatY+R9c}s>Vg3Hywfhbm(EMs-yt@V&kHf=Dt)SI*xz!0UkZ)OeDF_-#OkHkjq?Y1?H#?AvbrtakyO4}-&QE`a zKq0JMi{V)bk6$rNZrQzF(I0eBz)RsyUYhCj>ca>I?kCVkmXkMitLCNsZZ&A}b@8>g zTNQp~b6I}0g&$^4@=YtL*1`7}G*g(vOB-EUrMYu_pD_}d}hLKB2zd1HvHLr3B(`#qYUXNu1i@a#(J;n?ABcG=j!e8b|K0WEV_Sv&-8Ae|=TKN}69<&f@)>7cZ6eimmj0r- zycsF8ir31GWT#bhm4}lpRx$i=Z!%ATau{S3UpgGe^|7uI+rJ-yJBXJKcf-M=@B6Ws z6WhKY!9RqHHR7Q67vqlN+4t9K7eG8DR*s8^!zwoQgmd^>-3Q}L8mX-(P@gC}&>D%8 z&koem7xJAJ{y{E;Mw;ty!0{Xl+FL9)-D2pGiFmxY=*VH-V!7`Y6ON99#2L3(d^EG) z1UT=T0DgBe;-sJKH)@^&_$h#s0KRVjwviX_u*Ar|fl@^lRFTElyE4VFW6@Y8c0Lx< zdcmb>)hWx2hxvr|RXz#BE*YzP!Qn{e;ceh#Gnbp4gRTRf$kE!l3-d9W#j>m9>}ec2{ySY^)?PV#|^2ke|-)8>lz&AmBt z(^2vJ2Z1VlRa8~>gLg({S9q_k>;do7l`Y9T&WfKaT^w#B{&c=Mx$Ua(`*;)qDCg5Y ztrmiBX|XJ`7R747UWPeSmP8GrCk3cFA+-=?ItK#22y@$7m6&Ko*Q%>>rg>Udn z;>o}5#O=hfpT*#D;?tk?#cAS+&ss(Fw&fM&M&(Aa5u9Q>SfB1#QTLfsg>P5bs($k) zKRU%%G^X?{M5Ts(qy$>-yB~JSF>j+|3Zch2gql}kyHg@90N&CgY_vhfs3iEx8 zgP6J19eoJ`-~Ho8XW)YmEa4TO*JNR}Ul%O+6^n7dB?ldME}0daUS&l^LF`@1u2{|b z?P-$X6mR|Z0ok-!+%4&Y&dSG!DR7pgY)v`onE1KWY~(5jcNxQ`Ov_?^M*E#dmS@~{ z%RraS(zecKG23mHP7a%8BRnJF*#q!sc*2}Eiw)pQ@GJnhEnGpOP9*t2+E&r`K?L#J zREIP6S(_r=>1CV68GlR+sMo{Q8fa=+HWLcF4{Vvt$MM0~`ae zp*4}J#E}o1#rlJ4*h!<_Ls4r#e-B{=W_*4Y>BCmIm3Z!9M9X&_5Xsq|tWQ2%-PCv@ z*2FGMr8;o+dkG%Wof4!1<&?cy9u4_qL=Y3Ynti`Ol^aHtq*ZPxT>2qMpc8598bU5NCG zIMf;j*LkK}n>VclcTLG**P0fIuUH2J+=fjNIYdm@gi0CxHSsrVY?H1wa>&b}gBWe= z7cj>TnmF6Tgx}6GK?x~DTwv>lP2wS2C#d&^EgECdX?rCi)XJ4Msh)X)JNW+lgH2hc zFYcktRM6U0@jZJFTqgc%Zyl8F&WlPp(dBSZI?nTn4ul2mL$Os|WWWxvAcBlzm*9}} zk~q4q1Kuk>UpGrN*^MMod{j3uXaK~;P~P1W0Z>kGv$skd?ud+dwodJFNQ{Sl_pys| zSn{_bX^8loqkR*t+b_K`?|hyy8cCbPvyLzvCw}Ybhg*x0&e)JbxRnMARCe>~XHRr9 z#pP$`Nfw=$<&42dT;S{$_Kk~0NxpLFtG8O8LeNk0!Pe&$=bT{}o5g>)nvuhH(dC-w z^PH1^5Dw<8P+a2f+dRve8i5!!4_KLICz2kqw91KvT~ds1KCG+ctXw)8yBQehkSvQwZpRJa)}P~-H%w^UeQL~U#Q zAV}tK3Ny8l?{c2L@5f?Gt3zeTa)(|0g8M5w*kv#9eKx?|7D)FT{X1OgSO%B23Tp2` zR47~Co>!+>ETU_S>?3A2JA%#L<8QwQPV@4;=yJC_8g;qI{}Wh{J{1_ z`X<4+B2s?`yWCJ-+kPlq3Ye>Pf`0{8W0=bX1ZW)g(hGf-OKvaDwmm*mFZp4ZQ>7p$K_kWbAO~0F2v%@RY%W;9og> zA&?9aL^1VlBKMo6J^dUm1r+}7%&x!m^Bq+7iwvjBmvkNjd`pIvOF%vVe<#DrC7@0K zUzXuzGJP1ppUH5x3^xb(Lm8HEcpU#|V8L&eanAZXJP`M^5X-xCkq_>Qlj$KJ9GTDp z$cvJy?nMMv&O3iEG|)JMAH>CC;{!_&T(lq?3t$1bkaq4kt@XiaINIDni{Z|57=7f6 z2b1e|n&yXZ;cK*c6Wj}bL#H*tpW_1B-XA}&S_L<4$Iz4h_%!~UE^i8xI3ty z)-srW5r{VuY@_3Ya1<`1PY2-}xTkq+FrI{QB|RE~_XLe{?mf(=j_MV5H`53^n;vv# zD2{2;8Z7J@=ej!#)tri<_$2;=4i5t}vV_KlO2P+vbmo(KeGJkq59LI#YV67hQ z*eaK_LVCE&_A#}D2a;gl@_ z0KsZ5iNq!j4>AAU0A>ikV15vTdl9^gwvWSe!FIhGhi8&|DynXVf6=^th8-W=r*@%S}R^VxVjAMd8^n*)PBG^;s&0bA(J=9uC`=H)H$(-`-n4_e~4n%q4hojQFN z^<_-9(l--uH2#WyoPeEaYTHW?r~;Fb1;%Zp+cM>hPC{wvXH(P4?L~j+?A!xw)khDa zIqp%>wBf(>%_P5aBgn6pVhaXB8N`k(>BLre2JN1Rb=cQDI1xAH@dfjQcK9?Q1zpVg z4mgdF<6Y?FPB@Ni@_hGpp{tT{C_U8)`;qM)WJwoV%ZQ4*(DBLeJ=leIVc(S=c$ZwL zHli9_IG9*QxC)HUVPk2{-(#pZfX-B>*s){J)Q(9|!1!bL! z6kg%=Z}IxC`Jj*wBZX)|pTh?Q;$T8ZXzFu(>ey(43Ae8u&-w8B2RJO~t%OK{mUqD+ z9q_4O!FghcF!)SV(4`N8g$KtYg`>gef|i_&6gu$w)4V>GkMbe?o)3tw?C8S}(3>B1 z!GAOfyaK_{&l#>AiaZs91dCq zM`0cY+krF`(w=-7KM`t;Pe(!h88<5bOGRCoJ77}{?nek4>ILgEL z2+cC#7(?DhBOT;Nl9WQ)Vjwoeje^rQrg%SilAv%D`~s#i zoVl6K0J`Q^Zv7d51Uif<-&@xyP=2tY-D8lYRg#tUNw7^d1MxuBXZ0A>cKDHshi>oj z`sBd|Y!&=2#zRoukd*3^^jbPjQr(5$%y_5}{A5N+5?xn1F9V11^%zxoeH{^}vXC$g zgojR*6&4R^HtIg4uV&zus@!ZO45Ejh0*~rTdNTvZsP?{ygkv;zB95fSL0C{(q0Y(l z<}g?YhOB^5II)xt8-(NV6}n&$Fo*&MUFZT}pz<4ygiVYxMx`5tgxNA%)po#+qx**9 zASzA4Jk<@xe8^+SXG6_9LRO4H!gxj$MpGeQB|)JLbl(Wzx&la7GFCxqc`%Nos|G`7 z>PJHRfdlJI)}C;H8+X!?ujrY<(D_MU(QgLhIMuupTT>- zru&EB7OICp--6~0gSnM*83~`UHY*MFyFy()4cF8f6viuco_)Vgs4|9X&G?>s8nOfrKq|-$K?6Loq*lHVBj` zmz9lytVdRE+}B88LV5*X*$9T~#b~=nFW&qVfLY_caJ&chDr8kPojeSOs)hi*BaMaD zMX+jwui!!*6l3aTa6X8q3>cC-jh-2X4fqJXJ`7gE+Y}GSk%4(rk)Q@*#+S*lcq(l- z9ET=u1-xRkz^FhTlY@g0L^M*Bd2mG5|~}~!pTr%)%`~MtShw2Iv6pP5Uke`@D!6Mqqu24mh%@?Cq)oXmTo> zYGJBmNOqBXD>e#}UNy63>HuZ~!dvP-eRTwmB!>R<17J#$`p|Di;6&BS1DW|^=0nA# z{EkMC#4%({D(yWIbWq+4Iz{GRI4V^!Agn!%KLVXVf%*Zp6&N*!M?C=tKLI_PrwG% z;+-%|6f1okk}H+uE=c+-$z))XrzGE&vGO|6W&sk$(5yjV>`Rx!3UgtOT!5KoiNVMB zzyPKJFhc0iF)(wgS16kI+KSS>NQh&mJgoWU<$vy!Di6#C8|%c`0MAg&>lH}WvN0Yu zC~E1SOWpER;O+X{WlFx6ivj3g25w%xdWT%3)cDlz4Q!l2)O{XYLawgP*4vb=p=a+t0f2Yr2h6%(4-#O7~6&_5q)^Qxj_ zxnk_Rf*IjpAd?0>i^F-K^mKD7B*)3Cy|3SMNZ2b&yNsTF7Kf;ekY|*K04aEv&I1cV zj#SVMPr-_oy@tLEugX&qYFc;9f;xXm0 zhL@JpcH?2j-+l%O*XZhTII@tnf|=-RfMT}73m3x(W9~D9*<$iCxYznd`Q-q6>6z8| z1z;uutD3>b08WOqcR(;c3?B@5CXPp3H7X9lU}M4hgsC37nW>Tepf(ermHUISP)#RI zfLV|UFi8)l<0ruSPSjXfrOcT)f(3(8db|rUEc2o+GU}*M`ppEKXb^yeN#0l?-tIjg zMhz2j3qul=RhIg{Dy=e{PMru!OVDF*J}zb9W+7LbV0nG>j#b_tgNu0XX&kAlMp!V( zwuYQ?P}f9Q*A0OBkQI#7dOHF|(cY7ABH0y5XTvvS6OZNkz0>I`$dgIWO$C!&)D#N` zl@@M|0UgtGxlqlKI4u02V3Qq4n5VQGyhkBqR{+HJp}j_USf`hPa2J$CEEAF=6i+l) zLPC+^v+kV?x-NrK+hw`i-F3oVMOK*N_jq?y7omF?Q?~o^w*0n^)=tKTki{Tc@V$tY;hDtdSd4hu{NEE{^>0uS}{-6>!JvH>pu z-dlH17)o&s4R4ZW ze;kr23PGj?3H{|{Vm@G%5#Qjr#&Za*13c>_?Iqc2T`Q5afB&rF4Z8drzBlgSE6 z=ovPd%3;B24yOjf3R%)+#j3UZI_`O8bLo|MBIJ)#4AjMEVM-nWI7y~&*ob;{m}{r= zrhyJ`KdP^efMm&X@g_zn#fELL6}G|+lV4R1a8V<8E3|i|(gVp*S%N&+I_JWe@R}{g zWhKCkU7~bwq?ii4J&_JwoGq)>kO`eMRTlZLt4NWWp2>v{-Rehw$i=hg9)vO76KK6w z?V?682n=S`rhtKH+~H+`U?2d`Y!FkNcZl+SFxWhNm=zuea0hD6*0Cjn-zE>iL4^5j1Bdz)i>!? z2iu0<&jXWIb&PEvU{Z(Drn7KFKynu(6a&}(9?s`!w^?|gI=u$=_lORg2fp9#Ss+3< zAmV@~*+b{onO#a#2yV@S)%gIWE+8ZaYG~+eoQU_*zO(U!kX_(2vc`Mu&Fy@)pJR>y z#dE-BN6lq0+p)vGgkcEEqlP(np(-5w)-G}m88?u=I|ru)jDr=Ptw>&G$0^PS9{0g{ zfF+Xc`VXvuO^ssC@?i0nXR9YRa8=HdYdT0@%*Q9m;@9c0xe!6~gKJtQ7yykUXt(#% zRgl-a=bNBusFLM*ZGO^0B)t0suIvyJwtH~i`ERYI-^|5^F%N-$H*^l;;T^o}*P?Qb;B% z1P6h@Ajje&Al2Av8$HrhZKfYA#&Lmbpb%)Kejbhsq_vA-E|vUF{g;6Cw!(@I``xMF zGnDl7jx<%}agS{bq6JGJtaRmp61nqs&ix(rvZ9@gbagre2q9%qz;yy z{U88SVSDoq3Wf$o$4CUwNS?BptX!8TdD}Zna*2^Lz`!wYluoQ z$8x&|_73zb0K=-zM)*NU1}jM;ba8Ll+gGjZRX+uSKZHGjLJ(D7jAWmq!=A=(kc27p z@zb!1j>u+IvSRj*^t#%rA~`9qqW(YtCmT$2Ra4k9D`U$6+fGpej1(_H`K08J*-(^5+mAS1q3atSkQ6{ z2p1?jT+Q2DZt(q?pO64B^i2Ioy9~m2XA*?bf_$tpUR378KMOLae#y35cs4Y-7|0sC zgtq}!wmB;4EE`m@`LIO-375)KO%AKX4XSJqg^i9(4{Y>|vFuOjmSvzC zHA&F&{02UqzXMo+GJf!|h4n+IhYfizybJP~Q|g@t?*p8m41rY8XSy<|O5`MSN<*fC zx*E4858xJTpeUip+vn--l{nOQ)p;f8nHIF1wjT_eyIs4Pn%Op0wGP@6t}yn4WN$?Q zps*ALX@#;7;bkMg4GiotN|OHq2`(kM0W>&Xw)kYthxFL9Ft&$4@pqL)V8tbtl*b9{ ze6=02iU@7T)<0QCYAD`C_8>yOgsNEcz2UQxF`%^vr0mOpX%}bW!9UbcT*E1i2+JOXnL^cmzm1O0W8W z?R{i7J?SJ1b2SY8#Q^tj1fOciXIr1f&1COs^Zp{N#c4<48}_&tfyD<;z?DzHpLpPSpk?$I<7w?`+=3)Er=e@` zAhNeTow^2(Csi%!nKgI^DN3Z{pTh<{6PM9j6T#bqueW?cYdN3peGay>dt1}DpTix= zuD0}t=fDYB+=1GmFvWhK-%G-2CF`i8l?$FD{I8MLpt}^1&f>sR-0;bGeWmbCA zUFyFU_a^8b9kv$!2-%8zbk$nevz+pw``P!%J^IO7{8C_13oN_C$xx07cdG@Ry$*K? zG_+LkULlKG()ZWl7J!v}0?-1Bf6`dJ4$<9TeDnhn1} z^!6E(@9Hg>SU}5^!r&plHuNcjdp-dt0n8?*m%fV!PVtnV_$&SSdAy&D=}0$}fW9Ud z)3;0TN9w$GfhgT!UbG&M;M8U915vWm{P`xFgw=Vy17XUU@fPgDnsiej%5x!lM#W{A zhnM1&Ds}c$DCss|+J?IlbyQv;y6R*0-;Ogl_3`-tXw8#$;tF0JF9xEh_U6#N_!CZj zWE=2IGT(X)tFZe1tAS|K0CUX&{3WkGejpG%9AG~87SyKRUKWT(narnETsz+U$9s4? zR%iY#5QV3kUpx#Br^fH^P%<6UfIB$ee7ORDLDbo+gV4n~`uZ_^OdT9+KsvQK$BZL6 zb#|x^lHN0Sf0MMswEQG4*9Kq)eCQW^Ms05X5xy6tzIr4CZRgFw)i@ced*%e8 z+g9_ioA?w~R}Kq8SARF_e#8&4dga>zh`(&s{)9il8lAxh>Hdc3@SAw6dCnc&5^Lh) ze9+y$BO34{)|)Ht;s?-{!w`db&;0f;_|0bOo`*xwM9w_cpA5#DN<^scXYzORn+DR6SC@e>CBK{D4rLuyCj+2+V6Kjb zivj8q0IobR|2>h!5={aCl@d0;FoX2MIF%l*#?kzoocy`;rohiD+%+T!S!*!jd45Lz z{G7!obNaHygCRR--ju~C@CX7wC9#qu8OBY?&shYR?T9o(0L`71s{lLz^X5OT0D>X2 zA;%AZ`Wzhq4IF|Eb7ryF5pNiwBoYkiN}>&gzsR#yBZ1WY ze*;_kIvH<{Z%?AI#t+(=DPbCW2M3$yx8!XhxFa? ze^uXbjbrFV@{&3^$_L#)Z_ddhPh(9cXv6w3dP3L7iF(&df#^az`o&!GmHNoIAe8jb z{Kh;Ih}GFI2BA|9^O^a?U#%VoBRkt>zPyA?2vqM~13}n#&7De!MWenuI|$vinUhM% z0$joBtOPDElLz?-!*T{9SD6sF0f+&6- zxj}cmLAI+ZTf^itcYBk3iZvJ7!VQYm$PCl9EvCtD!w4zu1LylY=n#>sF&{lde$~KP z^}Y(SIkGWwR5EIgD6u^t;FPt%bdhXPmX>(BERUpbWXJ1F#`az6&niJw3`j-1DO7Jgv1sGynzrV$WT9RQD8Ra zn(fkXC7iC;0m#%K;FF&}9SS}RIc0)j(X456rcBGppM?TNHDI)cVWay^Su}kfkc1Pi zS(O$A1pWdWtdlsipVFX=xl5Qmm_%?-lF7;!e_xB^& z{N&7=nLmBX-1)iFQD9HdX^LSM$TxjS{z9Z1JD$<>M2XjEUi2mT8tT-8vHjprmZ-r-1z)Rb_7aGa1B_iO1=LUx-LbcZi;S-P^dR*j<-dD>=CXkWPVk!}NL6U}VBj z+;!P3)RMa@FeMNE08?@eq_uv?jQ_uzDe3eGOi4{OjK+UuN+NDR=KsGuV);PMO?4!2dA;RyLjxIhd;*_50j8#|;UUn9C;DA$aTuj!6sq*;GJK>sHhhUF}s zHD*~OGQg%Q*yVr5W-HjI8?Y3cNd)5M%uX|Vm(M4kqPF#G(kO(X{-v_05L zIWatwizKJNrUfTRcvn`KYgWS5Yjf-h&=@nXIwh;JA#2RCjCr0MdiDf~h*l`d`TD|R zme*4t`XG}F@2rsQRiQ+Wh4wb`Key1?CER-T!$==g{Sp1GgmaQD*J|+yqODv zt0tU=VOeK2PaAjy)sbqg+)413^U&Cwa=OkX~wAMB!JFhB+ec)>s!G$Duu{4Ah4CUgvr6HK^JVxTeApuODTr+^|(oingll$Z<0l7JLE<$D!Z6XL z|CxubE`v>~Zn|v$IT&2@xAk0_+)YWRz$btX9KL~zVc!DJ_eJ>11n-?9202l6io`Pt z`vz`Qy?Za){s<=BUu{2NX`eGBjOk|LCN7+P=Z%JO!ZKbs1N8#p-A$a4eXBNc?HeqA zlScc64Ke2IFvCN({Y@@apz(%oyT)4$+;N1_a!czmQUa|Ysz3BUbR5> z%oE5*v2@-x(pC@gTH)s?#XvK8pZ0=?C zT_D`P!5lt^vl4ZFchK_|^M=jjXG|UQxy_yOAk4Dq71(0m#w9Alk^-db)K$^H$H7Co zVeRE93SMW%+D<4 zM)2yW_Q9ykW&Uaf=gTp&>Swvb>P-+gdRQ*cvtZKzrM`xU!RKW!Z{Rxo8_&DO`}78n zi|yqbdtCJs@2?J*>};M7_dzR<|H;|pI*!0pwly6`D7FT^vaNxyY-<>SY-?CTwl$E$ zYz?_EjAm}+zKf_Cq3H9^9wuNFD^oK!h9nSd3Ugei2 z3bv(-dG}^660?dU3x?(m^%dCa zU;V-iJNRo*ei}{O#j?s@u& zLHWV_#)GnUCe6OcjUn3WwCAgwQQ67GDdpoOn;bAr?1JRtw`CwBU-SN{!yhW)JE z|LpVwdwO^J&)B#D|HNx!(|~zxY}CtM8zf+KKIydqne4SGxlej+kSlv_jEU^EF|vQ< zwE?m0wZT{R+E^jkYhwx7Yg0=9ORsHk9aq1RA2;bg+{k~Lu8eNQYr8H(^WBjvFicFB~_Zl^r)mD?4rq z?LTwefK+ze6pBWUo3};(>BgOmgPW|Iac3&&6GQ3fZFs3V>Tm!$a@BnE0B0iV@(XZo zI?&wqO)d@oa%NN@T6~W#d5arLmaL`c-{KaM?Q3Yt+uR@O^NZl*%}(KzGnIqmVrtuh z<7wU&Jb~K-&?j4P5_x}}IiZZhSZzERgbp~(?cd>^_F;?K!DHMt_5IcmeRY{Pn7K|^ zBTWuQLl7~aKhEvIn)B}m!!KZodHM&;+tCdVMpxYC^C!9Qfz^Ou_+QePUq8)BSd(2D zj7AYccb$bxkLva27M0va+@?}O@Yl{>+l1kr1XnZTbi>;-%w+j(|Ba=;-iX1CKo{sa zEvKiMAGA)Sy`JV5`1Oa&GAsQUMWsY{f5?3_=vmKB1GnWR_38_Qn)I0 zD)qc3(WZWU2p#eR{6VB-EgXyY3UQd%g z;{-nRz+jl>s2m>UcJb@N8o&N{TJL7%>g6)JQ3XN2UoZd^YSmb^D4hKfT}KF zlE;2aGp=wuRM)_FEuwd?a0!vj-;E3051EP}hu{bZ{{D%s;3}rWAH$JCgWDUBu9_Dn zK~eZ)gbfFoak_x-KxwVNhEPZT3R>|s_f;PqxR9q-{E2ApHP+a5-?Q3Yhtvr<^&X_| z%PIH^FS?PC3ee5HMnC?BE7jbF!@41Bl$KCvNx3=pD)$>7lMT#MiW)HwfCJ??-OtyV zP6u44?XPn$s_(<42V*h)T919uP)4X9?yt&jRBV13j_0qdha3RoZY zQNa4BPe3)zu7#A8#k56-Ve99e*X`ht<>B9dz`JxpZ@G@ zk)Qqx&X!qo7j|@{+fRz01>e$Nxp&)dg;riEL1@X+`EV}jIo5~^+zq{#2uo0a?#sKZ zpN}H$GYn}u_dd5(odTPJvdvUe!?p6Bv04Fj>cuDArGJYv*8hG%uKzh0Q4Wd!=U~Kh z0`>px!3g|*^Kdl|dif!@l8EMUsIPsbaeYp`YF%vS64!M*{gKEivL}GmEm`rXR7%`qP_?~>TXH} z-atA_)GYAZHA$%ui+v554Ut4m=tN(BquL0l^ZRLyFOW@nM4R~WThy6=D}SBt^W)E` z7ehMzP4o07{5NpH7XZf_v~N=&PPfsVru+-)V!$1Ln?7#Jzph>h0aW;@^gbOQ+yWwy z;9#?(fH)n*AmI%MyYP-i1m2q?nfqO2r{C-NErt1TC+LE?k&o{25d(Cu2LpBBKA;^v zgq8Tx#NKRQ4qSDNQ#sGxljQd}4NI?;)4SyNuksu2&H+AN#oht(dx@4H`QI*h)4Kuu zdcU3!-YY-HM0_Khb{GLW%O5`F)U@DLt|@(CxoS>I8;I7GefC!=6-fegFX(}PU>PvD z#Zt1wtOayX5Pw0v9j+QVzNO*8{CLe`BddKJeK41Fp;dgnBNjJ#{9^S#b}n=W*eJkn{70bjU?p92oJwvge0-Fki`5*k{6PsctxcW zk|cQ{eeREQJ+D2V&*}Zo_xp4^a~?m=s;%zqrIh}y?7Fc54$^k@X{*om@IQys)&9M> zWb<2SSl97tD~DtD9kb|K2YrQ6{<#-Ed`5FS>c?wVAilRhbE9>Q?xc6%9f#$e^u6K7 zLD`(Zl-BLI97eb2zvhB_Mk|j0)|&r9e*BJ8?Yq(6L-k#ur31W`)$gc|rB^UcY6si*-C$+&hB`|i>Q}ljOy65~E4Vit zVp+U_!jm9bjIIA;%}gJRa}q48!2-%3j={(WhhR^gp++P0WfYyH>z*^e zZbwf)r7x-31(uQ z?6Ei&iVd@rw)!m|UcVcq$9NP1@!RXTc*t961J|gn8kr-vJz!#Cuax}sxV+4qyvzc; z+hd04_WF5k{w#XyS)GgwXs>ylVw3bB?O099Ou|TbE*WM0Cp}Ek7aNxmkN%66CF`FV zrMOIU^&=XaqKDTrLNJE`CQ++X753+Nrw}DQ~OUG-_jGLsV>K_|?Kd1RVI+?16HZ$Y!Tj82m zQ#zr7Gjs9g6Q^As>rVb@$Vsd2)FTb$$=7{w;iy_VlACeda+3TGi!}wCPOi!0)Ae?o ze0Dmt^X(zeeKc&0-a5pL!9I;e5-yT zZ1j6_So6nK*rzELxi_cGO3xl!z#RjGL?E6`O3F*mpO}RrU|u!O6Y6kviRz}J@A7S@ z2OrY*487GjCYvzsCRY`;^4~;tQxkIgz$sDXLKKyKitl^ArlK+a3dNru79?L zqBZ06Lk8cx+WjHb8K*asx=k3ks=B}VH{H?yzjX60u-p%6>~ngvBF?u7?1|^|25wzo~QUO6Lz^!36PARPHWc+J5_jwH>a|SmUSpORnNo|2^Skbr2ScXXgxEI zD}6}dY~l~H%vRZCJX$4Rb$jpu{XAX|sb|I&&(&`1f!TUngL}m19<+Uj2&}4*FVB^K zK#g+rruED?3_x>pDjb%hxAkQSF+e9~D zD#wg!dHPlJvfxMbSDqeJPhK2E&)e(9)+*oZm?`=C5A|`2MG+n$aCVtHd|0pENin@+ z6nlr8^mKvlulaZ1HMu~qt{O*h8SzpD&7P8!@Zt+>VRr&3Lo3B z`$f^i=k+EU^fxKg_Zw><;YbBtF4Tjh1QW(Jf0;y%Uu^wKHwmpKn-T_3h7Ejib5;fU zOwn5mVH->s_3AFc*VDxY4IUx@Vq8+>^Z6S`Xp_uGksl!x$;~_b56!6%FEA6#Y6C{f_Uv;+pRJFX~Nv%sB3uGPf*$ za9w#(Z(WULs6!2UlJx#`F{qj+)t-tzZs6{0x8wBRX?nBA%s6~WaAMgbhA&r@gAC=S zrSP#D7P0|wg5$v?g~oeQ(#z-~czx8~6v{Vrr+iL-7wL`rm*T~d38U4TqWGzL5t8z3 zu6p7DxfB+sQ{x`!YGQ6W7H~gCQEIW?QY&3dCB^#wBEA&N*SSmU;c2u>Q#YzUvdauB zNb6rPW+=L|YG)A^UkU3nJ146?;ikIm-&Ai=)dcy_mXeB7^^Xj` zq9?V=OjEAYavhW(N`K$@(k$i4-Q#QhrD%R=)T&igX?oCfSOdq|Z2Q@Y0 zxK_+!omtxEqJ`9%dP8m?jc4j748C4{`8fSPQx9lr#ud-w?ui5Nvd^k=YWK4KrNP&; zwG&ipmLAZR^Jc}qGA(y6PJ{1(>&-Z#BqSV2m`#C+T|cCh%@ za63h|mQ-(&= zFVO#ET!zTIhpELvJ#YXgF=6!7I-DUn9(@P&vl1+TOlyl&laHu*_pzrPif&|J+uKU zFk!_L-($CG@q7%A+JxavrLKz=n$jGgTWT(7ALJ}@ss4e%eksm=M*l3+ zo5&(HVR$)k7m`?22n`^Zz&ZN<7}Z&>2XJ@tA9^ZBA4&KrVl;Um(XTaF51 z9~!HVQJWQd<323SgfZZ_OZ&cRYR=F&_m;y$7?v#uO7wDrU3I{12R@_FRMwUWW9^9T z5@&6_vQiId$BjN4XqT~(4G9Ly@qGIk98UwRTql0D5+ir=Cve?$l-^#Yhe#DBj5U~> ziYu!eDzF7mRmBx|6`jFRsiMnjblEtJKO-ur#_O2LnsGRn0+%xfF|X_28$9I2RZz<{ zU^C-*%(=0pt^u1Ts(spL^u$^{_zBLT31ij-eHD!|o^V17>Z3h7k7DqW_29Tjvm9!dPQq z5>aU#{kE=BK!8&~(0T}%2?2AD)6eVmz;>KH6UG?iDnL^f1AHVmx=PbGivXS`x%Byg z>{y294aqIhfoE&#ADT6hNy#g4^k0jo%w5gts%ohF2ED?&8;oSbF0;h#ntBW`<0gy> z^X_2|1{V3IyRcrqTn4Gw(88L3$bGC1fpBZDGe>qF!2G=f7;6YO)>pP**|8;>HgC}bdBi=oMQ>4)ZB|F3TVdm!7QLx2HP{=G zah#UFtp`eBCXD{#=c@PfxAi6=TcR~(0i*LXr(j~wTZOp*-5QHj!|J+k)z=y9`pEM$ zy1Z3yCWV_Y+&a4n4}M1v;Uo*T>n-^I3GW~&J5Y-Ll>D~o&FYzPjK2+BZ5p~wZ(nmc zY$^mAzX&r!T)*v(P{ek}uw%k_9=avY+^#pZbeg5|R81BVY6@ZZP8&X>QDu4)X}Af) zZ%sp23zn2Qh18NoYYMTXu+yl7BQ*P6hZGZ5JPX{URJ`ky!Y0+;p_g_)h3s>^ZfJ*= zib>LTkIF~mklgg_K5>rTW$~SI6M1b1K7s{NT<84%sQ2_W279+U_}Q{@y|H|#nIPs4 zn2pl8vgFS&252FXW&|}OvI+i=@G=JK@PhTb2e^?ov->tW) zC!+vYyK+*K5A^MV9gZEOFFw#C>&Ym5d-NTKk_-oA$#iNDn!g#xRwt(3E*4H| zEG-meVEvZ1f2g;pC!+wDxN_395B0SMJ3>>EsbsGn(#(u2o@ZRyH02J!gvx0JeZ3cb zsWznfCsXl9dT|D9Cno!9@!zZeBCr!~7rTH$N>Y*z!FY?^XBkS07UylLCV`em^1T5?2Rtc5-aKFD6I1gg2i^V9R<3wvRA zJUuUVm|}m%q^)Ecsq4e)d)Qm8rHoHe;mO$WnsIA0av)r~@u*%j`549kcE}fXfEs_Mx9rXGOc>MsD)L$fSCMB2!c86)QE`DP z6(7S33-^6p*26W$45^WtsOfRXeMP1e$TIXW96HxM1Ho2Cp=m0pODnEo113v-&23 z9bsyZ(O+lv=D}th+L$RVuWcvA9)vWDUDEXU3Td{kz>;nyUHeLJ5pBjX)H%~MLz*eg zrP8Fll;;(D9Uw-T2*q9xKokQGD~6uaKNReyvy8mH)`RQGD8S{+V;a#chWdZ4Zx-y_ z^8(%ZT5nxXMgd-Oas|cEW8df-4E6?Eu!?^8Mh~^(bW1WXEM>z3;J6IyCZ$DlAiys-o%Qp{;&Ri zjmMEQ3~F2~5G1RR|{x622F7hE0yf?YB zn|`{ex2SK%G0g&NLdHZaB2Xj$#8Aj3y-fN~-9ukr(t~{1mFgaZF5t^d<)bct#8B<; z^z~iX-|A5)%N>A0<11Bt%)mZOUP@{~lH3GVEqWoRl+KQlu#*E@u6(C&=sEiq9(K3U zy`Dhov#J_s;C@Qxn8}XB7J0WbG1eP@AdlYwgWqjx`!^2V*ZE$5F)pJj`c*%8rV~y#3IMrZt3l{Rv}Nnv{nf``=^f%Rlsgf=YL&%CgoV;F@tR-$}j(&O%1W8>)ZB?)vk# z-cqf_0?q=>Kb^A!H^q1K4ql8OhhClOaMdzs_s+lc9h&`b;Qwa49JZ?W-F5JPdRx`! zN1z{zbfU3g7D+iRMFR@FukY1r^`&p`>-Dwjed(|J`kzvY+SbWV4<6{pyYu}L;Zcqc ztgE>YkNmV#i z_-_O45%})`tu(|}YCPpt6WuhA{!~^?ysPe|(Vn7h-M{;3%9i%Xl=M<&f7qBdc#8Mc z-IQ2ed{V=njS=EwRo$spqdG&v>QjtOY*I7ms!e>NR?vPP!(itYG5RCX=VhS6(liGyk!jjkUc**$+-x`pNORX zJeZR0VntEHV#RYaTxefF0)7QG$bjP+cF2~Bg(cs9w-`J-p$ORJoBg99nzD_dJa%Hj zJhK?WMwkg@19I7OVTKVvslH3J+$HG2(3Y5zm79TAarPD4mjD`tn`#TMYX8Mk;G}~cbycf=zwQZ zv0Y4lj-7{>!)N^|NQio%sx3WPK&H9xGdoCCEQZ@|LdJB4Nb`!~Au#o0(9we$e}(Ic zfL(ITa_V=c3wTEHhZBqGu8(MGm>`AK z6W>-pg9p%sKiT)b-B+|WOmJ6kUr|G?&Q8+V6aG|6s4s$s@r@}9rQqy2#?$eNeO8>N zjAv+I=J?D4IK#y7#hiUya4G0_jB5p)OBUdI;COwpwoe)KuwcCqC4Ny=PpL-A==`KC zDR4|K3f;j_?56ddN)6IwL7AU;vtceoL@nnQ){|Z4#bm&BNje%CR843g8Z@i^wW|Eh z>449|Or5Rz60pnc6|CDE2tO|-870Nq>w$_chq$}k`W?PR`AS&kVU#vc1B)kP{ImRt zM%`7_&ecqhqOsELo1%KHmJaHf*Zw%ys$%c|q^1nwIG(`@=*aAGDf20W5H(g94aOwihqU~*D>ONK8{u@ANHQHJxX zp)Vt-=QNRh7YJ=pLXHA!V!@M+kE9H1B-U#4rqb<3BBJOfkPeGK1kcJ|45p@LDfUkQ zPG!*a(DymOXBixyG8PT`JiusxRkD|l#UgLWre@~C@oV0A#cQP!3bw@jNRApZ+Log? zdNQ`C9mkK$czcd+;pl{*{j zn-Do(QhHZ{Of6D^E8!{3tvJB8Cil0|GVy4c^oRqHjN2s8!KBP{0FpA!WSby!+|L2X z+%$IpGA}v`pPKY!`PIUlMWSRqzsRlX#DKT6EZ6`=J zF9#smZlaPBC$we7MJtta5`rqueuV>&64pqdy=mYq2FyZvT1I8z#>lA5c1w<8T!R#E z8I=t8xlU3f!w(!CD;ZA6C>ZLjR6dY#$+4k3Z3z&owcKgcuZak6vYXqR*`2s?+G5=wsZngk`|`<0+%F0BM*wq`Gi0QuOzewze#-b5~z-1T%JC z3O@D-%Q7%*Zd88aINarKR8G*4W@4$0KLc|Dp=1`_XeJs(Sny1inUXhlBIi)S)!P+7 z;Iswjy8t)%6#Jc#)UmnP68-YiJh}CevwvP5^Nz@&?|7NeLgEJYHuq1?OTJMKoML|$ z-wD8^cpf!rAr{&A6E#=g!Eq!7D`EZVk8sf<;Dro6#$rn_3z)AutHWFSey?%DlDDZ#OVQMD#8X;| zw;sC-Ge=-^TEs+P95V?3r(HwpL5z*v#>x;RxJ(icNT$30o<*gQ!=(!c4^8 zxzoq(PG{22IBAt`!A#0s7Ye%vGqL_1D`m-X!o)^9v9i6I*t7vo zbb4N1PF|AP6)jn_on#&%%|u(BNIrOCB2RUs#$7~-tpG)PcN5mPD`{63(YTQXPjxTe zRmz$H^jjCPOp9DiuRJE&wB9QjaKtV>A8Q7FrQZ;HpYrsr*DB=!Q{}nc7f}XQ)!)ScX!$H2HvG{6N~OUt%?#2jSqmwQM006VlfTsAw0F@we(aE(Kxcs%bKDD;p;aD_Cao< zy8?7hF6_+NVvxDjP|-t7_S*acj;tXZUyI@WXH|XDpuw+()o-m@gano+x76`^0;v}O zP8^+|o8&bAg+W}uOKs<7;7ABQY1gHc+Vm97A}n}o6%pS*D&iy+_k;xg^xXyyrPQRC z2V{bO+kZYIoUSArqc+X>!?wT2x?`)xm6@?dQ`+~gK1H; zSmJdZS@Ol|ykH%Q=(?&lH7F%A)IUX$ZB56`M5UWjYxvO0}{#XhL7nrcF5~l^d%!QS-Iq0GX|H^(&fk-y~YC^qz8s zPWBZI)i3F4U-7!;vw`OH6aHP&XTy{LOgIrDSVE<|5rA9_Va6DsR5{1FP6wi})ot%5 za;x{n8CZnE4K$&@XxTQw0T-~e3@MJ&ZUHC@tWp61gP&7Wj?E8g2P0hCKq&)6%a#^= z)LquYM`T@#qaqFa*rx`FqJI50qRh{$YBevO0-8n6C3H6gEu|UGOg!mkSu8-8j523? zpwN}EW`K91C&Vmm)NJZ9P^{8IH_?{^Ma$qc7LkhEWPWq-UXg*ci3Qk6nT*X#eELF} z@}zlMpyMD6${RM(e+G$=I%TejPMaLNya$U&Ron0;^%)}CJaLm*@^dj86Lax;aVQ|O zO8)@Zl0oOdb4T$5V#pobbM(69ngiYs5<_YK5V2fSHq*#B;ot6qS2g8SAZAGjqgYO* zl39RUvd@h9K&fVdR>X;Xo05UER|umvQ}-uDla>~|fdyqqNu2B(fU=4!Wq&f1a)yd| zwo`d{Ih&7TC7Y@7P|>`l1>bcS(0W)^0gZ-H_E0h3i$CW%7$M{>bn+imwUa@m?Lr&1 zQZ2$jBy}-m#v_t)hAEEj$vIjMgN`B0ev5t`CW2d9Fb=%9iaGm;m_x&8+Bv)nl;v_c z3k?cZU4IMTFcyI=E%>&(l<@ef*{UB;{=>z>f&3NIJqU4I&|>jgvxe8Oxc-h7%MHMy z_k#qN+~omusWRqFil@JZWB;w}Ra!nmthR-|4T&hI7*8th9p=+kwR5ZBC;MrH5|)?C z8^}C9A8{AQjPJ#B^9iE8BSfx^Q~03WY0s0k&p`S9qB6%(1YZB}{qFZ@LZVn(Yt%fR7L-g< z0x>|*gaj%{Lbobrilz_+P!zuA8God)2mqu+m$O%P!^A>RAyS zY{9wEkvS1}g6HE5GsiI*YK8b~BX|gUPHR7(zI|4#u<@65XCg$tPt%h`P=5 zo>fZ8Q;1<7ZIzP2G3+(1QldGQ3iE>?G8llf-GOQY0{5Z&Vwg-$7uBiGvGD3tJ4s~P z_-#g4&gJ_wCs_n|Tkvj{C$$}?J;~x78-EdaF+$)@nvfy_d@T5OC1XSay^$ie+79Dn z03QvSx|2qZ7ESwFaC`zpj?Hnrb*~3I?>R7X#@+~s3yi?$lsHG_9G7oA7@C(L2kKpC zM~hafjlWvF8zE#D)k+hM>shehNTk8`P#wtHg8RD$Q9sbsa?LX?vmiAiDK0N3l~(|&o#k6>G0yrV~}38`!WTcsw{PT-@Xm{Qk=es#E4f~!61NZ$m9%{jP>&sT2h zE}+lGip93eYmUcyHI!n!;A%~?8O-qMdz%4u$CM&P8qpTc7*ObAhecg)=cgi0rI}>= z3d$6-z4;s9-B8cH_rYKs$DgBl(!O3{zUgNDTI2+_$5EyM*d5CJ7r_eSan&uaAP)UY z`qDYa$@*lcRU*pVatVK(S;9yChUPsdR%j3QQHw0m#=jfOap>B|@yffj_7N+7b+N)RaIh6h5*NTZ+a)ynBN!`i=fxvew1~9eQWoW~AUGLuImP|~ z+0rFsjuSsgDc%v^tE%rZ%?3GR5b)qb@q7UZitko@G9KrjE3p+xd?&FUwayeTq&}#Q zPm9)2J@o^wuV7!|hdK689k1MZaIhGoS+`Z89Cy57f6k^Ur3^cY+uXuN6(!4R-nDju z=%jY$kJ}q4?Xpktg#1KRw`m670L&bVgQB?9VUaJeAUUdhiN5eKnc^-QzHp}@YSBM+ z^}Nnm5OW&A=a?yGX{8um7N{24KgCr{R0^HT#~LZkkDf0OYmJ0RjL)aZf1(H;#qm*+ zTd^-&h)cUNF1Mss11w`uw%l2O76Ym>G#3GdZv<<_5qO$IR)S;WRUL8Hpp_HFlDc=R z;Q$y4yTcju%>^Fn4eBvTH0WcYuSO0g z6Akivi!M#uN;K0&N2he?b7cJahMMBXuv^n!soZ?T4nO6;z^T4(X)JRO4B?LWhH{J+ zO%Y4I)}UpK2H_m6iz?C7`kqu;gwsevUJ%9*ix|(E964Pt<0+WXZ$`cs0;-blsX(c| z3pGxh49V7pe`Y$Jsww=bc(Rz1lm#L)6n_P^w^X%u9jg$~>0-E@Df0Pm@m083a8Jf7 z+v3lUns8>Dl` z?gW5+8G`zc&_|a6q2eq|>X$hipWHV@5d@LSq*oEhNfF>Qy3N6t(j-WtO`9)g@2#^6eVXB@(% z^XM;cYw9WwV^UmBUV(H>6a)W4yfRW$i)}9}ULX}4Naf4IUw7o{bD66xlGqi50Ze?; zLl#x;3~|hRD-N9A@m4*LUqGe*?4fSeYEo%*m`@wkJ||F9Eb?W@aUPqIBsK1+ruyE| z6r{fGO(idh`dV=bz4ej^DJm(!3TiC2b|HBF81KsJqQa< zBdG6dE`_yC(yjylfN48jX~!h3HS|Uys3$efj-yrl#5B7y4}{fByryxJp;0r@EV`hb zj6x{*mLgvkO)Fu)vGmN#;$z!!jJ>xIl#3KGOSDWp4nr+m1agy^TNs~{J7f&zJN*8W z$(bfPMmoj#y%pS#NW`Q#{#q$s8sf|jT&l$Y=~8;fOX%HM;?va4LiN0iu>2zGd9$Ye zSFM$sH;G@V^(o9O=)><2@S!gU(^SZaeN|TE9-xjPs6VPMCHAJIodW(6(|(dP`tK{^ zzuKz6U3+JXx~f)iY1hd);yJZw3EDw8io*YU=R3V4c-yI|b2YQE#pb2sOq0b|VrEP6 zIbV02U;G0tpC_6ITJUYwTKH57=HO}OhH~eYn5ksY`FSFsJ!?~k z8wt5+VCj?a=*#bwmBSSy2_u*=IQ@Bvv&^H2`NH2g0(EDxl|Eni28Tm!R|NI2TFq(W z0S~r+Iq;jS(X9F6_{g|_a0MM<>W`?a!x}yZ&UMu=AE9==~GKzo)5xYqe-vR9K^aibaWs zU^GA}FFvP#Hm)0CUBp>k2})vaVSlu?6!~I>k*`RkRZ9gKWG@k)wNOC8&W5iNII>XA z+A$|aB?=GZAaG=EA*SstbCo(_Z>r>8Gk zMq3w)gSM%dAkIVBdyNWT6JgaY_&9BOO*ArgU_Y{YCVlpr@E3a#zeCr7_N_ql2Z$TV z-q-Sy;$wO#?18ZH67h>I4bt)udS55|QV|+v!TyCYm;|V0_vbTR#($ zFw3`Jo~uc>yi&A{ zw%`kvz|@?Hybr<#k9f|JOXvOKE{x(Aw2HkLnQZtR4PPaiG?{({BgDws3FFgo+_f!| zs!!PxvoVY+UZ<4@}uiP(1HtCxXY&7vgh7h zyjrMTFaL>6Xz*XYX-*h_H)`hO_vU>!Y-aiEMh3A2?c0Q!C}bp z)3(F{S=S7804XsKcij~G-=P@yve-q(ep@-J`ZB_jTa-{L0;^l_ahCe0jhii_BLAS` zbt1T-1z%?~Tnw!}o`SX*-gI)E_|3-ho<$C?|3OFBi@??v95J44H&3i{n|}rcHI8vE zf(AMSg}otuwcSM#b$Ec4+ieQmAc7iO@a%sPwB^lbHwe`hj3m(r$$wJDM$s(5f{*@7 zlB*6~`!n()pS?U$32$A1{r?`mTQ(DwgfF*gUi8vrXcnjdihEQ}0mu zo1$Zp1&3yHzOYrM*oVHNC=VHQ9)LQdT#^XcY&)UZ9t7wz&1OxhK&g%C2< zRC~J!(qeN>J}%WA2%GQIgY6>NX2EH>yF$yvM%A{vDdtBZc%1!1U%e}uRl+lKsb>Z5 z0yo$pe5)S?lOLEy()QQjhjZ`_G04yWdxg-t9b#{dg1@n+f^ZHyS$5!KF2yKn-__^EN+S^_+$O}J2m?K6 z$Zio-374CqeQrt7{G68}aM}_MV>j&<5e9r`c`niD+-~uatsHSL7?=znkRQN63%2Lc zi4Vk>TF+uu?E9-$0k+yY_1q)82Rs3k5<5rE+KvE!7D4@82Sd%H)eao^q11N^Z&xldHfI7I~~0*o9YA5SS+js+RlL)U!D-6w+m{3Sy?zqE?ac`5}{TRW4hQ*;HMSo`*& zuKK~2gb=#94|P?BIje%g?ogd}?HA$x7QBSTV7bIORqS}DuGB7|zxNBjmNy*=T-v~C ziE>!VNlcyPyP$K7D(3~l0~;oov`T?IgjzlWUffC_9}w?(Uv8{=MmE8+y#@;DA6;G7 zycSLG9@?;uDxaMeIfB}LEb2GAh52sgL@WP1IGA>mu(7od7ZAgKGAd!&bk;~~%mfACppCABXin53g+ zeypFv2tOBWE1C6Lb7S-${J4+9{Pa6X+X?&;rrl{SoV17fHn4>tU*QPq@)jOBp8zqC zg_=KFephs+oMU2w_g;T2q+wY?Efm2u4|RL9TJ&!BQ15|e5m;pVL~a6d)|@jqrvMjW zaTM1J)-m3#OtKi`Rwjcd((eaFGhBjO^ogiPZ+$HKMV*4$O9<-w%{-izpYY%u_l7y~ z2(v}0ixiPglf@X9sQ1#3XLKCk;caDfA)h&241$-g`wBSh;^@;G;aIc^5(u?x}fRuY+>9s;RRBYb}ck^$RtN!JM}@CZhImB~HT)El?RZo~7DDg3^zEmjc_mzo z4~ZQUr)~W}8;o$cE?qr_{VfY#G6@bE#22=1Sk63)5a~ttJ`*h)Sny`HM^=kj9mgo@ zxVYCb*{*tKAnf+SIP#6E&S_}K9fCob`T6N-BQw*pFwL=;u0RHUo9VzO;!WG_hS;cT zqG6G?_4;?#+ z^UfAr3|WrhqSBCURw#C1)C6j{AlGF5gus46;k%ZRJo$Y z^_-cql65jQ{t6BHGE6P5i_n1XeI)`~Sa9fMZZ<>VQ7sQ6DlcFr0^|FIb_EHh)}^ksAyz)lrm>==e9HtY|B=^u`{e?vEaZ zXZ<_%%^qextF0Hns>ODS1+LS+MXFv%l{k_21g#xTb0#mQfTh&Ql8dKscD|!ka{b@p zOe(P-aaC7Su0Yh?x};qYdwQnblq*!v$i}FL*&gauTP?Z4fqFnSql#5~1fES6n;$f} z4jNsj(BBut93vNEif_`q|BAg~akW*?^$7C&@(OFyj&H@DR$CD-sDrV*3FM#hP=BfJB7b;x zK_<4UEuO8k;-c_x)aeDYkBv|7pPiZ~@6h0oI||0{1v+(6_%yose;RR|{<$c8YY9m3 zy|4K}Z*CnqObxh&G)gSVma`W&9Y;`aRCjqMy(eiGfWOYP-&|=YB~5`mdmWm23Egfr zs%106s302fooHAI$GiJvMI2%pB^k zgNu@W#E?7p1*-U7l-bHLMlHr_qBxkQ{2&6VTkv&S_k-xwIv%7Fgv7!)IGIRKlU))! z4BVM(P35eglT~vNVonEB-OK1SOVFdY;?e38LT4{yiDSWmQ%U<#3^z7_zBy19Uz_2O z;d@If18O;va7U2`|Cgbs^kVsVb0W*=AUIApp$$KZy(z^guTXU7GtE%!#Jjj9{R57RSi=1!X zbmIqV_0@QiDVXV0(4t>OGurfvXi#L~Lcq$JF*S9*47eqcse|Pn)-mM_gA?=Rc-=ca zmp?~v38lMJa=ESUPUEy9^H#n(F$b2JlC#jfaGb`vDC(*(v{ao2;8qxT4*^9g zl_>TLb@Ao_spPL4eSQG*0?xu7gsdTq3j>lqIV%Mq|qEsv6a1DdudUWuJ4 z=gWa0MIxxDbeA4pDrwQc$NAH{*D-a=K)leO{&OAOAwa>CAK`L1E&f&XY-Pa@oR&E2 z?rIU2MrFp2FS{XpBeqFom28(VvTC+pETYy|g>Pu4Ou;WADxW(e7=;JpSaXZ;9x~Re zh>B6HP5nVi#Jg|a4{C#W?02%uCBWzm1og7vLC1d<<+i;Tct+rvmJvadeiKcbSg>a? zTkWPU94M-|fg^OB_vR`dxUDGrCYI+G+^=}oiksp$51Wo*aWFzbBrU!z!rEDI21_k` za$-6=-D=(lXGSIBkuh#_F;9|wjW9nfCyJ^1pV+`Uhqp`*5q#Rx=|4s5))suZs?6Hc z+4NMY#q2Q^%6)2m2mLh^)5}{3o7>W@JEC1n3y$C|gBw8u)YTxPb^p@ni!%l;TLG#W(I z$ZxVnx`5oTAqCzQzKO|*=OU=ZwOuB^JN0T<{!IaX0n--O)|{)u*$^dHhpSj->=$yC z_Y>HzGwX@knq1`#nNB5l@nER%!({UnP-F=k3*GpB5zs;)U zuY`Ku!MJs}K89ZC_3K1~ABe7PEjW@>TB5jh+Ga{ocp)}EKF4geUI&%yFHziIBDlc` z$sUuFI~ga`Q2D&x=LTCww;zaS{YFE>UWCNdc$dn5{v{gsw+Qx1MPem(ksM~u!k(Y% z)0)4r3-A!}+DN5-RL!M4K9zjUf$zk$eXg|IvVBAYAJ4QetGTp~xzHlp$Lpp#!MgzE zVB5p2r#;Q~ft!i)#~!YK_(N>$)rls(-#L0&^$NoXJ^?p|YT? zqI(jBFkmJ%{s)tKe_xa}^0d4Q-TOzhZ)?FBoWe@LW!>rJe=BRhm$~89UpmpK=W`E9 zT=vO%Cb@0t8pE&Q&mbfg$|)wkjxZ4(XdDyG14~aCOtO^mvfxv0vbn5p(IF4x%Oc+KarD_-@pgGEGvg z@rfGOFuo_|PE3c+z+lDzbfOgMpf0bu;Rzp0lH9Ts0%ClLg=WKU7Y` ziy4^Wt}>Z!RyP_%_F|fx`4nWD`f3nuv_;8E z>|WWt4#L3G21ljuyNxL-&q?B_VKai;%yhv0Si05LxU0{S2+U;6Rw>tn8MCQJ z4WqSDf<&eDcIDSFW~w$HY;WcQ%wcrd>D)$RB@ryvn-xZhC%aD>&*!$3+x<-RW7F=Scb{e^H4o$CX ztZF-REv{!EB;&Jop%>L6?{+E+@~BpyMkRQ9Q=^W0CSCF}S~b0a z%m|O=?a%{q@ktPz*2zzePZ`aAq5hJj&Fv`C+t_Kl@B%z?BE$`#o8CrHLkm96_BpP( z?%AO!-_NOh`B`qej06?aaMxr2J@7FCiY!=}>z*j;RXlDo^YdKZT(@LYYF^t+yor%7 zN!jHC5bY}wf)VmIw@b2Hkerw{J_X)4CgNkQX3~p5`d-tH7EQ&`^cOMfk?-y0kquBV zNPBbuHXfnUk?~bz1#XlS-<3M!y^x8-?9uox-S`w7JIx*o=X#E7EqqVw16J^v#}sfb zLvYI9B<26;u^ia)7mHj;uSwEB9#~>}UT{lPEGaAWZ-JGHE6p9x6vcOrVDvuACRa-m z!Qp#G4+X6^(<_tq1)-hddqa-}I?IjJLF$_=vVmRVMhTirA2l)Fx0RIPLf*Sr2DM2xVyMoPa6v_W#&g4JZo|DLgl>b;Ic8|;f`+x^ zE#KaQdiETR<~#v47IDr_^$u^os| zF_`W)FarBnaI}flX#%iMEK0cp`A@ zXxhMnmsb(JhvFI;$Gk63!Hog*w3|aPx4f^ZOKN*loj#$Bi&Q(;fJHu6C3W_EWI4CD z{8Sg$NgTuGWP#gsJAhT}ZUPisnK>NGv+SC{_+HY&p*;%0z56s;l%e?E)1pC0LvU8- z|K=$)YK{@>EKToZTs2>hP#%XoY}M3VHN0titFU@cn|ZLv@X+ek;2tvUl7~wSJM(Z5 zV3j;<2TGNty}>N(^7n8<8ub|eB%KK`ns>2a{{`-9LUcEmLAnKC-&NWyq+XBU)b0a<;`_d~0oV#R ziYh55wS&N3b)(#ncKxDV--eDE0Arlu&M%AmC2obu6c>Gu8yE0;H}=Jt~^1l z(klLh07sAf3H;v!#M_YBP_+fYnW2*)m_MxJ6k0t7-ZZ}THA=lX6Uz~L$78^Od(SQP zYth2iVfCI-Dk;$FlEpOuU9LGj(G6#%=;jgnqM`$LRfHrBfd z;Zi&mH!~WCTku|Yjo$)v8`JPsL8yI)+OgQ<>v| zyXb&L5MA}D%jbVx+8n-vXO^5}kmCW4T`l;Gpye%$#@#Hq8)UgYQ_=zZzN&Qq>j(sA z!3+h#{6(8RnahBO%90VZIn-#JVZnt}Bz|m4+zj@^2u_JRSRxi>M}WQJMp-K<`?agU z+TE;}w@Bf;SiW@8*H~*ijK^muJmw>wqU&Ks;|>;lu8Ik@7eCSj?}LR0CbM`(@#A(2 zMvj|Lp)MBS=Ayq@7kuACUbn)h!yGIT5awE9lK}J6MShWiXE~!8fv@%8a2ta|XiY23 z=(^$Be-uLWNHQXfU_T39BE=PCVz#>bJ=}qy=m=xCcQiQ9B9x890R0UbcpY!r8xhvr z@sP2|d)*UvdJU%K4@$wjG|yqS{TPJ$0bivH3ZP^cOwDU&+Ih>7kNokeH~_$wUjzof zy9gdKrVA=-Wo)p?e89SrM0&P0o|qOK&-ybe^OE@*t!!<)=Z$j~p8k_C+rfv*qfTk+ z)-Z4SeNI?IM`kSYRA=fH~1;OzIyK zmy?xZe&CvmYS@xxZH;rlr@^iLS+PRjT#kJa9?&tp^cb}ANI|`Xy&|G?_P|jn9e=7^V z>@J}JJ!+XjRNTe*aac5x&qeSVZJIWxvuq+mVmi2(rdV7NEXkSWlz$OCnCNC#<40Qn zI&S&%n4gTMi;o+P8(44wr*T%+GGdQcedycPMvgbmdU$fB4orhFf2-=-5w&R0+_1nP z)uNQUr~VWm|L}oNqknb_i=E?MK7V@X6-hq&ZbHn@^s21gdyO7_hRurn4M;bOV zB%MBsGMY88V12op!3~z<pNa>s94<@H zm3HtDl0o-l4F6sh9M6fI?do*~-O6jO3&uRgAxDPiSJ24bMuqn!)B)FSSq8FlUsdO$ z&M(ak3uvTPQryk@7-l((_BNhLi3NDrWKz>uBdDbXpL0)Cd*vgQcAs)$@sQq)9iGw1 z*CjY+>}xb`Wx)|h;gYWu2Jy+4iK+6Nvi9>Bn+C6>$$ha#IQkr(-0+8!^&Iu>XEYsc z!3CVg^bxe;eLUS5bgXaI0zM~2R=Nt?1F%ZFS^|`6?!ctVOLn{>d=p42J!kZy;&I^y zT^ej;dPhuv%PscllZD4^v4^@73)Ij1ht{W({-MJ0%(ZxYR=HXA4THJyh2}Dq?b<6b zLtQXy7~@>@6$7kdX(CXv2PB!k<@o`LkG05Waj^VS8uq(>{7Y5(GE(j-Ide3Am06*c z`LS(Tg+Tz}%y_Etgb@~I!FQ3`F~xrymNs0?6K?5pi3=F>VVZCOdkB?+ygRIhdkTcO zY_u-izMk$|i+YBJHR`TdlrE6rB61qQM5oB-7{reHb6At}l{3y)!fL7r!P>e~i)}Sb zWfN=WQ0GBLP>2OXv#acV04vR5aiO#{TOyOo_oyA2PrFWbzK0aN^{x?6q=KJxxWFV zYtxZ?FP{Qw{%+HvzQ$H>EeCTjbcd`wbcNd<>UHeKqAU10dVxibXRDm`JYy{z?b-{{ zB*wKD#4^U2kx&NRGExtiDjE3(YScu&M^D3s8ug0i1LpauOE)RCP`vHq=q2S6=brsf zB(4z77jvHHmxbIERcLfA5*{CZ1)uL99vaFZ9Ko?El9V$EQ+#dX`}E6DW4Dd_MC9wZ zSyMo74>LlZwBS^8~cr@?$@wj(}3MrUK7vqhWO_0Jti4cLquw>9{kv z5u=#4C`(b4C9*Z!4ny;@HCQY^Plui|S`}IF1{Urtz!~cS#^N5H*(}l+bUbUvK7}{Q z47(W@YGT}ss|Q>a<1SP&j&c$V-v$~OWh1WAL4Tt)3C4T2E^wEpWMU>)NKcP6{M%S? zDeH9FeD+awhk#OfqSA-1jWn{K)cWDr8baI@^kr-^CwcelIWQ>(-}W+J!N}^gm~Kn) z(jjW*PE84a2&k%l>@PNScnF~S>Ia0hqp{u{Wo-?QBV z>jMP1_y74>qm`cpk8)?9U)}hmV~bW36{tckB`%l+Qp1 z!KUc_n%)!?64rQ>xv6iF54(#9*aSQHw$G&W{_&2Ne>H%s()oWxDsxqhr_!#a*cCDj zrtfBAj&&muD+#ujd(Xg^$UD;rDYD>htig1E$~|cxgG1pLU<|H%@^kBLM&!Z^fV_F~ z6j+usCdHhDJ^}b;z*X!?0?N&vJRtBZRISY_+LLI!;mrjS*#pgUCJN=ArhZ@Do1#O) z>N#cr7Wo2eblSM`O;?lpz=Wxc`G2&%e|*o?|NsAdoagpI{ zksrfiu^6U?VKEXiX(IVC!d(pGC8Wi$dX5$&l^89lq@|@LY1JxeY3X~rKc3IC=i^D2 z?_clF)8%;VdhYjgKfll8*Lj>{O42k#BYwfKNz+m%&&K1Skx+UBp7*8mUn8B^qHoq* zY*vKVnGWq)p~!fBs2lHhoJAVNj8Vf;EG=orOteyNYq#MNm($lX)Mhb~3pfF;6yJL= z>MQVi;3W7XMW5RJoHToZX4qK6TD4SP7RaJVfkRQA)(nd%X59*8##zzy6A z8b1s7m6A&lz?9k0*B*$zF1#MdZ1sNU)8db2savBehGOU(hGFnU44=z|vfNsm&mhj( z|56$QL(?37M&c*GM!ROKCEmUxF}T3#t7uW0+SE((QW`lQ^LdV@sR!F&L0vrpZow+V zfc+HylBB3 z_3&e92$Bbv_7Z}vz!Dis6V3<+bHrnu3Z>Rr&Jg>%KF#1tx%Xfh{z%K_s)eG@F^Wl7 z+lx5`l$Nd*hVsU1P2loZE0)1ml;_V1i}VUSfXCgrXKDC6^|-f=yKjD~?YD;N&sRf( zBu7HYNWfg|YCGA{B%U~6%v%WUqzpVPww%YL6a?%Jhm~ABX1@uK(Fis5)Oq1}X%d&M zd(qB$>NIcPQE0hvrE6&5(`rx`$(bC>;87znhjHA)7Rzzqz%21C66+7`p>WDa_)_{F zJoX)+b}MjM;W8QzaXMV?S{kYQrawKp_F&#Lwnu%umjl&1>Qt z7x`m-2ClL;I){Cz5KB3y;0>hUVR-CBklDjn!hcM`AJ5>Asq^s1l;!yE3DA^m{4tvU zcng2TyiPq9BGH^+-_bbRWYN8aYU>*I$)yg9RR74wa*^+R(E{204XSmZs=SO?2f@Fk zaVKfI-~1a2*f)sRtSE*2CLMkjCv6Wz$5G(Qd-f7FI6`s+?3unAtg#g|Od+u-}}e)q!;T;C2gc z!6w?b6gO9rE1+pgG2TDpW?;^gKIWYaGTF2L+;lfjyq$z6rYp#KcHH`6;dx(%>%zd4Cdr=YaPov5b~1 z!)Y@WjU^uCQL>qOJg){$kQ~8=Tn%O`@V*R9f)~ytJY9sdyaITC@#E#NxzP+i<<(Q<*roL?X-txY8}OZMoXIvE&N(Fe1+} z+3V-!sw&Eg>CSRBNMv;){}s-kHA&GLKQElEt*LV&O^L|+}3>Vn@15V&_*lc z&_;0{S-O=fR^Vx;u@Pozd^IZnb-BSyyKjCYA- z$IYkj9u!m3VcPJLI5{YASlR&I z^}~qO_t}d$YaM~-Xk&vA$HO__=iyrg)%)7(NqD(;!0+IL$4tibNp8ZI4%3Jsn0fF~ zV0bOszE+*~Xl{2rq=pOIiHu|KdAnA7;Ltv!V<+O>@mwPz7K_yB%n2DY8_P96Idv3P zW5vZPuaERNd-t6*OD^d>eaIi_bw4zr(eWx9UjZz|?tjQ~FJsk}?&`FiWk1BNp1(&XGq?+PPj$^)5n5 zm%vr!P~-J#keB3QidnCo_fAFKZ-7hPMGZHo!8KfV#L+QFZBXCyzKrmbp>%r}g}khW zJXyn>cAnFX^`M```gV>S%{mHSw?QrGc&TtB;y@^f^|JLrLn5x5v^maz%%L?oYmz`(CA13V+` z+EK@8+(`VzRaduaU@wM{?CD>Gkb6dzL4`3Y4Pv(~~>Y z7Eel!e-pVL)erBhQ)lq#;dm{DjiEjg7OW4BCxJupBze{ptZl*du^(Rd70J`^dZ0*F z!4tn2I=o%Y_0C7cW2WG0<~7>46Bme*%bh9wai@C6I~fX9Pa>5E=*Jv2Btx>tTh0`Y zm^;Os!of)42FUJ9P87TzNX|5Pj!R2T#U8D^_^~4|kHFLaAF*{R9&aJuacNJ_!K|Ap z#tyv6mgc_vw6i7aREq=9IroHVOdjzO9oU8Lk@^KjLb%9-G<`R&nz^P&aAgPS`2W<9#*z~_URR=K*&Rcbwnu%h!O$}F3b@2W zxGBVpp%QOz8o4>VF_tgodY9tW?j}w%PE9lRRpy)>vO5}Y_gB@Q8?d=8aOG_Blu%B< zq))u9NqdJ$DK2w2>0jV((n`SxaDz;H)lVCQ!CDktavm&VamQR(j0*@4402eM;?8Ws zmCqp#3m5jOpL=s?&P!Py9o(-*1V~PC53-~tNE?cL4R3-tAG_fa4I92g&WS9|#(b$D_xzyGwkXpysUn#Otr{KBP1)!ony zdhQJr!id*#Qb~X%RvUVRf^yZM0LdQ5+;ZK7zB%Lwf=#}2(Fv!2gO?9*XOB?VH`I_e zlB3+i&1bCHsf;T%!C`6B8|nw%rD*HZui{qkC_Qmd4Q?rUqq~tyj8oCNJEL{yJHnql zsDA3rVLiUY8SyCXIHU%(l3eK?zWs4ic;DlWcKXL5R3KM^KrXWL>9ahwRaePFIfSdu zcQ7U!-xP2MTgqtccE+csna8QqVLYMeUP6-(t9QMJUPH6`8Z#i?q$iFbQIZSYZT`k6 zGxfDIQSTg4Yl-$HbnXb|ZDoCq4~bDio!_DZN7dlYl6~KHOWZ6*X(*1NW@za2wj;0g z^3~5D=Yonw+G6c!H<)Slw`T)xHv{5u(K{zS;R&p?<7hQfakYCqx6JVryTxi14O4bYAlD&#?E^iXYMViWlEiI;EC+T^(g5j3(82i-}a}TDP zoY@K;Is51>HIPgGr?=EkynQZXLvpm`xMOtAuC{6=c|Qkr)#eRGSzu?KhQbTDKVL#~ zz)*)a;(bgFYbDv^9XA7g8Kr@+cN{5s@)#QAZPa@cw5j~#H1N3Eys_jYcLU4bp(V%F zd$HV&7oe7hzKtru&K~=PQ6=cgjthRH6HBEWcNr0+v@F6+#UDA-7JK) zeX!JWhN`hC-OU3r6d9i*0JvR*VtkSI5rsm|U>a@wRhzE-=>j5W_ z5qvQFkJZSCajorqR_|!3QgM%aBCb9d?Fa7B()5!!-Ez<8ajWD6wJB0V2TQJUH#gxV z^5mF2^3D&q3IX1isV4AJ@Yc<77HxNuPKDu7NKJ-%H9?c$(@FM8WC-ude)IO`u7}lQ zhVkSX$N5GoE#~N4CA#4xp9CAywo~e1Z>#~YuZ8n1qA{n{u*Q<}+{3(o(ou7JPvb=$ zk3|FFGK&!TN}*g+8c@ktn;&JotE!EqwA|goU8jY^@8a>rew0xPdURD0%{rsDjFKEs z(_t4 zf{8=phE41zx0F<*YG>G)mXbCF6CJA2ejjJVa=~~JwMMZFIfYxlnYcsn^$+)=4)Gq- zyxDvhT<#gVbyf|vNltUOvz2jf&77+hryQj<=tK3*`W$=?n|Tja_<>LcHlUmYn_o{y zFObp#cZ1%iVekp##TNJGKi%zr;j};J90tyX@wjM(OMah5oW~c&l5K3lk=0`#V?}F5 zjL>{OcMQ>s;d5VKmnMCm$tid^%2Tv3oLM%SU$w+YHDb#WE%%_C3*J)Rx;VgmE9#Sg79D~_*% zcL8e}bi2A@_tJidhoerb-p zBxYfj!FpWpe?%Fdso^%sD`Cx4QtvZ5Z{OJJek%D)4K$LijMWolE~)x6^`{0^>u?hf zyG11!(!RsMTfYg_ZW!LAgQL!*xZFL8(6jDQc$_sFc&%}Y%lwop>d)ReNbZ;ocq{oa zjsF6#lqJWo0axX!AG+JS3GsbZ`y#v?x6T${uAW^>`^hTGW~k|c^9^b-b=E_j zoNpVau+M{a@F|5{#mk}}tHrKJ;gCfOC5!Am_DT4MjxSEIG&s;JtI4%BFN*VlhSh`9OkI>TUD=>&$ixE zlwSold|DFj=dGkebqO3c`}z@~E4yMA6`ao%I#`Z0OJ3>_mqBz3F8K;A{0?HtISz3N zL|5Souh7675KAtir*5d!e*aFq=79720;xEqD8~eUw$jZlKT@a6k?hDE)WiX}R1Sku z$QA0Nqp@>yN4HQ?3#&_U9eHm-EW6>(d_g;I;z_3D;9^G|pL-aW32=c|Y5EUpGjGW; z#axIxMfz3hbPI)-RBY4*Ro+r{QGAu|vggub3Mx}KHz-0*&%uR#iKL+++)(gk<>_=2Nc_~!iz zTv;jY_yy%6x$^~HeIl54d>dYeGQL))QDP-Zr1MwwM5Wq7#9lD+;f-&}^?10IUs0Q1 zVP0~gQyz$I!GqySzoMTZ_m!M>!8qp>(xh8zmJJ3H;3BUfUxf~(7#{DY8BQ$p$4+v-N|;??M~aMfkh^bfU}m*h(7^9RZ&3!);pv~TE3i0euA zy=auVrI6NNQyWp`Zz?v@f?g(E`8Txfj@qog z&BeMAzDBnzmfc`omX$srbK3E(QeXB?OviQfJY3XXr#Gr_wJA9c8Q={+CQin?P1zuh zqNe9S;Qy;K9pSRzY6|z5(F)Qm{%gbr_@Dbv*=wR0{`dY%hO))Eo*wy2&FoRV3d8G5 zJpBX>`mCZntqx0=h=H#o`Zw=Xq)3Gc0aJEJGLC!4)uQ3S!bFt!@ajBfp{KI_fj@5L>^MZ$OVRJ9t^Omgr?j_NVj z%s5(iPi^?H?5UZe7=e8e_`W(qPt6ha;Xl+}Mt7^#SHjzO;)QMk9E}tWpqs_l;gwY5 z)iIL&sPG^4padVu;^W3ptWb9v?hG_wTjt-UJS<~5A>g<-Ap3^owUa$fW z$yVZG;3gu&w7}NfX7G`YGcGBvL|pzCl|pD=g{w*P??zr1Sp07(rSMOIC6kQO6zyg2 zFicO1gS&l`Y74D#SINF5C|yjOm!&hrDf>lig@08YcOf^8 z7MoRVws#z|p9SahBc1Zp{JkU>Qkkc=E?kEw7H;*Aj@HxMD4{;XW$TghQu6WEg6##W z7OQxttwaF0?Azq6YfZc)S5rG3#di>wAbgooeVfkdT3A!bfghs=U7Pjnuyp*GpN;xs zg){A0?~PdVir2b|`-Ap+Y2DjN?$4o&6=*HKUY`rgOy)GKO*MChV+GQEmT@0bZEtO# zm|2V7^43E2Q(tlyPwhly-da|h9HewBI!MJI$l^h((uT8Wnn)w%OFuT(WD2&PKZuaU za5c4+SZWMy7XRhqBK&Xtr)-y~fWQ9Ye}#KTc*DQdf6BfPHu(3S{GY-<#6bA}w`{#N z8M3AS8SV}1GWc&s_Dz|fbw1kqw%vcj8cJ}g{%5hvV z^U_YP>qM!cU!vH$+E$_K_VT(~Ypck4hiW&_4v5t!=~x5ppwLgyG(U_7txk~A5Q>%W z(DsJfS`qvIL9fa-2>DXnRHeF`Cv`+aW3o$g7EV zLJT=!|FDTRN)gq^s9B))7QS7ze;TMARmA&6v?@q@K^Lbix~F1&ow9(2H667VM9Nue*a>Nv ze3oA8q%9OHKctoq!9dK1^d29NoTI6oQKH%B=%3EeKYgB-cR^;Zo+GcW(2qPv%e!i) zMZ){`!QHeVMI?P-pBAMxQ3Q6y*5TfT%zVN+BmWHEG>%BCJSso@pX(g zOMG^oM)bk)`Z+q;N1HD652s;7 z()axkbkBJj+aJ95J$ko4(vWkO1`W`5=tX#pgW5etBL`}UV$NuKWS}-#*+B;fYEzUv zsy|4Zf;oEh^dR`=(bYlPY^8*T#A?rrI!W|VtTtI+>aehvwhz`4l^ohU7(qrQ(cgoS z1KULV#39;P50P|=3WjS>h`>`6JOW3*)3kB~6c+cSiV;X(a3&?jq4f8kqVhOxf_~Z2 z>ayv?a4m>ZMrwVIu4}&XzvrkRb<_VEd-(EUF>uD9s)=<;Q2vM@e{`6$6mm-SS zk$nnka{oH2n+!qL8k&&|6RB(H>ty&ZSV!Ha;+U|;zHX|vsjgm*>mIA+3k#KP(MD6o zJZ+IWV^S)%T(aMur{&ic_pZ}{=h21|HrTsoYU31MdM|51R*{%%@3>i;qlofc`>Uh{TE*p`=-sWXvfn;so7PSd_0Y*rwSH9lORW~o+oe6{tRkx1rNxTqebjxoc2bn@w*S3bdqwD6 zlvc|fqe>sAzh2cAO8uF8wTZ%KkNx6aZMjvXziNNv>D13I)#HsSw!vg z(AzLiFAu&I^ba2jXxd>26Y}hz9oB4Uf`c~aqZI@UvZv&0^Q^*>LSNg_8%yS(+@h_~ zRPUIUs0Ypjb+>jgNNkxywT{7ZIn6qTKAOGV{>d?I1h(L_w;(S9{+3T8>reOe4=}-GVTAi`&3n z#b^W`>O-FOQPb9|mIj_y>pt3hPP^z6f+}obO=EvQT6|uM(fhw*gvzHg=e3QZJfFrD zYYUZp3MtmQ=>?k&;g{rhL2FS@4K*6qZPq@$O zK^v=tQq)DQQu&#}Kf;ia)rDU82z{jNO}g=sc0^Qr*|(Nx$Ca9T{^$ekQCd2$rpoML zpJ)N9*Uiqb8Ekz+(10(r@m{G8+$ij?eW5kDFLc0{+QP;)-9{MQ%G9ee_Gv+l`lLR| zpQxnF>`YG7D^fAS`&Kn8?ABAm6NRU|7r@{ zJl0jG;VH4#!cPcP%IR``pGzttW?+ig{j_Vp_5D%TzX z)%#Y9Zl2r`^&4-EaE@Lz32SbcoJ_IbX~Tk1ybr@D7YDoUEK|p-4V(kn9>bKrBNC>1 zTm9*u@3cP6<@kpb8i8c_8Dp1FXygs_fK(3B-CEoJ$_?#nTwm0tg*UZ(!q1Nu{-Av( z5`1XXE$y1{@S#pWYPUpgeS1)aMv924P4=H~ol&e&zn`^N#ePrwt)I0bAvXHhbALrg z7fV&U@9)}vT&ny_$8T%zTd^Co{rNw%+a4nJTYBcMwp1*xMStJLX(G86J^we3o&Ta* z)fgN%{zP>k`eu=Q_szF;e?{c~MW0}! zEs^*a%@#T?zy6}OR{gZ7`kQ{SVpqq|ziFoj^!@*)Zl3xw5%ahGZBJ|`Azrvcc-X&0 zq~4(^n!Z-V{Yk%T`VmoZhxY0EMNxT&p7zquiKsi&&s*OuR^PFI@2!vW5Ctu$M_v7_ zNdJdCeIdB%Nw4|p3x(}pYFSTTB?3I`hwJG9iii>R^Y!)mNTaZS-9XP)M3DzQ+fXkR z6(08S{yNUvkzus0k$y(xDfUSL`gkGAo7qn^(fx%e477h1sHZ97O0YdPNDo%Tf)M-k z=DLR>;+s=iFj5}doGOF$=_0xoC5GrPh$LSs577(7?I!l!p&TOCm(H}%i$q|k{e>_c zSB`spX?IKgu1NKz9j){nk>yD-tx+gTo70)r$U=H^im|~$xv%}6P4~rh#lPg+1`0R- zp^a_y3XxmSzO1d@MiI%C_Ja{Rt_$Mo*uC4c?c6%{Rvq*tMP%2bm61qR=W6@yNL@$v zL+$rE>KhcXvAKQ2L;4A{kGl3zUGy=?+&wzbRWA^$Jt(;wvXI@BD!S>_0+V)cMd|Yu zE7ldaPwB3AP()!hZS0|cW-Wuy%xJx%Re02)oZk8laRn&Tp?yr8{;neYYEjcsXgP1yqSr^EA>67(BSxbX z^J>xg(fTa0xt6_0yxzk@WbU*tNI*&8O7XeJ^tnp8{g21=Cxyt$vrkCW(YAdK(yYf( z%$fQ0+vEBHQ9qA%OwgC%j2SXfe^(?eqZ<>E(fp(ILK2!}+CdsM32i+15cy9=i}QJ& zc27noVh+*#Dd-DZ4pIGNG?3tfv>_Qyx>FtvoQj0)Jw&Ic>RU1TJpKgCt~_iHeNvB8 zMD$!rPeFoX=2Cfzeoge6OJ}C({|euE_V=di-ikQBn?9a_h&Jw~$5T;CXLIPgR2V#x zLz8AAq9+#6H#7C0MQILwJPQdKx{F?&jXrdC7tKq|LSJqli{Pf_ksC47}?N?Zq_pF{YmL+BOnz&{-*HV&d)S?FMvSgO4q z$M_g}21nc{m9Iy9V`A*jZqQXlxoXdRS=SV?c@VAHh@mjDx4q{kZf-&S?ZY)MSA3KkvhFehzX(R31x9Sfm!uMOcv`xkcc2W?M^WJp{f1IW|J$iQD}ukZhvw+@Q0{~6U3Ter72z?MI{pt`B_Wnh{ZGFk z5{A-idtj(e6g~AS{8JyXD|>a^b|-hEmiwR(+09;izup{$NbO$JpNHkcujx+4a71TLwdwGm-JDJ2pCOipP+d)8BJxMz;M`Td%|VChawin)22@`a92{?XZiFbJ<^L`eZ%{P;;>Of>u%{|mAB}797N#`iundc25RL)jJjC=r-Rm3)j}L;Zi!@v@K%D`C9dg#9uLjl84#QCKC+ zX04`YE0N!X)%0s6PPvI#Kk8Q$YxOF6+d7_PPg^Hg=Lz( z!ykNp&xhU}6nnu6YV;?1Xjm-$`=>rZY*|4QtMt8M;{dz%7mqG+P`HbRs;{uqU40lf zU&1Yh`?H4spZk;%|LV5d?sq4J)%tE#q^+bRtJef^a0eAxy+(E0B0#}%(v4p*{_jtX7I}41#?Y`uD6uh= zw#ciQ-xwn$@eVD=|7U2|BCqbsY07H@i>K{(7kPDB)y5iH%R>q47u#p_=)t2Wj(8;4 z78!0)T1t-rqecbW+I56iE4tRwyOGkGepVYaQfySG6{sx*X$`t4?WsidZmD#z@95m@ zXXj*++2V6bU*7~;YA!mQV8vxkg&X2jV{U`S8-;b?Wcn}p9+pqLT zeOnt5^BaXUu(kG#|6N!jX-5NFqq?IO7dTyP5u0Aq2hKmJ?RI3+&ix3qmM?1*+0pPK4m`ZO?UkezN!|5 zG_*yCz}hsTA(9_ihZZ)3{lvQT8vAGZ(&r6r!6K_3{nZfRa_Uo%zb#DUHK6|f2w&ny zGyGwoAZND6I&+~4d-Lz~z_#Fb7oy9pXW z;X{3iY@s+T7IE z#wX@stEE(`hddVUM`cj=4D4>j%5WipXnKz%g!>x#?O>FJFSgVRv~?7EG>r^I{1wr( zED-4p>_z+em>)wI1ChSlz3ErxQjGP@Y$HX<0Gi&+_K+wWNIRR^B1Od@`WVMr9*aF^ip$_?wL_^g#8Of)0fR{%>{O|sBVtZ%Ns+%!6?n_u{0nUsY*+r8NmqWF^<*- z+Zv0)ar9cSExgvA@yIvwxd(d=Wra62^6h8?TN2451eVhur*3ArD zr94Srgu+}EmYxo^^$_LLD5?eYE2q==7Vs~fLC>~;-q}>jZeeRG7SEz%%n7sU3hO1M z(cdl5jPjqNR$*u+E9X#L804ArX?7UmS^W%c2}ALxE~E=!pFNAL#tsNZGx_yjkA|jx zk-eBgTB0!XpQTtnmMx*#Ezx$cxFL=W>8r)zwdq7lR8!7UI>(Zw&(WVP(W>zLrDZD= zbJX)Rq?N5zdt0U>mRC@ueTNN>jEZth_5oVL;jp~Yaw|`5v#80c66~k0-f6dupx&^BstRIQgQ6*%o@%sIBXRZ5sst> zZlR&!h$H6}njMaszMW0$*}rNO9S*nsPXzCxF>Nqlr0u3l&Q$s-wwrP4dK+iTHY-ev_jBm6m2f>Uev$GP zEoqN@N7-pdd$i!l0y^6s`3*iszqd#JgO5}54(QT1-=>%jNV&&5l-2<)8xt&E>3}9u zdV=2XfT5!JBvo}llFk-UcqE!k{wW$83I9E(=|$$?_sAZ}L&^JeBN8Qn56S9uv~?A} zXZaXF6FMRhE6>rAjwr6B=P9S7Ei@>x*lNi}vRA;R%}bp-6-Swos$weZ2!lQssct72 zth`9wIw8R&A7Psdj9~>Ow7C-!l=Crt&oceEGwpwn&%0@U^+CSWJYI2M= zC7;r;hmg7a&uIQbw)VA3K6kVy=u%c@c)(bW-f;p-`oe1QKv8dkPv6mT&V~P2?r8MM zSFM&p5cja;si~8m!Dl|0Cd$87a9E@LORFUw2DX7HtDiF+L53{iE9%u5<=|09Nqj8$ zhL&}V>8^O$;tTP4;f?Dw^qwg7~}$bG>+G{NS`x1)ldk=|H4vQPTzG# zYYDhPUR^L4CVx*Iy4XT|_S|%wXE`f$qHnmrF(^5%POkhwOS+(Rt8dZXF6g2$6?6f| zI{80YEs-^m(fV#SKfQ?&OZm?f*cBb6;uq@P)z(C;uB0(t(SQW*-MO{t)}EzmP6(8H2LN)LR$`%`yYU2&xu z-Ro{^>1k>1f#;=$e{>IdP2UkKb7=ERd@`fJ3UeKX@e-N7m9pwERF01z14&1xnAhs zmxs{NUa*_@2wm+3JBh={vp2e5!f=Y}ZENS5H^RdbhxZ`1K#IQPS<7fzjtgYVNZQ^T zDTp6UAF^g<7jRS@>4#Z@Ghvi&>yFQ z7^Jgw0$t;y&m{8bgZ$(1XLui5>#*u69+p5f)O^^S&tqc$si{-37&`wPoz3q_O7DY` zEKi}$eNfU>v*<)0lw8;x`lgTVA)n;A9>yH#GYCN;otz!jaj%e>PBDFv>(co&qc2ib z_6)7-i@|2~v*<{$mH0f}=!?`>XOeF}l-kmj6w?p6D1MQq^+PH*uA;U55LfO?bhsbV zP`a8vVgJfCRMijR%GOe7f8+}DXJY#!w^>;yq=Kz#? zLfb=9~)06?Itpz!hH2`J2U>_9@K>D!cPT2s|=IR4fXP~XSxcNG>A59pDtFiK2 zdS)OJS$UXV8wlh5kJ87?XWk@b5IFT1g%7f|u9bA$!#K-ekq#QVDm;W155l!W(%ZCh z5KJc&(p!Tt?#91E-*c$U6I3@A4J7L%b&W+*Gm9uG76bpvQ?w-(^1Rbj6pN0O_b%OL zE<8hlgK?>J`8^Ly3@Q$>SST)5b&S*e#7S8EKA_oy(fCR)(5}HKo|up5gTaV9^%DIt z7;)YFi~@(CSSvrL-h8}$g(eR{v8P?7mxkE7d8U7f9MIY!w#HO8#1$cN~`>yY{PI&{eeagLuIYJMNfkV-2Bnegt;Vm zMY(=>I$}%|2RqM39zUV)ps?O_s-TfidWOZ$HtzE?eK!p4tNLfshU0ko7YZMa>y0y& z6gwORRPrm$7;bx53_V7BnX`YV4~L_`N^a9{!%=DFe^B5ER7%wy4@(x};WHa4q2Ydx zuIji)Sy@GCBWxXOoxST}-28F-sF#U*o1zhDAJu8i~Xg)~2n@d+N~Xk?2%8b?N(&2$$jVh_nu1_f?MK14+ftWD5p6^}N_-Ul$?fSmKHly?d-)jEk4j3d9&8@-8^b+i`MPJd}Dp2E*CIX!>JFK>2Wb`7vb7CytIk zhJ+=Lq%!u;97SH^a7<00PU9fYd5j(#hc;C(j-DNd1YH?VIpes)B+}_|D8TH;sd79g zV4SUyNSWY(cH;q^Cpus}gC&X5$3y*W5@nCK*=l7?ax^Mjn^E49@P_0w9$g|~G6#te zVN)DIr!U1FUJM$&sC4>_yP?*mS?p7oObZi{@TF5JClQuopP;jeIMd+l^=Be7Q2HbV zKaLXGlR`sqtd%;=(^8D~!!fpBiq7=Tooi3;F0X zkM>NoWr?Ku)HMn9z4~dIl!RhUSU}5@P^`9RXg?pr7Sj17=*KRiKa%){W-+yzg!IHd zOG76?Zoxh9BwMs7Swe42LcF*a{)pwdOX&}Av*hPIYiHtr(AwJda7T zFa9X()GjU$R`4+~8^|;<%d2KaTLWR~;yvXVJGe<3W{7x7#8^I_@13S}l{1N`-|Szc*kmh;EUW;uUVEt%!~ z#kFL%&mUz=_C@>_{$g8tumXS7Etw7Qr{9uU&THgKW;w5)E1BiI?yh8(=i#db$t>qj za3yE30xw!BJy?O47M09$UW`;S%XxiN$t>sfR3)>VSL&3^a$dz#GRt`dOebepSb>+v zbb1(#kXP!I%t};dyCG$t>q}Gaa0v7zyA-HO&euP0R+4 zo0tupF)_>cVy^{rc;0bBGRud@xR}GoOU^*6Wd;5mOa@>DKg?2*Y#1=HVZg*JUu$BP zZ!|H>`HMGckLA25H#6FwBLTd`xLJW$jh4&?ctvT+h5-|^oVOP+%l%Bua$fz{Eax?8 z!QB2G3E%~5%?iBWtYkL8i_uEv1n?@hl3C6x+Dc}5j)_@*&crO|RiYj7I}^Z5NSh5* zn3xUla>-^nFU%~N<-A3LWR8HhJdn(C-X1|R%XxzXBmc4lcs~TQ0&im=nGNKbm<{my z6J|LtRUw(>ygz_s4$pfBNM<=N_0Q#xpQ8$RA$-ZKz>82xW&>v@x|ro9CT97yBzJka ziCG>$*ZqrLeUa;1H831yzz6?Aus(PnIlLtF^9ioVwPVqG0WBGP2su!@#gY4;OB^dH=dWw z1`15f25y*`)5r+r%ude!*SNAMwH) zKSu=o!LMWv&))<~=J5Qzu#+>4^F4nkZC2oKswJ}l{_a~c8{kjGC9|AA5SGkx{&-k2 z%lQ*r$t>s3bsgNzG0^Zw>}Cc2;9W8s;PnzDvwe zmh0EV2u z)p8mzE=f$(F#>0_9YC$KU1`~4xJkiupN0GCf*L9N2a-N^c zjKSNXz)MV-6$(tu1}5jY%daz&r*{E0D&0wd#8ndicwb#XLCVHQXSsuLK#Vn6BG0U%+nB})k40(oS z!|Uz_a!t$z`scdK6HUzWizem>%1zAjTW`3B_c`cdV?0}y=kj0!Ste!!2adYS^G(e1 z1^MpsOcS#l`x4ZYDBCYHu`!;#|CYM~e~$@0{2Vo%Uf^Oj!0V71VyB!}E|bi1URzEw zCxF+Plg#oW6C2~%O_K*JRGOF#oH_1ppv1&1Z}YahJkrE0Pct#wPj|6nJS%W{7~@r; ziP=E4iP-?2@7LsrV8hd4!2M0of*I`5qG+ zo#2MagB2=F%mzF@bVbN=-NY;x7w?msnB}WX%;7hh*yseEF1Z`vrO}~>pQ8kL*>uT9 z0!+*i@M6zqIj`F+ndQ8uvt$m>Yqv`_Isq^2Erku_d#dSJIcv za^71*GRt}24aqF$y$GD_=mflWzFC3S^_R>BwtVekHoz;So8`QEx@4B~+VGN%1YUPB z%d=|Oc~a+X4`l#W2sSYrh%qtCV@=HRQRVL87n_*n7jL-BZQnatp44M*x+^R&F&nsZ z%UvG%ql;NS(8Qd;p(bYe7!$KR(aAL@^(_@HgRGEeVm8qICwFVVBvWZ!K#l)PBQWLX0=k|T! zO$>R4rSuPXg>nCPE{D_G;0R<*zdEYWImMBPcd88>lcb%Ws>Q<@mtTt+(S7^BQLPeiL)}JQq90D~oUiU+FO!A?envJkEO92+QDEMID3U+VcH79@-H zb*XTWF(&39NhW4_iiugCYGRh>n3&~zOw95!6GNV1DK~kr!qR%K1hIi^6SI83iCLa& zVwU%>?;bwE#71}%8xKu$O&+Xpr-8cxKR*|24s{#B5+e zD|h))6SG`z?JoB*G0SsI%n8_IV&ih4INaSpiHX@jm5JHF(l#!Amftin%PUOG@~pNl zeU@)Dv2i(27~!r^WMVc@VPZCL+r%tSZs#68#l$Sf5+XGx1r8tOV#npcYL|!6R`KpHXPJ{7%`Gzdpg!;S+uGDLZ^y5QxvEJ5;KTz+x-qyZ8uR$#3+aSjW z?8_kUYb6R)8z{gdG@-;{8; zg<$z+gc)DxSc+HEoDH_M8FID{`%gkW$=N;3i@$)2rMV-FnRJp+!X=@_`_8HTd#%>bud_9xFIJ zwb9lggSP;Y_OGibka!pW0p<;Sq`a1f6TgXDfO)qaDenU2op>Y<0UP@c!Gohu0`qoB zQa)cpf%4up(&Hs4@RlBuw}JzcTzm+eY~qt(`38w2_!9gV3UC4pV2={ZA7J?giRJZR z`SC35&5oYH^0vAk3T(YAg1%7LwVsY_vb7JDvmrR(4fylcS~6kP_$zEQiOsh58S-Hj z>ya0_ob%xm^Xp*VeN2Ws4wet6Sbh%tCgkzX1YZHmhf^&76)c}cF$-_UzMImXzc)&d z_wbV*VNj3{r#L_lFmLTB<-@`9;S|d!f#t&}=5#PGjw1D!gL%tF$pn_qrdWT!H!jY2 zn>VR&0t&oyp5zj+d|1T+u7l;nDdyW?-keVAi&`jI69ZURzHvo(7|i?h$ppLy<~$1zpm%=cAyiyjQa+#wx(#kMn==~4=atysC!Eyo~hc5to40h?CuW#vRi7EcL+XvqlSR4wes!S>CxJq6xuzSJ}9vsW2t@Z7BMVbS30N zu$(W)0Y3*D^W&Tey$((rNqx85CS=IDm8|!hKj!cDblLH0gz>evi-W;(t|jY7fyczS zR`>wC*(CoQeA~o-f$x|&2y343 z>SeMHI*u7~))^Kh5@UT0A4ZDVE_nzz;wcyR2B&Xx@o?}wu+7;7#y3F;Wt$Yzp|Bl{zHhXVm%s;1 z@?7xiCi!`Afk|ElJ_cUw4F5a0bG9o1zD+HbF5ncWylvBXoMB7~eW9=&ywRyJ796?V zWgrdQ5uEIluK>#_23#Wh!0&CR$vG%lIh&3B2M3}J&vV(C3J#p_;$`3<6BAfYX5;Y3 zz)vi2>3<5I{)~%nf_cq8B+KZm_X1I}ylS8H2*t;{mrdLiEN8=U1Y^M07rOM*z;b2+ z%a?<*a$NFPz(-8{2KcOrPdCH4{X=+Q^f9XPQz(?06n+4I1(sFuH&{+(;0WvD8%F2U z1tUi-z#s0yMnO({UBGhY0_zV3_t}kYmYwqPtRSZ@u)=)sCMY<*zEmvhz{kO|gbsk; z-c5aX?IWEr|^p9WpF51+TR0i0Y)b>>>mw7 z;}EJ#;S3b4V3~kV!18H4NALq!K7D8QZs~gP%Nz{e?R*f-91YHF=(0Z&EFT23d}>R0 z$Opgdu@qbs;0llhwl$$kdu_ckk}F*$)e_CCbG3^Hg1dlcIde7@EMMvwcERsJzSSvz z1uWm$vHWfD5C34}Ca3&M@D)?d+-ilY`T`!Z-~I^&`A&`vc(%4!E}&|Hod)WGu{v)} z(c8ey!Ka<_p5QW*d<^&-@Ia@0CRo1lV*4+(MpdoxP-+^_J}AgnR;+LaydH0;aQ$S| z?bqOFQ{(&x9Ory7!usAe*NYP7K(KrpP$6GiOx610U1t_}}O)KH;ci6NiB1Gkgxv z6D*&}Gd~8F&)}KofaN21<`=+AozK>pcY)=zc5pY#Tkwz%*ID5#SUyZ=z7CcT&zb)L zV|C}#ui2I;8S)J>3qEg)ODwdu;m*3c4Yr~2$eh)}eMLAJz0Ii0V6c2a%i(*1595Wc zY>Wxu7*jug3fu=Qd&9~Iv|jmwmJPfLg*Txv0V5#~H2+_3_a0|c^*?@m&zy5Oa`(Z< zHHU^~&WX&J8AdKMk`RSlE1DTb6eW>MI22L{l{TLcQc)@jhoVptxs6Mx2vPWSp;9FI zz25t*HGA3L-|zAL?|1$v&-Z%owbovH?aMi5?=u^*{sLCYkKn3Iw*IOE7qR|+Rmw}& z=f|}umn|a8*TDMwRVh!yKT)oCw>I_D-S1B&p&JQjn5|s;IThq%{k4IVkH-A^_t53Z zN2B^i6p4Sr`{Yf#kTp`wXCrJ6%IPnj6B+ud|hOc0Kw}RwXyqPb8jq)&_X1L|e zjGVrGK^C}^gmXqhAFOX*kn%_Hi+{Qucna&g7o^z)$ z?^hXtGbEfe{5RIOH%JBL8uH!SWw(M5u4A|f&NkczUo?CV)?YD8eWL>e_&NH$?<7Ch zMc<|%1xcxv)tO0}uQo+PtnV_A@{YJ2lQdVA55VJ%bIl0+Vk!H*cawjPE@di^=Iquy zk7_N$`cQlT>#x?O-k-3)l$)Q}i1$N=D`Wi?wB)B^{gt!03)WwDiU%~JS$@^O&PrBL zKP)Q+5$5dRhE|aFoH=?6UVwE+yJGnh1=@YFewbF4AB!&*w-et>ez?5+Z3>9}%lbLPP0Pdj-gGG+g7vN9;wf0)`7NGf}eF`cW)dh7VsX{p6JRMy#Kd z61T?s!6)(kSU>0_9*6Z^=;A4OK5r5Al~5rE!aa{$p=|mr-we%cV%cTaByXxv#dv4_ zcosA5cKgH{K7<+YggZdVP5A)Pa1LJbq+5P3*3S${){p#%SK^*rA?q!< z9{0lfx{=P>yJN|nE3A<3xDw;LP03q0u%y{(Ym-0XZ`jzsu1#)HVMTgEur+HYmCAQW zV>0bl>yjH(F15t1T-N;9NGmk4xIKAYa??5|jdxp8)^EHOTBt@vE}VbQuuo7&1%0Qu z)Gc}b33i0T+mCi^hCPi=jlxNdI!BrDXDvxel^99q`fD?d!Wxq`mk zT&Go>X8-yjYcWhcASH3DC2Kv&PFtV6D>`wa+nv(c>=%Y>VEvNI|K=Xwi+5CZmmi4r zEr`<2NPJA)k|>^m^{sp2dD)zc_W$ly@Gc2`j1H{B`XwFM@9~eg=kxCJe`5Xgj5OfO z;iIY9Zh0B}&k5I|9L_~o2~?mJ*|QsxpkLD99Uk|^{(rj_jKNh5zl0kaeivsO{v3BT z{B4v#t`WG1hZ!!_iapD4J-o+oOMJ|5M;xl^b}$#8H2j$4S98mwQwba=kj-k#2rR-k zRd*BK!_5qD#d~VF<$G}<&R5HSjk9aI72XAM8 zIPba^p7N_}S;Jg9Fj94(KIQr)?X`9twItA!KvTYkk|gQCV0;T+jAfgR$KM#`v#~$R z&3_HIH_mix@$$KD`4+4n9+dhI4jE_D!?-r)qQhC&?{SSyMHR^RdqqzY$-36U`pF@2HlAbT_rdzfAfI((g7qW; z{Unequn6lXf5h>@ny`hz`j{g9lEL}b{sQ@ z@lvDw4!jIkiI;b`dJx!QBn-ei-2`g{K5djw$7gUU)xaYByHOrrw?{u?-QK52zhvF^ zdwc;8z1to4vUgaP{B=`VMuw?AUTC-j-e`CrUeMdkpNdzwj#}>!NWR}q*ogHHVMqgq zu$AkUpT}hk7w^EsF@}@y3d1e%>s#FA`Qa5y{zhzk1vrvEL?Epwz#B*W+~+!h+nn%1 z!%MJ!LQ6Wh7Vp{S=5NE+cGoBH3B!NkabKu%c{-<5N8YgL0Iq?*G<-8o-s@J_3g2Yd z*_w;3&`rhT`(h8uPrkvClzmg~qq`UDmu%vf4Le8DuL+#{*lplEZokpB?@snL!V)zhlXbdqw zJ!8!?d=YUw~V0zq@g@n*w0xY-VOjl1KCh6m!4hNC!pmzzHg>z8bT zUD~wooJ-1eqQ?u|1*+ruSYPWW;ZnvX$i$_wK0LO;la2E3SU;yIEBFAezu5|Qr#(3& zJ&vEm(!MhSQwcmp;BOA>lCS{pGPdb*yc_H5jkWlqQN9gd!uO~K4&g4w95{oE86%X~ zndcUFsNbuR9#$kUl>}Wu687(OMa6XQ%CcvrHNqCIF-$ueD zd$x>SP2xpZKdvn0AK-Hv+zuY>%KQ(0 zBw-|8Zg?Vo+we@RUor<~+s$_+*W#}w_vU})mwHOq+0&(To&C0yuKORQN8+Vd;{U6; zo7^3CbN&}S>dE~BPf4(Xa@v%U{Kr#XmIKSGqy*=ZMapx@6UY0SU{#j`k9tYJ!*~bf z`NVX-IG&OawbDHc+>RU8~FmjguqSHYnElzkBliJs2U%yP6}U^4Tr8y@Uk)l5JKS z&*RC3K?HS&#POU2tAQuKIhF?rq+OlwK3I@o-R{Z12Y2GzCDP-U1>S^*JPUX|&Qtz8 z*3U^x2fXD=Jo&C!e_7+zo`kJfKUgglddm-b^3P!XoVDa%@|2hC$>HO)d-$o2otK=J zr2|C)<@!3||KS#%@=oG2ZUf%(Tu=UEcr^LazO&6H5?Eg%zKxx2=viQz#|!W(qd{-^ zJD&V4xNV}_!Bg?_YSO+l0xD4Ci}uca9G{B!aw0|HDp;O7$}}dk`5aP`CqDzPVehR% z4bFP;e{sB4?)~uOcgONn&%Ahk)H%SJkNNcTEHKRDr}0d7mQqH8V%^|uPyXvT*dQS| z$5jw6D^1sKqe1jpUCOraTo&UQhzc?3W52|uL07|eb z$(5RV$z1jNMo)QDkMH#O0et9$I~AVrl+VEWM+u_R?Bi6rSAj``a9Gx-~f+2l;YD$6%P|Vk0o(jD7PW~R`o0ES8zSGzl zY-RbJKspe^U7T``BN8~M0-Uj}pTpB2*%Dp?&|FGTsU~;Y6|GtlW^^$?Q+2b60 z?7`$4O8a>>E0;9+v@XYfn zJw}3eMZF#J+S}l9>T5xLdP^kq<`G;hgCqlA`x>)%=3EotPDYO>c)ZBtO&%ZjIH8ZH z1Eyu~%rOHv&*KRmFYyiHw=Tfexw0FySeSv)alDX`0tE1HPd(o@j_5c5CuABe22EA+eFl*4p*x=85 zyvF0NJpRYD%=|ie*H+lZ;|G=XkUod?OJ>MY{3&mBODoYFErudck0**W4Em+oA%I{Iu`2%omwL(%J#m&_wtH20N z$1NR4;}t9I_v;PEA# z7c~-s5AYWUvFwJ@p^Eq!oTQwCSK@NY1MwCt??5DfB(Cj?pJ~LCa0-?o=C*F@1$--p zju+#o8Cc^<*yiyOkI#9`9az^iP{reh9=9D}^|@w&Tu;JCk7s(k)Z>jFAF^wn;2d|^ z6D~LK+J4sdIL+f*J?`ppUyp}g>!>yP+JH6J-MV z_<4_C_juzq=4yD~H31&G_V_wJQZo0P>K@LDt|Su6j0?XzZGX`lYh`~R2uj}1vqaw4PL+# z^a7NZ9nAMVSRah8$8YO$Dy*;ES}mW2SL$+>&%x)l$?xo%YXTDTRDf^796y3D=mjVr zgq$P zJwA(TSG9s4s0uFQQ}~>6sUducSl#Vlb=(|}SIalRy{?ZxekUWAjfY>)H9;L!K`#RH zNqA7XFD_oo9nw)a2Uk?(({VT4OnEV$guj zgNL&JO}NPl9`eP9bSw$4a3BAtD&a+3zzG)q$-zkYxpzD<8nCu|6<;k7HPO@K3zSaB!Gq zePOsdK7iGvj9MuK4ik_sVq}{&!x>GjAOqp}PF%N{`~Ghreg>zh@-cV|UaLF>uT=ML zNqw*3uW@&^$v(iTE!jklIsfk_&@DT@Msn$V3irUH)dGLv!W^E+VwI)B(!+UNueB8% zrpl|~*|%{ks&W`t;?V#ZA*rtou8K2N2M6G8x?Ilx6AAP(5?;sLj#pH{dTe7oX}04F zM)_I%r{U6%bGL)x`uMWpPWXy)RC+jsz*QsR1)R{JNw^SK;rQch(**>6BJi2ohRgBsPHqDm@OfNO zRj>yKI;#r`I(Pz?$8z?Q4*!g6V(FmxFU&n6MRUN%0pU@cE$4qpC`VuefjdP8ocOpp%^}Zx3djo`R(`>?&YhX^3URxhD(mNtWSDJId-dUUWGu) z{Z??HS|Ax0;)cpCa6+y-Lfvp#!vk?moT>81;JdNzfQ<`qdsY4#UKu6OKm|4sIE9C( z4i(~o`R*mvDLfokR{4M7*@nwL!J!#1rd;OKjkusMH=J;+6=&gu0q&9WE*#Aw@VTn+ zK1mqJ6^-h^Al&Ogw?kv_wucx2RX!7+8st{^2Cg~S^=8}+zoYW^Vc#R{hRjOYME`w) z{jdI`?y^06d>55Nbxp!LDXaL?a&OIGJjv`_gQ0WV05S1h(j+d+H@jCjsW|#+{FYnUZL{$yte5YM@7@xBW=_g;CvpCNgMdDg@o25J59?$3 zI9&QO_d5Os+{o~&xEI!k?ikM7%Gps(x*fRh=k6vsjtAm;YQ!#0V*i^#KwqPk<*cy? z_frWqaEWd4`?jUW4R8)_tIFHpXAIwu3$Z>FKa3N$yPkwo@gTMQ3sC~|3F!TJF@7KG zZT=4a8VA(^ALH+EJ>>(q#24{rKBa@FaTM$Fi}*FH4`juj=BgL#O%kn4;2;6r;~R1D z9qv_Z3)~#*HReocO~S=g2lDYL98!K9=j?Ld8BM?)u|AIQ=OC@iczmLB9En;B2s}~f zCcKSP_QtPpWQ{(;^|5ZS5NF}-s=@DZiGA*fUBsz)yebb&VGix*bgSk>4czO1-mN+R zM+l593h)amco9CN7HEej9CVM}eef)-%OAmm54-Pl#^WRSIn{w#_@S@d(>Z^i(h7Xd z>D7B%I+hAJyP6`~=nqqNng`+)7nA3#a~9O-efS zI&N%uJ#LP#llmy%i#r-Vi+kf{%s(gLGJ%ypy1QX;D#v!*M0Kbpe(fiBH%rC`#HvH- zxPa$L$E*BS_!8cue3#^(cSp1zK7yltRKgSGv+$`4 z?tx`4_Wj{rBfgHaus*KD@L;Ux)DHagADsX7etnFe&8?~uf}=}rs7jr&yjh! z;4k;0^Bw%}%kGhHJ-z|!L+@UkgV(AK9L1NS1e&S9IRX>-6`VA+O|Rgc#S@A~K!&uLmAvnMfnYCBtGjM0D=gfcb+xT-;{^oP+{}ak4 z1edD78WP&^=T^!n@56aGsC*I+#(E9^!mnYy39HRuj^KGJzX6_KK7M1hY=Rc}Z9GSn zca9S1RU!U!U6Rm85^#I94Ts`N{AykUwZLTD4&S5vAN(plro0MI;#c*aSKf+i^5<2S zsQM1$E&Mf=zg2mZzsYND;#c+hsRU~#hfaQKZM#aSgfC#dMqxakpI*~fNSQc+Ut0S> z<+sHfaAj5Bz4#P=J*9*4aNLexQd4t=UxpyijewpcujAovg0&V;z~xi}g?P5)s|ruz z!y$Lh{EkP}c89psEJmPC{C5jwgzMtf_^4AK$KP}U>-e)IdX3uSRG#)3uNu5x7En+B zNCktGoi$*$8;U>FI!IJzH+{FfbzvSRXsf<9e7vS z8B)qu;|V-opz}B2?=Xuy%WqS5CMo%Qa4jAukbLL+|HD#&dcHs!{9ZXzRq!*8QSNLa z%CF!;oll3ZW44KtIZ(**RM1{o zSI`Ad)#cps(jPCTbq#@UA7!u<@d!cz=?hL>j~M2i~SMPQGS@Fo5o%cPSIp1~V= zzyWe&Dw7Z&GhE?CDT)7tP5Hz`D+!Yvk_E&mn6(edHKn*AuE_Q;3fw|~#zJgjC!r0l zVJy%chYa_{3k?s#OAHUkOAU{~%MCw;<+H-j6m}cw(K7^iQ&7~Q8MuStm+*ajPP#>t^#@xZes@RIZI1;wH-B*^K`R0?AImXEh|@kl{>h1^9I?Ro)Eu z#JS4t@LI#&ag}0LsI4l$59b=r$4dc zUW5LaPtKfQdXo-4igTZK8ytfd;&f)Ylt=OYsk)qJwI&m&IL!+EOEowZ--uNYt>^K5 zSa)zPo`~bK+-J?h3ykHL;Z;WdO8kvsKDf60>bHc-N9oZ<0$j^Gzg{Fg+=}&&4T%e} z{Ps^3)xmG@NL*g|M?4M7`CanQsR^=_9)eHA~GuEnfN-(?Tzy^2Z4H}&H@U24&@`e>y znr#LS8dfkg)~;j9%F5S`OzJ;mP*T7CgNDT}^-bxMT=kko;!q28pO*4ng%ShP`dRlo z`3+x5X&HzOS(5UOKQXnRUH;vaJ+X7kQbK{m%qDj2WhuL3$KOr4G2ly2PmlAf)hVd~ zUk0VAL&LjcM?Orc7D&vxGeyGh0EBl{FoB3%brbX8c*$%9WE1F_+!dupPl=8u}ZNI{zyql zNX$sJ8x9R0wIBYxSn=5Qiz&|r{F#j!HMDD|g%8CVUQKz5K4#`imyg)b_`>mKV>G+R z7du`e+#zNH0ef({a5JN~xHlQ zeX05V-5!jKgoAeF$HJ3s{#DYRQz~3d{#88Ix_%Q{h9spRgZVK49{hi`)0aJ938n}^CXEcs)wK)&!tri*_E)%dHSRL8B=CSZVzukFoq?Mh!J-piPIw%tH zr8jYw*c~HY)^Gp0H(1&(Gn%0qJ0e^!!Ix&PW!cee9O7zjIenQqmTg*bbodXyFEc+r ztg&yR;ScNB-=9p`8yoOyxUE07@{Mp$W^zH6^mTXa>$k(b1OANu@fo+vZdff++&-~7 zWpr%ns_<-IEa|UsjRapt-?aEXRN?RNKfYLKZMY8eu3uw2uWDpZtkMVJWOl5y_*RdV z-59RTR_vP>Zz1usa1NU&-cx75BCP`c{4BlPL-ispaie~! z-Z3{h&d{Bjo)+mGNXWC#wFno+Ry2tWU{K=oK6bW6q=Mf*-#XGd-rwJDjnwz0r>QOW zYwHL{ro8-u_{v^vPygBFR5O=5MQ#cB(;GJF%kQ4DZLaGPd9*}gp0g+Hj&;n7g#3PM z$iRN~tRpGs?A-p56po$@g&ZL7eISzPkL5lZNlNgg^JlA^VE4zQ{ze>Ooo#*Zs7OtQ zIbaB z!m6>?KFYrXJ%2A@Ew=-oL~aQ9uTQoX+x7Wp>7_%sQhAe$B2M=&+r2-DR1YkzmST;x i$5NUYde2_`Nu*w4v-j-n{J+YuT@iWLQuInt|N1}b^3bjT delta 128011 zcmeFZ33yc1vM{>V+PgbDBb{`{&eWM8ga82&45I-;lQ4#PkRgE}2?Pj(GKeGyNEi)n zWC0?Bf(H~KAz(8T6g4V(f}#f%AskUalDI*jhxG8*+PgbM?z#7U_kZtw@4owA{d(`J zT2-~CTD5A`Ug5+$M{rr$5nLY8x!^)OR0co7BULKWBa9M}2DL(0k05c>w>Dqbg@ps9AMm?>2`)TA%){Evl26cRCJaBu z(9u=cY4g1B%~BxgWEA~y-_6y$f1h0nM_N}T^oQSQ5RVR6y$NIidjWo{;n&Bw`FfOC zfiu+0x?r@ki})BX3ki@6&giq6(|!(@rDZaP+AU^VUcQ z9YUkVtD-RrBoY?zkKUV~@jxA;H(+VKI5#+)+_8!qf4RhfE)0KrJYC?D)5s;z?tms2JBTlfX!=7Kh1F*qm-^P zi+e(HI|sE;!h@3aAXI#uH~1O?PtKJvDn4t-LW?z(b0vbzxBa9m=Bm!2*D>}J{dJ}i z)`YnMT;DY7rk*fGF@9N`^no?&B#za@cmsUWD#Um}V|=Ak4jkhNlwESEzd;S~dsaS% zlS|)sunv(7)?CDs40pFUy|45$l$Ah>P=c>i;y@2eQ&8f|wb0EJUrrk25Z8rw#&gB9 z;o%;6)&dy80P#k6WMCg#hdQU}u+wRJV0W5qc3tDuvpCk@paOi1_(x=a-!3j)0YGUl_K6CL9_VC}K9^OpqzBN$fX6MR6<>(T z^Y7L)?BUXRl}*y4V@;19`$}Ho?WkwHtF3$;I7dvtIzczaiOzS{W2u7!C0Z{R z8t?%k?Qsz4p+hW=j!%BZ*$UVhgP+XMadCG8ii~3t(vnLB94UxEyj`e)G(=-lfFpkoE8wS4NvfOU*kAx7s zNAzg@EBVeUHnu)SmRhU!wdsqyU@M=^WqC@C7Pg+Vb|8JxMx@Vr9qE+?7-L|iH!K96 z2Y{#eY>^n&wu}GQ7DiugRU1+a4{jq=R5ht>6(Nb8#DL^i@c?mqaB)!^r~yWvy7OLI#bQoK-1#)C5%c=#4`4$@cR#96f@asK6oI&ngKUC9YA zeWTuMRYQo^8=&S!!!Z{g1h^XT3Kt&i)vxZ21_3A^JSB1PDT)2f5=kzJJ#or%=yrs7s zyBih(JPu$A@Irtm0=(Ig?b0{rU+61j`o`wB&^OhkZw}~~;?h?D@I;rssScfMIL5Tl z$A)}FvleB@hl;)(BTKkiA+h~sEL*QK@O__>>;05mcNZQEBh}5-ns8`AS66F-0Pf;y zO)H1IDrD`u8``J*%w~iJ{s^=fcJnP;lV^83;}|-i(why z{pALg7V{5w_Nl$wD(#h78ATWFs?xmjYVweNGE=H5 zQGg>kplKz&33w#H5$#$@ZvY$)unyqY01gBG@#c$j%&SlzS@CPGhA_oz0S<4WxSOo# ziQ?Dntm2XN;h?M#%5(sS0Xz-hC{WzqToxk?Zzt=W)}q0aM4TGZZ3alYo7D#-+|B9% zFl&~|yaA*`Wa%C)q|=ym|7hTHONX_P*2>a;($CIvkk&&e>SyCC&em(zYtHULY{%ja zn%EdaNS4D?DSnU|nPN93n?q0TZtw>eg}wM#-@W{O0ohG4GSvsD1gIWB^#N+IS+u4m z1}`;x>m8;scBYC0Rg3LD(iyXuo)+t00sUg}WDtyo21er*aaLN7Rs~IG>($T(7EgLh zOT^=8&xGEyON|-pu0XA96ObAUyfO?bsm?C)UHg)A_NuI|gE0|0Rc(D{2gduwPTi_- zR@JZFZjjNNtr)6*#i}y+$9h1llGcRv-cl;;X%5pOplV_{pkA@E{qhdPf9bGk6(4Wk z;I&?5@G(?0X6%3(*Lh1?*r0mGb}}RyY^Ft3VZBZZ_=T$P`j=qR%_)u<(3^xgtF{h^ z^5zBUno~S6A|HSXr>GxU4!e2f$moIDE_Kvio{awc}Ru`(6EbBmn1ynk|`cGf|MYD}(C6mNnW5aNcICks++)3O$wi6B&FOQ8*=4|L8 z(pNk}9bdYP5*X(fO{9E&-OYcJZ3u#Hlvq%E_b8*^Y!V~J=^|^I1W7UywxkInV^CSz@nyMDy+9#K*iq+JxWJ{bzZf&V1ivBf9X}SY z5G~{Th0bW29YMBb2&5c%6H6ZE9bpxJV--hD$RZzD#a$DU$yTd)X@VYmhz%2d825@p zUyxA<)#bz#z#d(fmB$2pt*tBFx7EOog^8s3D;V_(u2pzVUR!m2kQ z$!1Y>Akd-6H(11|iBaTdi`aW&Z*tZmE}u9PuMzJ~+>X18D<{R^w&MOtJ+xEoZlh4l zKrJm5|D4pL?KoRvEPr2v3k+7%Z%te7v_c+IYpcGJ=vSG~@>u_m+bD)LNF|P){Dapl z7soGFvHO$=?MHB;8h%@I{M8EH5Ez3GSWWMXg;UPA7VON@)Y1_M4&9cfmaf~_IZLrS zwe(M$I5amATDK@SlH9e4TXVa{{R$)GAw6KH2dMrG&vw;cz#l)63ak1fcP}QIPU7oR zI}?2;@zbeM?DgB!$(~EhDuZ90e^x88{j?BVST%jxKlsRLu=2R}t!mkfPqKPs<9ivJ z(!%sghL0A<7u?3@tNIkaL2z)@KW3%j&S^W~U=KfE_!UEAS=@i$>DED{drn11Mgh}7 zq+gt3@7bYxB7N6_>F+KkBv(YF&zw~+&Mw75twX5P>vN}zDf4typ>yHPe9B%GKW_`} z=B~CMRQuIa)rZ)hRPS$hb-`7=r+9yUcvO?^3CAOwtAVb%8*F0If>c~CPFZjt&!`%{ za4yEl;)NH&CPdry1*HWU4@)y*3d(ZZ)csyiSfDQ;67R@?DJPQ79@$Lub>zx4ja}PJ zlk6EXO>Os7P6g-N%JL3dRqBh?7*7`;ExJLBP2%^9lgZU4kzdk*IGV)NCCNBW%v&;@ z9I}cvOLmbOt5~q~4*9i79P!c^Pj7I4Y;rur%9pgnZV^9yDT;uR|MpTo`Q9Q9UbYI0 z;^k%GSX0%o>>iF9+k}^SzyI6*L*nD*J;`;mm|BvF->F(s zGMdx2Hs8BV^moCmijS+n%Mxj>c=MGmc(fR_^2^{KK0rdJ!$>%Jh|RxJ{;OSlys|U- z(k>>gS{xW|H8vvMg+?Ur5NGQN>>#41o6b`g!`}}_X4B=Wy{lE&cZUUh`nuf>v0iFv zs95#tb6797S~Jb#TQGtqSSU-@^zk?%!)wF~YeGC;H#7QT@y43bC2!e%^fuEvJBn4s zbOY!OJA1w&vW<$SrSoE&Tov~R^e>w-dRtivAabHF7-8G*whIT!(DXT{m;!ZIsl zU2d5Gp#ROv222fId)~&LBcUm(7%zY(+t_oEjE4X;#>SrgY~mN|M(DkrLZ#L8y?jDO zDL4bElnzG36c|jV)()}f`lz%oY>dh1^o7WxL>8!Y=IRl&43`sVH;OHUl5%@@%Z}ao*QNPrA|nj>wXb_M{PF6*4>M0$^Mq1@vj zt0zpB$#sgF4S{~UWW^(7#m_p#&KpuAGUf74AcM+rd7*&^nYt#XvyD@HWka%1W?_i0 zQ~Yp4s>e(j`9r+Fq08tYGW?C4K0<*wW3dMd!%(bmHcLf4C+q##;gjtJ*jl+|XB?i{ zENwCo%+zW+?%=a{X}Js^0WD`B0aYX}*%%$x4X{Ii6(2_uXCZov=|ynC4wEQWZj4De z?hu$w$tkkOx77o=7{)Q%sv5}4Pyy^Hzu#u^k08V9xuJ?|dK;H)fpF;n&>*z|-1996 zPB1=vb%7psPJJ$;6*SW_WE#s1uziD-O|bBWuvk9ZX);=bldJ@Ce<@Ai0GM9Q@j%F0 z2?V@{9m0STd>J!Yy-nVC2w2tk>L#WvOKe--Cv2YCBdfH(@Pob(j?0%>0EEE_@(@j| zEdNX!Z{zB^%}g&8GSl;J9%T{SZgJA)Ubs|zb91z3eUm~f5*7(jdoFg1}fJ~9Vl+z8U%@%zirJb8PL9gtmh4D4Z#Nf zeuj#_-xH4feHKBqEOY`lilouztqm%#<8W}i->9)_Yrh9fNpFlUc9?oPnU7*e_e$_- zQlsEyF->)@hUj;P86kCIhi`7&fobFgU7O^#by#0!jz9@;@aDYMH1Lqq5LZ!6?>=%x zi_F@(ZBWc7dR%@33Ka$nZ_Z0yx2*vIM7-bx?#duB#|iP_8u2Qv?O!O@!>jb&#}~{% zQ|neWT!a{$oeFckn75T6LRU!#Y`K+Jz@NIQHyVtR^ zRrSplsCrey$6g$iwijcz2el3O`3>m*s)kRzF8-Su3P4vr=;DFfk8z8Ww}*-gw|9l8 z`2FqELaok3gT?f^Q&Y(%>fY@%$U8qaZFW?(-l4`N^T2zYkWExA@#ZH+t~sk7C_w(p zY&z2vAH!!oHks{6|L1MSyLvkkvfvZ|3lGY-Ht~jdFjI#q&HPt0Rd{$qtO3VlaVqI0 zCkq#!7%J>j;`?vLByD#nG2Z@Ji3Yn#4`DuwU=-}nCWfgDhh{aIe4E6_Z{~-L0Cqhv zR-4gz%WZez-^F=5hkHi3%AT+Ka_6%+fmrw4^F+_+noM@fD~4n^|5g9_Wy<1ysJwq& zaRf^2Tiaxk#E!d;r?!LaDAuc_%}q@Z7&e(iiy#d%<3wERA-xY-MRZ)ONQv<{@YvMb z#x{`0rtUT|ba#IH1y-TbVme@N1v>!&Z;!y+4|}*LM+MK)9Cf)0m~GH0#`T7HaCck( z{qnLrpk@O|vh1d}s(#u1ELW1;^lX;N^ox~QcJJ)oFyhZN^@iQ8cb3z%6b>aO(`x6; zI+fG}6kK!tY(H$y8zW)br8+yUFwiU>2(YScY8%p?MqN z+}_k0p5~^6LGc59I>%+lLp^a#aoGta0L-v@0dtZ)0#pk#Rq*9O2M~(W8HAak*(zzh zH5l+LD5{Mvz%a#_oSB9xbTaVgT* z0lWn|yb9n|@U8%_&a8O~RP(b_B~kNanEuIGD(QRcgzSQDLheMsCj$PpbqwHHxf1}N z0QjfY5rEg^jstug;ODGE8Gqgwz{ddop><#h6UZ9{gi$~^Y&8I0mNx?M5rDsI?aT1o z9Kdq`-(~F$IHZ-}YsokB2&@aI8ACi&kiKI26WSx7r2_2&&@`|Os-$|Lq%capoAL`# z+5x4cPczexKxzXd3=|((?6NrysuQNV@z2fCtU1m21#>vyS%9a-a8S)ja|ml5;2APr z2^s@fwbR^`13>X(bwEQB8Bd9{8%Umv1WX!PY%5SyKv^+OC3P@Ea=^+~*2|FTD2AyS z4B_L;dm);J_x`t$5D)hF=shHC0sOoDNH_uS&)-GDHF)<2dKQ$w{62)4@ZR`0B=FL1 z2%474_L`Pe!VETWUMgFHPF`B=+Y286yXn=^J5cRA4wa$nO%JJ~IR0QK(%DwE;b2#ioo4?G za^H(#KU@gEW$d>S7Iy^6KxkzXYzHkEB)4FwGf=ELlu)w5;hpUb8&Zx< z$gY{mOFdjQ)yz~uO%Gf(QQJ2zM@H8p{X_U&g5N6m@zR$zw}xlEcg;dlo~`S^XR=dE0K8&L%kB(2krmR9yfo6*Ug_%W zj?jR3dt2B1CIJ=+L;Hb^mrS+H~>9R^2#P2`onUQH#%*NBUv4y+Vtbx&l9wx6w`r21v;|AF6 zt`E%uSH8M#l^&wzc204`;h}_cif+AXC;sEeTGGy1HMOEI_RO;@s+z9>YBso9rA$iLgb2TKD*nJ27em;V)N4gvE1&QUV&87inaryCyc&PZ(@k-uo8eta8 zKO6@@yjiUOFsI*m_+~X8#8MF_-L&3l7z_AVz*7MK!TOIDM*y2C#&rZ>RSbhFhIyI5 zsE3Lr#z@FpzGaNo&b~aYE`71Sl27bd>zO$8vc9f|_;+InP7`k%r{E}Yz=<}U0^w6+ zHk<>TreO|07i>4BIR*Ic=;!q+)VRCB7v7xwy%FiVi+?-OB}-rdA(C7XoXvz}oSj9B zk7NB~(-km%6zd0x2{?wsDH1;L4;}h-a>~%^p6Q(A3E4%KM7M3IiaptzBirp&Q_lpb zaF+POg?{indEps&-oMZTp6x$sLqZ%?V?J_lc&j-2(*!cqS+(rbQ3SBdHP5!a2GOU< z^iOkXj0gD0750o+_`W4WrEoeV04;;C9lkb;-9EpI&0^da9SI}`Mt$);BsSW8`6k{b ze)eTF{z$z2WgmP?%B}s_>gX{Kyc8IN@e2 z>EWnae$zm3jQGhfRrrj!tljH6Q|uN!3p9ocV^%sanRl2B*`i6y4#z0 zIjgSUO~PcMqsr^vM;PxDzpDQ(?6F1p*5N7J5-;(9hk0|-VexdsEPSb|O(Vuy=3+I+ zUx&PHX6)!}eBi#RwyMV;!?Ai5?7GWVimywl+KcuV3Inrh&8Sq%p5<8jRs2C(M6g2~ zasL#tZ4mt)=(JT%R$V%LC{a$Wa6Lur@gQ#Gd>i)-)}O8Sg7g^DTW>!y{pz%u201LI zE=?BGS*yj=&1NxehTnMj?Falh_(j?+CMV$kfZrm(yTBzBYDbbMz|N}52Vuk~(}uJ6 znp+{w**hD=?;lRoUa|&WhVQa+cZb)9LRUW)`#;Ky^lDVBTVs!FQu`h25$3LwX?;@<=OwW&^$K$qO=bavhwK-*jT+g;tU20`rEB(nB1G_Ra z*oN!oN}MXuU{c{c$pYtNy8h(A(mb^R$On1YxMwfsk2}O`NNF|BJCH?T0-C=)_0bK zR+k_|Q%YD8yF~P~_V<_Ia75lG25dm(jQ@@}#Tw(=&qCgJYv?6zwD$8~WQCD9-@}04 z8*TszDMq|$?S@B);Z0qj-eFCV*jJq0v^^}=%$57r%{a*&IC^xDVYuO|yC^3EM(vgu zZR>$gh|k&DX^Wf%5$PwpR%)|wfoEg@>|9@q+il_g?>c?z1ewOJK_O|E_=&9(EG(0) zPz5VRVgg#%t#t1{%P;% z8|?JSsxG)#ppQh-HnF241a}YzIQqeCtaro&t%rL_NWUjHq3-3A-3+lsxdoD`M!evN zh8Ev+bPM^XgQZn&!2N?Q=J5#T=`zFrQPs&Ag7L?1WaBte*!0F6Jje4jJAXeE+}rv$ ze#LzfCfV~N(vu&3>jSMEYxjodDET?u4n35H%FjV`5XPTPGTFTA&h_QLIop?fJ50g? zUl$X}%fs-yEyKV*s^!8#ZX*2HZV3L4suQH>#w2n zPWYCT3G-lqxS;)AsSj@$Cc*JS66pmsws3FT1v<2O$KCF_(D z(p;j4k_`??mO0cvy|J)FzF{*Aq9_En7j|Zp!!;syk0%}O-LShi16!1+<&thd?JrYr zH1zlC15p@AJ_;)~o4&Du;&nF~p7rYGqNV}$GaEGIy&DbPy`FJVhXeHt<9)AF*0Tsc z{B(xfml56-jf3I)cafLfbb^Hlr=-T*Q|=p?!{KHC@L4^-xdB&PD#7{lkGw(6b~@S< zk2k+xvTrUN(v zzMu-|57Rd^+8c-Yorh}$WPLI02sM3&8>zt?_r?CkwcZ%6!FtmnzIYH>+eCNx;(y{= z`m!JHg}AOA?^S?P`d zoTPPHJhutu@$i-6zUd!u+rVMkV*Ez{?t!&`n6zeaF$Eb?Mg|ObZllRW69V!2=tpMW zkYBmi;CVmClXb*^dKd;8*kuE>#bMe*{~m~M;1uJLAUp}Y@Te+va?Q%IMD;f-298}koMCLE2VaF(8na_?FM`YInm9Zge?=d~;TdEJPbbIY-#s>- zW1l6i&|wKU4(sWH1pE#@M?+fUx%gGOrZp&NLl3sbui+cCTN_NVXuRA8FTyy1X1B!$ zeQQrjXU^V1eVCGE)Y%qC;?p!T3EKl2&96fa3;fD(@PH$orYYy>#CG^a9B2Ht9d5uc_#yf6~=I(f8Yh3 zDp7YKLN`RvRSFTFq~99$UQd^2;b2w4dL(pElQPYoyR97`;GcbaYVUrGW7*K=@Mzg-SPM;}lhg zCq*gnmkKU{6k{`(Aye}f;XuAwRF&Bb;!$+SKsHLyQARXbZ+w&5WvyW}V;^ zdg0h)(I8;Myqv-O%I4WSmD8)7+ zV7%DeUmr~m108zs)nFX1x(*V{n1pug5X_UZ5mY?{M|EF50*1mhGfZk3;4Mcy^BW|L zf^x7p*|PL5?bVm*^emw;1 z`d$UOoEFu%4Lce5TUO8XGJ}tYY6Ad{ci|~lXwpy^%vHeOn&!=cl~hxUgfHl2dAx^W zK58fQq&GB?Sv0?zdzGypy-QqwlfFF^$Evsd09Mb@ugBnES~nCXN&h|leJGA1*RD~o zVQdm_AR(7lvdPLAhIy6sDiU_k`_O$))~q5xH_^O>SgU5J^#)x&3vMA*PG6}Er4 z4MYvOd0`7rdryb!DHfb(lXH|No>b8v8w z)E&AAboUIF^+3V|>c0essPdsGo!%dbwP`f~x_ivbYR^-62H<+o;x^XwA#C7aafEbZ zji?2*H59weC?0U;LEZQ^Sl06acMnKUz{kin2WdcaQVY$C2P0vhvh2$9VaC|t(&J(SSTmU$$!L4-^?KA?ql{yp&p|bLXEwJ7@xZ1(GRRcKNDcs$t9f*WG%sj$l z=0D?h$uF55@k8#D@5s2-HD;bqFM4rdE{?_?Yv>9&^>Kw>QJjw}ScH-%6lke`o)RJpn^d0Id% zGd%ZXUV#zFkSCLD%b|@Uad1Lui$P){3jt^L;ugt)@r`H8EF|icen?mdEG<_Uvq?6# zTYA&Uqi~YSYGB^Z?S@pnd$EaY7z&L)^(+#WJ|*q$Kp?$23Wt=O02a_Cn*nP}J`7$< z9755*;3uBK7e9sPJ|#c(DSYBz@y=-SUkPa3Q}_fI?w*@edT=y2@aKUHvj_Wos^^%Gm{0O)tLy=CS|@&&#GCkhxSDTepKr+)W*zBcbb(zm9pT3ujZu zI`;Kqrh<87*v^KJ!{MDvU-+wp!KIm5FO#TQq?Efgyz&CwH4fs6t9y_zkonpWRW5+V zvfGvY?5*9jaUAq#;cnK&&EtXN3sAz-y<=gwt(cE_#aj=A@?f@Eg#_gS$TkqS87J>$ z8wXQPM(m}V#xrdT!5t_ns>fp?=xta#%-Y-|un+L9vbNwot|Irm>no5DOXOMeb$26i zIruEajr4}gfkmLn-QzC+XYS73m=lL!H&kXV1&Uk~conk#_LDK7x zVp*1$&+AhY(sS2B$&yfU@X|!;tKb24{^1Peho#WAcX!7 ztg6~j4ABDfqB?iWOMS3BD{fzW$cGM{41-?mM1nzH&EbQaVEc!TxmUA${tr74-8~uZ zyd2QcPbWi5GIjI;yn`Y*EbmTkqbRVmncfUrrYg}73kT$WsCq`hm^B-(pqdzih3iTe zFIwp?_+S#0sloDIrH9(t*p2eVLXEPen4#Sx6jONENd0nQ_(lQuHo3_i7Tb`}vqh8L z2a|~oWzS#-8+VU4w4yKOLS+%qo|Zm85pd0uT|^I)!9oW2*ao&@Q_Qvm)nEX7D&R#u zo3aZ{N;b5MT#ScN1=bjl|NuQ*d~K6#2xmn5EeOXBymE^iaVz zWdKW~F)Yo!6Ty+@htunM5ZY~kKU5st!jY;nz;1F{#N$_E>Aqf=oxYe94lT`>lnOFj5x)d7OR$H}`KsRG6WbySpY)6-xq~D1|k@|`f8V|%ZPd{QLiKF z^+dga^!0WxrqX0EC64ZT363`s?24+|E^Kp_1Czn2Fp*G;+m*T7vQJ=Z9oiB^e=ooR zWbrZTC;%S|siUYu+!>Fc!wc~&)wQiicuX%8;^5##+GWrJP?h3p^r$zGP|JK%Fg-F8 zdjyiH+QkY-hKpla740w+_f=h^tUdBsc*9IEp@QQG90LR>vSgV5wlpNH0+~#gTq6Bp zCLW-^dJiH4L>uQq^wfJ6G~oacVu2^s#a9fSTkK+ZWfquk{8qXP7)fe9{csj+c09c~ z3qKc>3Q-sv1h-4cg6ONW;=XM27-8&mj<2jH3Nm4fMS6H@$ZF;Ip5D4{@PY_a=v!KaDO zKH4}3>w@>a4Z9CmLdyiyvb{8FF4pzF0#~7KL1nDW?bmDGg#hv?S|(hP+UBCUZKJG# zzBm_0joI)wB;Z1oL>)n1JvoZ4Y%%P@55qrwZ%<)2)fzPjLEx)zkC(_eJ<`w zG^>oU#W32PF9kn2M}?{o%7FP|*1}d6!;1lDD=8O#%ey zOI}YMmI3=c5^9^J$+_u;g?gL*&Rd`&FQ%w-Q6w^`z&(&Uq*dPzn!$x>#jx zNav~F68tXNFqwY11ooH@r!X#gT=sbQ8}r*muTu2Y{pr-O_f{2YLopD zJ0Ph(0#?|dSxyO(2?B=5{3QrU8LZkVmkpncL*!J@HmD$7&Vs7uf6k;>G@^PQbh{MF z$-Z)T1<|S~5D1WipoBBEPhxJim7f3{W}w-yrb1QS6-RLi6lT#OSo zpd1)WbD+=F(EK7?Ctllk~!?FT|$RFkAqaHZ?SQdkBPzOS>{Hz z&7IJr-b&YDn9>zu8OTmhz%yW}V-#=;44y*)bpTF~owGXN0upSPo`c{=bq!P;R(!S> zOwD0=Zq@6)LP9B_%g4fQC6CTl=zdpubmU~qWT=hx-tBS!3HT^w7K@>w%HmKtprNid zcL1vENdKEmm2LTTpz0LgG)4y5!cmu>f+QcNeo(n;!wJYS$ju`^o}s!Gu*6Ei$y`+G z%7jwaNavnprw@7WsRj_fJGd=d#e+TwFq`qgfM+Oicm=Ssq!F7{cA_gi11$!a{TTis z;PG-2R9OgsMk$jV0lkm%o zO5B=UjicYM!~;oa2O7HyPaun1)8(u14wBfG>Q>_@FE{@l1*gTUA({nN+VxdDlbraKzWpkW)d{y1gYK(cK0phVvnZ1701>z8 z^;dCkQhu98t-&3L*Bv@^4SZkA7wCNU&b&jnuEDPdBqm^CD#)b5k2QW>0_|Rgy9Rvf zqPrWJ*qXjlhFb?rZmk?~-1MS$^c15D$;#<3!= zf2`Jb2!MN9#(wMZ2u_{fF#!2A8QkwlVs3 zyiBDIoeGk6<6erNA?hnL0#JpA@%nb0&8ds$0wNgOzlE!K^|jXn(8FZoZ+r2loVw@@ z(AnO2bU#*M^}e?PP<}t-*>~~Ryt;T_0J_xAxcPmkO`UTn03~M{hj?)vc;m;FcpFv= zp9dhRzcH^0LO_p;UxTCp)0=m2yz%Yh_$#7DE3{~wg}!hCf2cmDk3u^+W2ciioKvR; zd!mfP^vB=u8^+sba5na+KOKZF5n_C)9-mViA6>+EBh-tJ1)+Fiymb?&V)eCLEh>I& zjQRzi!Rp+hT9hvt>u%wPSe^QwKk}(Hg0fGsM_r^R%Kr?}=wI*_V~@MI4fePex?UZ$M>J}2`pOV3+SzEV zXie^_Xmtm|liWXyyOT)_@u-2K!HwAX_ZeI-OiK@v*VN^MwWzk<_;V++2zwlY@@oy4 z-oJwbjdQz@8=OaIh$pJ4L`G=;bC_17lM3~?{+_7zYu5hrYGXnM`7}aZ4IQuf)Odd) z*+M+Z0onNpq80H(XMA@Gsl)1?Kss~r!?(#y6+QelDe*V~!;%QYvL~6O8Y^aydaO>4 z2C*-UU(eurV|uZcl&d3Po<2tOdM7f07QaVU(QUKIHV-}M8hjBoH*z>fcg`a#)uX_y z_9WAU`Q%&msBv0!=DyJ}p9Ekv+N?!cR%7r&;-^-dVLa;}87~ZW9}uve{Aa<}ZZqnSkgEbdLE8`GHU{<_ zq(ygr$B5@ug>x37q+MLCC;fUD7hCc+CUJaJ@!SO|>FFroUBHB>X$5%;78EX+GHv1f zA{4NLCviDZv**4zeaef|r=fsbz%vT)g>&aWKYe=s)Vyi4P{3(m%8x3TTRdGZnES#) z6u_&vxK%jn`NBDQMN?!-B2c#AsN%wW6fgwfeVF6ECN%dG5=hTkh*v?ceF(w22brRx z>A;kWxwxGkQ40#E&6+YTuc#0Oyr>3>XVlQq{iZCKJ_lHufTh|K`3HOjq4h4D(@$x9 z_Usp?KpQd$?m=>xd~x3VyxEMjgy6pP=1HRMd!FFQ#4Rv{b#M&pU>1)HNRGP(CbFEz zbD9|$;VlFgP>8mg&K%C^iG`=*PLU{GG$C>6QH4#M7A0A+XBXAqNG=A@H zUCVVf`duX97#Qf3iClznz$YY&BmLi{n`_9+?5+8neBx2GG7wceu<_dGWVp)XAuN}` zN_mO*)tq{tDMV2-mdu}vG!5_5uV=v0IrTohKZ67jz^ngG;E!|<(eni)k?yV~$JAFt zJ<(Mo-8h%KLDRn>>parIL7*=Yt!z!AjJLlb-$5N=p6J$zC%zy88~^-)d_+9-;FkCN z-Q|P6zeY4feE`HuFEQu3*;_4v|C#tTee)%*);RJWS;~=6BmH|LF{<~0dl5dRutKwq z-~B;45i;&Ft<1Vv4aq`F_je_w})8|Z^n?D^44A?YBNr+K= zKrXAu2{rBQBw@6~Ocn%I=seN53+TVzil=jPxR`?Pe*XXALho+jv!bTXE@ZA!Gw_;X zZh3QN6iuHp8zuw=JnaB(Okq6D4j`yTs3B29*m9eqtP{<-ZxM|e!Nrkt-_lm6iTvKv zL;^#h07SE*hUUFkIA+NccA9&d1V$>Qi=#%u3hW1damv{2In5gB=F=pcDLj0d=r~q` z6IQScM2rL@gOa&6g+qUa#6~e?T-+Y=m-YL^Mdg^e)M+jk_1@%v<)S=El)P1F27IrK zi98ybNiv2}lFNCyh5sGrMca+yBL3>RT3NVIpO&7B9HuH}YfRta;$hfd+tw4*0Ch*7{bhte&cT$Q@#ivg&*of1To@L!ED`*9Egltb{C zb04Fek<(}A6&K8%KRqjNPChJ~g-B!hl}2m0OX|#*wCI-EcwfUkOVoVlAXJQuUA5fb zA@nSRNXtUKL%BD@UcCzjI9i{R(=T&M|C~`vil=8ze;#Q*{M~pyl(YJiLk-5$Nn8dQ zQfOtJ(nQUgzGO;2q)||R8SU>z17y_TMzu0Jz>NmVXcj|hR(q~dU6cXoiua8@J8-`c z&f!GH*iPJ!Jn>aiM;ez#dZ~?RUAZug$3p0Bg@lbUN60-DSLBI}t&WqsM2W@T;{VIU zUjJP@@zQV%Q;nkj6P`Hm-+JQ402(=hi{}~xFx8wUu`;l?iD<)s@-JL5S_`t12+L+v$Ud|i{mdj}lirxO0sKSg#)^P&Ib&CWG6S!qE;Qu)Zp%ZhtjUET! zaCmW^9GfN<^@vvNz!jR0mQQ>Ori1S-lS_oC=kuq!5uYe_5^$AhqH^HS_Z*Q-W;T{#v2d4$hC$P)lS%stj4R0U>hKvd(pE?xvOd) zi1dmM86nt@Rr#Ok5Qx%ku+%nk$x%ZfGNk2SkVxabQkO*SO0Lo)7tSu3M-*cWe7mnw z_mi{Zn)hjOHR<$U%sN}1+T5{%>%jJJZ1X<|6>>IlYdyBX;p@_ee~pc}O~b(Zvc<>% zc`-6TUW}WDDT|R2M5oAh{F4XG1WwqLJ%KDzhmpKE3fqBX@_8 zyiDr9jeD8B%eQgwsyDzHu);Zr7QDQanw1EY?$ngdPGQ&%Z1Q&(OBG~m9(UiDgvoubjW6`{FsvYSJ!_=GDXhF6W9KjqfraeeXoZ5Qb;dnBH`uq<$%pQ#V zHIH@y9B>418PbH?5Kv?G(9gf(sx>M58K>|rd;ahaMs#lwA7ZTdnj4M%R0kQArEHwoBNer%J&wcW9^Kk~>J<6oyP6eC> zJP!Ee|KMiHL87CdUFKHBtpD<{X1MVz4Z-uge(oGZ+y#L zQSH&g_fO-TE8I`2z(jzr6thMbhOu)eC-CA#hyyf_v|vDZk(#A55n7 zojbP(L?C91`iTqXwtR=_FF(QG##~uUXI(uOfc$}zzWg)9b=B<=I#x>OUg179{&1c9gHPxQk=~x=E!6r4 zYy+`Re_-R508jXDAI*Efh0&gc*y;q*zh%H z0~EA58=#=g*#HG?&ITxGb2i}qPc-y4z6+-Y=4=0VgBm&fxNw04QNMfK#s7S0!!ZX2M+`09P|q!D8Q}c0?%xk^jOQES zbV0&y%CQX>b`w+iaFP3f+o~>x-u7HWZ4bEc;KR4r{2oW#7g)n!>4_w`K2t{cYL%-+Wv4e)`+8_mgkS|2IB4 z{m;2W{$%bxLHr+l?)Wy852DpPzf_&t8~${AD}{f(d51a!;Hz6{or*t9Cf_lZt9eRh z9)CrSGf~n_LGQi?f;2Z)D$yrPlPNH-B*hd&h{{{IuyD%s1q%z^J8&lB>KhcS)S+?V0eY65+P|8~NUUJd2f`e-2Kq^V}jeKnBAj0ZFE z`wG76<-WtUq9re@W~JNUssfU8Nv^=&)k>u${+bcNpg-UcDA>;+xy7spw7ZV4QRl!F zi7VexA)KG!ksiTnA4f05@Lg%f$s`@MZ&4LSlz#}9+hCAhcyTV=3W^Q*2$U!Xyzirp zy(9QotS*ZTKt1mmpO54NRq9bje^h^qmd5f2B0ef%$A>-Zq5T0xaNK)6hBc-ZG<>_9 zX2$Wqs>@FKqn*DQJI3=D13X4O6Mz;sA>+As;oq$>rls@ixQKGN4*2j{HnPve5x7Le z&L>?Mq=5tWPd)hU>Y~d5=!AhT?a5#ASq$)&0gM|gY(y_Um7S~0dhutHRzXSW7*_J2 zJsXGC9obVkc^cX>xGIS~fqzbK-Z-ip_^*z8!mn_iZ^L+YC$Q%~TeD}8{JfpW;9m0c zx~#2pFD5%BhfSR+UY^%W)VB}ci$<>&)KoK3Ju?ofs3>4;iI3QmjjH>g%*5fpY9`W~ zuF2r%_|&t$En_X!uxuI2)%qWBD@ySwPF6td<`Ju(m(wM0<|o z&$Y=1`r{-N0rKK^jPQyV2-+akE7o1HP{Htg;Owo{YeUztc+-_%r_bz`g7O)5Q`Aa5h#(@$k3mxlzSX zb^y-V?u-VLkA-i|>^Xitoi-8t(Iv+74fUSHZ}qtf@WgA3AI#%}N&M?Rw}6sd$0!fl z(?OH@Ej|)ZDt=)Ua3=SFqP78L+pmm2juv@&%=H!EvR>(LjHNb({4dhJJwC_skN>{! z-Pdg%!-JXG$;>beb4bpIZ5A4aVfMw$4mM_c?4S`ghe}yU@^Q*JBq0g0oGVF^BuThC81Wn3%G4Jbb6`Jtm!2J`e{4iyFZa}P8lI&$uWQ=nQyxmTBRylX zV*jZlEy>awieEZvN;|rfXVjybw>Lme z&gV6(%a|ov3WO$Y$12f))=X^n7$uC?vyG+DVs|+m9Ir<-Hto3i8GIGuG^GQwJliq0 zC=+`K{_aRV6A-yyI#TNiNMhcfj(zceOn`UOj(zx&-x&!_Ipyg+Hb-w;g|&MDb46F4 zF#ODD@y7S16tq?94nzfnu-OiC&qgpEr2>{JwXoAXk5^)8CM3 zV(hkO)|`yoafMt^UDJ*;Qo4IMF_ZN+!R#>xTqACBv=qzfp!0S9Q{Q+ik<(~hijm!v7tI9ZpSpD_trd48kCPnr7fc}nl@ z!&UPqQ((9$j*pxqzDoy-p_pmMv0V0F(J=f`tlyBQRKm;Yhbel)x_n|K99oonumw-m z+j31EG*$m^y)U4+@Cw&)N#)QX(XlBpvDopm^=EqWX+220+;LC#(|T3a;8QS;gH$|C zZyd>*nHa}aaDu@Z{yCKGv4C!6;quS)(KP+A!N+N~Vju5xJxuyGF;4P$`d;^l?@QD5 zLk6GAd3b;}%+SLkIBXN+N+eI;AyrrvG)Id4Vkf#aLvNrV{F){DL4yzZ3_D0?OZ0|P zf{AeuRCC9*Ki__5?qbX5^q75qjKfhQUXa79FInv-AdoI204(n4}b2q30scPzo7Vgfa~1 zkx;OEz}dp@Xi}v)P6#)vN)KnDndkFS9gfk&*?RC}rX7`x<)zE^YI|o*X^T#5c2RCN zZ<|%@Oz~xk4Dg-KbZ|Dx$@b3l&1_UUK7NHmW3SE88~B=b9DZVMnJwTtKSys>g=MIN z4eGT@?@K$zH}f`i;iFt9PtYgN=#6`rb{s@z&$52J@`|b)VdO|pEyNZG7P0|2$@vA6 zLKC4nemLaj8gQW%?He9~4}4lKw8!LppQZ zOpL0_oUTyUxp`ETIY23{uR1bo=!<%&!Tu-t(CVuqlq%JOay~?Rn7Yl^gBzK4v@f1P zJah|!rq9=p^y8zATxrS!6{W`X zGv{OIycGF(`Xu#Vhy*h2=w^6&-0kL(<}cI__v1sCe6-Xz7)m^&sV`SCm59m7kIR4( z`573qI(g1|3aeeiU5mT)(n2V~=Q&#)q*06Xphl)0r)indmDss%{%GYQ{pjO-9+Yog z>=}Y;a6(hpdIby_-YX$`L}G88z2Wsoi=&MFrlzN31OBpCXvxcZqK3aWUq&(JQ>LSj z()PuA^8nM1@*zWx$;-_&dq%Hyq2CtkQ4OE#f+i%5tjQ6QjnZo%kCw2Ibpm=4$gO6`pb~1MGnJcBj6ULXU1;VK zd=mJaY{-Z71nEtCaAR#^T)ZKL$;Ns$q^Z%u z2Q*=+9xgwXCPo?alzOJJRNB83na9U^#~i1UWqL$?4#~udH{OA@GH`VlI)0`T8@qiKCU%Z=m-1r0b@RttT#g5 zKd-6(7-ka~AD=R0U>vu9P{d+7?Jh@Ceg$+(YKRP2iSIR^VUGTYzFnz@v}4~U#u5Em zZdzzc6F?8&oV30eK7_8+-!=GPbmj@V{i@zTrlg6{xAPQ|Tv-TpUIi66M)@DnKdbc6 zuB?KIQ6D{huVYxidn*+C2Vh(9h_wH#M!xVF?#Pd*!5TfdH%l`ynix-MS1bGG2#xnF zD>A!Anz_YC#c^!B%UZpW%q%H#X^Evec^y z0Tr1?-)zzk)hWd1j6Y$C%~4slYw9sCT)WpO!WYk^va*(QD7q7_=zqJpLSBeVUai;B z2>C)*z{m9E>w0Kg7GPpDLhb@IWf9;bk<)Q;@);3gehRtqiRar5xbrZk1+<&1slRDf zZzeUr&{>l$9-NDHsi-MuDu+NV-++F6b%O85^xGSHSU1+s#3;3%zN7tESQ=)pFo^%~ zK1P2acobC{yjB173BHtp?|_&a2?cj*>PS<+zPZ_!dKSkRDY2pzzUqWL2tRtCvfk7~ z>aspBgI#Zz%!gjqY?tgu8 zyZ)-d*GoiwNKrfVW_3-w;ytonMLK15rQ99*F@rCpICPvkzNI&jb;`u(NP4h7^%lk- zxm{@~UOME)cHdiiQyHvJVN6Dhpp1a>Xyp;DNM(e3tk5BKm+y+L?x zS52AE2#QA&V7zOQiwm2rn z7tq7=h~0W4D@-$0hNFLm8&pgoHIORpPf+|Gy@6ER#Q3%axN9(Hk4s2(nY5-5OUe9?$y_H<6BKQUpKTxNkxxnyH~|maiAk3w|9cGI$30uK_|BBUC+N;TJy?FwOpIHs(EW5a7FkHm7XUr8w9|gQske+C z28Xofq#i=ICpS0f(3|>XgKuUTdyKrx^+q=4apK3y^(H~mPeOAwsibvA4| zeR~8IB?`H`_(Sr4PY;qhnHa5zr%n$a(P_+k`Z^Jgn`qinl>>V7`qBy*6okl_Qz~3E zx(89nVSS~+m&;rmOg9gp%9wW4EKk-MLA3gPeTCpFX?*G9gL><_(h9iJos()F(zgq~ z!=?!xJ)}p~l~zDJis}lQybtR;jr0`s0#a~F0p;Jcqv=LR+fBpC!BRuPH|0dr>LYs7 zy3z``*qxKUKBBKS_-dW>6e>Nchc`CuiuYM}Hchz)m{ifFppTAnJ%qQ?6mlHX!y1@& z#1VaMH$6H4;&+GEzNx<=FZR*t$@eiC%y<0ol|PB@{50=xFL4h0_9LrSC-0^->NX3EU7Yl@vS z_gT(n35k0PuKyj_-)ay zf*t|6kGPqN?7|**`J|F;0vEl9i-}K^cJx!&&2q=R+85$tdcxC2p;k)Z)SM#cw`(W{9L_-;(qqyW z`aYv0G>^yKedqKxGJQ>qCX!j*G~dYBUGuphcxX;*&LO|jA@A8k)cZ?4Qpz(i`g@h+ zY2lURU3)~{_Ak+lML=HLLp12T-a^VVG3J-qzngyjD$9Eu1W*0;okxd*?+?3y!TMKv zgp_Au#J7^XMU~~1JR>)UJa9%G#D z#G`QVb(7j$)#n;~Jz9-9^v6X#Jk+$K1HpR7$13)}5KLHO0NxpKyE}FHM&D@k?1&Lw zNBZF#y-Ap9#|#8BrRTTlpxD2IpG9tdT3>=6zMpOCGWz@8X_xh|y3*PST_)x+mH4qc;pxlGg71y% zN#9@ATh*0Tc)IN3`mQ@QyP|I}_@X(V<@EU#J;Ji9SFw_C67(C(=-^d7%(DM*Ro~cR zDd>k_&c~sb@u{jtcn^+A84^8oh-^{O#qdQR&t#&#|J7eN_@cYT%V^v+y@6#fyQaTW z?H|MpEg5GBjY$^%)bj^@j=|UDW!<4$-|3Bl-|L~_RvpHui4h*9@x30@>U%8b@-2JC zd+6NvdeeHQ9UU&PCS?_2{D2%e+Jk(5(02&FnJ z*L9qWoBWaxn4=%si!W8RlY!}%{M59<6gdH`TJFW{Q(l~sf(abxa{ju$p_l(J=!*Y_ zn)M`npHtOP11Br8Gp9H`Th4o3o-y*+gE(FQ1;4x0P!|F8&vkuzvIBahjLYMHirm*O zyiS*KRWL*4D@RPRb_JW>h1YfIXiih}26*B1KvMFHQ!wR(?*kTC5R&lfNZW4cFBuB% zK24}ay??@}!fBuKlRiq?qiWH`pY%=Mc|F;~jxw5e6KlsIW%$6BQRvTlV_(ybZbdUI z1$*?O5kDidbHL>@pS*ABQMFAwT3_bECl5URZt0f|zHf2Xe2Th_lI64~-NtfqEa+q5 z_m1A!vbVdVZ!-AS#xdCQct;QPHSJht!(cXB?o4Xei)#J?E^ly!lu`LFC}vLkm0z&m zhcAMRo=;`J>LHeW$FHcBd{?AiMk9X%-DxlVO@FOg?_M11&D`!#!|$-eruSXFR-@*U zx-TCh&4z)b ztj&M-q9OP63z9h2jo9@M{h}o9b0apruV3_L?>~b`HHV4%JS(|Bde3)% z=`GaiEZ`i-{L?u?FVdF3_4c)yJ|6Wt+j(ili|_2Y^S8cJvmb`T-|Qe;u1})h*(utn z0k4DFDau8~ycrOFc2njHnuyjui>6bWsHc4rO+RSjcPUD3l(zWb z&mDT9y7&?T#?}yBwGU%yO%3sux`PJS6m4o9#s+{b?GP<_ACi4?AT6#b-ch$wKfCy_ znx2cc;(b-!tyZB1?IP+?yINwSI+8Bb5+CA`t#!5WC!EID5skGQvDob<0=50Iw5^WV zu5PB$zM?gg7x;=JYAg+|D_SrtsVj~LJw&j=YYrFK5rtX#8L8LgSl)eYm=lWsv?j)UjOi}XIgYY{nX>atSgnD9G z317(?i)&g>!vily^*0jw#`4uqY4{TGab=6ay91JdFOss)d{R@kG0NwgAeiS_MimE~ zbAjCEVVGeUNUGmr&F5v*WrUWTn&ZgAg52DuaO@68C2qI254uIdu>*`+s(R&p4nhk! zW_;a`7Wj)L9pd4#7-nQ468!^JU4%>ISlgV8)O8e7y9w=HECZzg7;!@Rge2H@I zVyL$yShO-sw5NTrsHRrsYk2u8We4>M5eYEiI$Rp-!8i-8+Sb$WzFXi&pi|_BjrD3__GEl@2RBEWG-?-&DRr#C!$x9_nt-b(u z>%f9_b*S+7VTFx_rP`~ZXyV=o6Du^Isnn;DXj5YE0s-b#V1M+-eP3N!URFN7(q02J z#Rt$WlHAStA3UhZ1=+dzDQS5H4yE>b0wGrJ4;3` zNO2FfKam4vRdCrljCx)ZxppX}y_A&akH4$HlM&jVT7-+$+TE#iGF(KK^l@qYIe32U z#SutL%fa?Az_Sd^+qQlL+|6)e>Nw=hP%@sWfRg#W3fP|gZf2NO%+||2 z**b--2iTg@c2d+t>9Vo{vTKPlwE|CN?j$E{V{&&e;aKT4#0ey$Awhf7Gs6jFTt+e|fs>3%XUo$h>F959ny&XS8cm)QWr{rO1X5(V6G&eh zoIpyPB|#fAcq!kQ)%avNvE;$|`1NrAeZ-t2$ZMZ?$I~wNvGzyIn z&ExFR6}5}Y>R5)Z(m0S|LFz;YE*;9`Rck2nIB1nhXgDp55UaF==@ivWv??j}l<9{d zid*@=-y6_X{x1Ml68B*Y7kD$;+hI>mmC+_?m60l8s~PQa(kdASO6$}TsU_Pz>&y{^ zTlHVY^u(l-etm*8p9) z2f~XWsLAOWIjK`pGIBB|X5<#8ARSgJMQ})V_Iq)%wI5*I3GIa;n$i(O0 zK}*ieR}lU%w&rD_F?~(x&UV~j`I^$?2|83q1d%;T2zfSk5MQ{T`363ob6lJ4mnuDe zQPsvqVrs#J6if)H7SlxzGc|u)5l368y-N871ngAc#3;l$cg0>~C{=GQw#2+TO!f=s zpia3o~^8DOH)&8Z1(3E7dcYoc%IK;2pn1eq>cE>#;+XA`5BYh&(n^!!mpl%BUzKe zJk0D>8>J`%=$p3URU1E(&>Sfr`U1^qCn5taoa3qXc4cNC`na8F8uD@)?*p+VnW@|y zlGLHC{H|*3F=7kZ+lxkq)847Qc)inHX!89n^g-vLPqaW&Z>ZJNGYT^>#UQ(pisimo zYKQ&dik*dC?L&c&iRN|L`6|38ssC;(rq^|3I{MU!;Q_L{J+GD}6n3WVKQk1dkjUmX0_M^`%3dg)fCZE>^{~ z$zjQ%v#nB;nV&aNj>hxO@hn@cbg*t@Mg7fW_8du-x24)grjy!HY#z+dSWHGz-JI_# zJIjrL^N#X!L z)nsaWp9%b>x=U?ZVIJz|&Z2Pe+1Ic*3gwiSDk~P~R1B94sTNm4WyLZoEB4$(+TU4h zZ8r!fJcL(asZ2SH($O#}cAs=6`b)*Ep?kWdC4ojYhGAMrwhTGLoB7cDT|~BR+FF!q zycu%nCF|(gGoT*(ss3{obS@&OlCEat{<4pzH5reed(M?RZ zZGhf4)?=~q6?(k82#vJxR!`m6D~BtmV!K?L-CgX6GuwvC#b_I30`f5{jCQBWR5dRY zR_uKpOgv^1`D$c&+DUjV=4c~LO6iv2J+i`}Rw-%e`wUKd$bCX@N1i)vPGv%Ro< zDV(^bUfhMQEe#b`0f*0TZD`Cv+yQ%baG-P#v(r*gMl25+q31^;}e@QhjQ6-px8 zu?nKtdp?ch9Q_o$!hyC6lBQ^9m(%bV(Ijf&BNA>|66|%SY07C289V!tnrYOf8GVI~ zPR58Sw)hojTK`hj8V1!G*37S!YCt_!(+3l?m}f}CUCgFtaUhJyI^*_l z?~^cU(^`3_fR}+g?>sEe!jf@i8lCPfUbWu`0VS=Ce4`s%>3Fsb2P@;mOs&tWRObm1 z_2eB6l;^e;yM2bH^os{9#I>4=J*-4i9%qQzmz=TkmhXp3I0yqD;%rjwKi#@Za*npmhl>NdP94Karblf`0Ofh+=a^|kEGSrTtfP(ZgSHXpnt*cm2h6$SPc zp{*>ugT=^+cr2j6)Azv1V+$N9F43RI%M!5I)^!%P^uf$sMOFHV#w{(Z_xF_18Mu;+ zru}K{$C#)^2`I7gV@ux9Lf_vVQ8%<$SS?--ntCb8Izz8!sA1S~zHcXDkN; zSBhm1is~<3u?4|*KbWXB^l5+5u%(3^l_YF@RKm*xD0qNaJb>S>3fPV<3TrT@f@vA= zIzxL6PE5hdC?;sRP+1JeD#^SB>{bq#_3Huj&j7Je`@V!W4HRoMWgYcR5UmIL3`B(F zEbQr0P03_rmeOgnG-ZhCXqD1Gm7X9B{F6)RJ@)|mU?WRQIAMEbN-{oQJDw0aogO3{ zRYTC*gh^jVse?pN>)x|9CCN#fV+uzL!y#`2a#NWZR}7@BgT%|W@;GcWggFkC2a6Uh zEPRp$WJ%qbT}yCgMMZ3G52Wpb#6sINc-{#UwVpZ+5iOcqI21nI1PpsbKn%?vB9_H2 z#rL-R*Q#2jHg|5#p)rTDm9O!UAIO-ABBe3!twCn7MEF%_|F4Ht|A3f)F_b`&ky7c zhFP;2MG_02)oKq(=<6(!oa+_to`O#Ry5$#h?ioU#j>czY;j`pO5i7Og*YQ-TXdZT* zeL8p&nVZ{?L=TTVms*XI$B5;&yRSootE$?>n||pLQKzH1o_q#hZ(kIduJGrQlK-fb z6p*-&V|_YPL?N9{72cX-3tdPRQ4JS*NI1dB^}YO2*^@{u#)|sdhD3@RD>mBn0mv$t zJ6q`9SP|OJ!q?fO+((p95vQSeobyMOIU-?rgvLj>t5M%Hqz5iwx{-z|n*Ihomo7s4 zb_I9#L}w3a34mKVa&n9UNloTaWeUc0*?H(Ca$jmT$dc;x=@?3P(#0zg?QfzN1~YdX ziqu|YpkWUF&9w>3b=OdO>6#u$K?8;Np3@nkg=!1O1CQrm%65_%C&I!ke4O%;0MortWd7A4HJbc zltXO8gxLyZDcjNz2Nfcx0=Qxi*RjLsP?jJYuTh+U@!dtK*&?Klh3&&F+2OP(TfAxG zha$red&e&7J6?qNS~$Lfan5jhdc4?bi@>@+@A)~oi`q;Ojh?XZR^}X+=Uh|&{W(n; zoMckugu-7Sv}XbyUSa)x*e=&G7+o8_XT=23Q!U|lEQ30rWq1dL7_Z0b-m(2s9Qk=^ z=nI=W2+Z9PPBsTi!SvQ`NY_Tdo{^TGQka+GT*Kh|_b-6Ol{V7%N|4m#G|clz_#t4j z>7$;Vy=-R!a-UDEF`kpOXVOH`RkiV}n>zMO;6Ue|T+uMb!l4{Avbyf`nsSTna!B%?ATeOUv!fEe62D1O7GL&=JEg ziYDcWxh4F5>=|S<&hyK|2hUlVY^FH2;!P^T^C-NOCo|j0zQaxP$tVQb|B^vTOvjM!wUO`9KZT-o&|>Cw)&oDx zt-1W&A1RZFMimKP?YogwP=rszVASFzFn8ahMw3O8Bn!7^uU2(pJ2!)`D5u$q%Kiyb zb|>41@DU!KEWwU1&=xbzEFme*ZFzhZQqCw2y4-dbZ7he7aDc`=C7L8!*atP-3he^h z&Ctr(>I`ia+k44pPbxwyWm+W-defDsgrAy3YbIl!&!xts~w=Pi$&Ac z7QWBkopGF+0=w)SA4N1qN@O+}-KotK5zu%Yggk`77ZK^u0t|}ZRy;Ti3PhV!e{xI_ zFWLB2;$3(eJpCY5n<^S~vhY%tYGutB*qzJgPa5bhvzs&F%%vhEHizuH=c%cpgW8p! zKpqdHAIG=xLsiAQU3|JPdmKt1&Tv@H?OCpDG~PjJ9|nXU^}4UuTQW^dd7R%=?f@xS zPAOL_q;St&wVVs#&n0Ea7}_ySysE|e(!l9rwQ&Y7L{B?Scc+W6G`8=O+=_kj3)mu) z%0A^h)igkFhO*>l0^I;(rPlXLknkj>#;-r0hO8v#l(0JNSE0yX8BLlkUM%6qrTZXZ zeb1l{&i7I;tKJn4bdAkVEzHitOs1@U7H6zf#Z+s?SP!+vFsx838mN+5twB;pV8aPo za`};>XG(;BPB}!HU!@dm8sL(>!9~ISB}^$}3af_6NXGRbO5!#q{>O6179e*2fw8kB z0zqOfcmoc&9KrYN>KTgR9V6T)iZ={iZmN-(v&wz(R zxjT?naRICIo~G_wG_{pCwl~NJ-JCm1xMj3FU33d$emcT)#=oA zfT286z~b}IaA`1D+AHcz4?xezDv^68J%hV{ZQgjQJs(E-lER-8&8k}%GiORN1@BV* zhc9AlQCdt<%s5ODR?d>O!@iv8!*awT8gI(I#_rw2eCkkIRxj^FzN#@EscZt3T{f= zdTlQ3m*H@|Hr<>nPS_NFnjYr-c{=pG2%S3pIW1gmrf{YPGY5h}+E%#yO#{En_mnyuo^8}EbwlkP`#s(lu1{}@rr0vV&Qm* z$}S$Biq3YrIsf~33q`^0TW;wCh17&?8qVJrN9W{mO0yC;H4j2Ue#T^c01Mn5hOxtd zjHe{crL{U7^vQ#9;5R=vo@1#d+2Wq};#drWc9}3Z4{Nw$@tSno2l@$iJEm4~xgC~n z5r|PogGMhACr4cV8w03^7|;C|{hDJM9=NUU$e-LNBNdlA;c%*AxtAes&@V1Kzo0NK zKO@6k^Fh%`NcCPh+2e9E(%CC#0L>`(~@1ScmZK-JdgoU?q0y+~WF|Thf z4k2O4#0m5(T#_BdeNpIAr2JQO)n#th1WtqC3Hlw?8BpDEJ@Hi zbcCZAop_eH=fW~ksJMt4mo&v9*|YGrbSemHf}Sx6f6d=wnzUBD zYYRss)E;K>kCd=dG^=6ZaQMo0;2j6yXIu2Lrlgv<)qde`TM0bC!~@{&w+6Ti@Cd%G zEk7kOCK?^~8T9)~@uSTLvIAg(ZqW5tMMN_T{b!*+*RUx+p#~;v4PoegNj#+Mx8BujHOMSl)|Hm zYjbgN5wKgm?+22a&_qqj8dQ|Qhnn!3+ZU_FXSVQrnEZo@{fTz05iJH-SkLy9H$&or zaVZX5U4arkrUGM*O0nla<7g%oBCTXEkteOfso7f5Ktovl){4uvp3wUcO!!S|zYe>7 zEWEN(SbpO7-migV3RA-gOb+@Kf1q8?6Yk^ z3Ur5N`p;CpUbN|H;r5m$X?aCF@4}JVX3<_?MGc>m_I|n^-R?gx&$)b5S&^hmSi{4s? zLE7}!#Lt}zA%*$MSrU4uzZjMzrx1(5XM(4YRenj+TXH^*(c!kc z2(-0;_=THQG!~&3!sOhcsMkfP&BEb1rlg6liz_xR>g?eC3ngt4VF4D7WtH4i%yfF% zv;_?qOT7hi>=#<|24=@CJcm6w_r!BO8HIE{Qc2JTryzB!_}Mo1PY8jT`zzhwDjEh` z`0~F9(l&K?Q>eC`NYB$S9e<;q+eG6K3x`g8H0Ja!dx@vV|I!owg)J}%=qAU zihNsySKzr$ripK(ow^JLZkx*PQJ-BRqylfwCC4ris-4KC8E=b2wm#r1h3WYRjeJK0 zMOyeeqUF{+$d{25I;hF!SDsO`#jR!C){7z=%Q*vc{SR{N7Qt05+@6-~ z7ERl3L~<^Lb2*H#unK3h0&D#qP&{^05eK3J02?3vs^T(YY}`Mn4meN zMZhiL0XBxKH+iH8!Ke-5V8lJWu z5RDpHge>U^-MfOq;i(0^Cp!27)0y~m&v4MM2gKJlOr3kz@KP~(M_(Qkjl(Uxl0BlM zRb1G+*n#sS{6$vmBjEFvgF+7pzq+Tvku2|39gv5?``GG=@}7g9JS5KGIy8*iu-YB2 zQq#ktVO0zJ(4fPjzHh%tESn`tpDZ+zW*ioghOg;q$6<8PV_{zh?K*1o)Da}Mg|jBn z#v>xL?QTf%`&ml>+bXc3Hxy$nj@r3%vL5b=)dvJqrb^w93cs*FVYk79y4CQm+~6{R0~sM$q1&aovojgd^r=#?fX((G&NC`t`F{;_DH-6@diU=-RF<(mTXJt?O5 z-+b)kyCGw%Z4SXj-Kf`WIn|kGa2*L&yV*YMYt_;OZj@z{jCH6JVp60CNjz;wdrGC`J%-1L@OKDCsw0 ze*mL?-`H?zd&7%k)e~wY1W}bw#e1~ylF$vmP?SXS>{qOKZB*{8*qwor)O z3v;YG_4`aT4YTl4DW$l75f*0p z&kChqKSRIr0dl}M1jB@ywEK)`Qi0DG(f4P>nL2mieh+44O&n({)6|&_YEtkU%>wMI zEOM6f%_92!bMd+D8fM51j5@sSbmpvRQQyMKWGlzaq8dhiUx+_#-ZfQkJIq2m1)LLs zRW00;x}OuL|!aH*2UjSSN$5#JwoFg~Yp(QrUAi3r{ZxIr z^rhHW=S~gP`yq@2FZ=dDQ+cF5hQO~k3vR4hF6S-9aG|!P?9Ut$Pp!yeehm2$-B9(u zjF(`)5)oA`tk9=lp(KRScVCG(<21M~?DJSYhmb*#H4S}3i zHEHWbQC=q$t$qiXn{`pHHfZXX!J#xLx>;Zoa~Fo?>|ZP^OPU;dMo-~|((w@5ipswc zXKfKExE)~}ezg1&63)W$^zkL}yDbP#VK6uS=)||8VFk`9rr*C6pVujaJ`r|&R_Y;c zFM8nxO@n&IH1my6EtgURpImHClb9ofPeAeeTw4gQ;dZKbMWi)45Bqf(^`DwvY20q^ z0}tjnWm&O9eyE*Zy(0FvABh=}X)xvf?pMn9z>?pg0B_8XSmSK85l+s_#Z-0`ea2#R zcy__`tWU%KE1I{o@Lkqsjy4reJ7MrmmvaEKYbr|JDYA(1piUODL@06-=3;#seN6<{ zwQvOZ{MKsE!s&*c7G4v6?ME?bjgw^d6fmwTpmtS`&GvRTM%*s z9hvuRRVH&2F9)8AYB}#PMVZCSbhC3g`+f?g{viBoeGd1ywNf)Xq=i!Myg$5gA6#$|W{idz^m^l=*VgQy=KE**ztW)DW6>OO&TZAlpyFY;ACZQG8az6wCR<8ot%Wm=; zcMo*;n)P4cxTP{4TOf8{4O(^^@yNn>f`<`$V;X%&)N5v8-)Y>0xhiG{;JBI6`#P}i z{F_$YK|>pazHS_hy$Q7ZT~&VwsZN8&1_d_4s-e><5kB1&$p+@%Ni*kT@ul1hv$P2% z|0=rKEIe%*t^HNh>DF&LE0Q)q4x>*fkqnCpWXl?x;ovs_E+ZLhNG^|I(;4OVH2MW1 z0xp_yiNP8w=BUjf_f2^EXc~q5Cc5}1BKUPM&{E39<>R#!W%o3i^c$8MSh=z2U&S`1 z=66L*RSRd)nqP%)*A6p0^z&y}l;f`70R;8uzv*|8?m$A@kEC0X8MZa6c@my>O9xqE zE%G^#*H0&(-$hsB0Tde8rikI4*Gp|`^?>~T)Np2vCu$z z?ROM~ZD_t7n4>O_pz-%auL_(v!_0~35|5aMGki3rhUBW06W3?RoGAH1CRXtyIdRye zW5&PYOR$Ye_=t@&XUG0T#FvA_CCP2UhBK;=$yjo(i8k*!*yFCq%5)vkxeudW!_uKS zFd+H^o7>{iu6z&EvpEg8FB%0~c#PDXmmMmUm{mga@1sk{$+8>9zXiqp58q@9uPNCx z>3`z3mu)LP1NV46suhj@TQm!_@FA92?3^2J5{QkOrLsW_QA*k2(N0Y>f1FJ#p(}rj zgSJu#+z4~C6>WJaTD7upSLxSHXeJXJX_8`Altao8GXB9A=)Mn*$b#E43oaw@J22`$)!n+I^JK~MhF5FITrCWK{wvA<@ljn42gHzQ4?Ww4z%!G=C=fJ$s9YILaSnK2G6() zqfz}Pv)Mf+&oKp?zc5pdJuP-FoZfU&7^558ATk{$IW5sG_dkWug4=6GC4KJ9O_Wjh-^7{j>iNscfkyh z{nDP{EZRT- zb10{paWjS!mgfX_bwcm!WlddCyABT*3S=V16`?n1)+UQD;u-fqIMMsj3LoQ(5}qjK z)#k39(aG4TsejpdU3O?L&oP@Ru2?Kt9x_* z>`fgTD4c9!U0a&|l7?zYgZ=b&GzLod}b{EU0BBiuJ@8T;GK!H1mtClTFI1U}Q$jb2;?cv&77 zPvQt7KHAQbU~%4+DdRT_Yd4SNLOQLr8}%dOq+8|8h+wMRec())Kag*Asd^n_yDbtK zasXyWclw}?5!TwmYuJy~TySH0NfIiwl3$HO&rv;Jqm|JS0{ZywdD7RIqmD1f)DurP z9q);3UZSa6)apfYB7bnk#JtJ8jh7!Nv$!6Zx^bCG%yV+sgSTo*ZLBxBEyJ)Mxh(CF zvJ`v$tr`t_2Rp?F`WZ`YqcPXD2qvi){o-fTO|x(mq#)|%kQrW-Op}0kFpYy%WN<@3 z#|{V(oEsDP$v`!sc2cpN6C9Xn?qZN1jYg284xyL6;JrH>I)}Uk=0PuN=x_M?QT$;?#+CIut&snIAn@*#o~*( z)TY0vO9NgM&1hg3-O;lQkB@rrV$s1+=gwf!3e8hFnLp>Bc3(-A?d zaPa|5$0s1_kg9G{jUiJCkb-hAiE269DJanRDEt%>370OkL9KA$%?<2{DM(999gEXt z_AjMVXd9I#oiKV)=@xIDN}g*jC?(jKVC(rbUhRO1=tIYYjD`Ug4u2k5={zdB{7p^i z{CvgApg}>w#*y4ZK{AoG%6T;pZ&B~_BR|M( z7?+@jh>PO)o!0|U{inOT{3Koe@d^O7r-#dV>9S0Z26eKB%lqu2_&qO}9EK!K&K-+; z^-@Nd*GKaCtes%-JFAz0VY7$d)l%v$eG90kJzUD9%Up2=)cYPTQ=X@_4UBhe5!-RX zdv0mFwOe4pn-Q#F$FVYZb|DFyg3%0na#f$9sY z-%0HlLc0m$N<|e8ir;nZ7N{XR6d(8eAX`IYuWiFtWE6~VJe_Q4G-zz$B>2qELcU`s zDnghFXkIX?*q6Ua_Aq0&EeNMX_+-e^csd0-eDPz8z0Fo(U|S=n>P*GkzzOTJ0W__N5&q;cC%y(&_kuC(MNg$W zGIl8)09Z-sD)dtmV~;Il zre`CJVxFHKP=n?8E@JgC>eH~c<(caj<%S3b7+3MH6Ku0dAPi{ zK%s=8Mx0yV9B_A-y@M&Kl@Z+7!oCYV0`CCm)?h7fg|?2{IW9IGhtSB@hJSqvCwh9F zypUdOZG>oO=iY2>yldkY=?=`zA>@cMg4n#{p{I)ElLs4j{ zSZ!|7vJ$DZjS)P~!lx?<3Vuln>Iv479)fIe;K9&nP)j{r{(uO@@1Qmd)Xg3)*A`Og zO7|2T9)a&4ChENPq3F;)tEt~-f_py0g8r%K?B$#1 zqHt~$QXHUHirOfUWQ|G7Z)iWkbTDu7S{MJ2;Rkp!vahM*aIGJX5!iN$YBLwppsq%smbRF3yBbGr{osXJ zy+=})Zbndj3orKc_P@pCfV1}XVw&I02&{jcoqHD-CJuhWJ!bDLrX$@T^~6*7rWK=D zjid$Ljb^D9_IU-~%>3lsna{AmDp2!4aWEwYH@D_yU?(V-mBFA?Dq@i!d1hM=s^7!d zHKY&`xd>A{3I%Gnrfz<$Ix;0?U`!i6#^(%2vADK!SguUF!f;?rin}_eUZK#Q#&@=B z5ISrP9&s2=HG3IBkruw|DWchuM@8W2rk=+4gU7)4X_%lCQ?-K~oT{~RSIy$;%7R>~ zP5KwPqorKidB_Yy8M>K5B{4=&OAF8Ol<@AqNZ7c9j>jN!vrvuvkzq^6(4JV791EXh zKd#KWwS+HG>P@RVG{a-`os4YTad_gK4IfKy^fsFNTiAy@JT|1CdmFoKap>Z4S92k_ z=?n??cWN}ozlaW)0t2pcPU@VgDzN+qvtWFE5Szv%_xs3GmK8d*FxXadY z3LeryXjy5rx{uLtkcH=Xvfp6nQQl61QmMRc1W7h&t`_WFqFQ|s3>WhD2r4I?KJ9CS zwy?1GQja9)4p>QO3kv9mZYO*0027r#U-vUY0xUezQ^2I9xQe5p5#yHn?2BWyGJ`&S z(ufSO@ElK{%it5I%ghEWD*^?Xt2j0lDm`A))CFA(t|2io#m+>C;k)!KuB|M}RSbV; z=#f}g-6%ZuhOs@@*-w{Z7Q#4Wi$w--HqXtZzxo>y0T%XN=8-zV%M>#;lkg=v0CN}o z1B`}I7LM}d&jhTLnnOUs6+ltf3_NyJQ9u(`VU!HBcN|qoFoIiJ7|%_($Ln2&<~u+9 zE~$M#8lsKMXi$Q2%oaHTAIKbxu(GMaAfwSZ3*+evR1SG@%#B!< z`1{K_2YXY4XS@w^3_;@%y&PMEVYW`7{|+&lg+EscC*>!G6ACEwPKQkAf2bB3(2hB@1nwD62D~IOF>IhE-CKieHBw& z`j#^E(03vzl^T(@AgRf`84ok?DT&22ezZ}uwv3T+_y+P)qw_sYlROySB`4~ zNh`+g?!2e?DORphBberjzl?rw(ENV$!gcrF^I@E`1Sxrw(P7k{*+GZ@gRVMPiQ_QS zuq}F|5#HRw_u<(samKH%9MgFEY@|^qxD^~KMK};73|Fx?(`;|{qM_q7k1wD-qm0nU zEIgNGy3&8Z8bG(Q5yiM7t?9jyM!n9JLOR7ERZgD$AXZL_E30YLXd@_mGu-@M^=c1o z(qTN3nrtB6*NFb_yNmw1$tpE zU>pulnI)r~q4O&`Zn&bXV(g()sY&tBX(DKqbZQThn@*ZPr#+lyy{33@nogd1?i5^q_)tOZ2LHZNYlk+p9 z+*byEU|M*7W*c|nSte$9_&vOi{z*4>+L96VkucYvru`X4%lZ~hM{v%o09o@X>$#h~ z%a#OIW=Whz2Q!W40TwRvWM8{pF~yGt?--av;2#I^7T)E_|B+KXYr-s%)9Gjy#9R2H zC;Kl>@pZ<6Hyvi_bbNtIvHcih^)~IAHL9;#F8T(Kc+_8#iJHI~F@rvXJ{*r=EF9^{ z+-rmE^vBSE@kXAl7#Ai^g>k^s1fxlSg%dqJWxIQ-vlkxr!CagH1u>a$yA~!B7B&kC zP%W2fp59;DK(~4uv1X9>;qy#GQwjmT<9s@Z!jrFAZ;QfvX&dv;%jx(Do#Wj=L+p2Bj20trq*n4NQsXiDIsnnJuRCn=96k1udLn zyxyV|UKhe7%thdMp>MAy1Mi!gW_q{WZ*Ep-WwG&QXF^QhN&)gcfQ?q2W|;?|@N1#mU!8ApC<6ON~8s_JVjG zW==nbs^t;|DQ-fOS?B`oRmdoZzjG|~AcXD#;R(2zzcOkw!`NPj zB_|HXyvd7@KF>>CuNq5UZsr@HsFq8yr}Q|QKFg?IFX9b^IizT;b!&{7N;Z0PmJvMU zk7H>4Ah-_%t8XIc`tNJXACQyR5|(RhiGk%aSTcsfl9qx04gjT1gXImjEP-VyEY4qh zQ(M-w5GHg!w0%cYUzFMg4^l0MbXLpK>52TjB2;HC-EV=8t5Cd<1jFDzpA~xbZ2rT@d*`^WcG|NsBb=h=47*$<2j!^}3r8N)CvKV}%__pl@l!?65Z zjFy*dX?}!QTJEF8h?3-Yo_;JAi^bBEG`0LFl_X6qt&+aC`*}Vedp@4(^ZoO^E{~4u z<9>hKAHN^xJkNRjSf=jE%!$Vf!a=aJ78%%wgDgDE`55@QJVBn0A=G?!!Jhrqz@amk zsRQJvR!qpS8*d8_@u&`}%$A4qT?EM$4?E{Yk3Tm1QDc&bQ6VmPMq zmuSFpHMoP|Y}Z(K10NczUWFHKQFN_Xjj{jSV1t>382Z^r>N<4%H?bnm-R$_ByWW%L z;2nhhvyf0Lb&aRxJO7I3Cyqx-zaLZ{{>@~8pZ$+YR^ZEL;b4nC3}a=&%ar+o8k{LO z4ti2q{>eCM?&RJnDVT@jcuuHb&$xN%E}q9tPki(r;yCA-8&m;2A1ah-@N#_#{~~;9 zOUYmO&cj8PGPf&+5x9U{Gze^C_K#kRi%WVrU!$?xCH+q^KAe7h)%$n)2h;TzRDV4h zGW9fOPKD)8Zo!dK0j zw&;Pz_{MJgYuL@p@Exh73wkBWq4X6R{GuA#NU-l7mt42pW4~c+cu_6$%0-xya0l1Z zyftd8MuOv9!;IZy4&8c$)r}P2qBC@U4L;549q7&)wbUzW7=GQuT_h@At2Pf3oWVv0 z@R{c|dlhfoW8opWAC+}zt2jFpDcEVEHG3gm$1mp& z9TiK%y^iT4HA&BmgKeVD7h=aqpGB5)|?NaRz_D{9De!BuQ5 ztskFjVaDn^?nA{gdmlVUnMYvQ-!A%2hHnCVAL<1S;pI96^n?$7Vw;l~xns26N9{MN z@f6t_-;A2Rf?JDkH@r`WyPr=L>($0Jyn5eyQtJo2%W?OaI9u#tvlWcLU6&>MX%9KQkymrT*9I3DYkdWzfEh(t$oxrPd(?AhcI4M;e5B!xB|6#gy6h?nfl0Sip%uq0r{@v%=3!wI5i8dU@JYj zMQz))~F!0TVXE#HUd*tD55ai}Wq>uc|Uufwy!-^zm&ylbNo zJJp8Go@Jl=O6@6lgF96kN!ueTJa1C_r|=5k>KQyKf4ozDGV}iDcn?&L@2R^`XQGF)#ONg9+JqB<~s(B2o(L98LgARss{hVT1$7oK*@Uo6&3lsV@>piNUJtxE9J9gTrVF{z2#7-;RXS&0Of)1$r*LUi_rRiU~Ufu&TQK4c#WukOMiS8)Z+^eTqTcWC!Jsu3>uhHIF{ zHkg=_W*!vGdDCq6pW5|yt9QIOya8AE4tecS!@~tfb0BBw%zntm6Al}5_NbqE9Yi`x z;Ck$)VSCj!jRdcDwXxL^=E^>`HGRAn?VSU0q7Uz;W&6~KMuLl61730lyyV4+?Z}zl zL&x`HT9x1`*Dzl6(q6P)p9A=G>~j&H_2G8xp)U@oA&mqZhh6d*bJ$+CvG1w@)axM9 zck@$xzCggRy>#!O8q`Q|l54=Z&Va>Ue_oL_sIiW{(L@<{-}M z_?mGZe}Lh_EM~&a+*5F(GoSL!tz;kj)fDi{Of@lPIbwYC1SW`~%s)7xe(IP1iADbc z?bxuPz_4}URvc3H&ergT>rbj`OChur!j3Z;F^r-Df(z~Wu)eQ;?pIQVR)G=hCR;nA zSU+?3qdJp~`ldA@OmelhQMR_oVXfCmG}3JJ{he^D4^z-7wOJ#0SSZ&f=aJ8#?$M-O|*xVa_*$T z+xc@@PkYav^WQ!|kBmS%v*4nS(dpA_vjKwhTy0!oG;528{&S#*?iz>TRr5^{tvcci zzA=@fQy4H_d5mtIQJcjGzVB+h8)mt#|(3V#)h=WOF$(e5AAA*Onfq5s%`>RLxD;i|djH|Md5$^;t|#6nxP& zqFcx9Hz2GzI^gAt3Jrq0`5v`9r-n5Wtes~4xl!BQSvF>`(gE1uQK(idTe3^ zT=q$ONu>Fa?-awIu3S)6LkLS;ZT`YIujZh?t3~!oZ}thkV6v@CaQ9Erl~2^ru7Z8v zcS+VH#;NA_G48{|8J!k8yl=NS=u@n>zA_3=n~8XCDW+Bz)#k$lXE`lyD8=V3MvTFH zx3&+$7vb|z!M+bK%p${0>um&i9b|t?X_m*HPw|l|@louH3|C!DqdvpKy|4Nk2BV!z2Fq5y|MCk zDb2c!nLFvIaIWNxGt~YIHF%`pfMS=lu4Htnf|>Ans0zBn%UK1(K=@0fr#{68LoN@_ zL0Abr_9dov3Eshmon*4VZL2}Gk$r$ zX7*WO_ko9<=i3=~-Y#~JN$kPn0JcL)e`XeMh0EcFu{U;p!CGRwM|XJOFU?+a)obwU zA_vomKcdI3;^&ayYtWL)C+Lh>b2ayQ%NctoDZHxcX5y`n>0?A*>Ec!OC$C&s{sk`Y zJe|7+%Yu8bDQC$qe8_T=!*b+x)l=DAO5LyHM_Ui1@E5rFkEzqwm@FVT&(+rW64zA5 zf*)!+*Ac@08`k2>wbB?Wj-RwOwW6_~sFf-N7+cf9&YRR`%Ir=Z9Um-@vCqGYy)A6; zA5NO$4$={wkUL*g8QH$UY;D1dpe7Z@QAU@Jm|tQq==wKQf9}?8ZlD2{ph4G5#&6g% z`tgR^G*)oAtF@pH|CRk}Xvo?3h6?&i&FGfd6772Rc#Lira1(n?vHs8eT#?W>PX5>~ zlzJevoce#q_a?mL_;SJA#<^oZhkx^5HJqFIFLw{>aTDw6&1Ko^licTw3m#$7XT!OF ziZ@x9TN7)(tR6bgeu#ioh|6KBL4`F8ntkAE-aZ7A@@Juy33u^RI(t(M^%NXH@Bg5Z zS2{$C;UX^5`X3+`9Bmh;Kr|aJ`yx%crG|P59&?t~++yqKIcwl5E>gQ6)xa9gI7>MJ z*bzSFrn-b~|ETKTQJ*2*A6TvbDA>9%)$sSWW``gwT;5pue>hwV`( zBHHnAH$J0fKOtp;%kAPgh=#%SxI`oGKrFc0E{=jI1}^s!1^ujsdJ7IXXD--(#Vd9b z$`kJPCA#&q+SpTYG`)BW~p1PG-78g>tL+Zg)nwd*pqzNa?v6dY|AC%%SvlW^`|(4Bi~V{gG@O6?`w zJ^*1kOzIc*I18+5+>}Z4rwyGmdqT}l141dI)GRAM{xO~kcbEgAtX{(OhU?P}KX0p$ ztS+V3s@2Vk&zBVQhuYj)U?!*C?NzvY!X7W^=Gq(KE zv*8Xp!lbD26X&M%pE!SJx-*PWDk(KPe<5|asjdy@sH))f3Pe|E#Z>rVLkBto32{X! zz4e!xlbOF5Q#+qSS+e>rH|rvEfH0RK*NhTErxFpF2Z!4W$>RGPhKJT4;nTkP9Z`PK z{7VNOI8qusuN*`KpTO0ODSw$`O0uQFX654IOnjR8PvJ488vZvR|98O8aUeA^nDt+> zUllL-ulrBgTDM&I@0VpkHK}>q?H~k8P!v*x^yuGeZiiG9=X$t{S5QXpS*^+H&@mGn zW1M}53Ueu`P>cVF#{R9Y?GS+=NpSI3?ZNui1ncD3*uo4Z)KVS6s#fA95`q;vg0-v( z)4enac!$K8YP1$dNjE{9{@S<`L z{_SA>-?F!qNcd0sFB!T-iG`Nk!QHUTU7O>T_W}kXxPa@lPth8-5PXxHuVW$O@Vu9bJtgY(mxTOnu@Od`ny41FRIPG)O)`hzx z{3f{QuVDipc!C`^FwU8cK*(chrn?pp(bM2m%>1`CvsbyMm-f1AYrS|G;6XUcH#E>g z3(6Fnfkbh^%VoZw6Z-$`ve`-`?4-jzRN&~c1 zk_oW4NhG4H#nY!Js)(rT&!_vbt$Ie3D+B1)@ z7=U&HSNa_y``&8pWRCZJNA{giGu#W6R7ChBCijbCpHZe*Uf@K0XU&C${ctrAJyk|g z-l)PTq+k$S#P@W;TdQBg`5#lIx3*p>i=-7k+RK^Mn2?&>A4BT*NJgb%ooG)6=A_mn zL#Py*$(T4>B*XiHVz~#u|91=i#~RuXFV)~`(pMLO9JSvE{*!n9r_iSCf`7$-%05-D z!2kY#%6?WJz&{E3ks{<))0~29YjeVHFGY!w&u+Hie6E#0d>o{jjK2nXJ5t*eDK5u6TH=~S6bmKVzCdRC&=vx_Bj@4_o8}=7Lj%r3Ii&e;?T|8L2DL7@+gWqbz;PBf)9i&CI#p3qT z;mihWmBk2^4_A|tFHxRuFCEO}Gk!NgP#Y#CAx&(E_QF3Yc!E#72R&%01=Miz1qu$( zHY&Luw!#3dm75Y-NZ&Tmb}E6#>7_tzw~|*#y_;f`I8;cNn?fY3FUT6kA_oMVkFs?;M=m)+gAE6B)+8avTVd@>KZBnvqbUjo%u6$8w+tOScX;tvO z=(jNKkdkxM_D&1!fK?xT!lHXv-3qC)l@>_Zt+W(n-3hwYN?WFUcbw)Lh^*ZSx@REr z2ghkyI5_Qu&8xL`&Z>NUiau`x>*G%mMQH1k^=GL~Tcmd7N47I)l&xY*nrur*VCt@x^hv%-6gR>CwKZtE}T>jnh^t>F4OhI24cnIcnMu^0HFe z&<~bN&r;L=NcyB=+xz{s3afIs4D0x{(F$I+{2s53^~9?%F8a^iY0Yr00i_Mp`YAaj zWE-f>R;He%R)cVz`ytUFZMu?ohTH~g3zYm~`rlw}x?cON8TMOxZm^c3pDZ@%eWqrV zF$9K^OX$Q97>GJc?T5lZmtuN#C{h)9hMEo2Hd({y_%LmM~aC1nB)PtYa-_a|s`tWgv?LVI4BJAvLDp-ob5j3n=okh;_Ckx)J~ zfj$K)tH;~Aj?x};S1M0X&STnCW!DL+=Igd1N*)7+YdxrV3=)|AJViZ@3W+YF!pF7o zN=gw0j)k64MA>7tvC6d*bZxBmgi^4|*7FIip`v{EJdGZwEwIMYN8_}4N?acG8IPu) z8cn~9*A^?Ay3*VUXc(0ns9iF`mu{eye9hZH-zB3UvNza9PSk$0Dk+sTa54l5HrhT} zo2%UJPK{D9OzyBJlGaJ{cRkmrfwO8us<+uU4Sw6xBN3Uz6sF&vX zKiieX+U{D)n(MS?H5yS>jxFd#Z7fa|&83BFPz-swwy)P{iB{$0^Aw$f^1%Ued3;Uz zm8x^l+0uTb+?P;(u|HDaIxUY9S7`~hoLp_VuJ~rt^?bDboNU{3uW3PUO4Ux=mI7_A zRax}5t^QUm&`n9XO`WzwW%Zl3Pq%B`tjda?Y<1q$rYK6>PTPXFxFeLjLF;#Fe`=1j z)0~T1Bqcwm>Gbj28qwTcS|8=&b~?06JE1JvVte`>ZG)m$nHjxhW^^3Q->WU8zxHa6 zE8Di(M(@*>x+y-}Y+oJJ{&BbZ&{s#a8P*;&@TfLJDP2g1j%t&1eF@s-BW@8i;;0rz zamTb+Jpr!)JbJo?vR5P8eoPx|4Wzrr5U6suZG53-D0(3tJUn{41<-|)PG3l`UEG40 zT2WZB)>(?p;4Ogu0wzp4fI1)JOwr$W^&D~uITTcn+wO^F9D2n?S!_bZ&sr+NK zi1HsPstomM(AqNXO(n0hE&761fC1l1yDw>7f>Pf_Bv!XKtg2P@!%0A$JnH#@%PoE$ zZf{pNUODKj4GDGaAgiBhkvgiPPcS&1lEu^}aw61#ME2i)=6@0EW z@8F@RA$F_yzlZv~>Zium$Nw68sJM7|nNm-6j2$&Km~MZrMOcgMwkp=c)?Bw`G^Sj8 ztd_rNXpm{hpZ1n(mDZ88ERTMqAj0TA*eB-~+_AA?TTfHx}qt==R^YK~jQHs?( z7ut4zrPWhCheW|}u-l(j`tTd=2~R#!9(dhqYkNcUdnj1`w-`|^sx9R^?S_XnmnN>) zLh0j5tuZaVtu+e&-NFfSTbbF&qoJRfwkF6QGOZ4Pi?ILOqn7#zeR*5!5$xg5*$=im zkNRq`+blniT5k3I8X#hpi*)^t)?)}CGmm<^X0KZhwWEhWr_t)xnp5ibSPOfaebqo% z#qxG_H2j0j|EpXfdzq zAMLaoj^};%dA-VADZft7c<5P5m>2!!p)XT>yy$rq*W%yFTf?bzVfW~5O~0bV{!XiO zT({k`&G6J~Ta|TH^gl2C4JEybntSW(m8xpnF>k$rRf(&nPkr=_%I)82PAwge7S+_I zwtiAs@hAOUTi>nh|ARKyL4Y^@psv395~b`9+c96grB!M08+}t(U##4(qRI92HOjT$ z=+}DsekJ}ldecuouVnp3Py6d)vT}ck5?v3>l#r;0v;MA>3 zhC990L|>>J{+n6^>MNBUifvz@9$;0O~i?y<92ww>2202P(>~`xN!4{)w{RLi%VVV4b@y zXEf)cvYzdi$GGwa`PtOR^>nL}{eTvYMc4>`+vq3sQ+WLKq$cCga>jen+vCs>)_KwJ z@hHVHUUY7}K3j?LvUQ)JcXw9;H`y{Kqa^V3^IVEP&l+$0Ek&QED8?S!_-Wj_x9y_Y zsVL^a1N2L(zEjz`n>IbEFR{i`$aMXbQv4i!Hys%rvY(dCK$Fzpp^-Du#t*+k4Q8Rm zr7fYYvyh4McWA+E^o7XXRBsL%$l+bIZVsCC+1=DX4GD|cO()azjTnT+Jq5GDdu^d} z^#rR@FqhKjA;H_`(v5lObzA3Bak~DGlAdn+V7~5URYq>13kwiY#1p zG(EdmpKk3>Hy7(Ol&tymXeKb)R+Oo`S(Wn{^g)(>(vvr(!qEGoH&rgyC)eVgrhr!? zRI6fLpP^4s3?yKQz8D8BTw9{gu#TZ2&m&_An{0Kn5sfv%mcLYQVpVd|Y)6*qgRDxQ zjpVTc2`}A9&#k~{5w($ez5q_xNJm~k$@*-hr7Mxa!Y6IDR_SZ3%GBAm*H-IY6ea3a z`fLrda(Jd~`&w?pC9l$ymr%G#`P66~`c(cjTm6@j2W9F2+jF@XVXRTM9k1wEvOJbz z^UTEU;>&mn*r3nw`l66RsQTxFK)(2m>Xm3S-`Dr zNnhL0E&5o+nm{{V*HB@Gbp2Ya+eAQ-4<3d)*fLwq6&-9&hWsOaBucGM+l@ zMo%dmK=1F?zf%ea(_4FBXl_?}YA^iD2HC9pbo`<$=|U~`Lm{_|t=0j(8Oo5_9@L+Q z<$VYBrgjOEa zH{(ZB>tp&nrEDl|KBh0TMpMf|{bO{+dxiS{l!9(F?>#htl5X@fUsJl#jN?erithB+ zadffDZnhIAxQ|p%q`L3xbCvRmw3M%<6X_3J(U)hQ)JIvZ0aSDfO|N8pXE4=LqeQG7YB>#nZ9jIOft3YA_)LHJ&x*e`G``HBwW zO101Fnyu}ZdRq*?7bvL$QN(>>3;aqSiC-`yDeVec*y53N?Fvk<7-<`GRqt+9u8g8r zu3_j-q=f7G8Rg2O)aYw{D|$}h*QmPtiPYg6jDP8)=)yM`M$!`L*&9eg)&v^(Ep9B) zwu*1{@7R{+E)H`fhtq+~5$tNTJfJ_)&LkljcpE4rsn~ev;PF zmh0u&z+LfKPP=Nuc>mYPr;g`HrH2m#<~? z(rQmX+WD-fH_a=?zpkZvdRxorPJt&z3^r9}p*e?sU;W#$FV&W~{bv#>yf7<`5al!0ii)zVPsk{~(?C`dH z?dmVQ&CEOWSIGJq4t=Yorliw3LWk}PvhG;+r{2pw{XAm%pX--;c2ylI95RLL z<}}Y>+sjKmCtK^MBAuKOgfahu@&82fUhdi1I+e|ZDmc=*eLIxawJ=W)|EW;7S`zKL z_Wu{qE6Y8*SvOHxClu8t+nwc}9apxrHt!qXd(^0bqb3X=9Bf2}TdZNiqu5&#_4R9EZD+ev z&ue@w+st6EfI9yt5fUP7WSbG`^`!OxF23c*I(or*!}-9~f~yTz2hJC+uI*UIdhb;H zpQMKi{AsK0ow|Ol{tpX)p6}B%c=^wMesKP9_2C-8HG~U*YXsLAt_fVA?PtHHArb$F zrGW#25Id3x7X;S~E*LHZE)=dgTo_ynxR$o(`?OmArE=qQ@(D89D885Jksu?&d&n1x zh4-SzY*?zhDZBxXot9Q`iY5C?S{G!5D`ge*UXalqQ?KbxkkL)qaf@0vGny*;Z5r6j zXzdaF6Lu1%kYK})Ry8x~Dp7Z6Q!}HLcgoM$;1s4YVVmCH6z*r5ZeyCxt)!ou8Euu) zyA%{`v{3H~u zAqZct()mf+8uP2=kfqmSE{$~FaZ)y{21S@GiG&B_9vTD)XP$NvqsZDvI z2*0-uod|{9QeXNe)G(BYdQ_`9?5y^q@y(5fG`zV{OWEbm5T=yYr|jlNE9@UY?=**U zQ~-U>*VIO24TG_a#$<#U&6MmWG%(C)6?!<(%@T!jcpq8EtXs$AOn{}iSs1sQ(mD=T z8bn8+?|rSA8#ZFW!D}eDf`agdX1Rr%syBnFb_r4!f4@>-P~>(s@TflfV;i= z!c5)6VYH@&(NZaGL5Er(FZWy0^%h9JVUX4m*TisY+Y)6_(3(cJMBWd#p#?3Gjgkl| zXlaBfhuhMrmPUJ@{B~}ZYp`g>v3W{(Kz)FDD^@Iv+Pj%ELOH2V<%Wk){v<|ek6_T9LkqTR(Dk3}K%a_qw367!$2BNzkMX`nv>0Q~`X=?4u;X!=s zw6uj&EH}HjS#IE8W(xLA4R1nc4Z}+*?MjynWaNG{-N&^>Mi0eID3<10QXic+DQ?Pw zCnrzoKMH8Egu-FxuWr;Y96<_u(Ts3ogt9l5j)xnae2RLzS$t6Bo1sNHlfwheGUsOt z#ZuabTC_GIl^gx&vDQWxrMf?@ZEbY$c8{+KLlZZLHE$+PG44aCunmg#;1Ign1~tBID5(+f&l^VVBhX@shEqZWsv>6urAMG@@BqFc0?ADn zMJFPRkft{h-7JTZC@zS}ldvL!|LmPL|55ro0=1kynvAwaJ0;^W8q*f06UWeVZ4qVU zck22aGbHJXK!Q`NtE6WjjVVa(RCFQ7pkU}n+NG`|BX zAUA{Z`C9Z0Rd&E}>|Z8@`j# zh}`R$bh;yQVacMKtXGmn^*b4Dd~%+1!^AL)Wdj`5N^*2%yX~r__&f_+0sZK;PR2XR zj^#8Y3OT;9f@VY+LCUTdXchCWm9#U;2vqV`QArfq$llfTLllx+{UYA=AuIlCse5OX zQ1x0G-`Qxa+aC{S4x!VXVa5L?`i`Y}>&UYUQh56nYSYCC^6(v|SawlCCu1nR+Qk^9 z1ZpqNL% z(QnbXM{uWc-$`p8K|i>*llDJiq;gUNyCD~rcc@o4^s9<@Xm&SahmyR90=grYk$Wk+ zyJ7ek``j#*NZ~7RG@-9YeX}n47lmR8*iSEZM-BrH(2?#a$7=`ai|$C<{ddW$2b#vs zL)57U>h7YA?)Jc~EMSm_pEL#)A9l0chas~n{~6@bL~16O8E~oxva#zZ2aWX3Kjvn+ zZP%q2H-tAbRqZ#v0IW*vi5x_ppsb!Kp@1T~*3-ami=N1a{ysw&CF>Lg#Gn{6im6)+ ziXrg>8Xsdc#^-Wc7=ys>XXvdM1ipEOF2o>9CHM{>V{}mVen^qMP<)t5KCu_{7M-J< zUdYn5kLbN#JhGps?|UJuyFMo0SY(~wCB#BL<`bF~i};g1r59sSG-VfQH^yWo>=Kp7 zA|04d{U=}denEk~(d;X}q~5*JNmo?R_}<6j1f<;G1n zO9B4%0$kdhdDxYT|C++#5#iX$UCU;UnrbnDf*Fy z^+oC`Zc}<+#6I&5z1kPGw)$uKkgq!`>G!@!^~Jl?I1Z&!@hc68Gh&sZDtaLfV@T9J zIv$5oN&1~`#vwN=s#(DfB0RUFB<1UD5_H*Q53WjF4b|e|Jlu-HK(-Jo`q7NQA{c zen-})G}bO_KzRdrRB1>j2B3+=Hlmx%d5x(~JmlA!P}g`=Wnfd99FMAw2%_cjXc9%u z=&g9e@GcFmiG{|$;mBSHqQTuegdW7B)!YxI<^z#E-!SSw5GImZ(DZ?bBE2QOG!RiH z8+3G_(b{`;l)DAX=XskDy8E`nRD@~D=Mkzq2n{!j*sL5d5x=Z`g(7||I+7ah&!R8j0gRn;bTyl&L?M>T>{b}=HbfSa- z^vPg!o*nUI9b!azR}XZzMA*a7mbbziG=#RrV(-mEhPazgxTd|xI7d&nm+YdUv~CDW zE_)aq9fErD9Z5HaAkDa!*BXlKSKuw#P&8f3Xc{>bdARr(W$@K~ENvQ!;!1vkP7Q^A zRTAAEijwxhopczk6%#3P80=O~qcOu!oPjgwf5Xr`lV;N1VTfnZEc#*??h6;^kjHSu zQ$Cl%hZ}7@vKP2p!YE?65m3v_K}-B!v0&TatlG|QJ$VS*9Xym*DXr5NT5 z;G~luL6-h-xPQDrZX<9XNMA`qM<6d*t7!fRq+-W9+B^b}Rz|M9T(O%0wcFrm0`@21 zF|W|yBT&U@8>sb2G|0398a)!(T(OlFjzkm4ew}uVG`e|T+vaYL*M%@qhr%11W3asy zRct4}QARuOn>*btiKtm@3PJnw!~JN&C}g6?E}8+UQn;I59fh=|?59(sP$FXv(Ctx1 zl+T!h?&c#eLRr>FhX)3K%m?42Lysb=(&KdXQRw>=k>_YM-;1ZI`)D+c=n|SZ8hK2? ziki`|d+lR7G#Zt2vy3kD_4Wn2KiX*Jk@~5-#hoTTW;CKpQ`EZrQ0}G7yh!68Gon0Z ze&!Gc(4NO|?@qhK{!QqsRJBeWuAzHo}_zNam?#+BYgt3`wuS}eS+n>igG|F+m4dJBJWH-81lVskfFR_O|-SW0e@ z#}mdQO2k2meF8D%-loYqqSa5}38dnVyTu>rMzgb+8R80;$Zp zOI}GBX^MWOo=K>#swzZFIZ0T3{%n#_8xxM{#U$h^;&>WQZ75@-} zezcp1We5_9eGlluOKAB2j6>n(c#!vaWaXerQRC4X^EFBuk0BsWr{~7Q^fpi0!T$If zT{a%A+^9>|33v*qtV=-?kgdvkd~Foip+Al^HDj|6F_nHEW=}M0n)jJ9i^MLw?N6H~ zpruDNpppq_*=Y^w-UP%^89+hFh%>e^^-BgPHKAF_7?ckOQhqWzC%&maNXBE+(H7yg zO>_1!JgOOccTi>qQ-_Jj%8C#gI}yRRh0>CV$Vy>zdXxEf7=1hu=EGXjJ@!v(MNKB* zdfT8_zDBmDDU%@2XhW+fq2rZC(0;xqw4?G#7<_WtlgDIaxipd@C&S;TBaNPnb{5}> zGMLk&XcJ%aI#V%U_jaLMlZ{qw%e#75+)?oS8xC&*c(dW5e5ecm+1p4(w1?RQp+S{f z9V4H;tZqI+$tftSs&2G01tVWn4?2{BCYTaKms60anY~Dz0{Mzqip169Vs8&i1Vv6o zv+8+K)ud9l^rdXpjEJM%d`<61p_p?=)3s^%RkdN7(NIZ#%nmz$ zP;1eyR5ZAVG3*neRF9$BsZcL^oVuiP2F6k{UlX3NhuEBo;DJeY_=w@A1O8$-IF9_E zL@G1JQ@1CLmOil)Jj~bH`6yI#DWaM479eawluR!@i5y%^rlU_Hiu{RmgRd!*sP=Ru zC2}(Ln2wxPO{U3wJ)A--r^EK5DYTb4b}D^79pUw9>t_HW)79jL_5k(qrYaNAQPUVX0wct z7Qu7vUFKyZ8gtXJ{Kv6$2W+vohQN6=Wfn}urqkM4{F7-u70p6QV;9hOFrid0AkW!G z5B_vNU^bF;ID?*?4f(cbXf1QnLfSXmXrxpxq*C~|n7PQqY?h8Fo$CcSO8f8__AJ$( z1Jf1HQuG{{+Pj#>&p|HJGHEGahh)*NIk=rAJV)2&7`>ISCDc3(Z!Io9Z?BM7Vac2^ z&L-{kQIJg&(@>seOKD}A5kbixw{f=>rWvtX<|ml%#EN{E;3pQI|70TA7yk(B=wy}~ z60^J%Q{IF=%Xtc%V3v2m3^~Cp=NWT?Adw+27-FH$_C&6qWVuF)d9wjl$`y{){<0WP}?`nz*{_F!4_CU?7@n8ksF4dGf6v`!L zId8Wr%c~`3d2Q@aD$98nQ^73f9Zm&v21+JnIz3pSc&d|G;iAMW=j~5%!Jj<`JQH6q z%hyZH;rUc1Skz%%y+vwWe%Y#>WwmhYFC<$PusF8H%oF`r*3 znB|$gP(XOFfp&A9%nDHwvwW(=Ea!78aKWEF0zST2Fw6PSNWmPQmy`>JJk!EQ1q%;W zFc&i8*|iC9d)w60>}|#I?Bp@$u-m;Ll!!d~~{Cjv!ECHZVwHmh);7q0jP#60@B5 zl#u1Cvz?sD3OSMo8^~MgRA4!;Rh13gkeKDX)K!-AvRJ_^=LN)q%?vm>(|qVmbb6T2 z1L|^T05-r2Uu6TlP*yO@c`2!2j)0e)3T8Pk;}*C zg4qBs`xne|-Y!5e%Xw=7!7S&E9R#zS_ku7v0Cmm^ykUf_kVH+NH=1Sg4i&$Z>LZ4YNE?Vh*2xWk$H* z&z?YDb|lz*Ixmzw*uY7N*+BGqX8@MRNX+s}60@AwBH@BRdvE_!VwNjd6lIDbH=oWw zkvvQT5_1F#H#h^Z9LMR_7+`s>#4OK~nB_$hvm9sXitzTQ^IJ|2v#nN2%m(;;M_lk{ zFG8HNTEi?KDKSUD=P$ChC;>j3Q83G+YS{5~&TE`yg+Pfpg4PnV0iInd^jXduCkbXb zPf8Wca^9IqFv}AJi>GrwwOCf*6PX3G0Y2qiFdN_l$py1~bb*suo-8rT%Oqxbxq}Ca zA`0E&YJktChaUdyjVODoli9#Fi8+E>^!IWMCpp_))h~fWFlbGd=_qfUpiOu1p&wf`090lQ0 zkiG|;%n1yXm?Ic}&{duxu_=GoRnChd5e$E*D8AXd+ngR80dMuiVo{U44VYk-^B!x0 zIRf65O)$$7BxZSr#4OK}*c?t0kGL90mY5A3m6#0_Nz8J*>vl?O~eh6^_BOKkQI z-ZWWO;6056a|FB%vS2pATbB!FIqz{UnB}}zzhIX0#^Hil&ihOYHhTx}Dla@(fzOE$ z%m(;$3BfGqE%^nroOg>C%yQn`UNFmzD^6xPZy@fF+j|G^E-nJF0`G<{m; z@)U_#KC{YIo-Q%Vt0m@q-j^8iOiQ2NTn)ra%mzM@ma z+}+1%kmb6>ET1be%d;dld-EHT2P^E7m<}T#4KMeF=f1B_-DrXy2h9wF^5Q$m@VFxnB|tb z4~3W53@t^*Cl4Tzr<`mz{&Qffr|F72ChlW25w5s z25w8tawF0;e1ya--z_nR-(SO6$%PqT7HmGb_*J7_pYpdY!4^z?bi;o$?7b<2ku>W`P z=ToOd#P{*96(i{i^fJZED%K-UbOFc9DdxAqd|sCbcN8q%O|kqexF6m{B{~vZ4i@jG zSbi5Q-bFDhUKsr^I_)*^LJ9Iob|Qi>D2SI+9H2Xx&oUJ9VPNrYisci*;$0MTI+%At z5&BEPe0rf^0*iN3tiQtx&t80jnou|n1wMdIa2Z&UB?*sGsc7i_uhdExBaRNUF zM@#%OSiC%AIqBPtu#xe}P7BL1qZLzBYAn767Bf;f#6hr_fx>(aEM}ZAe+w>|M2oi@ z!!pH`IQFl`ovU{@90-7g~A$#ffHacC6474V8{F{^TzZOSWL%axfKf-uyN3)H*h22 zJ%L5SUx&Y#JIH!Au$U{z{2{n5;%)7S_c9o}6a~F$4C`Z`j%B|QKESPB%)a7qwdkLB2Gzqb(gg<%IO3ZG7Ly}c{xtYQ$agyAE5UQSI^)?0 zo(GO_$ajFn#5oRs7@QjK)IV3x($|tBd0c~nm`KL~er5xModNg>K<{AHxdd6R_%YM* z9mecTF?);smt%P2*;-ID_42{x5+493O2gVGU@X)$Pf7kcc#QOH^#^#Y#6egz$(xl4d$Hj05>EjqOT0V)RWM2N*aZdb zRkr4BJUmVvK*w>-6tl%RL8Xn*RGxH3a0MJO!^u@(F}aKNwZ`~3G21B*0q3MSxfj@H zqmze$Yk>_%6L_LAN+?QFNQXjaF#5jPMpl9QNb+6azLNYLI6;zM1CIbNa)kdCTq?{Cw*ar%o!MP5F$G|0$JPrIIIK?4f4i-}jxJ2FrkISc+cTloo z78?5x3`84Fcg8aXoHgIcOTbGcCUA-LczgtWR^rdV=QEt)Z-RM?J|xTRtPcWFvb;&3 z@Ce1C+GvTpfW<5}PT**8|AkKdG_aVG!1ASFF#~~l19;G8r~W(OWQk8U#l3wZJTUs0 zRrwhd(j|o-!1KYPD*ghCDGVGzogf%2a7NG^JQ1Acu-6$}F3AUiFM|g;g|3 z2xdW{16cIlEO3k@e+AqNJkw!d2Y9C>KMsByEE4bu_^c%V9()cgYVgk~@DQ^txQKj0 zEtYW1zNmIY5C{(5>r7xD3*rud4(;Z!_jy^pUt z;+drh_?F`<56dILKY|xK^4S+GzS6M#3GmVf&hSrx#YYyFKM&quvFaEd&2o4-3{7c2 zJiumC+6ILKU~~yn;Q)A@;~NDVC$Pn@|v+pID(79D=Ij4Gg#sTm|2d+VJ1tYR5+q*7q{-nCJND!5jz{A32y?gT+S; z=7E{;(Cav>CJ8J)TChSoSbU^lUJn)@C75@C#U}~o<6!X#g85T$ej}&-TdePRLC^Bc zYIy9BJbc3O)Z=(V&k7-6@kXAxCs@2-XMP+kUZ^wA1&bHx%*(*yeL3?Muy{WX?rJ#% zkE~|S6qbO+n{f{CHCVg}XZ{mw< zjim@IKBlt#EAU&2RiEleKs8u=EM>WOTRe}UF``Dy@PT0Qt(4^*!Ouc2x?BIYQO=K{ ztnerlod9av@ zz;Xh|{_d2&4Hi=oSpGivwj{sQ9{oPfF%^Loet<%{#P`8ssshV>BQ2IU{%}SR4Bjts zG`LLS{@@kTNIDiQJ{PmSg&y$0X7am_8EZyflNxDQ2aDx8c#@+kBEe$D00$fjzKjtq z*&$B_`+7JV>C@mI-n6FBxRV(z--9|@ERTT2Q2ZHKd?#nSKY@2iH(R9>BJg(FZ2%UZ zlUct5SbRQa9tlo#e7a;#?SwvqE%_h3hYX4pt1M`PHjC2M5ue$}yMr4?I!iVY%;yR~ zZ1%dzV6mc=!#@jNq0*J(#_YOcB`f>?4F4fC?u0QsQ>;H_?_r(s+}hb`ZX#GrAZK|R zSj_ikUcpRG{XFoZ15Vxv7Bfm&|2SC8AZ0$+8L8f;Q@bL(=@1KLS<| zH;&`ToWI{U=1danp*T$KXgqY!bjH~VES4*=JPs^YA2Ck=i`7QVi<$GC;a7k==hOL< z#+7=Dq@U^w9zmVIKF4VVyO-D%V4pz zhIt>jQhEd~1m6XVCqo<#O>Y+)BkCD=qk~d38<=-@R73}={ef{@@!3Y_KQLnI8J(

PXOOqg?|rX`B6F%yKQm5?rOyq|-*X&_&X(BbHsvv;-HJjo8h61fCg1 z$6=$Mn9(h4q-W6s_7^j`g@4u(iaBGnt1D(`3;$qx_KeYMq?p*v-oN(5J^Qw^+^jL^ zBR@I04)_JIxG{0^7Cn!LeO&qT8$Y3E?y;x$j zuP3I33$^T3biM?+@O3OyVt-37UbsZHKQzu`xV8VeTkihTELIS{T7i3lOB*&kt<4nM1uvn$S z2EP6Odb{)ZD2lxC<2{*72+9=>35Sp%M`nf~0RjnfLj>ejP*6ES2oM3~NLD~`U^$d? zLBIwT1d&xd(cL)Ug2Eyq0!xCpa)^L(E}}$1VHJ2j)m@b?>iNB1&ws!9LwSGe+tpRo z)yE{=9ju;85x#^MY3I+Fj+XToT-kE>&B|DPME$89z4bdi&LSbUy0^k1I8pOt+*I=t z+(Gl3xWDG@c$nrRIA8OR5dxdEKzt|8SDKUY3C(xoq#9lWJK`X@lk2z&=2xJl<<;;q&DHS=%{8$4 zi0zzixVKn7xwI1zYXSkj*O&g@;CXz|ORx&@S6cbMan*XI6<8PXiMu@e`674{kERu3 z*sJ57^}X^`ysXrtILi>=>tyNKwHH38c^E#A@0S%$z^xm4`O`7qaY~n8iEqdKWxg2p z`u4?rDYYUSDdOFUrGr_B*I==%82pd1`iQ~%x8V!8anM`UuQ)E`*_XwIgXY`tH=ZL_ z4Fbc%-U5yA8=5om2CS}nyJPhc4azqBCoKNNx5yDkfw}k!u7t(lzlhb-dwwh8v)(08 zb^(7eQYLJ}b+D@7Aa1PrI98AMi52{a)zf^!{1sHI%OY?2gnPO6&@2Xj8FQYWJ2T^F z?@y`X%=ovpjc^x>sE_Dl8^iYtYnO4N%8gW+L|B{wvW@&_4Zn%in;B?w#QKDQdH_cB z;V4!&OAG%8kGSOZ$=8)5VTotafFc?&SvH^|6Y)coBD5;pM-M)$@Cz1OLFYS9-HxA6C!r`BO;vhJbotPb}~w zR?p`Niyn5f+ZMCSh~v{HZEM{mReeNf>vU6+Cr+%MH&s=QU1%kJ6XR~J`;GkZh8N)z zZA$wVu~ri}NkCmNy^UvSgYgeM8*@G34Cd$f?N3T8u+HEUntk2rtLAz*Wt*4Z0cVuD zkQRxr%VPr@xf_1qG_TxxdPUIfG+8dW_UitFt1{3LFwc@AEo z`9(bJb1(lbyjb(6c;ara{2N^13u*D3%Z~(Fr~tl!M`}*!#lBkPRlslKtu30Jt@)~z z)VPehFJ@BS|8-@OB%vx;|B;r+A9UfEg9ope918>oeX5H~t{2=QShophH z@^<;k7qP-|1ga4DgL8yP;1~JU5N(?-!b7pT!gvusrT$Y2|zH3)%>t z!Zr8ESH6e_{7Rq}L#Qf<>&GRAHl)?@a(qLspdnU|B#PxT@Jfc99}GAh=!U=1Ho+h~ zZ=bhG@-TnL`I$p0H6v5`H&>5I^qrbwtQlB+#Mb$zVLunGXY{RsZ)k3gn`m33D}GS( zP(0pq#F|Lpc`sl+i`7RoV2|O753t8Zz0M@#8TeBc5?e0~ciH5XcfnbhlcrNX052#l z=O8$Wz(N9_%Y-MfdKg%Y?joGM+57d$I=m5!MvC%1SUnsp{5{@Ic?VhFH5~hqm!H68 zd;mMANO2HsM4+dZ&=vQ>s)Ags9u5{OD8Nf7Unb}4OspOb7UeJF>07)NZpJG#7vT@3 zLt=rm1deD4SMgEYL9U?80DdC$vHkIpl$zPe{JTE$Kg&`lV(eDt) zANdg-4dO#2^ktCM3WVJh?meRXytJ6t_h50K`9UpTyYJk(m-3*z4_)N{Wo%MR4Wu#D;!OEL|RlZ>6QvgZqCHwR)6^_$)PxfZQ zyT$_BuzFBgG@!^R{|?ta>-G3&qug}tKsmzdWM3MPLtafKNH@ZZwH27tAg)ZbK>w@lXCSD6FL=(hhttQNPfgQis?_w++!@z z!|)Is&mL3Gt-x7c*j;^u&F5r0*I3|X+=*vD7HBIFRx5bZ$lr<& zQ7%qDY6OH;{vIR$Tl}3Y_luM54@QFN8%BA8xG0k!F{BL)x5J~gW5E4J`ADoD?RO4B z(+GTa-kU(n@m|gEVD+fK=;1D`KB57K4PP*P1FKg7h~_QzVIS^zf;b^LImEG0kMRzxq^RDE>;jH z%gtTtf7u>%Dy44nk1VD>q91XOD!F@pqP_A|%3bC2dBSNJCE^EdiS}-m^fk86^S?-2 zV*%5>jq?A?qm2A1n7`YR+t9^=5N!niH@5Fixs;w{+Bu`qL;^AG#O0Y4-pB zuemt>zgB4WFpD1Ct8MT+!wU_+Z}=u@^yGI@TpSb1D3>4mn=h6TXsEiNdB^XAWz;`mxSSDQd5}fjc9Dc{(F5tL6-ibwzMTKe7 z&~ba5EITC1AH;3tCacT{jlk_4N8AOTB+ywUu)re2>kNNnxXAD+!#53AA0gMr`kfXx zQ32`BhKCq_((qEl?;8Hh@VC-p{Z0dZF%sf)Zyk}khSLrA#aU_u8RFr%t1=@x)$mf+ z?#qwGHhRxU_}uVG!+#jQW8|$XOvl}|26Qm|fa8dJN)!#qCeTM);0ePs@dH}F0L<~ILfl#$Cacz;GI}}QxN%maI)V$ z(+KmXW-ExrepU}ZhC5^EcnXf_frUoG8pD4#yvy*{hJP|#X7sHMs5_edUvEGwBcYGs zQHCRiZNu*w{@Cz=(RR(BxZC}z5igr}YeQ=q4jXQ5xVz!OhR5IPh&A)pfc1jm4TgCv z>Xw1qZ}^Pin}%yVrZ4a3u0cEV5*O0_Zi(}Q9>WFp6w)FqjqnD;n+@+aeBAI=!?%yo zo9DBFw>n~F-WssF8y;jh&+s(Ew&6Doe}0R(Tt0bAfT#Hk`^VnegKCBw8E%EML*_?Bg=Yw?BA|{&SMWPpg|XvYcaarT!tbkcmQTbb$}}KFH{}`9{Eo_L zz`gj2o6ki934IB)k8`gyMUO}0j>?qJz@0U}h_mo*vclJKA6!oQZ+I{kLn!M1Od2{q zQfhJ0K*FyCa^(W`aNOgr#R9^03}@hRkQHpl-SOD6ZuvgEwHiH^`N#1-?h|Yx^Dp2)b@vG> zQD4jxmQ@3@{oM*`5=bMU=0Fg>3<*qnY!OyrYo-UUUjJK>ob=;@eL=UUu0$fin z-xROHk4d-2W$JR#poX+BfsS>(3P#`oxQ$$33SNRcNiW1-YF>k@CArU6iw1mzv#_(< z;m>d(zC$j55En-Xs3AN<;4~IL7ZerT#J*(9c~(le@&raeb7R~O$IAS+cmQ_x3iA8m zT+QMStQBaUf+MrFz(NAm>hU`?Ii#=RUiG~me~6c3b(OLkCpWO-x5x$@!1pw?;)~QI z#8*<>``1MWe!{6iEB=VgzdC`7hB6^<$bA#}6)OIxOo+$F@EqxCI4A5rqa-R!#_!|C zvb-@qi5E+E!800ji=N*d(f+trQ!9RrEFUwG{ckIQ(Xz#pNeDKx;$M?qjEkFF&SNNI zg)iY=Exb+gS3ChvmKA=0uV8*4;cUVk_yO)@?;?E=uf(&YzmE`T(9+vxzvFbxRVFcs zG>7p3&7EhAC#MH30~fgO(gwSyt%#GA#v%v1^)w2b;>#a7ZXVD$g@x}ZVON0nVqfp zd|5#WzShN?BfbKj9J<%5@J>7px0DTRk2h=OkKnCZ`80e@l}BjNQUbpdP?KgY9@N!a z!FK$J=2LjE=GZ@RXM^TOI9qd9oTK?MoGTp>Lo$!RC;~~c2R5FI)o%4V-ip;6Da3i* z+^6luCio05!L8*89>&G@S@Gv&eP_h-J*@cWrGLZydOF{RBF@(r-;)d}f!Ab072Keg zcdW06xhcqb#fMm73tWsF%KR)G=?cNSC!XO{;JO&E#4Tn15&RYIAoI`SWL|O6TbBQV3vfGi{x8E3 zWHW&znNSlS#!pM%jR$bonkw&!r(s6iX;2Q1V6~e*iRWUq!uj}Xtj;y-@M+BX#~p!B z2n4w8P5B$#0ILOl!_9FgnIAue9^l8MYvAKpH8>SN(%(DVb;c9$0-65+zTThn|3DcS zNnpSLD}J8zRD2viEWHS4K4`^%!8Q<^Y%TV4A6{iyz8zQ7{2gwDN6Kyf6J9vPJNDni z=|dw{d{bFLwW;hDL%kk1#*;L6z%#Jg#t+~qRts9y+o}qaq-i+Us`ETM;kFy)f+;fPqF`{PxJy+nLXoh3)$jEcr8}5yggp0c_3boUy%9F;6anT)AeG!9joKY zdR&k%9>$ZC{%Q8V83o=7j*u`DzaSGX;u=p{&aYm@r1MQ<$gyfrGTwt@W&S;Q|75QL zJ#qRJFMk+rrTNbh0+|GUls#C6v!;3re1N-Z{sMQ$f0p@Y@jl!}I_4Q(gz}U(>1yDP zSRA-S2g0~J7PmbMN7@qzK2v%=wtC@J_&+jX2;Mov+wUjgvVZngFdw(o{5qb1*T@xa z#dps1^1s6UaL6s^juHYh2&fANe!pw&!1ZMXx8t)oMY=XlnB^U4n&Bl_ee>yx*U$F8 zi1f!7HD}}WIchKC{6CJs00JM#6->e9pY?urHxIYP|CQU=#{K5HcP@${d=0O}BjoZQ z;J`fhNq zXX3gGyaQPeoQl<6)gO<;Yv@o!v@n}MwME_v$Kfno$8smhbexB4N-xH<@omzt;wy`} zw@zMWzlD1(b8prY^%vrmc$3Wk7!O#^_XO7O%)&hc8oc0bg5&rY{#7n;McDRsEB_1{ zxPn8m+$0t7%9Y+6sfG7p)qyZB!L?<5t#Q{?VuToK(ZU`C1`tr^|3`2hep4>+IKFeW zH>6W=8df9lJnpFZRooA& zP*1k7(k$M6q9xpg-_gq3!)CMpohP7< z-T5Sx?BwhxC(T^^%V*vuS&gq@RpE!Y?k=wbdvO{bAy;@9uf!SB7jQA|ChecY{#WC3 zFHn09U!AbJCJf^xnmgg`c&zFXPTj3eCfufjJ7cxY$KWwIUgkfIC*g+D&qoNXB=9F0 zSdS}y;UyH}bgX9e4*URCo8(J83abX6!ZvOx>-!z=!>Y#>p5;)##~aZ|T>=FJlH>x- zaq(X7n@>A@466f4FFc>S(5J_^2a-qd?L}VsV|X*B*g3F0g}353=|y-q{=#*{T1Q}I zu{UIecsrgh7x*V$b%4{YoD+xf`7gcw`W!BQ(DQ$B8a^cRydgSVHR#<{}GKW8^7A#mkKZ`R+$bNNF#Tp~H;<>s@%C2vTR@i;t0mh)z6 zYY*|w&w2&3#;N4gqSn~08tj=C@arG#Em*ZnyxeIWh=exf<~!)r{hD{=n}Yv_)d>9s7voKG1ux;b z|Mf1*-@ysIUZ$Dcq#xnIalXfPcW(qiSXcBIZ)h3*YBZCO2W3x?QC{}Y| z9bSqPWd$GLcW_VXo!G~VZ`3ya8n?yj>-b5064#dv`Y$e9&gcEiXc7D03<7G>q%L9w z_&&LUp7eu{E?9+GQTq} z!4FG66d}-q_tl+{feAR3*VR2QJqz!|>K76(;Boxbkw0YldpM8R)s2uV+=`3&qa$C) z@&kAk?=({#I*YS-g_*iSiu^)g1A&j^0)fTMO5SO9hpaFWFXWGi^pxf=*jgq0Q4lp} zdgAL?&5;~@Cx6pJl^5V3t|aSUgxg|yXpdNH3C!S~W@^&BkCT(UA>NI5;%8(9-{Hah zHIHwlOK>)SoI~}f%o0wwc)BdFjR(soaKt7IN;?e{uO7IYK#odaH*6#ACitvQIFEAW zZukk!y>WqBo)tVSJzO+^`iA1eTKQOMXGF#C|0fa%^8A2WU@D%ES>CB&jm7OVukCZoohh+79L8uvx)FWc#6z-&i}h)AcZ4^s9>L{Kt94FhU}R1WZ9t8 zc&%1`MOu|#$NrG)0C%J$Fq>;AQ(qlvM!^03e|-YulYDzUx`*!g1_tltv%RmLn8FaC6Q6X8lY35zud z*TLdVOX5%}oPv95ZiUBd?t+(T?u9pLeh`0yBdWro1S}pfP@aJ6Yo3C;X`X?{Vlk;i zgO=fpbazBV58uE8HE+dyl470w7;8Tkk3x1BhLaeX_=9<4Wzcucuxg&lQlkVhq z#ltY2a@-S-*YbPgd>$rAQau_(V3t;H+ReK7=bvFU3D- z%df+iusHvV4i(}^xmYWystoKU&=hA#e}y;V6vuw+C_be5B(?&)^GcSV#RKs$>C1SN zX5Vr)VVsrJO_rBg&iD`00_90~LvvMp33rhT)WR*wc&>*hYYyTqST!I6*N*qx6+f-{ z!R73K-)Mnc655pY7Rbjh<0RRDr|=fsL3$qMm;XtJq-{KFs#pFJ{uCE6?Gs}B);he5 zIj5F?BSPRH0e8s#)_b_zbTw)GRutF9RpknH;HJ2o^j_QstL4RO$MW%OOe(R$uP9Ia zv$w)ycpz4rG;)f-bS>c=-iFiV3NGQR+5(qx(o8EUS(g8SyI@tJIFFCT?yUD)3HWKe zQ8uVHE}B!?porCoK&5A`q!x0BLb%KP(gZ6F&%#yY3R_|us|L2kd$DRj7tE`NlH-l&y7jk&f@N|gD};&V7b z+QwYEC$VLmP4Y6%;LS762t}yyuLQags4o-V!s^vDVuhPT`C=={at=g(Yp3w@INq)B zpzw>HzZZU$ITCQof5GZ`sRYY!#oEld4dnBQzE(3B)4}faaIj|d+lPZM+!2jT2o6q( z{<<>wUFGP1-VU}5MC*PKd@t6YnK|5EyEn8yx+WS-3ixvEq7Q>b(Is1hjROAMrX%fs zS>gTBc{_q>ftZX;d(GZZadgq{V2yw;)9!aOSR9?QKUg#1PtVSEYsviz#w_t2Ea5;E9)}Ni;(y7(W>+|1W!2aa7U~4ZqN^FNedU<;| z?^s@;m{2uTEt-=M3i|x%!!w+k-FDQi8Y&Z=R3)@H;LpfzR$6-%`$+Xro6@#b zwtuY{PO#TB3RQ`&tQk5L8L$Sg=kR+7W1{T`(%ZS-PH_jLT#P9hMs3`hLN(2dxbR_=gCscRYS%t&+V zaH?*d8*1m}+m}X#VxtE}g?^*4nIp9A@X8pyKlYljq4;Q<$3wrw#Ut^ht?tn&nE)4ynUd+gJr)SZ_8$;b*Q-V(z8Oz4fUJp)kqp z_0CkBToOtO#AN2!eY4oJ^L`86@Y_SKhdSHas)RS$Ie&zL97|*_@zyMwo#9sem_N*V zT4c!XPA(gckBu(g8LI7zVdFYSif49-`X*KkceF1R2LEmsR0xOt&4#yhIv*w8jLpt)j>vUOXV(g+!j^L2W+jL3qt7GLqQwov_2c+guG@@Vso_o>n_9VRJlZ_m zon&yK!#|*f#}o`;R$79S~Pd2V|2^o;iOpq z_`DHz#|yzrcG09T<2houd(hgGAC8HQ{`;9wJ)b|fh1@;9m>#Ma8{IcKT%RLZ+DLaS zc1#r`)v_r^XK~=(H9gD`cX*CFiK5Xt;UsZjlG}g70x^#1t>h?gdOkdy#>z#1SP}l+ zZ=YNp?&|h&zI9w~xvwV=3Kc*J5uJNzg c_ZNp7#w>Wvp346dKiw7sick_cali.sick_dis[i]=can->sickfed.raw_dis[i] / 10; //没使用原值 // } c->sick_cali.sick_dis[0]=(fp32)(can->sickfed.raw_dis[0]) ; - c->sick_cali.sick_dis[1]=(fp32)(can->sickfed.raw_dis[1]+26) ; //有点误差,手动补偿 + c->sick_cali.sick_dis[1]=(fp32)(can->sickfed.raw_dis[1]+30) ; //有点误差,手动补偿 c->sick_cali.sick_dis[2]=(fp32)(can->sickfed.raw_dis[2] ); -// c->vofa_send[7] =c->sick_cali.sick_dis[0]-c->sick_cali.sick_dis[1]; -// c->vofa_send[6] = c->sick_cali.sick_dis[0]; -// c->vofa_send[5] =c->sick_cali.sick_dis[1]; -// c->vofa_send[4] =c->sick_cali.sick_dis[2]; + c->vofa_send[7] =c->sick_cali.sick_dis[1]-c->sick_cali.sick_dis[2]; + c->vofa_send[6] = c->sick_cali.sick_dis[0]; + c->vofa_send[5] =c->sick_cali.sick_dis[1]; + c->vofa_send[4] =c->sick_cali.sick_dis[2]; return CHASSIS_OK; } @@ -63,13 +62,14 @@ int8_t Chassis_init(Chassis_t *c, const Chassis_Param_t *param, float target_fre PID_init(&(c->pid.Chassis_AngleAdjust), PID_POSITION, &(c->param->Chassis_AngleAdjust_param)); LowPassFilter2p_Init(&(c->filled[0]), target_freq, 80.0f); // 角加速度滤波 - LowPassFilter2p_Init(&(c->filled[1]), target_freq, 80.0f); // w滤波 - LowPassFilter2p_Init(&(c->filled[2]), target_freq, 80.0f); // y滤波 + LowPassFilter2p_Init(&(c->filled[1]), target_freq, 50.0f); + LowPassFilter2p_Init(&(c->filled[2]), target_freq, 80.0f); LowPassFilter2p_Init(&(c->filled[3]), target_freq, 80.0f); - LowPassFilter2p_Init(&(c->filled[4]), target_freq, 80.0f); - LowPassFilter2p_Init(&(c->filled[5]), target_freq, 80.0f); - LowPassFilter2p_Init(&(c->filled[6]), target_freq, 80.0f); - LowPassFilter2p_Init(&(c->filled[7]), target_freq, 80.0f); + + KalmanCreate(&c->extKalman[0],10,1); + KalmanCreate(&c->extKalman[1],10,1); + KalmanCreate(&c->extKalman[2],10,1); + c->sick_cali .sickparam=c->param ->sickparam ; @@ -80,7 +80,7 @@ fp32 pian_yaw; 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] = -Nor_Vx + Nor_Vy + Vw+pian_yaw; // 右前 c->hopemotorout.OmniSpeedOut[1] = -Nor_Vx - Nor_Vy + Vw+pian_yaw; // 右后 c->hopemotorout.OmniSpeedOut[2] = Nor_Vx - Nor_Vy + Vw +pian_yaw; // 左后 @@ -102,6 +102,13 @@ int8_t Chassis_Control(Chassis_t *c, CMD_t *ctrl, CAN_Output_t *out) { c->NUC_send.send[0] = 0; c->sick_cali.is_reach = 0; + c->vofa_send[0]= KalmanFilter(&c->extKalman[0] , c->sick_cali.sick_dis[0]); + c->vofa_send[1]= KalmanFilter(&c->extKalman[1] , c->sick_cali.sick_dis[1]); + c->vofa_send[2]= KalmanFilter(&c->extKalman[2] , c->sick_cali.sick_dis[2]); + + + + switch (c->chassis_ctrl.ctrl) { case RCcontrol: switch (c->chassis_ctrl.mode) { @@ -124,11 +131,7 @@ int8_t Chassis_Control(Chassis_t *c, CMD_t *ctrl, CAN_Output_t *out) { sick_calibration(c, ctrl, out); c->NUC_send.send[0] = (c->sick_cali.is_reach == 1) ? 1 : 0; break; - default: - c->move_vec.Vw = 0; - c->move_vec.Vx = 0; - c->move_vec.Vy = 0; - break; + } break; @@ -166,17 +169,27 @@ int8_t Chassis_Control(Chassis_t *c, CMD_t *ctrl, CAN_Output_t *out) { switch (c->chassis_ctrl.mode) { case PB_UP: - case PB_MID: - case PB_DOWN: c->move_vec.Vw = ctrl->Vw * 6000; c->move_vec.Vx = ctrl->Vy * 6000; - c->move_vec.Vy = ctrl->Vx * 6000; + c->move_vec.Vy = ctrl->Vx * 6000; + break ; + case PB_MID: + case PB_DOWN: + c->move_vec.Vw = ctrl->cmd_MID360.posw * 1000; + c->move_vec.Vy = -ctrl->cmd_MID360.posy * 1000; + c->move_vec.Vx = -ctrl->cmd_MID360.posx * 1000; abs_limit_fp(&c->move_vec.Vx, 5000.0f); abs_limit_fp(&c->move_vec.Vy, 5000.0f); abs_limit_fp(&c->move_vec.Vw, 5000.0f); break ; - } + } + break; + case RELAXED: + c->move_vec.Vw = 0; + c->move_vec.Vx = 0; + c->move_vec.Vy = 0; + break ; @@ -188,6 +201,7 @@ int8_t Chassis_Control(Chassis_t *c, CMD_t *ctrl, CAN_Output_t *out) { break; } + // 电机速度限幅 abs_limit_fp(&c->move_vec.Vx, 6000.0f); @@ -227,26 +241,35 @@ int8_t sick_calibration(Chassis_t *c, CMD_t *ctrl, CAN_Output_t *out) if (ctrl == NULL) return CHASSIS_ERR_NULL; fp32 delta_w,delta_x,delta_y; - fp32 sick0 =LowPassFilter2p_Apply( &(c->filled[5]),c->sick_cali.sick_dis[0]) ; - fp32 sick1 =LowPassFilter2p_Apply( &(c->filled[6]), c->sick_cali.sick_dis[1]) ; - fp32 sick2 = LowPassFilter2p_Apply( &(c->filled[7]),c->sick_cali.sick_dis[2] ); + fp32 sick0 = c->sick_cali.sick_dis[0]; + fp32 sick1 = c->sick_cali.sick_dis[1]; + fp32 sick2 = c->sick_cali.sick_dis[2]; + + const sickparam_t *param = &c->sick_cali.sickparam; - - diff_yaw = -(fp32)(sick1 - sick2); - diff_y = -(fp32)(sick1 - c->sick_cali.sickparam.y_set); - diff_x = (fp32)(sick0 - c->sick_cali.sickparam.x_set); + + + diff_yaw =LowPassFilter2p_Apply(&(c->filled[1]), -(fp32)(sick1 +10 - sick2)); + diff_y = LowPassFilter2p_Apply(&(c->filled[2]),-(fp32)(sick1 - c->sick_cali.sickparam.y_set)); + + diff_x = LowPassFilter2p_Apply(&(c->filled[3]),(fp32)(sick0 - c->sick_cali.sickparam.x_set)); delta_w=PID_calc(&c->pid.SickCaliWzOutPID, diff_yaw, 0); delta_x=PID_calc(&c->pid.SickCaliVxOutPID, diff_x, 0); delta_y=PID_calc(&c->pid.SickCaliVyOutPID, diff_y,0); - if(fabs(diff_yaw)>5){ + if(fabs(diff_yaw)>param->w_error){ + c->move_vec.Vw=PID_calc(&c->pid.SickCaliWzInPID,-delta_w,0); -// c->move_vec.Vw=delta_w; -// c->move_vec.Vx=PID_calc(&c->pid.SickCaliVxInPID,delta_x,0); -// c->move_vec.Vx=PID_calc(&c->pid.SickCaliVyInPID,delta_y,0); } - +// if(fabs(diff_y)>param->xy_error){ +// +// c->move_vec.Vy=PID_calc(&c->pid.SickCaliVyInPID,delta_y,0); +// } +// if(fabs(diff_x)>param->xy_error){ +// +// c->move_vec.Vx=PID_calc(&c->pid.SickCaliVxInPID,-delta_x,0); +// } static uint16_t reach_cnt = 0; diff --git a/User/Module/Chassis.h b/User/Module/Chassis.h index b2e31af..90930c5 100644 --- a/User/Module/Chassis.h +++ b/User/Module/Chassis.h @@ -31,6 +31,7 @@ #include "can_use.h" #include "cmd.h" #include "filter.h" +#include "kalman.h" #define CHASSIS_OK (0) #define CHASSIS_ERR (-1) @@ -172,11 +173,13 @@ typedef struct{ }pid; fp32 vofa_send[8]; - + /*卡尔曼滤波*/ + extKalman_t extKalman[3]; LowPassFilter2p_t filled[8]; /* 输出滤波器滤波器数组 */ + struct { - int32_t sick_dis[4]; //获取到的sick激光值 + fp32 sick_dis[4]; //获取到的sick激光值 sickparam_t sickparam; int is_reach; }sick_cali; diff --git a/User/Module/config.c b/User/Module/config.c index 0ddc597..91ea5a6 100644 --- a/User/Module/config.c +++ b/User/Module/config.c @@ -133,48 +133,99 @@ static const ConfigParam_t param ={ }, +// .SickCali_WInparam = { +// .p = 3.0f, +// .i = 0.000f, +// .d = 0.0f, +// .i_limit = 500.0f, +// .out_limit = 2000.0f, +// }, +// .SickCali_WOutparam = { +// .p = 2.6f, +// .i = 0.0f, +// .d = 0.0f, +// .i_limit = 0.0f, +// .out_limit = 1000.0f, +// }, +// .SickCali_YInparam = { +// .p = 1.0f, +// .i = 0.0f, +// .d = 0.0f, +// .i_limit = 0.0f, +// .out_limit = 5000.0f, +// }, +// .SickCali_YOutparam = { +// .p = 4.5f, +// .i = 0.0f, +// .d = 0.0f, +// .i_limit = 00.0f, +// .out_limit = 1000.0f, +// }, +// .SickCali_XInparam = { +// .p = 1.0f, +// .i = 0.0f, +// .d = 0.0f, +// .i_limit = 0.0f, +// .out_limit = 5000.0f, +// }, +// .SickCali_XOutparam = { +// .p = 4.5f, +// .i = 0.00f, +// .d = 0.0f, +// .i_limit = 500.0f, +// .out_limit = 2000.0f, +// }, + + + + + + + + .SickCali_WInparam = { .p = 3.0f, - .i = 0.005f, + .i = 0.000f, .d = 0.0f, .i_limit = 500.0f, .out_limit = 2000.0f, }, .SickCali_WOutparam = { - .p = 18.0f, + .p = 2.6f, .i = 0.0f, .d = 0.0f, .i_limit = 0.0f, .out_limit = 1000.0f, }, .SickCali_YInparam = { - .p = 0.0f, + .p = 1.0f, .i = 0.0f, .d = 0.0f, .i_limit = 0.0f, - .out_limit = 0.0f, + .out_limit = 5000.0f, }, .SickCali_YOutparam = { - .p = 2.9f, - .i = 0.005f, + .p = 4.5f, + .i = 0.0f, .d = 0.0f, - .i_limit = 500.0f, + .i_limit = 00.0f, .out_limit = 1000.0f, }, .SickCali_XInparam = { - .p = 0.0f, + .p = 1.0f, .i = 0.0f, .d = 0.0f, .i_limit = 0.0f, - .out_limit = 0.0f, + .out_limit = 5000.0f, }, .SickCali_XOutparam = { - .p = 2.9f, - .i = 0.0065f, + .p = 4.5f, + .i = 0.00f, .d = 0.0f, .i_limit = 500.0f, - .out_limit = 3000.0f, + .out_limit = 2000.0f, }, + .Chassis_AngleAdjust_param={ .p = 10.0f, .i = 0.0f, @@ -184,10 +235,10 @@ static const ConfigParam_t param ={ }, .sickparam={ - .w_error=5, - .xy_error=5, - .x_set=600, - .y_set=100, + .w_error=2, + .xy_error=3, + .x_set=10000, + .y_set=2000, }, diff --git a/User/Module/up.c b/User/Module/up.c index 922e03a..f514f97 100644 --- a/User/Module/up.c +++ b/User/Module/up.c @@ -246,6 +246,8 @@ int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c) // target->go_shoot= pitch_cfg . target->Pitch_angle = 58; target->go_shoot = -190.0f; + //失控下,最好切手动,手动用pitch + pitch_cfg ->go_release_pos=-190; // target->Pitch_angle = 58; @@ -287,8 +289,8 @@ int8_t Pitch_Launch_Sequence(UP_t *u, LaunchContext_t *LaunchContext,fp32 StartP if( u->motorfeedback .DJmotor_feedback [4].total_angle>-1){ //当2006的总角度小于1,可以认为已经勾上,误差为1 u->motor_target.go_pull_speed=LaunchContext->LaunchCfg.go_down_speed; u->motor_target.go_shoot = EndPos ; - if(is_reached(u->motorfeedback.go_data.Pos,EndPos,1.0f)) - LaunchContext->LaunchState = Launch_SHOOT_WAIT; +// if(is_reached(u->motorfeedback.go_data.Pos,EndPos,1.0f)) +// LaunchContext->LaunchState = Launch_SHOOT_WAIT; } break; case Launch_SHOOT_WAIT: @@ -352,12 +354,10 @@ int8_t Pass_Process(UP_t *u,CAN_Output_t *out,CMD_t *c) Pass_Sequence_Check(u,c); - if(c->pos) // - { + PassCfg ->go_release_pos = - CurveChange(LowPassFilter2p_Apply(&u->filled[0],c->pos),3,4,&u->PassContext.Curve); + CurveChange(LowPassFilter2p_Apply(&u->filled[0],c->pos)+0.15,3,4,&u->PassContext.Curve); - } switch (*state) { //遥控器按键进行状态切换 case PASS_STOP: @@ -367,13 +367,13 @@ int8_t Pass_Process(UP_t *u,CAN_Output_t *out,CMD_t *c) break; case PASS_PREPARE: target->go_pull_speed=PassCfg->go_up_speed; - + Pitch_Launch_Sequence(u,LaunchContext,u->motorfeedback.go_data.Pos,PassCfg->go_wait,out); break; case PASS_START: - if(LaunchContext->LaunchState == Launch_SHOOT_WAIT){ + if(LaunchContext->LaunchState == Launch_TRIGGER){ target->go_pull_speed=PassCfg->go_down_speed; target->go_shoot = PassCfg->go_release_pos ; }