From e2bc674c7db5a23be5a29ff2990a715187a9bcd0 Mon Sep 17 00:00:00 2001 From: ZHAISHUI04 <3150778793@qq.com> Date: Tue, 22 Apr 2025 22:49:28 +0800 Subject: [PATCH] =?UTF-8?q?=E4=BF=AE=E6=94=B9=E6=95=B4=E4=BD=93=EF=BC=8C?= =?UTF-8?q?=E6=97=A0=E6=8A=A5=E9=94=99?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- MDK-ARM/R2.uvoptx | 177 +++++++++++++++------- MDK-ARM/R2.uvprojx | 15 ++ MDK-ARM/R2/R2.axf | Bin 2753628 -> 0 bytes User/Module/Chassis.c | 37 ++--- User/Module/Chassis.h | 4 +- User/Module/config.c | 173 +++++++++++----------- User/Module/config.h | 10 +- User/Module/up.c | 253 ++++++++++++++++++++++++++++++++ User/Module/up.h | 233 +++++++++++++++++++++++++++++ User/bsp/bsp_usart.c | 11 +- User/bsp/bsp_usart.h | 2 +- User/device/GO_M8010_6_Driver.c | 108 ++++++++++++++ User/device/GO_M8010_6_Driver.h | 116 +++++++++++++++ User/device/can_use.c | 139 ++++++++++++------ User/device/can_use.h | 36 +++-- User/device/cmd.c | 173 +++++++++------------- User/device/cmd.h | 223 +++++++++++----------------- User/device/dr16.c | 6 +- User/device/dr16.h | 6 +- User/device/motor_control.c | 244 +----------------------------- User/device/motor_control.h | 62 ++------ User/device/vofa.c | 8 +- User/task/Calc_task.c | 64 -------- User/task/Calc_task.h | 10 -- User/task/can_task.c | 15 +- User/task/chassis_task.c | 10 +- User/task/cmd_task.c | 5 +- User/task/dr16_task.c | 12 +- User/task/init.c | 10 +- User/task/up_task.c | 118 +++++++++++++++ User/task/user_task.c | 6 +- User/task/user_task.h | 21 ++- 32 files changed, 1432 insertions(+), 875 deletions(-) delete mode 100644 MDK-ARM/R2/R2.axf create mode 100644 User/Module/up.c create mode 100644 User/Module/up.h create mode 100644 User/device/GO_M8010_6_Driver.c create mode 100644 User/device/GO_M8010_6_Driver.h delete mode 100644 User/task/Calc_task.c delete mode 100644 User/task/Calc_task.h create mode 100644 User/task/up_task.c diff --git a/MDK-ARM/R2.uvoptx b/MDK-ARM/R2.uvoptx index 3f23285..b9480f8 100644 --- a/MDK-ARM/R2.uvoptx +++ b/MDK-ARM/R2.uvoptx @@ -117,6 +117,26 @@ BIN\CMSIS_AGDI.dll + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + + 0 CMSIS_AGDI @@ -129,18 +149,35 @@ + + + 0 + 1 + chassis + + + 1 + 1 + ctrl + + + 2 + 1 + dr16,0x0A + + 0 0 - 0 - 0 + 1 + 1 0 0 0 0 - 0 + 1 0 0 0 @@ -775,7 +812,7 @@ User/Module - 0 + 1 0 0 0 @@ -803,17 +840,29 @@ 0 0 + + 6 + 49 + 1 + 0 + 0 + 0 + ..\User\Module\up.c + up.c + 0 + 0 + User/bsp - 0 + 1 0 0 0 7 - 49 + 50 1 0 0 @@ -825,7 +874,7 @@ 7 - 50 + 51 1 0 0 @@ -837,7 +886,7 @@ 7 - 51 + 52 1 0 0 @@ -849,7 +898,7 @@ 7 - 52 + 53 1 0 0 @@ -861,7 +910,7 @@ 7 - 53 + 54 1 0 0 @@ -873,7 +922,7 @@ 7 - 54 + 55 1 0 0 @@ -885,7 +934,7 @@ 7 - 55 + 56 1 0 0 @@ -897,7 +946,7 @@ 7 - 56 + 57 1 0 0 @@ -909,7 +958,7 @@ 7 - 57 + 58 1 0 0 @@ -921,7 +970,7 @@ 7 - 58 + 59 5 0 0 @@ -933,7 +982,7 @@ 7 - 59 + 60 1 0 0 @@ -945,7 +994,7 @@ 7 - 60 + 61 1 0 0 @@ -957,7 +1006,7 @@ 7 - 61 + 62 1 0 0 @@ -971,13 +1020,13 @@ User/Task - 0 + 1 0 0 0 8 - 62 + 63 1 0 0 @@ -989,7 +1038,7 @@ 8 - 63 + 64 1 0 0 @@ -1001,7 +1050,7 @@ 8 - 64 + 65 1 0 0 @@ -1013,7 +1062,7 @@ 8 - 65 + 66 1 0 0 @@ -1025,7 +1074,7 @@ 8 - 66 + 67 1 0 0 @@ -1037,7 +1086,7 @@ 8 - 67 + 68 1 0 0 @@ -1049,7 +1098,7 @@ 8 - 68 + 69 1 0 0 @@ -1061,7 +1110,7 @@ 8 - 69 + 70 1 0 0 @@ -1073,7 +1122,7 @@ 8 - 70 + 71 1 0 0 @@ -1085,7 +1134,7 @@ 8 - 71 + 72 1 0 0 @@ -1095,17 +1144,29 @@ 0 0 + + 8 + 73 + 1 + 0 + 0 + 0 + ..\User\task\up_task.c + up_task.c + 0 + 0 + User/Algorithm - 0 + 1 0 0 0 9 - 72 + 74 1 0 0 @@ -1117,7 +1178,7 @@ 9 - 73 + 75 1 0 0 @@ -1129,7 +1190,7 @@ 9 - 74 + 76 1 0 0 @@ -1141,7 +1202,7 @@ 9 - 75 + 77 1 0 0 @@ -1153,7 +1214,7 @@ 9 - 76 + 78 1 0 0 @@ -1165,7 +1226,7 @@ 9 - 77 + 79 1 0 0 @@ -1179,13 +1240,13 @@ User/Device - 0 + 1 0 0 0 10 - 78 + 80 1 0 0 @@ -1197,7 +1258,7 @@ 10 - 79 + 81 1 0 0 @@ -1209,7 +1270,7 @@ 10 - 80 + 82 1 0 0 @@ -1221,7 +1282,7 @@ 10 - 81 + 83 1 0 0 @@ -1233,7 +1294,7 @@ 10 - 82 + 84 1 0 0 @@ -1245,7 +1306,7 @@ 10 - 83 + 85 1 0 0 @@ -1257,7 +1318,7 @@ 10 - 84 + 86 1 0 0 @@ -1267,6 +1328,18 @@ 0 0 + + 10 + 87 + 1 + 0 + 0 + 0 + ..\User\device\GO_M8010_6_Driver.c + GO_M8010_6_Driver.c + 0 + 0 + @@ -1277,7 +1350,7 @@ 0 11 - 85 + 88 1 0 0 @@ -1289,7 +1362,7 @@ 11 - 86 + 89 1 0 0 @@ -1301,7 +1374,7 @@ 11 - 87 + 90 1 0 0 @@ -1321,7 +1394,7 @@ 0 12 - 88 + 91 1 0 0 @@ -1341,7 +1414,7 @@ 0 13 - 89 + 92 1 0 0 @@ -1353,7 +1426,7 @@ 13 - 90 + 93 1 0 0 @@ -1365,7 +1438,7 @@ 13 - 91 + 94 1 0 0 @@ -1377,7 +1450,7 @@ 13 - 92 + 95 1 0 0 diff --git a/MDK-ARM/R2.uvprojx b/MDK-ARM/R2.uvprojx index a04509f..f9d4bc2 100644 --- a/MDK-ARM/R2.uvprojx +++ b/MDK-ARM/R2.uvprojx @@ -1108,6 +1108,11 @@ 1 ..\User\Module\config.c + + up.c + 1 + ..\User\Module\up.c + @@ -1233,6 +1238,11 @@ 1 ..\User\task\r12ds_task.c + + up_task.c + 1 + ..\User\task\up_task.c + @@ -1308,6 +1318,11 @@ 1 ..\User\device\r12ds.c + + GO_M8010_6_Driver.c + 1 + ..\User\device\GO_M8010_6_Driver.c + diff --git a/MDK-ARM/R2/R2.axf b/MDK-ARM/R2/R2.axf deleted file mode 100644 index 67ed57f8735c1acce78bcb3232296b867eaf5791..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2753628 zcmbrn3t$x0y+3|tc6N7mvq>fpAcO$3;kCRZ_{2wblEAV-YC@~M_Fh{zi0uaSy0lfH zV%;EWM5&7xd#SA@^wt(1x6PuoMw=%1D!y)aQClCij`voBp@|a+>}K=W|L1#VcC!Jz zz5V|PJ98f2^F815J?DJS_k7P|?pU$fF9-t5{u7yxk?&rC$-fmAus`D`O3Z#PQxWcC z3M*z;N0>U_#^gD7GTC(-lf8KN&Sdi7>rBq#$-bLJz@2S|zXbQv2bf%ov}gLw16+Ri zQp^A8;_>16Fy!t>-hyhvTx_K&jQ;OwPQ~%n|MA~Y+UwT z0$RNmy;JXE@_Y;CLcE*)4jshTEFNZvDP~-ga<@j0FwfTIcP@XtUvR#+LP#)UP3l+2 zTt&|wDP|K5p}4GbsJzw?Y-KB-bPDWs{M^gy4dzi&!o?E}rzCg6b@}uX{{EMBGwgBr zH>{f>;5nF>XvoDgIK+Qec&51$H_o`a6EUx)-?r&9Pq9SVFwO84$ zernV!LD$puMgz|$i>t_ZJCn`Z_1i2}X1cb&DciI3g;%PKsh=IUM~FgKAhOaGU@J$v zPydqw_B#72$K?b!h(1C6?dtC`mHO7zTg=~=dqfX2nj(uoH7-Z)4z_S+=TqrBPuSA- zf!S&M$**e@Iw#lePj5XTBIKoh)jp%MGHoAT-s6$f^S;s}t*-AWU0&9?t^%oL{9MtR zjYn;s3*Th(r*_8D%}F8cJlU3xBpKen?^m5OI@Ppu*x%!Es2BWtXkhpkN9|7KGN&=K z;I)3$;Yk+^ElN91F7JHG&*rL2e%ASQKd=`3OOL}Nch(z1!PKJ#t|x}XErFvBxoetZ zNPN9u$oBfiqaNX4cY$B@SNjA0jw8l>6AvIA!%z6taTe(~QlW)cYCVEYIq)NAaY9;9 z_@;75er3YUAJ?Sf>a$ayZK)C76;!38-pEub9p$k%owoRwDx5k)7`5RNwBBjcoQW~F zka%!Lf1=E*e4Q$Hn|X*v##Y;7tE}k}Yakz<0gpv#ewQ)9;=r`X>;004I8er^ z+DEAu?nMnTqwtw)dk!Km!bHC;-GqZ3nCRc-|AAkJf-eh+)&R#}VnpiA{K6~EKji>3Tqzbp{T-0}%&?`TAS41~f$+-I zW(+pg`)0_8!OSoHcGl$ovR^fv>@I&Q425d8cyL!|C2|$ zT=~Bpe&W95rO*o$J)7|}jO1k*{J-w=X z2Pi4)Q{1AT{jl-)43Rzf2tw{czIMH>F97VHq{(Muw^`UJHCB<-SMSB!8iQvVW$35yv(iJXh{BIwn~>pUmIKyZ7{tx<>;M zU|!OGwtv1~MXUM2aCi5=_p)dIy;penPrc&92l~36 zw|iO7+r7ej5A}-a9{}eLQ1$~*y91Q|0KXl)W(06tb3cMOwJ*YX_W|OBz98q-2Y?~> zNtBpc#E#yn;3GQ)o?ui9-b_0NUuMBm9T0w@Jd2a+;sfMMX~*EFSn$*Wv+#tI@QW6F zK0TA&D18s{!9{#{k6aS*CQYvI#s9VMm+mk2{inOWuNXBPbUTe-r`k~CXZ3AI`_pB@*V%c^KiVMJ@iJ&w;%!RNC zr-aQ%SP60Cl(fn?xE;NP<6w65df*pxX?FA$z;Da*yT_$x`lSDP3-D&mxyGfX-e88y zJPq}b9ca&HZxX1lziPU9`u9wCHjM*tR6`6f0%|Oqhn|L(ds&r9?l`NBOo|Wy&5qt8zD4e;z8lLQ0oSxX!ToEb zuj*Tm-xVl9!0mw6Mqy%Dugi1Jl~!+ZHiL1nE*4VrH%-yeXVWEm?D_U$bPXF=1!|3mq0J=gPc5FfmKUaMY3&{NFu5q;E?<-V@+Y}*Lu+D62E8*dv#+vS`#v;kgc zCQoetAWujm;BAiA{XfE!H+rX?p>2>P7~j^ZZJ-|@pCHBvFK@#ipsfAyH(I?vfVOV7 z$MtBBSAZ{axm8a1FXtM}Ti{8oFHo-bH50Ai5A}RIdaa{8-1iakZGl@V--5OkK;4D= zUg2XB>X*mmw|B}f-1jMH5qMrScJ1gbNBRoDwqhju70NaZbtB+i&fi48!)O|Tbb0&{ zz^NEzcHq6l9A(fxrdeUcmvYNp4);`dbs*ZyKy3vm3L@21gqFGEC=u)X4E{3sr?^d+ zX%@^BgiW@>%B`@;ke}2GBye;pZ(%ROPrb?vE3?8(d2fbIvBFIGZiY>^!fYHLm6$jI zJSZvEkjPtu>9)abK;XPE0- z_gngwscm_Ht98C?z3Qe@?gwyS;crm{G{|Ip6z)sE(=eA1@k!Gl;^8?FtQt(4cGd( zwzJ*TcA)q0ur2W>XfA=ieL3yLVO&NW-9EpM#s}?TAKJ0O{rvqfQEotvnBxtN{$m=+ zj$Rt&^R*2c-A!!+qkEdtLe5xeX;kO(m;61Hj^Y3Zx8OdOgCiYW%=4T2yQzIp4U^`< zzz0@D^egbcYo9V4O>pMbaL|&ELf%s#lqkNgW2(7vpII1uXlfG=y zLGSw!N1CJd9`c2D6X7*&rU#v%iTH8@mrbT7V3y|y)ysP~K}%hYG4G3gguNzUv49t6Jb&U6<$we9iCzKp-DT0IL~p1(EK`z`L7{g z9Z~-3(BqXF$NgwpsI2C$*0fytW$yY>TB^L7yM6%I?cB99eKyh^19Y)h0p@$twn~N5 zur19hCv(>wh%Mu>-%Up*! zf{l7IZ1;E<9T5B_oI^z&3j=K_fr-)ic-xo|orkxbv1rF2O#HArJk!_ZZbr>^3`%)^ z0e&=vT)gNuYkw-N18O zPAP+QN*U}ZgAFv!wP>_~W(odE%P+xihku6Ux5H2Hq?4$i(1!E`KgIG(@Dn`E#3-}0uFjyuRoH^*bV zFvtcXRm^vL9I~LwV>~cOqY%bjNNy!PDGte(^A*8o&-t7Qp|ZsGMdUg&!&Ip)+#&UQ zSSHywLfC}LouVIcC7F<4Fupaor*}D|uHfF&TZ6ZVw}!XPO|g3i&(br=UuLjYFp^0Q zj}#c`j0!uUkTEg7G!l;yRp)YfUj;6c)rcrtdP<1hy?9&*%9;vQ+_nF}iS$ixyg%C- zFO+|N1~aAzW?sNkt_GNXwr-9j<73Lt2u~Ed2TKA`&_E?pESKmm;x48a>e-T=JIE@* z*G37PxPMfDeS3X3*&)B#%_>9xDZ=Mtr7JCwQ zouT$ifMfkAxdm@A-0MbZJ;ZNBmY5kd~837e8|>eOmwU?>`u1KOr=2U?8Z4!>hmf;2zb&D4QYXd)h%_CvdI2P;Q@ zvfs~3_my!pmIBNFjF{Y*0QUzY#0@IT6@yODCRP@JlJrovTttZzaIYXumWmg68sal! z#E&d*1pm~SFyEFCVY3zk!=N(Vof4TE$4@z6gO!x}Dpn$n-pSa}7np6ebTq=Wlvicy zag-LCeUsykKezQ~F7w0>#ROkPVv26_$#Kc& z#HhrowepDxrc+rMR$ww!;f|u%Qa{saEGjUhQ3-LXUo^go`oy2w*R3458#92XW1dB& zhi$uo*lA(d zVPUxU6bzy@;*qxD(uG-fY7@0-G5h7UDOIuQwH5E|SA56cr`&qG8&FSzKP&5Ohd;zz zx(yP0V|x)~XxDny7j>uLr+N4=tn~`~TlaImFR*_wwH<9ZRC68olXk=Z9g?VxNdDRF z43gMx45rL@lExG#_=WibZ&{=bF{aw^-)d3em5|*>YZbF4CA*`XJ}=s$6c^_^z)J}& zQbLQA0%^3$6w+U5M}GM2ruVqEIlf(<0PM0gXycuu;IbGHjK`q?qOI~aP5z&r;(wU? zsok6K59ax44tm3=~=uyVY&_y!IwWE%@iVFj49d)h{n^o>lq-F~uLJEw+ zQKe%U#5fqOh9JP2W4BbOf#Ri$6`(--$JyN&X7n6FZKi9(b;w z6+7b3^$W$f<7q3tEwMr;&AJ04nF9UAv7csJS)UU=G3P5zM^ZGtWMknU)Q)A8dT5wT zZ3!L<%BtL0<(6-OEV|`Fck?a3zoovX%q!d)NllN`_e}LR!!PjQ41*g z0jFphC@SX^#ReCFB2RuUX_Q!s1Xs_y6y{T~1@*aET>dl3l@t!?v|LdD}P{{1r zqzSGf{WF3Zx_`6j!}yFEAsvy%>JLFHX`Fj7&x2KukN=Rq($7dYD+yySm>n4Yg96!ReCtyGaEvopyqE8X@%>JjZc-ET(ZRkD}-ofvJQ zD=7yt?T=?y8Bb+FY=i!nQ_U-FzQ+ zJs)A6N4moYXuWk3@0nq&w9;5f(kheu@^It&mYNF^YN+)Xc;%}){NWL1OevdMF4-MU zE+;!F&OTT0#x!3@uJr}yPZy3l6sf;L$Ryt#Ei+pehZ6Fj?ETw>F}RmTH&z_lUtkdhXxyIpnF%Qq)(T&py&(4%nCkpH*wuUpwTQVlrV5s$E zfl`GrydW<6l(>y!??%`}?Q ziaV>6>g)m8_`;x6XTy5|a#cEBU(Zy7Wb@jrPU-bi?6g4<&%c7ka0kWH_~h}^JY4CZ znJL$AR_=s_iq@E)#z;$Zj>U5gR=1U1mm$%UhEjQ z^;TLtkG)Q(+{gx)O?{@^Oni6?2kCcxx?R=`i`6?v^(x;lQSbFj|cM3a9Vb`^qMVuPE;FO+_sT?yZowG^5`N`Af6ltyr1zpi~lE#eCko6_%i#n6+>1 z#p)l|NMFiH08@W8_gbX8gSX2u_4cxMA1og;Qa0UO@yCug^>5u8MYgj4sHY8yHX8IMgR4o|CS}n^oRI7em9@TZ^QilAwJLFW%(z;Pj-N) z<)7?+N#E1^ec0rtU^aU{-jnd&j`w8uGy1O78YaW8VUZrDYxZe_HbMKhrM^? zussA`(`w|0z2D8{xTklMTY~&>8&gL2^xh2j)o_=<{Vlk!fxBSz$Y#MeC9w-seAs(q zE{9#9<|NuV*(8XvU7%{rKiT~a&_t#AS`NZ2?N=@TWR%uiMKd{3oYNKD#-}5tKFWA_Y!X>F*#?~bYA!rn@$!D@ti=0F{UvO-Eb<(56Z-dE3>4|* zZ@j+xvWI_2|JwN;9BRkml{?YbA51k=?XGbq=BwH@52n_@jlH0%(M@q%(RwL-D_R=u z!J!^+rZjDSH0Dm#h5l_e+fg?0-_V=I{&jFiY|B2gcYGtr<`n3SA@}r` zj=p3wx%UDSy>{cDGB;L8i~HXXh8Ukom@R2_hWzJZW?{C5<=nrE`>W6rF5&(sx&Ko5 z&&_-Y`9tfk)W0R;`|x`#|26R64Zm#p*TMfi_$AAK1N<1%)yKLSYpuclAgo!p;@4c> z)w`hF^y`-2hxO5*<(?0>YPsi?)BKO-eM+U*KP8Y!u1QS^s6jO(w@>14twL^}0GCub zVXr!UBpDtmYu^JqDOviZ%EG-;zsyFG*Yi*hLPdl+5$ZwcKl4xrLTzrEvoTgAx1!E7 z_(wkaM|r!Aua6d}qsfyQqQV9$%2IBl6*Dh_D3Z;2+%?=X_+v+QUUwz;59j==xqlPp zr6&Ax?tdrezl8fQ$-$q?{eQ;%Q}APqSyncyZRq$hIS{$#(Dk+j_IKsbO~+k~O>ep0 zrkn1T>sxLleg&O^Ecltaef@n+ueF~Y6BZQ4#RaywZGn;~g68qsdYcjX_EY_lI~c}3 zr~cadr~13N+tf_X)$eP1>IA#CJV9xlR@#z;8)*f#2=Mvo9eL?7=5`dN1@C9tmJukv{3n_1r shm1B8iz zAWYvF#2ei$$bm3?7de>jvDn{rw`|5vOeTYtXSxHMBQA111-TH*jnQ0Uw)z0utSRnQUqa0D%64FUL);#51hmbfE3kR(@q3iOMjL#r zBqFzL#4Moub*^W_Vz7qR_1wl$*iEQzXjVq`^(Ri~KF< z^#j_siY}iPnl+$(+p~IBaF%~sXkxATo@JzLrc0c?yr)Z=RV!H#wF8lJW(7%hDVK;^ z1xmwU2Wg9y!==JiMzh;atk8wD0Tz^lJ* zT-kIH;2`{3WwF^Y!RQ^-rnN$b+R%Cn2_Ij<`Yb`~V$kB462oW#d=BnE z#>!%uM8Q$FDX?tm0x)9v^QtX8$+e}SU?axMj)wKxKtyd=E5Np7pag~f8U9@< zHLQm24DAcCcBW&5S%Q>Hwj?k%1*_U^1`C$q8EIg?Z^vIaE;Nes?e7MG2je5~7#)Jz zqE!X=g@Wy{XLKD2X+5j2QA6xRSC}0YlrDr7>u-N5bZI@Wv$s7s)(bufxm9p~g_uY& zQAIfq;*FU=M<$OuNwjTl$6QIhXN*I)C)Tv9p)T|d8;i7$aTeoph&55DFE8|XH$qRm z!&?_a8i_@N(U1lVW1(815_H0PHWtz)H$dAR^W&@vi|2)Cz*NkX#xWR#4BVkHcXWK1 zryhNL846?*-@GJS9cd&^;k?d0OeIw9&IH;y@iT z-&JuZ-d&Ja-cU=>37(b3XeRnux=43|^Ga;R0J|PmIYZ{|$W@|F@qbA>2O{A^F^oZB zo|48xp7Je9iBXQHyb38XB9c3@!c6%BrL5v9tE`k&X3BOmrOH#T;3>H~a-NxTU)ljG zmc`sOMi5;$E1>#N&;dF%gv!hplX(bHI33U;ptJ2x;nbBPR6}Tig(Gr3;gB00;HHMq zEDpJma7+WV!f}|b)Wk6%?HFKHTFiwwUyRZRf&@Jq;SnC5#bSnELGW73Q!dcC=_$a3 z)tC&f%dr)PU`HJH<0vcqBK(mc#Y@}|yEORM3V)cj@TcaRg7sSkHec1}iB~}qc=QHX ze}lf#grZN^r|K&V*V4nM4PAGgI2BoNXzzKQ8OQxgayXF>3c0>daU>s!enIWOMAO z3a+)Q+mJ?3b@XQqy^q@4(Kw}5Q8Q-RfR%Rn=cIk!N-I*@g!(q!F7l6<7 z1@q#yaq*_FH7{Nr7jOFXT)c|9B??Xaq?M3Qy<;qYIWJyCyP^1CUc59e-t@iosVK;` zUX0g`^b6I^fG>0ieVE1;;ue%2$WU`d9lOZ(4JVt1zfz}$T59SNR|UZJiZ4U2AWc*7 z6(>-ODvLHyxWU3#STPK47B%%ZiVp;oWdtF!6?MvmW@-kX31d@fyLr^tF(JdRc6c^rDy3V`6t0ObCjN*(QEW`IBi#3lq}|yM1l)*lthANE^|5U zvrnVlYtcS4mts8aQ!Uy>HaU-Wv<68KLK|M~L=nxDJlc^OqyE z|A59S2|U-9i5m0ZN9%AB^s<$V(R_vWBzV)3-?peEE*;$lYuby%;&jZdZZkrk>EyCi!k;JalHOghsWA_EApXEcc&gZa>v6EA11BHR>LDxznVh5)>;UVS`&i|(_-0B6Hc_?B#xWls6;e(Avg*(;Uo)A;c%OtGT~&_@D#yO z=swbfpmRjjh>2x@slImghC>(?y*IS1oTRtj0NVX~;Vvfqf?&gdfGfxU8)*C^Xu_)U zyqNELF41WQ$9&huvoZUEROfb|FJWT%ztu3MK65RpH}br1Y+0Eio$<7i1UYSupl!OY zZ+HiEezc)w<&<1WLRLvkIeuyz&^HivN)fzq*;7HZS{z=E(fD=V_=A2+y#%|Kg6mm~by6?SZE90qVZI^3$5Lr*V<`Z1t&l&^Ywwx_K-JV*WUV6z!>up)~>VT%wCK&AK~X+FW1^@ zgX<-qE%DZ;1%R^GA{AQ3il#Y+(;i%J#ug@8;nLR!z?0GBO(VXTh8|{?@8`&K1$3j) zWF1yjvh~%5-jRi1>aOm~a5fxeU1{#4n@MN-<+oB-LuT(n&lh|mWEx6-58)(9Ky5|v z&Eb*`JOHkXu_ugH&PJ2lMzXoQlA_rg!$@YeCQClh$mXTdna7zNbC8B(VXrqtS@UB@ z24p(=uThkC_~-aT6-tcu0NR%W(vZ@TY5Qu@Z-zU{a`jZ?7v`a^I_Cr!^a6|KW1>SGO6qshNzoPM@sX+oP(h5TtuR<|^UMw7EMX8fNKKRG~sNMfZJF}MAr{mVev z2cr{o;Vdb!m-`%<0$qg9>!-Mh8A-47FXZm`tr9c=1KCwnv_1}k3NuPplPeHwddKOK!`v@cH8)R>69DWuDOkWo5HFA=m9R;3Hbsxuo> z-1|penCnOjCuW2kJ$C8In(riLY<3tn2TC3{UE*026VXsTv(5dT)>d23{u26~R#h7f zHiU$^-$%%d%`YEklfRF!hM<|kc9tt1&r9(Wo+56=623pkB5uC;N@^av!kH{8HZeOh zMKhWRw;Ah4tdhfGVyj4P^w z=TFauF&;Mc3WNm9t~h^YF8q9gok$_UvCs$)ExJO!v?^Fvq0G+=%>7jg^}HPVg}hAA zvioJ34Bd_NHwC{^{L1jF01WC}^iOOmpnV1^(|P|mP}Ah?5p80RAl3FrwRbjRZ6Vg& zDCh;!osHp@0@@C5gOCH%x6n2>$;(aaAjUYA43rgO2%X zsu)ivZq!+rBHJ9}_FR%duupEX_T?HLw0+v2>%*Sbj+9J2phH>YJj}3y)-VINwWRE5 z#ey!V$6!4)x+#AeOG@#R4^U5I(GpHgL?hcL(SWgA%bx+rGf7578eB88+CQv)<_rNR zL88dz{1h}d&R1C3{lMXy@;>x@n^5_%R&e=pS8ZyxN^OcP!u1cBuB;z7(^(!kYZk1$s!v?1h&b^el|}w9>#v@3;hfH=U{)DlXdkw-Ou(* z#p1j5hU6A>@+bVPUqYy}SUile1fi|{IPXZZ&FxOR(zvC_?d}ob_M{P3P>}WvJ<*SM zkF8);Pl4q1Ykt}I*Fl=mf>y&RI&c$E{mG1NswQ1tP+QxBJ#d##h1?3S^x!TZtclyP z^V+Y3s@GDRF|coFlD{mpe7(1Qd5>M25o%jIRWA!g)=Ni~<*ZVMn_+KOL#mQdNJGW* z`vWtgHOJop^hz`CiWypJZkQ})B%$6)$#w_!tY-H>+xe>WC74g#DY%>FTk$bieyP0_ z`g#0`nH$H)&%u7_F>F5tHdDg@JhaJ(Pfplj^I}K41gZZLyqg_PJr{CfCM;~tj-`Gz zbwZ+(Hp1Jd-@((n6OQre?SdK#yYyVBiNlUzIZR=`FpcHEl>{Gl7^5B2`2Jgo zbz&q(9eufo5^aSKo%o;Jjr4`9=$3LDg_8y)g?{~Y$=lx%_TRoTetJtf6 zl_cVfP2^>`ld<)@U9P0_4^fzCR`KG)6G;y$glphm)I zF-Kn#Br|6RdP7)H+py!Im{pCd?e}vWH(S&-Lj>b%_imAny;wu_|5iG`4qiBO2~7^$ z$4W>o&TLy}F5`29V`aR_D&yi$N9(DNv9_=CmPaRoz5@-}Y4}EEoNF0q=5G{@Gr_`tmCCsZA_bbP1 zHPKg|Sb5S2yLuR_dg_(q?g>}>-%BZq)A(!zz7n{Zy!=%>O`pnru&wEo+Trsghi?5T;Gep0ofArttZgXA`ihsJF!uO0s zAOQsyhzVZDiK-wwxPUf7Nop?WmQHVUKa3S|vYcV31zeyATKJFB;y8>dnlpHxA2z@mXbsqrpw;9t zs&A|icWbg3MHzkDd98i{e29P#ktMft|Ije(S#uuNvt0PL#RZ$i1>-5SO@U_LLR33> zE^Gd(u-l9Jf?H@=Lma|l1=^R0KoM)V%VJcCvz6xFM8~t9gyOAsqW-YMZPX1;WdzZDrcYyylN7CaVLZ!I$wKlam_k>ySVwzc&P3L^q|- zYeV24?+;VZ#vR7cFxAh$4(UPM%{auOmA7I3`$K9A#L?kFi=)6{rhj6H@m?+`D89g| zADTIv@jpU5wTCkF>N2P)5%wD1!kof<`OmsG31~6YigDlB(2d~CzM8&wh?3htUqnHT z&0L%i=2Yt0b{0>uXnv1i*eyCC;j&s)VM6fc_n(8|Bl|TYA`t!`TKL}ue$EdiOX~{a z1@dAumm{xb$ct)jg_6t59IY7T<;&$YE8!Z5RP9O)mkMaZEj81!d2{Hk>|mHmj@)_4 zv$9QV&q_A7(QNlN%+0CXFJNA7aXCj>D$R@t`b(sq_?$_)%$AL?EbZNZkeEc40=_y& zt3nd23j{rtps~L0qFRAA`q*Dh?a$N)?Z)&>Rv*lUEaM?`YJ{vwbYf&KtdSj(4|ZJA zy{N8#ihVrW5N2#Z4TZ7i#_PrC;V>qT`YNSew`0Eg6%^X@#|Ah1D zRI@Ln*_@>~|Ce7+)!|&7ro0X0hAzqM&1@W$urWW)!C<~mXw3IDH-;)++D}}4^&K{6 zfo|ckYR1Zqe8|m=V@J0#3xBr$O#GJ5!f*M;@F(6GEA_QjsrL?#mHHaYvbLp`G14D9 zpcz01#7UVo*wId>9BEA^o!paALv8)7^);~j(fkX$t}wq6*o^G_3vP3MRX@a~!%J5}}I=a|C@P`L83{R`c>G%|GnMjiY1p2fOiO?9)`N zxrv?c+B93=nRR;bsKL}SyT|GEz2FoqFwkJkJbnSJglA6Z%y?R{zrc}b#W-t=@7sVf zSM9rwTHSv@3ObCoaeDjzbko|HIeW4je;TD8#EOXX-q1m~)b+lYX%BNSnz7S-RKa}C zEQh&{c{S<^GeEYl#&!6rxSHZSTWUn?MB3Ty z)GGmtbveMc9c?b|O-$#0UeG7Bwt%MB^Hv;eV!#c~$tj17NaoKkfPOE>I z+7`W#KhM{}gP8csqp9>v`1l$4e0VO$+L}9MpZ?&*ww&enc~?YZJe<%6WC{*<6V$62BQMar@KR zl-S{+qwi3kysrC~Cang{N4yn2&MCeC(v3YOsQY-Ym}Sv16Ldi4f!dYbtvPJW*B^i6 z6f8gFSW0!K{yWDYS{O!0vKZ!eNAof8l2G4Yln6HMgQadePxr})$*2F$rE_<04cq_; zjvkM??vGO*cW~Ia1^apqcHom+^I>yRC!ApO!hvPL0*#^}+HQ_CH}DXQ7Y$8y%d#T_ zeCB8)%=;$s6{CDx`#QK#*WtB1-(6O|(OkaId~%Hi%Y4V;tg{u|mJ?S7LNxNAjjpK+ z0snNpHDvb{Ca$o;C3ZOv=Pe0P)RI>6I2FF-xj0(ypqA7c+J}~O6>=wuwFbG5NvvBx znX513X-z)$#U}#hGQi4sUz~%bx@`PpaUSGn31JD&q;OuSDE(Z{3*^?sd@JI!a&7Bt z@zy30^LD0Uf5A6KlO+}x3UgdI?~^In8V;hSur3DiQ`?Ard(9<6W$XIqk2bLC9#*|b zWnaTP2x~2DsDcW+FYtW|SwKDHW30lPZLaVWoI5mSJ>iSj=_Jz_TUiq+T3N%w*k3^F zM@ajcmG<|!w4Z$p2}NxNDUT%<=`<#?#9u$g`Vn@Al247psxIhF&Cp$O*O;KLZ?2gP zYeQGKN^4vXnLo2Qfz^SfS;}KaS-k_0;YOk#zMH5&J@+wF+dn3n7-*xhk?wO?k+J)2 zi;LsrzAQt#95f};v<&kz(YPREvI8+|@CGi)3r_VY+OE`WMKBbKrTtl< zt|pbwFAvdfo9jutTZ55k&p5sAsr2P_wAbc)mR=V?eV`9D_|b>Bo&dLHH|Khv7AQqs zYlg@!tt-v#tPw5U&+M^dJ%wXHFEKHcS$kIm)!cVu=X&8{=!H+FBWH}8hq#}l=LY71 zntG!vh#7)+cAzSU6ZNps= zlLKW{xJAXnpm|GyfqCOjryS20fkzIsay)$hOqHO~S`6)(A>C73hw&Td zbl$-acO=wG{ubEyX$_LO%oc*R<Ez6ZuI?btjq7K5#9_{uy(p(+U8oK>klyBM~NBw`1D;Nq>r?2h>T1B z`_s}FTj?+2E8wD$8kS=!$`-s)#`zV&W$raV>qQ$hITY|;o3o})!kS8JC~Wmecf#b& zLae95E{p#62smvtpPADpkA=86@1Jx>tgu~}_vJj^{`|T}@A>#1&QtLA@9}kJ;G-Ml zb@V)R-3)rJV=6+f|DOl=-tc~p@Y4o4j-}D;=|B<6~AjN1kk?`$6*BK2C?4?b@{brydw<*@v+970Yki?*Ghh+wPz1 zGf9xMJ`$uc2!P1f-?L(NAQ{Uw}xz%$}50>1|wUq|{`RF+r?3ixx?}Vf( z`ia2zLJCM{)){VLQl&QZnLT5*)|=w;s0}l?=;MC6^Q9ne+f5^&1o@`4KS%4AahxfM zzRzpZ7H{YBY7)jvA)3&spTXu6ryWMwx?L9i_?}1ap*sHf?nk-g`n*1%lSI2|6|cQ# zKezVI$*Vmjp?^Od6L;gLh%?qB-5!#abfK93z}1j;r%Nm14E6)1x~8?&NN;)I2E=ZbM5>(v_%zJ?eKfEESzi&xu(Yv7)l6vwPvHT;l zT0BiwH~81)$?BPq*N>edvj=hVDl4;(4_bPuC9{tXT6*ajWcCMn>HcJ;(=3_&2P>UF zPiB*>$F8s$u-)DvyeX)~dT2(yp?d?3#a=q0=)k>hOr?;PMkl||2DVu2qpdRc6m>qB zy2R34aQar=3Low1+nV|UcJeF_DWT@jY$Gg{g``^egJoY-VC$R~S71ks)K7^|;{J*8 zQvNQEPvq}{_yqoT#!L9y7FYP&p728Ny*eZSS96eZ`vTVn%v@P#2YAXD_Q&901e5Xe z;3vVa;Rh4r7%!~{kOR93p|}yM;di@uR2+4G|UZWWi@KJNk(6!&*X4rmgY?} zAsXkW=HS$$We>Fr2873qFA zO3x=omvs<-`2O!w@MyW9Wp_}pdDM@oPRDlsZL?~XN~nhJ4$U=gb<7>O18dB82YsOi z-#Ky5pH*K&T>3NfT^?6_YjE>Mm9H+Y`Bo<`)Pugo@vzSsr&TQ*p6uG{M4?`dvvcCa z^*Et}TMDr%b9cxOtc3C0ychv75t@r&TyF`^(|bZqJjEyJ2H5CDtoKaMg?*L|@~~rr z6LVpQ(;5#uGU(E|uGBf7r`HFuvj`(XpRW+|8XxA8N#(427Eh-T>T@KJ$WZTuEo zjOUGls@@99n&=Ey8Rm+ai(}yXJ{u*Dp(~Gu|FAH;z%ksKhk+^CQegcErBEP|&|JVA9m!P%3?w~e?1;sFFRZyyIlB}Sf?Naj=-Tg_AIoC z9p{CuK4s2HXe3zXzn8Czm==>$rS6m@T{(}NhB>u4!j*CV#P}5cE{;#;?}B&>w7`P&vZ zrMV|T@($}X4#!y@YhKQKS`gADL~YabG1#OT{-K@G_?AE3Sz{gXgY56LlZyDE`p!={ zV#VAVpOx@rZ%B3%*Qu`5>$2M7?_m?`ZC5wYd0VPWno}@7v(T)W1xZeC$g_0K5jL}$ zOB2u1>LW~K3vebt7v}iDw!RGJGV?r=X#8OWt80r2;}XsyIn0zzRXB^3J%=P)=a49kIS<7if5`fm z@mtwMmY7#*_m_)iB(&p8#rZ}${it$F-)~3gE=!8r!cT^lwL1o)VdlFzZs+n2_D7P^ zHxU2Tb$0Z`su-OhHN!+6CXNfkwm87a*m*>`DD7j=*v-FAy@C1sz^&pWC6DJ+Y=)fF zXv8Q-Jkl!d&w`@G+%|a<`yMpNdMGnKm1+h2FXjCAa?4HW82>w4H#Ed<4#4Vied~td zq-V4x*1AE!8InSbP?_XcGA`Z4U2CwXokG5t!DzMa_HL^2TfiHIG2gf1bOsc+*TP1A zrWP1x8be@880$+Z|SxJj)i*J2Qt zUmj}X`Q;fOOQS}9tjc>aO2BV~&9+MKsjU)R8BSJ>wC?!t9g*^8zLO(1YU|eY)*T=1 z(8`H=eMi?*RD$zPp*H#tQTu^^UX5|B z-r}0XR_AfeoHyW(>H#fyrm_c6c4sCK2;@<};tbS-cb1iVIJtz={~qqFzL?X0jeZfQ z_G*jTMZA7hM(gmVHD4W9zq2h$HCCBNsb;~{4{XcRzo?dEUWb*SbpL2sAi7Ki-iSRA zWZoHPq%>>SA5OjpoA40sOl6%D^EkZ{JYJKc=cOrbpI64)=bwRn{?B%%(%o4sfcXy2 zP56SMMt5{WyhKy;_T}9v8F4OKh_)ynP*n>$EQ0^OA{HFrX?>;68(1) zMrF*VeEx*6n~}{~9mQQf=FDsSxGd~e*FL)K<89O{y}VaW2{djvbR9kAb(6^r`v=_D z3%{HdDxbbIw9p@ftb2C&Cd;OeHidLF#?xPR+^FUndcGuO*rOq;&vqYpgvo_JVe&(e zHCdh%pH@C?T=@cd<;$iyF-UwY;A6HO=ay)+qY+zN^`(>-XPD^h67i7kFseF$6G}KG zF|t_+7pBLas{`)O~+l9(O$=bc(1U4ZWa{#*1Ds; zPWZ(I25!Tufgg8{m)9G2)a*Z6T?|dH5>mF(9iw{*krF>?f!ZhHZCk+lwpyv}l)Aj8 zud8)ogVOL@==R`tz-_oe4>x$>ZO3~t-t={cg?NkZKk_fD-ixmx?&+Q9?!p(P zkk8|7_+}gK>f_({*@HU;?M5g~cd^ng&DNPyRvT-InQBeTg7oCFp5WaJk#ffhhb#CLlc(1rl!|yWXKr!~5(8(d{|Akin z#~sU9&toOkjm#_DLN_N1-h;SBS-4g3R^K|5T#_L<&`kGV;VgR`3fTWYJOv!j*9cDt z9}?hr?D(QI$+_WVA6EZ{l2=eHqx0REQRdDb@ss@n5tcpM&*09N-Xte6o+_5aglo(a z<57o`gCq3(grCp95U&0adj5s`FM{jS5qkcS`!9y;qY--k7xyoR>)jE0zRdl8xDq4u z{M`thXQFv1zV)+;c^v_Vab?O5mmRM96qQWrh+wh*#6wKJ1n*h+W;RNPy-D}9m3qZ} zspOM<@0k$&HkbM$+sL^A{um;o^#T5;3Q=A{NSN%HfR1@uEbWvqM-1T%vDi~$#mZ-h zrJWRJTIme2kz8!#46$l1Ry{*3P9j*Cm251&7NW1Y03*`P!$PIvJs++xTx-O0;o1OK ziT@n9zA+5A1~E#j*L2%B*%HLZ<|F2dxJO@%)(^BOHpC+4u{j8>8B!2R&{C8jRfH`Y zsyYR7Izkr@kv5ZsWgPD$gnK#OZ2AcZDH|f~!hzcU(=a_>3hcD6BdpJauoF@~RlpM)RA!EC>&$4&(5fgauiaW1S8J*}}$Y;G*`Lf7$`*@SQEj3yg-+yl62eKaX%s0?IRp>H{`13TJqrZ(!1 z7DPQ!XH<@wIoGGv0O=BD&ZJAMIOfC}e>Ud~*B-u+f<>so6?O65sCRN|u1QTmE|2pZ zzk*YXgwy#LQFtFuvw9qbvPGf7;V*m}bUi_M4pN<>}wh1SA@ih=0HZfJv!C;$>0GD#0AV4QB>jysKSY%#DLZb&Ygzp1D z7tJJ349c-|GKCYrpaJ?1eVZbit{^~pyLc*;9eXCEyp-?ol>`8zXD=uzgkFj!?_9eq9NzEPs+R~b*8J79xFlzjU#t~&Y}%}ZGZgh;CdWWW{4kl-fns;ateD$58{1y z(%(xg4|Lr&iuf&hO(24s;B8F9eULjagj|ZdBXKi4yCl$so8uXyF9kMZj9wOqd>1## zv-1NQ-VSzdfZ=UtX9v0fF9A*foajC)5V>s!zOS_?pyBOi3jz#p7xM+W051bhnX?LFU^l>>$?x|MJQ>>hEhak^+;<%jc?qVxvd^?QiTwvww8ke&JV>tfQ z8}Kz0jBypVRSITVnW}Z&_oMFOocF}tuft+96Sw(|CZEIUGt`K6<0WGRM|GF}mf)2| zyYbL4*$Bv6`eUJgZs-F4A5&VynLGC&N0mTiMZvo+ zSl_U+fL&jZqSe{><{;gwdd{E|F!H-9c9Pi>*;7e2Lx$A@R;GIxb5~tiPivg?{e-u1 zZsQ97yD6>JJYBIIrz_-$4{5JTm?xKt6SaY@$WylRyp89Xg>DXhTbIeML^n3!)KL{q zXe?KngCT_aU{6_>I2Wlsxzx^6QeUZ)hHRa!bY{~JHj#yW0+Y*^tzFmtOjA|6ou97q zg>1&pMs50q>z6gj%a=8NwBHB4r7^u!pN3qfC9*W0nv2(>aqQ$7(P*ZwNl(ykXwRbp zxBmEee#}ex-7spxorT+K$N1-7N<2)}J7IDB6L@&Y?>PFh;51KVNqd`Ae1SrImu~(@ zJ>Xs6+O(ov$4VeO{Bh_=MSV}yJw-oL=&~(O>_4_2cRBgJP4s;$waK?!ZNz@}1KXq6TY;TXb45ovk&9D zz$(5tyA^uzgV5g_LYP&QBjo}C^Mb7ic@W>6*@`dCJcygHx57knCHgj_ zhN&!6myLZ}%b)MHmlHpEnHHc-3uvbIJVFlly6|@6E#vLNy8x*?3pVyW55HXgVecjU zu6x2KB1Y!;8u1-G%%m2a-KPPY)57M=7% zN^wbyzN_g>5r4n_33?R6z516je8FZ9?uU<{FGbLgB53)0_}dM)3qKit8E+?kG-JlM zgn(fWS~|Wbgr5y#&7b*vG0fL8Cix}4dxXBvhVLoU9o6MB?utE{Qn05aQ+2%iA+)z_ zsBVQGL8zDu#ht7i_5+0CUUv%vPA2ov!w8jfp`BLf@4M%QuMZOK+t8D@f%a_{?KCf@ z`8v(rX>Pm?W!=W%3UD|76Bg}u|C1Y3*vRQb3#_gDHY|m9{=qH-0|-W`-wc{(+#cOP zcXVGmobM~)r`-t0P;%j@1Lx*38-op}$m3eXVnK7x3o^+2%pjL=xXOEu81`z=KFdPf*D%BXLCO~$N~$BRM_ufK@}cCkk*$8R z*LEF$t!h&(i>}bIH_TTPA4(Ph#?5et*Wq70XV!~uwng4v{&#M-uBUw)g`k($0beID z_Yj+F2AFf5w#U%M$NEe+L)qCp+#oi?+?(jrux}W;9@A0k6~9VgKt?Yi9#r8D7Po)m zrY}{LZo(ZkYE?%j`6ryR!+hGP9iguj4kfV<)p#UDYq$<$kSsF?{;jRb>)e;bIy~7g zlF8MU{bDw_pc#>d%AEZof-{L+cLmplD4i111|k~ngfguGaGUYC#X8C)IV!4!(Q13q zPKUR6=RU8pQ}mYXbb2T3bnY8Y?!>$?ozw=4F_#xDYe4-#Yl9s&fJlQQY6mUD=*I-L zcyJ=08}j`&VW!!5&S8F5kIsg*^kVNhbl#EV3;dfAG{-gl&vCyw2NXl|FW+5L6sL9N zg7`eRW&X6s=fW-Wr!7%wgvHB4<+U>qrgGTn@d~)h`EyEq8r-G)SrRXYyNEvv;#2=W z;@$;5s^a_`pL2FMdvbwnE8m%JBo`<}DSQ+o# zw$jGo6#SJs@eI zySv1?(z=#HxuyaRC*rq@Wty4^AsAwMU^{AGEUcUp;K38YTEIgyB8SY~L;))o0ZglEIP zd@RE7auEL7J13s=-7)bTyJJc9WhJ}tm3X#SE%DA@B?BX)eiCq}@*I)!&S|AN=Ukgd zcwzr0CtFuhV)02^a~+^r1|O$<|$RJTEm4e`BfCRVa1U5>R@FWf%Wzl)S?% zc|h5)X=~K=&4G12$2Rejvo9$599zjt&dxsPTS;Zg9pRF%MakDv$+i?K*_Kk`c@uSh z>%uyp^IdOSX<1w9{e5-zIjxv@WCYbGn{wFYMcT_1o;UrqcIKS(l`g3+J-H*b)bo4f zXj^UJRE*Rm9yZ(LwW9Uvs#F6oS?6ks05vOH zZGnOHs1D9Q)4DOHc`M zv8d5ccs;3B75$AEQ`vH+7F6O~3!e{Pvmzk}k zm(POhFQ6{#%`LBAZ`IHAPBY-w&nQ=s+w;AX%MT&^U%fdz{Lp%5c^<->da?J1@W1tD z8l|nzM*h2c$CowW)he~j2YE3a?)T!x!!5;)f%`8AAxSe8?*EApk~ov#?m!4hqV%$K zCqhUvjfeX%LP%0o;68#7l3Z>2!C-DFyCtQPi+$GhXoGX#0?pxn z3Hu&&Hns#cd;#??=~)b3TwG?=xAv8lSK=nsLiiWLe@|a2{AHdp_{-qm)aQb~-s6Vf z4gcD{LV~XE^M##Z%NK;QHl?#6YPt(woPX3j`U*9vD$_@K{J<0Hw z!JnRmlV82IXC(ZG;4kI=8k7)6Wv*h`Di8TCLTrTBDytp>7ihiIGp~U>%vc|2`#jDp zZhV|6hwxk1$doPM=}(%N@*ns&{200s@R!4%kKZJmUsmFG*^^AM>UZEh*Lygx&n)w8 zU|nxYGth4j_FMHEaZZUFKlBdF&Yaul}p zuUjTC`*p~we;%;9^HC=kuTx1cUJ&`N74N5yG0Ips8rW^@PHRmqPezKLg&g?X6?7Q5 z^HF9cVn<@{HsC*k{I2YdEw5i^)u;5>jXJEOw`~5|ZD6%6K)POD;6nU=2){3Jyjro> z&S|b&^`8e)!S_Gx%>h>D=`>jn^dyy+eK!%I>-#dXWBC0(Sg40Dr4RQ_@%u!tMWg-V zZvX1unDRpy2~XhtOB!hot+k-^XS&}%{^1Iv%+K*_)$0NllF`46(SOqWb5pLf=ppR$ z{tPdgUx^*!<2_crDqwTZ{UkeYF_#~TMnKrLFv**x0EN;+#>3YvR0JWfd-1(tUF2| zKjp?T!oFGzo#ji*c|M1rarX%AR$OShx^V8F+M z{v~}u|IK}AclB#p8EfZ)~}OK6-t?=%dQI81#~a0QFIe-V*!(ee{IcM-xyk z%|$P*!zy=&ww+e{<*=(*vp)uwVqc-%3exEwMOrFZ*f*cl0ysc1-4ESiit{0E9?KSS zJ17p;OQ0j^V9*~!epx&}DnslVU?tkA?VvSSSWoZ&f-WHGF^;6Qb)=LFv;heQmVS2; zp16TG#`y}m+*XHH=ghPc;KTPWpBdl~jqp$z6PcrLfERo&k?dHDYl`T=u3$ z#Y*d>sYdO?Ip99{z#P;pUtk_C0Z6N0IT?mN0H&Jr|9O-abT5 zS2+%|!9tLmS2OB9w%g#Q`;s+#+slCv#>c;I$+QUH_Xk)s#{Tb58%&KmNC7LSJ zayjMM?k)c!p{l-wJxLn>CdRn0@hraqP*!zUIo&g|blhqDcJ|`^^E$Vz_4*ItSA+H~ zTe=>4-c?@Md#SLv$Ev^Rh1MkO&K9`8^l$23&G)pHo@D7J%(8d`W}^X7)xFI5FP0X1?V6MlRX=_Z1Et`v1F~0Qw!%P`>ilv(ngXr~6VB4_ezBZ^_ zL9s}=iDtd%lnnjE>?7aXUk4jpqug>+^U4=?fHzlXqmRzR$?&t#1Ejyo>Z#;j%~aC* zmVY(dJJCCK{AKRubv^#y!g|3_{7Ipv=6`if3-xj_CKp|FOfKU6<-!rp82^kBZa}PR zg?+aFf-L?7^a@F*klvl3S;g5|PdmG}#CIyyWvy{*9re`PbfS|;VOl@)nNhQ+NCSmW&pjKP@j#{ga*J3lLo39I(N#-c)D z8-ZQ+vOu}7$8 zjz4*A=Per>kk3h;&j@#3nN&;j_b2@<3zoNFt%=t#jIp%UX+m@W0=F3>5a;*8p7K^E zZOt+v+5nLm4Pn+=+L|^*XwlZFIRq;t>w8vPA5QBfVLR*pPx4}k&lm$%*y&5mR)Mdd&mcF_VFB{;6tUVh? zwz$-NzC`?e)mNgb$bN-g{wH6$LJQ)4BO`$!+(d%hj4L* zahVv#B{Q7Q@VFSfwDg?4M$$j(vAO4iXQQbsgT9E}=yad=KOGX3bp^7*JV&jdZfSZA znBF00SD2jeU{K0hGDMq8TNlZ4c9{uv7og@xLxnlYfxU|;P7}Rn>ufD_+%-|oo@3^4 zJ#x5w2uNuwLCr9siUD<5G*nbM(B_PAbhsR4q9uERnR+5pXAA))ZDs0Pk^aSdssg^H z&{P@rs(J5IaMx_badk^sD^Vzx=ZRjKjeZuiYp#j5sE`;)UGC!-#A8Pe>*fq1` zya+Bg-BEL5r21DNL-W+$j~=SkyPVQtt)6Kv_5Oe){|G(WfcbSG4lrhpyk%JSL*6Xp zxd7pLEs}F~N1QXIBi=c)GfR6Suv@l3>X)J2Mxh!)i7pO62CPr}YYrhR@41j;{__>Fy?6Sv32%)f|xBe0Jo2 zX^ocvdEzp%{+E>psCOZq8f(9S;V*(~M9DsWW_%Y$cglAYUn|l5!clGu%59XFo_ndr zwhXVjE+eZu22?Z8msS`y4ny5oyxxUx+T@C zHr>8v{hC#qH{E_)^{P8A#QV2VW$ueA6KOA>t=>?*Y4e>`>rsOZ6}NBNjIxcg(lMU| z{5SR)I662EbSiuTykPC1)(`o!Lz%F$5zR4(+YR^$3yG+8Vn?AqS&EeyQz)Hf1f($ufFsVZ|!sB6GV$Jimozem0F{nUMeW zAlb_OF7kOr_K_tF4z+U-)Gs*HbsVZa4E3i$P(R{OMI4G-G%{*XZPY-NxQ#>2(3WvH zZbieuY!KY-94_6!3@_xFn3+&9=>0|wzRlr;?>g=y8aqL;JWjEqbq2)*2E`mEElg3# zjJJcL0w!-ju2aLg+FAk!^!oOe1JFVBwdnQubwCI2Bl0s%uV)Q#saJB^eiO5hfn#it z)~g|Z2{bbPNvl+h=ZWrI_YAUTrqtBWs;w_h`zWuLH6&`)yeF&JX~rlEYpTuerhrTu z2AwgQ0d16d@*NmiIs`%D8_IZ_t9XN1G~eC@6)dwBh>x*BhMK=>vQJ>Wv8|9w^KW6V7;)=#rL;4tr(y0bHjA0yk3v!t7OVv)$hVr?q zZ=z<`@#HGpsmLRgJFerXncfjj@2jpDkp4>dR^-sIpw3OV+~p3_UN0y>ybEgqm}l7} zgX^d*3R<%6rr)p(f;;^}5(x7iPUUERhWzH7);YSYJ)q2g6I{7eZ+0c)WW|abAaa(Y z?4Sobja4#kD!}3*zjJ$VrL?NYpNTsGe*aHHzAQT9`9rTO8|x14@?}d|GF)%qjNWm8 zbiiqhI2<@MTY{wM!c|0!G-)%zUpQX%_~+rYgGRM$`^Bh6^%{Xa6YCdyRi=M0Ao02_ zJ(pX*a$HiiJpWz}uSZFJa|f)mliuODHxNe_xdnn&X}}H3yxw3 z*Wdz@_(r<((bJqYt25MEFa5=?@~wSd-|7s*?djVScHh)@!dG*E>`-C0faFFyAO#07 z%Pf!P@AkD7g5R_04KG7FqdDkk;F#>ncoTn_`md-FVuX87z2mhL_3Sloz0W!R@E)w( z?u#*6+sa>53HeWSkJ7dWe!9|-CmbQ-n~a{!7P7XoTef39q+g3EWpXXbG( zLC@oBAA^F__9HPm?W?^CCxMEa)nc{tzL9@RH|=&22C`Geis;7939t{xYTH|8}-Yn@4=?YRV_xEA9owL7*;U;f*c4VL+*LIyF{Calr>nfQ>e;wF?In${+Y1u6!P!y zo}{JYOx1&VZ+u7A-4vGHJ(@$N@-=tJ{{+gr*(~ptZUe?)mK(z*tjGAtK*;|{cbqAE zE$TM*0Yd)XfCVpbLNatWV9oC0vOTSJJbaz^7Wy-B*v9UWng_BFBriziJJ7=^^ww?* zUu}l`6G2<*jfCGXp-E`;AvW2`SK#$6Dk$c{i5$ZkGMX=@y0@Ctzf$wo#yO{P89hB` z>V&CrwyC2MjrGCV?ulj_ei6(xUDIHrKh1Q%3Oif|X;odW(eOgt7ATlDTg2-%h^SoG8usz%+w>1n(rKkQ?s2-tyD(P z|6!;EP-d)|6WghpvG0XQTji@`kO1s0*zq7d5=?$SjaOVG9%9iH$lnnhgZ@8ZU2EXc z6f*eD@cnRrZzuPKXI`v*Fz!r&oR1x=Jd^iaocHKeyXbZG40COghqreo9-DPH)wm32 z_o3X>j@_+7it~9Z2S{bJOwPm_S+h)G_;hgC)vc6zYsi9efm~Mucf&Q;#Mba#&VABe3Fevf^R_9Lu#^EKN&wzd+ZWiDQm!YfXd<7;si5hG37@A~D-PQ1;OVcSz7 z^Ltc94u(4g%%#89^kDnhI5z%n*U23&*n_Vi9cmY10Jp|=s%X@7ud_tBou27%7gmoHG9Do#o7C23{x(bVDvKs^Q;-@XE?{F=vxk0F{6Zdj z{pLVwZ(Haucj0{wWru#G$W zCgf+w2~xr`v@2`2LI}e#9aRoM^m$SM+-Ln zDd)Ond%#i5v1ipDa3@oZUmt$$8V}(yfItYH3$l@a3or%0N<8=uC#B#?hM5WL;eOmG z;jaG=^N5AJUha1ozkRGlnnF<9xQjuam+>CObndCP@|Xg*&igSdDD=VBl1p;eLvuu8^)wb?Y^ByFJ@jej$a-gIQ?>e<=ufPA z!!>!-BW{g3RWv%UDiV$soh*DYQQ?0~_|h5){|0)H!{|ZP17jlL*AFP+pWdeGeHdGg zd7Gkg9j>&WR{!yAa!ekL-zJ7q?x@bnYG;ec|2x(0NIn=VtT+)eFp7b;#kdH5gW{T? z9e7g*-LdsmX4c}?tzE(!-+Abl`7!${mLMIq80G=9UWSh-A;Kr{dgYmTHB~DuRHtL! zV^J_hy)I1q&v3m&dMVf5na1m7KxguLnPr){oB5z+^#h@hU8~_ITw~qi*Qb^3D2{!9 z>A5_Qt5Wn03DO2;qschyTGttH#1k%Ix1JUgaksn4E#<~`9t@;jX5`}1eUr)Mu3#$Z z;nAJ*yaD5RX4KfNo@1i~-EE$95tRU{mFVMKNqV_8)A z!Gw3Lk?`v^;bzqXV!**ctdi6HIR}5K`A zvXu2hmqNW?DqD5{GUERUR_w=l4{dvSc5Rt^7G$C~dY%9_#5dIPMtd1PqL~OU;q8@Y zw!*&Z4p2kHb>aOpqa{RqB+lR%k)KnGZfUX+se2jT4c4Pdn#$Y%P!YB4h52=bTV2G_ z8%}w=?Tk`p4byfewr1Oz81c4?#8BIb7~!Ikfm%p}la+?RHX7e*F}`8Hxsj>q?!~oI z?iHO0wdlK$y-QPbytuzo`U+%74?>NQQk~suxF>reVLrDAgVefvbp~rJ{=#u5+x-%M z%REjSD$kQ0SMYF>$D+%c_BE6>IM0(EtgRNiZuOu;WZoVulP88H?ZGm+gRIxlH~p=m&X^HmiqDTgDHZy55k;{>VVNQv?_0_WMdUzP(a*HN1Rb zm?MGq_+@trR#DQe=PGGlK3|ER8Z)UU2KObTn9`GfOtqMD!Ee1WC#{Tjk0=FnK2}># z6{R+N@tQAiQe8&rJF6Y8$o}mVtW}qud@MoMEx6#zeeD6}b7dI+%QLFx ze{tj|EhLZfSPv{&o;;{b?ok3hz?B2;XI+vqp{M>VyR55|PUmRVL%V-iz3J^(#Yr>p zt_Sss3Js|x)$f0_Zv%EiaWWE;oTEBsPd|4gS^GgN!T11gz}#!XtPZIyv!|aw0$bIX z&1X-io5(%KNq2?n8t+bWcS6>t*NO46rb6ze=Yp%PCoQRJ356It*D3BJa4RK$;2|Uz zl6DO4Fy@wbPA{v&J0ZFFD;-YEp07>g{;AwQGW#lR3inUu{t?+%Xn4yC@DsT|A$z)( z#r-Px$7fH{V8;saYF`&KC5o^8`&vMpLd zYiu^tVzZAyHmIpM<~inFdamYr+sUnyoF&H~|KuHLf9V)&|Kw9fZ#Vkxh>@Dh(BdjytZLlIv^MIeWNUHuNl8-RlbPgH+H8=w zCHKLzZ&!qzQU_WKrv`n;4~<_Y}XG;>-%h_k1Rv@J}zE=G&9r;fBN#Oly8 zZo<*)pe6Dt)6xL<`B|Hf(!lPJKGG$uMW&s>+Wb^0+t*cb`@&;O^*-0WQ>BU7hxeU1 z6z7MP!@M)?abFsi5_hJZX^4~b*pP%99;rH8I=<~=SYIRyj4fx1VB;e^Q znRO;>C*I>cJvGh?n~HQt6ZRMZGX<7Pl(@1pb?MKXo|LYfc@|+g>4twI_j}Jc)5%_? zbfyla<30(jCVk4WN_ZdG#)bSVLsn3S>1nX%SZ3O`1ob$K9he(o2TnL#(7^tkq@MME z(MvfRA?JTb`zi0VW$*28#qZVly^=z5f*Du6z4KUM=64IO8u$2qB9-=$m5Wp*y zM*aU4w7LzLkAl|eX>GRY*t5*VZ?3fyywE12#&?4@b!_ ztnmwarN_Bj&UknFV9f;fJ$E|Xap}w1%XkkZ|8SX$Qhj{-CbZX0)5f>GfwrxIO`g0n z#c{udTWPB~^K2Y6&orei5B5O!o$xJyGlP=5E=Yzju z(_TVt(^0#0@V*cBL>cEC;+ix6X6%E+ciQk>{Q>NM;%mQv7d@xv{UPoz-yoi3th_yY z@4evIau$I`0?Vx_o+=kK0PB&J)*@Nwpob79Q75B(1ogb)tNoKVoxGW1&LH}L9jCp`9p%Qq~( z@*i83!sflx-Y6eg?%vj&eKm-?i26TkM*mlzyF9%rKeu)6%fI{6Gt;j6C=`0bu&CQ| zrk(nGoQk$??+Urv@vak<9`Rc-1E2LD#LaUt79r>T)EYF#*6mwjwn*WSEkgJ5ne&zp z$m%S(9Q7_my@{$Noc_<8E;ju|yw#{po;iIr5354WsZ<4Ym)oR$G{&(5ZRnNKzJrJ( zKeZe?aJkuXPP64^nJt%h(UzMU)pBS>v*jkEY_l!#`}A?9uLwMKoM>dU$cV$nDD`Nc zF@DVt5RL*n=q-R+)4C1+%>nBvrsuvY?Gw~9LdL(!7`5ALpJf*&Y>4^h&b$6n_|pCx zue#z{W!}`id*@xO4f9ZQyv{@;!h(;Ilclq9+j82s zEgz$&1kSXhB^+~?p4^>5{qa@w56Bzs)F%;s)5oXB#!(pjaU0QtYR>p@H?v`ye4eem z{cOC<;KoRvKI_auaGL}3auIsq2*CT|B#f!B^@M!t;;d~3Mc(c5Ei6q@j&X2mcTFmdQLia{b z>!-V@^SB@SI8nE7aeosp0a1v!DLeG7+{kU$Lp=Ruyc}P3!*3{OC(pSaH-Rh34{OLG zH>_y*{p1N8V({%{AM-`sUXI|!);f84orlo-2n zCGKUzFI&LZNm~sVNI25MdV(Sty3@S!Y+{mtdJg^wThf=qW)z2DiAg*%<)8DXf+1LIUloi$t>jO+{>=aYOB&~a9JF7Jsftu>nX}O^m4p2^ySUJPTmIzo4pDf3q)t?5v18-ch7U*fHx^C zRNvX8`nI!6A8k8(`=fN~8azG*9DP6R1+kpT8g4&z-&vhn1`PmT3jJ-6^l?4&=Sv++ z=3||kGfGRuK5TsFzO@CdKMGW0RY0L}nk7fkz%FdJ5y$GRPO;mT&ULVs^mixc;_UW2}3&4BqGu`j96Qu z#wN-74ZS3L*b14b-Aq zOQ@ltDX6-k$AP*z_Cv>{JFP|5b73I^Zx!j;_@!8k7d51X74q*evBdoYwaCXxn>y16E_4!Pk8C`%Q?H!Z0?+@J>;7ZJEO32?G&{{^e*jiH2 zh8D%C(H_oPtYq`hGVfy#LGHL+mz4~SHFebXYNd1uxF=wwiANe+ z2jwOy)UL9^wVk(FvF@buNsAzr>z9W7uLYQMUMHJg*uiGZ?O2fcdJA5LhTd|8Q#qnm z=e5{+WArM#bdI+er^MlZC1(MA(>dCy|FnQQ<0PVApU8Z?@v25AqQNH2%62EyoJXxhs!%5Kc|+`l~_H8peU#YIss9yFsgRO^pJ z@{2}&h$rPHybi()e(Jl$=6(?Rph4)E88llMMU7G|R;QPXY)OKP%~#A5vbjVbKqnh@x=X-mEKT#2jc*Z$bHYy==KKg2pA&dQzO}+>L*If`N`y+lxEVbP zyNT#kksg)MNq6rTK^OPE&)71#VHxyr!Fxdqc;dUQmOU@OyvV(b;wmWIhkhV+@HdH? z-r{=sG45}mUhf8t7IA1}I2R{q1>o8{aWB(4-P*x&3XpbQfR7PYK3~;gzT{d)W6SJb zrjCULmAb%9jAlu^=c#w~dov1J=d`4hN#5A;$z@ExE|{)u8B6aJmU><D$S8JH_{wQb7ciSk|UWuJIJjjW=sTE zLJJb3PZm-_;}WwFtUu~O=qloFueYF;UMg*0`^j3^kvWzIn6U(%k%n{x?O8p#Tw5Cp z{Yd%!RJat+Cu=3h6Uii(;gwaU>-|{E261oJ>utfESu-#DVH$67Mjsw;X^zSReuQ%& zzQy{i%NX`{VwRWe((GSl?%A;-bWbjx5#?r%F0j zCnlC^OZ>AIq{K}=%=7=`Z)dDV-agQ#5#I{9J^1#(9l&?phE2;D{yFxK)|kG#KcTGM z`=(b#ZN~Q##a)?%Inmse3F+O#^jG>xm*|!N$??qjX{X}=$s<&sTzs^%J;JT7uW89z zuX&}?PdrEYoeJqlmiH5A6lJgf#QTN61X`TLC5F~GjpILGr>-x9-3tc2u4b>SPYL+Y zW12maw0ogVm%ZMDRL<@!{3@j$Bt7sn6>xefR12;0vL+hCC<#k%qpAN0*8zGZfI;oB~_a}3| zOwtNYD8N<2NPu*9pe#)GCVS&rjWu4JC(fJQYC+gxuLCzLK$!(Z`#ji)uela|LAP6T zTiVB~x}BvgwvHP&4!8IgXG4-nTC(2Lk){+-OyXiRR?dhe)4l6G3HY1qNphE_FZRSP z&haLAlqHK1V*CXSOJkPgdh){2NwH?ih#UjD7IDO4_$k^L4`rL$(t_*E@Z?Ec!Z&F&~oA~H~k(}k&HS4MEQX=oiO#ffKt1}96 z&mWmT*fE%<-%zklyVf6$Nezn#6-GU^xBG6jFBKNIaTs2|`f#YcUD#-kk2oyH_O z|AIEP#=I8qL&d#EWOs=-rSu_Kk}UBq_D(D<@sMWLB7|AJKPyh^OjvC3=D?+NEb>~t zs{ygdWATpj#(QjM>ZdR63Z#Trje)&AmyWBRyfVLM(vf;}}Q zNy{2fJ({Qyuf0)hJ$%57u_A`|YrUq|=qDcFPJBx;4TG(MJ?qelhUBjQx|e1+Bj!HD ze6|iFr;zLMUX_q>65Z)2O^hpDJ&gfS1n*6rXlbr48haV;KhsIqbD?9H>nzYhB8h_d ztPYyj!>ze&=$TF^xkzYT{JOK&)-RxS2jQyY-JfR7g1ynCe^`GtTn>Nx3>TZc4GUNs zLH_##+iuLICWks&iKlk=$a^q`LTl2}6ldNKjkVdYELs(#%q=E~pZ*gbblO9BSeu@! zu1ljjP>rq(LARS@CTjdDYRDR_P0v;rr?H82Ygp1p;{MvVh8b5N-C%tZUDL}=f273b zs%DY_F50sUIvZG>2_|vcVMmq0(hyqpvz~#}l(0X+>y~Z#1#yFMH+P+T* zjaP%l0q{ct(k|`y;_qU*U(%$$R@%D1IOdq7|GS^$_>iB4GPJ@L*n{vgub{2f{flwg zu#ianx4Ku-JNhf2pXaNf*+q;+SfS}}_EUQj|514~FX9z&FaEbmS?EVuS&%hDvtkw| zd15pxV&3r{@>&)ad6TfC#2EEEk^yKwlJsD&%}u*dJHYEqj}J(yivEMK!y}d1NYC}a zdce}!AzzyWxOTj=O0t6B*&pMM1aX*XN98xo)$XysDz?9WEBaT~cvt~JZT^N^A_F;C z4PLBmISs;eVa|gcF?`>ER>&4m!-Csq4C5@VYlyFj7BX(3OWJarKsst)z)PkND)l%S zXN+j<$`CXjZk`%?|DqB3Lgr}mqQ!oK+jroJCqw>`p^*QkpmE!b>5q0dcF(VXYVlf8 zMnS8!D~Cz?^RU>)U||xP-kLXa{>yCoe{eT8gmHR4dim4c3^o}XyGxN)4fn4yq{TZ` zSkoy;`)Dsur=dl{X-kpzzOa-)5(3l5_LZZSN^8i!qHh6QDs+x(I*+y}`Buy>*!jcX z_AZ54OUWhh9F`Wj%R9b-T(%cqb8OBvd2X9m(q_1)%{ryyL5#mvs53_R}c=oluZ86j$B(nUvS$!CyT{x15T@QK$diP99}BRn6FY>Nh)EQ>bASDg2lLy{~^2ykjEu8LL9vcm|7Oa zdwdg9c>iu10UNaVMEFu@%u~#{MD%+HNn24#V9o2SC2H!Bv{&*SOfcJ8awd0De{X;JQhZsnfchhiceDZ;j(dq-u1w=qKiUUF zYhz!MMr|WK*~7TP&1RH#C|BjWv&%iid9F*%6Ih2{LPkq8b82r(KUltyxz|913pEHg;Tl=KgKYA~J)zI>RPRb8rUSxQxX6~T!!0aqr4mQ~roDaP4A z&HgU`Dp*%_aK?b6hSfPO9dOznzGa^B!MAp3^+Ay-FN-?BdXbUlZ^m9gN-h z#aOGxYs#W)19^Fux5g|g3FJ8}r`jzyd1MV^t+NYqDe>?Y$bQ7fv?n$Ob_GKIKoBDy zb7eTtF53g83}a{5H=l+4$)V*0VHcu}Mc;Xa#tw_F&j2 zV*DO!X#o3Ruyk}4pG~7Bd#YC@>SOG+74fjTHa>e$qkKrPvsa{L-=g&@ChXBoFQFSvvNNV_8A}KSP-R`ECwNq;p_j z1#!BN4nU;`s6P2-os9kKdBIVwQ-B%MoNmlv<6&K+zjLhp&+Q_^53x;8Mv$e~b8-QigDHZf}t^0HE=tD=Qu5&4p#y{) zwXce=03WR<^Y%Z8Gd?v-+SBD<)D64L0mkSRJ|A2%yAOXYtPv-!yI}df5#KJHg*W2c z1&i_Al{532AHv0_@cj+}Q#S`*B1*;%5)9e1f^Zh^E zxpUF}fR1+pu`d8xGW73_zfUZpbD$=)FU>EF`0_uecTz6w6SU8khJI-5(O_OT=XVG4 zGRAS^3}y_h@?E@baQYHZx+*XR-iSGLb<4Bv*sh9LnwQ+{o9=~%?Xkw7--=u9wAP?i zkdMz~swwlY$ zP`}2YQ9qhrX)Mfj4>yX2@E+~a&k~bWuhc8!9whc5SJ6(Rw$7EAy*>-t@^aEA9$Mj) zGFs*Q6ua(XHrT^gHdw0!eZ2Le_kFR?gjG+-|8ft_`XT?XdP4pY=y5bZ8*LgY*|smn zUGE;xPuB8>#gMm2r@CI0I-Ha!PnSEjb^NsTqWu?poqbBHt?5$v(GKFyp5}F*&`!@0 zdAhT68tlcWm?zR;IU=$)^zyYK(|^=opQeL>9Ligq;*n;sPw@;}&v7mDbdW19_k z+d_B;8)w|dNhYv%N|SfXG^zdM@Vg|=TFH~SvmgxtyB zswy0|jebY{=Bu>PjIY*4A^-P#FivEBem2QhH$Vr$2AjBMi_DnR30ZSr^E%cr8#|s< z^F@8}*om!gjkHdM**b6cIa`R6WQ^`~uiUB;r0ZqkX`(hiVU1;NJNU|ipRhhU{WE{j zwtdupXiYwR9~#+uY3^h=-~Xyyx3v3ztn+i*6G8uby|tO>k>Nh)G5g#tcx!>$a^?We zTG1`3F~nJQ24`J|ne@x!RBwZ`N_$aPCFC#bhMf<{dg-)V5ti03l-={Y4bEx|7@W1K zpExUrb5)3s%xiR4qbLR@x(qL&?@fBvqS6Y76GKnnTt&-Ip zz#Hq1Ut9|r0Qk26|B52mTMPPAVWlJJ_jJ<^sTI4`HjcTW2PMvh(AsgswP-$4e=lT= zES?QCvNQ%N8_4!dC9};O1IsIReU!x>KZ1ESI7>WhvNX>ISB7WJcx}y^aawDa40&VC z8qP~`DOxg*z4Xk)+FEh;Kf6;MPpy_7KC4ZOI;$ORp4A5Z>7nNEPUdj4XFSj29h?W- zu}1Y(&{>b@$w7Z!sDk#V9$>5hbR>D5_$V?z(5cvy^p@d1$Tbba?eGWv4WUBVW*T~2 zryeeMcs9U-4AHRJpy8`swnU<$5~gC_04m-JD*ldB@m5fgq4fU_6@LdR7It2mIwUDK z0FIyOzR}9==lC2`E9grgY;67wv1=DIZHJUlvdqBtqJCQ5*A(lg7vje4;%>TeuKLG^9~26|!s4U(0t}8qnWmXIe)l+DGcT zj+Jj{Es;Eu3OiF6!7JI#EfV%9`f(42dKc}0M|xLXf6#w@e+J)iacxjNgqx8cbW|q8 z{%|3rqS~j^`(T%Ns1~bF=6oF zqWfA6&dAy1IVg2FiUj@l_02%MD>D~4(%uhgIZZ0fq2O9rWkcM4iSZ+o=XW6-~}k6OT}cOKe->MZI{?Ly;>3m@?h-~Y<#_swqYRFdNM}a)w#rADeftlks>BnAG%y64;6oY zmicgkf*TcOZLZ>dJ-)NJ0nioK@rSPQ7R!0xs--83D&$j^Ed*CRDb)j=!uc#`k1#8urkYwua)G1@^xu@wgQH9eeaiggl6k;FZ4;y#KEcnb2Di zzVsZ+$iQu=g0_rPC5h7EhY$u%)s?_wctjC&T82^OTG)4N8`&j~oS|DrekWjEH>cQk zRGLRJo=r$TCOL~vNeLNnCmb8ux%6b`779-|wKyT6OHNSQ7N0t@#i}jUl?2Em zCy#7FjBRp{4Y!N!F~9AyCd3>bdFuWIx{J10ml8Y+K0cA4$HvRB7s_Z(Vb7jtSv3d7 z!WOXPTy{#brnMbC&r-KzKZkCg(G53O%_lfFBl={-N(vkNPiA;pHtJuDV>F}B{3pp4 zYm8lqB`>)>L*-%R`eq^tEBFd9WkbOLJ2jjO-i;UvW>8uA!@xMB^2r+t2K7dt4F9Vb z1}2(d&S7Ap^I_~zDP!$)SBx?3vHARi^GEof$TIOiZrHzx%*LRT#s8)P&dxI#_~*85 z-Oo)OReDY5x2E*9f0Tdz$tPBRP}ERT_~NQ%!PRSSt-5pl=Ig5NSjSdxnuU8djNNwU zDz<9FYF4#*bM-B2?$}(7uvJyJu~puxJMO5ygRR-L>Gn;xtX{Jjw$=&0`nGERTW{1= z?EszLl$i2-oTR|5*58XZl9?i<&UO?_mOFFKrSFvvsw19ya$`~4-+xy4-n)xkDP<+A zeXq@*>AU*T-=8nEW=%X)d`C~|O;=lIrI)46y(g{k^2;Ajz5b~u$IknvYj;`fjI=B@ zUUl7`ylw7#@4kE0xSFEcxb%{=n*eha1kFrFWv%%vL#6tWs;I&8>b{m$&w?6v6z8DxYHB~pm+d^B#gyI zJS9kIL%iUdYw631BazzCiR zf=eR7W+n(M9S@?-0zVQz%{M%Zxg(*Ki8m&G3$fj-fKo7o>*xqIiMChnscbpq>x4oFE#b@F+3;Yi)+bAj_Zst z#;za3x#whKIse=A(F{)K%Pxf>x7*idjPr#%{IopYPHSb#$-I#1(Ug=|rlvhLf>% zBAW7FFFZ!c8w5PX-9{Nwf4rSLkVlQE0TFwn;ki1Y5S~qjCu20>b%*dUw)qO)gYWz% zr|4Z*u{0q3y(EdoTE=P%O$P|gBx6X6jKJ~?Br^Dl;`8u@@Xu1UX~U{jmoaI}$m9{2 zk?oRQwp$ddVpC!iyP_zuN}LjJPf$j}wgx4{Kbjvi@cX};2LuRQ>%;E%|3M!0NK5nf zP5AZT`|s7o?vw3xvVE&;-zM9)%k~|z{eId0fUMNZ%7e19Q&t|5m4{_zm#jP@E001( z7+i+T>7_tWP-JCDdMQ3xsgsqhva(H9w#&*6S-D?U{`+NItWCbIdQchvFYEF3((3KkTzRvczNSl9+ z?J@Km^7Yl@qO|&N*5iL?9vhs-m=7*CR$n+@UVIKw!gKDsnBSZh*cQVt&B5f)gCEmU z*gt!aKYx&a&LDrmAphJ!{=z~2d4v3}LH^<>e;#C4*yT{LmBII38p;1CQ})7NlycuA zQc=o!d3nlx4)`g~`#w_^!)=F*K~f@xJ^TX(Q^sNVTKRO!eN=a-Z?XFS7i15XO!YM7`;kXL>h#U`|Pf<#(+>-JGECkK? zMx=w3IG~&rXqe`!4fzJ;qx1;;D}aB_fFBUP-N%%9QTd4Sw|JORII#SmQ28Q0?{=o_ zj-(^}7E!#QV?iBLp5pPG?wjO=DfbE7KSUhKVnr!iIE_S_cY(|5NSfN)Q}6--{6vpq z>#$d1rm^fG%0}wu+{%<0JZ>P(JqV}%GPo^v4}uqUdg(5vyaXDW@TimJS_ze+_9x!T z*=F#T@GIXR=vN2D|7XI$_`tgZ{W;)O>PvzydEh5<55{*g;IM$YAUtoF@DtOAhR2go zL*~QOp~L46lYc_P(D0Q%8#+8=82G?2c%m_f#4~M}aK|wCtHXq+?HD?L=P>yf3={4h zroIK`Ou5ErFV3eqa1#&DyPhex;+Oc|y2ElmxVR`~Q%M~BMYLrjcwPGzQx@{{VYqO= zTeyfR#fU3Txo3OK4%_|K2Q2l}8$=l$_cP_UJpQiju{)Ie?GMD%+a9#;v^-?=85MDa zixV{X4u`AVuI#YiAM=2%-uj?rCqW6AhXFGeu*E4C!ie%Ju3^fbu&69f**s)Xx>`! zjxkRO|MLe2`se-0z)RF|GV=2BydwNZ;}Vs#9(h&pxXAoM;q3^&E-IYLqVQLdS2Enh zFXVr-jVZ@~6R*qn1j{^PlTYyKye-N}15T5T{K9htrC;$n_>G50a1%7hdjoTsk+B~(3Xv`b{Fw0;HNx=zs&TDa-M@fJ*pgmTMfcz^YBQUh&*z^yH3Oj*oHq0-;cGM zn9^t^-neH#|51^i`b!?-pM!g-@rd##7*8c$1|7r$gi8+E_0t=ff}x7fw^V-}enW@KsnLjl%DeLyWD64QC4HVF^)u!6GSV5tpRKS++r>lc^pN!XcK~aX^?+0{3_BB z&rp2De51_4V-@8`bvS`|>L=u8g9Iv~!$L)x{UwOb@AM>DX zr}ZHV=T|D9(sck%g7nLCL7&o9D3{Z5 zpxi-iN_?M-_1Rut_Q3UX%{r`CqQb@4yJC~U!-PAfxBieR*&Hr1whGv5HV)+X#in2I z)4yv5mLc-20Nfd#XM|QF&!!Cn^Zbs9kBHZ>HvzQxcu4L46ySe^UoqYan!oaxSZ77> z7IB4$s~J=$fm=K3OLJ;b%7y7F5NEVwBu=!$zkru@h;|V9PDWZo?ueunbt*($GRhSA zDUS>JI07r;W+0AuKN>%Q!^7(_4-bKZDCc*WBZzhar`O^C(V)Bp?5ifM=&yaxfDe#( zxc(~Iya4+w2K@$(rRhIq%6gO~^8Y#fB-@C3HSQK`j|fkQxCFos*SB7I+E^b(_g6uW zz}-w~=Jl%`Aaja*8=bX6NPL!YETS1oq^7bHH;OGM$lqR}Saa_Q70b}d~3_sQ%{){Qu)*L`vf!`PZ z1-WEUoWO6|zl?N)@e}P*=!bmG`{A7f=Naq>$@ijp?k$@7vUlg27CGDcB2hdxas^w(BxRx(B}%G zUX7p`jV%J_X80+;=rMv|DSr?8F3qO`)`PtB2f>QCCd3&yM%qcl6`~ymj{yRoLZqXy zP{5{whjtGtL%?1KSOsySu6Y>mvf&@xCj`9LtgG;ECVq)3t4WqjdPi^;c?Tqk&)b9Z zR*{})^C9}hX#5V%z;RI@7+{4G5<` zC&o#~$4q$@e%kXNbavpud{ImDg(&Oa|1`!SG1n9S65d}Re7L#u5b`hN`41f11Px#L z2}5$f1OPE&6Jq8Bg-&?o&ozqx>j77cxq8-+uQj zWEO00^inA<&V$k%8nAdiF|FhZtLC}JE4gQiC;;ak}Z)X*;ZrOswBs0 z$*wBfN@5~gt}G=Ev{0ZxN(0UQ$g%<2ZlDjkY$=7dP@t4hN-5As$` zERWp+1^(YNk9)6VC!`NTyT9ZU+xMKAIdkUBnVB;)XJ#m#uzw+^0Y!)40hFN|u-5r5 z*p;gQm&+*$`mY!G(y~(C`(A}LLq&5h+T8ts-wIf_x&D=Uf5%P>k=E?>RQ6$Q<D64&3`}AZ$nzmzsBDOylk_w z-_Y`?`<5KXb)6>9np;jC)`<1payyjhP<=dT$u(M?-@5?!%)>{28J^NpIsNaE{OPx`ZohSyyB;m<;4#t-93$POskt<@jIw7tZH>x`Q&jexh3i~@xXa{Ep~1hADbsk^W#Syk(}v=_*n_KS;)%CpZI$4I$2*@rZ>Dn z>-OCI9!FSt-RgAvG0&E5!bzw5h$k@*rgmATpLSi{H&0qkcPZwq<#cr!uYpWSUv(KD zP_Wi(o&P;3JGDK9$FOpd7?X8)HR|A4{5_*&>9$EUf4}-W(1sk{Vbo`lY%f26JyZO3 z`yXw=+D)av_0+xz%@b9_bo}h!Gv9-NDZa+_A7s9Fl;QkX4;WQAU4|Xs*0zzTU-E>y zg$k+Z#NLm)ypb8v*6lAu?OO0IbwbC*MM%Pip}1YhhsyHvH^R1c;;O!-=1Nax&AU8a z>SNx7KBf}zyU7gC-syRoNsCvvSvuC>Uu2DvUluBRZ^D&)Elxh@FQ4)!6}ojtX0w97U(SM15D zd>*ev|0ZOl#>t-A-N<7h@>qa8DzFe82EE-qwU^oSw5%=#-;aG$+AUhYy{I2lf!$74 zUM1}^m+VBDzl*freHX*AQCYVn_r33g%`W6D_dbax)noHRa-C7@&AvwF+l8>BwasVF zl=|n+Q>WdFFw(>Fv|7Iop04+pq<(4q-Sx6ux}9o#!>RM*pFw=mO&wpiy@QDVN+EBj z&!KXXJXRuXBfd55C&7!GhQ=QOZPP_t<9}F|r^Zi%?tJn00$)x)1f%-#)8zUDEp^_IR)I^Jzae-r2* zZOvGh;RxuF{<`%{hYg|(<$fPjK3bc+>l|lolFIQ`*g~rirptdDU>{&jD+ajSE+E;E zP4*4YLYHal8PT9Iy6{TOr$AfFaO2xb$8wF|3cMU2OZENnD@yGu9sgP2sV!-})_m*- zosG!Ptus`%<-k)pbbQ?o2VloazE!`2Iq{{nm)ZOtX)o1HEt~ji>2IO=X=p3uU(4)C zq;C@W+I4NyhA>OYpz8&1g9)E6ZQl-n_S2;_&~2c1tPI=st%OJQ3#1eRMiJcyLsEsQVV(PdGBu z={6pNmn-H8)Ah3)dPp?fWhcE@3Ov-**7@(EjfVj1{08iF4lkPK4up{mHBGHkH*D7X zCd!_e^+d^@(CHo?(dCo6uJdZ#G*?%2*t6%)4b$}A1$s2rX+CtC0pQyNelG7Tw`kk2 zw7p$=6k02XHO~$$ozEHbglXP>3clUEY5WG1bw2!kpVWKak}s{JU;DV6|L8m)xKsBF z4nIvOE7j?*ZkOerZ~ac!(dOIa{I-1j)!`oo{a1qC(Zbt~lAg*Z<_zGW8{fK4G~LRh z&}~9o;{CS>r#hRDcO7Tx9Y>F&8K%YXC5sy}kDO-;g!g z{N-iWv@iaYGu~)_N?otxca^pYo#)L+Lu0e1;rsMleb!;-M|HpG@UFvFLOx`3x%(Tf zBUz-QJT#nFa1(GO+bceSa^ml?WP2&bd+@W z!?)@+>pkv0FT3viS8Lsx+ppgYnNu0u`ROvPLYN#6=9XzC^rrhL=^DZ3MMnvXVXWAE zl(6N{u|FIo>{jSwIZfS0ZvxF{p#$aX;JO^s;Puurx;pK3pOazbZKnzGNe8XZFdVEr zwtlsOx3y*TseUQ_FHkq6KRUl%kWCVBd48H#yiRx2v3vh9>gq7Uq+ZUgtJ!(dX?f0<^SAdV_$LWj&&}tG8?--_6Q;}kjhm&NNA1+@>#xISua`asN0ZA2 z&^}uG+H#}bubi9jT?pGakGyrh&mx@chw^-NcnIa4FTHNRHzWNbq$il#;w;KZvZ5b? zZw0&*-|qQ}ZqNG>W{I#;yJ9);=L@`3o|S;BaoNibL;4a8Xyog zjg?%?|2*T)!IO}d#d|6k=?Lj(0ds#EJ5*m8s=XBUx7RbYNUYt2t1gfqfvSl7AfLX6 zd#b`BSOAc`S38U41071U(eREnkc83D>vB0X9_)+5ys$ z5ZO9&;DJY>Kj0hng&KX^B1p5R3h_v$O^TmuzEQHqhlL_4+l7L49p{0kbl)xNQmTO-bIw1J9t;9cI-$oh`lkAQ4E0Sqsq6ay>iZhNPHlU(K`8K*eYh856FN!t{p^Es z+$1^#Pe10gOM)*hgOh-@?LpxeDY#puzZ@`~8N_;+-k00U&zCuW<$*wzXRq@eR{o%r zH|g+Jl+CAjBY0fFx~*jaQ~Tah`zAX5*I&!N{4j-)Tt0;`*P2VOZif{1fQv54stp$o z=)Q;Yc?{uDQ`UqZD%1Ix&&j?==z!9bL7^uDup{vw|GbM2n@Wa7!8#Og$@m>i|Z7Z6Rxm*^J^OM0~)9bp%JJ+rm|7%oV=-jQL z%*@V0ZhC9HBQ+Qv!Jn|EZh574Z9nvkBw$rMwMs9UAc*IR%71En$5fM^C=da zO-7>OI5XiukThaR;xAQT<^zmx@vpevQ<%&P9Ey{k#0^&Y8T7fc(ag+DdV6MbI$O*z ze*#w!d0Ln?Ju9LzvxR$FydeKACJEY!iSqXuA2U`QGC(<)&Spo`V>|8e8CDG{8r@r* z8Y@iXrkKCqt8&<7M{Q^3eaO{o6|*+3gZa-}O)-5eris{rGnDyjIp1j{eri;oEqQf9 znRyOB+s@jJKg8LJ8@*Z(7Zfwaj4D6#+oFhsn17X$Ly?(x3kk$R>C9wqiY^ONDTs%k za(=1N>}O~`&3-@Dnw$NnBV~{|!Ee^En;&7SJyAPqHk-Lr_Wtw~ zx&o?bKj+bAiPYMtRhoh=&g1@AEHgEp8F%9kQ`2kqA4FF)be(4zL=Ebv@}b-CeK%Vs zR9py+=C&_DW?5AJsuLx#y-(J#OOH4byMx8F@{ugA;{1L5%oQK-%tj-Fk<>sWkxWIB z;VAlpSyIqBJO@ zVh(L1@<^BmDeA%^sE%1?&I-!2L?b*k&df6a`_K}pWj34lNbZUAcFzBa8!LWo2+ES_ zy63|*TG!C-DKr)HvuKIc&7cevHRAMyKz|1;_>uWlsCIS-+UpCbdp$0lu=?NebPapL zRsVOf81(}aWA0iiRPft;%_~0SnN1`E$w)9YR~bUZ$;mzF=hc{F?DwEDI7iLx5<#8J zTtHQ)$(Jj_zcT(g-#IJZV(2VvebAJthJ`BF1n-eOqlnPO%vT6iaIsHna31Gh^%*Pn zS7^G)U=Q00eG;iKSP>Cse8Dj973@kpxcwAy3w0Fn*64l`eYV7`l_}ed-x;FAIughG@V4_pBXNI)_iR-$$n_p}w&D*JNMdFy{#dEyb-{3W zILuk?w#7DL9wo3CYxbYEVm|!0={4MZ)5|YAO!^~GBD5T-Fx+uLmF{C0@pGt;FR zZq&?#cfp+O%jb&I#L>qM{^&wu#cd09zS7QvVoAN$DycX?hWEPE9QjFxXwX-xDO4C^ zzJwvLdtXg0rAZ5Ho#v4Sd65Pp)PuYdjj$hxy>q<$Ct&Y0i!^(QWIP;*rh0~Zdtr_) zHJ(~1tR8OIwF!>D>!n6?#iCLb0q?&wuQR%vdX0SbM+D66Yax}l2r1LI0m(9jQ7P@jZl$J`>6whe(bS@QactO)I>Pw+(_kr;C46n|hQ~ep zBiz~*LqQXnLQfzOj>RLG-U`aatc}?4TMz%DiWtmh(s>oqo6k)~5^+fWH4hp5A>NGX z0%*n46Ehh*u^^UCr7(NL-M)(Jt;K9SQz+&!{h&z&z`@LJokXD6Yp(b5|I3%o62-_& z1acV9M5ZuF$`_{#xV-hhnL`u+2aRAcpGPxwVoBn&Dl5cd>%ZaUpHxLD<kgqI@b^5XCQu_8Ke9?4(iC{8x;n9?V69J=9Zth4F_xews`c z%qN-gKiq%AD{!~uI!un}qhS6I%(5pjjVSp4NBsTzh^Xmk<3jGZ4-@+nd>o>VLT*@Dx(c5=Ks$oHK!9JLpdHJ z3GC*HTz;akhY1EfEo62ml79t~ZN`6iQ5dp0FogsYat3)3hTATrMg{5F9hFavrn4fN zn)694#?M)5?B$uk0GW*z3z^x>On)Xju6c;TE*Z=fCbmsv#--VBeh#$BHWBDOqLj@1 zB9O37#B_3E3@ZtH0$B(L5&$XL{|ieclTGgljG~1)_=}(`pQjozJE05oCH~!o9{PE- zBYO@C0iCdZ`0;u)r|;LYXYqgAn4aL#MYZoyE#h zRRxP>C~s9q&oDk>)PB|gp}|~0F6Iz@>dGeyGa`q`)L1?_NJ0ep(dkPsWb;wmInEB3Hm5rs@DprZ|d*YexSnQ(QnmoKV8IMD>x>UqV!;X1P7C7{F^Q6%j(`UAT%Q%KsK#8UT9QyR zCod|_dp!K@m?D41C(A=~yJ0HJtkh6uehuuDb}{QjQReAPd{#ycp-RQVFq5e$3R~XE zz$l!z^T7&078*}gEcAhvsAMg{;#DF*#YzFdj+8>}pV+=*1U*bXn$GXk!fnDTr&9T% zSY-SggCF2V?RyqN?M2U%$YwIrqG5sQsqu7vTwz4Jpu{sH>4^fgkNAOdqbWeAMWiUI znufB=vkQd^FN58Ve|JAW8{iUJ%{*bt(V_JwE?wqxmZNE`{v3;m z*;FhyK`l`T@{^qR!6w(!sZhF*CVhGe>uN@9R?ZmB3q1U7+>nVW^uHK?C-) zQ^@ZTi<~CrVh6cbMsx#J;QqKO^E+dzT*2vNrBNt(I7jK#S%Gmn%V<( z!(_lp3|7np0$ZG^ItGE|7E3MFO=Cv?^Vz;d<-o0gC&Q-5$c_jImI7M(K}!ppsy{_ z>0AP%1`}2j&C<#O!D9v->TpaR_4a~p6wI7KchHRh*{y0zVFNH!v5AQ{Ah|5pMr$lS zJ3uy)xd(|t)>zU7hL3G8(A-}Xy40+p1ptAj8H~0q25hU7s(HoT3xqm~fdNz53*|x} zRjDK>mfpW0szrBuLL=0)5KZC**&dgOc6_21b02$+$u7ls(Cq(r?7PYK4fE-Q(w*Y=_;S(OmNR?9tH@i7;Pg|5AH& zWC=XSJ-Xv$8q=u%#d~yj#ZC5rtNvf;9-R{EpJ9(q+IldN|1x`YGW+McM@OlSwntYU zhAoYkz#biO^`h_5iK4!Edvrw3({f_==yWfkcYNmT(Me`b+#a1|=(+9DNgiL4dvuaD ztf$a|#{^b(U;I5f-6tJuk1qK#-=mw(nQY$~SY|mvdvuTf$*s4K7=Mm^vPX@1_XdqQ zn}h2we@;7U-H&;Xxl?F3yLw{HkoNWd)K(#_(cw-Ky}#fOpSyKuW+J<0RcF^$Z0FKX zFu1j6VruKERa@1L!q%C>cy?m+#oSX^S;Um}Oi~SJ+ZO9>%g8K2k%&}Usz%mMo`VH{$`Uw&fk zUWS{$!v5%r7596xrSb1@;?pPMs|av^Z_b`(u0M~XA z_)*4R(-bS}w4Y}DJPFFg@cwwMgk|b~VSJ;6W%3_09uU-0@Zy-U^Y3%vY%cm;NSl|4 z3u$w7zRbc!6MRM8NSnJsH`eBH$c?o*jmf;WX+|N6VFx8i0=L=0*=&wDIGf8YDifO? zg!4KVP7(xis|#tf_}4C^&EemOY^DpMM+Pey8A%~PYMY2KnVwa3_xe|ex>E?$#!fg{ zh<7gCZGLzrlV2UkZYS@79h0lE#Znx@Mk&_E(XwC625`)VeN7Bb#W#^p$zPy#c)eci zCZ{n{`n==0BAl}rH4)KZu4SHzdZ)qM!aS8{5Gd>FPUcxqN1&`F3{t)`oCfn%=BYYO zfV#Rp)r|s{sh?(^Q%)7IO#UqMEN+aA;&cerAW|JYrBaY!YR#Q$h#M{n2c>}qV!3lIC5!enR1wyw5y zv$H3xe($@uo;~&r&T5~k=JkWQsVH_z$qOzrRY*nR7fi8yz1%vFrl)Wmg`5Z^zEIy& zoav>9+9h19AExsvF3hg_#AezQli_cy4`oJ++oL(`bm6IXLHp8ra?MX{me8B(6MJUJ zK}~{ht{)i*^~rBmAKM&~pS(U9h{jUb;l^)4#Zwt@=t&#cq-MF<9S5qGdsdAb1!N6d9D!E05)JibEMR8cCVZ~j&gcHHAjDM;q z;`)@z?6i7#v9_mr;+s9Q>sIu*#`*<{JViu$2sU#d6Z(z8}#zgtVHT@ikj#41rK`YR>U zEh<&+SIZDBs#Wf)UMI6&UEiCCs=98gPlO^v65mcqRjqYUu~lZB^}{H&qTeL|6>ANp zSept36t%Skt6bJm&K;%7-R;IHF|K#xRGH6p;}jRKapM#-8|uSJ)h_=^d^(NxJkrVz zTZvyQL0gFrGmTJed{H56HNKbW8WNqtmzX<$RsQ=*kg6qpxdf@CaX*v#q2hdnk;Zk} z3iyDAR2|_F zR^J;NmUy@b$0&A6?3u$&f?vmt)}JqqS#ZWRrx(x;K`;)NZu<1%6XO+q`m97Wrt#GR zP$7Qn{GnbQQYQcv(jWkMSrdUq0bs--><8zk$A0{EhUj;)m#4<=StBR7!FZAg`hr^@k)0cvCR*vP%8{gmK%FYAfiH zMo=Y!G<15*T`46_hvFEaL*QKt_z@8J;}XA>jHp!1N``a+z4#tbcptv|)ps?HMFs{_ z$=N8}OnP#&4#lr8;NJnoNBw>)?of=oD8^kB}6d1wLBLpK%qPnY{?T%`kqZs8%^tq3PoYJYrbAQNa_)c=0WHHCnFl+6>?% z0qKmJ6D0?s$c2>TJCH=tu2aAM%RgN$(yG3*G}c#SLTWO)}joZ%$QAHdlm zuW>`2xzESXq(YTc3arOPM$2JUVRj9D+{gdcW3+y-zS`DzW<^MKKe&k6v?EaEj$2`) zaNb2aCRU>5%NnA?b>vtT3&ved<$^{0I^^-2Q@ibm%u0+Tj<&TBy#+dFjo^ht0) z^(T%2{4J&BB~z@;*-f|gsMA)Uuc`c^d1p~PkK zE*7JK&6eGri})QV*ZrqKM?=A(P*_HzK2d&otw5}&z4sys`3UOJ5SnqQr!N{DcIdsk ziXZlPTAyrKX;XllY+7+T0wK!bbJ|3;6}8b|L+4CQMSnNodswAxw1Ok>Y|?F~iNMH3 zx`9C;D&BH%N5g|%*6&pDe@0pFJ-xxj+n}p!frG1NF50HQ!Ckxl_FKK0qdHKJ29zb> z_LkotDZ<4smH5Y!o?>j?yV zdlhLfLH$YHvHB#a`&{rIfCwTE{}R?BsuQ#{!BRD0c#Z8D2v(Q-gW?(0q1xjm>+Q3rR# zV?3g0cpVxT`a_`cm`EP5dQ(giX~%7)xIIk#RMl3a>$1` z1)NOCT7o*sH(Cx#ShW;ztYA&?&|;g%Zt4V#mKziW zsh~#7&5Mo0uaE+`!zJ+b%)G;IwA`}TLhJ3(6?}OUfytO`X(*6@<2Jlk!l41p-#(eZ zLF^X@o%sO)4QcWR1*ohF6h?s2-ku>{e}@DnP9u~mO_T9^dGH5L#dcBYd~Uu5WfRfS zk!XG&P>8rjJg8&zXpWEQC^qJ?COi#_xr^O}EkA|dVHmA z@>3KI)JZ@M*$pfvmq_g5oNw|+k>6v>nvAb3gN~3SdqnDcOxmi6i79ALdTJ*Y8nlu9 zS(873L|4AD(RfxQszf4DEx#;J6n0Ym%;euks$ZPbZNU)f&}B>LPp=ij2@r+%S+PJe zseo#`a&b^vcDsHnjGjb=*V*BAx7=W(l*vc47i6oZ6itwu`dliqRlstQtpc3hURj0I z+f%kG9EOK2osLweQ_^L%{C6nnqs!|kOEq&Ln?Zfbk}5!!Q~}jiEHb3N{Vwud4)G;* ze6QDN{qc(BRuslfT+4ANd0|XL(2_(f9M)qZvKUs)ln!(VJCY19Xo`+fXZ0lFidKU) z5Zt7`8;yTkL27}~GC;%PH|sD?vREJ3bXdyP@%MwJCt8_iX@nka-PlOxB(g^6HqpOfbw>-bH`^WR>z6pF9Z zn@qe8m7z5h&}bihE4*V*`%xb%T^&AEII`85Hd-)+6Uur72UrMjvY)BvpGNkFR{AY1 zDrUE8*ynoibu~~>pmj~V75$=~e+eWWS?RNzE()OAGiC&_k+>6k&8hrh#Qt&HUhaw> z8yJ98l$0>JwZB1A&o!&9Kz~nr9QLIYji2BS2d*Qy(}A6)W4AVRMzENjC{4mHy} z5*2(PW=D>Ryj_T-$lZn5V&|`>d7hT7B7aw$ivU@m$MkHZQF`8b}IiBRO16{4socg ztYl`-8E64W;xIqa+J$~5t~(3AH8QM|)mg#7K%_?{Xs`kU@u;@6p#*?*Sd%rP2eGAK zSf#-756pi}Z6($b^miM+b!XFsZ#xNQpP(x_++ZaG_T&LIO}X0^KhwvBom@$DXL_HYE^_vMqnLEP_hE!P=b;fn1&LR?7+H~pkxSkp#&vM zu%t*|uu)>`%bObb4HZV~H`XD~*wBd919UzEo3yTAjvVjPY7>mA$+#GZV*-5qOd3C6 z1IN(L2@r#DtV05#4~d~2Qb?nShEa_GSXfwl)_G!TI}jd}`Cz6WOvVQ!fT@0PXm~Iw z6JfHS49L$eXEsgKtHdUyImX^~bJ`#*!OM{4MvE4bf|^*ral49I?Xnt~c{8F8h^R!8 zDu~JB?FI82XU4?xyDh?7&)|n4!tZwI%0&6BpGsr*->LvrpZ2_o)>a3&-f??@2 zcak1JosI^=n9E%JuQU0h;N$1#CP96^Q4kvlDid&G8=$a86&7}s9zM|agHcU{#=)o_ z6tO%J)HQ~+2@)ik53rmPYJ5j0udN4IO*+dq8cY>eUG&`{6Qar6M$`uSRu<1jbe6im z2tff9kNq_7P~QXAkot*}n&q?R`fX0eszWOKz?{13?H>J5&;jfSIF47_&USY8&}m^Ob;oyD)LG+Mt>l2BKJ z*H#mxqeXu^*;0!iK(cFJd)Q<3VJj+_R4s%FFrq8NYxQBY!zdv|?6dlY6AoBy^910ruhpb~VW0+m(QL|`wLr?e74tzyY7y=|%fLHcWlEVl&0 z&SjFIlU^!gz&=%B#4ophqWlIkWp+hdP&I$$WO2RTI0d`#UjEWpx0VT(u^mp`xWO-5+eJf9`Dl0Hl6Tut{)gGwzUW zvkfrFAM&+1KYA4;ZPh~^APIU6t=}P1Os(!1oRrkt?d!R4)01WuWu6+JrlZm}yX~*w z-v+xs2!UNx?w?{8QT`OWh*H8XV254fv5*uq&59gW%}6ud3t%%!;+`tw^t-R%-v_6^ z4mVo;E^Y4b)w2Pw)!#cf9F>A`WZC7`XKGcpwER}Tqri0%urT!-MjRQmboV(^*P_D;b_<{9fFz@M)w-3}e(!Bt(jM z9K&uE5`^>lTwasMEt_A(l>Q~_!*)kSEt|bx+=)=;wK>v}o-A?5mw`=Gr+_PRd6iQ#UO73yHhW>_m+^(VU zk}Giy{Q>ioxQ2e4c{WOSMd|5=8-D^#jIke@f#PkkauzaFU!f*Vg$sRmR{`ATj zFc#>K!_lIc6%Lp8abAPf6OLOZh*aM$=*eQ~;OJH%*m)E)k1}A;NFCF$K zePNSKaCt$IZaFDMe92UwUs29zUfTYOxeg}14(*xcNq=C`$CQ^;Z52^jXPx>pWDcnoJUr{%m zSCj|hPx>pqAb&->i7Gd&+d)x8*D@qD4hQFfC?$P}fZFc{pzaqsHv!WB|uc*0u zIruA<%jY@zE53yMvO*8|*u^){GnGg2%QBw3UzYLQ{j!Yb?w4h}D1KSS^YY6wj^8iq zzGM2}{e|uWZ0KgJ@vY*G$(NchrE@Fat<1TV@6!yo^0|B|jZ$AqqtutuDD|Z@N_{Df zGG9ug%$L$A^QAO|FXf@C5+CE}#5f+W-<{59W>zP6OytK?c(SChXSIGWe03sM%;Snc zabI96o*YV~Hg~KZo1B@LN#$lbPMF_i@*6d5>F4J@fA|Gl?fUmsvE0mN+-j)26l*K_ zdIP9Ua9qqtA7b*FTvN$Igih|jE#u?DwV2SKtK>t3)(^=MF1Ud2h0n5%OAg6|#-s9A zasSZQJj=|7=*5X1PEqiJTVBUFpY!){f9+Lx08xbuO^x9>L#DwP-W<%0PmBq_Wfg_| zE{Oa%7thFD@AcN_W`;H~hCjl!nY~$m>F46!q!BP6Ld$g_3w;>O-7=#wCi#I3XWm{PTQ?F1(F9EO6rSQStzvu>-y& z0>s;&Htv3bv)>@I@n4m3#S4isTykj#Jg5R@=w?Up$d(=S2!fIqrSNoK5tl_0i_#VU zo7`-@YQa)#O1#E(HQonfR=R+@QAg=9N)d#BW_)mhl@1bCfphQWhl{Aj-CaGHHi1; z9*#?@TYs{^|H3$@niT4(34he!PlNFNz88V8Q_Y&X;pM*q^&1wx2-JnHXu@ePe-?y) z|6&lf6;2cXte0Pb>wkW;sNsbP+nStq>jyO;$A-*)P?8X)(o>{dWl$66J8AU>6q>qaU{= zHY6sQ$xlv9!N+}^IkX)P1G(MIR|>bYg{6oN zwx|@*$*M{bU97qkv4)*eidf4Qmm=1&B`!oy29Mzm=JJ#2Ec4HgZ)Y|02jGCf`~jV; zcK(1aRyTjZ8dg7lz*=_d`~mCOX|4cOf`&P$c6Rz4Tn9U24z81(IS1Fp8t35Fu(Rgi z)-r1jZXG+@g~J1|yYM=(kaE-f_;&V+`2#vw^ZWswtY!XyF1B?3fHiE{`~hp(E9Vbb z$IfvD(95@QiMfVA1HrLQU zoFV1JNZI8EHMxcqe?(>k&PP(YzpJD=iWH3 zzy^237e%PDBcM`-;sRG~S5&YkC93Wer>^Lx^wBh|UR2t@F>cB8luZ>Sb4PubynT0k zimFXw=^A;w5+JUSpPfzZNM}!|=04%AW66i1xsTz@s8%L=hdhi2d(~mpa&#bcA!&0d z8kb8Z!-J?-((KY8DSuV%^kV&d!GT~hvKa?l9i@_7hdMNfol2$wtTnHoF4I5|BsF-{M_%SgBd7`uFybWh6Wh0E@|kf-_4OmP9FOaliiI5R)F0Zmjrk?6Uf@R3J2S)68h5I|;VmS* zuQM|_F+)>u9d;U4x5Z1(y%XDV%KlTN8my#DP@pi~CF+Ey%Zq{|xSQXW$28{`!%nVT zZpo`^BjaL#vPGh?WNO*-I*Fu51WKdheqwRotqgG`sa65hsskv@_9=Q|Koi8Rq#_wz zJg0GWnv|)crJ%)*oyTI5sHn&IVEWD4|YHO73#OA7&{Us&+Q zO-}`Glwr;OUvHot>?BvWdsFtMjk*tkh(ka&>IfSAMK^H&+I4;oF@ z7&@eF+e*08%z!OLz-Kc9wp3nVONG{z<*Fi-^QdAs3R~>4()Y=QEjBKnO&OaUKVda_ zA8NAt3+|f4g;%NI4%8)9VuOXexKAPlmECIal?GjhWrt!NDnlWc8GM7cB!tqDl%F+t z*dsy`yC)!jtW^;DbT2K95-A*c0leAEr_X5pEY6+pLSy{F78)s-wQG<5_FB8&puc^r z^+$*}ottq*1>}kh2%WVggXq8apdP2TQD%JB#8UIe$4sR+|&AP&^R99*r^8tn7dRuJz%{kOi$O zD;2Zy>D^^GZd_j>B*AgbsS<*D5Pg})+H4EF+S+Uv#&2!5g^kt99BhioOd3Xolyw8v zeD>t-XFYL&=wFbiy#O~(mPUl9fl=of>cU2KB`7)#RVNbUu zq;EHW5rLU;(bQ)$u+mgdVr?5A)j+kCE7~Er;n)S$SrHe6OR!u}qw$X(L5_Qv6&fw# z4G#{`X2HqPrjnxDkVT`%;3QSF_$_5^MG zsNtVL{Z7&)ExN3IR91-+^FC&72L|`CU?$q#i6^0S@!!e$tBuzGH2fkm^M67WU$XsU zk*LP}1fC@QPi`j$-(TUp!)W~n3{=P9OX$dk(mvuj&i7B`!+>`T*R!7=L8ts9tW?pA z8r!F88A;8wB^nphi4lXM(2bwCtqi@hoP^UHpg5!F3npgZD~;M4)%wBk;J{FDlN^O8 zv4(K_lmM~4VW;$PzD6vVyd-@l?)#FDJ#)=V@(o2^`i3GeeM6C#zM;rV-%#XbZz%Gz zHxzl<8;ZQ-4MpeXE0a4nU!95Doahb3LoZLC3IF{*_VW*)^qIiQ0*&n_eI|;TqV$d+ z2ab7sCWJfSpYWNG?u|$Fnb6*kn37M_|beOWNIuuK0lv{-RIxWL zab}jr%kPrCX&n_?qS!Fgk>y^m9o@Azt>VwWH!bgxEZduw z$QNsG+Qlz6dgtfY-d&z|Z(38JjeDJ*c5~%7?x&~fqn+(z?oI2Wy7#74NojAIKIh+? zmf6U?Y56Vprsa3Z-n2xO?oCTv>E5)&mF`VT+{wM^m+aoOykJ%BO-tYP~vR>S-^ zxd*ATy=kLlZ(6sBxqH)68+~$bS^{csS^|1+T0(knT0(knT0&xPnm*^*o7U*#+ndJe z-;;aOEOhSHP-bRlAve7>-jNy%kKoVNXlT=`1Mw(p!d&g(^{)Cq{=MnSlD+Bwc(Z$N z`qaw_I_BQAOfY9}TBbaXz3Ixo@ZNM~$=-BC6d2>8@W49O-gM=0?oHo}eL1no%Dn#Y zxm$N;CbDZ*b#`qVtRvb~EnA-kgdNthLZL$rxUZVUx zo){hcBL{`6u!VdE_^d14M?c;(*NXGim(ae=i^=#gRet5~P4*bvab7Ks*oHFOCg3Ma z?#j*Poh&Aha(Y1}yr1#5W{FH>3MKe;4j$(oM>F}7(DRxh7jLCqhjh;6IrtZ3v#H|D z=n0d_<7;YJ>}zl@fR|q#J;@ddZ;k}R%FT=kRR2&SsSqkoTsi%~jmLf-jh07jM}bc; z-f7f64i|&rcuy*VS4YWdfxbgSgZP&C!J%Y4EDk4lMA+bk^w^dmzLj%>R{(H_8-Q~h z&J^fZ<3NhM8k`&}INxa0K8@q){XsiJd~WF_H#~ubJ42HE9B|wLu5wO0CJNiqa00iz%oDk7WeFRsY;JdII=4HMFAHh3veT1gxF$GB7vQuH@5vqM z{C4y)Wf7KIyGG%^I+K~2nH#v=D$bCz7_J1ML#V0Dw0&S>r3lK*()&v|K0`z_*KLkC zgWI;-`n1Ty_u&0kA3V8>liDYiS#S`Zz-fcCSJR-w3B>Mf77kMq;}H>Na)>mRqgR~p z@+rq$zxA?`oj@v8$=B^JGjhc;DQggHPmK$d>n44`Y?cqlFitsCK_ZS_ZjO( zi5klloiiIvaNZ{_ZS}(whx&2WVS|4NZof}etrV&!^OHrwNVP+9EnyB_a>E{iOXO;3 zg_H>(s~jXXwOtFN0yhNY#xgTACD=-$Qy>phC9?%29ymWr`Dl@8x$9Vq$|Y89ZGi|A zu4@bYGKx!Lb@PY^_Y~x|!{yqgAdMO&{2^s&&YDvp;*>d)Uuhm1-@s? zg;z3wrva>R zpVfiV0I<_lF5*`jM(ulW8dSL9vAPI6VlP*s#M7e_`3w$A<)-Wu&vL#WDSnF-gW=@J zP<#_Piw}lz#!foZ(#zjNgNbk|uo;I+)q|3CPMlOC77n8(`U8V~7++geUcnH?w_IUj z8y)(wbAwO*-y6njF0bStGR{bh;PT!JlVK*^sF#{IEfD=hI+cQNbuo+1j2bK7no8_W zPj99Z_5^QD_3SBR(4{*-hX$r)hj-HgC{X316+fwj8e^1z27%-y3`bcep-M%Ziqg#< z=W)s~+}e%2is(LMSK+aCtD{m9#;VsqW@{E~tbtF!%{4 zj?Il#X@y{nM5dV8j!1Qb-|#q!(Q|Icc}hxk(ezXi9bKWAhh$5W z9YiwU;3H+p4vS>5JT8D5E0m>p1SzTq-(r?#^b3(9f!o38)#DP*_(Ey~pDatzvXBa1 z(xaB8>p;4?!5^2Ud!0yU_uXY_UXL^lto0prI7=j~0BwLXScMn|Qdu>cNVD9FgGG~N zxOokHn97*vV7ex|Jsin&x;=?9*^2Krkd+rIJ6Zb#1`Z_Dz5O^QiDSZ&(yYPM1`g&{ z8pCi|80Lj`eES5Qo^?==oJE>B7^!|^f4zwZe3vj`+@oiC=OReZxXFbjo7lW|kdf8!FzGF(Q*LOAYg>44k=0QaF2L}U_n{N+Ys>@iOFTcLn)K0FDN$tj&{h~TpZM57_VUgNI#<6`Q zsoY$FdX$z1+PTs4QA}2-G2xsZIJ=|5_{Y=C>1r%uS<}LvWagnNqvbBd5+HTN%=`ip z-d$llb{f8%s1z2&ZGjNm*OBIMh4E`U!Z17pW!k3^bRT7EQ+fc9vWO+=2PrqOE%~C% zj#OAUs3wDX%i7W}KXQSou3MNl&7er~B%^PqcW*8hYHa*W7D7t3_Gqpl) zESEiD^NG53jNNb>i5M4AlOp9_U z4;@Up+H(pW^Teq^d3F)sIPXK>aNefVnjfMAO4j%UP7)Fp#~nW@Pxh(=*dA2Tu{kKd zV1fPAb0&0UY*z|x()>pxvrnI@7RuGJ+b0m_QO9wYpmi;A6(W?|JtY)FZ4ra#4sj^y zMuXe^j%x7pBpaTd#&Q7??dQ1YvGrSqT$o_yVdBS?V0fA=F5DKV1oLIi&of%z;XP9< zWH56Ie7WNjUn)h=VeQwP2aVRdynHEuqzh6{-oJVB{>?czhdz(9B-*Yz_LZbW`1zbAIezNT@hr*l z6Mi0NNsf>B(aw^{)X)1Y$?;}B|5=if%>VRR5*gh&OQJGAd6wklS(1}yNlu<6IeGsk zT><*%zkl;3a_7?zaRb$s*SVaJgkz?jnfyiWeCm9wbYmjdQTZ+XYUOu{U#*TR=Ad?D zK)8m;j_&fSRq^NdtJSMNf5tnXT>N5TL_+$`C(Wh`OZ zxIb~{lgwWF)yi+_S1Z3u{Awkt)UQ_JO8sgjuGFtq;!gV23P+cdcRsCXO5#5IbDIMB z$zZVQbzS3~YuAkbHLE_hU**!X7`v~eYb*1sJ>EN?q&6zQS_vq>S_x>sS_x^tS_x^t zS_uiiTKb&FuU4av&#(4na_7@lT7TV&MevES%+?cp=TkT8fB9C|(02TOwWW7Hop8U} zm)4z6$M08rymvm8-dQAdB#_;n%TE+`Op+5VcC>`Y(uwr9`T26jnzln-cqLuRn;CBs z%i>;7#mtTz9MSZ;xvwIdo7&z)zYy0~_9m2PfsN3~9E@0Z_c^eOkbY9k>+_E1isWHv zzuo*n5=9aH>dD+1yGkQ3AE0Vk=6i0>wr#cF|4( z>T$_wv2D|xxce2C_W76Kdu^AvezxSjE>G!uU7phSx;&-tb$LqP>++Pn*X1dDugkNs zDON<8)^-s`Uu2#@6ZWX;d?mhd)Mu}jefDZR1wgy1Cv2DM;JJ(~z0%cbt7eyYfcuTx zxcOcNZ@#nBGpTewpT_3VN7&i)@DetPeuPJ*=+5LQcCqr}eJ1nYD=@@6$i93Ieoxp7 z%`f1qBtCS01fCnyMRYgJyq@uHqxCZ$Ty}?Bd#@22Pm`!D`tn+nc&wbhu=k8gqpxa~ z_!p1gxZeYaxXR?G@xaqxam^8SGezc`vCZk^vR-WU+>Q;UQR%kzo-4VHM=@Vdls4Lh46plHaG@)JH`*t}=v?VLwFtsnPpguAJ@$#-pA2QE|o zwJ4rKt!Z0}XV5RgrW49e^6OmF)-B^SVXqCh^*V{*7ffPy3iLhBhmF>^R4ljhxP)Ka z;LZH+{yR}9bb}b@ltONhWUGPVbJ-Qf&l1 z{I786U15_&=(yO@{RBwqqtWTzNkQZT9zJTc-dl-nTvy@!>#vp~ zcNbqFxk~^F<#CBXq2P&27yl~AD_Iw>qKQk5|F4I?-e|oZZ)?$>YCa{e9ES4JUZzAT zrvO5E;rEco);O-w%;$yQ5@CJnR!REC&5X8c_rmK&Kbx@G;4^quYC(hX&;sH105udB z`HCIad+9AQUI)#avOrRugqW2hlkEivpZ=+}i*NX?us2R`~ z)C0|czM4ccpszNT_`YwW@sJPr(#9F`>ZVYuL==>@AlfKZ@W*HLpB8R4+ld|L&$iImdk0^ zxggsC!MIJ-sT3;9kG=eT$l-g7=w@9(O?!_p*826Tn?1CtjW?}Q+wg9k9VD}1W;gk} z39Z^jz1eRJqvZ-H9^FvO%ttEV(&2&I_C$6xhaL6-z=r_OY`-LhIXv^f{q5w2aDxYT zi1rxG=GQ9(YhY@$f?tnIkbkk*QztZt8g?q$jy-->!Ao!*0_Q2gbqbtOg6k4Euf+9{ zJW_$}yQ1x^qM{tv!73`tah9ARrn+>fqSkcZ@A7Fx+&?$s0U&d3uT8N04#VLJ`>s=uiRG;fDv!uyA-RYN{ucEJt* zWwP&n9;c)3!0D(+bQq_j`r=`6mWiNvAQTC}vzxQlpYVRT$I|V>%)j7}?B_-QE1j1_ z;kvDf$zm!~%);@vL0oCO0gYKU+6Y3>aPDCIHJ;jsaBfOfPAYj}45zWe5G}nygj$l7 zChu$YWgYio+T@UbKYarUX627utHK%S#?YRLhXqV(x!yj zQbIv=Y6V4RjPr=6^_GhJxbAl3VGlD(J|wbxQ5akvkFz-$ZBY>$Z9rbwzkb z%SbfZN@7twvzFSNfs@*oJbb68^(tSt@eh^q)@~YU#o!LBPnt`0G*lX2C=XYox{T8$ z22q(%4JXn#P0Xg9EFqQp7idLgs{E@H%_oC?aI_}WWK;bTd)DxQQ8*6Z64w%-S1=N3=1d8kr1SL(N~tH86t@VT6RLGOs+ zY~TqS+Ct0g*aLV+Ods_6B)RV!>J^|+G>|HJr0PP>FZPK0z$qwEa?EwW!>63E0i2l3 z2Gx-Q8gxSRT)-0^zT1g|d)~zxY>|*1q1NDU=bji*FFQ>2J%itj2Sgt9wpl@RA9(lL zv109mR2t>A=o#v1ysCufRHToI&%z;X7hJ8Pkeg;8JLe%RM4mUKuH)Y z+-TPeZw}ghCA@=mE{7M_$vXkq_8GznXZfC+gBH&V(%I|U_u@?xx)Pqk#H)SDcwjKm z8%84et|0{=LT}0mfbH}>ymX?IZ9#1Po*`M>u7o0pQme-jMQ~ZlXuCU5K3hkbinP)8 z^3?L-Iy-_WAYKR*l$~OV#QG6M5hmY3wA0~CxK35cR{UU5N=TqoO)thNBY47#N4U0Q zQl%f^x?k8i^hO->pZ;O$`MNC8e3&_jXlpDO4r20s7lOKnzT#VE-c1j%zt$_xy#}YV z1>IVh*@wYo!_ZSY&X|nTpU!S8jkgo=HV(aap`vw_j0fSBPphU_qkorFa4ne=2& zdM0C^Ig?FeiwY`vC2cEKZr<=(x*F~~SVm+w!w4|wgL&O|Ed-;O+pG@B2d(sB+up9( zSvput_h#rv9NX5-&YrMt_u0R}_7L7EsC}xM*W-OD8Y>qD8*;`V3`cU)jCNTj*6 zK8E2hu~|ZIs!!~}BkC}EMc|w3M@B+@@|)GiHizUVuTKV|F}fK6zePk(eLNXVjcme$ zMglhKdj|rEehGN%<3ZfNKqaZD4{u3E+9XgZ0IUE|$N~Xi>Q8`A0GRU=uuuS)>=Ur4 z9!;fgbcH>kYOWe3MGGD(Nw^rh6>H|1RE7&sYF&S%5 z;eA&D)=DsrXI=$dr(wliy@V6ER6~THDvG#1r7}CM9vyOfss|^2@v&aUX^==rm;x2y z(PpXh*5>jEWl#t@&93g}DH7Q-TrwVa%ewXgDsb;;Smp`#)*Uvfu~?JBI7^I>f?CrSOgql^}VrS`TZ#N3J58dQW&lb;@4r}_2-LY zRwB;KX`CiyRxpk|9QyR)6YE^`>9Z2in8sHNK!y0N^M`tMNSy#wNP_^dJVpc>1<)md zCaXWGvRi5m=+EU=;sQ-*C4DP8ZS<|kbXn&EkW{*@^FuoR2KrX%T*ZA+@Hpi3G-l?c+%>9PDzDKSHs%t=v-3BtP;@FO7b z$0fKGH=`;*5KYYT||7ht8c#*fw?WTqRtBI*bP>XmQ$ngepA#BA7K_f2p!)X z4q@YMF^<1B8Mm9}9~Y1p(2OlGX0|TGHiKb2VwxBDaOamb<0?8cdl7n@Vf;){t#YVB z)5j5b#ISm!f+vu{?axukD>f3mHUrpTB%Lu@_98+;N7&~?z?P$oupbe613Jb5CkA#Q zWsHM}VMn;eYg}0;%ZnMlE-!W!{{YSod5s(D%zZw7CKXEDO06q}nP=jt>tR)4wiBsGbF^^~bw)pkKx9&`Kea4k!?Q zU=&wDjVdmdrKnqJlHh;>m&&*bT5g4gbRH||ThTy=5|_!lSd0cXyIglJ;&-52_n!tG z4F&ONrHn>>qWtn&xM-xk_aX`T2?4|_bVPd4DCO+^86vT4O5 z`rGHUiE1lqqrrwwM@>b4H{g3%QE9Y-BZ(xv9jyccFmjP@U=WB3SPt%Jc(8fWH}*X z(WE_+thAG$l~FH%?O%!ml~MG&2-HIACLkjFButnI3bg5RZIqxcS4e>EI<#McI&?sQ z9Xd27K^>YDV5bh$t^B6r}p@nTQQ#a0yeI11j;X?h4!W0cr`1*ir= z^q4ACcd`2f3_DV#-tRH4vSdD|IQd`*XG^emAtU$UmJOZTgBlfea7R4GBZ`LCp@E@4 z1RA&xfcWWCm20&8&|~~w#a`&dMxUEU?59QScyBPQGdy63;`Ih>%t6Dr=WNNci@;hq zjex*4GJ4;zo!@=dxVt0QQ{0fmsNk9!X!tXc{H0e)FmW28RB4)w-#1I{U1M%LT64YzWfRfSb7+1aP>8rj zJg8&zXpWEQC^qJ?CKjW)i`|7SKZW067_E0MZLsW?jYkh;Da6q1vYmSEZuVxZN!`*eGT4(d-4;swqViwy$0H?QCRw4EFl&uPf z;bBXsBh~4YbXhI`9ZLG>@;b^=&0NT4P@l4-3XmmL0QLkTL+ab_BH!f@UsA{SdX3f} zufXU8<0h`-hV@(i5%NQb0?H#xzf{Xi$E7jT>8u47RaI-$^?g z>oFrW?rD_`*fknss}w;nXrd6FOpY8A7bb$eeNLW#tm8K!&wqOrj>%~IkW9P|m7z5h z&}bihE4*V*`%xdNS=8ZEg(F*?X`=;GIH9aZaDasXC;ORt{%K@?Xr7oF-J!3`?8;Luy*PO~9M(iKA?d7iMv4H_dMM(*h zTl*U{^<1;s3iS81$6;Se(fA4OaNs(EI~~|*I(BPAX9SDciP9u&W(QtsykpgzdW3L) zcPiadN!f=7RqkyfcN^>yncHCZ+-AE$R zyj_T-$lZn5V&|`>d7hT7B7aw$ivU@7v3JUwrwlY*s1(iP>m0)ImDr|vXYrSXP^Zj ziNpLvYZv;Nxb7_c*2u6kV{VU+^QKQR9_ zwUt;$(BEzN)}2ikzU?HKeS)s!aD$Z$*tR=rnsT=zhGhOW+;7*_Iz1{3SUsC!dbuJ- zK)a%xB%nh9TL|b>z*Yjf6mT&CYZNd}z*+^MA~(g>DIiNgw*saKSg(Kr0qvTFSpjJt zE)|euLewlpm26P0icrZ2tV0P(R$v@TP%;D4P=b;j;Tc4vBtx(ZWvFC{Toa%#*eJ2} z2}NbjFgIkDp272W;RN+BpGY z5RP?7K=dIov_lGM6wxrM5daGda|WF!rnUp&K}j4l{a`XaAOTGEgG0lENtpkWxWJ#gZb)Bq7l(V`hM0={IJX!003yCld($ z+kU9n;?jz1v309kQK_P0>sF?Y_?5=0Q!?ftIKj`O$T{NuJD@YGHy%_`i!3G{jaZAQ zjUp;#Ngc$-h%8gSmyQmK>vxlc_a4PzXRG25Gl$xJ^n}2ji5eNipat}l0p;4@R6!;F zu+0U=(wgo>Jvenb+6aR-cJc2=^BI(sPY9LrMC~v z{Xmn>g!aKEy(!{)BA|P$%r6K@>;pKbklNp|$ZPHaT$3&mf)Zw}X3+O^*;$zKCKFXj z--_dzgT+#>7d03Fs*d$^?oi*2euxGLE+xo<7)aKrUS7)o22%WVR;k%I`yyDa>qon- zq7-$Bs*)FM{J1 ze52y~j)Xe4+Z-lHN0+D4auE}o(SVKqaTa5m7Wrp|Et=VG75E+L(; zbqGU$rnAUD7rV8Y*6W{(grRUqMn;R_Y|?XSEF!ldP!YORITcq|M$S51Psy~H!3{9@ z-Bvd(Qr}GfH$x`*g@;+n6yu)R))b9Odm|@ej+Tuh#(HkRtS!a|iL6nxDvj+b(Ns)U zm1qVM%|oI&{(4)9n6WP7^3#xvABvurwPL=D#?e)VFhd-nr@XoGJ_rz+^!<#Ve+%@z zx*98PjadVvH;IM5G24Laa8-wC0ln#fr9@dK^>7i|Vsn=GYpTpn!Zj#4%(z$?Rd&!x z5wxKNQv02%y+GsnkfEt*Q2m9KlH9?0jha2ha*1mIv&z#%m1>);TFvm+)Z!Y=tjSF2 zHfvI8mI~skn#@5i&3M-`Bh?tMSIHg(fpslsVDj!LBW|k(?_XAQ$*5ou3aU%-2b1cL zjpLg^^(O*lqNZlWt!$^63>fGS`kFN#x(mYQ&_f>}304g~zH4Y;>fw&fNm2a-2uaKH zWT`bk&}M~@U{?2p@%-ng?w@KJU| znx;hV-mXL+6xz(1ZXeJ8fSSHtTk5a3jpq6~eHw84>+48@Tg)ztmNV?*nP!zqEw8`c z8o(veVU7r~KFS^@3<UZof`lE0o3vqd{?;PC&{Jw1R_E`!2W7U< z`P11R)cI37e*|eqcS>Z)<)F?Vl%7U_&R?IL+u3yfRFIUZ-&dW#M}Qf4Q0LE720WX4=CWY_tVu|7cOPew}D`IElsI)BnPUFT2wX3_bhfb2SdGGsS&{v?94m9UrLkN72MiJA}@kGkiC7{$$zNbpB+>kUD=dcnF<8890p2pNuf1&Yujn zbpFUqO&?C@PsiCUoj+N?5ITP{a7dj$8En(}dkW)(YNto@?(6(f%HeeWWO#O+KN*%? z=TC-Z*ZGrSS#|zoP*$Bk88nQ}A2G&sp7=nWzbW6Lh+60Gbm96?b^gS_z)2vh&R@qv z=)0^sf78{N+asO74NjduJH}ghNi5k#y1}XCQ|pq^XluA7G&R&mX4R+0lopEi&)Eid zd#R5tVwUFL!?@grLSL-25%Q`HDZrkjm@k#b*L%t*f5SD1Cjh)0N16Z?6oDWbM6JVs zumQ4R%|K7jay;|@FHBfr6d0>rz9$&HSSOZ>Al&Oh)^q}1RAu%}fLpZ}@hiq3^L%{r z1%@tya%Uy}0W;^{%baZ)J|VUc837kym3@mBSz>a#ijfybD})#(Rb|0|Pjfflkp>$RfRg#50WR z+#(fGK{bQqVn#!ywZ?cLGYq%jA4gcDe;_XMp^Gu8_!QPzpMdK~X(Y2vXGxcq(rclP zH60Qd((5cujxed_f*jXzzN*j&J)7qqr#c3uKEcL0$;>AIJ73f5%z3r*YFW_uZ60+f zM6OgikZv1li>5(v4J9Gcy4@e` zNi0d`Y}H=!4RKa!0z8;bVVQkiW27iH<55%ct zXNDpR8~CPZBT8uner8gEZ)GcV){ou%H+&+HC6lR!erO}dx=5=OhFu2|DaL&7Fe_6y zIPwS#2+LnqEK&9%U=)g?5R3kP4@4>3nA!s@^Chskk?ib@M02NK`|{69*x(izOV?g2Y~9BkXd>Js8qDjg3L=g7j!(42hO6Q!10@P$27x%#$3xM$ z#7WZ`=o}>|F=XGuf$R}+$P^{Xyc*AN6t-r{_g%t>B6Rm>a|Jm%7kmS2-fjjg zz+1Nh8aiss7fiw8H?hDyB5}JlxYzDw}(aTOs0Et#O)Z@Ez&m7l0q2 zzeaEYd%vzFI=gZ<#wUKVm~Hxjbz*w}LaG6vkrE-yuDXcxQw-tX7;H)l1HAMcE3B#C z8qJekyiSHxBS(8kn~R?*Lv#^dXhbj`E)#{=R}t?On-DNh23Rok-Y1`d_k8J{)(>8T zUkVF>yI_ZmY=emAWSTg!d)rK$Sl-HJiL?Y_c|%HLA%IoWvL?10kM}Tf!iw(#(l*hl zaT?hm5nm@Tm_8F<(_!~aew|40ti{_9nKG9NB301NnJu!e7k!8f&CQIn%ZyV~ThkDz z3QH_-8Cz!ao)x7b6lj@W+q#hK2m~8Z5i-QWD!${ne3Z?M$tlF)tCj3jTCV&g0a2x3 zJbkkeJkxj~-`6UDMWJmSO+aG^C%H=FciNX!v&s7`7?#`xg*DR-3J^65wIP%$m}>fN zp}`D`lmQ%9(2zZEORTZR7W+EAn18I1`$3;lJl z#uf!)W=AxseRmc556d7Z&8s+b3Pk~8V9>GmsaxoVAv=}Q#Y4Fa6QPL`c zl%B{X;ARS@TBN}wv7UH~9P5ewJTdJ4*_Vu3TW2n9kDrazuM7L9HUagB+V}*m0mn}B z9`ykxs*69*4Yj5Ugj&KX)ysmf(BRv6kqlPIre@eCgKyVKYX$VG88qI_|Duyoe)YnL zuNi!goBv&>6u_ru$UAO+xl2_?Sc5Y|nhW?fW(ZctfqpaSvI2gi4x-W|Ftru_Q~|$F zhi8cQOey4#>cF&x?AAhliD49f1xtijTUbd0EJChOq=a};4E9%3vA$ljCRmJDBgMN& z(Oer|&;rXJSQMJ|YQRcJy0@h{R2!+94}j>Z>PD0EfF#Up!|HpgV?$*(ib$b1`N?vM+a$!thyAu z3$!P!slgq!vaXEbUq;Qr;W(NK#Xg5h>i)3- zQp*ORhu$eP_M|3O`$GdAb`rSQ)X5wWq**rRtK`o!i-4)IkN9P6tmGJPSRAk^zaaynSO$9$I{?xg02Y;o@vaiJk> zF6?q?goP8toznbUTilN2Xp!m&SdpgkVzjsYCo zT!Df92YKTesPxn3d4xu8@nx`842A=2Zm<^I3?7N=iB+?CkqtUp8Esxlf z(wS>_TAF+qBEdWAt;Hq&ez8Ma_ZcbL2O{xk@8Z-F?JHoW)BNy+-aeQRE1iy3%;CNwAXng`UhsO%SBVBcj99`+3o!#CH%<+C#v6y@%Zf^2 zfu8;tR^Y`*1O1>YkI)h3LEAy5U4@`cRH&KLX1El$Dzko`N<+0}y{ND)0C1q&tp;Vh z6P=Rh2VWxUL|d=CsMwaLjsfymQ0}{(m;2_ShK%hxAn(-PI235^bqDX%Fl7(ksqOBa z+IeCt#eFFA-oF|5K4Sbk@kSlEY@I#1yFfeJ$Ji3Q>zK0sA3ffvwhT{@n(|xXjmmEa z-l&c$@kVuIi8pFSx8aSd_#YYGsI9)(0J7KDL<}V{K%kg#4w!(7pSz3vOU*P8-x-29 zX6g?IZ&X%U;*H90i8m_09eAVC%ZWEC{hWBC($9%ED*d3!8o^v(zAbpcp9DuQY`iny z0^F`ofh&PmONMJ}T(&`Np{a%h8R9N}FD_62g?q-<0P(j~^TI8H6Asc@2w8 zU9h~|TH9FFCNB6&np>dPEjZ@63tL;rq$@5-UC08U9W}MM{xs;jxkWh15VQ)xb!eXc z#)W9U{+_``7l@)Gq8mngq(k)R=t5R;y~pKG(Rtao22CSS2)f(*HokF5`ZEu%G|-&T z0=grmMkp6#G3d5K1~rk5XaI{y7hR1~!zzAKcoZb>BJl`NX|51?3m49F1DQryGFani|D3e87dZ_9kiF5 zVhOq^mKcydj67g?U0on>SH2%vyeTlm3j9baKMVbz)1RaL36QPdN_2?wFmGE9wG;U; zJCVo0ep%}YFq}%9F2?(6#>6@U98tWkJaMhm0RBN9_pNmp2ftnnu*V z{M*}vG^5yhnDBu78LgBwtkBz^=ll|w8@(QTs=bCdV)gZ7@@B8ExwB^7 zmsJafB#xPS*nL?y)s6$MT58;uCroB?n6^@fY2O;`eJ+8fBa4^&viz3&vix@J%hJoa zFH1k?zAXKm`?B;qxG#^`eOVe>Rr|7ZsD0U~U+mbIbB!q)EP=W+9?Z=%$3aX{T3Jo~ zVu?69^7V@kVu~Kb6!jg%6qO>8U~3OziYn~UgP5WR4yLG+FPKX20#os55`!LAuK5B6 zLH@xfNyOdV9q)s1>OsEXAYX70Yh2o75g4;}Snz{bD55ew;u(3cEj$-i5JSDFdxq`@>|*+k>ASh zh;)3Q-4TjLYO_OOjXT44)9#2YJDc4R88W2Z5g9y$-4Pi$jNK6#VMx0pGT5>^LT+mM zaCS#@oZYfJA`2M8?uZN=((Z^1w%Hvy>J?c#^(rKA&UX)MoKg;FcSMF~w>u)kvfCYz zVcG4D$gr$-M`Tb|yCX7a7`r1{Qtt!pj;!24Q$pJvxmCD6RJ$W$VC=cwk-fqi-<9RP zvnsxrP^p*nECL96&R(Hko&;_BZrfFN5T!>%@6bckH#tAnsCdyeQ%V4M>tB-#mFm7$ z@vH^41m?X~gn0bjT^-s{~@Av{N|=e4`H-uz|k5By?^e&r0c_Q+=|lVinYT z@oK5lVULraNE3j4ooIioz1J%1b;c`Q#gDppNev9G*9v95)~cF@D)bm0-m7{S$Dd zm0|m*eMvHRHtiOnYv%OWyQZqX72v4@anUmnNge}46b_?4%y+dIr)U#>xFOIXK44`> zB&q7`j8muF$M{&I;zHMMB$>NB*+)rsFg^|lPP>z&seN%TCHWXhc2vCW^7_x4rfYT{ z%%#Yxod;_p^yTrN2g@_`1-?eq5_$&E>Fb4p5am+O`SC`@w~Z42dGH5F2_`&dVlQN- z+j|li2y$jo1_1vN86ehIIA(suU(nUd+n4FWAzh(M7pmE!c=Y!3!}fKzz@E(6L|lR1 zzT7bp8~c_8Aw?oFFsCPoC}9p+kcuZ=6aBq?DaZs#8e9t+K;Nmow`*Cf3sU$#@^Jgx zL38@@_}f8q`YQ5wphxHnlJ+XJ#NVMp$3h}K-o88nn*{>FTtz5N^H#CTAfQ5ZkkzBg zeTVT+7!}VOWq!xnN5wI-GN_iy0E%p?GN_g+3)NDgC26Iq2&0#|4HcpG;|CHzHw=aEn;rpb!Y$yAYY81ERR_ zgdm;G6L`-Q)8+64fEIZ|$j%lMz*pqy#(owK)So;JPaeV}uVi7>g6Wn!Uq-O`6qHm0 z_NgW!L<~h5kMaTVWNo9&rm&=;2~eL@#HbRXA}vje0hDBJJyf1YvxBDW0e%?KOg zDq`cKy<`}N2_w+13B{Zjj87zE#AIO$k_PaKx!V{o$3%3Hdd2kTuJO=Ip&Hu!`1mf8 zYeRr!K&;rzPqT0!+S`e|$%GxL*Ib?Fy#k+LPA+u``8P9Vq`j8GM2joGtZqD_EK&NYA{g8Y=xFcWIo! z84fD~X1F^`>CNRG=DyYv{T|tiB4g z$KxICox+UWuUVd7uE8+&dQ6dvvwX6UB!6xoEPFq@j%oU><^`cobV4Y=_+f+5oR&{4iI=bzpo{ zu396_ca&gWNaimxZRSkoz365t%#HKQR?P9kxyp$$`7`53U=Ba-+{^aRe$xP$>zomE z=NuS1c@EZ_zT+zOSGNyzwUSPoP_v?)e*umKT76o|Be?ycR9~VxmQu=C#G-(RVsVx+ z09;IB=PD1NYAmaZ_bm&gAj~Wy0IG8-lrD)Ag!KpQO9&fPn5uR&C%y+6Kf@@#Ni7^A zoUCKkMhKG@+m>809R9*;NtqbUk%R1f_8j0_f38?KO&Pmbt-FYhD4IE z38D>&oPyyC8CGfhCzwhy-xm;C2D3hGF#l&)T%V}?0(}F$7|a(U+HwAbG$SMuu7b}b z*#AjS2qY}wXG?gzFqD+gW*ETSBkeT*k}e#OapbuQt{K9WRIZseQzZl;y*MPbE7u_A zr!AX9$-bW%qFY=5nXLW)@=`zK)%GD-P6p^UN|sXxG!;HnTpKH`#QoZN@%E zJGnC>x!BWU1#JKKH+3+@#1JQ+9h*6XMte$ z{8hN>sUGNW>Bbb3ejgKl3!q;+5Bjyz?{MJ$D~+1nwV zXc;utGy+CpL6eJ>p-0LWc*la5;QVZ(;+_0Set9-)=&Fw`hHkbdiT1_$QhT~p)Fzmp zbw>9%LTpKjQ~+@?RcOrOUOF`D481Cpz>u|HiO$N_C1aIeh`LQjELEOWWc5c_4ACKg zB96B&jbdIWQ?eQM0wzjg$N;_Q`Bu32RgkEEr(i6$oi5S})`X}XOj%Ahpnhw07_gqg zt=a+1vPKiY3$2n?0!*jvTai3zhZv5m07d zMP0C@F%hfizlu0k$uP_{I4R0aQ8Ft)QEWUz+>tt19P$MBX=8JmLm{0@iOEUX7B!h2&6#9> z3jC9f4D{s&JHrIrNf?i8k9Q8l)%1}m34k+ziY)K#>w!TDot&%-11Qt6h+t6-8^wQA zToVQBwco}x*}ZLBg5@n)Cb=6peFeuP_kpwk;)&!IkQSi$C3%Lj!qoO4&rO!MIFv!x zQSKVT-?3|agY!;f@@)kXm?~+AI7eukZ35f|=0Nj7muB!mcOi6I7Cs25y>@oyK14g& z!3R-7061sxLBJMFPdK|}eg3h&hYXw)CK(78z{Jy#eoo5|bU>AX0!2Ur0%}Yq=@Gc< zO(uz4jSeO$sHgLj2s+a~ou7tB7}NQf7BV(Tk9Ue8@?B`MLfx7b$|NCT@oNPq#F+E! z=fH`{@!78pFfo-kWt{z{oxsHQ?vgrmN{h!r08c8&?|hLXWSU?YdifeQfQKoK1e4gQH5cMi&#y?C~cCIt2%)O|1Fe z7PEJd_S}Zv>gB?~+UQTnD;BwS1+5I|lI3B>{~L?Ho7kcRF*N?Z+7m=oL?=><0UtKen0%R`{Bdgn-;{p|?9NG(&d_j;_Au|gvuMX~ z<5CdDNt3t`AsIGEYr)wMZFaahEeg1;l^{!Alxs} z452^Rptiq}?QTEnH6V_clAQHh<=A3&IdBEEsnZQCXosS?jPvXG(UZUC8q9>bAw(Qy zX7W#!a&u1%HVaa`Et$AM@YPFWeMD#S!BcrU)Xk3>znPa!e$zE*V%+HYL)jx?5(%N1 zJt&V{zCn@mAk`68Aep%J^?+^KiW-yy(n8dpdI!eh@4@NoZA0WNv3W2%_q@_T$Y@#C zi~A1Wqv+tGa^wszTuZ00M3DFYph_?q4r}D-``{=?-|yj_6rSdC*7Iv3#cbveao&2I z00FF99XVNmAy3zf(WL#%155x|$?H=_zi2WF!}>L`r7?NaqUU65G!ae3=vGnXqUWGj zUC=7GUK ztiyAuJuff(8oJ_i>tWri;{rU;oZ*WFoa)&E^Y*=5YG-rd-C{7mr=3vkTO5+ zxkb;k4)i)Jrvn;l8f)z#(u90tbZOMQa`M1vaC;ZsyK7<<`Ky!B_H!M5?v;M&?ZVv{ zMRnGFtXRGAG!*NUouM;^eH9|MNTLf(Yg~0cnHeu$1N*b|FhS9?+;-W$ZMR*PxBa%u z^2L_~Fp#%hR)D&=!eB59r2%iwiE#z|F4XEeuT?9u9^MRjoFQtL9-LN7XRxZRReE4a zJIsl~%&ff<4;AnSQHg8E$V${SRRLnG6@Y?Ss*o9It3Y~SM)8PHJ%D>nXZfG<@b9Ah zANwpK$akWMZjC^I&=gDy6POS~guy79yk?{xNlOPKX;P3POIV<>wyITvFPI%CUMixB zfMCWv{0EpUH<#4gE)vJVYOKCUtQ4H08UIX}*DW=^S?oJ@6xqzzYRG70*|Fs|p1xR$ zecZX&U|Z?y=^4OG0UH^qi9&2rFE?tFtH;3~2F?2+MeX1tAQxRpbX&7ebn8s!&NSK* zql9gL0mlFC(eJ~sFqmcb<7vV4w#|FX+rB(nzG=&&72sSRg}-BE!VASoM#cX^!W^(^ zsrKGZoV1sT16d;&73MwiR&fEO=gj931c5s5!cWs9{wE-EgZie8>baZ;&^c}U)HjP0 zvD`uLRW2xDZ9l?@zQ|SL55hRLx=+v#-}2Cdv(Z4@w)YA%@H%Rdzba00*EU`Y?9bd_ zLyL3dLXKv(tN1Al0udGjc8n=OWBQ24A+D06K5ErDnk4Ws>Y;0}PqgiZDCv@1t{AKS zQOuTL@B^8y#7{eOZPNB)$M8tkdoHfeG?_y}Z$i60{^kzpV@81)w7z%>h67un`)Tq% zpm$wkRj589a(Ap35UQSSR6I%tOiL2R?BoTl0*=$n$n7Vev`RSYSmbZ52|8FYFj+0F z4xbWW2GzDo9!Xn|#K}@tv85XJ>lZ`f%~8#hIA2K18hc~k`!{#D41X?W8}O=Id=&<@ zY+bMwXXoaYX2>`*yH^N6FSV^enq&}KwMA`$@V4@I+5M5v+}0`xMjD!Kpjv0N3s3ZMj386R9H*z+&;S5g}r%V7R=!j?vvxrw;BFW5S3%7t}m&)Uxc>@ARDB$ z!$c&o(nqF7AU}o1GBS^p@kuc z4>*tLZhuvMHGJvH3-=ScK^}iqu=<2df2{k#>gk#OSd6GTfjC|@Y!vXhRVc5>N3 z0#fhMvQx??bqvJfU1g`9JZ*AW829yvoa_k%%04rr>%@~!>iR4zVl|&y1Pp+4Ay~So zb$X<^b^-pksHx_RPa<1dn8cs)11_Gjc_A~ls?TaL1)u%_F}_=?aZl@Quc3eG!Mj{Z z05021-}wk-44-?|e!>egn+{Ec=y^G7d=2{Rc|gVKW>V9{-`4%nmd;c>myHRcF>4Q_ z#!POYekv0GTD?ULgFfoM_faSMC}&;tMiFCU{rZKf9Jl%9-mAo@s}%pr5lF_Y?VVWe zEyK8lthlqiFzFAV!ubt>+NoiBr%b8&24VG_HE0(av|@_YAgJkzi6vjE?2SO(w+&hU zszkzEEF!VoRe$Uu=#Nt|itbd4#J>+?#sk*(c}wQ?17D0xk=2EmSUxz{iv}(FI7`o` zgzsBL~Z z?6nFz>bY9gYhXux#T>|)a95-nyMkq%ZH)KfMfB!&E2=KOyq{eFsh+1*izZOdz=$<| z)?Vgl$I`y;_MG*}Hnd|?txeI_xRsOnbOHrijXFB#x1*k9BRyB-p6G+f=3HAf^-H>( z)W-dax_%IS$7gAAo*$F=aVuwC9*41rnl^NK z#>%FbVlp9B?mc`3^frD%8kS8BxWf)K(y^7kNs$*vRcPhGAvY=#Joq*{EMypOs)-7E z|4V&hh+(g?bXL5zpIUToG!{SU_!DO=0tZdMKwwdItas7z$1hUSAdB|5rHZY`U_rN= zByoG(U3~+j%B$>cy4?i>y`*dq?JA>5j0o|*-o<5BEONqINFJ6+hZ6V+3d@~DhD#U( z(8mO2BJ#M3@xO837_0*4QJW&rs>NeSm(VTq0TqeQdfvsa<{ytlKnJMu!h}!^Z}AKX zCL(bJ&>Za%z_a!b5Kj9I06LrXo{N9YN)YRXa)^w6N!I9h8T=+k^kFl9!{B#Vu_0mB zzZfrKxW#i8G7&9}03*a%w?&Z%Y^2=A*sO26`Q2HwaTG3FICL(ryZOUbF1^s79GWgD zdr%d=Hji(#CF@HRVlB|=P&4#G>kf8so~0Gv!2f9 zKTb<9Oi66ktNHv**U^#w^ODf>$I!?!JTTbUtZNGR+peQTylzCi1Q9a^28Jn{^?g7b z8xuSG63eN+jy$t;jL7@F0{$Iif==ShKFg30#oXrM_vcOMZtv)~$M3ce9TD%B9)4&3 z#BTHzs`4Oe{h%1m^8d?~`*ZeWxHo3AE-K^?+r_6-5K7NWKeyfl_mOmkG z#(XYY%;zZP&kOnYC`*U}bq$~Ag`@cQMV>n9(3##fiocLQ8Dm&C?~{2EED*L@Qgg=m zeh!vla^9?0NAX|hmjX`lyaBME*$HwkayTzN2Vyv8-Z~oiS!rvE9F0bn(Lk%p%$G*< z4OSA=bNKjpXTrLk&f}UkF@(LTT(Mt^u()r>npy5W^#2LAFzqfy?zdLmEL%vqs$tP& zY(M9ijFx5V+1!Q7h5e#(-_2-+JQ6KDU$(_|COYIJ**n8=s<^UFJ@aXvz64y%FsLq8 zla>DOSkN!V;1Yk%JE8PG5%!OA)g5K%j@#|6!pQk=;&VU#1>)Fm#n)NlYaPD6EWW;t zetGNj6o+D#`<}&Ay;`(u?MKbqyj6k6@|3NQ4q)EqUDuv4E8p8c%*vPc3$p^2C))x# z#CkjHAa7%1X%AH1=7GKAS$^f&O`hfA-R4>D+ijlZmxa5{vs{qQv*ZoUv+%rGPwxiL z5*U(ad3V$v^DK9d&Uz9WipODW-LO1Mx3tTat6eC8U8pQ+Teru+fLgitq7`)SvIDzJ z_Itz>H0c-7ZD@qPa&~dB>mVQw&FF4iyA|$jd26gx#)Q#YM zq}$yhvx3+U-1FV;#8DNG!mc4f*OCQTdT=M`TKO&U1Ld~^KTt=N=zKadTrj3!Mz`Sy zs`%OQ1Br*Eay#w#fzorY@dMpX{6JfM&4$93i=)1RTy-t25se?{w&VKh9EKu}nOfrq zy4L^|_{IDhKW=v;5X~ZGCc!RKQ|vOPW(XW z=fn?`eop*A>9<$-f$oF2z6zgqB;fiw*0r4C`g*ajt;gc~e;wC1e|TKqe8Tm0%1Ov` zq}UUs!9r<pG8NRJVgD#v&WR??aA0cL!ki*F903HrMQzw|p4 z(H6YE<+cgi(S$|k>n4=reo=4lBV=#C1!f;>R_xy1&WGIF`H*`%&%U?ww7s4GAKly2 zuz}^CrLlpf>jU?8@b9jQp95cbcNm|Hy`BGu?d|;F-u{v9?UQi8vesV5-cGU)OL8PY z_y!i7qabBL)Q^f6*;Zr<*4IE*!R)a1+2Yv1mRA; zOqI0nr;2R}ZRTEMJ;&uX6u`z=Xmj6Wst}Z}Z&8;tZ@k z=i=!sL5JyNf%|yrUvqkcRGy^hw=wrjqv8>$O7+0{`VHcs+B02#!SV&H_mdxtUd)hR zMJ)77m)CgKMGxSpRWzCCVZKjuT_f0q6NS%*yqi_ZsoWhfDjtNTiVj#efeA(lF%5h6 zaKiqgbaLT5Q9JhukJ{bjs<_WRM;qxSyXde1A=s z#0H^cDjdLru+|6Ba$)|jeOY*ry7X%}7<(1PJ9CLQCwKK4G|*yDBz%=7?z^&B4($pf3y$OauCYofb?3`kKZ< zfAGvPUhu%>oSeIZNA11{%HQ8A+=IeiDx70HT9{GT2jWh;zl@R|9<{>d7z@6rF!%`K z&~2QY2;_wdSrZ}ZHYTiqrIA=l&I599RI^*GH#FA%;&xw$5_XI-QQWjf0=ChQ4v*S> z8#jvIJQQ#Wv<}k5jsSO|p@!vghu?JJ=W_U+DEthE-wfgBmVR>u$U@cPrA;TWyu5V3 z=`1fl-R~eC^?`#&olRa?+ykiDl3V^|#!OiBS!wYv*Qt99#vabk-sJscJw7R-FxO^ek8L3sC5TeEmynC=8rz?}XqP0bCFKx+#O zuR^iUk)&$wd_n@#`A77l1m~lxjp8c|pj4gSAXgB|mKEVj|ka1>+&0ex9YTJ`cjH*;Nd`wxZA@MO~@DTWzGH@7tOc`NFd`uZ^;bW4U znm!yprjD~)_?WVQA@DI};E?#3GT4TX`4q+p)lQFQqWSLOV^T_E!ggy8SrehLWdZZb z@a*`QGAuhjrVPuDk14~l;$zC7toWERXc&A<2}^{_Jc1KpzT5L@e&d~v07HDQW43$5 zGa>U%`3}u}jgNV{aDAxwm||e;IX>oeHRkAOAi3;|@{I|rJ&?&-=PLKzlCP&L&H9`2 zMt_$>zcib?qS#}FIABgM2)dvEHt9PE_rwR4f8Rq(HJ1=y(3)3Ddi9CL%|XpI*u2H=t{J)G@5Yj|(>G zJJxT1wUK_Mtm2EtX6{cdf#f-okg-Z^Tm6gAW4QqVy;iv-D(Ly|%{Br%jDjU37s z1o;te)!Tu!$h;SW=b_RU14dE1+Myocz?P94kyy;aJLxa;yt=p@U0EjZTO zS|u|p(l$d?axV;mz%rg{yEvqoRZ^bfXlItDJjG_GJYi?oyy;M0MXchce3*R0$*CL1 zbwYVEYY(0J{1SqFg@H1L2~M>%Bl!&4KUu|}@@EhW$9!e76*SiVA3i1FeSR7@tm1u? zVKI8r)GE%57kI1@E^KNFLJ(XN8Q7%N($@Xb%cFW*xE-mNx`2bbKQG5`Y5N%4_G6CqCQqo{q^se$EVZ2eC9p%D zu9y={qyP>JJY0;8%NRfI@L)d-DU%Bt3&$T7T!sNCP)%=Te2zcZ(>@r1F$IYy3OgB* zBZv;S;Ag!B$Twx++AR`RVR9y7wE_5HgO^(8uCHK&AnBEIpvXdN7<*W@IuicgKz}Y_ zxwfL7>o3RA>s5uoC-9`83-;B zDxKRZS|RdjP{6$O5PR|Y>4Elw0F0@rLRJj{c-dSl3Ijf-4$v5Qg*J-76o?6e_b&#U z(ij@-;UUJaH8yf3)VLXAqYY!DYqzQrUdFAz83X= zQPrOyXj&SDT~4tylN;?}3S^d?Hjr6zifs(`xo9CLw`|~%M)Bin7b8#mP9gU%^0jXf za{E$o?E!M{QUT6wP3~VRCufk{#jNa{p>ijqP+=ZXY(;VdBfqq5Pi|fmptmSIap~6D zcc|ZhBSXJtle?#JN&T9udDMk|^`Ku{FjvYk;EWrUDGZomp$SFv=*yU6^ml_}9$9;m zu)vtB3a>zgH-YnOxsodUWoF#OeOF?hpl;djGUPq{B6%Fn8CADG?O|(fB;CvBu9dXg zn1yz#ZkX`&_LsBDoexl^tvB25GPG!>_v?`UDfdn}iT>U32;Ib-1}v#^-$ST8{>q%| z(C%VcXdIiVt@CR_Q%Rve&@`iNDtYIu%?}61u*BWgA>wJpYDt58<-VWblI#~~FC8pW zzTcwFe}d1etUm!Gakw){4kS_<3zBeg$ObvCbNpl8DU68GUvx8pGB;Xwm0Mi~w=S@-Fxq0D-P@!3=d{OW+J*$j=~1AOY@SV(2hf zFr?doK>_R{vG`0tAm2~13X;|O##paFss1VB4TkZMODZA!dl~3Xk^2=oP;#I%C9?3H z#7BDwt{Iel%Xt^5Z5|4|o2d=Go$-OL=+w?0(r9T<_TDdENTw?m!`^2q2`zT%7i5(;xB#(mcqGzq&p<*|Vfhkq zv!|T(a~Ho;7hM$$wGLaZh@cCdb(I0&D^=^k4@%lb5zM5&GWZiZDF6+JEmYaEgbhc+ zG{BXHwwK7!@Y~(|Io)uPk!&6Jh{>)52>lzRLg;|MUC@|D;W|a?l z_+QMDWK2~`qQ5f<0Jgt-pbDwl(_oEmBYRs!4Bd>G4;I2`jY?~Fpa>lzIl96@h?#E} z^6O!nL{QW0$l-EG?@+9JoA+)%apHiV z5u5CjcwNA&LekD0-@`|D8Rgy^FQO~HXRtTWYf!n5^D%Ih`$og=AH6k{d#@Zv{@W4b zArWH&hZzFA(Uki>iLbc$It5?Ph_5PqJ+X>H&p=Mt-+c2-3xZG1BohWzA~Xiy;v0zT zc>!f?IfcGH55MnDqO@Pa7fqH^?=eQ-%MTCDhYj{2i-Jn@Z8-(rDK- zxhP;$cYD3#=hj+Icaaqf;-f?jidB#|{!Gio-Q(xmT*i0+I_sF+HU2D{i;r)%xflyQ z;&PAczzZcC2Nh3B#DcVE34sviJC5@!f%Wjes4U^HnzF-R=Z_^mC4OaSre`3Sp(8}FGZLP4ZRQVN%GbwNfM5HMXuNnFOg z1-e!NN^%D!F^p$3lRy&nF-l?>zcrIoRU^qZO5!&Dsgj&xwPXhK{gslqjcYx=RyT~G zq47cH8%+Y9`Nlertk*?(RuTwCmm&0x0)HsnfXo{yDr|;}n95#wGmOtF`i_F}55rw? z%jnCwKMS{aIpcETp=Q zX8uq;>iQjI0ciJnGe79?*6F+_`RmQ^DgGMsdz!zgsjf<8KEq#ae$Vt*nUN}uyGNn6 zxO4Ca>kxN5Dn199;FH==@2{#+pN+;=5z_$fLKB6bf$*U5XW{9l0Yzn<4bQWU6{96l z;cXjG0|-ljLRGSv^!$x2fQEd^cS|04iE2gAbKLw#hEehM=py4el@oL1^dxd3@`hF2 zU=}x%m=JS8$8KJ)wxyKDaV5JrRBcX!6{BZ*(PN%#uM96?~#pB);WyVE^ z_$obo90=Re8fL!FLD+>EUq3`r<~P8=v61EqNR2?+820xm8yaoKCKdBgD%Nt~*qgU25fs`82u!IUeJ0SfFy;iEli9q5F*q zyYSs)=HNHBsT?Y-95B6_C*HEadpTaG>ercttqSJaW7?&L3!?C5;?! z2!~4ZmT;&vJB34~*)5a9uK{J#r=Fc--CH}gW#v0QJL`X5$X%3e911(KK)SgNx^V9J_IVSq+<~0Yx z4K2;eW0LW%oKWCk?ZfMD9@m5^A{(@uvccMbY?Nb$nT_(8X?)Ko`^=UN!cGRTQl-cS z6r*hBh-{Rj#>_@})EldcGqOS0=aEgL$Og2gY=R;iM*b*kUN2*I29KoovNJGmimO6p-nH zdXBxpjh9r!3vD@~C3T~W32$+Komft3aIMIPLr<8MaER5NLRRG)U;UV@)jPJCfHq!+ zOfJv&hg%!w&ZYTJv0pjHPj6Ie$i9YY7_JIeWBEd%Vh|r={9ff|>mtmgUr>##=qdxu zY4PMG6Vt2?>!lEN_8aRDmo+=iq5~%4v7^Pj4m4IZG!f_x`U?9fCJA{2}QKd43$uBDlJjtLx7S`I8=_;)i3W_;nP~ zvF4iX_O~{JKGby{e`~eg+5q=brT0Rw@Q+lffm|YjOy^h?3L;V_r7Bc8%T%Zub`w>o za!vwxZg8He>iwhn)(oS^K(Rjk)g^`J3j~ zwThl1Z5wi+`ZTHm$y#TYxu}TWH_E8Em>{73d8g3;bCkVVwxgUi@>4BugvLDaRSwpET*zIqJ*yBSe{bq*DE)*XI+ z;h{E?O2j^OM`+75qs6m+>*x2{Q|eCJowV1L@$Vmcl;}o@xtfufI6UnsH3sC35x`2J z?q&`wHJ(BP9XhhjqNt!KA7V7Y+mTas3}E*n#Ufj7mM^P(dOY88=;5N$HBo}PHH%Ce z)oD&uecunfiL^3d!xf&k;@JMGti1gg<9pg$d09FC=b?J+W7I%^9Af^Cu`fxxR0b@P z|L=#AfEQD)oUb~}Ha>Lf4;rnGTq<8L=T{$AuGfX-c$MjC#RUe;KC)SNPT=1?>?mTr zF{80`iG^MEMEamx)U&iZsV)uJtlv!Fe?&sXZR480JB9^DRZN@^z=ii`j0ZOB>WO@{ z_b6JvfJE4ZXFX8EmaKD0mNd^z_KvcKmtmWTvab?qVWsOT_Pq1WWq05EGyDLveSPQF;mS_nN+RT0#v2bWeg^7HQAj-Z z($)gey=W^$u9q{2Hblik7Bpu^yGo*=0cg?oc9F{{!G0Exrs&&U5^d zDPW>~nSfsFU3bap@ zR_5XL7tcI3 z(L@TdDNCcIYOE5IYG5V zCpAqrscJH{W*I$*%|P$)g^dz z@NT#fH&Q;bwY;9bynlkweLA+wRAQtB&RM_M{9ygB=fvsVGX@89R^hG7d@Ou4RgmNb zjJ4c%JxSvLorXRNh}v)AXQR7*_XvfXPMltcx{?fXMEc6M=te}Aw8tX@B*fjBBfB%( z(VA(cM1B&-m2E2bJ%TR*2IhMjAyO`a-12^-9FimQI#yyiOCAYr-o8)mPQ`i%c{Nup ze+@17R8Y&$h0;&C_v?4jzqACDd!M|GzNg$l|6cY!`4Doo_}jU!ZOmB%ccOu3lQ@%V zplsUATghkaE%fhazCr)~L42Prn*41My5M&5w;EpVP25a#(P?vUcpOf`A~Ywb7}vR! z@^cUR*i5V+QkG8+Vf&Cx$GqCpwh%sct_ErtZ7Ds2+ER57{Y(A0uX7EWdpWEB*{FX_ zBh|d=yrD<1sCZYZ#jEUt~uYw7M%r@ z-z&gH)5;!(u6(4fwf4-&3DfG&Vxzk0W2soC+jf)#H7<* zO%zZ!_cDG8h_nIp+Fe>@%*~vQg_Rf!&o8v=eXJajG6L~0`&bts<_^jT?3U2MK^Xxz zKPV$Wq6@gNKPV%B=Z%9h0taOT#FO1Y8G(ix@uGH6MgYsgK^Xyh9X%)`V2TtRlo5dV zz(E;-y^s-@_0Cay|IDtRHJ2Vz`2<7_?5}0|VKU>XEaO>o=^<>^%F=y()}&m%Te_D| zmwzwa^B2gq$L!S$;fG2mr-`=W8;Pp!f-^J`R=$6kixJ>w>|Ds%Q-vs_OhYHFzhMWsawj1lf!Vtoq5^# zVFWSkQ8OwubMyFNB{7Ci{C@fHq8Lb>+2h*JAwiKtS&UQHO&n4dBdx+i2xFXoNETrX zczzhd7^nVV;!xrb2Ag@&u|tY6sHUW{%Q4VZBjgPB;r=Yr)zhA{JG9IH=3`qra5wcE zUIf8!NSysfJfD&vh}2{e9&Uew5Qd~ckGg6N)-*w{70;Rxdd5{cy$>)vHmmD?-yhT) zkf6yX{JYn8ijkaZ$*%`dHlIV6%(u>^%j5`5f6D7+v|-ymwL@5c%H_+{^Joj}K)@PG;7^5YQYQl>&_|nE_y(> zXa_3ExSQ8%J!?GqjDFTYKc(4Z*~2&CL}yn{ zM+AC~-swDp#&xjP5-y8J$(o!x5JP<6vge$FV?h?-4# zkZMNH_~w#7B;9iP3f+dft^YRFjV#Jobz42exXUFM(S^FLdDyDeP<@%pm+l1WH24V7 zi(a}ddJS2(9KK?okGidRlj3xerZdRMv3!Wkz+2(q%@a|Nm8)Q5w}+W;9KX#N>&( zq2-ZG_2tfL*D5TyFFy{8z)l+)n&rL{60f)5u==ZC5SIk|q4?R(s%E`&dI}BZ6|*@{ z+qbSE`H&u%bvCe3uG1if6 zPcEMtz^Sx?{gjaFy>WXxBn3jX9si>nfJdyl6&AzquRyrvQv$? zHTg$pM>Qu8pz%dCdkMeSh;Ex){H;7|e1UFZt*I&LrenX1Cfn#XA5FK@4F-2uEH0En zq@KaC@JJ)%zmbKVkUm5ae>OSD1Bi};pdpQ_RTu)Z?{e|&HahC-M`3HQyS+22=BiGU z667=ID&2L(y89B)nMq&}em#?RtKfzIppA!r54>-WWTbT2f1*$q*qu2D%p$m2j_5ZPv*crnG}TDqv<}6(*tv@Yy&-M!CRM) zaeAAJzwGv!Yd~#q8cZoj?N!Os>DU{Iq!#y=k3Ax7``wNh_U-o{aLd1G2jqONyd7&L zeqrdO&A!jYpR&=Z1_-`b%&`Qi%x#3P5X1`7&*$?49YY84m zn70i(&EFLT;|C=Dh;R1Y%{&`Cpx>)5e!pSOP4LcSH&T#K$D2d+vdH%wIicJF_^cOU zJ~ESdXT!@r-o6O;SzxQBD(>}gEsS-y>+_uJ%C3d|QY$ys+YOv7p$vWH*=HqjIQ0Gj z>TLZ;A^*w_NP5%!Zp2#X83lUZ0yS$Jy=$OZAJbD@M|=ehwh{a|>`SrE?!~b#7{#Tf zzyl8(LquLY_$(~c(chEhAswxTNMa4iyVEIjIXu#) zbT_>0qjEXi^k?I-JqOPH%0hED&2sEu-jlINjC3uBS;0D*$J|@>(xg{k3o!) z)%dLPW{yFI&Qs_9(M{SuI!liRE(EZ0L2BOt^7eCJ=l^$9&<>+Xj2AEDTN03O|#?cCNlapdA92Dz- zD`PgQ0d@e6FIul@-6=Z^G+XQ9^G%wi(Mm^r+)1mWJdV+|%R#GOXQLG{qWf!nb*AFE z+~Ahp$2`yB_nMcn)9!ci|0&298ys#hLn&cfiR&mci7s7qL+34eh_gq@InWy;YjD!% z2J#W}(1-9Zz;%|%q@GJI?1(yb8{G7_xAz&2IhkXcy?HOVchGFz7z{AnW?bNr+$m_* zh;xnPl60hPL=>^I6Vd((mu;#^UcH33393n#yG^~_P<-Bs)r|g#Tad?0_ulhPIi^#^ zx0&Z`{N_M5_O$C={600dU}>s9Dvp+|(enm?K+U+0T2u&XiPPj4n>jn3T!}7P-NcZa z0=I)YVKIur2Ow?yk1)?ok1@~7pv~-`xcKX86AY!g0H%WDH240v9>#N3v?Y=f^bpE0 zEZ%jH>1DWVgNoAe;4U{mD*+2u-h9M=kO&t|MA~8VOb$;TKGd3=mr}4eV2iX1!R*rC zj02FaMAOE{ndglX&~<~0-(k_UA=PaWR>vEQ6Q*KJiLmp@X^y{{aAgqoZq9AAS}>~3 zT;sSLjtAtLmUtNE_AuDCe++cPYgV`1G%*};qO{1Sqotf=d%!`qYqF7Tor7%iY2xk| zek{jp+MVl|=T@x$8xF^sh8xR zywgFjRYVlT%H&-t#rUV99td~S41@#=}ku zyyKw2Hbnu31@eG9b9t{|o^t$Fg9fv|@8aJujtVWP3RW)+*WzGGe1?uuf-9w%JP=%p zv)0LQ+IU@x$%9_r76~nDPr!(?OboBK2pLEQu$YJv@<{h|c3UE=6cz;1N*_4WeB0OsB0 zTZ5SZ_n>Oa+X*5a2d8bK%g3mR>P#zK^VFTwetEC!%q5M!2>MX7*AR_h+w)fr8evX4 z2&7}zI0(I|OFwgt=h08&wFS_`@^UZZA)KaI0kdD+w#E|DMT6;bR zXU5ti-sU_9933`-2Gq>ghz^&y_+KqLz^umrz#Zf=tmCb5lH%TMq@dd!2=p9qwD{vg z%=0dOsR^LPr7r#(ixvuiL=i(reBMcn9odK>bSX*?I9kx$$OkQU5-q;&;#+LAz@r*T zx+`Mnm<;bown znZqF!FxpCVw0b9T&dElMb27OXn;h3ZyqD#YF6Xbu4e9;NGxJ!`1$q+S%rn^Br`o=BrjZBWrhM@%_sb5j~^E*p|I z`$cXpr)RY(*duSnFFpz5W}S;)W6eoi+zuq{Gg8NW+)19}@yHuXV9$V%y0~ZY!oxOp zdGtvUBHG7x_U9=%9LpKfr+PL}j~&5&ytZg_=uw|erByQhxaC@3Vvz-S4(l$`bl zp?Efe9cAB6#Y^qp%aLOdu&JEqa$TYqM|wHCUD0ckq8A2NCcSjzwN85dF`ZtUv(d|+ zguHb2`#Kp% zb99>Z)WH7O=M?()vv68VDB|&;n;ZY;!VEG05@!p0qCL#_4=CQmG9ypT7Cp5;}BVN!^a|y zBne(9<(N-EyKz7-u@nFP0Gbp$J{1}WDciR$euZe(+u*F0(V5k!^vq;apyi$ zF@t9w31gBjCh0KsJkb${t{W{nf-go5wLqRErjDKvv@(f#FFE0|$>FVrSH`F-&ob)f zkIEc%3#9N-+I!U2+=#w%xRz(9uzNe%gYU{WetSc9FLnvcpde5C#{ZyaG!JF z6~o82mD2^s>qrA_RH0FRKL#U16#19-rauyBLd?y4{MHjqpuhFM>YxCc1me;5q(v55 zQgrMZqJy=nU6?_ZF8J)*2%0$Z)-Af=*o2KI0VNB6@qC4$Xica6N=oEIUHW;c)EpXf=BJu>JbWzyD%#W!Vm)~xdR<}8b}dKXD{or(WioE(jqAAdAx!# zGQxOHI>SuDd<&llTD-#f_tgau?fqn>LlQy9>LMao!{dwDn%{v93V&pGaD=tB@(kuV z9ly8G*3*8?`NOV!LM{#lY9f|oSpe)#2h4ObuA|>BdfsGPo`rK{w(qZ}!=M*_Z8Olm zUvYl7)jlN^W;IU7{k^ks`H-xZe{bP`Bdq_9ng_lfzsIS4|KR)vt9=cj7Q670)lQve zA{rL6c+U=U+QhtSMsmBU&9m_THl>Yu&cg2%Y8&S24y$cSn8<3J zj#~1r zqmKWwvyDeVzreoU?i$H$ruNe2e>=7L4bHD~wpk0(SdG>RW>PDyO=f9YqubyXe*&`wTl{U=!V!3%bNhVesX_bV)IKO-)SAP%sUN0t ziPP0lwo;qG?$x*VcExdCq`Rs^p}VngZm^+6aK$hhGSCTK3j%Y4Ex*Grb3KmicjC7& z)ssj@7c=j7kjQoA+3fIdy55EV92A`qCdR^g{HypZvc)zM&PNFv!r~;<5}q5W3o(JV zm1jJkWTa8TSem@5tWsv4_w=^pILKz@PK_ zxYZQwzoaETeZzukj{XX!cnHxp_4`Twq*N7H7 zIlsv`1WVojC+~g0qbjaG;F-HgSZTmD(nytBN)f50h!`pLrTj~XpaIrofh0{?mdz$v z-DH>D4F<|*-MN5@hR8(rIMT?4vii(Peiiq|5oilg#-n$#@ zD}2wA{l5D=13PEV+}!h|!U*(&2Y;KbwiH4!R(IBI>q>wuN6^hG6Jz=?&_XH>_lLyf{MjjHJpo~fMd zaU`pZ6FFt`6z*&SpN;>m9r3GXD{CFjt(OV6=W?tHLQ#folyZ2%*lKmVAiEQr%b=QT zIm(`&RhAs>mvgq|h&4?}OjW8)o&2A0Y481+#@#u$Tt{PyI)!vyef+FJS%Z83nZjK> z04IEmM7_l1>i@dSD$g3^SCehy8yX_v7IK=U2^P(|fhr(mx6*N4~`Q~GX!*F1*8NpqOvd1KIwO#zcC8qqE zYdZ<7Nr7;( ztT{llk#LY-EHr;_h!)1>^r0xOKH`3NtwUI_o(BRe^$y7ELcm|Zp6_EP>n@aI9%S7? zWw}$z3shOMQxRmu%;I#jJT+$6~9Wb~1KHy&Z`#ybLm80eXm% z(R7R))6)Uy9y0EU&>K-mDjuq84k zI!8|kXR}M^J7fjlk3dlNcYO!Z)h*D~9SE^eXyVsP`E4a)WgFGR)S{NqY*-&q&l>Cd z(Z(M;J*-JK#Y2I5e;|UZuCWPt4t3L)_14di0RRWK-Sv& zijQ#aK7#i=Tf5f_Dl+Vll;0?zZ}BJF{B-3swnLfBb6LIUIP{`r;xR;A{~}u{JBgZx zdL}=Ml{KI11GV8^x#(H+yZ+NmoeLy306p>V zVcM!}%D4dXZJC21@%c72%#-e5Qy|W_lYO6Mt_)nl9Wk@n(z!|?4fNAP!d{dq>?9Jl z>RO}F^@%LHPDn$1r%e>SCtOz;MN5VJhWL(BTGYv!a7!W?Xu+kzMQ=k_W6%I0wsZ_V zI0SsUUxD@U3!n#Er2HO3;^?q=UaS^E^UZZ4K}mNL5-ii!jv>=F$n*)qMw00tQl7*z zaSuf;d}07=7Pe+x?-Yxg_?J^+iLdCFWK*B(pwCw#^sInfSnN8U<+AlkGy|Q;ft#5y zR9Xh*?bA1-rk)6rDl)OQW0V=$qKOC#AltCDXeGLkIT`~;46B{iJZ1QLel}a*o^J26 zSuQp8@o3E797-hU3?t7xV4m;Vf@Zqi_IoR}-}pRk!51;_JhOH9it!rkZq}M_a;R8) zI%Y@4LC@f$c)N6$jxF<-CgTzK1fk~C+#!T!sz+g{R$=6yq?qs2HDdg^rEAXhB}cz1 zoANym*}Q#mtoV3p7xKd`7?jU3WR#`kreGZEjuKPzu5yT3fMYkPZK#IGA7zTXgG4UA z+@Q?k@P}%{0!_p-psHuLrMKyQfNbJG7+i+11vm_SOG>{5K&6&n^YkW(@o~aK#XOy2 zG!;{cNHrq1o&c5kD3DD1vaw^xx*Bq>Mew1gIP9-d{a8FMAUK#RXMk-dYq$Mwdcy>Lca zQwjNSjl=zhyL7}je^nBvc8pEvZiwa@4jIDuL|kmN9-HIMm_Lrw!vqLRol;XTWeQ1M zYo0JhE4K*{==myr%`ygCzK1?0a99IJykSpExknZ-2I1hve$yjMNX@j(6k0)W(3D1q zx{gz(t9zoa(hE*iK9uPzhP)Q-Bg(Yw{4ryrC|64+p4`&h-Em|}xG^53xRB;MDR@jzF$h&!0_7oxtbxbpB=H86pIDo0bCD%OOq6Jh^HYq z1|(b>1O0CZN0K3&tUhzGz>sXTf?zZL>mYU`1|3_8&}|~>%w{Qn)`e6IVPIujdAK18 z+u_Ch0!A`c|5)c)0x9|FK=KTLEKLYWQ=W-hp0f@wkIu7J%Tv~Ibd+p5Igf6GJZ2wq z*k27fl*O8ebysBy%0fXLE#^NzP zc{H7Hqj3EvHQi-SD13zEm4@-18LIlaeq-<%N)mpmm~jwAI5f9LIe74FLt9O-H69P4 zk6YxH#=;~i##fCqvfMWGK)XP#U)?0=`O8wC!vI!M(_lI&V`<&w=}9p#gC;v z+N414$k%F`E@^HGW`T;w*3U~HBWJrWR72k#Z$sNv6`~<>4-9)v8k#RfD+4V?d`a|q zmM~j{M#nXcsg@Bl-WWoYYy%E&52iMU2MivZwITEVZ^5*kf~{b6wyDOU5754Q_sFqh z@G1UaAQGM$$2nk8OnR$zZZp#+Dq;1(nB;#1Gd5_+(^@V8lB|JAxBi0(a zJyZSOM89zYCI)GE3$~%u2BWR0`K%=;;thEABOIoU%Q9w##ll^LAST-}!~WjSj7}zI z@N%3$Cp?GB=^85u;dQ1mNaMh)1_aAP37iEBW*f_TvVRiE?L14|VH2_}_tNed5}@dP zkbCHLhJ4P@D#CLQ=go*mO$E`Mk#u2i2O&*Ct_4YQZ9>JNuAs57jiY8e0n^XXnL1TX zL#LgWax8Jdp;qoiz~%tqf?GOQI&m2h3`R^`H0OqNTnb&g zfq=(mN7KjuS=Jw%8|Yqwu+$HnusVH*(OFj)sE%{$o<@Y4zc+qcHN-q(t}9IFSM>+7 zEL#k6U52oqWW&_sttlO#YSE69fzD9o6pn^Vbi)@HT?Z;VoQml_fKV|-mEBFLvLp4* zEIZ9#?-Y-UReC#E*=>PbI}uipY$&_Msj?&4+9^AoVUANcXW4zlI$4%=a~EtjweyEa zzUQU9I#qU5ZsS7a$3z9A`Bpf^vX$9a%>QOtrhcev5d>cVZE(tS=^d;G8wEC_g2J1M z-X=A`I>$yx7jC4s%9Hmf?tVwqvb^B?HwaYy_9AqQ{s!61N72Tthpgm*_^8zFu5D^T zGZhX<>t9SJ0`=j9=hL@^7>=kVFL&pD2$C{58#;{4WNUDCu6ylN3_l)|a-Gy&D@+^U zVgkzxMrzhs5ChK!gpN^e-SPc>5IjL8!yi*JP@90wAE_A-sacnHG#S>T9B@#yyUCQ{ zfs_nn8yzxe*7Y4th9$6l+YmO841baGF4@I25$O(9nsd7n!M?ZhSofVUMtcWg09@OK z?V%$cNCr$b1VET;CLY3PhwE`M%IPp{(=m60OLQ@&qJ2Wu6l2E@&jAdv&ZTH-6A_(* z$j_b*Q+EzPq)U5X>K)<@eNW1n9xZMarVe4!l~|f>F^gwP{w76Il5axHX7C7%2SH+k zx2wa*I}frN-^TJTBpbF%%E?^3lj7lINDHi4;KXW`@>GhXWG&+)@;T!|?}I2mwsK9M zOUZJ(oocK3I$D~@{vYUSzH1F;0A!lm!KE0wD#};_Ul+lzBt+QVbz0wTp@$F$C zD?IBkvorNckaVZx`1som4E2K`H zO~9l;yB;z19Oy7|^n(n$5Vk;$p`S_l12>gFRY#P67Zi_XSm_Yus7lZv7|rfk4jPkaO5}DW8!ABw!?r)9U>V zF(Ea>4lST(`d_iug>&!16~rVwufHe6$4KR87UVpGlNCB6qNGMjZ>eHVqPcV zz8OJoGxA$XKrj|oM~C45`@j<_!w>aT0Q?Su|7c*p<^(LLwAk<;`fPz*Di!u>O~8a+ zbJK}~Cf55&%pnw|Ib)9i^t*6Cj5%G=8PO*w+8k(vr%g9RS0b8LF#pCOaC8ApFdXx@ zMB}KRH;M&dt4$1`pDq0JEc!W-e-5OdCH(Vj`dLIjr}^unNoM*KU#FtXxHA=H=4VpT z63V-lqD{R1yBCM{)HY$Q=SJ}?{qzro1wgDbI5Re~;d`+KjL;^UVm05-}qz$oV?YG*0WQ8K-e-0Y#?` zP;cBdSVj1ao6QL4T4P2y&mxYTHI3P3nh|EJHY3b7oFfCxKWj$RALYo|>I>dSsn#k; z9_OEo-M##ig}#n{1{kKF^G{|7@=s>CfPOYI!yx|24BzFS%utA*c-mWow(NCQ?U@_( zX(U2*%wC_c7=49VpKSAAnztucAGTano8lC;>WiPEi2z-!PL~=@BMmtZw6r=@0utGm zn9*Tu%Ual#2QU${#eu~KdGh4r*{mzmGG^=q^UOHSzknoGmYneDGn}F+>*A)UnhYiD z@(#9?r$O;A99JSu#riXT*9KT`?&6=UH`mfnrC68nPiFA*Pi8oeemV`(^Y}xiL0ZQ@ zxt83{Ke>)v#Xq?o#ObGHkOtD*ILeIQPDPp7or7j!5(u-h+_;2+$Bm9y= zGs3Ufk3%_NOH^fl-i&abb!LR~+|H4~>TR>l2&YV@h_)6(IAWTC-W)M2dm%^6`uz^R zTRkiApV^+J#_GqY{-w5l*Gvu3_O`1r`d*FEH-G5puk80IH?^$wd}8RJ??IT8v{{N1 zif$4^HyQFrohqW(DV0c+v+vx%m>(xwL}sAZev{A{%Z8&OV7NNx87W?--^xe`usn#U zRVhGN27<(4MUlV^e<%`ahL4gTZOu*M3MAB;o{>eji&{j>|7P3+uaD*Uw$%u7s4Mz7 z;&CK}p2iRL^zKMl?!|W=n1!X4)-)`KtuUmgARS9(gLS685KQCv?1&VOrm?+A+)1=x zYckrT`WA` ze-@sf>L;zZ@w3{JH)RWsk-Rar5q`l|nyrJk5RO%WyS<-W_0M^ZXde&_-@DoRW@j0N z;&J#G*N2j!U^2U9RfgeS{lDOwI|D;L>^;~Z3(U`Gibip9f==&-G6^T6n6&U>UTF|w zc&0$8^zj9k!LgIa3%&c~7RWSH>z?V!*{cZGH}0TWI#xmZ7h>7n%;h5~Emd5FBW1DG zGch9p*AeJqGsKTV{Cw9+nEGnFidOtn3W=-2l$H{coY24cRfFEVAKz1>{vaj={Pj4i z3%ae4%y+HAtBPMqF;-(=(Qk$Hp)bQvVaLO`3HtKHHaG?R96Ey|%ifh;Or7D$FQLA{WWy1JJ?2; z-Ou+d#hvd6-7eKtrWe-w>9F+URb9asVO(xo9D1qhC+;C=yBVM3u<71%|> z*PUfvi+|JmZ^uSv+N_DAb>N|OrI*_&X1QULnABW@ z)5~padb#;t&Mdc{kk)Z7o6|;SUFH~jc%S(?mD{#zln4?0d^FP4uM$zHiU%TXh>$2Q|xl9@X)8-DslUOkNUJD@JXZa zMYyKcWS!zH!DZr?An?=OYSW$NlYP0&)nei4w4C}igSm{*kPSZjEF3fYC=+8$Yz#L~ z#f`jbzGUD}iF>xc`5S-`v-As!DfDnqCtJ5ZWzs zobZuIgcI4Vv$Ij;Td&7D^_5n!-^^#!_EW`Ps=i7{&AHfF>dVF5AUN!8w>Rzemb;3+ zo{(DD_1&o#$3%A8Qztyb`cXBFRKl@#`}lXX73sZdF9K$~zyXLf=0L zY`CQ1aQeLgMQhN0lxX+=eB^K4*snwaPtzvBVtGxbl`WkjQ8#yBx!hMrE!y%Tez8-grV8M_&!?k7TkdbRn(GoF) zezULHhJ8|;iWoob`4VSeW|DU_LOo<2hJz1#+azW0D^pa>*G9qw?4rJ)MfEKDNQ$)% zVQ)5tZO`6kUsl}P<)$LrPO{nN5un)P!(ooqF5Q$jQdHLgd%dW_Q!d2HLR5W z5M>aa=YB^Ev-KF>QdUqg$D>q$E)$}sn`IYMeN&Ph0S6l3M%S#>*G=ES)v^elYv9YW z*pM+dY4wB=l|CqSBl-iOxaE<{i`+U#1>_F5((SXJ%lAuhCq>oWyw`s$#dQ>gOH_n+ z#uj}pW`i*Pb9j0ceQKLI<~KGYiFyF=wnuRBFRR~oY;eKdIqr1`ZG;OPTYmP<6fSTU zFmIKTo++Q;AP19mBZ+JQ@;;*06ghMLTMOE85X>gn(DK-0) zG+}SZ6!vmc*u&Yg?8~|<4$mx<>3Wj&Qz-|fWF6J!uWTDN9nc}J?Z3sA<7BJ{i#vZLPqFeN)Acb2hc?M;H(6uK7iG=)A7BziiI zK5v@|-)JmK%_BL{Mt{$e)7OqZYxcG@S?|k~^%hgsj$@-%K-T9G4wz-y-7c%MOf~D~ zG&zmY8D;u`Dd%>SYsYAFHs6XR421dxXmj9&=RT3`FxngVFHjq+8G1q*yT+c6xUH!n z)*peS+SC=6e5tYJv1wClSe%sQ@k~PNftd%4!SIQK_IDnx955iwT92q7dV}K-HZ4Rc zEHLB`xkp3?wzShBqC>58h9)W%9yI(tGOqsY4$@;-%dz?AodGz8S?%nCGWNlqQg6ID$9Qmrd$Ud z-X>+IB2#~1dPqlg`WB~X2NAW|R^ogMBvn6`Te4-?)@OPj z)VC(#7Cj?~t!_mNM1PR1tpuD^dPmFZSZjnv;nZoBl?GS3!|7l)G4MkE287kXfDZia zVu_xlk&_Z$bJg30zp_0^X%2y&_WT6MekNksTO^qcxt5S@*F!cq225eus=Txrv)xGq zonZxui7yqN^D#HDk7BCL9DE2HnHYoA9KuIpGYI1`q13DB1ACn$rFj@h3XsF~=dy`M z1X#>OD7*o9;2^9jZZ8QBdwY2hGHOoG1$H3LMa*V&i1BogSip`T-z>jy--ply`G(ogJCG}|k5eD1{8F%Pe0|3?MbPsBjeIAVi%7`8`nh z=?Hq-4P{u4u$W}TT}7um%F#J=)Vw~YgjZ!qc!`p*Bgi)e<+ljo0Lh0D<9AZ>rB8Nf z&XrE-UdfQ|X(gRwP0}$(oy~ganUB>Zgt{fLqgZnPMv-Yl(PyIuL#H2dO4Vnq!+a9w zi6E)=VJWoJv@ec6TQ=pYAu+7}+J`WS`K|@3zqZ5rJ_qiNv2ZkN9X4A2xeB4=CIAoP zP|6MZdEPPO{bg_i$N4d1DlgP~woKkKK#YyM81hlqYo@adsEuw+l|hG)k>uNqu$p9i z6{l}oGLC9-il|waI7EClQ^Y@|L_F*oPgcv3h2*P;yGxRFjY452}F$*Ng;_D51(EHW$|J@;f&P?B)$HrZNG%ua zM%HdyYJR8bhnF?Qp?gPKet?~IcfwFzZ^)$E`~ure0pA>mt1e8w6^y*_ybb+1*Gt;O zZgL+W+JmC(TlYF*{{f@Tl+ioh1xXe!Ht1au{7q^}X%~*1_(C34r*_Z(Jw~_`LJ7+e zMz4e-ej;VCK;y#am-F#Btr495E2L(vW;hfy57O_6@C054`Id168)YbR1xMhpPmyLs z@U*u#@EFNGx*rbZgWM}2cWQ5_zK941-wsRZhce?HDp;Lq6Ul}x2c#Sg7vi_+8Qb?9 zDMnKqGlPxTB%`-w_XI6XN4kI{i+^j-D+}-)w2f%FkP~_mPVLPN9wVHdfd0}qR@{wx zgDJxArEoD1h1RF&OGZeu&mj~{gdXMJizST3)dpoQ$KOiT7jH44(f*!* zV}!>%d?S75e!}AeDT|NS^#wEGrDP)n1EKl0+khypBv4Xz#D!>@R_rAtl*|$QZ}vga z=AJn=T#tL$E(yRd@l0P+I9~6^LDk6_XW~%qP^E8t)tOb%)_5>k?9osxLT^6N6@ADl_-q!$>QC&UocUDQ4nNUxgsQ%+H(p83@vA zi1K$iZ6)YyDec+G=eHySSLrdg_EVwK^i6F9$b@aH6iqCM#u+JJ%YT?Wu!Ew{7z#HX&UIWDeVE5EBXuw zev#4?` zfl`w6;&g}NkBpxCv9S~Ht7(mlkB1w>ErEz-=>GmCc_=4qW39pRa6FNmfD`0&s-71T zp4Y(jUHpZb*5KGcn@)%EZN>8HzxWj~QGTt9Y~@aT(LMzEpkdSQdpWHTpV9+C{?VTH zH%=P|`eaIb&ald|{B=%S1^RkQd)Kh+FIS5F_%}z}w0>wbya>BjqfUG*<=XtNY(LQI zx5j+fn-aGgE2)`FPzv;Tb63BYzKf0B2+8}cjTCoVFbF)s*(8Esb#MZs{K8n{o=Ln$|Ym+Ki*kqqs5JvkSHo+u1O|pv)Wk zI5b77t(=<5&39qp2@Dakf0bj-s~kVUYuZ1WQ^Z^sl7UT(v00IiA)xHvzs}ajuCw*A z>vSKxPW7?tbRWBp`q*{4kIm$x=wk=s&4EO7&!3jmpM6e4;Af)j+`6(*;^Jg9R#!RD zKW@|{{8u-&?1CTS4~ixO=drtBj-WzD)kJ-1e4G>JAkpyq@iq)E2Kni8{XzfPKMwqO zK>gr)zaPqmnix-V8$xO)<|4&uS_iWiq&A=KpE%)ysC-jo%M0C5wsroE`yCD z=Ca0ktFRRj6#81y#|ldyk7!&oHq<;8_imlp6bi)rB}akxhVD&A>D*lbvg(-utUO~;t)n=|0tjkmj}L80+oS;cq4jEu!#92)#6VE3Mgr{8 zd!GS+vbK@PZ-Oi*6oBB3ho)oZE@4lYNC~(&glSf($Vs42uSDw}Z=phz)t$?)bWtJQ zfG@ujLEb0}tU|h-(++~(8B)oOvXhneD5o`n-bQIxpgW}tmuiF%!*jC?d%lh`MA-Wf z+OfYF@)?8LvC*iQyjxW0bT0}BAhWrlT4IO)!jW+N3yz3{8(Tv4lvULdS=pnywQYpn zoJhqiz3yssBa(p#v0240s|pCi0lA4`_cx#w2y52@!_|iTf-xM^f}VYnaYDB;N}yHH zX*EK#$EYTl8t%jW8^o^6$sdtY8*3YbE>wVaK(dXwgNfP%EkKN)l@?}4)HgUrwiqqH z(v%BfKCvX)4Q+iJw`iCrVp5Wt|5)3o7OWzYjm>w>B1#);A8q)p3^fNZu}eJ)(k<*A z=k&3lHMcfnt5y8)taF%kTx;{xP#k^Q)?g5Og&SHUBgkIy-GW#^Q*WJn7*=|DifJA* zabcUU2-T0IvzgU979bg=wF}`0#!jVUtHxCMX@<~0ap0N3W;&4}ni!b1b~Ew}4l6>~ z{0J@$*d-s#H-si_g&IzM76j?d3%!E>`B`A;`CqFYy;@IMI)H3(uAxQ73x;@#vTxG(3;=g>l8SfXTsm zMNx}H&GNA7iMhF1Ce}Dv=V7eOU@{esb+!b z{AuMe9?3P7W-pE8K$`*v=j6`jPiCyqOS&{~7aSxRZ5H z*TQIGEDUF$F?3;Ts5Mj>!m)CgJ9ro7RWr{e7@Md0=_-yZu0a17ajU1ttkT;@RyXk* za9jOfpvmaaC6c&=Sta{=0JB-SslWCA#{Je5fSEPs82TSWe%U1rJ@y)4iFKw;Y1oaN zNLVHs{jnsDCw)@%PQ|eZBRv0vp(!9z5>|*8w`rujyFI|$(gE*k2fVtdW=1#^L5V#N zyP{4`n4O#W&)$w9D|B|l295s-81wZ4ctbC9$rsYgz}u?zS7)5U7+d=LQVMe_gJ;D0 zRGiCzywGmVD1+IcWGMZtuU!Vo+$@7#(Em$O4$D!s^Q1f2gga+cDLgHPeq_jHUAj5# zh`IxktcA{cK%;D4#7v4EpJdjC1n-n5l8;DqrjYPFiOMhtQ5)>^Lg~Fhrr}=GwYnJx zVR|H9ASZRMZNcQFD0)tGM{e~D&Q08(e-VBOFJVscG1%+1hP?K@oamn8nbdDx` zO>tcOhx3>k6Lf_u5F!QAte$Ep7EbADG!^S9ibrGAr8X(6h~j9p=7VCZx%4{B2%+Z2 zZ7-6(lA0FW1f=xUSm>+9_C(kg{_C=~b8QmG>5-zg;BD1OG-ni%KSct!jui7EsW#3p zp|)-yqU!0Ho8>bHZQU9K_g_&y%ME#5TKT9>2H~kWcee+1f7nQ#Rrd5k=S%vG8awdD z!We@zJU20-J}gPUf-rgvz83jT9WGV3qOlrjUU!XCiO)bhLqR7xQJa{Tp{_xj`Wg$H zfTAxqF(e)94?8gB31IjSL%x`Xq1sbSdZsx?6M{*$6g(LC4;qv!(@w6Yv;*uD zP9Rm|J=h84B)6kcI-@#CV=nj?ETbwvfoEi4#d8zKeb7x0u-r;GK4{2$^HOyjCQyy# zV}T%HNlL2OceR6M0Zv%WsOo6Z9ZHD->rAuZ@tsT>=*~^tsBI@OBAb94t~R3JIiVs?Q_KE1{OIwA4vK`m25AtP-AyJdZBg06EKGCRrF6W z^jeo(?@FPh#x5kg&RzzL!VRr0SUmjbav@H}F}}9L-2W~PQMwwm`~riPR}i(il+v4i z0g^PwB`=Dn5vxU2rFAjV-L;6<*p$&&SXUe4!RW5OLj0DvQ{$UOh^Z$pH}!KO#xr#Y z-JgPf&N1ZGF4XG_Lh+VR1o}y?l9-pDX4Y!WJQ$E?)L;StPmYdHh5!Q+ZwcXm!y~^m z(s3w_;=o-K2+dv59uVCnUmJkFICqbI#f*#7fBpaLb8@WbD0^bAfu_&;J`G&v8}d)a zaaunnwD4N8hx4#$SNDL+Wj|<;rp_tHWj7p2`Cly?k83=`r|9rgC$- zT0EvMqOmZ7y%6le)C+%SAcDNk>B2PR$m~#-%cATxoVtQg@eeEqKWfO|bs~4A(xwpl zebG4lL&NptWHX|rUM(jIonaeFqxcb{33(SFu&)UwyBRQZNrN7xJe^m60_V%QyqT#@G{2WIWR zfMJEndH~3U;m&7s>Rv0p^)t+uwx$0-T0n_sga{s*m1yl>Dh!na0Q2D~b)I(CkwP zs0`sJ0;vZ$#fc!9&c&eDvUMC6#fD@;@RuOfD1%A-iAkY&sOpk%k~ZvUrE6lP%MC0& zZ(^AgVZ%Rx<&%c|+-1X3RkM1A6jKW(>z2df*mW`?OzeyoLAw{s)cPb^BUr%W_J|#4 z)jK_xfkpbdmTzKLWgq@RJ%U`Am*?mO-VdnNw3#j~!gCrR!E6frUQLX?2jQ{I`QNmzIt}JYd1?`<6_QDA zC~aeb<>RbuaBj5q3t(5)B5d3S8~i6j-pV$(if>ETimfbx=3GKbZx&WNCV?#RI+4eF>dZ_$uoP#3p+}XN6yNPSk<*z-}TMaqo+$1KSL_uYl@+vXHFL z43Q9;ZyTUFOp7!jk2E?G4X^=H5J@a=0qamR+`WgB?Wn$r9QK_xC8Hvg|BKB_F}|x0 zf?U?gQfdZwRZd{*MGtxl!h)Beo4<3x<=Y$+oEK`r$wxucv|zADc2;vAApO(`b;}cC zk)H@A^O!Q>i37+a6UXxcc_3o$c_ITokrHBUqr;6&)}B#nSSLj<4&i79((l2XndU(g zz9=uodnoH^AluYl4Mt|B4@PRbWf(ti`6{*Z0m8P?u;DUnp|9Bpd`UK7jg>4 zQ_b%CTq0%}Tbx_kE0GG6h`sZ~FX6(f_Mmpy){4K*96%DElg06JO`C#}WQ`M^X9b*9jH?mQz}|Qb#6o|x3VtzE(}8`c|8338zRw5GSY!OUe08jD`~!~-l9`o zG4BuZJbDUkDM0_QCwxm$rsmwr*YQ_R;&q9vdEw`M2~#d4d3WHLwmf-TpDt}AkZEzo zMU&x%8RfW1cMNvxVXr#Yesq@6N-M$aiz+_hxfM=GT?5eLR&8QvqF^s^hN%3aFevj+ zgnJlKaIUxBcg6Wlk9gBIoekYw!)%AQO#$%S1|FLcqA%nv^VDjPOMC2i>Rpvow+8jL zdG)b0{zm;G*GgGiM@$`mltk=B4X)l2OCZ&DSC*Ml@JnwSkD?{0xk06(v?usr2p^09~&+a3%p;^_x?O$MJ z_&?YM@+$Oiw@d#1w088*R6Nbwj}(lx)TwxPW+>iVqBs=qBBK0v#j5~YhEgr!y@NKT z>hIJVS?l>qEvp$`{(IJ$y%1VJX!+o2Hl2Bz)9OJ_QrerR*%aX|PFoB5CQAGGG)ob< ztdlYaYz=PXb7S$0rpm<7{f2zCw<>E@A59-Ws=u0XBNbL_1Y4fa?O^|@@hziTlGq}{ zOVmTBwv&u~@+!3_rJ|${V_FPKhGDmLX=tHxSGxrd7eR-8kP|Nh;CPO-pOV!&wgi|D za7p)+oxuGqL(c7~aMxSoaR6|*1)V?ku_XL;hB}6@ZER~Y)HXUAsi%EMC&1)h3VKHE zAP;EM@^9!k@(m^oEFcihoLiVq&mpls(1CK6CLi1cu!4LJ?`yHDx$5^*yEZySmmcw zBPURwMt5^K92a3mKzl+EHYt-Q{#R2PjZOD?Ya2{eAZxuB;*(1%!uFblE|ecq6d zbys?dE%VXoAsQs|O{6^8p;|YcW1|w@O7@gOTi*mVLo2a=E!H-nWh%K!LBXsM9L{*q zwu{Gj6XNB6=Ptu&d{Q-n{AYJd-GFLEE?~L@y0jHx$!_S=(}ujGdndMQ-U!@?(c7h~ zT?tSuup}`9h~rI!)OqqS2>}a`;=y1Rs7@tnX2-US$<)an(^4O5z;Oo2Py`+6pCC&g zq?vuQ75J7l2=cext)Yq1(IZ`p&T3zG3ch_Yg|~qxPS84VlB%EScnYaGXSa*uqnRj@ z^;=Fztzfmg2!CZJA$9O1huZN0*Di*P?!4}xc5Di!$)_XCeFt?JCxia$+dVOLX|*~y zhJw2$RqW1=sY^_g=sepQG4@~xUQAcV3(q8I(LRuE)tRqr^LCTfIJA|WMtRI8FU%uo z`sPC2T#o+hYJ|dffe}u-ytYW$JJThYrLv~RX!NLactQ>+*aOzv)z*boKCy-WWsb?M zDqb#NwHP?vj4+q5!aabq+rbJwTasI|4rmV~>gV&I-1Hmvvbr4UITP9K8*GC$NbbYQ zRltBwm3ZiQWqVMO94CHizA^w%>uA&#f>ON2*p3&)@FGl1>vJM(j$4nw4k^bioyav+ z`)xgW0wt5*mLoaMZR!KdWv3 zawzLy99i4;J}|)2{_o7TUoB2!FoS6<%(rN^JtX$6#`DNE2)Sx8CXdGSoS2&C|84_V zmRT%VN1`DS_i(wh)fEh=FzdKBZO5DTP=$HzBu9k-$DCZyp{?6+vNLw4ulN8q{0f(R zr*juR1IOli{VlBBXtol_Zl9T$h`6o&Csyf2cOD10sFf9__-3Jh&toHnqD0R@ox#Uv z2!zrzVqj(MLi`im<#X6{?SLeE5#-*^&XVYv3*}JufpFh| zAU=d1|HhDybXH>mmS0GnoK*O$8ElotL-Bh+uWcI;JNr8(^&r+Hi zscclkrDj|{5R8YKG2T)$8YM_j4p!vya4|Z$)Oq>*u;A|Il&Yp^YeZ?P!u-2d!2c>;rPut9C`$5mcUyyrkX;hwY zqU`wX^#a(<6AhU%>jx33?7H(b^nhHDOby`P@y8Mu}&Rytr6Zw;Rek0FG$w*-M-l zR{XG$#GhM@P}@dF8k2)3wm_Qu8o!U%i}HW6N!^K0+eh^5SW(>_H+%#Zkw?_ zJNFaddW}n7_f3Us$|%yH%v^`pyhGZ<7Q03>u*H$1&8Ale4}9U{*QPpUm7!^^aP&9Z zCt2+--fL{cr);g1%7U~B=?T4F-`&(4CE!2n~m>V&Zsp)_{FSqHkkBYzj-<=3;G zeu7sQ(8SeC$2q+SazRg5VhaUrj9C5|aQRZo-=EqQ_7wILl2b=eXohVBjBO-ykO26P zq=D^DB@B9dz!l4lcM?BCI+H4E9O+)~VE{@G*(xJxJp{a{`^$XN2bO z9(L-)4-v<+DHqCpJ=TnR!fmGHbL+G>wbkf^qWf`T!k^8v-yX*QIREV_mwY*2t-P!K zbf)RjuNe-}Njm_Qbe#vTocIIt zrmj>`qsQgykEjo*r@tjUFX9c?fNmQosWxdcnN1w?kQ#bRU$68PkGkR~U7G>K$p8YC zo4*Wa(qY19CSFO;U?T_mdQ^@tA?*0SmF2oT`PV$uaUPi{|0TNx4o8v~L2k*j4HTAf z+7!@Zl=gRf+QXbS7xX2R_98anXpcqc&W>EL1Mg$DZuKtA>wWQmu>-?ib;-57K|ybo zPJ{?}s)|CtsylvX*n$G=)Uert-NcirIZtucG|gGXylI+qllmhWw%`gyw`&7jK+vSq ztxbHC-CHR2$skc{Zo4XnYW-j$YLe=H6Uj4hvciQm)8MI{gX4nlB;qhf?0i z^S74PlFE|62_ZCVJ;cKTl5@rq`^ZS<-Y8_VoWGV&KmJPge9v*RxgG`6GJg_^p6}`j z-+76J4|7PYGa+x+zp!-e{QOMd7b=oWIzt0%z8i?n3|HWyvPuj{86&Ck#$ z_tPK608g?7MY~4nnzzc<7Imkfzk zx!R@PI-C=D(vDL38UmH2j8pK1;~VshC_Yi8jixl^Ql>;uCL!Ndp)$48DfFnn=Vb=H z7@~JEP!p8z@~O9`WT;Y8F*I0HGFB5q43-L&ks(tG>S<#c*LNb^(h3NhHdcI>UfzSY zWu&KK(}qeNz^NtzR%JI+%Q%()BKb3wP0g3=Itdf)zCvKvj^YF8RzW9bS8oli8U0eA)xVnIejjT9acCxHe_tZE&6RRInj+%2nZ@Yk77 z%Pu~nKgY>M7*h0rceOsc;eL#v9>Pt2dGfO^g{s`m&CQm#0}Wbq-qGn86<~1@hdY=( z;i5l@-3;2{_wk$xHG2v?w!X3&6+MyRqgcHj9wlG7GbfUvti@Ygt08As$ca@xv%2UO zL3nmUr5EC_7eD7(2ev$73s$!ANmia-__Rxrh~Cv6?p;-br3nE??OW4)<#V}fJsb1| zls3DoE$t7y8R%xv@1wLuT@7n9&IHf1`X0Z|W()7Zf7MXS*7_spn$;05I&y zg*vz6Gu#pjNw?)^=+wK|)Ows#r_7PL&eWT9M;jZmSkI>`(;5((G9BEEg}A`ZA2$yo zAoXbiqlB+2?HHk%5IQ}UCx>rCg4)!_p0kbL=5ZA|*ftwCA3Vi3xM~l=_Cl7!>CMl< zCdwaBD=?5d5BzdYXItq%%W2&~?@MWO?P>3D+Hlally*(pYUL5150_mVA~2VB1_C5V zvmwK9Hr(4D_C$!rW|Rez0kR+pWwb>q+g?D3@s|zz{?Ro1;Q@i41-W2TcOAgo26SOw z3J*0$^$_gppK!8gzWie+vksWsEUVDhbJ|w@jtYW8V?))UPmHmlDRo~|VTQ>sH&egb zz`nz;Dn&tfqX~4IXfGzU@0&r-Fud4;l{WiS^ZtJ`yo+fH%T|my_oH~9>oOp*9icYp zvzgTE@JCUn^#0FwZSpU`Bg*HqW&H%07T_&%eJ5Mpx`)$F1-(C|Jz`ILg44=DpGaws z+S5K{i#!GNB&Fes6U!psiNDGg`C;|v^J$yqR*REK?d~7U#LplLk;S^aRIzre?0V$>wVaM2}pk zr$atPJ%wHsenZE^+(wXNFPFm}!f>uszuY#6<+HRv&M<+F;SIJ^< zr!{6z;qSEDn7P1P+r~pi=W5!^$dS>?RXAI@z2GU|#H~;z(3pxK-^sVtuw9%s6ZESn z?Ol7?Y_4IqgZ==e?XjmV<+P_je~HpQ$al^}HRVD-hT1e*PMXyvT|a0S<;@SamFX0`S@!*xQQNN_wmr3n_P0Q;ZapiADa`W6E$JC$vkW31%z0u;;RU? zG}7`O4Fum;bgH0g)rE*#n5YK*z8NvBu^$BW0Z?rVdRXlbQ7ake>G`Pfh3YC2V^yg=F&)IjsfsODXMX!?Ctkkqh;BBi8n4QEp=q z>>ch;zmtzDwAMgU1t2u%S}w!PN?e{~)p4pwUm~`vBAuB%T^05y#Yz2D57p%tLBvy* z3wW-8A`C+BtKvk|y^T1{A4d$c2Ag(~Jx0v#tmdsJC=?eg6l&w`Ot3(pUdJ5JY?XvN zBHjhOtZmj1HB0O+f1EvzR^vl9kXBxf(}C?KOl$y_N3c#cEvsWEb5NU_9QOPRihzrw zvA_W}IMTZwBA98;+7dzmjvwfcQ2$M+!gYqcM|NrD6J^!jT`0j;Z1K=s8>r0rrf|$L zm>iy&Jq_`Kv*0NYU$d%Crxl**;E|Q){CD3Yt0P&(1V5uwW zkMtghtYSqteS)y07+76n$n))3jlzZMQge(}=vZ(~I}BWtO}OAzi`5g-Fj-yoMyy2-`&GVNTU0H1dDHAukd+_e(aO$ar~=2$$`hyxsY z8RYyYif_y#`jxH7)iM>UTFrqlIgt3{ZT@;pH>nNzx6%7Ix!wn7XW~q~e?Gr|r>hXu zzK)cibIKtX8ZfulkDu)d)`u{uXVii zOn&LRdFw#k;YjJhDOcq01l3LNO#Qjz_|MUw6r$eQhv>+h;rO~x`PmR%X2Lfkg#ORSfIBx_?-;)AEM0v-nid5AQUiDwN` z)Z;;20c!D+#&W!U6M}{3LL`XdH;ku1J&2H|Y)uSw?%+IoDNgr57=q3>?Esj6au>$A zZ0v{;Q={=D4o#uDiIa9s#@&!V+=RL*Jf{Jt&TZ(T*=zs~s$&Gw`|%xF*ACnc57;{} zr~(FbPup5k*L?9nOQJcPw3JPA_J!1TWt)n4nz9W6N!G#=2~R$78jmPH)GFBeCmk7= zD{qCRMTmSCxXd-=4igvjPBWp=%(K&=xgBxa=$7iC#0hJRMO*G*F(r=63J~@Z76%Nu zxa*0!Z5-9+H?5K{O1^)7)Ex`~Nm89_LmDU(XFz{qw9+9wWP=7%TuqSDK`$pGnx;;j zKvMT`(V@BY?)`XY@yo`Y_^5RV8Fr}nQ)4~oI}j}E^%^p%XL;^m-xu|B55k&Wz<#+) z{^46EvW>z#XFRE~x1p~2aj%V|mhMBm$%Z;Ecea7P6{#7Dx&hNLT!(*vQj!w~7C&!X zgfE$gkOue^QM|{P5Bfa_7T|xuThZ9NR)M<7k#ZlW{KoYZsJjuWQ%$z?c2#ARwyxKa zZN)BX9+nCBY+S!F4C{G2PD-^SX5}c2;Yt&s`8+eJY*Nk0B1CI#&B!khFJ59C#9NE; zRtwJv5=8L>Mt4w494R%Nve_5}>SRYsIj6j7OaXO~Bjs#LQO_a#mm_wWa9)E@hIO}L z|B>>h?iSWVGH<($385$hvl52BuABVs|^_ANqGge$+W- zi~XsF$uh#4J@4mEb8so*+8lh2;R{^eZ02AJQqyekSdh#n{S=ska}mYyLP>nd4G5Nw zo{j{5N^-}>l0FrptzU5(bZQNzG_CrpAyrzX8J9vxn^t{-s9mdGCva{up2BP2M6kfw zLf{nt!PpIIXZ%4c5b@ZOqjqZiH zqc=2mAe+8{0|(9FbBaElL{A^$)6q4yRzUL2A(Xg zHShkGvdz?IZsVHNfOEfvW?RglSW_sEAYMGzScx}0gs^~PjS=QvV!Y5ekX z2fx9X$hik$USG6xmmBg8!)oW$q$&>tG}{2cVjq+?AfDEORe=Qg>B%7*L-RnVqKEAL zKJ@5nL;kyms#EYl#}O~i+@GRmq2BO{eH;tk$HZRGN7eWVIpr7bSX{f6Uh$OQ2k`w&XD{f}un+ zR;>F$p`J11s_$!s@+(E+rJ$;4YdlCUZ#3_svuw3Qf9iXN821ZOA{)DDnmqfFH~@)h zn$#I2=Y-C;L2+u*r=}*A9c>-W8lL^HgEtj|=no~rtt8LOan99LM-7+x)ifgJ!ERkuf##mlS1<^~J-D zjiI<{2w2C0NF;D9!*8C(jlHTlgHIn|L&7g0e4aDphvybheI4biw80}a*J39;pP5nr zC>)bic^?-&m$my7x>q*0N2GgBU%z4DnNg04P1sBxp z?U`y*ypzW2cBLuM(h|ZkjNGQ^EQP-WEUIHdZOVL#CUirx9h4YRO3l2ihLxbCH7)%> zayBi)K*4i#^HJGsm%Y%*wFu%Y=;a>_x$+#Yx8qCCvgxJJT&oBbs{wh9qT@?Vq=koo zdloch%9`V--P}m{G8&0OX3 z?_ZXQTQO+=KfrAWFk6MNVxZEuKMykX?Q9!vLURovpe%ix)(&oy|Nnv88esMxgyh)@ zw_pFr#I3}Ro93G1#O>jBaJ#b|+$z)SX;oT1^_lf_4{Y2~jp4J_FS!|Gjsa*Vdcw5O zG5T+Pn_aD_?X`PaX|~OTl+`Z0k0?C{5OPD_9gvk8xmD*t-h)!!+fNTJ{V>#gtc`gI zmNmxIc?vIg2>)F~@$AhR*(b+^n;ZeU4}$DCVDb}7cC%Y)$*g%xoHCD5G9UGPLe}(~ z#?+*|b4X@PP_46M9)pHC5W^YvAxmt{Ugs2hni5-J{xe7P+&fLUhoY?aLhhk=V}j}% zj=mpzESP;h%{s>^^E(uE^zb%=lGek!6C|F7vIZXygGA5K&2MM3k4Jsv3gET>N5E>1 zA(yLVT(W`GPqxi)YfkqZhb0(_Xc{m-013*1CwJNc!eAW2+QFzR?@M{*H&V8da2T72 zDJV2wofCy=h~hbf;No9=PgVz>b0b+v`FsBu@*a|Mn`IkFUT`ESQXSpUO)^wQEcv)Y$7WA}&VT1E0&ea(+4>M##G zZ4}!13GZ|o-8=^}b==LdPE{dvBX{}>b+Dn-7JAMFMmRm?8k>&bYUOBsMsGpqa9`oD z5#L5s)ry?aj~Es>UO<=y*@s?%!^+jNAKAr`fken|7&Yqvr_c?ErWwX6kk~MKat4Qf z*i7;Q!tnor4lKmwgC$%~7z1nWPHMI}gn?C29;RqjGTs`bu7>awVrKbH(9{TD&l9WN zbuhd~VLKDCaMt=&WkD=})x*UAZU94Zc;Vw+xPMXQ9n+21~Mc6%OZ zv;WEkr6uMGKdaTmfKSd-6US`jE` zGo8gt;3{v?ZNNH?Xth-s@ETHBbk7+qRssjlH8^~muvmf%-BVb!i-Trg;KbntL~AV^ z9;YbIa=#d=LwmAFomPXUo}9tP18k_^Bg26WwxqnC!iMz3;Z3Yr_d9VZp4+~D99`R& zO*>EZgbIB(VSodCR(@006^Hzqtpozw>c>n(ZFDhA)C^0UXskojZY|UfrMjG{4_gCp^+vltWF*?H?KsGzQ+k_k&M0Wc zZ7hGPy`TSUYOAc4Dn@auy|1LG4+nZi>E3&?86}{k^#HnpgqF%_TRz9%NpF_E3r2qS z<_x}8j zy@U=Tr^2rxT3TOY6lleJU6%r+I}yyCFaGFsEcHH*_SjfBn#&wcG&$0brnYwlLS8w_ z{60gzbjr!p7lD_q>6sb`vfr5M>T2!-z`<7F7hRoRdKHS|Xo35KmR6#tfCQ+-(wxC- z3&tFz_FD|ZLU@(OrY`25q&0IcF)HatkEc+KO1sh51T$KUu%a( zYyJq~Zk5t28O5+cQ5+h5J7{SdeJx0`Ca7+vS0*8%KwO+N7!C%0ov+0uabtktbuM|M zvI%@GKqSz}b8CDTs@79w9CWrrgp>v4OV=P;j(p0juBRx!LU{U365>{h>ld-%ovkPi zq?AcrCb0s^f*{fo?uIQ!Z=#sHjuW2Ra|+G8>n1tNAdp*J@&% zrz14i0Z3>ohW_(25IhAW2v5&ZVGxW5vo`N@=`b9Ohp_qrV1O}^pUrP+WvLwk%~Sya z!%g@+;aPN=Auh{=AZkI-c61m7TC#>g#gDP3_&+$n6Yj;sJ~iZ@y6~EL>4!7IkNr*B=sEKnoTf^*vFxJNrc#VV2^EXFDU15!rs?5HV}?XjkXPdlX#4- z2(lJ!bhdf`2#wTbF#}P0j&407oASpXI|;L$&3b7fC@Pr|Gr`BC;atIal!vOg=W>~)^)PT@by zwX&ZHxo08tyik?>fp*G%U}o9tYiJEeb3NxwH|%6rR? zpyvoHNp_U?ZI9d6IrlpyK5ijf^P}BYkWC%$cMkTaA$0R$9ED>pJ}*=QDd_kJ z%=k^mlIyr=GTaaj+V_p>Ts#%G>y7z8bC#QqbI)OHN4oL4Wx_8<`W zIl6t4*~E?Xga%ft2)CyVxkvdml5IFIltcvyB@(o!Pi<$>+=~eytJ_};*~6;oP?I7q zBE&}H#!K2XGz+7&y_6%M)+%C%zl?YqoDYHIfb%I3)RQ}7S<=B(gV3j(06a04-Fcj) zhqyX14NuKoLU>tt?sLF*5#ZWN6dQbhVUE-Y4W})G=?)OnFr5SvW>(Gf?r=ILjptMu zU4*1sa~*+{cLBvQ7FMbMil*i`s%_?$lH8XzrvFp5nzo zE1@{`#8#-gSb{WFqkA-g{e|HaA3{ss|jTKGKT>d76w zqq(cDKf!pa8u;Rv$wg`&lkm08V`{Dv0@AAMGZ9Uzw2dHTsGSc)^&Cxo%-Wn@QyIoq z2-|DX2f56USGc&($s0n1)Tv7d3q|9p@^y$;r!7XyiJhx2!41C3F3AanKw%HU5%;~b zhQYki7-u0g{Sm7yo z@@-UzC8`jQYX3&obaoHq>^BBuMUoYJH@=W3lg^T?rqYs7nyV+|#bQ_RV(VUaQrw9k zr`fbpkQ5HKGN<$5zuta^tlp1~F;gl?0i81qlL^hbu!q$Emj>R&;SUN_a;0g&y8?NPSn znuD`%=&Yn9WL%uFMlS)_BRQbk~UZ6LVD{HKI=W4}HjB9P4s!ID&&@wFaKv{mD zasRo7xC(#aj|lP&nHPN)gnPjrdI>+wr!bc=n+Fr{6v7ZcO!<66J}G%gZrns{@+%7` z=&l58XBATOZ6~}y!J6Fnek?@M4Y)7!8siW&W)a@92|+$5UD1;U8{$i_(vwqoY=H!O z5elaO4_xZYQ=Qb#pjO9VcwFpUl!*PYPcIiNS&cx6@mhlla-;nAN2D3 zjUmv^7QFW=LiIYJIt7GVkrqtiM;rZ^gCAGp2R%pCzsYu+P=C8YYs8}oP^KzQ*=Azde-=1?@}9EfOx>^?-(`o*_^1ckxVJ7@G} zE9Tfp!o7sU3hZ%7!@&eWvu$>Q(C4NM5Z)sYY?^T*Skm1=1!(-#=MGM#!rg#5kZldX z>2>VsbEWhJ4uiPiAf+!`P0lh1Y15a36vf?NBkJpMMU^>)ww;J&iKK)0C=+q*gubJf zhGEM=OjEZ;kenw-T?2{@`k9ET=jhI6$Y#Clb0+pqA}nu&9lHw`c)Gh#owT-+3eC~| zW(U60D4LG%WFn^HdjS*E@Er`IdXBEYkWH+1!`^R!whd^4PTr4mEYw^E+kC#xjeRaP z*BlbtGWq)uO;f0cLBd?6-j4n%qUkkvGtn%weO&}`mXrFlKKIFRdusBP@1CWcnx4icLB))&8EzR$L?ztY_M2*>ZE z7;9%!w?+e}=?FtE0!~jF^0wnnV4MPxAnolQ(NaGWmvc3R8uw6QS~BJreVTdSqU%H~5u4Dp_h`%@^q1X6Xh z-t4KS?%qARHKwd$LU_zWsEz;=EHd3}!(mGaDlT=vgcM;ba2a~9AwM;a=S3E(CzWtOU`=7^G^bZ%VPZ2=$1Q9c zL9&@^!UlIY$!fYr&@|X4P2q)EkfX5CS;eafHl;uC@-;(`UNhthHCw<&L#=3NjwKow z6Q>t+T&-$)9zj)G3tBZ+cd>;Lhq1F!mlt-e4oA~y6WpK$TjTLii(bg{b*{#Jwt61N zTUflq765DiA6DVrzxFF?n?WE2h|k3uj1hC{GaN2|PI zMAc}VI-mYnB0LkAai@z9(b)l&Ir6ohtn11OU{efTSwr~j#A0n{ z6QA-(Yoe(%5Nrx1aND@a<++tB#Qvj~F>4*eAuuWx2-R^Imic%tP43;0xhop4%_R4ghWx!0>Thpc{VlHXv&_c!9$!2)+bx*np0ptzq$drQ={TuSYbkk%@xjY-BD2MLju$VFe6C1fh2lM&g$^F)H6|P)vaQBWIvb zEHv9L!o`79m*1q2qSoc02|_N_r&W-D3&L{30H@I{OUHl?<(U+X*9)Opdy>=+9L88U z&|q^AqWt8LE^Gw`2M~I+DqWb9j)THLv(;r_aD{~dwVH7ggZ~%$SXr|vG049XVF_V? z4%W`RwE9pMZN-wmLL$YSfy6Tw5@bKtnMjDEJm)vN?abm5tk5I$oeuko+2lL(PE>6x zpBE5~SKv0P@v%_czK=lX*+Bp}Hvjioo?$};NEz;(CxWP+9r*7k`&(Jln?ulMgCfU?BUhDHkZsU5&!B^&8bJEKQi< zIe>8FI+{({_tpq^0c2le%Dy&3_OooVYwot?|6h=O7i512q3;Zo`=?U=&LR6~l)FuI z&Ag;N(WzfU&yb^P*RxsfQ>xLsf$U33_CFc&IkiSjI?q?RnOhiCKUp)cS`PEAST3d+ z7AQm4qihqWqF7QdUu}k8(CpC!6rW)yRI6AfHe~INY zqYqfhC)*}qr{Hhv30UBN^Wy<7*xbzfMI|E5m8ZI1w>R7 zG&E2GRMP1V!^|L)157i6p^;*dkx^n=kx`M7kzt}?VNsEh*Xz};x74`lO>bFQdCO~7 zR8;@(cdfn8InUcLZ_gw1`Tx-K%z4@8?6uck?|bdNk+#Z944!KAu$@;e7-eMM;al*y z4mZ+Re;jUkSMdwA7o5NNLM8P}ar3Hc7GJt>anoGAb2jeCzwVDc6&RP}zlC4}j@cW4 z%TFY|!~M#MOE;|+rXH}O$aF<_qmeOWK8DMfOwbV2SZ`?>vUFH(sn=cGqQH1*c_LAA zH;#S83-+vix?exyg@aCW8?U=~^@R&Bb}JA8JrrW@jh9o=Q+W@t)!2gZYNfVfT*uI* zme<5gbS(}Tu?=@X_7+ZDx~k3Yf9x&kzcdsfpo1`pd^@=_$gHRju3ryk|Qe3&3RHU?a1u3AIaec*>_~^f5jv9_}8-bUdN$&;4 z3v4TpjElG{y||)VQc?2*Ue>upVGc^{&W5aUnH2OknbOyHbX(#;qU57Eb`n>Z@A8RK zYunFhZmerXI#aXTeb<$IH5FB-enIT5#DMc*$@j-a%-B*s+YEm-!#FKjYHc(z$lgZn z)@O7Z@ip%Iu;V`foWUOWbBV00M#x~?V(Q`b= z%jQO#o%#I~T;e0%!kSFdyRzTXmbu{+|H6?vZ!xAW_aL5EVB4(aaoDr}1{rw^==WPm?{~$He%sfy zaNT^XOkKJ1dsFE55?(gKcPGbB$3+Im|Hcc~UOpRTlD9VlZ|E|W2mLaof#ef+KX0JG z_}lYcWRD^qa_0wuKO_x&#NlruxWBbMhCx?yWhw?Ai(_ynFT&u+t=aJToXI5PMg3AG zsGu;hu&>Ai%Fkxd;Z8`fbN>TNjQJrArlQald^r_`7kn{BgkyLSqA{oYq=lx-Co%YrqyMeIDYowVis~gzXtttNR{^&L zml1D~V)_{`+qfV$W$OW6)g#Tbg~|UKOnH#^LV0@!uR^qMz*Pp?XJ=x4>42pzm?or^ zcyAk+E@ZDn#;cXUy0iR@zCzOzznv&q4SRey@xM3e-K{h|w~?C)aM3($oYArdD`{K# z>dGf}0*_HQoXblmU#oGEfz^GFX6`Dm99y}++A_Zt?kG9Fzm{c46@Fz* zVHKmry{dj^yK5K23;daf+V zKq-dioS<7m?LDTi;ElfZ6FBC56nMjw<(R&sWqpjx(E(Ee-0`3N0#;EBUTxXzf zKo%M-B6&&1h>^3d?%`ZunYJG`b~$)+Kk@Xrq<7E=eM#>05?LGCDgswo z)IIM{L=^QEUSS;Loj6`59*}tbQ^kWWBbAN@S9n$`8W!b5L!!^vfloqSY=&F6^kcvS ze2))@GGocw*41@bu4r`wb7`&EaK&3vG4UubS0bN9rNRTej4A5dvmxr+G^yK`FF|g* zwF2)IR!R)%D>TG>jAw9c#wOC|elqDT7I8agO>1M!4s?ZHO2t^^t|QrjH^j}r%jZ+d zV8(u5!OcP7Wjy@a`F8?0m_7d0vP$|FM9!kdHU#xFs^^N$06Jolb~P^3Y?iBWE1Px( zQo4W=3n2$Pt;ey&|UjSEhGjX#L za3%)$vy+L3dAX_$9>goyQuS_J;a~T8=1sr>+rJ%0|4%62w8)A)iUJrbG~X^-V+D>Y z`*V=aBL)Q4kW#cQgK7`Kg5kIJK+8l0$I+> z6<88QV{e!7GD6iPTxOtZzDJi*ocKk-(k1I^?Q$L}n3wbu8tcBFX=$uriHCoBE0Qed zWAOizK;peg?+3>@EF$?3smCefldkZF2#b$`&0gmvVwfDwRn$C#J844cySU|D#hBYO zc;y~k;a}guQ}cpE$)9j+*s6HCCk0Pn#rUYCD?H#UA+-@t@8e|(o*Hl`4Nq^wtq4z3 zaD{)}AGawuJpo4xFNNdqDd6e5SljB@I6b*-tgXZ%LRok_5u;+8c&dCL9Z!c@pyh(K zD-r{Kf&xF~rNqeTSnS7D2Af{tVcHXnYng0T* zPo9MTwP>AgyRCUjuJ{b1EyCjR3@l!TJ26D5Q^r)BK15&TAQ`gPvb%sA3=IB93VkhV ztZ!_(&RO8D?1ogt{51nHFYr!8UfeqE8rnrX z{V3_ZKLt;iQ;9X5WU$W_+)2Dd9Ju1abTrMgcUHC7w1!jdjdo0SSJl}cchWHVxL`62 zbpHjHp(1@g#B1M?Z(FZSl>7k4x^2Mg)};6PF`%mHOl_@0&1?<8>wh{^dXRjM&TZZo*d^c zW5Y~?c#o>_2Pp6WFYE}(HhoZw!Be~J*e1Qh(NwW+*Xnf`E?>@TTF+b+`}#1I|5Dyw z)OgJmbOleys;fL`g<&(etf0XzsRayx}w!>HA-|@2i?8$ z5}F$$)e&D6DG*{Uf$I!?f}t_7SJ)|@9mq-yU>|yK@1HrWb?nlVIXd1|1DDQS)7S!7 zfOi`sS~@~;zO2vSd>n9o3y$i$f%Bii;U5^oIV8i{7R_FZ;oQA4i%5>d!wqRTugQk< zt91Cwq8USl=>xJ?_D@4I@+vaW{B|0bJ)7r;ctyc<+S8!vTRw=nro{0-Fc>sIa4ZQd z7m|(bsF}u`T3;HsU$rc*J(QIfAEIRE>rwgqDcB=vtr(JqUa60a8+n@{lH#@ ziGknbjZ9f{IzEAa>V9mr(Ej90uoF(j+~~PGfUhk{@7KkVtq|KI&lNkEimVY2 zXAtHgl!y~%8H&iizGFX~3;STl74Q#<6ZnVk2~iRYrn^G3(7rhNWMbrtxE069ow%k^ zz!=xfILE&?aKy$e8JeDe1hWZk?W?9tUNLpux?0l3sk8KB5w~e*q%#?PxvNNhFwyniGEY-KsQcG1#F zDXnnj)*XfYFaYpZ;@D@~@LJf0i79Px<+dJ$JTV0PFd9esmz1}EmW=bnl$3V3vU`uh zc9ftE193Flc07~Pj>#$QaAgl3h3zwx?ylTS;bvzOy&C;ZUcUrwstPVE6#YKFETk$C)Q z>Vy8ke+7;w*@l0`Dz(xFlWH$tSc|@xlq#fL;iaxAN0%Kn6KmplI+d7Qp&@(0&hqc5(sdJWgKWYv^?vjN zblom5z}jWp*|&CH-Rg#BP8@Y*W@r=kqZLPuKQRXQCyKWce$dh9zz>bf*Iu(=&FZKD zuF%r3500ufaDLxm9Ivnq&<|U@;PN)C&VNze+UEAC6|PvbZN*X5hF2k1DK}?*Mf>4q zFSuZBTUrZTp$$i8KUBXTIvU3o+lJO)LF1|gb*s@8Q7^bccOIQ>D0vTjYaB1zHq;06 z>RKDp`oR_28Mc8ZM-NY<560n`@c?M)5zku^T)N=ms0Y|Ze7w&>4-Ymg>}%UF>$qUS zvR&69QTuu*0|Nael!#;vSb z3*C~uy`f@5@&GFM8ICZdScR98w=YXnY)ih3`@y@jJ=>cs!TmR~K6@tlC)^*hF57#r zB`b0N?yS!?n;p3SXx3*t%>mqB0z_oM2@*@>qO-#G)wcIxvKx+P9z1N$<-y#>d-hZOb;LfEI&#$XSN9Zj&01Kd~O*k@rsDTE!49XUnu z?uxBc*e6E(&9$(@v4FzTOv_3#?4-ni_hB}(ZwC07v#9r`xO+>Yd(+&#t$GhL>an~h zKTz9_b@x8}j|9H)LdLV!@Y$?Dz8}6fr8auDE$!K~*t5fYma(o=h%;Dkv4}#BbM)wBWwia<{`sEV_c5(BIf6YgO%XJa(dSH>BKscu?^>@0a*se|#{M zEMF4|*pjHYHF+%VUzGLPy~%mFe?zus!qz#*D+-CLCpW;AxEaED4{-H;&wDpH!v;EJ ze90Af9H@AE8`c6_(R9saa}ooFAYFt?0RM8uZwlFt7tn@kaQGg!0~7PFu z=z~Jyr)4E-o0=GKEsRg!%qS9Jja$>*tqtL=NfX_@$9XSfErn1vx3x4COg67yhNYtF z;C8ZqA5PlQ?8OT&j-;|HvYTBC*j(4npM%x5JM7xS-ktdTLpZ{&U4)m!R^6K1gZs~A zeYPig5cl^0tc>@_8B9FQCKC#Yw~ZTM_~IC{7kGQn$^@Vdfj5x}?s>^K0WAJKiNnI2 zLaT*@xn(74gW>X#J4vh6CNwN~J7zkpOM4O-DhK&Q+Ve`(o)p;xJEdT>yXU>IB5#C? z%RYF;^G>E*=03{W1@7@UbV0?xdwWs(IUFHLy&|NDOpIT72XTK1zLfDy+WK;iw$`^6 zZfBD1=RpqRIPeJC`m*Ou5wCL2qB#+tx+3$?-X_52_;mf;WTJ^U__?puL=os%SzOS74tBf z;G2?!ut;+b-CbX|x?ub<;2hZ8=YnpC%l}P!bxJemUmDSjE3!>!rf#*PnIRV@6VKsZ zZnb^bn~Bda#Ss$I2)txv`&GFAXx3+Yk_T}AjjYd}PW}n^%K>ucH(yOw;C_3yXC&U7 zv|B)Y&wnrM7#uHr6ZnQsI8SJo2_Z_n?)e**c#j5{ivaIj95wqC=8+a=r^np$avEFs z_cV@ddaRIi4SuUz4L#QX6Lg-RPKqAGt;z1zA>MjBH@D^{Au_awEqrP(y!8AF=3i)c zm+%c19I9rMa>k;tr%GdM`K9^U|1ZpA4O*%9CbN6SP%$&B&tJ5lnwOYn-CBL-855^fuWf0-@~zd= ztH&*0+tl1peb%&zr&KRlv!;1wbzSSKy0%r-S5Ix2a^{MS{tikHy*J35@nnjaq zFTLqi=CoDfqE)6%&2y2^UZs zgKcwRU|XlK{SRRCO?f)1PLKL@ zg`vr%3hxUFua$vLuJkAWzMJB2YA^}EelQ9+T`Kee>?S?PnQeuEbJh-_+eaOoR?Y}e zl+*(1I*OW!INlcVHr-j1$UB{`yGP*rl)^WRhyoLlmHc1|;2TO*zH=yGgWT~;gSqnL zPF!Dv<4hdGaHlvp3%@3Kdjvn-hyuX>LzR^e87s%D0mtzI>ku$~Ww~z#sQ`T@!InI5 z6Pf~Wr{cF%npq~au|Qs9Gf6dNBKIfYoZU4xi0-qorNK1(76-lIZXa#38>@gX4Oi*Q&1bB^+i~`WYCe;z!lR^t77!G(;F9ef8%0Cnecj_IEgeQ)ZLeNK2>Ep+77%GRvumRrQEA)Z24c~O$u2*L|Vs3jQa<@~s9k447 z-_vWbBfKCnhzqZ{c+Q0rmSCu&u^p>Zh~#N#Tme5Haz?#sMDeWK4>;8BSqeCMQRc+a zL7{Wq1H$b8T`UB3Trk!*70?hBPz_MIYl0KXL1Aa%Al37n2Mr0H%DLY2`#;2{nu_Xk=thd==&denfZI2cO90XS8kI?phj`Za;+0mbRS zpc1AR02(Cd;?F3-oc#J;P;FrwfNnO4Ji|8P5rOT0RiIS{C$gV|L4XgY%WS`xfYO_U zS>Trn)Ho>%952{TIK4b=-0I7j@j_@h@0_}<8#ki!cK@jQBoWROysSgqmj|l5E;{M;)k5&lXTK>l@dZZ{)sO*b zB^S@fHj{6yt+ad8sdr!71DeK?1@_XmnuP zj0*(pw8dzz<_6@M2U_+@dw;14tkUwQ(m&br5<*`lZe6v2%pcN45M9R3Qrs1DB^xwe z8f4>(Pm0Z-=QiEDOWJgwdMX3NT{|8!@Hh%YG^f}MVB|BHENwIWaLRsVFP5oWW3P(U zWhV<)dvo2oi4U=U^#`+lf&6RhGUEWFNR~n7Q^F~~7ES@c4*Y4hv;#VP zK$4`>!%yi$`B1reM0o58@|YRKu4*A7d~sTe#e+X4I0-Mp(Z!3ThBM_kiP;;L#FB>A zw#jpUenoZ2eHt}`4~hCAuJAiueti*E5Lkc`vMPY65ol>74^zoa(GJ-zQqBuTNvx;3 z5VSb%>q3i+k^%(bFES5-)%a62kpH;&px>kqiY83OZ>eh%ELsX1=`l1yXt^|?3_%Z( zezYVl5+0OB{YC1Q2IFuoS_Xe(Um;eAj`&yP^JB{$!$z@%9fgp&3zc8LqN4#u+Nga> zr2$pzmy-B+j3@F`{Frs5+cJ&YX$&OKbXcYK;nS&bMv4KQ3JqCI>z`UudIsRL4+QRN zztpT!W^=I{jW^~Q?(r()|B?zfp#@6)5+N7Gx1$YV5$fFSh3Nk?)RDVGZA91qsdxo( zTZ)G{14YSUB5NzEkCJB`?o=3`bTEot1(>YKN?a)%R{&!fK1%mSRa3npdME>sYk;PI zUNsw?4>PE|oI1@5DjZEI&)x+%AmCER8@mTbSKo>Tb`j!bNJiG+)wO42>E55ok zE}9ZYst>CqzV23!Xk)2J-%;Ss>T-W1sosU-s4oVosV`=JFpSuQeMZx^ziGu|S_S=r zlb|2_0ne~TJMQb=g1tng&HWB`HC{xE+s+0Y>R09!hnpV~n)|geEo-Sm|oIX=M^JfiW*3hBI+T+(d?yaE}tFOx|Ky-yCN> zG+J~bjnvT*hn5aOvHA(DRH9d6Nh8LCkAkjD31pPv2&lEEhKOI3SNvcT2--2<((&a= zwl>tr(p`jFq=3i*Ih#NU!T-?L#MUvvymB;5y!c@9;BwQ3CuRWJ$mTkH*?5e7$I6)w zF@uU{OC`h&PEv4F0N%r9v&79O7{xWF3MR)ObWCCNYO~h;?Tos0d@`>zF<#}~ok|np z(s!1Qk5`+>*D*BmW+Sxym}obpdk<%BW-Znt@$$GLC?S@a`d|)|NYXSp6(y)SU=;hK!F!jI^Sq} z{$W_A?SDce$QpgbsDkgqKsJL(t*ZbOatySO)I_{giCp4R>c8ccX8vSHy4{B9wa7r#d8hwlEakd%#q4yWKzaZ!&URus|_!?h`x?p z#$0$44s41S99|;%d1ayqbV(V%MCfw{ezV08G64#|iNVr(_5;1%`TInJ`~#BI(f!ii z`0hge?*HMtOrVl%Pr$saH@^LldUQW_(w}yW7mRiAH}^&zW7M+zzSdDq;}Dsm)~^O1 z2BX*}$p`I~`u?gK?ZHmex3V|d7ifK-arIUEqio}71!?2ZU+uk7*Ld|ZKcsaHlSrb= z5Tv0A(-H|zw4DYPE^bK&#LXJ5z)!o#$KuGZpG&>3Q^Y;+OF>&p{`z` zOYG1?3-bY2R|kC1D|mcd@p!ANuRQEC*mX*m%)Q;v8+7@EYPK!#yj(4?9B2AIhHs&R zv;5M6^k6~8@_&0Me-EfE`&XB7NRP()W?_N=Jz09O)}uxK2>yX@G@xe8Ks?h?A9{hv z2}WvtZ^_zOZiE8T9b+K>hNA0q&k4B;Cw%~LY+>+)-Gi=EP#=3m7}JU6e0-QqOFy z=jo2?S%#LFL{I9Op$RGbTs`C%20-jcBXFiVxhHiTnkw9~5k@h_PVsSP2@bLu#VXZK z2f?AfjXiD?7cYnK{j3_{$3Y>NAbS9!7nXp=+5`5NADqD(Ri;e_q7FK71gK+p%FRq31MmNWZ_$eLp)bYCNPT{kKo+!JacJ?SN2gqxbyV?fUKaWqx~; z;C~u^JIkxJ4Km+9iVi)4Wn|H#`=Ny)Ii-Jn84z*qJA>`n&YfHD;(rGO7Oo|oMF!Sf z-qzS!qjlFLE}U6&ZDUjOnP*IyT7$J6c+8nob3xPUnlsL*Y0@}gjYvGaHDP%h^fKif zFV1hiW=(5T`^r_Ks#8AO&^l?FDrh+q&D@41b5>uYvJT(T#i4NtS=T7*UNkheH`cei zkQ;exue9U-&a@*fp15RXQ)@%*LM)MS{e+9Kx)s-znxJddYTUC{R+_qEa`xs#P}i?& zYig@q(>7TFuV2-G6JT{MFi^Xyu6?Dpz;>lIK?u9bq0<3-7J5iQRw7~1Wo7mo6F>&% zn8PjvTIfTJ9RE1y-qcwD7DH_ zAw-xArd-QTE0I{PFTJCpt3=Ly&OWumEZZGMzT$5U7p13P7%rpga;|;7u-kO@H2dRZ zQzfvYN-v;VCq53!H~#~_N0gyXAcoSBYq{t=DseEnFPk81Q$)peYgTa8S^SeT5jSyJ z3Q-exW<f4sqHSKHa*KqI-x9xmqje*y8vJDwVOZahMYi)gd zZTs~tjSVu@5quN}iaewC?|9U8WPPq(V@Z%3_kaXH2!|E)lY}*@+6*JO&?uCVNm8AY z!{hOqNpz#0Ev#p>85dS_oGQ)d6R5(NFUuT;!NExND_kx&V?10jfI5K>OUM*4CV&Hi zD~R#fJ-O52eK_PL<`~o;e=X;yisXYqysX^O`=}c8g0R>^U?#FfJ}2kU>(}u>ja765 zUxzmWUn9)uNc3OG4sqXA`=J}(J;?74M-Xq(v8{e*BA6J=UrH_4(Qp_^+ zVHu*jDbkfiBG?eO6+5ikIGWA+#vsRcD2H*U|H0JCPR8yYiM*fC0aYuXm;EdKJ~()%evE zOOG>@EDZCz3&U>0V9W~&gK}>d^;rr{zK`EaN|XYC%J`u~$bfbkL!}?)L1at<;HXFW ztQ)kym;GObgknZJ!HA#pbtv9DTw+fCn;}`ssKEEc#knT(n0}E{ zjMWiA#1i<>w@YQ+ANQgZ^8102kxx9nf*i~YN2z5#J}{m^;@Hm+)65ct$?})_+}&*d z(P$KKQz@AQlull7h3MsRV(WFY&fV3hbF8^d>oiysLonSUz0JpRT`-{*{sBqF||xIG|>9xT_ZwKs<;p z5lcl-qc?rLQf$YhrbYdu{#G|}Rl@$6VSeFsNwuR-n2|tL4aYapNUY6?$x}|HNZLo# zeGW}T2%EZ0JcHn{^QKJgLGTMkR3qk>7?s78)SQ;eZC_FDDssz}emP7OK6k`lOq5 zP(?YFG}8b>B>_M^Nimy6`Uo-b%=b=~INZ9Pw6|t7>Y8j$iM6*B3wcQR60R0l0V+(Z zL;zEGtcF!zsqNeNX} zXUtHG-JWaUA~hahZFuB@9)6}A+3 zvIR{Pdo(W;W2q3vI}K%Q8*mmi4GmIP4ks&`nz2_R8ix{STxd(?i1%pQ(gBaPEea-O z13jb&+sDfUkIePYiN}!Mp1x}qLGVW*Fa#?Tbd6oZOc;cQZdk;um{w}Ff}!3Srk!kTPwqz!%@I}j-eKFH6>Y5 z$rqnC5No8&a4-pPA#B5{iaD^vK_-0XtvJIIEJ(7S_GK*~Gp%(cBFf)l9O(MeOsQe7A+)9WCjyYTk{H^2~bj-B$()yjy!4-lzH9 z(dG{K-JqA?eVOvXGaq)}g?T&C+0P9U#cw9hpfyrmh1CqW|0sMB)IR*u>M95U^qk=&M|*+?zQvTI zxZ#;ILAbuTG;R|STpplpgg`0UX`j)8CAIUQ4aa+Pa4@oR84d*N11<_5y9axgu^;^g ztY3M@eFG5+xn7y}PKnrES?jenS*gJAp49hJ>c>i{gb4z2G9vy(Nwkphzaq$ebID0C z-NCYWNTHB2pP)lqE}bsJko8Nq0=K@ogK`?H0TZ9HgN(CwkznR~<5f29LT?;F{^YD@ z{D-9vPqRa|)&3CRmMwvp#;-AJDWt1t#X@>hBIP5=An ztM!a5hY6G8!lZ#*P+PGl-!FO&-ydQ)5lUri_p~4?% zJFrv^da@t67Zp+k>2iORbsfmyP70Y+nXWOckK~(1B%UDTVIvEm$T&SjeJezx`fHx> z+j*UY%>|P1<@B!sZ!gQYmf^P-<+W{9hQK};pgU)o$3Zs2lH=WYFXSy){fd+HdZ@@} z@GH3XI{Z4X^_@8PDPN0{Ovj~=hPhJYnNLFl!4~m{N~9!w(VRdrpf==70LCObjEl#4 zDrx~0&Abx8eUaJbjK~=d?z^QO=EWN=1 zD@HHYKRp9Ya+-=3nAIzIgVV*nfa6p4*e1BB#})OH(?2Yge$7U0xz|s2t!m5AuJkeTci781ov7=3CQny~f$%h1mIJt&T zBtzPLpMTkY>SWeW4I@j?r9giXo_rMtOS=Q%F|j+_g_gV7$0h9J`DP;kgd^oTxF3Pg zlxhay9G>|X1ZP`6zbCY{_juGho#Xh@-pQ`!7ZXzT-8W?=EzkE#j|l0r@>sk zsQOv;MvgdkrvA&+yf!p0ay1N-XP1AfH_iv;;Q0}4fhg#nZog*GMG#HI) zsdQ+^M(Qx4onVklP9m!1nT82MBMVjA=}aI5VI3(H&!c`?;QZHYaArb~vVUzia=}9@ zBpM72Aq1>xc}ihoXPoK5!|~xdiyhm_A~XYb-$rQ@IXVOPS=w}YS~{vL;)WyfjSM~p zI` zg8es_ZX{-Os$DIqonne|kV+gp5g5Mg$*0cWF*3}y9DNI;17Ze}2rFh@Amvx!*9+bO zqYU&t3ssmz58+$*DZn?<{J;g6XmXK~H1l3pypeGNP*kN~3Rx_K#rQ64AJF2NQkbul z2dDUmqG0N>B$~`uFpqw8c zycc)z4whJLl#+0Xf`5@x9FeS*d;A@wC^HuaU-Bn118^t>e5rXfft)VRYrv}EyKa(A zmVm!K=%60sZ{?4re}Aj}dpg{@k$$;39`*Sez}m<+zt2z0dz!{9WyMr&Cx1873WHPR#{P5fwZRj;Xw8}E#slO z?k6FM_;r%S0j@bG_O5~i*wXYvD1jk3nA5tp4Rd}qTOpLhvAIK34w@%JE6*gBb<`#S zpmT~k5vv10X0h+KNPQi~Dy=+;bqzj6F*0Bq$ZR-lDG#(zBvZl%N{~o$9>6)cNs%I3 z!61IbC}JtS6hDwi156o|m`WBX16|2BV^RFP$Fu}Q=cXm?g@~56cN!0|&ssdpqdFXJ zhFT*I4l4u)gJsODmn?ot6vKfe{4KUJ3ergm>9sBZABemmUa&4K@zT#MkMOcVV7v~$ zsJQz)#SP# z2Y?=94yX;3lnsI;9Ekzw*-{@YYUY+v&T6EG^3}Hm0f`-$f*_KtGo7R^166L6S<*1r zG$ZDfuCGQ@fEEnZy29x2U4`KBEi?cL|rRCB*x z6H{Z-EhRNHF3->-5sQMx;w%lOu=ChSe5#ke1nRb z6Q8+R7$yc^Dw-C2yHwiD$X8CfP788GlqEVU&K@9y6U6K0Nwx<>Wj=8kaSfN`oW zopB=N5wef)Qj{MLJV(@wi-_9+s~z+Md#C5AcR~-wVCkW2VL`SN`qThRopTUrYKo#z z51xwi41P?Ng-xrQ+BM`xZSuy)!G_i0Xb1R7EO6?+r0@<#3cwNYazhSG%GE5~c?%Ax z98o((0q&qA`Hg&9#4!fF4izEGlBFai4lv&dXieh7gg=*_U@t}nPA8ok7iR>LYF1!1 z_LbV+=u$8m7y-`SeA~3b@`k9N8pFWG1h0Sg%+R8(msy3A(`>pd0p57P^UjH-&am z+-)#(lL{SJL!LK^qrL-XwMkwDx`^P0=wE7!0NHd;gPFd2iRv38tN z$JM%5&og86{bqTW5NaRDLL9%cN8l;2W7ikQu zC%D_f_MBzLOC3jO4())R)OGL%!QJSbb)tN;m^`x#Htm`bq`G~ttv`gh*_h|je z&!VpB*l^yaR5P=X8@9qWBdLQ5NgpLbD{}4#Kg8!dKqXy~6>$wh2}E}}6i2*B(;ymy zUoW)S)|tA*%1<>`A~hGA?GB)`+4~9t)Kw_OXag*h`a4_`Es|T>Bz&K$YdppMS>|-< zO{|fSA+!+h)i{3l>lnZ~&NQQ3FJg;6^ddU0STh+Ru&n%0`P-d#JaaDUI3KH^k}3yf z5gup)LXkC5J&IV>kCpyVgC@`9E#|IJ7#beXsP;YMA(|s_smJZXhnH8-&R4L;J zCOA>|P_6N0;S??!#Pm}HOw99iV*HpQ$GSe6pI>DITK`Ry}h2}+&xg5BZ4+t?4VI7~nd~oUSBKU{+=2H*?5{m zdtPvs^7Jz4!!Fh_|D8gMvvP`!s0!-nZq>210d>r@#zx1@=yo0DY{v{UHlOWS#&%3I zBRW}!%Dyi4$AFKbjw!N^mtB*L3ZKKZx*S1@l8?)vx(<0amEYnzUS{8ioNVXfL-N@( z@L}XFs;*bR>J-%1vCNCUOeUO1p?4~Wc&!wo`jc3yY>5{80rLo1SAd0@=-E}MDNowy zUfs8{?o(`XhVG-%#j07i+BjWp_mix99!J6=*~7F*f1oUV0~1dD2-tCu^drrC*?1<7 z5Iyjm5SOqzu0{B}tMyl1g!(7ih3E!Cr*OUUuu2R*(tt#@664o;J=mM96m8xjbspJw z*Cic74Yz~_&q%9r)JPa85l0ts{~$c~VnPAGjV(3rw#yEUv@Nej6jVwCm0U+zx208> z6b~zM(7Q`w%)JX9%*s_$Ca>TIdDvsl4pWJ)kKb;P_p-u7|}tf zrLoMO?%>zS2#*DR;`DXvR5R9Nn}XWVer&tGt-WzoZP-LDlQML~ew{1*nqyv9 zMyx*55O;V{d!&=TjUy7i42e+Alp9}(#JbVcWMVgN7x?bPFAArRqiCE%M1YeN9Kq8GWmql@=b9BzDg+ZhkLKU(6SyA4Z)a#H@;$+t9d}9^)wq5UvT+w; z21mMcZR+Cl=-k@nYj3zg7E3A8D4JUh2bZc}4+{KGbrSwuAg7a>(p3tW+1%^A4X0__ zmPy+vHL~=L_0zKSLu_O`R}wvBpXE!n5!Q6I4p*&1T(|Nuwn_Us%o$)@zgGrHETD*H z$l`}Wd1-@Eq_;3&0-Sq01irg+;HH~kbyDcYVMFhSI*D4Vy+QS@^djIqAaH&o2b@Cl zuAe$ryX)Q5z>|CkZ0OcNQn2hoRti_=*4webgdY-SMmttYJ8C*=M^=cUDR^-S0`Q{J zwn#+x|IaRhQP)GeNc$_te4m`^;RqAyqdp6zD|xY5Xrr#nw2>jUQ^+FYsS*h4TZ(c= zn0FZJYo{kdqhK%BlJ(3R>b@m0@q2)HY382^DCMMiA0~%MI&qOKio%RWU70X|GcjHC zHX;d<=T{WWMEprZ*W!I(Kn0Em@*AdU2_1rf56rploa@G{1l?Z;X_U4M;}StIb4cv6 zSax3u?4*A)W2?V+_3;J$*Prg5Iy!0K`a|GDf ze#I@(3ttP3uOI0jJIF5rir6d6_PSUL1d=!9%a}GWjmFv$?)W+ELyUe){7iMrL_i9X z>)2)wZQ78&9y<*%o@X$CLpRy(A_GJNFNgui+RL)DAMnoZ;Ow0da9X(vfjX^4bXxHr z{peAtf9XBay|sR{+6Uc)b2H(bVFm$C>~L zVW4?bf>~Jj8x!Ndm2~{~!kgHx`Tr~ZdcUk|7z~wW-Ew2jW+lyQ9y<@+Dy}c)(&Lq( z=5MxP+HvnsqUB!T_O*QFO>EzxSEYU1&^~F~Cp&7}OKclNBPah$x~rw?k7RvG+xlzh z5Z7Ap=nk;Yo5iC~>W)FXxbjC*g2ur)(&&F?gFsZ)3w^F0Vp zz)($Km{cNy4K$;1qXNOQ?YF`Z-$$T{c0(mQUVbXdC7}yLpcU3G(74N+qi@#zTEKi+ z;$fBzFY7=oolF`i7XrRCTQQ|y5Qw$S_J#eAeA{%pqbBC}*Tm)t*EoxyM)zZ^ak{jI zCImO26cYlrFCVBbW&f{CCQ8ijJ+HEI*jWBErIT=a>e!PjD|z5@Y}Hu&y~~?~Yn+Z7 zH>^@hjvZT7S#`?T%9HWVN#Rt|^~|lhpw6)vXi9?dp;rc1Pync8#_Bk^>?LEK4<++yLfCg@Ev#w?d! =&|TR z!LnaWfDkeaG1f=7k)dNr6xC5CvN>t#P@l!|!rusv|DaCz0GTT%s~Ho`f(m%Yki2C? z4iIw+rt+v~O{GAUF-b5xJZCQi@P+v*N9FK$l>GX^i4>dV@DR)WV|9d5Hju~YO^Gbs z8_24rRF15!7&>Ys-_Y7xvem|JWI6UC9XO8vV&AZ0S>l2IK9V}+PN|sNgdJamPL{8Yn^n+zsSl0gND6$YfB zQtni-;k+C!Ys1+G;xG<(7wk9=yx=cP%xXu&Iv$z-b`1H2wBzr})zV>p@&q5-&<`hl zB-vpA)tZmhxKVn7UXvAd`zH3?iBbk5JMs!&#rO``(#2192~XaGU;LkE`7YzGDZ2{i z7?JIQwCtA7NChMckIR4(;&{3g9}p5flCem=tY5RLrKwp)k}xJ2Q!7QG^NzE|>l#ZIzQ}Eoa;E-JZW#Pe7+q0W9ba2tGD}<%qW<5H1bL~>6aR_N_Ed@U6ddF^+KWG zYj_^;tup`6X+uM>xVK%sn_8bsvW&onpRj5KN)jZp^_AxHO0h^B7HzRlZ`a|xSL;?8iW%gf-*=DDGX;e&l zX%KtH7grh`Sw2Yf)@alqj3eZy=cQs`(~RXTbZ&A~Ah@?fP3~aRKo0!~X(4PBk}U<_W)3f@o(X@J!OL7Dh?>W%L_$MQ-2D$-ez`KxX_J^ zvWDWyor_(syX|q^f^zgZh(LIM3d)pftcsLSCZu*uP(8>$jtDRJ%Q!rCOi&r#D3y^2 zae{^5tdJQVu~&cT$74(l_s%op;8KvXfS0X>l9L-L$48rw0WUtLP`S>+c(J8=hzyXM z>oUT&w@|Q+Cv0b!HzaNur+F%v5L9|(yuu<6Bf%D8s1jC~j|Ik0MD4f_iP`yRqR z*Bn&XD?mhMurKQ-DmO$3rZ-74qip7YF8{N-N7$N4b|#n*@r>H~1>oh!UqlZ>b$0z4V>Va1br8laWUg{prR>mO_W!9W$~8d&8iT!p289Np|L6g<_m!$z8K zq`|}RS7~q-38ahxGU`37a#+E+Y&uJ>oKpylIY#7w%v~s$t+a_a9Bw|B9p-Xi6{0Ez zC^i!}*!f40i@ttMa7&Lao8Q{a*hKCqOuDxj3%5vc$4~BOdq$Z}S=xhrf&lyHxy=ez zzW7^8KfK>-(LH-U36>jEZc-5R=qxsiJiu~y*w6_@kJpT^&)+mO z*LZExJgeiilt2AX~ls5N&Ai+IzKi9xW(qq(_L7E9nxo8gzMwW8) zQ1gZ{3{1}~iHVPNyxp87&He0k822)L!!tW*abt)QFmh-QgI-*q&Bbms2dCHTKJ+uG zdn3Fi)ZLF3bGdWqm~-PW7MzN0k(^(8AU}Qe%C7{L$JHZBszXfY4FAz;Lk6XPDj`&p z0kFx&G!m7l2!Zz92tEdc0~ru@vC$$FM;D_znY05LI-sxc$ ze+wkd_?avm7Mv?X^!L0sC+8KJA2HXG?xrNA;X4xrCw6S$)xLt0jf#_>s=p8UL>!2e z@~1GOKUgsFz4zqAgm1pe99!}Bun;=%A>@xFR7$xLJdyuEZS-u4kgyNpvFmzXR1TY5 z0wD}|6w7+&w75zbKMO9AsyAh=nyCvV=68~$l{L1~0xUhOg$bymmvb zB#6M=;-e@fFoB&6lTYTqD;yvYRM1~?1P7Z1*mT3(PvaZH=2kB_NA}yulU&*Iicsul zZSP2y21Tl7in58w_h4QF&M=gZ00a0@*ShZm`f;DO?sbjNLT<8Upc)EniYhC3*x({` z4TBeyr08XdIx(G78TFGlbU>ajViOWFYANQK;KYfsq&Zb6k(!HQ(F-c6B!EASPxk@* zE%e2{u!$k%5)2-`e#V@{ML%>hZMRy|%-&VV=M9)EQw41{ZNjld6eSumY+Wq_AF z*%li#z2#x0@!>M(1_@OHl}o9jj3%WUk+K?8D&o`_OaG^c0R$Kii%$JN{6YX9mHrsE zoXO&j#WPKuDQ>+m?opHBkF~Ye)n8jH(=}+GGiXpyzo{HGn#8A3ZHArM1^c;IZ14!7 zSxoSve?ovJ&F9BTcz6(JO@WA%MK)iZlSPdA%@_y^GY}L8$;$0jN15BN#xi}X8mmMQ zMbk~lb%-07pEJA4v69Fw3FlK#^GauM*=1H3lY-8}eVOAG1cUVBHe>JKuF9>g?x!e( zOf$GG3i1c@}R7e=EX5~kXVH#r!vKVmiRR~@N zh$vcw&>QC(g6gFZ-o-beEllz%GS6|^idx82uD+~f&ir581zpfir;258mJ*_0 za2ce)@xt!3GuP*ZPTCW|f-xT-DOk`51AANvf3Tk%;{0cgNA@nJT@_HRoc;hXZq z;v_wx8{J?5e8Ie=$&Jy{C&daCp=E3lk&d`W_x8}Ui*(~kf1A-yRVR3z|vDBkq zU(Yh&O3ys1ORFL_3fuvE(t$6o?4YMVIams!unwov+;S#QxtKgjyLH1v_Q#2sG2{H` zL(&&VKW?^a@7|-h!9os#mD`$fV#SzWaXCM$`X|baNT^Lp*(9eofcJGg^yqK|3>b%C(S--dnr0w7q!qC9cc50yzt&KomKc_Z1dxvKz$B$bH#j_z0B0Y zp<=4oTqTW-_qLwdPMzkN+XhN_nhQHX;)rFDjE!aHN4MOm`t%mm4f^r|sBhqUSs&3Y z2bI3Qew;vmlGK#X`Y0wpvi+pGR{H+4HDK_ z?QXnfYhHM2uMS6jy^1g(-mDT#qrXnOie6S%0C?$V)=E!!Kx) zbAKnRc0i^`lYuBib=hGI5k!*GKxt3igWm75X#cs?!LmK zikn}T3f-M%jZG!J$KKrm>FpL5kCb+j(CPP)L6?a{mGKYi@DvLx#t(E*_#rJ!sy#_4 zQk)i{VjnI(nB1Q#zX&`^uZY8+a<7PMBvbF}uR#zg>vP9s2?qj-1{$AT?@$CEe=$7rAk2$X|h z=6Y&~xslX8gR)jPZ|Ng+{fzouA3Gkp=h$+;3jQjjn_aZ$(^+Sg3&SVP^T$C{TAWF? zh|G!5t=E0{S)@Ag#H_s|s%J6Kq?6A3tHKs#Br+G1&LKf{Ty~@tw;)}nbe51tO9k^K z!1_>s0OgEM-f^?zF)=_>8mQg)!6f>RXF6<3dthH5>61Nb&EJ9b&(Mx4iA#vg#MKx( z%bNxQJq`S^ENX3o4>xC%FIGtZma7Mb|G5_#$KZMf6dCA0-I`RF1Rx@9z%Z!RXjL^k zgDI2z5J%=kz)@mohXfER{4&2<%$Oqnme_R$E}<&GdI9{bFG~m(VQ)CSB41&JA-O`N zUarc5lVspebJ6-roVWcokz}{3uF$qH+}EENQzWB#Kn>4@Pk@v%K^h|4(4Q)V5!8n< zORJCZZX#GdWo5mJAzCA&;s!2) zK=K03I5EzEP#Vsd(TBSlPyg}qoGjs+&*>TqbXzGS@)HNHVIoA*{6-;H*a*AKGzGMp z`=D70!$j}x%!}UJ$4F|@{7i@9i_B=zVBmNvwoxKKfjPzM7ZvjtKe-M)tqW*l&O&KY)OS4wu22Kzl?5Tl! zrrj3fSp^Y{*cjfY{yCBKkJ)^Nd6Voj2wr}v$YAF|mPA)@^03BG<1v_L^1`Q^)joZ= zL@WSF|3ckttwudW`vV?dTF-@qRFzOE1fpwcy-Ex0q+yN(QX?mW#W}bXj9LM-wIeU>+Wj)*k7qu~xDMu@VUZgNQeKVqa3}fW1k*Ai$v&Y(7Z`ziwvK&( zzj9wjH~xQ-f4@-r;X?d^*}IePgb4xB8aJ9l^oo4*r``W%7czjN*&tnbN$05413*q^ z2v>EBwky))c~&u(FaEWUkIwp?X9Mhng2#*>jo>hDg|aKFo2AJFPdMk5BS*Rx;}>%lH|9UI zxcI!P2glK+M*@^scq zrIG{jA7Lb6@;@g%++R`>7BZ^!Ktx3MwUOAHCEPUyASUi(iO&6~Cw$fT)1Y z5W$g8#I`vR4E$Jm_jF!l@2M(#?^4-YE*do%3?Xxi?E%0UoTDHv2Ag9YByt1QNL)5c z?nK62&HF`u1+a_v5ymI3C5ms?W6KXOzplLeY0YDa`P`~YvhcF5o7Ur8o-~>AL!IXO zH>=kuZGnb?A~_j#^UXxw$g~SokjiMQP@dU$le`+3^H5%MO(7`}BarC2`=X8_q)g;v zKL#?K!&o%YKO6}bYgnz%%skBtkxxO`hU+ltJkg^ehaiU1EVleg?z@3qC$RJe+rkKm z9i07k*1Z92{AsUDssd_td>hH^E>5Riq}y_E8pWh&?EgR?u{R!7oP5pUWF~N;7Vlp> z!pUKoo=#g+W21k{T3BPF8-Q*6$HJQK^m+${H)>((1ugu49Tfh66!x=4U4NbPwIYL! zF$oaT9N>>q+!T|-GrN&`J3lh#fJR2|)d|bVU>ZOXn1&z?o^v2UohRZ~<8t)5X7>?# z+VLl`AO5LJBMe1w)%wd1cC^~T_l2A&e$`qLrTalwKyd;Z^WQ4y`Ltb_v5}1<`=hC&T=HV)1 zzFt@6^h7n&ybU;g!87-9&78pq*HVe23v5&Y%d8W(Rzt9h>=J0?m+gSWBzhU1`xKsE z>C*gTXpTxKOsNI)#YrEeofG_4BQM1JXYUiClzgAn!W@(cg2C|ltrncKg)vl~-u3cN_HfU^%-?t5>3_~+b;<8-r z?RIs<#L_lVvwPL^94uCj=qsnUWWhQKnu%X+b2w#cIS}`sp2W_KdH6=WaDsoLT#l81 zs80EuEO)fLq{sN3xue;m)8#wycZ+2`*y6Y z-c`{HQQJ~KC00Cu8mB*?N;yVZN1m~x978_N1#8dJy*ofUmf=iv6 z1YL>#XTLLf(?etz^56z`FnmNS3pR)>$PYd?Y!iHZRADLka0ogTuLUGh?RQ>%mxP?2e;E?BwX1yz;@H|4QE?);3<)TeZQ zt+WAT06G#?K*I!A78Lq38b8R7OgePE!14#3gQGcGDiSDHg~U%MXji6?I4N9~c@jT2 zg?#XY8@9;u8>2}%A))Xk6|`uR&g08ZoAxMv@5`W(lLdlMN!SxO&8hfSTQ@(j^;enp zR1CHh@z4I=oln|R{@JIrHyFXl;hc5_#4vC*75kE4Eq4iDAgn?6nzzqPy^a2c6+{gl z=`4+H5@%RJiSjG#yjWZ%pR`n|bsvh=9m*G4e6+DbkwSqE3lC@s$0+hC3ujy> zy!#6mLq|xND(O5#q|Ak+X>?(50+#(y!;9S}bAWBnl5J^3(UxZ5(-~CcUbRzc6oDRf zPE>yS_ORNB&m%(<05gk}R$8g#iO&!^J4YHKcd#>n+Kr>|q@SD{u?j_EC7T0|6?w^b z2FJ-7igyYheF(qV;y@j`P~G+Guz+uE<2tuGcFf~*t}OAXu{f>~oz<7^5U@;FGF~OU zyS?ues@Q@Y0jtYi5Ip3ozI|HXmvu%vW=~V-bAKZVT*~Q#z;S(%z#ft&Rk> zxmgHmmxNt0Jq$~-4z@jfi^neh>y2V3qC+5WcuEQ44%|f#@4?mx@|e~mAF)Hr<)$pw zHQq?(B0Y`j?59|!i~B7=lm*p;%gr6wAJ&-P%lJ*49LQg4yX6HJXWSvUcwX<|Q+))oEj7Er?iMI9*jGjV<)!|gt&z6Bu1l;{NwPF1rmOsW z8VQod?7qoy2Xa$NM6pq#QQK1Mj+f=0Maa2ZlQVB+D+Ml?#|qA7eNG&b=G0%vOM4e8 zzIUF=W1_Go)PG(Bs3vh|NzzGOQ#BNh4750cZ67g+CFCAj|;7H5*0 zNzS@keW`@e;7tikWlRE66IMJ1319+Jbb>7}K~H*LBr*gzQ_E{iT**$qUzqYIN~@st zQlRYWT`w3;Q;M=`W&Zg3C6&z&jTgf$zjghKh6(>(h`P2ajeR$)i|&m{#=}K4?fD=7Qj{VL1KENryfISiE^R}g7#)D~i9BZg#E| z+3oidy zAvVM?$$thQ>{MNQWN)v^o0PhDYTY-->lQ5m!~!i-VT2<^1LwL(lq9Rj3I$At#z-9G z5xjOp(FrcELBkyT_Pt@6Kaoeg4N%yB9)~>zZ;$5>Z{xM@ojM6z`z#G_<$||a0ud5V z@OK*U;>+YFhfT{FM?xg%uXp2QDKzlPhlTz=s6%ej7Q)4KDCl0%nTf`+Hs?>KJX0rd z+^bV8N6OAKI(cuRHHOLCbgw=06%Ug-jCl@`)tJB~*nBR+S%eHO5dDk`85z0}i68>F zT&6SOjZg+l2RVsA!<&gu#rQOwOo_ju5=s>aBIM~XTjpvUWh%z{n-23BN-wIRz zq?CLC(H;81m7R1L6M1G~7981ZK{K)r;jgL+hq5}^d z%Ab8PNL|?(`?5~|9s9TnQ*Yrqtd2hJjpqrjU(^{&u(m*1APH{fi>={-J6*$-{GbjOa4Y=! zX5guAb;o$RvsZ1QdRHCsH2*BY(>FC1PyshwmINFm)I;%55uObaapCfAsOn@eLd*{& zSqrJsb}W+!%dv7_&LuO15=bL3`WEe-{JkZ6%%KKdkVtDJ_h4tF)Vm6|7=Gj^o%X=t zTH3!f2lcL+P~@~;`ASBu;rDYt!JGyW*MeQ=ns)Ub>p3QPFQo$-lKp3pc_+K3Qn`ei z5racytsn~=GgM^`LGQ*_Q|Pi)`S+)qd;^`7$GTdyuG=+nD!+AIr*-|l5bbK$y6!GS zyKd0BHWZ?+bz0X~3sKjWb45NrTZp=z*1G;&h`I(S4nK&gU@#E!OY`fsuC0Zr>*?vz zUpvFPG#9kjY>c?>9Dkrj^;U!894adUC)%Nq7b3XQCBQT9zY)PaE12I&vZGy5#k>W&|b2UU3hcIl1{-4 z8d*j~E6P^Gn^gIwGK@r2okLW;g?$NgfSv`;uEH5r@-;Z0Eq7I+H{yCDjPl~(!#KMR z2dG2f0HNS4Mi0As)#pl~hk?p}n>5~~Nm%NY)1aZN5PI6A2L=q0#K-+Pk1-9T2_NgR zomOE%xBi6AAIuA1?V2Wh^_a#b1_PK8%38G6EeRVy$q46AI6N@bBo>BsiKI1X1W1ukZt z$DH4Yg&XP1d`ZGH8?E0+VifDvb|{CR(2}r2aaCqWfi!D%wSVpTBNs%|fq>vlsX?Qa zy?PDyxD4NChoKdgzBUU#ybr%XZ0g!6m`L7Xs(d$d_&fH&G?$^J+wi#A?+RR&$=@lr zYU|gmUV*6taQy6=zncUfm*5xoQt`o=^&KK4WA1=9mHyw#xk6hX(1n4-+4GO*U@UqA z{Z1l+$L9|s-FU$`)m_c`fo1bNz+%h+rSsTanmpCFRqK1i)hB5qQSNrH<9avi^UP3#y2sxNrN{H5;Drvr-V2^qJa|K>XWo`KzQN$E`C2&bte~&0B+jd z1fx_u5xR{!SLNs0rPvJutCSk^e$KrB7t@*(wJ&Otoywu13T#a5nLoTs<6ci5746u3 zv9QR$Ino?blr+DWX__L7U|mw}+W(kS7hd=t7JoCF+nxT{eN?pPX>HFV!t!j)^HF0U zPcH<>cPq%GrI(Kim|s(v@6kTcb>IchQ2HRN;bxo6)l;G1UoMfdc8QZ2F`8@T&Ki4% zFL~y_TW>;h$0BURc52?oo6R%Lmk39H4DFO={aU(4#G#9M$}j^I5n8Z?-2~V*4%Ksc zGMDniGh2~pB;%N>Y-Jf@FPNgT_DzUIH>|4b*bX|>t9EW!9fjD=*@BYa=u*Ig#rP-} zf2|73DrnZAj>UybQ_#KzAu-_QHXd7u5^(Sex+30D9-a?&I3$m{FX_JWYkLR@^F0xec+iNV(1%wMw`Wyobfpa;J>I^^+h>dZ&&!Kk|I@v!~8_OX;IIxta0+ob&)e*u#JK2_eyIJH@ zZ~1&FeZN8b{s6X2a_m58x!y5`@qBZ=g2v7U@~w}c@-i>*JflAI&ANqC6~>QbSv_5f zP}6WY1}Ec;vQENM0_ghNB~cK|k{HEhL5OLMuHa13%;)`0D=yhaNl1$*L)J1DnWHvF ze%d)lcy!pQcEpbY^lYTw$@T>TdLGjYt^r{?f3hwwf8=2?|bgegv{`NagsCV zoVC_od%gDBkMp>EY(@tjn$Ko1ewJMzdi*!mIK*xu6RXz;igAVpO%({^N06Ayi!+zY zp6L;J_(e-pI1e)_`6Vd1lfudSzspVETlpL*MAStnjR^>dXyH#Yxam6qujKDeGfMaa z;JnujAQS=wf3fPMYHB7V&hE|xT;);+X>L-s@G}D!NJ&^+E)c{E(Z;ShUu^U_tk3cH zKltZd8&uB^QO~n4ZW4Z|OtE^WZ8D~3{1f_AQ>rOLM_Z6!153vBkgs)ACOMCc&@j}P&TLHpoySSjboB$bE21nH-nCwN5l ztd_l|d}&mRMp4>y;D{XxPt2G)?Che(73_^A^%wjfL-E%;`d+KI6luF|Ivp-=p2siPs1|~ZFtjB9ps?sgHAK)*hw?RDmKUEG0OStxu?9wwLJ8e_C^&PA@h>iXQw)xV)#a`ls_pRJW?gSR8} z_q}9-(;|Ph7iZIw#Y2(QwJ6>rgv84vx86C!v2i!$EfjuLU*eRXi^5p-Ou1=v4#yP* znRDkLvfpyrFEW;=Gk&ub__h5a;FqNHL!|KoB4{($&19X=u+GJW2c)y35mbFy6~q-@ zDQ{|Yzf-L1f-|IhnQ}B1Zubor^C$R&6DvM{yc`#Wja3cTJr6(Ey-v)I+MLVJkm|iU zT?M!xYn~kEX>wC6@n| zC6@QO=OegA#nFhqq3A!jf_XT5JN)(EJl1nQ-MD zEf!$eW(!l?YcTp-;MbJ<3e))wlPE5pRvrFQM;91|>T@$+<*$Jk9()IVC7Bf-bDCiEzkWZT7ff-+CE!L;tYnoh$o*+RjqO5-T z6+-xo3sOq%ZxW!Y)15BOUKin)L%_JEK115~qwmO;d|E{F`oAnV_zP5sIL`uKv z-}qRAaTT6m)VFvs0b^AxFEpvyRVaLf#dh6M27(S*XmK*~r##58s8; z`QA*_z5mNn_Y*n;mH{b;$()&R?}9lR=XCl$Mb|H8LXNvsj?Wu8Xa)o|>R;mPpE)0F z(E9JUKA-{I2P?zea3*xWLhHVxcHKG-oQb+0*1F%vx(jj_3NPJD&X_q{-}&1b@4V%~ zRU$f?Z}DdFK672unjj(23k{_gH+IfREb*@3&E917A@O8tZ zQva=4{agvv6&|iFmm!rbbffR%*rth(u2(?|bH+kmx_icCy-{WTp+1&QTSc-q4bEAu zBj=_$mqN(PA@0Qy2)$n>=R-3l=NGm8e8tNttIP5UtHm-W$9kvStbmp0tiVSen$9k~ z4Yzzb(2y?&VbsZ64ZM4)6hNH8y9-EruaNJRKQ&{r?|)3<;k!B=!&m=N>zNpdyEYjH zJ(oZ-zOm7->)s3vJRP#2X+A^e)WXp@gV|_q3bc(F`MEw-f2(&UV*SD25#8RWx-AT= z{@GBD_C~~W$5?pMT_Kn-z``_2$A1$2O>?gF*T7NfX8Fp}RVXti^wL@|BC}ll^9~q3 z%Do)c^-~F-CUlpWsY+k}!|@1)m{ivWV? z7#D45D{mD}NpxPspWM=B*(`GmW)ih6hRp~cTI>{gH727xMXbs3HwX2sl_kWEbFNTs z@&*xVoU;X(YQOmJ3@LXnflBJ~fxMe~=Zv+f2Ok$3f70iJcHXjdHl|c_(Y~6X6fNDw zd{AUQn4jeXo&2I7&^5f7h=bP8i;TJ$Ed7w)5u-&ZWAmJTNT)tVe9zgaJ8pg=3FLHVg!w})H3H6As?0+AU7eD@&lp&(tDya zVdF*GFFfRBT+k$sM-@2ph3~OA!oR0W&UJUgni^l>$GNx7SPpnp$3OS#YYqHGWMumm zd}ay8qC{sRouA|Tr!!$X8c|jjr0MY{5O*#)vy&?DgHSSMWg76|!vP&Aq$JlZ{4870Kuo-%omfTV=-i42gJ2LXEGBp^N@}Y??uc=9}IsWNAva&>wR#> za@HeXlJ@kJ++=LhaR6?#NkF)Sz;_$*d5qKb`$PqK4pGM~@>q&y4Tiw!64waxFmIkY zxp%AF|M@)R<`+L;-Fk9AHe>c)rhfk4y7Y)&i`035wjhe-MuTVR17Y2=_Qy6NGRMeX zdGxqRez_1Y5*N^$n2<(@%Uo{e=8qR?p8KB6AK8|}Z%fZyop`qB`i3eW*Wu1?%g=9Li)(gegtPhSnlZaB-({h^>*#zJ zFtfS%DV6`%b?tJxbFq$hUeMpZ+P`&M-6z1LPu(rKcDjCx%2vts;9D-1{_Rs3^SF7Z z_Te*C->q8TbBICBPk5$V^OLUa%v8O1YQ0}{v9I5rmycT^hmGcljzRK+OC(7C(EVVU8yWHe zjD_r0_h`3@Bq8JASLqSjOh#>wgWe=J{te?wC2dEKs}rQNCR?`ov*1je@qLxo1Xfa)Y*=2fTbb ztEz4*I^>q;_b@EbZ{B2W1$y}Tua3QEMAqxof7hw3XUWZdX$c7UYKhspc^gPxA(6*| zwb{5)7z>Izi=fWiIkC*tfwJb_>x}4f+hr1q-_zI5`GTzogU2l(4krRC4gpAJ3oq8BRVimMlv#C6X_ zWU$Q>iB9_;){9A%XKgiQx_mRIoa%f8}8p_*>S8Xo)6y zDoZP3vxO^Rsns~sl%$chD!J|uk?<;+iUg~!1LVTO+wq|BA_~&vo>V*ywKT35 zg1*Cw5{kSPugXf1X7|fKYLwi9a&!Asz0(f{>H)Iq0;8XPnesUupX0%6zqlt4)Lxe7Sd2lDX-OJ-V9`nzp- z$&86i!ghr=Lq8l7fg$fRGdJFN;yvQq|HOAFRbKqn91fBEGcsHfT*i*(r`Sf3qUdRz z>|>=0ca;Q&nRZxelZ?jz!0!c!PN#A#-E_WqvQU`s^n~Z6X%yxR$cO;C>hmu%;+u++L!;M-mrW%drW>zoUb~ZK`S4i<>eki zi;ELRJXWRwhE1{iVLIeoH*@X&qDhI3|L_YeXT!aa@!Rq|?H$*;m%t%gff7+d&Xp*u zSQXa{4ZY^gV#b5Oa2H^Stmm_hBQE4|EJ=qrXYarc|9oUvcJT9X%{P7Vu@Qd{K*}KD zNV$yuh@s~L^pvS-PF6E(gAA^#K^Xfn=q71jT<3=|tKOIE#n*`V38M=d_<=3Cs``*t zWzWI=I-lLMd6)Yz5kA-j|LFR|D)7#I_U(A=IA87353xKViwujX7XBfp%{fQx?k`|` zEXgi+>mC!LQ`-sDyX#Q)GSbcui|aolF9yMjV7wTNq0hv+=rhNHbHGNb?e~B0Q_o|cXFIwL(_PyWpm8m?Z0eAu|>t}~f zs*a^9`#q?`^>O8s;`bvyzf&mOLYe1=vB1gke3o%mD7aLh|8&XO@^<0* z57WtWsml51F;De*4?J}OW2?glHy?1L5k1|>(hVFZd>mGP*Z#rSF6GyAf=B2B^%-^5#fwHL z7jnV#tn(_Z^9xCxvF5D0s#?Ui-XA?-Jxf~WIVYwj>f0bW^r91MpNDqs(YXRovbL%B zMM}qQo1r*c=2LGG54n$axR3s%A=cD_D8>>{(o}tr)My4C%^2dh6mAn;Pf)(ckBNLg zgf}5Vk?|q9!!|1)QpTg^>qQWoE1D8*j)JRY{+clV{*;k+F75>g zS1*_s%C&tL;7%3|Juc4qh=&Y%-|__Q)1@*L#XRSUdH7p`Y`aD1%rxsIk`@3dMWQVD zRU`l*A|=W(T_)~SY^m#eC#Xm3KC$Ij&~-zGsE0t3HT?q@Ih;+U3DdF6jj}!t;p5(f z)YLoKWnlDbcMo%e`2GajVE9Qwo@8xMe=qv@x`*OygV$Uox^smg)jicGO7?#JL3&5& z9a25zn*C#2j3xn{t4=$Psb(;N#aO`ESfJDb*FMf7mc5B z=Gg3c#c}w#HlAeqT`@)dLUHPM=Nm-74(f-LTiszaHKHewbva%0JAONf_}`-TJ3ER6 zI2r+N^XT)lga1hx{$@vJ2mO7GDah%I(+=}qFLwBwTJ2efR?Tv&I4mYMHSv?LVdTrC zo!4l&3eD(X!()=K?t9(RLz76YWCU$Wo6{I;Rakuli?e z{jZ*e`Z*CQH2fP{N8WsDc-OXVySM+$<^$UgUNEt9*MV)7GGd4b^8VGTl*J;6>VAH#`5-58OVq7D`Z*O*e+})4{kq@ERpX(tp^V6JE&ttFM|g6 zq0I;1qGxW!9Md`dlt1WqLd6DBTyYp&D~@(Hl$IEHN^-+jYS=&o8Q!<;@b2xIVBNdl zwC}*KLp%3mpl#dVx(lYD38cuDgZm+W@6OE!@f!mw+QCBy4sShFIdt{@?c27y-{IK5 zYa5V|cFUe!tzBIz>z>W~aRLEF-aVTS?Npl0I}eZ*b=$lbZ_001@~wNw13K>5wfm6# zXaOixH=Qqc*VE1Dk}*Iu*t&74{C47`&`_zzFExbauabgWo+-2-G+}MX|941Tzc9tR zPBPTgU71-SgO8tfH906MnoMD7%J+cC_tB}yH??1?@S$TY=0PSt#CqGd?Ay0n<+49$ z;Q|B#sxhw!Hf6MjKJ^XtWHz-oIDV)yjRx@2*y^1sFO77OK4}JkQ8taOD{JtZs((W+ zYB;!k&;Fh6Cp>=o@b<%OEv$-T3$2Tz0zj(n(Vci*hJTid&}3K_Ybi9Ghrei+aa|!{ z@)ls6-`Me9aTFczs|rt|<87M75l8{!5I(igh*urkIP@U@^7H1ugzKz@!aHS>;@;cA z%Szz6;d%4C{#h9;JPw)N*hu4K9XRIMy2ky`>{GsS<~%3*t^=Dw!@1yB-<}x@+VTe4 z5?}vwa}wMl$K=WnQKH+QGHQ+HA}4*pr2{^Wf=AfG?xz}lfWVQEnRUqhdBMpPAP=j9 z3|CADWFb&W=8U*yWbMAWUlbcI#NYZpIk`T3yr(y_noLU!C zUA>5u{UnmhS=UM3Z?93e&5z>~7szi7RVL|e83a{^c5OMZ`M}lcUq2QUyhg*s<^ylq zeh9-OcxM}&z_AeIkSp^OWw62BBFF7hkfYxCG#Oq_(NsPF+5ab2LZ2H(aMGV_6FL8{ zlaw>-yRuGX_pXEdwJHd}K2rMiP*Dw>w$evBdPN$)K+MiJjpsUo%SEt_hxv<4Z3yQdcD+f zZH+qW{>+`kFWSwXj`kg$M~+l>Zr)wtgUc=`JlK6pDuFs;zQ`1OSl`AcBuni|L!(mt zwazz9m;Q%&LoG+utX9P84Px_S(^Y54?y)OEl`$C9nbCEeq|Z+6nnrm-4RPH;By0N} z(^YTi?rK&F+dqKX3Jo8bt~%v=>~$R;3lqNIo)aUAJFt1rj>CJy5*^2!>YukvtIWss z5bD*oF>U?{1C-b#CMag0PQS=kug+<1kJ0|L*;qbboo0Q*(Ejm z;YAE4xseDynP&U&qoFzBU&B72HquDHIL-OW))1Q_h@|=ITar8e@_G9O0}nya&#s>)A8yr6C4l$hQDLd${?@$JPAb+}j_1@}C@=X33Ws^pSVs_^|mR^SstW;=dD>txun;yIyZfmmm?o z<0A_p`fD`F?K@c&sdeMVNbGJ|$rA|Kvk8!x3l#c(hddg9-$&!K3A(m)!m{&uy+YyP z_*poe53OJvHzxBT4B0VCJ-pw?jZ-OV|{|>0#JRy^0+RD4ejmCf0ka)Vx$c z?>Nnqu+~M`P0jOhxkNxwH42J&&s8cO6dP$gTd-vw6dNhRN@;Vy&B2M&#DjQLt3-kr zzKX4qX}0KV*_bj;=oG7ENVg6~Gd5laU}Hm-rdjzu5Y#D8blvi-piX(Blk&5) z1WGkXl%jNq-x{IC7nN$quVNz|$y;^g*#_*k76x7=*a&WHxHQ8?QZqWC8xLBxN-hW@ z(yv2C!FdssvK8@nDRyHS3Uv|48XGp@Og4H+K|yqeoPuh}sn|#oBd1~`E$BJQ$>U>s z9^wR-uKiugnu$*0gC>U-JSaA*nLM-jxJ9iHxGw=Vu>x^7ixnanO?)Ue7zFe-J``I= zhOhcX z&N-!xofR8J6nSQO?8mT?mHZ4~`D^T^A<#$)imYRNt=NsA3!9Nau~jmJ@$MT@$SO$F z&`XKMOnoe21jH3IB1rll#a7jq>HJ@ywG|d|y+q67uWYRB$Jmovj0}pcrL$tIWI(Or zQx>xluuj99=%i+&pJHqBPR&W)rr&&Cw)1j#fma>5iB5V=Be!B}#`#4#yp7yM*S3jb zYuaQ{4sT;`qHFV3Y!&Y;o;W9hRoG6#X4*H=NgkzDXj2}UnsL4uhp-vFb27K#t=KA? znmOG9Fa>*R8#clci40H0M)RgPXDmZ;u#7U2DNl3~1;nboa1u5X8(O@ouL(I~0}9zH z7vfs|LJNe=*lhs7+CEiml}}&j`mz`*LEO|$8lkdgKy+eLnxNXIYDk%jkRb6gU0b(I zPGnFD7f(0~n+g|s%=lBWbz*2Y7+HssuaTYTL|<}O*?HEY{Z7hAv!7})Vl|U!<;;>&&kK&+&p*j*OC|H0HvV?9K=U@zCjc!`DmTroTtVYdqVnq#7 zD^?U6#maQ?Vcw#xd3>v$hpe>@*FD%V%oxFeVT02vaJW)WX>jd;@^)p^6{n&aWP&tQ9kwp1`|T1ax0 zHn*rwmamzQ8N2kPX((iC>^C6TTE0l+O#1Kyy zV_+Vd>6m5n&YesZ5dK~X-}$d<8+V#kz&{c*15=*pWSq7Fpt|{o1j)FRHDz^f z!<7w8Tw0llPU?)yGc~8>H7}QWAbJMMqej%KokD6c0pX51{yfeF>tliF6NvUku zjNOT@Yj*}?YB>{Y$BotJC%?CCF{gHIWwM4xbdqbCdE8h}u~qG8CV6LmV@RQ<$nF|( zl8R?`?i1U# zu}G_%heOy5Z=!4aPq9(WeJDWx*^MxaMyf$kUub030+GzbrhIesh^%h$OSF6~J&8`d zV&qY5)K|Pvyj_&mk~=3#jogZ@lH06vElmXyE9T7cU8)2!Y{q|zjT+8$@v(MXi@KpJZ5B4-Lr$VT))@3EBPE$b8QT{H8%2lF zOR zo<-#u!kGNDR4txo3(qRw7&(_K&k!!uTg_REXGwTQa^3|{VnZtC43D$085`aSV9ppA zMuXwh)z*MyL3q~ZlNTsXWf>zVww4VQ8`+RP%ks$vTv^Fjg)=A*L??N}WgzfqXt+o9D&bT%`hEd+ z;|_+}-J-!8g#>>xP;_fUsWw$pg++|4U}OzV-Ez-Hc|`iEHexHqMz%8XtysRy8MY|C zo#OL&q@ple7mpmH(u6!d?BF=a#`q`P7=&;tf=J}yvvL|qY-CbwBr#<|b=a$y@&FR} z@$i}d$r{u&Vc6Ill6ImX{tX+O`}1vMR)-_tVy`_6?vS{^LacT(>N~TR5mgo+_;TSIVy2n%U6nJv9PgFRlaiW4MaGhjAnfDoPe@S z$~dV%KKU*v5|>%M8Ai~Xc9iXA{Cx5$z0p;%QQbyY#YT0r zy~O!7C(vjR21ri4ntW2m`%(~`I>^?A>jCV>Qaiz^6Cg}JkJ-s5UCatnIQfiZ^hI9# zjsExaJa=^Ow0ucRd0ZPHiAhGpZopoZJNvW<@qVKTjIPX5HYzAQO=)z+m5tHQ2sXzv zvZ$ljjV$9gBe!BBzfm3tfL*f+&Rgi|B?_O%<5E43awRS8t;TcG;5u3g07!<^Nlqgl zZFFT)_|3?vy+@S0TR~Q3Ujn@lo(+$LCl;iB**Jn4LetZDq&PTV%Hsk(FY(BRLpYD@ z-3WLqE*)uPz&B@bvcQ#Y zJvbQpq616hP(;I;DEbFYjt7=XM##<;JSaAbE!qv5W2c64zQ9`z{&-T%M-$=Vu|}RO z){7^@YiB6F;A{YQpW>)+F55N;vr~W{xQSoAkgYQV-V%VbGvI9j_$26E@jC+W&J6hQ zQDKNbw`IUb0`R5`_-FuL?|^XT`>n;V%i!;`&ODaEZ?y2S3?4auB!=Tkw~KM0E~xkC zZM_Qtr|pbK=Vhd<5?8tr{w~<5(C~rBjxI!oa<+LaC}&DCQj4yjWK2_e1a}-CKl(jH zfaCah9>*JM$nwO|zsO2Hkynxi^`cl=$T1*{c26GtbjIw>M zuFELCA5l23GO0wCH1Nps&VD~S+MY@EqllxU`0-J`tKg*iaUR97Yv*PZ$3puwe!TA5 zA0S*EkL&U%uD|xPSsY)VM{&codozj~@+j`S_B3R6SIeDw6n9^{wmDGT9Z@(tF%?Ai zb5^+b+G0~Ed2e3Hs7IiwwR0cmfy|TVh%{5n_)M`;Pwu)!9uym8YLmwmJHh(=#)$;; zxZhxtyiT|a;JhA{@MP3x`fJ59=Y%Zk z<4U(492|X=`!CAiQG=vw481bJ-v!vIyvhBH4_w0*A2@dH*KxvfazO+)QaEN&MmBJE zFh$aGGaRqG_K}QZ)*cPT_18X_QDp7WP~33s-5EvJ9!>30H<`dyq*$t(uDvGXm<y@0$8JDLRNLq(j*){4Ijf0Ggja-^J+ z6>%vW(-MWs%PPzY9?o-96|S<4aMKEiV1B6@&&$k(i3EA0$m1eCZ{ab07XMzrIIe^M zQFG)_&%kk|+in~jJU6R5MT$)AjxK8c4O0Rewh53;Mb_9)7b{NzUDgj28|4ftjJkPH>;%rjMzFR+o~^}>y4l>q#$1Mc#RJhv-Rf<IEIa%Tbur;em zVvBL0jk8v4spL@vM{Q#XI832!6hW4>4FyG2zAHy+ag&_Jjkhw$2OG%3u<14+#AjufxzvUS)xBFY^<{yEmbQwDmEIyk!Ki7y*c5y0oNB}HyNCH zey4yo;;(G%OcfMyrZ_0bgJL78iU3<1;S$$2f29LEQW%~@=lC+qe>*^c8dxN3CKiZJ z%G3HTC-Iae!C(=OOpQ1%^2jVsIFFx!%!K1qHkyZUV==;MBDW^+AW9^oBA3>9P;6w! zxl&egzG5RgGU%h6jcXZFqx-13MM`2n4JMu64BUg{NO+=26fZO? zKBDIY%SHTT&+B#7>WW%J#+M{XMxQ1=6dT#|Q9)%E z@Y`CPq;*hM!g#z@&x6%zu3NC10R=Ty&;-uHMoJig2Qo<_m4(!|JZo2j&<|lV?Vf1k zW|CMLx5#z;)Sbm&rTF0T`MACUyD=E0R8V9cqr+8FAo35fsqJW}9RCn(s>7Abi4jAk ziX_MxC$ccX2|ooz{1g=Nqg}E#Rl*fCV7*~8IumUiO%i&GI`epqo)>Wln^q~$G7+74 zO?@isJcci! zl-D{m&v6B$`kmw{Evb?i1PrI}H%og)S0M)M6<}#)p+zk>=xikrbMsNJQtzff6XCV<=l1 zAc1>48Wi4l!$Ry*X*i~0v`Hj-Jwo3wIGEz{E zP|pqlWa*sdq3}t2WiW#c4=j;b%+#mY&@Mn5*=w&{XVno;Be=et=w!xccq_Jww~0Rz z!^8`CC6{7r$)(tuat&!P&?~a7!!=>1 z)4LD|dfv1!<~{|5vGP2Cv|#kUlCiyFqr7cwuh>oC5;hb6ij6E_Y_HhR4UvJhJ%3#? zjVX%jY_C5)8P#m$Qf$QA$fej?wpVN6 z>~|d(adr8%Ipt045}jzFUXa}2XVN~m2q@B{2vA;p zhH(YUu}U0dqd;owh)*o1YmcGOAr!h9yOC!VE>)h8k^zxCn6u+|__CwXf>95n{f~T;f>kBj895aj$;q;*FDZLw&%H_!@)t|I8M~>bC4eH{+Dc{I zNG3@uH*zU9XbxJ)WX7rA5J2XUyK(&p_MFz2$-PK>#31(u6u3$Xg-$^lWIPZ6fz)l{ z;a&k{wJ*T+J=l}1Ln9zod0>e|wm8-qPPT#I(vBZB+9F#n2SruxEdgkn2f5I9VH`;l zqnb`0uTsQga}tBx`I4V;y>4L2txa*fjiP=&5`^uqohhqG*}( zYT;mhQkfW0Y!unXrizU?&qjIYC!RWOm-6@-?9jZ6$It5dQXFKX{|GbwJ0pNXTgyN} zf0icLy@RPda!et*DmK!_=&IOA8>6dYBRf$+wo@Lzpy%|yY|HTXVeICk#q^$nLaQQ3 zOMZYZkgW*}0E<|ASpxDUD zvjEn1&a>OG*J(>c8})DnYPBVg1A0#5hmCq?dE{bTf&Zd_#))b!ekMAxi+WOYQ*15W z6dOFm8t6+G)4cQ>!O2XXQo=?&D3-lY*a$Xl`)_>Y9b4dw6;=k9RvbOUvf)#ztQNoTMhg<^yz>fP&lT zdj&=9fnYb2S8NnRYDpPqDK^KF5`T(~yub*`bfqI6nW zgqpg3SFuseC86MRfu!}DDMNy!r=&b)zR`(Gc$!j#jj*JY(NVEuff^^Yy|(KVny?|E zNmHaI=c>7etB!cTorRMsIsy}ZbUzgG#pD>p%hzE65YRNT-G=M?up2)6ad|8T@ttJ8 zxooJqaQO)Vg-~k2<-(ZiY2@7JB=44ejbFg!S7Q)!I$sks?B9mV~mAuhJ6us~b&y1$HAn zT;RTw6SWM(_ev=cjagVI8#@$n1-YW8Xv!0vFu&{`s!j+wK920Da8)8)|S@TqEa1XI2|0uSOFGvfa7xVZ9JumY3sGbKO-HhwI zup2QC;qq7v!j+u~l1bu8V^76a$!2on11N6;<-NGRRd|;1SGKG0cRzL`R}U^30|vAd zmz^<)f_y?ikpxCQ)}BZ|3m_w35tmjz7Csw$5+#NwOVsCiCn&&^gtAfR+p!yM82xt$ zD7d{w6wMVX8Fhb9PD9w?%EpOeBTG=%5Zjw@VKt?V=>sEG4I5L$+V&vd9D8JKl3CJL zj7vKoAUferxwG;VvQBx`A(#=wGQE!b(s_Uuu_t}$G69i8*mmO#wS{Yj;g#4;$@6h} zQ4FfVpUjMXaRuH{{2dTbmav$))a8*>CjRz=BC*%(j3-Z*pbn@|!l`UK@RwiBFe6VY zP7t1-qW{9i>LD->(W7k3@t4WSn3VD;CFf#}42R0}reL9vnP6cpJys*f(JQyr-r0 zpMs+L=yI2vaTYcsHz|@EZVHO{L~_$LsoaENdLC-PiGreVnIlxvMJqOPhJvDcDJZIv zDC8UVI1fR?lf}X?6k&syC2YsHUZBavyBEU)e)3)3ud z>0W4w23RCBVNI%-&jEpC&6^a2ndY5=g7O5#eD(_@=0jM*M?rP?T%5y)u!N6->hQT$ zJxEK3O+!M~If+gJKEz$1#|eQs_N$tQog`i6*Y8TD+1Q-vid~iwf@(Y~pjxq|*eJHN z8Or*#Vyj}yjH`BlJAx}1k0+Y?B8wY)ZWDQ`cuu#SjEqZE#?x>J8(~R;QBc$-6clMP z3k9bttC3;a?3DTcK1gCsPu&Ph;$K0L4mN+Ck>s!C;E+TS4adGQSwSP%yr; z;TAmK3Q#BZB({_)EF*!yy&)vOU8mScauZvM4bEa&6I+T6u}!S8iDDy*Q4z^eJXwkz z!O_K|Gf#;}u9p#xQ`y$x?=rv|8$$cw49s>Uh16jBmxhjByjg|nU#-;&fTZq4o z*^mRtmq#2d&@t9kj>sOGZDdVav9)Ze*vJpYmWr)qOT`9VDJInS@xjwu1e6W;C?mO< zV8E4q@8@R0M$)SHWWcG|NK-lu?08UYBoD!C_dI?=gO!Gsjgfi31Zz;Asa!$9H#Ksj zQU%|W;XLdvH!3#L!o;s)BQ1>06Zij8zkY`zU*K;=agiCYi$KJ1CjjXYZf8_8pA zuGmNyTGQEFv5`E)dYj*`=OrFL;ov-e)xmL)?OyyP+z46327j~Vk6yWp>8vdc?_2@1v$#b6Ro`LAaXD~zX(81-(`3f zL2+U{&#vZ4ABCJZ0;$2V1ek0*xfn3>VBeAe3VDnTL#cv)76wr8&-?%i{$Xy?g25@Y zi-ICs6O4%9fimXUWvXM#7wOcL_!~A@bjoA%8L=M)SdQIBGowo5HM9`Azl1$mnov+Q z0U@P}7sZYN5H?n4+7a)9q2_rWzYHf@DysR2^bk>4DkxefQBYK!f@;a9*m}9c4doYj z`37*Z0lP_&UAVkRzJp`UBKgfJ(uIz4vx~Yo#F7NZi>Pp zCfsNv{a`^*nWE%;!$2jJd7NS+3mO|Kwx;}tRL&5bB~*7ngo-4n-z#&3HyR^P z4pUF3k_59-op$U=oN1)XdKOD0Hb`WrB&as1$HFRIec3~k1${#iyOWcb+!!oH>?SmE zC18LuY{Z9P+JMJv^qiq1+XnnSg1u4hFbjyflgum+FaaMDP!OL(Ni7(13VV75g#cdw z&;cnJNu+5;o-x&$qBKLRxpfc4hVTZ$`dhJ^2=!YLC)VHeKVfD?hrUoy5R=|hP|y#M zJP;|fw!$*j&A3c!%Rmup@{#_NCl}%m*wCc1@njWXW@1mNh$*iK%%2&Bva^l;N{Xu#pEN`R@lF@{^HlOYv9B1fA*ed$AjpSb>6qN`P4T6&uOV z7oMf_#$Mi-jtCIN-PCIwYc6gvdFxtd}lyJ}jMbu7i!idn_h(n+zA zPP8SIz^)(t#5v6swiP%t9S`9O3h|qPA}1+TnOMKkXd1sfdj>md3xW3puKymp@e(70 z!DlRbMxY7?Y6+l7Z-P-U!$x}F2dv71ldw@Pl;ME{rs0z0eC&10kRT~TyJl^c%0g$# z6gGw;>g0jwoZOz3XFR3l2}>$fP-J^LHEDZ*_=jJ3>Nip*{1g=Nn+K{Kegr3ljZGCB zMUIWXFE+*zL5b9hGJYXC2}Q$Ou@P@#O?$l?mp0&N?ZwzlbWzc}1QbGvO;14~-~e%x zW_>nT3Pdf^_*BbAv9}xrs^f^z#B>UZ>`r@S@xV&ccpxm{qo9b-0WFEY*+%z(TL!?{ zvK&}q*Bg~2G-TSeh~3zgoNo}&Cj6Bx14XtW7}96h$m+(f$}X~c5oN3GN@!va1(ksa z+ftlWmnAeQtDtEs8~d{h^;v%sOIUKNOF@wgq@?e75Xx;gmT~Qtr*2I@sKXYSWF&IA2|N0Zui~I<>QQW% zJfhgpz(Ehsi*Q$Ua0eWuX$rA7p(I z{y>2~9B$TA&x2S>1aEy7hriI%r*TliNEg}yoOw`eqzh%GEI|Zao@=ku~W5x@Aa^ z$o727(5^lXm+N_CR9?8)A-ZkYxiS1`m9yK!3!bVu)Z4=vyjoK}F zYW(o*DIL*8ELCEe%MhK6ca^)W=_xkiPQ$pIq1cd>fIz*zZl3ia=|Y_%PQyl5xn~}T zHaVFjCN2~k^&m!X#fB*z%d$q)CdWQK=Qv2VGw_!%v(7=d8e*IW#YWXBD2i(SUf~KY&ZER=cT@<(=z2wVZ&zhCOV1M zI38z%fYR~!q*`Gqk9l#b7SVS>Bu*o1&j*K``47Q~1gy)&tYRadQavMrsoTA2%8#7zVCeuz(kNFcBUAjCUzJAi9It}gAh0& zG>6a(MoCR+bJ|^wr;WW7Th;D@e;D5|S7a9B9}WMg`75ZFe-vBgAJYb%Q$mAT0SVf% zqjmJ)a70h>SGM{1OW|^C0gF*PEl{iND3-npTjJOE0>Oas_)MOSymjy%?8&-ZeR;G% zWHRFq#YXbDh?V}6*#p8vLmx_pj)MoH&65DQa$Tv6DHI##TEv8IF8za$RctfGZDxER+%B2O8AWjh;x zmtse#cH*!@Pw_Ww3`iH3ijCwkaiG{p9&4u?zz23Jdd3uPFLu)mO1L~m zoETdww#t@aKJjJ9hWc84@zZefMZiq6rsfI?&(u&M1qBOwkbSDq!%XL%fr9-!$iB_w zVP+_vf!H3yM(N=BOvox-p`KX8{X$+b6vYYEMNIObzmOM|W|iR0gJL7U*_gZ%BsL~- z>9UXHVWN!@h&8+w8`VtSF2C^fGuXkNVJ+KQ{CyC+d8(7)uAm^~Qh->*G>o$XRjBTa z016(VIh0p$F9S|NAqW7m_ET)FxL0h{qOAScyFtN4p7dZY&lJe&KSU6yAH)x)e+jQQ$~hX6daXz@ks09d>)TGbZXIsQ`xrRFF%%JYNe10 z3Wj84v$XLduI%#&WM{p3UPH?9`gaZF){{*q|x#*mboD=TWT|Z~5M)<+^yhUC*odX8O32 z$NeTM7}>mb2QG8;%;)QScOKVjqOIj$qI39qJ8;B^^Qg47!(BD-p)XjGLqJ%P!7a~) zIYo%i*VT0-MILw7*Ollxx~{8HueZhV@QZWGv$GOg;21WBK#u;ZU!cMXwN9o`3M!{m zUPc?2-%x85d3;*WqqrQB8tUFxwCwH$IaGN<9tyfo%SQYhaS*N0&{%lgtl5RN1!;aL z+}QZ?N@a4qr_$TkTiH--C@h{eyKx0C21hFWJ|JcUvArx!;?267M=5z*H@(OuavUK#G*R4I4&UeZ5N86SLO ze{p3SnZ6;AfI&*KsuL9JNI^+#;VvM0ykfnhBLjo$D}DXry<}ZnwHnyoz!-HyTU*+q zk~$k2`z)45nR3a2P!hV-sUTVw~2mlD}K)ZaZ;RhI4@^NfcENBTk0H#o8$m9|r~anCowQJ@K54&I*_ z8y%_$&G-aVWO0f$sU*<9XRN>b5`rnv&5Z~gm_fwq9v?3*^Vi6DY(ooXh4#bq!pp1L zQy+qDAT+4gOL+#;_++^}IwnRQB4-N9Fzpln^b!U$_mxM{gvN_2fgMP&(zXV=d;1kV z7SQF<%lgNlLI*Y5C}39`8hHO$Wqe``mXk(Mr0w1)BwA%I!B2spGSokUA{#50PIeCs z4h(`1TM?>h?FNr4Er~-&tCgI>vb_Vo$|J37P~s|IVsIdEB7C!l_m=~lA-cuGM<+5y zbkbIj80sEbKiEh0LP3VjHjf{j*g);e{fO+40U$qX-2tM$%3$B7O2&n{(LQeqxZwe` zk_p;YB7J8-l*dNt6iLJH3P{*|uzSekDDs;F&Lt#Qj^e&0;DUpFQAWWYprsj4 zTwd-60?o5~EVR(Q5msCZVWoxai%=U8TccE@lN#=iaKqi>Yyqo?Ip8s4{k?uQX^99IPe?a(g=+s;2RwO%ht`a5ae&qm>5x8INZ6VauHyXGsch#G^EEn0&(~ zb+yNiqoBc&>Dw%>yRQ$4Ot{j_Z}&J>$Y2>8EKi8RT2}#mjYpGhjApF9!=qVRT|7C~ zJux^sLaEs!9rYAsP({Iryw+2YM`TjAw`0sq5(i`up?iRSXNJCfq<2GQV61ysT-FQZ z&k9mnfCN$IP+IJ|1Y0E>-SzH-2=S}QSiJR~1RIIR82=v$fsF=Q|M~>45@xA~R-_w# zE}^q6yh?65=DkUQ!ER|fG}+H5sGd;?h5?}7Cn#kIn-7mp^j9wHzNCMW!y*aa8!g3n z|Ik21l5oFpr&Vtf0vCW7DOEOf4^8+G{y>DRs(|ICC-MPYndl#%s0@$xg>Lm0;o!`K z4!pZ(aN_a`y^A_zPHnzSqA%tL`5c@dowWFpT+?t`B(;*A=aQYcuH|!g2C90 z?xzGF&rq7$(4L87{r6YlTtPOIUyG1K9A!(h_@swR1XOw_#so#dABa(d#pN>&z&(a4{_y-C@qdk{T^p}pDTP&3h@7jB)t8(bv5-*prcJuh>GirOoFS*A`1#&ONvIh9WO6l#7PO zhYN@lOLb8W6(&FFSZyK3YOg5FE-acoyKrXH?7}POWaBvCWbVW=hOV(&0&wGCU$L!i z&INhCF2vryS5(Kw|)2at%nZm+q-M)!6leS z2z?o2mx1wOdwWO6s)ojXg=OOk4%vVvhmQ8*#$5*v9p1dV*t>5}dEbFUV4}lAAK%j1 zaNOXFVGIl6y*qZj3AF2lc}UAC-QeCs+Yjv6ymdQB2SLhaSV2CN%t5F2@lf#@Itl*&^Zd3}TbflFnbc*X*=TJ|Xl+QKg=S>Z7RjW@4UG$ADTYf)F9*%S!tBN~ zhmkx>$RBHv56&tN_Ff`at8ld>YsSngr=Y~#EU);seNsG`t6ISG6i7N3nd8*n?hy>4 zFskQz2F7*c#Zp(>nl?ytT88SK98*-=s*bKs;9f%9`r%cr?XA+YVq8$^>BjO06l>eD z0~GT}Q68M=-C&7`Zx{T0;n1Sm{jUQ*;iz^u@v`8saGZE0IR!ayaM%#rFPc3SW1di)yP)~vc0u+l`Kz$l5HqS z=g{A?DkQ=Jf~4Ih?3Lh%r2bXJiBm4%k08SPMKYpH+Od7rKip=%s*{* z;bo`KE-W}>cH_dH;lb9fE?9qkrMtIx2;ItH*%?ag@QRe6e+51*8a?dLEd9z9eR(L&7+GA6_N7+>{i+oG#!#AV;p}R(FTEP*SEp#K z+l^x>X>ho|(kcot5Q=rE+JuUY@HKU)+J&kcR7+ASj2vVnUQtecpm}XdGtoa>t~j~d zY0{;+6wc`FwCXu21xGWKqLTr-EX9sty+@i|C)?~#q-Y4)Rv8?X*)^H0WEG_xs`iMA z{yR5^3cN-p+7bR(mclx!?Qi z(v11e6dhu|l`+4v8tqFn=2xZYI09Q4rK?k#5Ff1rKzF6+9xR<*HrO|@fi`9$Yh06( z43&p9!Wm!}rr5{>ZM4DbQWA>vc%3;cAzHCfUa1(eE&loJX);jbJRDTg1vnWqlb9 z@3I5C4s9>*+FR1>J+4qrS5_1~2p)O-&3I^c2KIJQ6esY|J1$bZVcuV`JC$l!7 zNM;YplX)oRTU%z&Mzt1ecu>sQ$!z*py?ezWRWj`IG_UC0fEx#cT1CPp#L>6K;G^IKcd*SD@&-PyIKwWD)Q z=gPL#?X7EeAn~~YON~+;t5$V_>iqIxvE%%<&bF0n+E=aYSh*w22Tx|q*!VI|%4u(R zqesR$&ea5SHaZ6;cC%5sLFUEt0e>0b3ua>+Gqh{Zu0z9{kCb-p-GBJdiandLHuCo3 zt{p`M6fY`z5b?#=^YV4YcNDkpKDgbGtu3CH(D9mt`rII8du64vXY-+*m7PTlLMoN+ zvEkmK!5&z7Y@CbFD_d8!wsv-6bWo`bjgGA6UfjKJ@0;Wgx*^^I#;vtAYtYXjF}5`{ zwvq{!6H#K@_N}`Q?%%$(RH^LUcWCEIqoPX_4bLx&FR+H&~N_DZD$ z2K%=j#L1G)n{l$_TrLo;tYA%aW53ANH#*sa#WqyG+Ose7CStA(Df6xS_8vS$j<54& z2g?1Mdi%>0#Y~q-oKT|Qmlz!3J;LIyy}Nhq-Hx@D7|!*_;=x0k5AE6-NJcXQM7;A< z-C3y&3{A+2+49oiy$5%_Y47%J#pUNN0|;{Ofh7hVwypS+#VQie?4<*1ayU>C|3S{) zq48qFtiNik;J)f$&&YT~&V&orjv2*jm%9g{sb{|5fMr5`&H2$D*!{qvYuHhin zmv-#lxB1Yy6?9SqgCks4uAu%O1`=e0l7!H1S->K{AOGH|Fpz8SFVEd*6+c#rzuyka_)v_>K&xFgC z6}^c;TxDWe%Z1yKUn)Dc?%ChTMdKC4($!ey<|qmQny8m0e4_OwQl6d-*nSCY4}!YhgsWbj1Bp#21@UZI0d?Wf7-gLBXo4s_$L z_P}uW07fj&&dGFYnDtNQs@yQ^yV+%X!>oJeW`kLd`Z*5H9k=6d7@yJMjKn>Y6~^m+ z9N#=U+%GE3aqGocvur%Aryq|d4h~OZl5{@q@o|~=bb)nm7{j_TfSqjs`gvG0!7_1} zD|ZtilfQEn>O3{O&)7Iep1YD^4yP3;)OafUMS=7VcLH`grW0piCifD|a5{PJ3y<>Z|~}8>sr|X(5o=ZaJN|Bj?vGdtM_Bjgi#u9!&Ww9wt|z_Svc<4 zR<;nnh49Uo-ry3gd^6H~Weesj5N+um3^w)V?(^cgwwkB6YvZiietvO&gvnQ!?YuZY zdU1YargSgPk8&m{VIJtGLQyyDfiKRFWFq~1W_h(HI>(t4)GCI)<;D4tn{mPxFV2s! zwrJWgXSy%Wk9N2?es*cazVySEo-dVUnk&j-tD6HB+_OuWe#d`isnCKN&)Cq9r^0djbAY#vUoz1>hy`3+@lNSW zN4hr-@~V{!xbve&m=;X*cVotdXNQUBjkA{vqz6wz3JCYiC=BOOG6oIICy8ERX7NrddG6?(r=rTfO;{#Ep6SvT$nl+$+hLd&-;x+BTclgf2jL%Ha9Oz zh%NW7i!|>V_ps|dM>Y%L%6~{3zMZfw`E$g*4Q{up(|F1_-mG&EFF>kc+y_0}(0J+? zUPa}5F?_XcJ??h4uRL5ccUZQ0ZKizLu;}Efbov$`ub0iY@o=4^OXJJs>F$BfBS-jx zNNA;e7x#`?9-r}FP6EZxd**!Eq zk+H)q46^%JH631;9t(7AmZZC{nvVQJy}UI>x{p`Wkzb&LctUr7H68iM1Ao+mcUZ{p z*Q)8r&(l#nq5DKihaQ@*si=|V#vR#xG9eoo<(q4R6L>iiZ+UySQApwXKn^)x&h5M0 z@s;~P(i#VS4cH>rl@n!_eXnGU{=NH3D~3(*i@<$5UE7Tu@y>$<|Q3rsyw)3AlVs zxQt(XS*2~_Qlp&+|EB@jPGpWKD8~no{wxr7)F$NU>Zw53S(6ZCPYYSkcw3%Se-n^3 zq?$lEO7+b^SVJljQmVfVgo#wadO~T;r&XZnw?fgC`3jMe4_^IUAY2s_Ms>93)$#YC z=;{+F+Qvs5{vj0YI+3DzQalq_t%+IrkfNr19^xMZVOwiV8L8TlSIM`tvJ#J3$kiJvvUzemoAF9wr!KE{+Weogvh~6#)j!wu-_3X>@l{`rL?^M&KWDs>5Hucy z{6BPb?RkywM**4GIOEYSjqiU4!o+}$XRFzahi3SwsDmwpDnsI8E(0RgrbH$7IsK-Db!teS_oOe8evi?3XM}|42e2 zY(8X31_lR4!*GeBv;V#;r3eEc5D1U^ghIX*;fEcfH%ouqw+8O2PWJr z08-4=`(VK8E8Ipo8CO57cnmG`r2d@6R!RJOg2g~`7-Ni{(M?uqQR#~bf#o2z|9(Q? zM{(3ZlzT!528O!VSH>>wEoU`gmPy0>afYARGXu6f3F9QF+%mBTjqGV8v~aNjn}wC*tg^Dc3}U`VB+XR7{=#bIP`sIRmlN) z2cWvH0elvSCEit4ViZrHk4<6?DyPusMlJQTNvXCeNyu*hx~h`(BxH$qSCu%Pge-Nv zFXcY|k)sU)Ma=zko^*VuAD_?2nX1t_<3pDS^$ngHR>BhaW!+;VHN1jQk`nKWOO*N6 z$3}Fg)%NW#!@dyyMqdJJVWR_BuBj$PtO@D+Jt@9Ig^zuSO!(YZF8d*T7l`a{@@0fP zk2?@T`LWr2(q9+1d~(oSop;eV9=YF+CyRV(PP_a0cCNfO z^y`MN4jn3k6NUj^ZjhP$*kpME&#;5JL7scwMT2;4VDsLs+i})Ec5d++Ji!!~fR+!N zI@}QEq$*kV`r^^*S{^mE$k%`Hw&m#LSZ}`(_yo1VeZDGX9#5)a*B{p)g8?-a5dKQP z(ZQ#(S5BUb?{U;N_ifn%kvPw1DFN2<21FtKqHH#}cET(du;RY`m)=5j)MJ_oyvE2HpO7OEEm?m&0{kD(FrF*E{Pc5CLccDStF zxeUkPGFe#*D#jS=vKV7s7Gtc-VvKcJjIl0@G1g@bY zgL>9_cTy`Sv?czLn)D>DL#Dj0hFW-8XuZd?&L-ET34BRne0Xret-VPlRWMgyR;;z? z>N`GZ+tf+hi!{K;s-?tNjmIbQM6IeG(JO1!R#d&4mqGj*c?OaD5%>9e$0zy*`%3bc z=5Qy{m{x0B`nV^>Ix0xzFG<~rkhZbmVPjLe-_!RE^_H-cRt}()^}k>91o&nLUg0U} zL7d@Foey+j*IB&n;mWPI7c?{5r2=l%jNzmz*95oOEraMkxA~m%K1^ zI0?Z|d3Kn-4&s%plKk~v%UkzR?*Zehh?Y*Ov9df;4fbmwDJEWtsmA8AYpYbTbIT@y zLAEv$K=A@d0`{vM0qmAC!gab{5fH)_u5!=iG%l%NwE^Ez9O!Ia&1Y@!_|gSlFyvWaVwpS_}x9{Dy??7ez z>Vp%zw!TF_wJ4w0?!e4BVRC099+lfr8N(+X2gfemTl6Olg?sp9;71$rh||4|c<=1J z&6pyCQa&&SvGn1C*2y7!ueP}t&w$}J1fF2Al5nQ)-HUGl=%jXZ*`c_iL#f9 z>1Z{I68(z?t%U{K-71A|v&MI5DC>FuvZ$nNGcPnW-r?X*REN?lJa^UHUG8bK_BZF~ z(}`|3pkm2h{GYL0wLM3GQ_l$4$ID8)VCc`qqf)}us73(t>{a#bBlY9*BSk#coCN-yWfN!eCU z`8F@;{X$w#dp16)|JQ`Hp8E8bkba_hY@)Z0r0u@?Pc~n6S>O74l)m-{ng{Ds@|_#0 z{8PhPjINC7(P3!sS!k@CNqC&%$H zSUnLsy|ABA+Im7Tw}`mE(L4#Z^}N;T<$Xv<>qRT>u`1W!glfGmYv;C=m0s4*lCqvw zE4`$@Map_Qt@MIE+>DixdbO|ewSSJ3^=e<`YyW&RKX<2}$jnO;o(s{A1EIxP5Tj=terO|nXLbSMU;?|$7S)T zVDoq%M?SR~`B?f2n{z#ThJ5me&EuDk^Y=k&a}7!2kD57ws7LARe}cYWQ-=~RQkDN$ z;;FSBsdwjBg|wblAwPVrnO}J8_FR*`I11B06;d}UD5c%Dka_|BOh`jB$>Zu9-cv&A zzfPOW)!XXNg|xqptReXSLP!Vdk$PGGQb>bab7T#@9;JY&nyWk9-=4Lzq6!1wIrk~mFwSIQs4b0q^p(d zKUh-V{UxMb%Jmsb>N9IX+O1sw(USV%T0+{RT)$0HuX$bz2>sc2l(NbLuCVpMvzF9& zz>+!-{F5d1a%3X8mMtFmt|c`duw0!7{@Icm4_H#?f#)o#@qi_D9{3kaYCK>`od>>W zNsR|Asq?_UHuvM(Z7#9rGyya$_3HP9a5#(rd@%&)zbOjSOXcHH_%8LU9u%yiT*XPdRQ+E%MefLrU{cl5!ha6lDRpf1Wc#jSESc{;@yuH#iCzY=CNI#w#)GUi1^J(EvMDSO+@EZblM#}Ftx8gt5$1S-)hM#_k$;6nB z?7e{uU#INBViLuCSA66)K&10TLD5-RkF zI2P3 zNz<0Em|G?Q)xAQMuUcEs?PEffuUuQu?!Fc*06-`%0~ka4RRPrY@fObfK_UwPh9)cs zfav}fPWnM4bALk=)&fBEYb|cR4?2wLZGCnj0F<9-;bgy>j8O02Pm+d4NLUf-X&zvW zoZwfJ*_l6T{1k$ivwINAi51Sw`$73>rDVFBl+!+apTJMxRd^8vgIJZ~_cEPKb?ygnGAqfiyH_HBB((?~;aYtELHV zdz3WUWZMzr*PZt4+nd%MPsySD7g@L%F=%M~{T5Et!AR!oM*J{;N6E+77O7%&TMR0G zsYPe!q|#}+WtL6c!S2f~oScJD=IDkj%-KQo2XyBe5LLTeXX~JOoHT8Clst#1P3K3T z`if9d{AyNhLH<8%k$E_%Bg6vO(jL+=mk?C9#9^{hgU>#(C zDrEF#9yc8vgY3^*L z#hJUI2{U;ReYXXZbB)0FP_42 z6~BQy$Oq&6FRSB`j@tz@K33_ztglkucMz{|@kyg!w&3A|Z{eF=ZIeTMMS+|$deGis zXe}1S@bsTY_K)I$5b~GT%06hpx%?eH`2VV*_56ty{&#xh#i0UuG3`SUJhuj40#)2) zseK)Smr6by(D-idgsLGAD&8F<@~iP>P|rsq`cRQjNKN;60$&Kfi$H&TG=k^W<4b`0 z-v7hbTYO8FWk;V8)9(J78LRPA&nhA%m9&;736)ZovQ$-(QKjlp{RutjiH5<<%*@Qp z%p4ia%*@os&)#9u zxh=x|$-A)d0?<(NK`hDQw_Q3lo>b|JPMc4wrJ{h6-Y|lv7R3^28Amd#>B+q1Y_V^6 zOK(mJ?{kF&Qj4YCv$Qo6{SqrBkj`HzkaiWLz$yuRl>=$RJqoOrKq{%mH*Up&HB}%z z@qhSr@i?v(1&hr0Ri)Azuj53u#^%XuyuPxe#}v4~Z9Hu@h|(TcrBY%eCn}tIGHz34 zX}k)-%kL-NtWtYmGna^4BvT>Xm6=;BQ+iWx`gY1jS><8=btSebs)45w30J|!G#5!+*nXyP8$ zR0W1FlaExk1~`3ynjddIO&o0zo%}0)O%~BaKBlRP3|}T6SDSysW!+t$XvyRXlm-MQ zJ#y*SIoXoQEhr_(nNwBfH|e>ECqdc-Pxp6PwcydHf+_Q}WU3YMyUz=9rZQF0^!=^* zfjBEtdt?<$#B-defab}(^OYsN2i6|;#-CcGPctCFSzqzv;*sROSh_1tL(h~;rQG%* zZr;^p^0s?uo8BvxH=Vyxw4HOaUlpnSYE`jx4A(eO9ff)FaoluE=f8aYU3#}oZiU=J zw^(QgYi1JbHu)Xpj!e2!85*B{>aWMf<8qgU_9SGI{~q}(Qg&q0{mRgo)bkmdjPRSf;=hRO-Rx+tOqdlIn(w>7* z0zD^xMaqthdQlnDXWRWFogZF`)E-vF673ZyDx7&T?{#JQP1DlDd~C_&OI5m3)yyZ#RIP4* zbgG)KBh{YWp#{@2evu5VVshn0?Diit2G4K1RN4F?Ds+)wNp`~Ou8C*`t6!u?Gx5{E z<|*2qBX+{-*{b@%>2Fbl)8X}M$u$oU&U}cyD`WWtwR1@y)f_F)&t@=z`%0$5x+_Eb ziK*>#lkT>^CfcnlB?f4s-Sd(X12xg^SxJdOWukgc<{BO>k}sV+CDXlCPlO?yC>IXT z$DwSAmaV$WVd4)Kt@01A{CJM!^U7EGRW_nU^kb4|Vi8Txhmo49jtjp0j2M$`KmGRi zX@F1vPyd$GJV}pj(HvY{$x1ST$7w2qOJ4?$S6j=XmJxfAPiV>L!nS56wq*4A*qWIn znNGGS`Koeqi&nQNIhht^il$^y(qEJ{HqfT3t!7bh*V9@u@uDCzy(JSb3NkY!)7cg! zpHXMFXmyK{lW9?AX-XC)eYt#NQD&>HW>Ik0b6PU-q98N3B@-_SGV>(!l`TrXR-50V z)h$X+rbStxDOr@SY*7}ft!7bh*Na**@uDEJxFr)W3NlM1^Vha0HkdDM5$jeZN7Je- z)0C{rU)!oIS6j`h;I3D+Wa3ppW@SqzUKM0kN#<{SRq}T1>K3tXRdO_~${J0{s{DkE;%Qv=&b*qx2X;n69N>=4>ZB;g_t!7nl z*IQaL@v0!RwIvg;3NqUy^DA4G&Ur&^dy81NDmj`~WrwC@ReoiwvQup}tAe}U)sl%< z1)1F~nRr!@*&~_1^Hs_FFMC_Wx>d>1v?}{FC9CpxwkrG8RjN#BcvX-&*pi7? z1(_pNCjBGvZ+~B2z#Ubo{gO0uX+@4nrdkkprMpP)<`Gld<)FJgp^0{jL5Y)^XtxxU zIK_#4;gY_TBkw<|RI?Je;Q3iHyb^xJc1BF`O5kqKY9d?-B+h9fTnQx3b0S}@{Nk_j zrP>9RYE}YQITt0vE8&-Em&6pW1n%~-Cc>3K;)*81l|bSuC-Nmq`VN`KbK;sxH7kKj zo9mL{mGEn`8)AxA0(W~;6X8lAaZ3~7N+5BY6Zx_P|5|cKwVI{C^~_z#@KX2%**!7E zOM$z+uZeIeka(bpa4C>@$ccO{l9nQ0i9J%SW+`wH^H?&x6n+)1mja15nh2KyiMO1{ zR~_l!lJYgzJJo8I0+%cACBsYM*IOUN6fXtt_M;}kr9k47Cc>pa;xi}mrAAtce4+J4 zwVI{CHA=VtFu#!~?K0&P_TTYR_(fKCF~v)PyX~Qga4C@JsflnYkm$vUzxQj-{O*L_ zs?{t-4yLnCAIb1i{JmXo_7zjS6u8@dnh2KyiT;`hmja1FIq{p{eV_IU)BnFuA2XaU zIMTaU8t2o&?POn({24QNJ51|6r1X$B>AW`LPIs98V5~Bye+IDMB%kp8HyP1Rj(!uq zhxD6_Y?H2jlfs>UlQEU~EBq$;gzLY_*miRCoA5oP-(*~yboHAQ?);lftjvFn-z1;! z{5P4@PL6&PzK8UiOm35|ev`tTf0Jq1{7>myA^xeWy2kj?gOmHS}(_#H)<^+#`W-l@Zu0fpC=(*e8K-l@Zu4 zfpC=(IM59EJ38!JF%Oov`}%4h=RoR-Lxs1wus_;`*Wp66B`yAuHP;vJ=1A$xYgxRZ zj+{qJXI{kOZFJ;3RyyrTT=Seuz_4FU|RlA?&PqEPcxmJbJa-60B7Q`GWo!*8= zhPKbM^8U`Sz1_2{w4Y^ryXRPGKgafV&#=;dp6%_PU#0y*Y0m>d`o7-ArR_x);#I}e zaESuts`{{VnGE5o;{L9%Jz7=Rud+Q_RoJhwJz7=Rud_W`RoHKo_B>1A{Bx6)cv&%l z+@e6atUfs1CPTQaxW7AWkCqkoyKIk^74~~ z^bCK*k#cF1Cl|qEwuFmY-RBbtM9W(Ro=PBE;41J;0?`szf#(v47P$(%pn#9NcG7t% zQq3x3U;Y(GXqEjR6kf9>US-_p8wrG~jKEt7gsY6eI|+oVjKF&dgsY6e2MYKo-#J(B zN0Dk)8GHVpI6|xJ|5)*vE%7SjKEFsHTxA5h{YQDr>ko|`uRo-ZJPB7Bf$kCrR~dmG z5(rlrf!+vw)%cZ)k+u&D?U%R;rMBox0W7dNa#!>tL)+yo@2@}G+bwQsAHeo@OIz9p zvc28Hmi9qxZ?~+aeQ;^dOYIj8Ls*Dc6_3wQ3Y4qr&)Q*R2v-&NH=OO!s=_{k?a`{j zK9cRxs=_{s?a`{jKDxB~_KOXzV_1oo760%xmICFn`oGtWBSW~XxWDmikCqko32cv+ z750g2kCqkoNou&tQAB ztgz2yd$g>u&tiMDtgz26?RiTe{cB0yVwuBAysX$rm`j0jS$%tD9vQ-A#r@4^d$g>u zFJODLtgtU+d$g>uFJgPNtgtUG?RgI%Eo;6iSi(xYtk^kNN`Z1&eLrOx8Ny}7{VivE zw5+hNV0*Nzu&-o$w5+hNVtcf#u&>Sb-=qzNzoh?_7Xs@B zIYO)KmkI~i60b7u^PmL6RYu^D1j1ED;IIV3RYu^51j1ED;3x(1IS*G2$3&`GWt=OI zbA(peuN+RWC0=FR=Sc~KtBk-Y352VRz-bADtBk^+qtY!OY^`w{~d zu8e&IQ~DQo!9G?g!WPkleIhYn;mX+O+4NnPzXt?aOKPJ_u2NXeb`ZXP4s~Urxq`oGLv{8$)91BBa=Q=hV=K* zPRegG`^-Xn5;BSOh5QvMJ2I);ziaG4HRz3xK5)Et4 zK7Yu0`Tf_uR0@DqE)jc6rinCHX7;H}Rn$L4sjn#QiB&2A`*EV;6}bMDC4I_)A7CCx z2C&c`hD>4&B!7j8t<0?}XO;=0#RX1Lw_Q)!hh!Z$b0Sn&5%95TuIK=#-o5V_c8bS#+nfw(i zJMy7TsSN4aldlfbk>z%t%1V0_LJ2jE{1qxYGHQBdNY50Y@|!Mau+kodP(sZle}&49 zjG9#$8c!Xt@;jhsi_{)g#S(1}Cn}tIGH-6v(s&pF%rCilss+R{)&|y`OsEWhVRmiok~Zi z4josL+PPFar#Fp}`c)fOFxlsZwbB_i#NuXu!(ZFU2w9Gvk*dl?Jxkm$AtH5`^{_*So#}+xi`nHMUi!5tg zrP3O2=R~!}=E-ZkgDov1P~+Dt?{cU3bqrGfF7f9TF5d8?{@vow3tYVINBw)6eta^J zeUJ8D67Ym9K7gumVAV$h?JM2Qb;3sj?QhEXkfTod-Twzja7rG3#Nx|)-Tcwf3B{Gu2Vm+8;wRm=5EZWU3=^SAJq07gO8g zp}ReyiFQXtiIY|0Pv3mq)sM?Qu;!FV?VkWuEFINpPE-eFo_tI{SC+0n{i(~ZzXvg2 zUYuzW+cS%3qMp@M#f2}EFPP2eL%-6_|DtkH6o>L|!nb8GQ7>`Gn3X3JFOvlqQu*rU zib%D{oJ`2893rIe+1{uuUGlj5+n>6UEuFq@ish#t|3sE_4twi(r$fVbmq09F_`lmVO=lB~I+LMq;q_^a+NZFA|?<&K; zq|a@(W6H()o`v=#WD@BE`72U(WYWjV@b$mq6Dsql`iX`1BxDllGx;l0c4X3*rs134 z`Re7@O}GCT&!MjyLO}9NB6TN!ljPyF2~iokcKy~#c_`?~LVFT2iPVey6)8LNG4-wt z>C+Q`?GKc_yRMH&?O|0c(fV?t!kH)Y`c;oQ9q$gG^2v zLO=Y=*Z*8p#b6fNV2VuQ3?aXP;K-z*mEor!LCQ@rjD_|jWD;pO`72U(WYUPrkiOLZ zhoU7$ve2G{Od^dUe?`iUOd4Go{`H^#=%m~dV_0ZULMD;MlD{HlM<$J{42|P-RIZ8f zqO@mKsRWzAiHc^PjGI_ly8hW;RrvyZ65ZY&<%tBET)HbvL(h;YmD~l8Jn~MZ+uK7t zks#AbcLiza88W?+fBO2je#)>7rWvfX=OC0oGs$0(vLmBrRfaBq_7`k^g3m5*Z;!D+ zg3Kwr6(Xq_Fh7f3)61&MAHJo}^;jTED}_=Cw2%{-)%0ZCqRP_s&%gU;{}_>cM2kgf zkE>D%w}cZF&O8~nw6c8t<4;{3m(T9YL}`z!QVF-56BW)p8MmUcbWJa4$K@CAN>SS5 zs#Lsr3TK{-TUS{cPZhsf&M)EhqO`|V zsf63Wi3(?)jN4dQ8V{)B@{4(sDD81oD&aPBqQaRchy!>i7C{lY~6-&HBoTzx_$-KjrrSYJG zmtPJ?L~75gVu^Q@6BW-qnRl$RG#*s&^6TNaNbPx5Eb&foqT-n+^G;Tl#)IlS`^@uG zBDLpLvBW#giHc{Q%=@{reB1awnLPE`XF;4{#c94B)VTI8Ko zH26!qbAIYyVx*t4D56NGW{9$@j8vJ3hPv3pa zN{GV4^o0B+${(hurNJMjuky*|87mVg!@U;8S;Z@t zQt7dJ!--65dQv`ZeiW8J{`jLmV)-KLol30-XLp8NBEFYQfy}PV{7{(Ezy3Hgk4hg^ zikQeH<|oM%%r?8~O#w()nx3GOxYIlf@J3}sI`bnlhW>;qRFHDVp z$g^I_59I)rA|`T)IZ!eMGrKZ#P}9^{Y-i?&a|@x+^osHcj7G z$UNMQ6D1%bm4M?p(d1=M#!YBie)p$}my2hjN&&FSCE_H>G?C`Y%*jntV_C~*>lBp& zW|d3Ksgh|j&6Szcnx=H{<&$-~C;<_v1f0Q%CNFz3Zf4WcIB@6X>!evK1;8qoh_fZr zM4Brz=TxR&|LZ^E#gQ*!=8DpuSfvth9w#cEc`|N()AIXth*mlI5@UfV0S>8zTgZtf zE_*U=QDyn&cWIpsXOrw=k=paBSmG_=M8z{t<}Ix(KmNMVc*{9a z@ywHXD=JH4*A&N>>vW|^?Rix!@m6u7;+ZG&R#%qB-YIzb8M;QK_Pi>VcxyRP@ywHX z>nh7nKmK#Y%a`-(MQYEhVu`nb6BW-qnYXdBRL^UF7vPqx{5nk|N%4O$$mfu)EVTX_ zWhVU=+sL1PiOP|GhwV+n@Bf5itn$fSLhAw7AE>x}($yK{>1rLi)eNSFhqyP`Do3^`cJ^lpI0^&a2VA@Y{* z18DUgCU5!vl2-50%G(tOYHx!$MuH#d_x{!z+>d9{p&l>o)uA@@e5fZXxeGA1L2#0U z0OOg2IaS&#OheC@GgrZ~t zvqif=0*=PsV$)c&#=UqXQ7)G5iqgvU@xNcnZI85hR}aYB?ns;7hn4roZ~htYWylZI zBUb$PFE+Otzdu6h03MUSI)d!Thw!8_{PaWhwuyXo@sySJD1;K~8Tl(zc4XA+Z0Pz! z+REtqXL^^*8&O(WluEF-oXE7MC*$5VEnU*0G~ej*o`nGBnZ)`){wAv7$fS==!w=Qw zYUA|!iG_gVndJXW{wAs6$fPe#!>|ARgMR^d9+JBKr;V3;UV^MRD>Z1@p-tWXO1C?w znnc`3dcQ`~@>5qJ?QOt4MRMk^T8IdyL+r(wCNX>RLH0GvcU{vH<+~sK+@7EP{X}tK zamwpjrV_3{Ck$74GHyU&>H3fUHjzB83>3w2#jDM5o=UhuoG5S&PsR-{Ek9s~+)hqI zRKo%CgP4E+^v&@3VmVQVO02{-T$wwvt4Q+))~H zaMPE`qs8Xun4tX+oTs_%pZt-|f1T=|EjYbJYfGkRBG1s6lbgPDH|Y%*V#^-_ z;nU8n7Oj?y&ySd`F(LaWYRnN^{+t9n(sNtHS~NamVV=eW?Vma^Uu^zSj&||9phc`j z=WJT zn4tZPdQxn3Mm^Oc)}nDnJ*_c8`x*7D+y2QPuJVj}u0?B0rf7Pk&uh%dO<%g3^p*5t zE6=DGTeMm-&Zw6(CS*UOUKSgjQLnU!wP>7CuWC%ten!0}HaeqTZxL(JIHTUsn4tZP zdfRM2bZ$AL-Vw#AWp$OQ^bp_WgaIp0%BTH>riIU__gM&F%`@r)@;6b{8TDb)z-QD) zECi(H8TB#wo22TD`lM;VdC|YY?WrivYB{5(#YZwN<1hIN7m1bF>WtdsKg*jK-~HHFA33A;Y|$z( zol(nZTHIb5b8r)p7r3|B$}?)87Oj?yGiqOr3E9u6{lrFR)c!4EEgEOk0U8supHT;j zjn1fpTEtp3&ZvVmCTKsS4s+W-`NLJ7QHQr^ZOIf(kMszQIl1Xecaz?3A-3|2I;ush zCF6`bT4O@?GwK+z(HV7Yi&%@s8Fie-1npVy`t7L7CNM2!jB&!|(ftxIFq zmrrq1S#V}iTxBLbzSGE`VU;6=J9M1hH1H{I1`7eHd5W7!{wAq9#m#COaH8^4+-y;t zC8xOjdn1_+Z4RfJ#O5h(ZqtG@6;5&UL~P}=B+3!I8R~2 zXr*cuvfSFXgG4q_S4phEW>@B}byIVbw7IbBTC@t>JjZou*@s=PF$XshnY=-4cDt>) zN!om*_q1qj$rMe`u)P{{a?_XYCVeHg*vfO<{uZs4jC0%pjS1P$aRHVl5iy zxWgI~w4dXSh>gy1M_a^NG|q9yG$v?2$DK4=W4Dygai>^tCY|G&ne_OcCcnXOuPL0q z$){=HbKDsg0#frFcb5E3Qgx0y*EHZv<>$EbqByJN9G8v^$#iHJIMpOJ&v6%<7M!YZ zj=Ln1GvyqYhzKU)WzIB-&2!u}vsBxc%@^o(Q5?wUoW%3tFX3)*!f@3+r+oS(h{D3> zxLcwC*TQR_<8E`L;8o|iJB0=3DV*c(s#YQ89G4Cf*>sfmBvxRX=eUP%YHnLL7xqz$ zR)Ogp*H~MOfQkE9V-9X2@(Mo@TX~Lq+M?BxagKYYF(Lao?z!0L9QUF{tVQD-_flhm z_H*1TvC%p1b&FVw#yRed#sux>xc6>rZd*1V=?^VhTQWt{BmGfhPHy_r-K6(ch^;)w zeQwce$vDS-(U_3^9M|nXZ|qWZ`3}Djo#VQ>nQh~m`ZEJvyI5D(-;1~xq@pWaDPS<+&6{^=Wg z|4yC<2CL-2uZps4+*>o4kV7O?G2NA+!`+m+=lgH`eOLJqN3h_)wByzIuUT8)|F)S- z%#oCGqB}Bg6dB5QWQ-QYiL|D6PdSxfV>m%H{|mXXWbtau|L!TacIA(oFJSx-!!uL{#AZ=$8=F*Tu!CO zZU!d^=bxuOlPq3#`Ca+5M2T_ex!If`oOj$DvUtPgH|5V2CB~uK=5c~>-fQ#8;;ok7 zlfOWe7>7Pv$O*!Emn|Yo{*ps~m&#&MVjR92aS0~~=U)`Llq~tn|9c#T8_+ufa=KeYwb1sumNg@6TH$8Db_^x{D4SSF;J_lG|mCYBf;w%Ua1W z)Ej0Un{dgMJ7&FVHBhw72FWngduAh>ylCtL95<;}14Y+tmJCC^ZMLw<>&8CMajR-I zP&Cdq$uQJAXFHp`bnFwfcBobZMeppC3`4zncCm>ru6CCBsl} zq+?|2>=!!r?OMlGi=h@w=gSk4A!u@?yXesIB%8dE?0r_JRI7oakxom7q25S8vk4bH zxslGORs%&Nos|qjy^+qb$s5T&P2{|4HBdCt1<5ef8|fmOypil(kC#-dfufNvONOD| zNLSe8jbz^^c2%_+C>rUSWEkp=be&D!NS*W5&<)jUplGC2-~{3PmH&|}{=(1m&nHo09A5RGIYBso z&3_?_zvS~PzT1D%*!}t5pMCk&n%-OgZ{=iOX=yJkJ=)zlK{$W4_aKYE*z?s#Pf_Bd z!z;ZPCkW@S^WJ1B=bt{J#5i1a^yLKM{F1 z{@JQp4HS*EO)?DiM%rnn@4s#gK;M^NfVoQ)C$>&NWj0;=?dF_OD^I$Y^hqadDW{;l zDz!OK+!^MeeUf3MPeS|IgsYXtY;r)Q8YZgYpk$co)o_SSsD=jfuu3&dG{X_eFw>ji zD4V<)@=$b4r5YxR;kaa&>BVq@OliDRyZ#iW_l}JV3W5(9+WPsRKr9mT#^hky%a99shpOss8qwm zRmxS#Fw?J6uCb{cnXao;!^B0(4aqRmFH&x@iRY$UEn*F}nw)NHiouwj?uZR_l!vFg zEn*!RjdV{_LiSF&FE%eFo1h-Fh;?N2(nC!N*_-K+*u0u-jC$N6){)UpPc$WD@296? z^MbNj>RF3eM@C0I*OZXGrCx~5YsvzKD&6tZx5h-ao@- zOQ+mEx`S4zzK5nMA$y1QU>i?bJzK<@W3FbcUYcSurmfy$^A59dt51tqM@EPB)s&FE z!}^I07gl-Z>fa*PkWbcMu!d7l#so{hKS8O%%-oQEn*!R z9X3o;LiP?DE;jEl8^K1jh;?Li*hozY**k2M*u2AR4jbJf){)U+V>BgX@366A^A59N zY+Q?2M@EN@*OZXG!zP(6&tqSI+qL+-z{#RGv~?gWvuV_r!a2iMo^&tib9~uS4rJ3* zYICf(GYn+YCBsM`$Y!t!S3r&7Xr@XvOjO4#$uQH4V>X-68x7_hm1>wMjk%IxrdP&1 zHhE*@fo#4?HB8jS0?9Db%VHs$yeslRwn(KKCW>OQWSHqSv4lzX4)e*uO|Ou<`%JzjCR_mDIt45?H8LD zlz&-si&#fSM;+9ZkiDf2iOp-u2C~B~VjUSxbwpD__O3cAHZLn1$d0v$b!7C_aZL%? z8|#GFys~T{JJ}-EkGJUnr_urJ0(Hj=pAd5_zFy4~iU~r^x`c$OSfD4euZ1SFkkc3z52lAIBf4zPz z4S2CONS{~;NqCihCVxrt*XNhg;4jWR`*i!S@}`(AKz>Q-ju<504kLd_^4DXJ(%>(~ zJn{5oAv`9$3VV^iB>C&FcWLk!U!HUNun>~)s_RSslH{+qex<=*YD-8d4g{NoFVuAqiIk!^mHf{2E|*X(;EH5iEox zocTwRza;rNe^hDUsb#cCA*`BM#&DvRNDbHo~vVjlWsEhmWQ{j!cMxFE^X!+Mco9{ObiCy3|$vXLy_FE%r55-H}PUp8}s zc-}8t$m0EClfqV!VjlWs8z+e8{j!}b-Y+&E><}sDp_lD{N*TV5*-UY2==yUs#LLQ~!#e@XJ5yjdE&Ci4t;i-nMcj=W9&lH?6} zr!;s$<{9oT3n2;Zc#r%g$-D7>Y4B>yGu#6fLK1rMA^A&^x8kGH;H8*nxW_DnBsAg^ z@|Ps6Ue>oB+BGZsP;y6`#qOOiL?i_+jln0xRg3n2+D_=@}`$vg0MY2X>|jYuJ^ zn&IAZqQqf_dq);jMed6CBE>wk#RpCh&->ydS-dc8hWjK^%tL2<<^=Ju^FtP|4V&S* z{nvT#$BMI4e(me#Po??p4=0G{-O+u^Fz9NHGsB z(w7s&!(I?syhv<@>n~EwLzfKT1o5yVL>8|To8bnD6!Xw1gE>Jw>{B5|h!peCE+aWXJnRvb7M|foixl#z8Ey|z8E&FTF%SJRi4(-b9uZl*Uu=e(B2vu5mC0025YPK%8dkonP<4YEQBO<|oJb+8n&HlKqQqf_yFeCHh3)r<6!Xv) zmpDN@?~BW1@xrhf?utk;51nz96U4*L4_Ul6Y=*loQp`hh+~5T9ygP1^#mmEHxLYE{ zJoLwHP7n{fKxFX>u^H~JNHGsBa*q?l!(I?syhv<@dmvKGLzg_{1o5yVL>8|To8cad z6!Xw1PdGt5>F%RwXiW9`c9#LuG8Safp zA+MU@-g2VkVTOB07Vj6E;ogfB^UyCJI6*w`mycw@1xcRaK8Y0b&@Z1kK|Jgck;VJP zX1H$uP2MB23$xC-A9RnX(tMAI6U6g==|L9n7n|XFiWDCo`lS~qh=)BQvUtDP4A)1b zn1_Dp%L(FPkBBVZFE+#V7b)hUUj}f3c-SK%i}#DoaDzmOdFYqHoFE?dh{)poVl&)O zkzyYDWf&)jhdm;)c)!>TH$tSChkhB!3F2XosI>45H(I2SSIux^I8pL2!;K}2_lwPN z<3x&i=$G-FAfETjB(r?gGQ&+~p$)9ar1@wH`3(g}3a7tlD-C{N`MPWx3n2+dHJ$t= z$&YD9X+UK*X1JLwge3IkEb^BmZ_C-G!OJqwaC2A)Nw^Z5Oa7ANJvpy5cunRRZaxbk z2_3nB{3Xd7a$#xkg3L4AA{Igt+Ho=YOOkivlG5PSm}j`9EQBQV;xh7=ByYv#rNK)v z&u}YP2uWzfmExP z%Oy?_&->*vS#Uv;XSgdO#XR)ORZb8OdqiaMez6(ux=1k({c?j7#Pfc+Nfz%Ho8fMW z6!Xw8w>d#P>=BX0`^9FsyCTIr^vgX?5D$AqWbuBn8Sa5dF%SLnkQ2ni9uZl*Uu=eZ zEKU^UyEPIYB(^5s}6F#b&sdBE>xP%PUS04|_zVg=e@o zB89wahI`A2l7|`Y9a+3zY=(O;Qp`iYeBcD}yk9<><*!?2xGyZUffboFA9ee0^A3;S zXec;RIDLwEY48Kf*JV9e2uV1qp5!k{eoVbe11hsI!}Vq%B%v?+kiR5(TlOstUY2== z>&HS!LR0o9e@XJ598em(Ci4t8kcE(hjvPe(lH?6JxHNb{<{54X3n2;ZIF$S)$-8k_ zY4B>yGu&_%LK1p$1o=ynx8lgs;H8*nxKS*GBsAh^@|PsoCu7V_67E=)!U2 zFG=2n<4c1VVV>b8un>~af)mMKlDq>al?I;SCW{opsu^wyCrTV zF`W~{^S+ot7B38&;bw{y^UxWyI6*w@{E)?K!)CZSBE>v3$6QVj5Boo4@$#@4ZoWt{ z5B;%#6U4(V5LvuJY=&DTQp`h(Ean99uopxYFA|&KmWmYf&?U<_K|JgTk;Uu8X1En1 z#XL01N=^_D`$A;#Qn49swMa1!y|RWA#KZ0oS-e_ohFd36%tO1Z=LGSvM^svPhTAAo z$g5_!O`IrsnBg{)#rwr(xGf^ZJoL*}P7u%gWgA&=L6T>xP%Mnfx4|_yp@qV!x?wCk15B+kS6U4(F5m~%nY=%22Qp`iYoZ%a2Lqp{bDoRMUi42`sETQi0A!s z)hvJ0GQ(YCp$)9ar1|JN`3(g}3U}yuqcr$|` zAoC3Ol!cIlc6>(ulH}d^yfk<<<{9n<3n2-;_>%l3$y@PNY4B3aGu&$yLJ}JB4f#uw z_u<>p;B}a1xOXgsBy{0>@|PrU!Vjgvi!je{A6W=VXu(h9FG=2kpGyPJa9>0UVbu)R z?Z3-=Jys2!ep%u$!*wSMs>1erM2dN6i=Lbyp7%vBvUp+G4A)zvn1{~j!wKSH=Z7p_ z8#crB6Dj7QIr?*gc-a3Tiih1alxtt&#_K3*h{bDoRe34=v`egwp zh=)BQvUtDP47W(6n1_B@%n9OQkBBVZFE+z16)EPSUzTx#c-SK%i}#Doa4STLdFYpw zoFE?dh{)poVl&)okzyYDWeq2Yhdm;)c)!>Tw@##(hkjYl3F2XosI>45w^5{!SIuyn zI8pL2!)+#u_lwPNTSSU^=$EaWAfETj4zv7i%M7=Zg*LDvljfscxLPs7We@XI&JYE{SAoC1&f`yQTc05V`lH}cZsx){t<{9oZ3n2-; z_%r!SlDFcS(%_|-XSlO0gd{ZLIr5hz@5A$@!Rs*3a2HqzN$A3hm(k4P~OZE=ee#PhzmO%^W< zo8j(=6!Xv-cR4{k?EH|$Yr|%^`y$0WG{*x@5D)u5WbyK_8SartF%SLmm=naqE)ZF~ zLTrY6DpJfti#+25@vs*}7B3Q;;a-Ro^Ux(PIYB(^2$99>#AdkHBE>v3${S7)5Box7 z@lvrF?wv?6554l96U4*r5LvuhY=-+NQp`iUeBuQ0ut!u{c!v8TQpl@jxNiS_-XpS0 zkIueFgrDqlBKCo8g9t6!Xw8Lpeb_>=BX0 z`^9Fs;UdL6^veiN5D$AqWbuBn8E%wFF%SJRniIss9uZl*Uu=dOD^kouzl`Gq@vuik z7Vj6E;UU`PCCQIzL1{o`HfFem zEQBQVbrNPTG&u~jv2uWzlrQ|P3-jmBpgV$u9;g+)ylF*SW$X}AYAy<|L zFUUN@tzsc0p&eI~za)7#t|<*(jd_M!%R)#(FRmkhN%B@)UmCm=^9;9vg^+|s+(`bC z_;EvM3Gu%#*LRdA! z?czj}1~JnRvb7M|g*i4^jx8SXkKN?!7$e0oO^S-f9thPx?J%tOE2;so)$Uv85H z7bJOxyCYJ}L%-bR1o5y(L>BKCo8j(@6!Xw84>&=BX0`^9FsMxP%X>}`4|_yp@qV!x?xRRC5B>6q6U4(FQEA~B?u$qvubSby{SSGM z$VQv5e2)k}`5qBjykBgF>mgFiL%;OoM0tE)dB5~A%ip!kaD7>511mCVKI%t)L&1^4 z9Xj?e4Srzxx@-UoAqht{ko+adk7-b8KxH;&xWO!hB=qGF@|PrU%b}&g%QDY!!&nGO zXv*Q_FG=2$BT9qUWS-$hvJjHck)z08lDr{Dmj*A$Jj0D)Ata$4$CAG!c{h$L4PK3T zh8xd9NJ1}8Ab&~nR-9NGycF{cH;ILighrf9{*vT`4(HN(x}M2W);H})tn$6_JYXbMPf7DT9INNx?~+Eh=&~^vUr`?47Wj~n1@E$ z$O+nc)!>Tw@0Lyhkn`13F3Lb>>~>bAou-BO;6Ui_LIHMT&Xomt&kD9`=aH;{9SX+zF9l9{S}ZCy0kVBC>eD*bH}C zq?m_(`I!^M!yXY?ykBgFJ1bJmL%*Ek1o5y(L>BKCo8c~q6!Xw87db&Z>=BX0`^9Fs z%Ob@*^ve}a5D$AqrG;m>Ya)fbYKFVciISH*DWCR;$m0ECGu%y)VjlYC7AJ`3{c_hV zf8R30-D9B*tjMJK=sx)k1xG%z2c^LeEMJ#BWFaKss2-8OB>6EtE)A&6#tip_g^+~4 zd`kY3FT5R%Y{U&vpQybrtm zk9nKMp7~yfd4}uGLP$av_8@;r@+RzA8oUVe4A+Z=kc1ZOP5zSP9oVNd@C?^iq!3ok zaQ!$@;xNPYCkv{=_IpH%d1#A)oFJa}#UQeHVb}~eSfrST&KSZ8;$i29EM6Nn!wnND z=Ak);bAou-{~?Q)hs|&!MT&Xok5QZ;9(IAq;uT^u+!&E!9$I89Cy0l=AhLLo*bFyb zq?m^;nZOC+VMmB8UMDugO%f^Qp;0Dtf_T^$B8!)b&2Upiih1ajX`CP)c8AE~)nYT; z43T0U+GQpuh=)C*(!w*`Y>`4ayc-}7y$bt)! zJi{#%DdwSH7IA`j*dro~_lwPNOGJu!=$ECOARhLJ$m0ECGu(2KVjlWs1t*AyJtDGr zzt{}7N~D;Fep$^4;$e@7EZ#3R!>tu5=AmEKae{c*BO;6Ui_LHwM2dOnmyMht9`=aH z;{9SX+-8wt9{ObqCy0kVBC>eD*bKK#q?m_(+0F^#VUMV^@C>(8q>xw5aJx8B@-V~g zCX4rr&2W1}ih1aly__JP_sapZboyn>5O+|NHn=jCMx;ZWFkIzH`3@Zqlf@4&U!5Hh zCC1_Cj&g!I%1O-jZJ~iRjYxbYhFl(q1Z)Ylh=)ng0EDofueCW@3{UkWGf4RjYxbgT6?Hq1bWypYo2ApQAf@ z4cU0uU9}o0ny80l7>dm&HhCG@jMz)H8Yudxw`3TKeJC>Vpx9Tn7+Q^r{Uk$B42%8Q z1xgH@}6qLGG3hN0M&Vv{$L&5grUtAV1ChD(N_ z*qdULHhqLHRahN0NBVv{$LO_eiLtAV1C zW=e*k*tsGTkCwAli=owUIY%-C#dtZFP2Na0U(Qpl28u?SFByh?cv8MY$E9TPL(Er!%S4HBIKJhaAeWG=S{ns zEMByE##|#xj6=(=l!V>qUui=+_OLAe^`BMzVOh<{5L7C@~Jrx|tJ% z^IqLT7O&MjV{R2C#-UTUae{E(sN2cng_>u~9iqfIwCPSx5YD@F7g@YY^NhJ$lo*E| z-NOmOd5i8Pi zYBf+a&RNMY6#H6i^3t&x^So*`Q1s3P$uJbVTWs>`u^ID{YBf-_&t=Il6nk83@&d9M z^Qvk!P;}5W$uJZ;(MXRZ!%%Oe$85qyPo6QKs8$0-BR!Q2L$T|{ zCT}F0F`uhe14SdfkPJhy>%}H-B%3i`sa69;BfXXkL$T|{CT}F0G2g0I14SdflMF+# z>%}H-B%3ims8$0-BYl(%L$T|{CT}F0F+ZzT14Sc!kqkqz>-9g|u9r;>oxPE4#_Xx45m_tQrM=VllZX3o4=fRWm9XbvtiyvaX3LGIyjKlGbnMFSB%Y=D^;t3qGeV|hN0NYVv`q* z&6sOctAV0x)=Gw<*wJE>*Nx4X>s70PqH#7zhN0NkVw0DS&6t~1tAV0-HcN(~*xh22 zSC7q@TUD!pqJ6eWhN0NwVv`q;&6qn>tAV0}c1nh!*y&=E*O1MayH%@!qKWoMhN0N+ zVw0DV&6xXCtAV1A_DhDL*!3b4&zJ{Qi=owwc}Ow@#f*8FP2Na0V;)hh28u>HDj9}) zBOPNCE_(8ed0e#`C>rU6WEhHFFE)82*^GHgwHhcI>9k}Rid`=@c_Z13c}BGwC>rUk zWEhHFFE)82*^GH!wHhcI>4Ib!id`=@c_Z13c}cYzC>rUqWEhHFFE)82*^GHrwHhcI z>6&C1id`=@c_Z13c|)}tC>rUeWEhHFFE)82*^GHxwHhcI>5gO=id`=<@r-#-wHR8> znD-?^P|TPQ*yN35Gv-6pYM^MON0MQvH_}r#ebq8!J`<%Ku}G!4?Kvl$2T#g(==g#x zeu()h@TDj*4#)S36NK}ldrcP9ZDYoKBT9@z*S_Th;k;?zk;RKP&zSE;iE(Jz51b&J zckD;9c*W)!^OGns4*mL>6NK}2{X!Nm*F0l(`(JGH$sX$5i@*4*U;bOCKmPcOfA|Nw zD>Q3&PKYP{x*a<9AdA;(o-uoh5+5BpwHGG{=Z)H%EMBO2#_S_Xj6<9D00< zIGa!|wu7Zw4HW${QZfwnh8e{suNa##N2^u?Maztl3`4P(#U?Krn=!|!Rs%)XjF${U zv7^N%uN#{&C#qHhMdM783`4Q6#U?Kun=z-TRs%)vOqC2nvAe}4uO6E*r>j;2Mf=Q< z3`4QU#U?Kxn=xmpRs%%`&6W&9vD3vSuOXW;=c-l%MH9`F3`4Qs#U?K!n=u!tRs%&J zEtCvHvFk-9o-r4z7DKBUbBSaKiWze$o4k>1#$2Xa4HS*ETrv#xMq0rpT=e7_bERrE zP&Cpi$uJbVUTpG4vKe!YYBf+a(pt$d6uVw*@RcP&Cp8$uJbVUTpG4vKe!e zYBf+a(q_pp6uVw*@6uVwz;u-UxYB98$F%L1c9MlQydsnQr^s(CI8wMn z$J3?34=!K-{mep0!f~A;e@XIVI$Ijhv5jLo$3jR#y`Cq3N%CsFP#U~g^Gtb>g^+|! zy+rF=grdKy_tu| zTP%bmROW5+mn5&tJEg(PGS829SqMq!$$R84N#2q7OM^FL9vvUB5Ry=i56NGWyci#q z2Cv0DH9lq`B%u+XkiR5(8$K-!JTN{JDTGzy;&V=vI1Gy~$bzb{ohXrF9@^p+Cy3{L z@tQ1N7&a!p5h>=OGv0E7c-V>}i`Rxti0?&;d1#IgoFE?dqR8UqVZ-4kkzyYD<1;6S zhs`Lmc!k(p*p2*cccbj2(FrZmofG_%eGXj@y3vcoM#7#V#m9#(>BR~D$#}i#Mz0f_ z2K$H<^Ux@LIl(^}uOHp$rDB6%f01GydSw77_$T8Hq#M0jYz7=8Qp`iU4CVy?WV|8e zjXeGh6)EIZ!{0DY@K44YPB(hL*yJ}tq?m_(8OaI$$#|paMqH5Op>MQEF%SJRh7xP%OpWkzyYDWi}`HC*#eb8@*p_teY!R z%tOD-;{^X?y!mva_lr$*3q*=}=$D0@;Gc}QsJxMfxy2%dylRwN!U_J#cuVOWrkbLLK|3-N%PSf^3xAST3g=c2bQnP*0B(ha8&EbPd^xG zLwOr2voXVMWFaJ>FE^2&elXJJ@-{EaJi~2aAta$Gx00WJFw(a2Hm}J%!)<3FB%vdB zke_}q($4ZWFUUN@?P4J$p&fUVpMEgXp7J)Y#yrFAWg#S?7x$5$elXJh@-{EUJi{Ge zAta#@50amLFw&v&Hm}1x!yRTJB%uqBke_}q($VrZFTy;-9b+LRp#_hVpMEgXiSjm{ z;ZBMa!m1hW6esv6=OKdy3ue=^=Ry3s4dX1MDj#XPjg4NmY+ z#=A*3dXd-+cT1$0hc3Cz3I54=cj!j16Pw}giWKwEDEBzQKN;^n-RPxaGu#7_VjgEA2THDPy7$X%!3H@#zt zEZ#3R!}Sy?K0fqIFHR5-Z&@OX_lwPNeME|R=$F2nARgYcL>BKCo8kJ46!Xw812{oE zylIIn-Y+)84H7BlpQfc8CZm38hubSb8aiZiUPs*o1xFd`Ai_LH&M2dOn zmyw(xp6@}AF-zx`8Ez~KZD2(vy%xri-%xPmBO6~D{J`>c*#s6s5{_yj`Ad=?)1=aX z%52PVlUWE!=*ubOFG;?mKD9J>S>_pT8Vex_O*x(XCCT^FXOsr7$vnf&WFaJ>BWIDn zB>67-?9$)`nP<2;EQBPq<6QEWB>#7~d8NUtG0$-GSqMq!#RcRqN#2SJOM{nUp5Yd; z5R%Y{i^*S-ybqU@2Cu_B!!2bYB%uqJk-sE)6D}_eUW9puTfss|LJO`We@XHVTvZx) zhFdLC2&-neHJm7M$&>OOI<6%Ps>1erM2dN6i}jo!p7+HDvUp+G47X9Fn1{~T#0lbg zYiuTq*M`k-TSSU^XpXI%Af9)}HnMnm*bKK_q?m{P*ue?nd4udEi&u!vaJxi`d1#T{ zoFJa}$R4tIk=P8kSEQJSF4@Nk;(43wCyUpK&2R@qig{?1gPb6qcgi8Mc&XS7cUYvD zhh90t3F3LP93_iai_LJyM2dN6m*boup7+a%(!w*`Ns&TcHN&0aM9E8@luz#nB8&Hn z&2T@96!Xw8XE;GT@0YV=!39a4;m(N^^UyEnIYB(UJBTdaFE+zn6e;GRUoLTiczBNx zS-f9thPxtC%tOCi}LP$bicKhG*u8ti> z=aS@Y*}XJ)S>_q82MZwyP1%$DCCPiTS84E?%rjhX7D5s_vJd%7k~d`E(%=P|XSjYW zge0_MfAW_k@5TY8!K*RPa06KgN$ABvXyr z?EjF(%fn{4nIgqJ^v5ht5D&XRWbq2I8E%e9F%K;=mlMRpUJzNlNNk3iFH+1ymn`4} z@vtLA7OxYV;TDM$^Ux@ZIYB(^3z5Z3#b&srBE>xP$}&z654%HT@oKRdZiPrO5ACv& z6U4(FQEA~BZna1uubSc3aH8a4hFeP(?-!fl)`=AJ&@bybK|Jr54P?OuNuJ?0iWKwE zFPk_)JnRvX#rwr(xGf^ZJoL*}P7n`!L}c-Pu^Dc=NHGunvV#-E!yXY?ykBgF+a*%W zL%;0i1o5y(L>BKCo8k6~6!Xw8`#3>7>=BX0`^9Fs10uyd^vgj`5D$AqWbuBn8Sb!1 zF%SK6gcHQW9uZl*Uu=duCQ{5pzZ~ZT@vui!T6l&#DN@L*X1G(FD0!ISPLsv^#b&sl zMT&XomouCop7+anv;1|-40nNrHn1X-=A(<`HxwKx+@a&8(%=V{ugfm85R!0ISIA$I z{Fttm22^HahP%c>NJ3v;Cx1!uw!Bdqye#t!caw#Xgr>Yj{*vT9dAl@tP39Ty4hta( z9eJ1hCCMA|UTN@x%ro457D5u*@d5cul6T|7(%{vYXShc!ge3IhWAc|IZ^b92!AmjE za8FqXNod4pcarBzXtE zEe$-wy%Q;fRWsasPLw#za39Ems<8bYkzyX&;u9x`=Y8>+EM6Ek!+jAc=AkpX{qK3- z$EvTBZ~WjV`*(ouWbxXt8Lo#&F%QkrlM{4&*#9Ammxs-8y+w+7=#M^}ARcys$l?`Z zGh9EBVjfzgKPQNXy&$r9k=P73P^6fLE*ZoL;$cUKEM6xz!wnHB=AluBa)Nl+7b1(7 zip_AtMT&Xol@XjE9(ISw;?-g^+$fP^9@=FzCy0kVqSC@M+*px9UNysw<3!2B3^$%E z-Y+)8O%N&OpTH%FwHhklvM3F2Xoh%DYOHp9&qDdwSH7I1=i z*dro~_lwPNi$scf=$FNuARhLJ$m0ECGu%>22^HahTF+PNJ3xkB7aHpw%lDB zye#t!w}*w0gr?j}{*vT9xvw;MP39SHKMNrV9eIHKCCMA|U}^Az%ro2}7D5u*@i6&I zl6T{g(%{vYXSky*ge3IhG4hurZ^h%K!AmjEa3@#@Nod5A1oG5Xa;VzK{Rbl%* zBE>wk#T8Bv&->ykS-dc8hPx(G%tL2f=LGSv^FtP|4V&R^iWKwE9Je?@Jna9F#mmEH zxH}@nJoLw1P7n{fKxFX>u^H~ZNHGsB@_-Y>!(I?syhv<@dn8iKLzg_}1o5yVL>8|T zo8g{{6!Xw1&p1Im>9`=aH;{9SX z+;EX%9{ObjCy0kVBC>eD*bFyHq?m_(8O;geVUMV^@C-Lrq>xw5aN{^p@-V}VCyV!s z&2SS$ih1aliJTyw_sbNs{B6q&HN;Xv+EIFG=2$3rd66WS-#` zvJjHck&DP*lDr`omj*A$Ji{$vAta$4my*9Ec{eUA4PK3ThFi`;NJ1~JAb&~nR$N&c zycF{cw~B?3ghpIV{*vT} z!<--<_JYXbMPf7DQITREy5txqh=&~^vUr`?40l4Ln1@C=$qC|NUx+MTDmKHN7AfYT zSAOOM@vu8Y7OxhY;m(Q_^UyBmI6*w@5tSC6;Vy_2@~Ro`A}2~7X1Gga@qV!x?y^WR z5B+k56U6g=xk?sXkmMQenn*DZ{c@cX#KRsDS-f9thPx?J%tOE2;so)qM?@Cy7n|Yk zh!peCFLyaXJnRvX#rwr(xcef-JoL*0P7n`!L}c-Pu^H}>NHGun@|Y9E!yXY?ykBgF zdn!`QL%%%Z1o5y(L>BKCo8exF6!Xw8FF8Rx>=BX0`^9Fs*CNF{^vfGg5D$AqrG;m> zcOr$nYKD8yiIRsI?gLr8Uu=f^C{oNrzkK2Z@w{KU{hxVT=T|K=Tz3}Qz=}+ok9v^b zP;jJhhmJi@ znVcY=_r)x-cwyKKH(R8bht8P83F2Yrhb&$jHp9&mDdwR$=5vC0*#9Ammxs-83q^`~ z=#NF5ARcys$l?`ZGu#r9Vjfy#DJO`By&$r9k=P8kT%?$XE?L0|;$cUKEM6xz!>tl2 z=AltmbAou-7b1(7ip_9qMT&Xom35pT9(ISw;?-g^+y;?i9@=FiCy0kVqSC@M+-8wN zUNysQ;Y7*947Zgm-Y+)8Z4)WxpTcSxj|hkiNC3F2Xoh%DYO zHp3kiDdwSHj&Xu`*dro~_lwPNCq#;Q=$Dh6ARhLJ$m0ECGu&yBVjlYCXHF0gdqiaM zez6(utVl5r{c?^I#KRs@Y2g{}f=D5+n&B>TqU2$QyF?c67n|WOixl(FFIPB0Jnxt5 zX8F688SVxPZD2(v%||!MZzwoYxI@QVrNIv@UzgoxAtd3b?vTGE`7zxs4XDh<40n%( zkc7UxPyUkRZTX-ycv45h>=OQO0tDc-R*riJr zf(w#7!_5{c=AmEaaDsT)BO;6Ui_LKJM2dOnm-(C^9`=aH;{9SX+(MCJ9{ObwCy0kV zBC>eD*bKKsq?m_(S;`6GVULI`-Y+)8Ef*=~p)kO94XwPa8&!rUy}To4wME|W@Cms$U;a$UmhZVN%FQlTpGMA^9*-{g^+}%JWBqOAqgFMg8U`P8}ejn@Pf=U+$k19658=J`Ad>_gq zCsNEqXWZum@v!ql7OxGP;U0<<^UxfRI6*w@|B%JY!)CZABE>xP$5T!a54%8Q@d~jS z?zu=Y4=wV76U4(_5LvuPY=(O!Qp`h_yygV)up>kkuM?Z$-ij3S&?xUXK|JgWk;O~J zX1EU`#XR)NM@|qAyF+C0YOxvavq&)y?ec{a#KRuZzt4L_cD2AWTz8Q|UNyt@;6%y8 z4A+w^-Y+)8^%5!OpTH%z3MhkhB(3F2Xoh%DYOHp7h+DdwSH zMsb38*dro~_lwPNV?>I1=$EmaARhLJ$m0ECGu(KQVjlWs0w;)vJtDGrzt{{nNu-#E zewoY(;$e@dwD1f!Riuzt&2ZB=QSvauO(%=@i_LH|M2dOnmzkU(p7+Zfvvm4p%MdqL zls33Bl}4m_oG@JFN%;;P=aa<`FJGN45GBUp=oWHPBj1mV0jcaeq1zTK+D#A@){BN<|1^xMlOl#A^X zsa69;zwDO`L%m@Ru*oaN2Ec==)j-iQha|&LY#p)5i^itFBdXOv(KSaU!%*xZvB~Sk zM#1B%)j-iWCnUpAY$&nGOULHHQ>xWK(L1Ll!%*xkvB|5)hQc$d)j-icXC=c>Y%{UR z3&+?7YE--_8G>S1yu~JOB%2m*t5yR=Bi)ea%RS`8G9^jb0u#a0!Yype2{e5+aw6pi#wG7QCj6`Q<~Y@qz0S`8G9 z^ieVl#ikXType3G{H$6H6pi#nG7QDe)nDbEE1!>ewCt{046TOC9+Dv_#><{;@qJBln`v3bTEElP|- zzmDMq;k;ePlEuq4&zR#xiE(Jw@th!>_v!?)c&+9cbD}6Q4xKuQ6NK|dolF)l)I4KO z5hccBj5(i8C>PtoQmqDxepx6PhI+#+Vv|>l&6tZ-tAV0rmPm%7*vn#* z7mdxB%T%j@qHC5*hN0NeVw2a6&6q1ytAV0%R!N4T*wo&6w*|tAV0@Hb{n{*yCc87m&@En^dcTqJuU|hN0N$Vw2a9&6rzNtAV14wn>Je z*zaPKmyykwJ5;NIqK|e;hN0N?A`{P;yH$&!)r`4EG6cnpxtC4eNH$~cQ>_MyM%phK zhI%6%U=uES@{D;5ya?id`=@c_Z13c|^4uC>rUgWEhHFFE)82*^GHywHhcI z>4an$id`=@c_Z13c}le!C>rUsWEhHFFE)82*^GHcwHhcI>8xZJid`=@c_Z13d0w>| zC>rU4WEhHFFE)82*^GHfwHhcI>9S-Pid`=@c_Z13c~!LrUSWEhHFFEa6rc|)}r zTFsa@B|}imn77#EjbtCKeK&P(nK2)T(vDc9(%klt6V8Jt529d=>aulo*HOd%_9A`O!Tk3+lEpV?Gll#-VGUbAoW*v@giwMVn{Lm!iZtwCpQR z5Y9XHHCeo3^NjgMlo*G8eai{LdAq(NirjJk} zi&tr$F?)&?2ByLxc9^1mV0t`;mob%>Jsy#A?PIAQ@s} z#vI5dl#A_Psa69;zYLZPL%m^!u*oaNX3U|g)j-iQ!z9B{>}9dZi^gWm5vtWd(KRC_ z!%*yKvB~SkX3Wv5)j-iWV}#>fOUGu+ajMlo(L3WM!%*yQvB|5)X3UAI)j-ic zlO)4X>~XQl3&>{7DXP^#(Lqxs!%*yWvB_)5X3XiT)j-iiGbF=M?02!r%gAQTS*q1Q z(MPi-!%*yck%?!_xvIs`YQ~%=8G>TQoX;k2B%3i8s8$0-BQ2B+L%op}u?ZJFdB$9< zS`8G9v_vut#jY2dype3iT&7wL6pgf8G7QD87n{71Y{p!vS`8G9v`R7z#jY2dype3i zT%%eI6pgg@|0nFt{;jH(Jx};gc=U6#vWmUIt|}|55H?5hfKVGeC(nK1KgfK@m-~p) z_ex_!Bb_vgV1x9af+DT-A}F9VDj==WC~d`z5iv(}W9;+EJojGW_np5n#)=gq=2&yD zWf*PBr(Rk_6)D|gZnm+CDOaQ|hS8>c>ZL_gkM-{d(1sHRx#y@wAV1&lq%8z67_TUnBSO4Dcf;nJ);R_M|JhAl2BR2d(0nAq-@7E z^(RdzJF2MXl!OW@-eaCOk+L0E(+iqVc2r9*DhZWRyvO|6M9OwtM}N_TvZE^ctCCO= z#e2+4CQ`QJ3VK-+%8u&i6(!O4n7`Rr*|ELHylNQb$@iGow1|sKI>EBBiYeEZ8-~%Q zRAFvv5tW#9k9o_+DyCdzem9IZ<+Cg;qC%7IF>l*g#guE!9m8l-KGD)5DmUpK^PY`W zOu6FxX&7zF=UQ4sMJL^3-nX%eDc79`hS8>cx}`-_deS}SBO9xja`ky^7;VaDTv|j0 zDBWX@`L}e+mA2B3_?W8=j`*Md3pTh{45Lk{3cadDREE+$=2#o6%#kUoQ!gdb_n4DytZdreV@@%QGUa>Bsaix8DcxgEv$2XPSET8N z(WX?9W@r&NJ$R2f)5a>MT#;Tgj5g&{FD;^ql6b7Ewh?_n1p;tYXR)X{lkfDW7_25mlsgkNK{RRZO`e zEjNrd{Ictyoc8 z5OCNk<>w|tVAu$nMY=uK0h+~N zHH(&kS^T2(Jd32jS^TO5(JbWUE@^cz3#q=W)xj$#)mOB-U-LRYSDe^YRu39BpnVIa z8_#PdM2kcPiSjXHuu9i8!OKJ%T&EjC^75eWA)H(3w)3WsmRvIo#ZeW_*}jHAoLHVkEoZSc(Jk&cj$uYL%D(PO1=o$#_~^+XAx_fS(z`Eq0a zlPHOuql5R5RKKFt!Fx!m$FjO9CN$|z+*rox2u<3TKOW_HrRPbf%i^RbC_yyob_}qF z6SX>+v{X-KbyFXB8hErjMMr2FzW(tvrYb#8BV87!F--}gX|!X2X-wDZU>Z_AL#u<= zPO4{Wb)o+8#9n7L7AamMd>hR&AzGxM{_(|TYl4@FE{*FnM@XZ0fsR@qH!cvkAqnd$Z0vSTU;2% zdm0SC81F=MFc>P_OHe-O#qN&I?vBw=S_XE&{~_A*rLlm91NR(xkBzPZ%d;%J0uIR$ zxIim10DY$(6TXdC#)9IQ%vE4atHLYfF-Zc)w3>nE;$`|EjJG3Fi)1eW<5?5oJRGIR z(R{>mc-1;_g*x@C_His|$Kzf#eH9qdC*c)%NZJ?2v_1o{Sv9X(9uvN58)89mOy(*u zrj6kh@|YxnW7@(%^OFI3Ncg_r8phiZnO99;0>-l~!g)B#5=Zkn%VG5fnY_l~d=U%U z@wit_Uj;_ABfJ6+N&DiMb~+%xYN<#3GFJ37D838~>Z|YyZcs?zpmt|qsGeex-q!2ka$7qY zMB9^UdU-OG$v?+Bn*Z{&T?&_2Be}&}Nfi>Hhk54t5V8 zksR>G?2Zl;Jct38yGoyZ8U@beUMu)-Bf9>UobV}}KXo8>Vg{W4Qu@{j73g%o6?Bap znT)WwKT!W3`w#&(52dq+D&LBgPRW$ z`u6GjAAOtuboA}}GTf=_Xa`3-F*>P@b`2Vq(f$~mtb#5190sSf!GZj)PRDgqRUn=r zAuzvbQr*t3iR0X+x8bgr2D~to%13%kV}^~zUKs?tnTBZ{Nrk4fk_ZauizEN_(!i9V z*ipU^qt;$*J1Z#?OF=#-qb{Emo#YiRx26&60Ii|uD8{{ z$5upu(LAYcZJIcmEKK3Sa26CxG#5Hc4sBJugJpm^0%|c z?PFyWE{s6&FosnDn@5q=IF9$Sc<2yFkaifjxx61l3!{)U3}Uq>^B7t!4q;6z?auj_ z#chiA>b+Jd>9x!{`iEY)LR91>cmV&9Ha?__o{ZVg>t5g83Fp zWoy!*@zyMBUI#YDcic7?D;Q@IjJI1V85K***`V1#?M*{TH6h18B84 zgdJImDZ?Yc_t{P#EDS)f;QyuLvOO!&eODGXsX3%8>(UFj6m@)hGPMnN0HSyj^kO3Y19q_v-R5`S{Q|-VGt)g zna9v-aR{ecDHlo@L>8xA0sg61@9%}ONp7X17q?gMAB2k5JYS9ep;zzILe;KG*0ulC ztM?h9z>SGXtg+mTUm-5!N`GGNv{|@ypTj) zBb%gE>3YXRXngJGTFt4D#9(lDHInRF4G!v_kPKx%JOusIM2dcdf!|*m5q^yZ{q9Ri z7rh7x0iS8%ck zl?@XIhEp^m4MBs3Q-x$O8>Uxqnh6yRi37vw8WDz#1`S_Jl7asmIjVcq=ojHZp@A>S z2SHyChFQ@C(nyRcj%T)#|6?SLC9U}!7o>r7gaaWO1~J!yY5sn*CPMD2L`w{Omue(=wi@(XrX=zy$#+ep;)fXcE!T+h zqX)THC<%QYl9qU-2~`aF@2Qyr)5oJh!QnKzp z!v{>GNB&3i@ym{(_eRdYGY){&&@dyEY};RkGVWtqF3(?MwCvK;kdc^4;)Bu zv~fIGh7)IsZ?f^u=ExcjohiOK$A`V}ayM6r^w&9CT#%;4PsZ`IG79tBYNEWb zW(IPV#|O{8QURJ7fAql_~R0)GmK9m8%NDfkcsMthV#J2eWl z+M5L<=xvrN$vzbzBb$r~0iXR+ooyhFE(c_|@Y0|=T^wTlhO0D@?2fVPYo@lP8u`II&Yk6i-ZE_Ipc&6O+UbnHUByB)wqx z>DXx#qG{Q;FJmyPGn&YgLJiL8Y?d?$mi(|*{AeNtJEp+yCrxBK)S%tDEEzZiK261Z z#F}y5L<)9Hf!zg7WINQL-Nh^!G^9JZ;Rn+{>j0VA!a)pp{i5{Qs!^cRuSyVSM!wu7 ztq!vyt1oBuh`|F#byEez5B0COSYhEZ3Dfz_Qh7$C!%1DuvQY!oarZS7DVQ<^me)0r z4N-%3H?ri#QEZ2`>ZXYl?3e<(Tbjsrs6o5mvt(2k+u?E6A0|?;V+!nUYa-jB2JP-- z$)I7aA6BfpHdHWdIdHsZm~5F;==ofZ})i2$qnQk{JujwX+Cc)-BF zCzteu;A0&r_z(m}Pn148H43zP^?y$-@k@i`jr3UYujJAEZ74nMhiwf3;4votw29WaKbQ$SnA?@G% z?N{?aN<8B!Li%))!pno-d8$?u7H6uEK9i*V3({#q`fQRuSCCE@(&tdxJUbH(V1|%B zkJ9Ernov4ZNIURPDEl_g)r8vDq&B@?&0{v9_I0Vn7Ys&Q(9V)te8rj@vG}^Pr50bZ z=B6yx&XHPt&6*puSoa*zUV8;0H_tqR{M^Q4H{SuE7^ zb%6ZTO)p*v8E{*m^wNu-XIrQQ!M>_4_l{QkeO0L!X|?);BYe9l^mkHV6Q7?)z{;r9TscK_z4v7NG<(d$N&6Uw^g_e|-yuIW~ zqc1FatA8K$Lx;dqTCnvG#`6|9r@@3>ZDW2JH3(Dsz%V!`p~6Y6$s%X~T2t%=*VCkyYmO&kAjqwe#(Z&kCEeN)o43k}x3Qad>QIkz{%$UA4XN!#$Oj{64w;Cp! zCKZ})%cADxW>ajfw%b_2v<1QRGs9%lq(alrv#5Ew$uxZv(ib*XFl|9F-C>w)np9}I zGmG%0W>>sr`_csqwiyNAuPl{~Nr%q6vaETz*%;rkU)xy0w*|p=w_&ntQlaUdENWhE z{>uSu()Zd}!L$Xzbf00eX;Pu-{w!)NEUlPTW# zAF`o>XUl=-VZ&t4q(aXlS%j}NnPM&-b+LkLCc*ZYrLr&S(D-#Vk&)WLj~KG z1J@IV$)-t#p5J9r^IFsAJ6QWq+EBr><-qflVX|jZq38Em)V$Q>iIx8c8!C9V9C)5K zO!iDF^gNSA%}Y(5*bJVvp@L`2f#;8g$(~7tob92T(z-+X$yksHN#}nq(al{S=7APY>Mxh8#Y!jZ9y=-X_#!9RA_oDi}00ZSA5s} z?t%r|jDqhUmdeJYL+9IB*1X(oj9Glg#tObI2)1_(lU zEeNK6877-16`J19qUPmhQ+(e%u(5(^3xerG!(`K>LeocC)V$nen);>3HdZigK`?z{ zm~5IZ9@gmmIKduhRL2ug`V@XsClW$6Z@qFHdOFzIq+O)nCzKU==n|-;mb^>xYI0h zv4U$R!FI8wvM=e-cuAHuFE#n%J9ViI6>M7$T$dRpn&6N`E-;=`Tb!U5g`@HX?Mf(;8`_+z<_DPBMA4p-70&I`(q%}TTv~OXs zU+Xw&pOk3-p%h{!us^=5J_^Fc0c0FT@UbW55J-z-_(V#Z#NZ)dzOVDq;s{z82Jorl zq<>PP{dy^E@{f;)a97;mqec4`2K$YUllDo8_M4=zNes5fcim+Ov3=qdQy&nv^azxrL;*38UeoZfAYcN09qFO&pA%oCndUH zMB$6M@8bg%{ABTGANBSY2K!$ehxST|_PT$V_DPBM*Q5}0g8lKmcRdIf2as_X!3|H!A&?fwa8pW~#NZ*| zJK&a&7Dv#+Fo543C;gKW?f;O%rYP|-7w)^aeY9xb!eD>Lane31(f+O!Hi^OZ`0l&s zqec4`2Kzr9C+(9G?f;U(CNcN`3OC;SK3cSIVX%MTIBB1hX#Y?OF)7#|ciu-qxHy1} z!w4RGQVxN%IEE)u+9U=K0V}|mzUgETZ%b3OID!_20leZk>EB)m&IzTkNen(1!~7fT zqec4`2K#Z2llDo8vmY;oO=7S;=HCP#E!wv**iUqvv`SOJS20bku{p&nzD-y08ShU27rQlk5t zQrIK~xntk=mJb%)TNd2kcARuiN_3wmg_sazkGtOdAX@a#Gz?&YC*=r8i$ho_rA<=M z2=JZ%jt>?G(6Zpa$Z^s>Dbal?3P=9OhymTBM+^{8$1T$Va&4XrZvG=5rpzc9zpF4b zZ7+_7D@ib{FF3+~3CmSBR56t}*uG~_GHz99{Q-+Q8tV>ey~c)W)&d9XwFYHtR-yIA zzFq%))R56bhJkUnZ0tAb0NK)W)0P3Z%}U=#DbQ()6!7Um^E)hCb)e{k4CuEhy>y~K zQQa;DbV`G7o6mHh=!6V7eXjJl3S=Gp zN(YKg$bi!>rI$|h<7Qt=0qr(e?|17!(FqxF+N1Q+iGI;+uM|*Mh5On*9Vj{>15W#u zUOLgwm>rM;x_`j?$8U6?=!6V79aMVhM892jNDAne%dlHGtOG?S{?W1{N-v%02g{C1 z0sUMVwnfKupyqx$lfl5j(U_2s?^mHoKBJkW&lqx$kVONI>VD;0g=c_$g{kim{#y~lL4ecO;> zoif-7M;0>JPX_zJF@+5Fm%;wMdXJUCr)BVIIEs+LXJqghcw9*apOwL9d-a|mgU`v} zb8y5UgU`$0^YB2D48mWTwX+`9-2rPfS%vi?!75ErVYN&huufA|SS?fstkg6WR!h|Z zYc*Yk)nawPYRyn#wOk#rUNco#Em#Mv*lQ}RmaGHT>~$4Zi`D_FHcN&()v9&Es?Anm zwQ8NPYI9Urty(9n+FThH_g-(Pf2a4yv*KQ_eeH(uSJ1yHk^I_19B_D^CxyG*Ezf)% z2;Pf=fo5=l(kCNUpwmJr;6A3g<#|U3icVZ)7Ad`Sq7t)M3b?{FPD^y4=)~n^snSa) zDlW^UK;H7as{=(RZd{fty>z0sWrY;TTb`9VP;}y!WtGxPCu&&UlLC3m^S%xgow!+9 zt@P4~T9pr^K;H7K(Sf29w<&9tUOG{e@}U&STb_?}pyz0MWRn!=Tb|7(R5WXEdA4Xm+VL&VRwdz5 zfww%{OsMR~)ndCQlpocL&y<7;M*1a!&rPW8$2H>%O(;LA8atFk-SX@-p|T%WjxRN# z{HS((r6lT>XO{_;{kVR7tqJ8v6=b)Ps9T;rCRFz0DzaA-%8%;EJ|$7NJo`V1RsInYW5_QXS+=R-0 zTwT7^gz}^MazaY7iEw-`4ogk z{%0AaK0XDZjsHaksf$lRXySjBLF(aC5L)<4GDsbK3PJ;aSq7&A@-11yiVZBJOO4n3aEmL#Lb6thiLN&KMH&j?HRddU8Q-#%HHMcysR9G!n zbIbF)3abTcZh8JtVYOtLjw`^cnoxFB0mdqcyfGPPB4s;nFve>_*-?WrK}qD@$wU(=+i`y} zNfXMB`isd*B5zTqm`K@<+l#51PxmN!hKY{#v|o0?E|)LOiyB>LXv zZ5t~)ws$Y{45K{x{$;)vadE*Lm<2XgG3ENQ&@kGRD$F}tL?tHO#VoS1iYZr_#fH(Q zRA-iGk-C*xYGV~st~JXHqfM#WysJg(erCCiRZO|!tT2o=rJA!+i_}fcDjTbqa@~2) zFxr$V&-+@W?rc`uSjCj9&j*Ilrc{5{Xpy?TS!-hzQ?5ZD8b+H^75Yev)IH9}HdZm^ zO7w|gv?cwvt4HeH*#cL;^=iL2LGVj^WbF6T!zq3o!bA5#+9Mjkhj zvK<%lZ#ALpsEnUb64^$6XCh@gF5xFNq3o!DpHdRpMt*N1Wjik3KWIYPQRzOdB(jY> zVr=FwMey*H*Bn8%5~?aVYDe#o?BX^+Q{E+tYXU5=MTeZQ>s6=wMey*cWkU;$~EY& zVYDe#p?g}S+Q>g`tYXTQ=r6-)Q>sPxwMey*4{WSr%Jt}>VYDe#q(@4m+sMZ@RyJ+h z$R~zTrrbu3>4&FS)B<%ha!<%;yGVYDe#q_JAWO%Jw_<7}*A$`xt6VYDe# zq)ACM@}EPxx<})G%M;1TK{Rl-G_+|`JemBJ7On+P&NwOW08PI)Er`~Kz>7ZJlWqvK z^fR24SHBs;%ph7H0>1>WdD0DmUWnJ7RJNhBf@pmRyhY6Rq#FWl6my(Zwx)A~XnhF0 zVZ7lqFq}<84p6AE%2szt5Ume^H=3oMbVH!+W|@=9_V?W&S|0*$JIg)khCrLo z3MbVq@yaM(A4S_5uL@W<4sMa(^I|TN*e1Up#d{bC*U8lZ>jy%W@&hlXQkh!kHBr2W zfpE248?b&LR4+gDV%1K66vcZO2-nPy1J)0Os^%wNtXk}KQM`wNaOM0oVEsU-cCPng z)pl=);ynz6>*vOR^#h>_y2*=GE5133_b?EyqFVyi4}|LIRxeiV`L-zD!$7!}ZVy;L z5UQr1d9iBQKab))41_D{7Xj-BLN#@V7ppdYXB6*YAY50!3|K!9s;pl*v2N{mMe+JT z+7|!ofOP}mR)4n_Q)Nx<{+=k_!$7#Q?hRN!5UQ;EyqKF%yam`F#d{bCSJndo>jy%W z^-vOz=pH?yTiy&DR{tJ2X9Ak$BT}8bC=Mii36Ti%PS*6=$JD=R**gEM{=H^(m1C>jw9_ zj+A`bruK%?3ny-5Z%P5b@v()yr6WZve((RT^wNsn{eMUSz5P>@dRs?|R$Kw@D800z z8gN$%R2zCvM~YTl2mVxgX+@RbFDX!s=6xM0T5&aap!Cv;>cK-PP_5)69VuFIO?a&I z(u%6W6Dd&5;+Xz;6o-392fn?VUlNnwNWdZZ`AMkluPD8=qT2AP6sUG^td10C#r0vF z(n~9<5aXplHGC6vq-e!eVxrPZE2r%kY0ybW=bfjp-)nc~NODn1t^ZO4T zI$-3BqX)p38V?;Xs_UhJ{}O-twjhX-C;jwVNJHu`^kg5eg=@i|qIv1)zW*HA{CYV3 z=VkcTmO#`YMI9ho9Eduls1rm>0#QFH>Ib5wfvCR}^#{?iK=iZ}Jq@CF1JN^5^bClW z2cl=C=vff05~2~^gWu-*Mt)A|<{`tA%jLK=#J3d-%YH zO3uuI?;67hS5%?rS|J+Ldcx09!UaCGv63l+zG3~Ya=KK=HN|SCph4YTBS)qT zODn#qDB_X8+x0p6{-d03?s_n+&816;;b{(sxy4|edYG6OTZ9-8^ zIMoGVoZCtlGvmx0j`MTE;Hmnq;Uh#n{Xz$L-O^V^rJ-a7{C6llnUVsXc4omycES$! zOC2aU5d%(NDSdWo6zH@o3;x+XqN}?*O$)yX?Q0h+_+=6-cUvmEk`9gcWZ8(n4QP$= z3xW2!Siv}xV7$*#*_d=_ykE-ljPd({4!Bs+m`O1H#!}K4b!dE0%0{*`#;*%HyP3bZ;w0%$u%{7t+=zEl4m`LqPs zoRn&ENpUnemBTPes%6dQ@x2ZdY={B<4@#en8U;F?&Vpg=gk}4T4iub-0jIM{pPd>7 zI{lahBVT$U%?ZEo>n9yxCsmJOZ3qIZa|*~-jRLLCD*^p-HQnu`Vx_KkLCe#xA=7VH z2l9(ro_@iae!n`9|E%TdSFGtbtONNkT8=-9%)etD$bZf95hI8EdskXl?5r-?5Us4* zK$@gu4wm+^Ve;Z86)x`;BT_$z+m2CQ_BTt&pTrG`tC<)%s(Tc@1@J9>&4f5%Aw5vHg@(>qx-bU6PyeLviL@0w7-k}+_+r-^Kc8uYtQlHnsp!K(uQ%{UxEG$rjp z7>}&o6@Y#i(KHOL$H6?Za?X-IPvHtY4&&9q@D*S%Pa@h5CgDEA z{sxakrS~r;_QWV$Ug6BcJSGLK8VIRz9Fvv!e>68lBS&$siIrqZK~Wx!x(Woo8b>2p6-aPZ z(?A-@YANX$%`YzOtXOP62*Q=*$QOX@SmRll9;C(mSnH)!O8Tlh0L(yT@?k)xdeT?j z40!URfJ{ZDuevYrL-!flG*~|Z(jjRO0Z+yYeQtq&1#-6ap1boFw(S9q33=hO2xr1W4`PGOQ@UIXdnkA z@y{WH(iVyLl80=lI4|O0UWW}M=hdiiUPp|mG_QQwqn0SlD-*{BF?hhh_Ja+q@89|$ z&CM-tW?^SN}S<$LiobV(9UzBVtaZrh?e{X4FfpkNihP};t;+U(ti#ZGHS%| zq3N~7kCT1~qNO1S8isJ%lVS+0#UY%L((VBxh7G6mN}qL{4Z_7SWE{ruqbKDUNQ-0m zNlIZE1`ei^(DYf;xgcB|L&jkY=RGOMKw2Eb1u5<3R7j7eT(q&GJAq*Rvtgufqe9bP zqzFdS+TuaxuRdBdZeg&#;$w!$$5lZ~7>WgFpXo3wMTL5VssB zMnFom|J?}-6<1yU4^PEaS5db;h3zFbm+@5YND9kXH=VNKyd+Brh5S^ z7mC%mRQFpkJiB2Un+Glyk3f)M|IkvcH|x;&k(6U`A*H!9fwwE( z0lgW7i(|+*jNvU$$}z~s=4~m3&CN76^MY`33>k+p%=e@m18H#`7D%aSY!=#B(LFad z?-)kUp&K1$;-jZNq148tJacbpgj zDbaql6Ba72y8H*8imR@o)_5vvY|K>FN{Ty;^lD+b`Y?)@UM$ntd=#*9q1XCKO6x7vdb19VH%J+`C)C(%bg`l_lVH5bQqnj#Hd~}jH#S>sh-^(` z1M|p7E87esP20w1yAg%ys4n}NC8AVR#21pFzJMB=9X3>)SMDcv8b;2mQQ?dDr4g0p zl`s31B?|M(#Mgqz%?UL&yM3^fDw%~`+2c4dKiSyq6+&(|a$~bEh?e{X4FlNkNihP} z;vydqQf@bLWAjZAEe%1?Foc7i6hmMw4&jiL=FWs0o5Ml4IEIYF7>;;SjzKmyN2Qdy zjZ`u5l=oN=E{-ANFoxrvlw%+*uEV!dY8smpHdb`cjm>w4k-lwXb5e>@$C2iZCpM>i zv}oMIFzfFfC(V-*=lp{Z=H7%Go6|m8vd=KspK+Y9myOL?As_DbtP3Z5tw6)7Zc~a$|GHFw(SbZ0;ISn2zeQ z_bd^mq9Xp11oZ{f*xa|F;=FP{@xU;0UX2Q0#D_*ynpeK;BTE$Km5C>U$ju2gHe;UU z(*LrP6!GtB3HvM&Dv%qm;1hTPN=!Aueo5u!oe8*F9)m79Y zPeqN5naW~Gai@`9Ei6|{qIl`WGL6mBfRziycKAvyC-EqF#s>aUaAX&Keu+oSD}0c~ zz|St?wxL;A$(4>Hf1yP8RZbYZPy&J#g3G_>DgQz_>U~f77s^qqJ%x{>@xy5G0<6*0 zi$moTFKd0UvZ}mRB`j{$o!SS2a_gc&fOnnOf(m;;Lq9y`TmS z7&QQ%U&pr$_81#{kXO|uYldN2H#$%(D=BeVH#uQi*7h;VHW$?OH+u}%wS9&%#P%o+}8mYzb`enJK*AX zrsnnvZs5?r4;u21^wxw2XknrD`Dkf{GYs5*$BFeNB`)s)CoHV4y8Jhuiq}?A2R#+9 ztfCHiDqdGb9T5~175G{YT2}lR@TiZLmNmn$tj8QDmX(yatjC?Ou&nCx-+C%uRz;og zRJ^Q;`p#4FvMTD7px~*^_OY=}+)2LoQCe1Yz=5qo3&XPh;5f0YWP{6k+6fEGn#Ts0 zKjW!*SrzqDOW`*g=>G1U55@^3Ss2QB$F(zUl{nK2P8iO#g;LSG=&5L?hWgo4Q34t2 z7f(eAWT;D;q85dYkuLjSWmR)~bH#CbRU0L)>Tgb1Ue$d0tDY*ZYNoDvs<^6|y6&ms zs%Gk@py2(g`@35{$g67lyUx)WhGhNSfnr%niOc$j6Q*Ug{hhh~ZI9u)+WyX9cRYp* zYx_Hc-Srr*Z2Q+S)B_ppp2x!e&R~CfEbQ+L_Ls-P{?1_cJr?$N274$l(UtIN!=oU~ znWOu=PSf8#_M}K1w!++b;-!W6Bx9-6jd?B|%#P~L=JC5ybFTzk{JzxOs{t3kGc`9( zaJfT)Kc>e1ZoH3{Ryf1()|}utvA(3l<(=q+h1FG;pX8}{Z51`yQ}N0wYKo`gbyd_f zLFEnwmKFQE={{Oo)(pe4&TyPqR#M`!&UC`UvZ~9!=BapD74^EO;$>CTEKkMDs;D`F z%H0qwEB1GDeUz5f^mnl7%l_^S$BAVnB`)imPFPr0b@{hE6)&rz=C@Qoe}1>X2jc{i zEF{oE$F(zUl{nLPoG_ee3#FpB$Wzfw4Yk-)Q34riiKn6jGSo6nQHw(T-Mc{_X=GO-x=%^kA?l6!Pa>! z?C%WrsmH?p&S2|37WQ`r+bA&6m2iKzDF}1s=>D#s>F+jsQlt)BVeV}4(!zU^u~h1| z23-8E)ZDg!i{F=;+a7T7J5zI?3odsk+~0lSqoozjFzh2c94FS7l(@V*ov^UF>hfQD zDqdSfedVcmWfir{Q}MbgYPX|&YldN2_c~52D=BeV_c>uhFH^!OE)U_U0$Y=~Zo%xT@!zu)M1I^5;EOT-8in@KkYCGj-8Z#Z}GJFM@*i ztM2c9^+8@$)8F;i{oN%8ie)7mT-M7@n3mP{cjo$6JcjFP`#XdE<}qAY+us@Ns>g6; zZGUI5YaR>xJA+;KSlHhg?1sm}{?1@GJr?$N2K!xLqATJ4?vEhMnWOu={-(dX?Mab3 zY=yaV$4d+ENybvCyBl!vyHa!a0xo`EYVOZ~i{F`=yDzxhp>Tiqz(-3foMG5U9y(5} zFDY?(A30%Rb=Bn`dn#UAMLqFUyt0ZK^E@BK!joF*1MGNR74@p1a)-kG-B=$jEo+8h zS;sj}EGsE-S;sqJVOiDXCwMAeRz*$pRJ^Q;n&hc?Srs)!P`Ml8{%)#|(z2TV4mN$+ z-%WFzSXNTvvQBrx!m_H%&+t^dtcrS_sDJ7w&*0JQ=D~?sK{QGsLjyV6lQdhY#p%xR z(qO(4OSNxq!1)<_?u~%+spPpg1I{Ot=iW9PH7wNa%?qNnCC=^6d{3GsZnU_>3%s0E14@gYO4m&At;np_u=h4-!|*Gn>QPQ2Z22*R}7YQM$h&N!_0Mo-GcCM~Y@CNC{5wX)b8aD|0d z+_ucgM|)`7-5x{>8766%@@JmRQ*O05<mdue5fv&Ei(D=%^8_6A&ei8Hq^;L1y!xdW2R z`(~e~@N@2Of+#Ps-FD3*H3vN^*H~`5hrBecvD4ZwKYHQQY(v#0asXP#r>K&`NRcnyO)A!A;TmM+wNsg<|(&YobnYfji=mV zDY)|jTV>qcQ36hakls) z;L1y!x!VC(UgFH%3ApkSXYQWl+_w8?5alJd+pc-i;V+NMHJ01%eJ@RG?6zIw@gM+k zk=?dyz=r`CZ@UJ36oB!zYrw|=7;n1xdi%Y!FODjv9E#3*Z@)BomQNWd#ICF~wuDryVTPiuX?Jf(Vyu^0f zH6K8~>ruJJa@$?*rLe~I`*h6@u)wbi1(NpH>EI`Znx7X6B=mbreVd;cYJOfQkkAh< z!A~=zAr&n*1~(3-1L@ zZjfXy_PmX448pYBb{m62CbzLoo|KDCT3qYRURqjeWw9mT3Ja~c?TH&P5dK(dMDxW< z?Uyn)pOt@)uH?zXuL~p=XDS744Y>^PQHG)~G|{FQu&g zIyU@jqpxhJXq&%|ZI@xBY5R3-yQPS}X^b|sJvKz1GP!8=;7icb8*Hy(q-Xn8Y5R=G zCzQSHeoMGivcxxn=rTXrbI`>~tJ#w9A|A4om|N1}i+DuHMhzTFzhjMG_;b{T$X0G$ zI1lE)^_XFVDXP%(xDgc=R9yC3OT-H*h!d7@#m^4?J4?8tXNgmi7{EUPj&FePO{lnZ z34@jUK@)P}K!fXcT1!gH)?V_A(H9o2)t@!`!jiT6AC11SV6Fa~&_fE27@58~q62?V z^}Gwxn#nKV!dIY0Vbv~JN~~Mb;mTdKvclTQOaJVcc>N^vi(}$7l+5Lp=@)DvSAr-l zjM+jI4NLQzC)>rzT3nv1Qpy_v?Ay&AcFo0#_DlkG-BQvzZy`6NOm87KZK!CQw~$+g zk*4hy@`n`ZE#$Thk*C>0n$>H!kUNHvp6wQL*NDROQ>pGUdx zVx`q=Nq7+-SW3(->EJ58dOs2}uE2es!Y$;n4Uw(cLi&wn4qTrYMwp@sJ;(fCcq#_< zfLQ$HNB52pmwm+&@q!BCRZB$gWi|A%mWV2%BF0N16-u~2!7XHh2^E*Ft*;X`Ar}rb zxNeiQq>zWB+DlG0`of~M`YA?VSh7|>)#wWg*6ODVeOp9f#cℑexbgW((;zxfIgV!0q7ztk48!o^Cf*^=-guC$bxThhT*;OjGm zj4Lp0A@AD|*_th+zuZDr8%CJsE#w0uDl8}u2PU(|67hlxVyz{j_p%!Lhn9#cq9Q() zL@JcLg?wT{#ieWO>pD%yg#!(~R-bA~Y1!IKt~dI^qP6-BMqgO6R=?5c3k%ljHw%4R zM0pF@;)1khW((=Bwvers66=;MaOJjHSz+zkQ9;gacTBu~lKIRr@fu2IM`A|8Io6Qw zk?F<^pZDLX1GF4+;}8rC_)Dcv3&9Fpg|CEQC^@B{vDSf-Q)0mBYo!-Xpg^bHLNJ(| z@SbLm4wRe{15SIDUO0gQo%RVq`{m-;#qBqdl2`s_@dKI=ZteGqeQer8V%YV%aXxe!$yos$%ywc$8D%! z*mB_btzoidQlaNb7WFgfe@X{Jzm@^F@0Fgtk^-H65CWC{r*)v@)TaL#r58?|{%3_i zrT>pQP;zS1|0ksvPMrSdgg~eNc@rsl<@CRx3E|eJ|3x9u>Ho8dlO&z=>Hmigl$_f1zpeDbiPQg%5UBLOs{R06|5FHb`u}Aj zC9jcnn=kmr~e~O2)j1@9}9_2|0gC=vdif|=D*;v&B$)Z2>4fF z*QWm~S<z@6QeMB z4_5af_5v_~NdcS&q3z&$y?Rd$#HmSC&(LWyeUvpNLa|p=Ptir_)Ck3vQT^3egiec4 z?7-FEjYa762=&j>Md*wO^-t49=*$T9&(lTdYZ2<7sEg2925mkmrVPWsi((8>7t|Xd--wfeOs!8~*5UwPfgx?O~O1epSUI30Seg@S6@wby{OTO8pg?UEkTZb>AsrJeLz8p4&d zlkl<-uB4rW-wokP+DUkM2v^ch!Ye|!l6Dea8N!vclkln#uB4rW-?#9Pf2XWV-yyp? zir15lt^hgrK>*v7Yt)!=YXWgK;j+)#2(6`CMn815^8#4;O5RLsBd=%RDYn!5QDZ$hQAi*{Va89tS#su3Ehzkjp z$<(iHjnFv3EV?a1;{>zl_6Us=%%Yz~Xq;dc{X9bB1heQD5gI3$MR!DKoM0CH(xA<* zN*RXz+E-z`nquuGAjft^xJk04$1M9glGoBqdhHJ3N}@@4PY731O~QLaxRPuV-WS4^ zbd&J@5UwPggb##pCFLaiO$b+#PQr%_+-$0pb*W!F915yw*IonC?ns22v`czSyQ7i3 zmUhzXSO{0rPQu4SxRQ1f{x*awX(!|{DXyu z{5xe`>eo(3@p{tH6(Hx%1h7rHMvWPFHV{`6F8ll#p|y0&=uZ(^OSX)ji_luCW%PW6 z))FnF7b3KlW*NO0p|vE-=+6;aOR(~1XCA)1iKQzIl;0T z6YRG@Tu87?rhe^egvJSG(Q6SJCzwUAM`)a27QGRnae`U&W`xEGX3<*_8Yh@Ve~-{O z!7O^)pv|sI8HWAZoiJWavGx*>V|OFmBw5m9mfefwwKS7ne}-@+(Ios=2v<@~!uLbC zl57%w5WFC%wjna3$>|JU)agX(!8LWDc7hm<7NipYQklo*CMo*ZW(<& zLTkyE(OD5%OSO#7j?h}7Wpqx2*3vAab0f5tWEp)ULTf3O(YFa5FbY1Ug8wp~ht7+_ zVS?EUK!VK=U`jBh#spgsh@%8kWa`%zMre>=0s2ma1_>6Riy|~gumD{gp+SNL=#mHx z5-dQMMre>=0lF+gg9HoEV=E)vBw5m9maU59wKS7n?}czB z(IotS2v<@~!mC5Ll57(GAcQOFCgC+9TuC?yuMOc!%1QXc5UwPhgg-WLv#F}jLq7=x z)wFA`0cp1`!cE#GJ*M5Kk-V06(rbMPSJF@TL&1q@9E}hj1nB zB)lbrD`_X;tsz`VI|*;MFny2(e;tF*?0y!->q(bC3i~{OZOS!j%(yQCaW&zx&yEPK zrCUaKMrbYBGWunN)>18_Uqxsw(K5O#LThQ3(XS)4mSh>-9ig=p%jmw0!Z$!+za~Eq z-5-TZ38pRpMeRTU=LE}YOt5bPaUsDnnfkSZ5gI3$MGr-2oM09`9HDW7S@cMR#tCN8 zqY)Y>m_?68Xq;dcJszQPf?4#0L7QDwejfT=7_X*SdkM&~lM!x`Ea@@JPDS!snn|zk zL%5P?68<5CE2$>o(;-|*HVK~z;Yzwm_-qJQ5>CQDhHxe2B>YndSCUS`=MCI!s_OI5 z3!$KzcI`DF?Jh>RNxP)SwEH=d*V0aU{Sv~Jw3G0!AzVp23114~O4>>IatK$_PQq70 zxRQ1f{w;(nX(!>UAzVp2317D`eUQcd+Knh)PrCe3*v$a8Dc7hm<8B4wYQklo-y^h^ zZW;X}LTkyE(c2MPOSO#NiO^c2W%O=@*3vAa_ad~GWEuT4LTf3O(FYlYuR6niO@1Ew zFbbCvOkDtq+M@u@36|BEV2=ZFA;B`4`n4w!8Yh@V$Nbmyxe3fXhvEdw@#OkSgvJSG z(N`lhPB4p(jnFv3EIKYi;{>zl_y~;?%%T$w+U%hsV!p`e;}?KL3n=0> z5U!-1gy)BFCG8}(qmfy7Sl(9+XJweKoa~c0E;Ok!OsJ*m_!o%A^?kNB*7g4SWF}d?hL?UDoOAw z1-9ECd~XqcG0LtWTuG*uhh+NNqbiw_7L#eWmzI-Bdh7|nVlqi^ZvYmPNrL+Vu$W8| z+#i6&WRl>404yex1iuNuVlqkaU;q}ANrHzpNE;pZOGkXPmP&b>JnBH5NR1Nn=$I2$ z(kNg5xW~##l(BC;R!*Ueo$y#Wfim`;$I9uGv6CJvCr`#sd90i|8T;O2<;2O@nS{aj zhQZf_!GF`k6Zk!0XI-pKn!)%V@skSr0#Ji~v~Wrsp~Jj6pJn(Rp7KM^3ocgo&ldpy zix$rQq(lF!|MhPph72D)Z1|uq_%giazx#?mW4IPXX$^(i9_Q~uMFZp!qa#$R4qoibb854hTtnS0BxaVljSiMf5dazC`VvC}9eb(s$Fzv+w z>*ft=xLmK^O9F9q=B>@rh^)=MC6{@UyD_Y0??&++CeK~Z@__Y|r{P+5`ZcpU;+1|@ z{hC=FwaQda?X2)$;YaUD#X4N0QmEEa=S@mybb;2wCtok>z`pzm-p|rEY ze}#w6y*io|RlieC?Pm2feEYjo1+#j(nbi+o>1XwHGpo~9nQmb1tngpq`*yrKnibud zo^@(Bt7qVJ)~SM7J=4tUC$IFgdZwAxIjc;!sCHKPuf2Mo_v&a?bnkh=sokueg)?8L z3TE|eGpnDy($DJIW>&vgWx5Hqv%-Jv)%#bkj%G!7mzSK{&FZ;cy)QdeFstX9SzYl; zKda}OS^Z{}={D2O3jYe0r;S^W4(dI|{J-W634w5a)P20-^?rWPf4u5-(fqIj85?MW`C$(-&S~Q& zq=UMU@qs>^AN3&7agON}vztM;*yj zukYjL2R+F&uZ!k~UCH!78_W;;lGl=UIQ%Led>T4@l>8|4br)-9@>Jjdke^a&63*Xd zS*j1tN9f=xy?W0!vQ*Zd!rzdZ<6<>qB*A#DrHnCEyf=(2)tmG)xo^5y%@|2Ae#=tE zm`c&xMwSY}Q}_c@^IWWEj3gM(x0Era8nM90(mV7i{1{=Oi`9&g1mkxsWsK>~yU57W zTjweK(W%8QRx?HtjF(u-7}L9Isgb2-`zbtRTjpXlWBxSeT}v5bYQ>iuS?Y(M!XGwW z;bJvo{zzn{rHnCk%d3nmwX9F!$=Z7^Rx{?$CEmA`F{XxgwUMQ+GW~Gy2QF4K<_`zf zSjrev&$-sfQilhR(&2&Hhdx^KPB0|cM~*Y@po9zc>iw}5ask5%_KA;H?YV}nbDXuO zD)y-rQW@*Oj}X@TXw{x8*#^g1d#Ys{t&oaY`qAS}K3cWsdbZhd)}AWb7AvHZ)`2x` ztB+RgxvFh*oVBOAw%rP;uytT%`^-nH_FUUOcbv7S>bBDexe>@)ESyeS4K)C*273Ch ztftc#LSMYgYWf)s^p;;+O@E_-{%p6^JZ&`4H(|iphM%lh;TRejZ?X$hP6KERCcjDV6_i9m0j+R<}A^v?1DEP@e!x8 zOWpx%ewmww-e!(9>$L-T9dAVKtb(5Ye>lVPknQ7WB9py!-te@_mBU zpk45n5a?+&*zVVu?qM~Uz7)~43uDuHITrM|8oU`_3Hd(3YS5D8f+ zJ9azd`vl8DH)eN2pr_?vySp*n!*VcvFQVzrFm+>-sq4`vl8DH?dDbpr_?vyD3Lna_nQ@8AzT+~RcFUYkL$vga|(P<>%#opkf(k%J#P3$ zLDKWOa2NPye1&jbsA+vGMtWQqwtTz5_p~m|&kK3#T+@??^9z!m*Mmj^3E^`j?J*iolirJw5CHl61$jIu{0x6}35h+L zL46P-e9on20cTxn3i5bR_`&aj7Gd zO1Ka_)a`^YLG$60gwh93r#&d!wX#(#Fg+D!TKzj&%LQ>K2k6y0>=heVfr zusTz|ZN2O`J5##9zT$+nneyd-^HgP~OkK4U-A3c7<_cD&JfF;W#^0x(UARgte*iNq=9`haDu6V|56mmlY;%2b&eZz=U*$^;*+ zPL)5GnCLh=Rr>H`k`vaZ%9o$)smfHDnqsN+aRGb>9De9LH3(NH+kVOI{{YZGoQW&~Vi$}Kn3aojWEhaj&7;rg7pLwVhkZqC#=&GORfoY`V_z}4o=+#JVI z_mn>1m>Y!abLL*<4Ntl`Qw#N`msaP@7HYGxv_;sG~|BOe_k*^*M9@ve=Vu&eT>d@zUy?*t|qGjs1-uA4p{$on%KA+7c*7?s(_@v!NG zKuP!4;)r}fzxPU^RNm3PJi`p*KTbH;P|&z+KvY7g?h5zYrPV52LfH-kJap(NE=+W@jvLb zuAt#F{edp<$C`FH(t3ZaYDc`*m9^%u`)HsG{IRkfi?rS!Yuj}=3;hQ_8fNpm1ugreZfua-NMx0Z6=|uN6=cRyeF`A?33p!AA;^zIL(n}{kkd*>z z?C~#Qf6;-W6SvI2D!p`~9{!RPP&M9vicZ|9UQv4K#80400X4Ds7hzX*py+d>Hbm9Z3Ka^fN(P`Li zDWKCSJV?Hy14So3|GBI5(uoeE?nwb14n5yw`JXyabmHTezm#4&(OJ-aDM%+6{0FKJ zOsHtq9(+91gtP+<@bE1bO2VZAYsF&|D*JJ@c%ljANA+UNK)f4C)hc~O2h0!8VO}wz zvLDxsS2dyhsA`N=5-J<%Z%)UVP}z?w$9PRBKdK!Ql!S^$dSrj136=f0eoWGY@}mke zSxKmbq`xYiVnSsD7Ct4%0?RuXeBAujw##KPe2ia3G0!?d-hFzo7cbeL{2QW$P8=ISur2c$6E1H7Tb)U2m4H0p2a zFm==^4BhlwI?QcviZ?Cq+eV-l4tmFVMxd6iX&UDnfm*z#t6N|MYWbSBYoQUS1#J4F z#Yr%{`KwRWzbw&#AkhQ^RdcD*r!->)z`c4elL9VEO}%|r2Z~Nyk(MjHbfS8+LJDO6 zvQh_%PF#ytDZO-}O7xx-$o}Ph9Vj|+6MDFP*6Fd?E$1e_5vkMJMiGK2>_@ME%QpDUkik1|29masRSW>7^6( zFPo%5_Ai@tpy*tnY}0|F6ZbFMm0mhg|MHm>=>Fw%6Dpdu{mU1c zkapa^>`)Re71+P*G@-H|SBoz-q5P;`e5E8*FjD`r%Y@2)TrrGEWk0SWhcu!5sE!oWigNAJ<{pf>RiF;BR%9HsBP7{r7|p)ApOfu={?e!~8%q zZpP5RoYY}{v>3zCzns!xe#jTY(7$}I!~D1{hM|A?L5I12Nn>mJm(xa|7Y0f>{0=0Zi|MHU&s0D2LmkUYo!pQFK(JzdYPY7N#ks#G11&zqhnn+=fSlO{{dd3V+LS8HL@iRy&muHl=DaU5iv3G{eR! zrd)Am8b+H^&3R3WR4??pja5v!?#wcbHl@llTZ;H+4byij%rT*&Wx`-zo2vUJQFJWal+2mgz}?wU7#eKt$0?v(1gl< zoU89>LitgqE>aRo)buRhViPL+ahfjCgz}>#U8*FMqn%iHmYGo5k2CaLO(;Lg&*e%& zJ7XuF7q2j(vLA1aD>b3~Xlq=hB(ybl;^$27nNZn}_r~`%q5NoXT&*OuH>PLwJ}{xO zA8(FpG@<-xb6l$=v^jR-XHFlQP}z@n$B#6j{OCO3VwVYDe# zpIuTkl0WU>+dOzmM#t%{m*Q~OyIaTUrkCPy)4NB<>7JM3aL>C}$LW@r;&98mPsizw zm*Q~8yI;rY%z)x>XmCKs>Ck}UaBA?4j?<|D#o^fCppKjV7`~lS$NAiVF3=nt95xEG zgs_H3j6yGBb98XjDD*NmX9vfOLN8=I-7t^u zbX-lN8)k7*$JHddVGgHsTuq@HX7Ig^s|j?&_bD_J*g`bSVEFrAnIit{v*yO@_qtMIP63xQk5PamQ?8% z8eZq$Rn$4*_5{DvqE*(3wx`=tr4t77<&KIvC)|^I^}efB)`|9{ds5}z#eb@(bHYxz zSMR^H$~sXmd|#?uJ$Rs^&Ixok(%JNu6ofCGyy?Q^}szGI~-sCMIY+?l18w^#4+MrZA~>7Af-rc^-foT%g8 zkE+EaqjP>#FD5IUE*MQEo}%O4k7~wLqjP>#HKr+@E*ni#J7y}K zE*{M;@tTf%KdK+E8=do`3NlOSbO~wpoY^|={iuq}F*@f*b>xkt8#?gs-J{{Z_Ksn+C*|rQEuz~pJVjV+LlsZHD_de1?MeB%REy}Y44+$FWrD7yj`V5bR>k&vc6|S6;D1BdfzbGlXk+@T13Y}c%JZq z4OKk(TxgA9v?uL}Yqf}uhVbO_LmR4i^4ZWwhS8q1JASN1bUcKo37^EpLt#Hf)(3@!uxuIrL-~cm>Z3Z%MsS2O)gk-=8Cl0QpTBT(iS75qLiK^ z+3JEdXRb@zEM=UjGHo|9DoyE$*w0+B=FHXUb4wX#s!v}S85OAXZ0rsftT}Uy+G#1{ zOjYVjBcn2vo|65_1#8Y+sdib)I8&|qTFd^9oAy)bm5F8mfAsm~T-oan~pr_nl z#d_+Hr#c(2{?(}*_Ef)ydagP%BnJT##5D5 zW$LV_Dyz!WkCx&pkDr_URApJ2`q@*J zWo7CYOYs(l&F8N^T3uGb6`E-P(gmz}V-tbF+^o~kS>Q@?qtvaC#9^;Bh9nYv~v z+Mm;>*w=lux~#lI-*B8=R@$R)I$>>D`SQ0sRasW1e)m*mS(*C7Qb9lmPAPr3 ze8)$t%gVP)cO7S!m2R2tIbm&C`SO2ysVc)`W-xuw`_M03*( zH+()c-fCd#W`y{i027>!PD91jMmHy-PDiJhQU@oQlbnuDAEgdXASWB0a|O>SR^#V@ z-zzZH>HO82IZSgpH;0bVFo)?*=jPBc8s;#==-k!dS~IQ2&jG)i;5DanbHMKbaeil zGY(Fm-?kb*2mFqNc~0l%fZvZW-|5^O`Zse};B;;d{hK)~G&(xd&U1iM?RTuk&jG(@ zVUg3hIpB9JEOt6Kho_r4EO9zFho_r4EHyg%z%9=KJ~>}zHGU5Gy)^GSotp!GE6sAJ zb8~p6nZpXFb8~p6nZrt>qmT0P9N^RaRaWEYfZuTQp3}KG;P>0S?{sbsu$#a)Rym!U z!?VpC*0#DA)1d~Pho+xy_Q819l`I@;eB`)xKWUY4A^46dCxqqkhZ-%EzTo*2Per?~ zq1JgS+I0=}si&e{*HG&%MJK*^sIkEZtE}!D(l;F zI|Ht=!Y%iuyyCik_MR@ayGdMSYtfz*dK)JYs|+}2R!N4m`>=v@zUxVv&F%HtF19}hXSs)#>^cKxY`;s zcf@gc*u-DQdo&2w*Oai30iQu`_6DRZ&>1 zJ~82mfap~#3MPVQS7V*fPXrII#yO#%2%cVzcS1jre$7NC7-2p(;fcWc)kG@_CV~f8 zlbp~`1W&LgJE5Nl9$`&!LO&5a!MI(b|EGi}NA#iLpe$0hTGwvUJc2H!u{21gEi z;pLI^q)YRZx+k_PSGk&;pW;yK|XmWy1hXvrj)F1D1kMI9P1X=Pn6 z4d@<`=828uQWJ?yTM8_fX`(eu8nk;?NJexGOm_Hy<#H1#*%1YHD>NbO8V%a56q3J@ z8{X}$(t(m$V!-P?r59G9K&SUx!ArwOj_U3jHSonWIee;ebr6j`6%EE8c(QfRS{%Zf zRyuOjfbLPr9{bg`CK6k>6xe>KiPkb{(C#B48BU3Vk5+!H10}P>fY&EVFRVa;PU~91 zfPwtX8NS;;Re{)u5b#+q)vZkvN0$w4c*JmizvH8m8&x27Ap~4DNpXr-8=t(#@?$*t0UVM?fxe`>X9mt z>4^PO4pB!GRlBMX>V59Lb^Gi-4?E6|vmwNmp32@B)s<^5Fm_% z@J2#d3E}TtBXefXnK^S6L^mkb9Al1=W@YBeFTeHm2_`khfs_^6gK=n*Zzb%-UKYmS zb1;h)g_%jhhfj@zBk5nGK(Bz98agBB2wIt4&y6D{SMT3Z|Xo*h6p z82$`t8$sWqRpICQ{=(rw0|!$0j0(%6!Do|5?vypbBCF>#170HrX3r}Kww7rFxmp%p zNFrr9-jKei8A{IY$zM_s?6T4xR3&#giInAdZ}y62C^^49{j-8#!*ReeoI@J$6c(R!zv_d7aU z{WGRp(!82S%c@MKdv;XDQ`$gMBHC_XU}Im~@YWGc!^8?_Ocpb>C6lDbrYu$tI0%o6 zFdB>fc!S|>d=l}Z&x(~5Raav*g!6ziK~th4FwmO>2)&k*{zr!lXu(m9ZEuRJUT28V z32=hG6`{!QV#qxep&pu6dYVP@Y4WnqE|zlFMq4@}RR!DRZsp2Tc$`GbqsL(j>8UKqkW@|+v$$gn{f}%%3^s4~sZSQF7 z9KlcExS>{ML0eW(Nq2S13c`$o^49@IyP09vfY!uVSbdX6ZEZ;=@iiGQs0SqE*Lxr> zV0+{&xj|jGGy{X=HcGTta&d@k3Srs_{;RtO&~Y~FfGxuu(%GW$K?n#aZ4H3l?j|RM zk$#)HZtHjk$!wSCpi;#lvLl3_ZyVmyG|bl<`pV8MW{U|X3GPZ+L6mV2-W_1nh^=iy znnn!s9TlBrj}^A%HJ=>pHMqfqK*PsA2_8z@wXUWyAMDR!MF-3z`2#6SY6A!1Zv(7a z)cH{kv%|q8Vv7bANgmRSAm}iV`z}DL4RK89m?RFX>t0H(uzF}A=P9IgM8bnk6^F_( zgj-s=`>OxPRoroPJ*bFQ9Dzhm3v7^}CYA-NE#pL%{*PL{+2?wo2;&Dk%U1aQzUwTj6-B9hr3!? z1SOfKuA3svAd%@3%_4|H$gGd#J$U7YFdXcv`Fr3a+*G&;-kjOlVW)Z|8vLJ+q`F6)h`mVg}CHy$x zo3+c~NnxSD1_6p9{~{4o<3N^Xu|&#oAVV&ZNI4E<$mJ3_tnI~tyf;nT*R(hNUJ`By zVfs{sp1qQAV+aqf!XG5zK_UE175*>@4-Vnys_;ii_~{UCs=^;9;b%g)r3!zNgyWuk zTNVD4!>!H!gI}yGK9iTtj^pvvs-Fuiw`vtdtFGYSkT6`}nRBJOZYnT?B)*Vn)<7I0 zUvl`x@NqBt|5x(5so@DEu}WZBp^8G_8xD3=J9{EbAE~+!jl*FS!Fae{T{pxdgVZ-j zw9D_~(BBxsVHCl5xJg~NMdB#3S)zkT7)7>(Fx~Wie*gpGRvoZqm_voxrtm=s2oz^~ z05tQK2L{C*>bkAt86>k)qJv5mhsdrFZW}p5_U+v|V9PLvboMBG5CQ^9djp`k+wT*h zkMC30Z5_`bnf($SRH`^c4umlE%I;RRZ2mTl*;9uA=Hw&zJS0nw{> z+q+w;vs-;bd)hnwr^e|1Kk9%slyb<j zgixsKNVu603N;-Gw-Q33o+IIQLMYU7B>a{T)X@;DB7aW^&s1kgXjy}^Bo^ULLU^_! z&`PFAxEl#=Jczh&a^2GrzR{9YoDk>rfOKM1N7W!d9+45 z*2MITr`1D!%mk3?qh-kRw1Y8hn4b&1u=NZP4cBv~2J;X!CPgHiR3r1vxDn$PL=Ul;)Rg?(@?;$lXXz zv?49oRMU$yX4;Z|_+63#eM|B&%%rQZz|x%Onv&0B7I@2Yo@+}!m|5U0&v~vf`GjVH z_g>CJYYwE(Kg0BARN(tL56wA{&ukX-KFE2Po(IbL+0gqi=V6u}D5q(I_fgJ!uA1E& zXp^L_e4nH|o(a+MKFy;%f|yxBrf&CH#!I`M--P%)1G;YKH(Ha*<@76Z7CN0j0$gBy zk+OQa{RcMgx52)&;(VW(#q|lOz+V~Mw8#}2qvk3DOpj^)0o9pVUBdKh$R{FGUl(#% z#wr%fePff_!`>Bk-PWcke?HtTGuGu%Z(BTwiB1eM8D5|9Qmg;$Om4`4b=`*3Z_HUW z-G*74au!A^e}FvcY|Pr6voKEibL0iq4zMtn_ly)DM(kAAeO(TUeNr%}8h1%FYLMe- z;oUNv)f+?IOua{8)7sM5eF{t44!Xc_yU2bfFeWwG( zx&enO=di-d+VMMzM--q`Kb-EUMi**`(Z@78tE1y-TvXCvs)Z9eu4?HyivJknL%Vp# z3mdMdl1P3(qA{6874?&5#F_#IJ?XTD*mWgRo=Na#Z3+C@1fSk_spWGCKE2~o{DlPH z+Wunv_yFVF#T*eoLBMAKmvTh>l;AJbM*ig-@m%QK_@LlQj%bJ<7Bp8$e$FA!L>+vd z@JkM9XpBm&Rhp|grt#@0g%2Kn%`s0m#8MBb^4y4+F6w9vZme==$!?}G-`D(SPu0+e zh6qIJY_}3l>}?K(?shu?+5JtX{VipfJx(%yPZ?&PlZ-!7M&66=8W65fTA)=Gde4Ax z`!);)<8sqi;HFpuYTqY8^VB<$lD)YB~_9>0U`Vy6KRD zc0UqOx#>9VsFYD`I%d3)XbJDbols(|*q#2Ra(bDM$KKEnBGn0_7|8$+kG^+er znh~oW7*zah4Y6+=k#bIgH*Xt(pBwSCtrZ`MFdodyg50N)wP&PKsphAwST2u4$=;2y z%1`Ld?ipfX9`)MkU?j*Sz9{2Gbw)ydaRw~ct@lRhm*lKs4M*0}oMjG9Y|t&fmn&9d ztRUnI!TLnA+)UZ6(bimeT4yo=|_@D;_l=cLG zyPewo4jVq?+nWb%Mad=AeHkw(2PD+@3t-j$td7t84&=d-dgPM&w;4~UdnD8k2B7Qq ztnMDs4&_l>UXn@vyNnm)0}}Fw1uzzXzOjNKMZp7DZwK%(>~B+zyK-~j8YlO~{OLZ%=eKUi#OCE(%aRDin<>NmaJQ^QYL z&~_oH3OUi*t%I8v+P6QBw)cfb$s0Rm$P6=IZ#RYO3D(-qRc-BnCp%F;RcouzhpsMSx`y&YRU@A zj6<1!l`z-&SRD8JH7j1!7YWG1b%QHiFd9Z~1~AP6Yyo%NEgiANnMAU;6+Q?80jWCx zG!1QTpm*_f_f;?JYYK1WL6!eeK;+tH7BX?y&Hy(#2e$6zl;&Uyjd8z#=*JdkAzKgZ z47n|EVC!K{X$iJ4C_gG7`mx1X$kt;!Lv9Nk*m`+bwcn+xvNhO3zj>vA=*JdkAzQE7 z8FE|Tz}Bdo(iUuCrTAI_(T^?8LbhJFGvv0wfvwRwWk|4vMdX+Qq90qFg=~$rGvv0w zfvs^l<@sO>A7hU%Ao{VzS;*D|J40>@9N2mzrwk3YFau63Ao{VzS;*ETJ40>@9N2m@ zr?dxKm>%CMAo{VzS;*F8J40>@9N3zoDJ|W6W7E`$@nNb7sPPn2kfUi9Tl?{NxS6iu z^vOFu5gD6X$f2!87R=4lq|V;w`Mw$OR3jE+^KC?pF_DC9Ein1o z6f4+YaSWL67Z5duWEQgYft^8{3LMz_h$(~6YD0QDVjssk?_(Qa zn#yvJr%y~iTha_TTHy#?e(6cCioiWddyc*zt+WA#BO?bn`oiQpM=1l2zRU=fZ8u(G z(fO4PsCUFU$k8g3pE&{pj#g)c!NCzm%dc%fy(7*+j=nMZnIkaZXiY|VIyk~obFB@i zcf>i!(K?f#IRXQY)@Ougf+MUlH`suBN1THkZ8Z6rBQW4-Q$~0;IKl#Rvkj^A&H|zzTbzY#?XolE zw&Gp4JE!n1GvFyKF834={n+9xWNWXTA-5H8y?vT8l3rgBx|Q3J+;1alT!|!P>VV1D zo|u6K{8kfsy4qv6YQW8R&_>i)5=qF?A(O8yF$0#q%Lv>V_)SBHZA85#PC}NBnEcFA z>`zBEVMGtTa$D3B76spzFg3PRA~JTYkV9LGEY#O=gT#fU8bfzKQNr|RjuVl&lZ70H zxma^QBqXXhzK3`-^2Y+C&YDO=&Q94G5@XCkrTvsscnYI+Io4CB3y^+%aT@Y<#?FxY zigV#vO=)jzNuT)6*@zlfA_D0TPC2!P)tF7Zd+_^$Kz2!ziD`@ z+%>?X`R^v6#!XB?ZthrY?Z)Hb<{rbV>gw*J$EnzZFd*Hx0j8ZS2l;tm^4XAPz|q5u z@LXsvJWf5b0rieJ2RV9d@-s(Zz|qSc*eLI6c5X2f##+L9<&_eo#+AxLzFsZl(9R+Y z-bNWDehBgJo_?(a>CYSIA#bl2av0v?1I=hnYHE#p2Us7BG2=C^Vg|A_)?#Zv9*>F| zr{O)V?VYh(p}H^^zg5E2*^-IK*yKWv#9Cm%+!RfsvFb0;8m5-1HloIuNJ6%znS5=E z8L%`xBQy+*p0GrJy8x*-71EHa8Fq%umgB(J%$y?n7Vf@T1xP=>I1TxlZD+`RfdgN2 zHH99*8Z^ARLKR3G%nnH(F}Dr(pD^>UQea+s*NhwH^9*Etp~ZGi5xBc$oPlgNL7U!OHwoGhT1TXCO15 zS?tVAg@>8XGdR6B*KJW_;9OzG>&^HKWM-ws&dgMJnE4`u4`nkLF~2n9^=5nqGV_(i z&dgMJm|2y<+u00;$<=1O-i*&cX1=!AnVAX?Gv6pUeJIOT+;U)z5iUCkbn>w_XDSyC z3lHlQwE2aup6;fO-~)BCz5pqEQEAA}20MfD6glv=DKsAoo}_`Wot13nc8M>l^u_Uk?kqCF&M!#vBQej8u1Cp z$WDWs8mZ7QvP*&8C)L3UhQi%8qHIPcAv=3azA_XTu(a18&`%%u5z%c^>?>jVv&D(X z*#1He!x~sHcfcTZM{^h=zb#?&4-!}#!B5!9c(kc#{r zE@d$cIvyMzQMBp|LQimq{gtC8pzKVfAXnd8Y~_gYaC0n&j~Lb!rWp5qo#RDNKdxdb za(1GWC3oj}aQG9`8pS)M&V-BA>bp9u!F7nm_gO1!dZkf7^2z2ogUb#j8s^R`Fddj+ z8(6hmFrsA_flVeZ=1k?mVPWBtg5r1to4~Dj*^HNMhzw-pip5q|7!Nbo89qof*3EFS zs_g2F1{*|U-Lk@_zd@Q$_HG+ob|=v=cgKP0kVKV-o|FBA;SXl~VTBDJ8J~RIHMq`) zM#IOw6iiOVag6&`xYmc~laB`mH}z4W;p1Tn9?U*40Y9?BwLUzbd^|R|sgDW`A1@F0 z`bKNvf{NyVo#ZE za8o0ppUhEUcSIr73A*h&Hll1sCZT$nYx0$$z(C#1%L%b|(0S+Eh<+@^8d_lTb4#I? z-qnQaNJ6M2tcVwyfEq(F1y#`^i>>W=JSu2$1`pGbdxT$N0_xqw8EL7-&fJ7KX_9y zKKa;ea8n-@8a}otusb2ZPOviAY6Hq%WDat(&EzXTfdNO`b3$0`5{CIh3S1qK;0kfe>+h_1*+@)4HFDVCDkC0^ z8ablD^g(nmg6H+4R=mbYNI*uuH@Mn}L&L~14aOmeU3Y$qllGd~(!WyPam@ToHYUUZhQ)IbIxLCZYn(7Ty$_cz%Yz9ObB1g1PZh5o4ILGm){&r7X^z z!Gpmo2CX?7#H9Ii5!0W+kckZbQp#c&bUYZmYS3DuK@0=G7BT%944KH_wNe(tpyR>d zb%WL#4PrmSp-)1SeRi449{%3>G{*=g52 zq0#A!XwMz>7*&AOxf5x~+iP})#2Ir?ajz$oA;a2xLyzX~L5(hg>b$8`1JBsAtTL+3piV{>XBYD% zCIu69IL9RRz9fv|o_?ne*T2=6kj&1l$z|I0Y#5$rlDnm0+~V`=aQz#O3CZw+np~z~ z&xYZ5O)?#r5mk&Eeqk-Jf6F2zd0teP%{0w?xL%ylai~T(#%9TqBB;)-N<~hWma-%+ zBM%OjS+we4O?2r__bjgk_UlxpB)9L?WwRUyK3spubPN^lXihYYN5qdx5YwuWhg^PK z$iW6v7QB6ukmwLjw1!dO(*mN-naD!MKC?3a3|uWNu|C zOJXnbVDKxZ4XRwZ6F|`)+H_S3V%jtEkh|4|9BeLS!P^=~qEkA~TXiZZ@wT=EF}#_1 z$lJO?4(Bar!Q1+rgffV;LK{kue!PV|H4ckFitE!=AU1u%z;nEnigOl0s#DT`rH+_py( zT6MH2c0c!F%l9Qroj;j~>>VrQNZbV$n)i4@s*W28bGUI&lrVMXWFj(mvXCP&7g#X& zLrw}EhPOq2EMfXF7ZQ=VQ-vJ4InnQaN=WWFlBhc@P)?Uobp~}ZvUsMLCow6QsKc`s zF%+I(8FQ|T>epsSMmEnE^H?@TZC*%;)zKwUnRxEFSOnFYl&Q$$rBasEV&I`7FB`Nl zZSremt`tH2ISi@D;m@TkhC?w2|B}$EV@|OO-KNde5~j|dOhop6E#yet1s1CBT22xJ zjoY-jUc&TaE+iszHwrm&bB+abH*-?x)%=o~TO~|C=0YMece{`yHz#h5-x5-FL`pO( z)-S)8Fm>i+A~JWUkRve{Sg5%_a#Cmwe(}uR5~d$>ArYCoSICi@6U}-*A<=OvQE}LO zc~F4VSrci<*+V-+VvIScv_}brj#vp_80sDuAa%Y(8uImW7k~Sp%1t{CP9*Wg9QYc= z6x5+R;T4VHf%df$#588)A!n}_a!wJPaiATYN%Qq}yc)0Q}t(jN`_3JX^BA1hjc`TRWVeQR? zSe@aDHHmxntrDcpq0B@6CKqxf?g9%nI3*{cuZnYIQ%jJ3yoEgEZCW8m?#;2_ZF)`$ zGY_ruaPz)h!t`S$1Iqemy&QiOxVNNGQW(fHK>x2#RbJYsmaKM&36-G zb#zRa#5Tsl5~j|gOhg736>=o@0t@CA=cI;#!W|yemJ~t#*o&#i-_lZ++@R;d;WC3J z`yhtBzA_k=mX{;a`h$Ol(;Y3k~LXB<#sHF!#tEujn ztw|(TR4fwQrWw$S7|3mx5PhrcNJB-zc%$r0I8rj)Cc6TtyW>Uwql)f#ba(5BEyyG) z;2wn!VnCpHdjp`kvzy*i#%g%@-IoPzK|v+W{V6NRG7icI0<5cjxKKv#`8EsM%7RMD z2UAv1W*n3cMVKlxrmOF=U_m)jN%?Tfipm}b zpnNRA+THuoxuNk;d_0fZ+LBD-Co*184@k(L48UraJeJ%YDEJ|d+VYZ2@;_$0ARmyB zKNWz(Xum+n_Teo(y={I1Z@_1y zKO151;aS6j$Ur83$;rY6V`1Z}fcDVuXg9Tn3ElOlUrhj4NBpsKS3;G7oLsZm!b`-% z&2l67s(RNI&36Kb?r*w|D>P*O3@Ze=kAUiR>SC zCUSJAkOjUB7To<&Ah}i0z=7iDu8kD#cen4Ba$r?7aA0F>&|;2zr5yNO@__>fKS7TB zr5uCkeK7xL;K1jeAjgAJj={)5y9vVv{L?>`s?^oT!%~i?k%PW--hYlqr5w*7$KWT) z@wk-ZS>$-`NpigW&(&V4(QMCEIT{8&Nsd?T9DZ9>h$00I@!!2zsJ>s$Y9d+FlVFroJm1q`093t~L+!I958uQh4Q-m2LvOuC) z1aXMG%i)%`c3%=a6f9KNO%Z00$Rdem5yT;~n8Q6m1XI=$b=?$U28k?{Xcj>nBA@;< zJ=ym4Hg(X7Nxl>AGhA;PBCoA*SnBv4es2ObyHZ?E+*GLK!`4W_jJ0 zo+l2M!V{?YTLhNNUq#VaTSd^SftY5SL>hGvk=rHGsD+5!5s|)a@%Xt@UN+mdV>s9N zE`g1u^Ub?k1ntssnmrO}mX48oCDJS%Blk(9(aNz9`x(i<27n#^1LCUL#tuzQ{B1;X z9Z(Dnd@zQr8VD&437k>>fcsA1jM4|(;ebPR&>Ct489gGdnho2-m3K5ELy>%|ejh_- zkvPRMfwPLlxZ?t66^U^t1kPyAVEsqnTD$xHss`6n;&NX00H<2|DI!sJ7ejNNj-jmV zGQ}BzOUo{CX9X@TyTqLnxU}pNcRt`yYrF+}L0q=W&Xs&IB174IyI+bSv+SJWvcOqo zXWSKmv&zo6p9Rh;JL7&~+{jj3qQYazcvW8ar5A%WRi7tN)Bh^4T>dJG#=j~7 z*Co=ZgNVE#kwz^<t^+M0$HCXuB${Oqhst6Oj~vk(WH4eb z(GgQ8kVt5$!n2Y?Kx!ESnuc{Z2QA$7%af2P7HOpRo@TI|$3X9W0ci?)c-;FS36=Cb zjr2a$453$Hp!X3&dVBnk<_>9nEU%kNoL8??%z>M*k3YZd1A&t)^ znne(Y$_frwb?Id=Fs#%8Qzmdo=L>~rA%}p{mjck_l`t}Vr2{1;$04Ov3NMrh0j1Rp zXl?O27#_ZsmrWIqCyj3emKCZf@~`3G5MIk+Ojs)~oB2JS@~;zE&R<25e?153)JxCM zrdBt`Vb5+u8ZvbRkF+)>9M)qLG&eD*yKP9z3w#;_L&N4YWNHc?X>Lh4tjQ>7Ze>j#+8-0}k3rumh=V2D6FZG?BXwKNUu@@EU& zL7?xlVBRbVm8$7*%7UQ8p`wliShc;|z{2PaN7IEuH}?$t^^B%y*N(@610&4_})K<|`*a0%UM2^A=5fkH~B zC0gkCQk@B5np;=~_tse*v2~b4Lgy4dC;@>2oezL&cJW%6vo0hNTPv_g?4o7_HHU%R zB?)Qra+tU-Cy}C@W0Bky&5&}0f!xml(muT1Kht9R`b7t9G3JogRfP{yKtSnN1@HyK zOm;1al(oPjvFnEJcER8Npz5@;waPY5U$GUKkdT({96*S zg#wGDe%Fj3<}i@E6Cgc9d9cKg^@k4FV$30}y9ytqfPm7y0H7OTq_01$Zto`%TPv_g z?15$kHHU%R!vLx71lGf_@hA=1f{{mxj}uOi^eAY)+*9qNR5JrzZDLJ~A+MyNqNeAO z=Bo)uYE~#{z77x_J)#fyy4zaYU+io0Pn5V3MjK%-{jAta%lITeCa1!I#=^wd4C*^B z%0AAB1`pxD57nH^j0EIjd``|>^th^+2q^V|YN6u?9vGOU174fXfr%QBG?IN&QJ@$Q zDDo5lXo=C@T)pYXmlxyQ)HLJ;<-U;Ok>0d~14WS?n$tDNwKGcib`oJlQNWO_qLJbZ zP0@m`LT3X)eYvBF_F8*h80;6gxQpgwK^FB#E~r5hDyhDcvY;z*DCt}Y8<`%eo0mt6 z+JQ{s^D~}QcSy)DkU+QnNndoul=*HF^1@<6&KD-^nl97~DM=XUEz*!|jh&`koZ!U z)1BTF|DnWF#~(;Mw*{# zhEyaB^gfpmeHdg#67qU^PY;JeR%(XS;d?Enn;mJW*lXiylAQ@h*M#r5yAn{jCb%o^P8r3TV8))5QLG7O z>`fVk{u>LsPceF4XmA}E3$guKtgiopNge4x%2M@LDWLy;D`D=~%Ydiwpms2c6gzJ? zEOSURq#$7+_nn56nk%F{oZt(M74SzAe4(iV{;0zHE{nD3_esPTKObkqfth2Pp^ERj z>v0V!7N0xPi3DFNKI2a&_)_s1|3iW=^wUtpp8}p97ibVvOX<^D(AQbAq7YQ-r)N@D zs5i!;2_lxjb6b4rCHPpYf!+SV~`zK)sZ{n1sA=vcRYwukbKOs+TlF zO7c?rvWA!)MW(!x;H{1#@jolP@Aqyg{Yw(^L zH7up?XogherSu;X;ufU*%CNgh$m``jJ*;EzX@=Az49a(3LrOg(q z>24|gC<*!UjN2F5E1zEmFW>8~dE zLQfBtM)#aNBN7sb!xNjw( za!qhooSZU>HNlK2DWg~u%$S-o3jH@0cA8@7rS$YHR@Z-dDgAcJQuP;>(laE?tuXyk zdS((ScHXcqouwI4kTArj!&w?qYOauSPJ%BqR=~fL;0sL^@N*U3cUdf@=OvM1j}7b0 z`I@1M@4M>)4Jj6%JJP!ezEph1FHG>I;xm3xf-m&bP{gIckL>F1d!fz0E(VpgOkL-y z5_6KE(Ac_M!ck8gM<@9J;U4-dr^oN@L*zqwIcUfa5+a2}J`!+f_$VYkb-|(S^a6%H zIK1Xf4+yaD%p@s)YhI}nd0UOtdX{)>z! ztr~)rF5$G3Y*?e8oNPY{m9^!U>jAyyBD3^rQv&QlSB*men{9X!v*)8YKy|! z?issPVbg&?Tim9w=^&u7+auOb{d5`_U1x`m_<9kG9VCkDg`El?Yo^zg*9s?V2>%RSuX*5 zTwr}q!0dEFT`zQmFp-{=Xi-q#3x1H{LP5EmepFbypo~4Guy#Qi`;)?&%^!+$)??{= zEdEPN`~|FYI%0KzNTM0#yu$mM@d)&R3kqP=jY@Y>qx0HP=t~-%*N;M9j%Ys0>juIr zD&UJOChp!I%Ht?h;-4it7MRcT{vyJ@zhUILs;*o8trFqJ{8gfbi0^OLWZ16Lkm|a^ znl&1*Hx$;a&w#zDuz7!z#km!+yswGv|J&-iuN1Yepe$ia^EZi(mBQPZzss;)DIwJz zg*7WBVE+(U-=Y{n?yBpB77hEC_as`F_bqx~h70Dob39O3+dN|*Dy-R}!Qvx@HCr@b zUm1bdB=p23y#Lzrt2)5dq7D%C3L4!}qZGy0ja>bY27pfG(09t{ptAhjbxacSdgAU? zG*TO@8IX$@;{WN-;}m4%b6yZ#c6=HuD>@=cPDnUPlTZ+SLxUQg@v1mtI57*>$T}+N zPD)u?m~c>jQ^EWjG|;f9B=e>C8u?stuF$&#Rxn}s=37-1|tERxXbOAgWoj+-vF5k)5|37J`9 z@}-~1fTg7gp=(4dzaq$;VOeGZ>I{VxggIoGKZEPOR``h# zt}D8yQ^`NgnMuJbEXw^^4y`G6l=$4>l?xqtD^gx}+dsQ04x`0NE9?s`_as6?4Doy_ z^%n*=Ep~-QxxX~Pbp?+yUs=qWqDST`inEW*djAUQuL0@BH{S!N&<5GQn zlkt+;A|&c+O#*D}?S9_18P-B;t#F+K=97nY1~+j5G<>X2!Sefq8}eYS2XM*3#*CNh z`>%j*N`U-@W9*`B&VzO8j!WuWGG3z2-#y-%02@LZ;B5IeD_rM*`Q%}{!A)EMjW*bk zf_)ocp|~>-)_UMJ*p=~8ecuLq6CkG36pM>=Dh*hidaRxzI+}W3;14F;>633wfHy2Q zhK&?dYX>bhtfY9<+aU{{4LB*)eQy7q$xVkGn|s*grh|^nJz{dxCqkQhRCBrJ(M`V3 zV!qP#2Q?wFBU7CpONqL^35U8q8DPzJ%l}{k?3Pbbkc%HJc5ou`aC6Fnn=LP?uH}C+ zxmL^P+|wr4YWbXd#^hQppL5S@u4?&nS*+OdNE}-Jd`i^y%`JZkF#2BeK>BjmfBeI5 zMqCzGxsj{yGSQ#-@DWJV!dD^zIxdFRyvm^lsqm|~TBqPhq;M?~Sb<_txXGbLsc=hN zty6F$Qn(!ntUxg++~Lq5sqlxmTBqPhq;NM9Sb<_tc)+2-QsJSvTBqPhr0^&bSb<_t zc;&@v=ZPBTX{qq4xLT*+NTe_-5?Fy^P#DdjXQaXyakWmtkw{@|B(MU-pfG_$&q{?i z#ML?lMN3<}dZ^cSh{wzyiS;7Ft}BNAAF zVo;dPp$2tR&yknwG(3$&-Vqd5siKgXAA;)6ULY^m%7lCST|o&le0MJnL3MjCk(X;_ z!VSJuP=XBK;_ro^y2sy_muqFhUH*Zf1R1{1KMp~4qkkeV*UE%j{Zl~+GJLbI2tjqX zuauW-Wy1abg`fl(zT;Pgpt|K(%gePg;imsuP=XBK_G?2>-S_L{*^d?eXVI$x~DEFxZ z$}gJ7rp`}!&^z!O6xx8}lK$z8m&g+m>SrX7TEC~s*8pA-a@L3z^&^`MoXeTgfycta zc?qT0EH&}E*Zs)k1tVPa5b5OMV$PHvJQf}?T9y}Hve#xPE|2HJA8oaFc8@y|hH@xln_*Njc?a%kh@XdW zKk5YJ;%-WI76cCZ54_oq)=Iy9cx&5B!ofo$>OBndPh)O0Na&>hD5v^LkXU$ld1Od3 zvZ=kdyRFB6T#V0LUNNHVL5_%&R?$&Ks?H?fj(% zjKE{^pf9i*fqhobrSgu=c)GY15~Urdf%Mzj{uOo@fyW!s8hvJyfeATNI{+3I-iXka zuAYu?_hA7rF$)&-BbC%ArL3s!aZr9U!m4i9Gopt}KYWy$j>y39qkA_+)R(~;q9Se@B!c3NvPm}X{0?v zGomUm(3=?{Ep1J`O;iDH2y#R5EF)adm2}dcoin3;z{0~^2d##lN}m6XWAQv2;Ekxk zkjeb7TQSZz6F5JNqqL&AoUirbYyW=Ayu@f zS+MwxBel}+X46AuD~%)7e~CI=V*|?ej8tT9t(nGIOBpb>!4rnjP+Hldf1mI5$0ks7 z8*P9$*5GbpvC?VHGm)=NW)|-&VZhf`Pr$=>YcCJE{0S`Zi3JC8*F8o_v+o~*N<~uus zauhkRb=aoltMG#4kpe$kjTiVw3w-$z93E2&{O=2V`7vA_|G4CLkEF@I+n+DOGr24X))Gl{#e>I|PO3WT9o2*>Rna+m7 z!ou|kZB-U9iQF)v1q+f*7H;OuXdz%>;Z}sUR7(vyP3yWTCX(Amv|vH9$--|rGg=5( zSol3cvGfQQFq7Odq6G_*O&0#hnbAVP!ouAM?R{wkZ69^}*&H*;JtJDMAlYQ$e$I>* z0u~k?L}>R*oi7FlczN-|JXkOwxTOCm<3)K!Lj7?B(vxF%*h<0P)ypqo$VdP6!GgNr zlKLwdFRC*V>aQwbPaE$e;i%!LJXls|E~&qk@sv7{P=7rFt6?RS9W&PGJXlZ{Tv8vC z@uE5-p*}VOdwQGOdqcxxrW$8N3;L2x2FB;i=pbNWVM2tq(yRJI1-O~&jXYX#Ajo83 zV#bU5jD-B82&7)o)S?a~znKLK;*m<)Z>6j#?Qu|^9AUjLMPUqmQ_@&LHxNm7YQl-C z4h7L^5!5Y2G1yH{V+GMbB+<7MP84-0h|Y+h-j{~759u80m&$H;YNin`NJ~1Y&&rw6 zK)}Mo>LeLWwS_XdwovtU6vQc3x1H;**c{1~>YMX!zI=!MqOlJ}?Vz zw88}+icdZ^8Qkb2qTyq61oL9t`@p(?ixn>TP<-;S)!;@S5e*;PBG|9Wy$vk>w;R!d z3&|!EJ91|95U{YYGeZ5++*`oJxXXwZEJ!w4*qt+@g@A>HJqlW_&%Fgqj(d%0*+O8G zg?%|wS#Vfb*dL*Ok?t*Ef;?bE3l=1sEPR_YqlJKlg@X~wt90)Hv*aNwTri>doEozgqV;+*833BV4c{>Ez;Q&Wt7k79PHjP&c)B3vT*4mPZQ?1epvR&v;Rv zk&r(TfjqCU0gO{8t$4wLN%=8VaA zeo_V;ofQP0WY`hrv~xC~XnyJRWBL5O68nTY}*1Mn@QaC!2thA(evsOtIL)PQ=5_Q~`HR zqZ^FB(@a3gjY>gordw>`CgS1dZ2@;iV+X1fQ$OL5MU4tu(1T>5+6kzv26O3TsU1Y^eMq~mqve@7XBLNK~O9Yr7X@V7uze{aI z$&5}yc9xlZVMs7w>3v72J_2c>j~VfAawg$}62!a8&Lo)0$lQm8M9yB$g27KB3GS-J zkJz*P)CwzO>I)T>h)P4YJ~L88OA!q_tNz;4)!x_M*waS`riQhS=o&^}t>_ui)z#VE zJAmHjf^bVWomuS~Dt)fe0q>Ac{!>cHAyaD=en2G}5HPY%06O_tdG#fi^*T^eavZ{M zP$5plgZ zJZWqf*q~7TPDJ(1z#Sr}kD&SL4QX~tq&jStB6mroI#!k<_XH$;H^CJT^Y~tM-L6H? zpaSlb=upBcjw0?4;bA?^L)yFD+jj>%g*o~_9<=2omo&f4ctJQIp?)v`dwSYk5iuPf zQrB%w&mg()BswTnafloiVgHIm%(6$+^^yp`9Py|`3laZf#P36x9*Tz#^RMi8PcO&P zn5`9wRHowzCn$OpN_HZET8Ho_p_nR9s(>x$DWvs-Lsc#f8ufVcXi#?@eGo=Bhf*nibLd&5T>I~ygI}q=-nh@3k4QQ-P4R9 z<}i@EA0XW?4G+&Pn3x`Uu6E7$o$%L_>z-5E;#3687UvwHg~EFPjn`PuQ^n z%K}vt`NwgvWoS>k`gX(kBx0&W770zz4A$}($i2ak5%k{gxD=ZxFPlOhPb!lHmL;kv z^1sPJnjpdvKio`jB@t64vPfvMX0VpWKyC^{XrT0WE^eu*>bfb#3=*0q(JX^FM5c4N z^F?20xQ*VHmrV(eCxsaT%K}vt`Db#lxyP?ZaL>$=m(BbhPx)sHEa$JH$UldJ^g>Uu zczZ`)HuHNt<)16CoWF`9{{jT7_sIL|!Cm;SxazZ4Pn7;pIW3|Cf$}emV5E03WM6_1 zH9GyqQuTKyFWR88)QFmDSprgBmXo2bv2gJ|pxrM~s2XqRA6Jtw@j)ImJ*0H9@L@)U z1BHZvPXO$72JnwC@M#`24Wx83@L5KM0fmHtl>pKca?6nCsU?P1-%^WbjJ`0U-hy}- z&e&w&%bW=Z8Vd`n6qI%hf(NWdR$F0jg5SbH{f-kyKDqeX;3^v)4Ikea;Ox26lv!gj z)8|l=xlS=#UZDHHRX>*5>y2nl^)s6az9DC-ayumydy|5a%bs5UT^|hao2_uU`XirQ zY%#dXhDXE4Rs&qDekHTbVwS33F?T2?eeJyGufzQifWdmF880`1$Uw#4WwBNH8IKCs zqu}I|Zb{b}@KnCn3fDG-=aZ9t23HyJYVfh&0M|7{lsRBAYZ@Xl52j3Bm0=`4lt;^L zKt%zWiv3;2OAGDiy2B}umIZ<^~@5dx!7M`+s7KxtH453(IAor7ibhNy{kAv7B zI-SKzl7UI0XHu4sbvOuL`Inx*;`Zuj>*(&FuRONVMpF0|GWy)lC5X4dQ%^Aux%s7# zV?aS2-mVr%`WCE{{k4=q-HLS?u5*U2j+VZT_V&K+>aXy75bhB4jUp&%DW_zmqB^=+ z%EFbD@lZ>*En0~}Pw@<=4KzC9+|XD3D_`UBhYj#0;q|R6NtT0(ao6OtAf1A6kS)F#|oa0sT5c4yvQaCf{<@=p4QL-~Eju>(9TF z!@ZQ}6&um7B_ttBubORrg#4Sztlvwh~qMZUKU-YZzE%Sy+Ie>KXxARDhuB1_83T072Ca24qPA zf~tEOkfj9(s_q#;mK7kVx@Q4dUVxzLo&)3~3qrTQsJf2}kgDpa=BlduqyVX^j%u!g zd|H51RYx^fK|U)$s;Z-!t012jAXU{-%~g;U1xQtORC5(%WdTxE9o1X~`Jw=+s*Y-| zf~?YzMogN6-GqQO(rOz}Gx~}gH2QvR^7ZJ;3`$BL*jt3Bog++|YivNjj*x>Ktu^_U zqo>_`u+Ad*pP<9SdA$wj*Aa4%qYWnCa^!!NZlgtb)<4a-lK?iNUrR_rmNuJw%hI#1 zl6F`G>PX@q+*yE#Npn{LA|}n<1&Ek5_Y@#v(%f5sh)Hu_0U{>N{RN1aG!GOYV$wWp zL8!NisykAEh)MHk0U{>N?+XwyX&x&;#H4w=01=bsi2_7SnkNeoF=_r#fQU)+j0K_F zN>tt10z^!j=L!%pX`U}Y#H4wl01=bs#R5c3nwJU?F=<{dK*XeZr2r9=<~0jKx4)>m z>jj9IG;b6jV$!@>fQU)+RskX=&D#Ztm^6PYK*Xf^djTRQ%{v8%m^ANc$RJFb{+CcO zY2LR1HKVV{L8I>jldnf#W>8Z4kk=yoMNFEHY(T$`kb@jOHu;vLzxe06|4TjBIkye| zaU8SeD+NTqo?I3(^{So0azz|e)F_kUpUK_x=4%B=|GxOK{B=8n>B~QukGCk)rNrGh zp#Txn=Nkoxm_8>KAY%HQRDg)-^UVT8OrLKRAY%HQT!4t_b4mdsrq3A`g!-+hx|s!t zm_BC}AY%HQU4V$`b4~#wrq6c@5HWquEkMNdIj;Z_)93sGL`!&jBc|5_ zC5)I~zb#?J1beWA5i{(e5=Kn1-1Fk+JYxr7mu zCcrx-jF{<#pdBq;VC0MC~A0jTT`n)xrmA5krl4768Plg zvBA|w92!2x{NMC0SN8=fbsBA~x~`QI21$;S=m9bgk?|osqP4xpZ;w`IfG6mHEyEnb zzoGC!2nZ-mjDT)0gl*VK>Uu%PF-Yc3iH<51hsawY+}Y*7W`iSSlht)w#4|`_ibMyI zDh`pUAsk*9kCo0eb=?+;uZf>7(Lp4<9DYU!({U`EW>s+g;Yxv)~u$0UGA}s^g^I6dFJ*#9k8k?a>)Pt3hxWx z5h%e20>D4+hP&@W9VjU|4k>-4@Ir|YQ2JN^T7AdGE%=EJl$0EYls;8>p+pEMeI5WE ze23sRT%oRe9sku!*H!6UMYuy&N_0@E;t=^lhK;6|slHU$yy+$OD}|L`!OShL4%puI z24AJPo4(coyGofuRr-y>hr$AZ(yj@B&h{R^srfI}ZITfG(Coe!xmibwY9Nu=7KN8u{wGIFTHx#KQ^?rGOyvpZ=@+mq(sN^QXIwoL5A(p zhEzW)tXbB8J*BW_NdxwD#CG)fWg!O8Gdkdl>K`boffzOBIaJoO3LgtwAyC@$5zyA_ zzq5q_^nwm}C4ZnYD0vPkT~zp}R3V^rNdfGNjp;6Hv{|(geMO_q%8lrsHCq14j8U+w z65Zvyo!k2QH3|7j5{p|jM_aF>Q7v853|UQtK|Nj9kWxj3ls6K5p{fG@mcY00aedrI zw{^sqChc5pjzop|P2ojZ2!W#fE&#psgj~JT!hJ#ej*gV19Eqguh^8ZuyIY{7gRCFk4 zz9K=5tcmsTt7)jH>3O6%D&a`Y3I)yABxn$8V(xrB4HY##k2FUo9I08MpgBf@2D2tQ z=h!q<)bu>k9G7sUW`%<0cme9{U`;%_PDn!~P3Dp28wp2f0tL;95fomNhi|b?(t(1W z=aAZ)3Lmv91eD&2fMzZmW|GM|P*Cz5QktUhQK>>eX=((F;BQW2CYh!K1trfRrRfSE zl_~_3-i`peM_3DM@fm5TpcZ(fH#6ZxMTdgsED364O}8SSoyLlyo=Bo|5{?wDP!N4b zf(8Xqj5Tx9SW(myNpxPqk)jm}qVpwaa1g~{vmlKXMLm&3-%U7Dv_e62p#XJu1W}AO zi_%z0l!+v|IN=CUpdh*=f_j4_2AiciQV{ecl3S+mQLI8h>U{v{RR$y4{UQsK(+Bc$ zt`hO2@u9#%!AFt*BMw%RhF3s0`B(=`jldz5PZXYY90E$8MnEGgp>KSq0|h0|A*Ih1 zJ}OlRD6NQqL9B!hu~G*LN}fYXUnqQ3st{26G6Dv(68gbcI#5vZ98y}P@KLEkKxuUV z&}1NAk?^$+*hBB@;pAEhb;q;^NZ;2?z?b&rk|q&$hF_9}dost}Mm z06-hPhhT*N;xh)fZ{_7&CE`irpuj@GN0I+f2vVzg1ytI1I$&!shg1$Le9!>`N=F2s z(JP_Oj_N>3$#F>OdxaNDgn-g90T|?!Ft{Dpfs&HrkkSc-7fOVH(n$dr?3FOM{h$LS zCC4G99~E9G5duo5BA~OwD`6e|lMWP=JcpD{D|}R{5KuZ30KHxZgWFko*;a9Q(l{ru zL4l&ke?A18eSQpX7vyC-zr$1hivk<+Qxy5HAlTBq#-XWwqiqh`F)9Z6OI=3dv^B{ zP@yHMdN}R7H6<{gGzy))H=<$62hV3Bvx;%YD_>NDyji)3w37Os@)9 zOAEa-7W+(i^chjx&6}_S+J%N!VNVu zW$EhR8|obaYj0`j>fzrXs*c&r&4XS#yQw0Vc=Ixz5cfz*L?vrw{UIxtlPVs_?^%rz#Ohbd!%VV6h@a`j2x~sWJuYQ_b?-#EnXy zrLl59Y2@blJmKgf`hKz^0hNo#X;-FF^?jn psyY6Y9>R&^gv5AhYgN+O;XesyoG4FBqLIgLrzzT6aSh^Cc4>rd2mo zV_#rW(Keg#i1XO5Asvb_eD`nU%DHyv`hIJPx>w7hW=Vq*R_hqq~CJ0mW{*;dVV_w&| zp9XWs|0&^URewL7PC$jmqzdA+XHtgUn1XROWt8rxpmAO^_ z>fjsdX8~((85CAA7{-6egI+qjsUnxU-qnmJ#66M{(M#VmV4*!!`fEAMZWG12p;>+r zgVFnD8uFz~*1C;-l#rJWw-SynpDk}B1QU#IjdBeg7sLld^d5U(#!uZZ^%@& zGZ>9bKYH+gjDA8vw~6>l!qG+a{p8gIR4yK;9hEYQMPtTmDWlX+g7w!^Mya0!##qmw zQ%JO}>vun~)E$>ZdDz|ghCM~YmhG^*1A*DP>m*+a%#fSn!cRVB&gB1A_mIo zNu;RgSX9WjHACtV21T5qAijj|t20TYEXU=Wr5Q@jmu|L#a4X{TlR0UqEErnxorI$# zxfSPXkS`;a%k$DujV70Je!|h3zMKmrXpnD3>_hQ4n83 zd|_(&T1*PlJ3R-BS7eG*%>f6jw`< zlk;(Ctw9)TCf-Sg)>?I4Xt^JysB{F0bk<1%bT|&3jR-e&clTBQk7e4Vt_z*`0~nQ- zAd=Q*NrD!~p|uTR{Q5+jZ!wfR5%Wm-3YhfCkd;+Vwv_Nk)Whn zNfJqIuO>k+CWqnyhE&@Gv^^CSzfB?~#YiN@gPO#O9s|Y03>j1@4ibt-l1NE05=rr> zCb6Q&K=C+323LyyTRLdH6G^0`7>T5KQj=KGW1x5nkmlB2`cW1>umHiIbRg)({vt^v zc3Kgj6%dd*qX2FlJy5JN1DaZv@}1RiETRWC7Uj=rI9AXD2N&VzH5|+5fzK7;7c_iu z^=Lse+OPrt^iKn-J2dfrQNy3E;Pf8h68w^eKU2Z!g~28GWetC}g3~*FOYol~d{}48 z3$7buwed?5@r^8Y5Kt~=QKMYdi~*tSz@V9b)sXCYDNT7T!KY74DgH*pcZMICbgPS- zNywKc?PE-%^4!vl0iis=pggw~#E;%?VewlMD(itpdcSLi((88f-<=3)enG7%{?L(v znkSLiU4@TY6#_-OCjmUWV>xkOM~YIsn0TP@Qp(Tj4%w9*$HTbt#N{f<`GSx4+e2ny+p zk#NXx94cdFI3G6|>xRv73Y?9a8a!TsvoTYHCn#_>VruXk3Y?9X8azpW{f`x4e0oz| zFIFQcRE=**xTr?|Gscr;xKxdtYl;FFs*%A{6}V8144$UIg=%E*bOkO{BZFr;a7Pn$ z$Bw3Ev0j;#M0{21RVHyFk*agHCbnTRm1{}DiRE%Alxt}MvdbmY zE=w6^xg=vbGunG;%^n)e&7SXNL9=L*N@aULWpUvG4yF4bg;~W56xVJaW*nn{3FnKy zjp%9W?(L&*pz!BqSk8W_uKR-dg+aogLVYFC17sY9Srx_umD)E0|gn+p~7rX_$X8% zP@Ihs(B3-COJV17QxYj?F^j}DYerN9269^>B>w0t76Dt6NI{NSB)3g7q8u=g+a4jk z{zw`|iyi8ELCP^mXs1L+8Hz(>mk9H3%wnT*w+@tK9EWuFD7+Bj-?A!D0vPk9aQ+JR3V^r*aO0^iPB?Jb<-YE z*I9=*E8M*wID|hc@m@##3h8klZl;Z%>bKU0{O8~P^}qh@KmNCvjZc&yUfiz}owSvQ zT%0WA@P;xLs^Eu&)bY3f{a^p~kAM8ldBe^4V+q3Ebj7fa%tY=^6|yAm0t@cWcv7`B z)YI&rQ_)0clZf}ChHt?l1Lriu>oNv%=LMvD`0mbyBvO*|ERwsZ8A7hYK<<)+ z_~8%Z`DGm_ih)B~R}@}K`H}W#0qB)u`Y$?AQgR$px~lL(i4Z8$uL4jFz5Fe1^rUNf zu%sBdqc*}ExA>H-Jhdji%KDjLsd_tQ{GmU*Q5AmIp6prH9s zg8XSR%nXlopr{89sXbPBspV&em;Z+wYOCR)D;)5_$n#1PDvE`}J+Eqpl;eXvqXcAR zQ`qCd*z;N%D=9LO3ix`$5t=}uI!6nTI?pvm1xj*!v*L4PQp>5go5T=0czNoN**33&o zB~9j$=KO>sG=YNV0tMoq=yng{@20V`s3Vf-!i1wl2?fzb5;W`ueiN?S%wC)Yi?U25 z-6bhY3Ihk_WdhdI+sS*)SO6_gV_w(q6!F;H*vCYYeJ|k%RiGgHegaZk4rba9Qij}c zFc}{S#<2F`p-Qm?`Zx=gsx(lkY@ehoQ8Hr$awlpN2}Z%p=te2}g(m10)=w!6(HL9@Cz`^Wc$)k zNt1b`xj*3uO`xE8K!bQBa#Pv2S+GVntQ8KXEG^7yg+l_?IlQg8-M6co&%Vo}CGAM2 zLLbg}Lfs=#@b5kF`Cj^w`f%Cg9Kq(MX)==&5g(kLR0v=cO=VStjj1^!nfhYvViJ;X%MV|2zYIIQnogkq`Cl$~)B-H4p0y_~YakoW``t92y z#vKbWySjJqyk)OTlzSnKn>{$vAs@9Z?>dzOEAbp5x=!#wI-a}ti|U_hahy_0~{ z!=ssYZpx4kk0xV&!jSC)C)7p@5{zsoV5qGYMointc6ZNV(YHtkeBG#fo9f1MsAd)` ze5{uWfm&JS0QBiPUGiVR!pyT=2Mi^_A*J^e-YGExN}vC0YxDCREhGBcTU$EmU6rkE zFVcUC@nnS!@XB9N5|{D81cH^oc-wr+Vz(VgpL1 zbPn>g)#M9Hf&oX{GeSpoyTym{9X7x_^5bmmKQ2G#AV)h*e&z@aIND_r)c9K?x7%jR zvABl4kJ(LK%?*7+{)NtUK3{$7G;TinQv>_!fo6LZb5boGsLjWf+-HFEqlE-d z3+LE4{JtLeB+g?_a(=8fU%|Q00O!XG37!$ovGsVO9{42AV@`5@vNm7Axz7OSKNJ!? zE1Y8k^T&GNlQ@q#$@!_;dA)JS&tcD{id0qv4xJ+bu`m&3(|U~t#gFm zH*7@p-+Dqy|AjGSs8qL~Ou;N(o)hK#t&oz&Q=^<{tKXlH@+9RnWT>2Xo=l-o&NL^= z`9~oo4R1y{vEaD-gp?;Kry)b-y!T`Zg>t4jQO^5T%9f_#)NjL6WFzMG2ldE)OQn)h zVIJ1zv&s-N!1|*?0y(ueVs3w2k9-pAF)3Mp`S1R5Mm`&mI|nLQ_ZeXQRVx9FC~a<} zvoeJ7hR&V|cB6P;l5K_!qS5uhQn~G%RPHgg`GjjD1Ij(Nkl;Dd+b}kcs|P-b^O%#I zkFU*FaPBj}`Gi7(zewlkY;V*fpTv4hO4cXV<||nD8DM=aSpB|T3gy_K3F^ePPWz7UXM>d^L=I#N<|Bog~d;e{3x>|g%#9*{34VBcGM|ztRj!*;&np*^@SsoDIssmonZ`#Mv&v8g? zo5Bk%LO^MU0`xTu)WhCR9eyrE>Fp=<%TPKxI7I1XCx80$ZXIn1(PygY9uaNzU$Mjv z;s{BQ+}&G=I_{{!APzz|&c*M%6J%_Dsss zy8I(_XCB;@BcaE-~Ro-{^x&+s=fN86kiCty}c1jhf4JSbN8M>b{*N7Akm}* zNb`4RH%2?VTRXeki`I-ZRRu$GL#>UfSFcdjEXVg=0c`!Lpt{i#x4TI#jfNee*r4~` zlK>4s5+DgW(0dD#AVKfF_aH&<-F|t}pFAgDwOWR)4haC?`M&Rb_uR~TGxNGFv&^Av zUZG0c`d%tJIP6Zpw372a52-uA@!;_T#!0;x6y^Ld1x*dOAq|}|KH?!Yr{f{#$BdKa zG$_jXNeUVo@CO4LAbwiJ)U2L~w4ZTSnwM~t`12Gt;;Xsl4~eibli!W!DF2~Fte!s#Apc>U z9P>LII5}(Lfd1Bxw@ktyuGqlU! zFYFJ4Us@_SSpqHYPduKYAbgGN&2ZVyfdiznD)4)%tWdbN9P)meMCn^>ZP8J0g@Wj6 z%c{WEN?Ad&1rFIdU83|mTeL^dP!P^me&P)K6G-H4K)%wQOw>t0g8T z5}(IeEb*XCye@&^^)2IWP(nx93yYXb9AB6gdr}}H_eGqThVQ%iJ| zThBsT;>bkW%W{%W>M)e@@)Yt{J5IUHrSb3;Ma*S&H;1}yHFBPbq*roQnwD^s_^K2( zHRd*!TKm;Jt1`r7{DpW%_gTSQv_B6pCb z>fNehoI!a%)4p;_FnF7$A{sP2GI)DRo1XG>4mv4qC}L{GJQGIl;H=aD;VAK)DXcZ@ zUnfGRox6&dn%Faucq3<}i3vxE?@nQzkeCkP_Y^TTv1cOjCeBI|6OIz!o5F@0gM)s= zNXOFqgs7T4vXTD&l9?KCShDbthb|o(n82&7=`XiPXskmcfL1c$Qu}NGa;bKd{V-A3%?C&w)GP5WbrabQp(OQ1ThJg=CCUao0WZ^>w9rrtg&N3ef(V7Lv zhJ}wyCbM9$WZ@GAUFP4aNk`33g=o!!W5dE{C6ie&ShDargO2;Rhf=HjLWtHZI5sSN zSu&XggCz@JF{mG-(b3}TGFUTUxyb)b!DH!xr0o0r!VU9qI}si#9(D`L_I|5;4-(~(NB%<;4)fEZ^_v9 zLkb>C4QpQ9@Yjy;#Wo-0tx?zJXIjdz-UVVxF!)(YXu7I-?G zpI0(-$Al%P=V#E?@NoKmy$i~qGa&Rb&qe-q1usiaNXmX;0i3}_gVe%B3Zjb-uL3g{ z%L=6<;*hONO3J_>UiUcMaEn!R0KBwNY@Zl8z1I*OW|V z*kH-%wIy_Bcx<{o5)S(0<+>WIo2gU}?yj$B2{r?p{N5mt+ns^VblaTogK0Xb+}IWC zoQqA@l&DaK{hPX}3fqwD(1zSB$P5j12C~hd+TYRz*=-}3DmLNPx}vZFsRr4Q;_(b~p1Ha6gnlF3XPEE&BsgO0a{Tg!Yeqfzr+V%*sf`dOj?BO4`l zX2s*l%-s@vCVe_TorZcUmPC;19+BH?K7S^(-<-QC=Z?3g{OOnGS@%j|eNT)BK5X45 zaPtCKG;RNb9*otmPCNhN0S}4!6CQFu%s4);M^Vm4643a#`5;1EVtTZQX;}jkX&>XP zB(KF$;>R=Cc*Dp4sw{_Zh~?vI0dp zpG`nmY;={Ts}9fcke1W)kn?%QNpcd3a=zq2qqvy?ZOVL{)GQ&=u;t}4DCW($$oxvd z^SL9EvcH-FVajKxZGNo`s@Ve<*~DGCKrimq!E-J6+ipE|>$jz_b5Ja4 zGYQz(EYQ7?6irsPL@@5AAuH*fJMT&1#EM`ilYyQ01&L@UqRGxj0o;em4EXOr&=LP* z9&5^b#GBJo$8mSr|LO8qs5&5Ypbn?3p#&6qpi=|LYn8iTvnzmb94;;lC3 zL!$P7zz0M_Y`{g)vy1um2?JtF0)yr0Hnvdx$Rsy9zK%nQ1L|9xqvJ46a6 zRs=hl4D1{#NJKjkO?Hk5;Qpf19m!+P2kUf^h~!5xPDt!fl=SEfly|ygcuY?kI^D61 zlO^???zjxZI^FR_(52;_&TK~PbSH3HmN|5~6FE%lbSKHcqSKvR;IvM6ii{LG-KjFN z>~yEez@pQw$Z_Zc{b{FLDTQ6t%T`Wx4-#l-rwjDF`W8(M?yLxQ?Y}?mbgQIrVnwi% z$-vHPK_c3TXtHx|052#y-5MTqK3J!VL?mC!I3ck^QPT4=P~Pdz=P^BL=yVq_PL|Yn zx^)?db-D|Spi9d;o!N}o=`P~5EOY2|7ju}_=`N9hMW?&8z-gUsy^It(-DNVe>~xpQ zz@pP#k>k(@7Nni-N-6BBUbb?odyqgwyGo$v)wgJBaMwn#YyS(nX2Ij;LGtm&@QAxuL^HeFiw_>K(b($Y}xP8QLV z5(_Es${ATgcWG*425}d~X>M~ji|FZyg>?7ij4Yjd!fI0jY2mZ9G?AkV(f6{5md>$| z?!KInq%#;Q=KTr8+>b-)Xo~Ovi)iT_3+W!r8A&>Wp>z+W5SNYS1`p=}H5qY`>yZqf zrgE7c_kh+Yo_Aa_J?v)U_NvhnWmHU=k&*Vvg6C65ByH$Z8E|;OKbuaAvQL*mJ-g>3 z`!fYE%T7qj{%j6x`0Ugu$y<7yv^`;Q6*>H5Yc&lVG z69!8j-to|uS+Fr(z%2{eF7U1p7Cq#2c-T@hy@v!#9^T8LXrayn^@I0?XvKnO!@>t8 zGq*rkvhX2;HoOJu3?B*6ngz#(g^x=nvtY1f;WH1#+8Ff+R|MN5J};x9gNzIVUlcr_ zKO!mpmj$rh@J)e=@RbOtn{X2F@wLP*tQb7G`G&)z8R{F~O7W_fXyrSB%bf%x`~5Ag zieNb$hbS|Ov41Cvhx;oC=f;ev%>R-nt0Xa$=m1$LSj!DinGQ}UIIdWG<{yc_LsU!` zhlL!Ie3ctq&0q*}*`@tPYh z1V6`1BHmGkCr>9u_<;3X=CJ35@4Uox2ugC!3aFlc+cHSWKuN=NQ>BA`~3AOR;AN^IuE;>pcL z9Nr9O=*WGs6t8-50V~H>lQIywc!9wnI5w*AP|0K#43?_!FoU{-1|2gV zDPpzs#64SYw3Q?Cloh{%{lhcv^sgmj)Bv{(`XFasj z#(I9ZlZZC{xgr+w^EnG#qyq5pJSTex0Y~{?iZCnwi4{$>|Cp}Z`Foe4f#OXF{fFu)dMc~M^8NK2S>(mj* z#oI#E*>EnnjZ_3aHkSg?NWhYlEfG3qov@wqo(OPuirtb)z{&d(J91})7m>|?J$vELfW?s)=eZ5FtJ}jk0v~l zOdJ@1W|V^)*6_eKbr>2&93(`Y4c`hsx@R*v^5s~y%#z~VJ6eT?^1x>fz)j|7$>lHkvCUrz4 zUCB6UQiGzTr>CISkV|Tp+0WoHmo&X5@Aj5sBI}uqlx8(3%6b+9&GZc}-`Tx{+P`6X z702{PjDN-SYK~bLG5!V8XLHPU0b}n9!%bo5a7^Fg0J6830dy`0Er^cn4Ql|c;h=?k zPvP~m!53ay}b(CD-;Z1V*&6tCcRyP_{_`8pZe z*B{M>0$iA4hh2AduhC{9wGCSu8q>u&BW+8-P*b`jg|z5v=H~uk_af~g=$mj{`1UQ> zQIT~$XQg>51!caB!)E&MEI{@m^~(!Le}I^ZVdq{^KyVYJQ!#rLkShzw!T>QZI0xja z6k-}2os(#ieKimH5+q|cR|7{x39ezJv;qc21-O=h(q7zaZn=c9>o_L%88}A^1Lk^; z2~7|X(+hyPfn!3`GZ+*Km>W4J_7Gr9!w2Xl4vKvP0Mq0Fx|xHDUhKE;78x1bnXGmz zZVceE&QHxK!oWgB)xB)x}`(xe7ONjGI6|4^%Wd%?Xd;!_q! zjv-=!abM2J^10i+?@u9qL5_y;53q=u&a#m1!JLt%1BSNl5fAB1;SFy1BN?_oTEtw+ za^8UbnF=8HW1Q@>2OQ;p(!*LNKmJJaKUKtP`BMSpf0~nh{(z(W&jr}f80ItWRyt*P zz6@3!q!O_3LO~B60+LL;?13Hod-hJ$SIS_`L?!_fuNHJ~A|lDe8y;xq9d4H2Piw(% z@|bgw_vnO(#BVWX^z8&hkNnVCsh>_un|Vx2>WN7D4&x+A2}McYO+a{@%Wo+i zySDI{medoG^gYH&k`juNzMp`agFYv%seZshE@kriRdg?u&C!tY!<>;MG#JYFaSoXo zTE55627dOl<$LU5dzgLm%_lla+i;U17lWZsRUPInVUo?y7_qf{=bv|W-+9+Pe&KA= zob_`ZRkN9k!R8mL4zrms$>x`gIJEPgJ6oHby`53om0#6xHLF|@X1}gzF}oR?41bf5 zu@dV%(s|@t7ILL^x1Wa5s%NsLLh!r4qQQ&@7Hz=+jI?a$UG|LLXw~;X1yZw?$iUe_vH~;a zIpphLMlnq@`l3C0hyroGl1uh+2PHD_b*QYse0dJ}I*d`;d+qUe%Xj_x@}IlCNfkR> z1=YM|QgC;Kro#M19yvUc(Hg(nZ4XwtqZEj9C-#X%2HuXA6__*6Az#NNl$P(Cc0uJ> z7Sen;8uA~PGm^XpL-~%+A#&e5fq_Ejpfj>{ccO-IHjCkav5*SE?@5XVGagv91t&9- z?;we{Qxu4^R`da5Es=q~gHICTySIUhx%cQoWbH)kYy4TkcqNgx9uAFW-lWg#t}qaojU zIU~tuFqH571k&^`EU-&q7qF0)&(V-?UCv1I84TsSFo6sY`djtwZA=&On3mBKk@8~3 zNpcd3l3tR4n*J>X_UlZSvXGY2(U5U{&PWm(4CT8lfwY$Sgw**j=OHbj=ON=2jFY4! z6y>}!1>sV=J?qlM=_(#lb2=V!Ud=dZPJ^PH*Q6lxsckxn(7fqd9#V5U9&%pCIB8CU zqMX;KAeWKuufHJ=sQHM4Y&T~3G?&YCQv$&2hU~^sPrR8$v|NsbWVhsuB%8s|hTWP# zT9Ymv&30~M5iOl#A>HjcBS~j4lx{-;>HNgEQJS>e!9!X?&qKyL87E0eD9U+P3JUFo z*6TL%keV~Lm%AA!%^BLuJt-*k3mS}W;vqF>>=*YkPMS0Hi~CZL+mkdfzdsMC`FtCF zAj7A*++KXx11528b*R&5`ZvGZ>#L6lVKHe=$Nqe@Wcu_87Ft-@OQEfH_9orOc}&gj zh)DeeD!9Y0gR$6OJ-JlfpV-bE!o=%VTO@M?~7^ z7$?nYP?Yrf6g1rNTT6}V1s+qAIwF$3$T(?IgQBD_rJzp7-8OFr2QTxOOPY_uOjB`0 zBz=W((xe7ONnd548C;n7&7RBm$X5^o?fX-hyIl4LhvB;lDa>6m zdy~T!_9iHEg~eP6dW)lQ5hgn8bI#u8sQz>_`<$`O9EEE?iI(&APKs*#8~5o@{w@ot zO~cZ#leXlHbRPjjyXd_XGTd~Hkxu*X^N^a*@sRNY#z|8e6y^Ld15Gb+N$Jf0Q4!O# zIwsP7%vo7pgQLWsq_CFn1XSEldB~;B=a!}qI3BWo#yDwGgQA?DGmzW|zTl{=p_$gW z9h&2p9EGoU$0h_2#=&?25J$281eg)~I)zP!W1qSB^$icH`@r$Q`Id3gVi*(^872jnw0ze(ycL?5+kB!v@9_8%^7Jv%g57e9x~c&&0t#QZ_THcc3=?{bEZ^eJ&3b> z-hiVGJvfD7g61>Rkn@ltsAl$5WImL$(#(XT%!j40W^2@ErjzO6MNrM`smOc;XQi15 zN12aIVVJOm)YQR_Dx+%dKt}ST3tpPtA}RebDX`fI+3CD`Y!OtGdn$4t$60A=!cpeq zQy6A(J~d4ePbhcB^<$K~5`!dUnr6_7w#$%T7qjzA^*)+|<2K=OI0_wiL|RYE6qzdO1wISwI==6QpY~Kh^dJ^6N%5^tTZv9O1Nt6%uaqXZKw2 zE-H9g_Sm~F&Vat|bVR#^hxE*rhrE|EPL>rYs`up{G(J2yiDz0ThbP@^!Ctz*LW+yY znE(u2DR8}s6ir61V&L&%e}fJkT&@mdq@{9}V0S)o$$=UNu84=@|{;oViOgx(-}Dt7!BnEb{i8L`r5V&x`S{ zu8aaKy&$nAKeoHQSinanmV`pl5bq@oQnwU!;Ob>XqcG-JRH#=3(o}0lTPhm+zN#R) zIddv7_L{69_%a-_^?FHZk4#K8C)_@y*7b%8>f$X*!QGphO6kw>$l+TBZ74NJLyNaH zOx<4;g1ya(M&Zt}$lN;xsWCbfp3$`DymvKB-CPucxh;xDVa~D0+VbrDN_^SNjH#j}%DVRFHwIk7b3zmgSJIPYTLl;)}ZH zrwXL*E6BjtXR<=!%W}xqSAjCp7+x|n+#YLB`P($9Ykn;QoGG^+=MUgq1D?JS`N2}g zAV=Sd1iaolew?9_?mL;Ceiov_-se|E&|PDq>CL`USl&HhyZrU0{RD1V1$XV~pa32+ zdu6Dd-K>4E5S8~w#>UP#q+|vU5lg$_&=M-{gGjSy)WZaxRDI4nJm*dP)mVFSq`iYZ zOHlQXP!RGCApKMYn}4LNke48Es0>Hvlp+5KKAPqqQwE)xZQT&xHz&KbmJB1u7R20x zNki$6D}Z(<^s@05(?7nX(LU(yw=)mL)(Iu8-*mg)g;m;#C2axGwyV-kDrpO;llN9> zCzrHEhK7$Kj`jS-UzCNk?edh8w%E`X)@i5Zw5j3IrS7qXJ{lOTkm9Zpu!AG*qac7* zuu|aW_AQ!P!s!B7?~rMlGbE(}Pu;+cdcZ0f;R+x%(nJI$SS|AN zB6tRs;hda+FDl}LgxO07&y^7sONj_9tr7XTCC?yB=jDVc+>q563C+Ylr+mJKakj*! zk_y4t1&T&)Ev6@P>l9L@>9DjHY6^N2VhWc8g{j68EMeglA5)DncW9?U#-$2E-f4vj zinCr;2(`&MRGP~eWywINITCzP@4j4v)QqJ%aCU{F!K?)qdApL4rbd2>w}H5I0_u5J zDTtc0LD?NQe==-~T+7?)i!1z37e zVh2Adp3FRy!`nmQMr?Bh=V2jQG2+=^K2kDs6NDuTkLFMu#=?3E9l{; zdNyo4S2A-Gge42lmr!M>lBak<;K>7&ocE%@qd8A8<;i(3<-9ib>3|#2(B-g~#du}E zMFkY>6^Wgf%;BkMujcSZVusFruZi)BnWz9WuS@LQjKhpCo^y7@J3?BKBTZ&1XSEa3AlMjV&`rgp4_~f!>1;vT1(o=)p~bCM%yM;ECyR zcrky{L5RG3F2*ZnG7-4>LJ~;qL_GQVlEXVK|K5MQ`2Lj$=w`^Pz|hx{05?QPTkuu%EGFv>Glxv#<|JO7pb)# zD+A=3a1FRQPUHta8G{@hUl2wH+nup+J<<$APf#(=7hB!+SrR3voT#Z3?mUkSo}|%i z`(?|Oa_W;+4Qj>gARud;qH56ih;>_8<5X3H7Kq*RuD+?s8mFlmv|7xDp0dV@LIY3d z`&~}A3a(TT^@bQ!u)9x}6^fm0Ikcgc?!b$<86qmz})$= zLUfjK$kqiiMLZ2H$>{cq#X5yAorom?MjuQCi2M+Fn|a+O4UEzmbZX<$4WL_ZD^F?J`B9@a9Mk!;(4@Z zZYgNfV^gE%77=#|kWNsy>ZrQMR179>Q*{cLfk`%R7m2vtlTJ}~b$Ek@>2A>q!QdT= zhG-8gGIys)YP9_&OFA6frGmQKb5iiPQBx5O8Xh^kTckCY;xTV`+Z3*>L;ju`uDj1D z2(3*OEzzxGli_=Hvj27kO*`+a;bv(#e9oexr5pAixG2b-_7L8nLhZAk)|?+yAa$ET z1|@w+Rw&F_4i)m@f-==;_!81|^${6ScjZN3>QRwjcp?T_daNXLf+bpoeq2U$vE)Qx z=?RfvS~3i>^khLWho4b@N0xoL-%~26ZY+_4x2H9g!k*`m!)FTG@W}Y2@4R$`c~*hc z-31wVdrnp;oLLU}dcLF#1z!v3pz?wO>Eg@Fz}JhiLg|Y*ygxI({&Mi^w>XnPBnW&K`73+3XHueD@0!zhitu7P)4FH zs@U5KqHZgwz}9A2p|E8+Wb2)Rf-e#JYSEGPT?J9M6;xnri>y%CvK+GYUO{Q?G(0@! zztlkoviDU?-CCjqb026bg+0$BgC7<&%_oYH|D|CE$P0IU~CP6b7exK$NN#biwf~GJ0 zo=s8W8%;vIe^ZqBR+A9#Z$15*D&YhukWNJz4CpVe00h5X>E*XcXogiyGp=fiyJQoEpdN(mM^e z{5P5DWO0askewAOFm|Y{5PanvvUONNX-*CK8IPGu94-Uuro0CDM~M8w5;4fpkp-bM z=?u|8_b4%5_u~{`=V*ytxG{J#b4&pr?cku)H2aU{1ay8lwt}h~%hX`+I9;hQ8M$Qj z_>wx&oSGPSwWIUI2`Z+G&8P&ECu%CCMaLt9C&@H_jh0RnC##rQ7_>?-c#5VX8}#37 zKeeD?S5LQG0coZ3G!0U>7j@ung`!cIb1W*}%7QfL@1>?$!|7tY?#d~^(isxF@MG{~ zW>tWXV0qtMST(Es?E!x^gbrt`b&#_q+>jv1!QR=bRPb0BA*1I=#2sPOEjUq|J68n- zpZOUp$>p_Ra*ZY#He zA{VM6;xj0+$VIA%_(X~s8P!nzGYEQ@%`- z5u38%QB%HLqjhh}G4~a!NY|zuMXppux;Et~a+NC5wJArDt5uP%O*x8Oql$EG%2DK6 zRitZEjw08oB3+wu6uB{q447L?M(9r(PSKg;CNUmbuzx3qpJiBj5JCIBSrUkCH%UtE z_O<{Ynv{p;w<`$eiOnJl61O{H+>c~r7Z1r1-%_Mf4o*~7gGqHZpzz}kJXLSf8u z$kzP@WwPVc*lDoIR*$6xJMzygek6+Ead~(!Ake9n{^Q*Mh@GR2|VH zG0Ekl1#z$+_kvBkvmcG)9#b)OkBJg2KCY=04n2W;hy96c-Y3rEBtN6(dnc<|_>qsQ|Kq>Cvp16MD|3Z*UL zkgpdD3T}gU$29v+{+DD#-IW)Csh355;fWYz>6Mc3(`Lteq9ewu3Z#oEF9TPv$qJ<{ z;*hU50>#`MYG!_oaG8kC-EYbO*%a4+r?*6Yu#_>#(c1-Kd^~$lX|oKdJMtQE^p40c z91(*Yy;~661DN(AvRPEyqCx7eq7F3PQ#1-^jz!+yFG%5rV>&&4Aja#ioB}L;D6tDa z22W-_D&V;A5pJoZM*gt|sauLVaP^6zQ5bV9^7d&#nxH!w?ZN?_6hG4-b#GAz-ac0} z3U7`@-o7YE=oSMzG>6mIL4T=(>i$wKIQ&Z0DLe)yx%|2y4o*&YQlE5B(l<3&-D$1| zuisX*3bzTH{C-!EoAEhr`vlTHyZJeXKMq+)-DZ%1!+m9i!d%eBRgHoI6NxjrqPxEe zs(VYM;O+oTrSRu@RJj8s8ZP~~MK(IIAEaTr`g20Ccd()%xic&>cSu2M;^JU@l#32~ zhpM2uy+jKB4%1W$gPunY4=-q=?a9fZmK)pJFAW@_g6a+vDL6b*Qz;yJ9yvU!pfx9_ z+`-1){CKpCsC)AwFm{Z{FI*9WEFD`Aa8)fluVU{cJWj*ZZABp%J6_Q!tT`5$JE0(9 zT_KvI1^W{5Mq!YfV8(MvnH2L~9jD-B*x-uk&Pu!k6Wcuk#Cvc|l}&H-~*k z^#v-Z?k$mmyLFmM;m`BP;e`ba@0{>E1Me-T1Ls95sO~V4g2Rh7mBOLtk;6+08eYE} z8lAoWXxN|HrcUeJNw!?HZN5{#_HB8-H6oR=c6pg~1W0AS5Gm^P~ z!pxZciiVjKU!x#&XPF8Vu9X!sUy(z$t}7^UlI`AJ%melWaaL5!o#M5e?JTVw}Z4s%S{|!Yux=g5;*qzJ_!> zd|XG>4W?qK;S;J(VKOkOhEEnmH;?u<=?M9hj;h;C#bEPkRj05Sm}K*rf@mhz-Xk3( zpH(1rgFy!Fo|6>{YnDU4o-Zj=$smD_H!o zmo-e?Toi)2R}_uHT)N`$YC(z%1u#bg=hrk$-CPucxz`nq!d$xI@J2!MQ+?Ou?2^Nq z6q=}Lvs$fdpfc0o0B`SBS8o1}l)t2lJb-rN;j_bo`n{X5-Mi*4XKv?cEr zGPKa(OHQk@TQp4FcNBu%_Y{r7rDKt~_Y0C)T=3rLDEWZ`sap#&aQ30BP#Ciu^7TIPFWSo})WDNF_?+5Ea7`dPj0&2)VHMg`SPCQ|VDt)@~~^gMF-T|qN5 zdsjvGT+QEMz-FJT!KB{IV=biaF37;!zOq8$Ea>9uQ$bla9cHv{n zcp?Us>fk^aqC5HG*%NounuUZzWPo#2-gVApAaSTD5lm$aGIbau#Iq(&ztl$$ml0iD zMIE?0LX=>x(lhVTfk3xMnl@wqVVC-;TF0mu)tVp%cgJc%!64^RQqso zFhvaVbXq|eni};V%%QW>3K`){@fU$POI`$)R*L+>5;4fq=>-8#XVViQyX}FNPeb-I zG>o%VJp5^!K@@_qGZl@(nq!f<)qzAE)--<{EZjkr8voe}!aFP9v1blBsSv!KBZ~xU zd2(`gZb?DEb4Vc0r(^R}8mD|7r$*xkg4cTPFilUt9*Z zE)*q#tBgUWE(wGodfN%^@S?xnH9+!psftmp31V=!UK0uiIgdPE5oomH*LL6BByU$1 zG1XH-hL@{2F?jGe%6)YX^Tz}_@m#}W_0+^g=4%-(PwYN=b6o&+cIw3wV99yqdLB~K zMk>uWW&&|)P=)Mj5V=(%HBym&(g)$OKQ@cO2zQy2|Qa`|>a?CgY!gqK{?GVNv^HTZl-RVsW2Ci#3ifO@v(x!V*P*W8TYOAW_Vcl>L#Ml5 z{`9(1pHFn1?aV{)eZ8~Wu1^b{mgz74Fl49BpQ#|(sk6)7j_$^=odv zEe1fnO9z-eRPC$l)Vnm(*-zK0cWI`xzphj7(oE+7U8mlqna+W_PQ6Pror4OUfmZnF zd_S!q9;`roSCPAOkU=jwL{=!eh~-fKI6P9YYSjJl6ie5@_JzAaY4mff4pJ&BXu<7qs!nvundI{Ll8A-K z#3k+h6LeG;n~4}~o~Y`SHa(MUo)U;l8s?h?Q_EUI%O>oyk3Hj@DkEfjTm;rm6Zyeb z#vn^87-6)(F*Pt0PJ>jpl^UjID;0vV(-jS7EwISk8H{9>Y6sfE99y>xcfwOgPHR1f8s$Ru86sYE#WP$in&z|`-q`9|> zn}zSF2;2A7)MVF=Pp0pe>G@kjAJ9Rwup8eW`k<;K8x3y~eMlzKi*Tqn+V}4~T!GEP zsFy=kAJLU$tHh;>J|3v%G1M7+{>Qxd)ZFGmr?)4huxu{p!_|`lH`qzga!eGh5YX#JAkUKTJ zE(7XDyav3yA@U15u_$jcLaXUI4ju2`5~4LPjtwJkmrUluV5umZ88kj~Pvhx#q;SoI z=flOj0+-n!H2K)Vz~KQaI)l6?L~AbMQ&sPmOy(gxOZ6dxj)mixeNgTrDehdbI|%Ke z$qS$s9}8UOgV0oqPXw@CdS=%Mi!`4~Oj>O2&u0$>^E1Z8QjS~4p`+I4Lb$dA935N! zMag6vZm_i7Uoj|sIwm>WeJ#bE3pP8l+vf#f;~Rm?d=Q$9d@Fz}J0MB(oy634K*HQ- zcfUHHc&GJ!cEK(Qqc+&IeI+KX=(9_71#^GKjNiPb&VPUqcI6h^yQ9O>fhCg_+hD2I z2bIuDsbh+R1)g5$$U7|X%&TS9+3w*rm@5M7jj|r9aYRKclto}ueU6mLetwF3iOt~V zs0wNpZoL|mj@FfAuW`0}j7-gEyT|IFSs0D8-Q!dp*=CsS9xoH)e3FhhG%Pux8*~*p0K@RjQ6`G|YBa zD@6bLS{&qP6moVAHyf*75QRObqNUi4Z^k`WCj0p`{L(CIO$9a!yIu}%*Xl~L**HBv zPoer3-oh*$?9Q*@X5-ci!tMnXEyZtqm+nP@Y`*wFPgQQ%2Jkm)n7Yv@1e3QY8ihf} zB6GJDB-|bHQ@^KaN`Jcoan{%b!#AfO17{m#g~FKSkgq#ria6nrQr@ZXrHO~czpLQ4 zI|F0xLwx--lHaI6>boq+pe}dI3PoKkhw8Gapy0q89yYaaU%XetIA?4I?l(UQ!Pnx`})L3WJJB` zcoFQLM@4?IbBIB^=COj%j+W>U^tgj3`y0t@KE&kG8q?k>o{+l#V7;mmT#*GmE=T!68kI(=Dzbn_Lj#JnOa2)@D7!G21PNT{% zWQ4QC29=>oZfFWiUy6KgDH&0IB@*flHm3VpW>*_*WPi)q;|+IqqvP*)LbzH8OGg#< z*&|$wa0jafF9EQ$OZF|HwT%xc_7ixO%?`W+IB#gc-AiXjsRv4Nx7GZCP`Ce`0=D}g zfy_7DplQnw7QlAX`6FLNoMEgmXS?PDPPIuWNHCQ<45#GmCV3?D90 z#fLWw>JbuEd|b1j9w|}92Q&-nQJfmbJpO&zM=KE5SmYyWltFVjMpoc0CLJ~%%PEZ! zHflOfMpRt|5tuq&fB#~cQ3WKH75<+`w4EGeZIs-#P z?tDlGw-p-1xhnfQ7ecL8Dk6!sj79Z2T_I_GKU1(*Y|qdnlw*J(ai%7r918@Avos0i zm>@{3(j=5)gCMb5lTeNkg2dUHgmSD9B+lg$Bh!Pi#nEVIjRvW=xI_poZmlB1TbyT6 zi#tytRa=}_ur2O1tJn7b-HTRM&7KR8 zE-_y76BJ-)qr_%zk}CjrGk93WrEA0Y2+^7m$A*nfC6k#jSgOap3_8$oi`%sRai0*a zS#WGvxW8mF3kFLT9$?T3T$Q#>gbp?jO5vIb&xebL1TM2dX!7we19x`9y$99^jYS?2 z<25Hi0ahNB*vyN?lbOdDe9(N_+?t^^m&e6;%}h{$nI|MRGh^{&=1B&}n)swMLyO{1 ziSe45pa3&ZOKfJw;>pZ23_jEem9e)BKPv)iZh{2dJSVZ48;d75F9x`|d=w7A@w)#@ zGC;P&HQ?uEksl0Y407~JL7fWLbyuGPt6yDM^!&?QZGwIITbY^&4jMrT`1z6fFu?s&2PlbA?fZLl9?Gb=Z5ASM_ zx}~TCS6dW~!kA-`xA#gC-E3&R(Rt&24bsJ1(1EuP6phlGWs$cJWm406qw~o}8e|sU zNC)0NRy1U9O}kG&DM+~5?VQmG=2IC^_vJO<>NAmFcp?T>>vM@PiiiA%TJD7sc74AF z>*_AigU2r`T9Q-GCcj@58bG0?peF(;%{?QU_H!T+s-|7>g=( zL`lK~%fEra%%YA|5M7*k6(}4fE0n&7L$;1CDe)xiPUgp`m@d|$63iW|sg(B86Z&x_ zjpkmia@5FFm)t{v-v_#hh1xwUcFq(im~b)+r?g zb2Vp+PVc8Gh%UCg3T&MwE0nf~L$+3w6hG7JnNMf-l?tMZEw2Jwr^^bZtvG8uqomL@ z&ee-f>}RT&F4m$F%$=pFl=d8t>b9z+(bUcvq%-_#71PCFRD!{?HI>q!r6VxJFYc4LTkfTwBs;2IvghS?75wsEflW1&8NrDy2imBZn6Sni(2& z%$?^redRZxU#w!BLEP@d-*+RZ!Q>^HQZUJRWb)FIhG9zhj*0y)+sA#s_Bb|M5aFjlMUk7*`B)@G}3)Ya$53?A@AJ zs14^)eeMmkk%sK@J_S+rSct*l{jyN-mvhM7LxD1c8NQi?((6I-9hCGl8xL1diAz>R zNf0g{(Zzz((hRwMJW|aWYo}rBHh<#m2_2++735&`NmVL3f=on56G^Kb& z!#Hp3`0JfTAy|7=(I~t*7MXjkAYmpH*Klb3{0`>v)^8clBy+)~hrdz{}> zAkH1TDa1F=AOmmj%L;`v%c07BAXCIsvXt^eg)g0!CH_YRzdhl<3uj;d`mv1Yvd^3d zit>rbFKR+*sU)A41pYAJX9}c?DK7(8pUVoRE#i=`FA9o(#0xE)Rwurc5p`Ey1g5?c z`Gu$WoY>a|!9U^!OLScOMn=>vc@bFpR^%6!;&Wo(6$H9EXs^!L2blKRE39(6Gl_-N zO$8aa+E-R6Yz19>SXQ90`*HVIAl-b$J8}<@6$D@5p4@{oig0!L5E-DGN;OccLq&dO zDKH?q)tti$0+lhnx_r0>sk@3g@O6ZuQ8;rf@^)lFip$7uLHZ~SQuh{h;O%Hdqwtn4 zMjum<+MQ|lY&NY#A1eduzPtup9VhY&PsE^V9bXV8JGM*Epn}$)Pf#&+Ux^Z|ov5i4 z?mUkSo+Q%RQ|`_a8aAG+V!9i2N-%herXm_NJTiD{K^yEJ^t;5ZNuQ=->IM@f7+j&L z6b3zy46ZC_cz-+AMZyg;wD@~^1ywhhslnzMx>8{@a>?qM1r_69dtR`Y1J4oxb$?C* z&Q?k6!jr+1o7E*e+?3WwJ>zT{(Z!DwfuVCme(A_C$kMq5p>1|$YbRGE>JDpEP~BJ} z1#fFLmBOCqk;4lzn!Gl-PQ^Hb!s?_MnKCt)yiilhOr|_Cc~MD=i;I4h@?sU_T$YQ_ z-eVMl$4fMw(xc;%$Mq%6997sV^kq8AyJV|4-eV#Llb5SHrAyBwn^&krb%H{>!;9F5 zB(Bs|v}uZhit->z(oxkCsoAzrIuT)o&DgP??RU8kvpYH=PF>-vJW zWT4Xw25AZU1{G5`m?**Ejhaef(DTUPO$BXg!Qd^LN@39R z$l!)R!@GR(lAw5t0bB5H|GR8BUAvL#*@myepcTu=^(Lc{3a^(UGg?k}qgt{f~tavep zh*e7^Ut)NvW-0zs#m);BvHD=6fyhbN*Pt`=DIp6=|M?LfB zC;#!|ANK&-_oJSF_y+_c$o}51{J!8vDC##p4=%uWM#m?Ia3}9T8`CE_DcA0U#CKi- zPq2+oPRx?nzhK7Vp|IcIV`Ccw6SLh|K*f#4@BL<@4kSH1lBO0f+m1%70n#CcG&C?< z5|C!&4<}Y*d~}w%h5!ZaD5BvqaJ$oL4vg#Md~f2CY~M_K&)t{r{Oew6uO@M^KuKI| z6-j(S7yX4@;)}Y(7k7zotHk@eY`>3d+wbGr_WQWD{XVX3zmIF%@8jC``}nq|A)jTM z$&#tj$=Nm#gB_46X99y-prHkZv_Mk}3~PZUT3|#AjG79pGZnzs4rf~cK*c?e-^D$S z-|0AbsmaqG$M^NJOg%#Ot>#=|P36#}r}Beyduminj^8QyHD0f|QzuJb(H!k>_b=aj z&mWbCd_)$Q2 z7fug^Gst4Mt8M<7CB#?B45ft|hf+%BBRh5ii9ELwsZ-fYIjLg~ zxOW&5N}y*-(&AJGsJLspRdCg#BJ;vU5B;(-Fciw6k&E*=>0yLdpr z@8W?Fzi%h?8~nb#@_S#e&{lx&>r;O3SAJih{Jzk%xMzH^8;!p2dBOh?1r!EYwt`AP zYcqXXqv@j}z7>nu|8K2`G(h_(Zs3CN{RW~{e--^M{C)7d|9^9byn&&mX5ujPJDT3k zbnSz^=uUVt+8@u8!zVxMnVz8>i?n{Bb&KEjSW146_I@#{{hs^%?T`J~AE&0<*Jymt zH<5P9DsQ<#cbEPiG@|ppV>F_{Y4c65-viU@z3JLiKIyp_T>UF{)_+vvzus?Rdu(87 z^LxKjly z)p`ZwU4cOUPM$?4!jTI%9q#QWEjaiJR}uczkG|>_{tL8rD$t5hAU7DG%Qfxh zShMkaF)Teh_#d0Zo6&|wmyWhawF^eYIn19v{rLMwJ@)+SPn-OAf4bzq|Mqi9dBmU& z-u^|_+17_z;-cGhXP{#W*<9Mh%NYFzClwT@=H<#UCIK`}yUL4CHg;+?hi4jNO?+8m zwz_h;{`q$k4k0&r;|nh%`HdLBw=G^i@*PChuCEgN*mA_6^7sC zMel#bN$YRDcuafiX=!6e%^j}a_s%7EYV{aMTl=ct+7>>D+!>`q)NePB)sFdelzP+4 zHzykC-{t^?8S?M|y8OSzYJT81cf?$oYd0s_v<&$YL{a-S0QXg)xC$GdwgsHP)O}hyEw_0|VmN#yAr% zI>s$HENp@AIpzYfwn=y!SHO=f8y=fnHk*CV`#S5?)?Lg!)@t`kdKbEO?NuaXyfe< z{~X#E(vBah-B9Cu0L?GjfWp!xw3n6*&GxQ{Q9wbv%+Qw2o@St+UHKbdkYN;J64xBY z2X+d}h!caYp6#Z$nsZf(G61yx=ETs{Bu<0vo`pbM%@KGYi9xPOA)QG)>^n1z_fgK^ zy-LlVzW(icA#>wzTDZD2H8$25UecN|mq3;dj7>LtdiU;M*xS3H7cYmx$lHT(_eqKC zHMm}byM=JZ?r^KQ<1|j)KkeyTyd8ozerp+@X*UMOnteUSMMlKiUo>=oPv1hAbE3C< zb4weOGv=u*)M0#dqNmRy$k>JyGdkfR+b?n&cL?!;oqGDM2Da?Z6yTEpv2a1ZO#{qE zkC`y}T^$#hy4;;aP#jxfP!Zbno8hs6_J}LP%orZ3K-K!FfIX(H=6}H5E8_YsZn1?K z+>s#`$h%2|`5fN8z$)h5UZ3#By z@z5Jal#YitiQ=aB6jt=S#XvmC5qZxukf%}z?|BP*w>OxVe>02^l#RA_+_h)8?f!+= zQu|*=cHZ^pzgoU~h`ImXYMZUL-fGUAAK=!~X)FxkyKc=POyWm+5WxQs+j`Cqw%Pgz zTW_=V*4u0|XPcqs;PjH7t>*k;V{&46bji%%K)Z=skB3^#cDrXjy`;!BK&&%i%!x}S zTg{m_)Lb&tnVe}249(x$%*^n|pW*`pf8MvSZ_)Psix(~E`L8{F+x7l=FAnKG@0=gt zIu_-CnXR{hi9djeKip=Ut>^y1HU`AJZN1GO0D`#lJ?DSGwU2h&oF2gc58(d^`2QpL z{}I6d=?}Nr`hT9g&DQ_RyluAb`J-*N{$Kxin>qiRCrs{uTlL}lfA>G&0nwiMe`Yr2 z|44qCnV23M!|(n0{fFuAW(5JiFTn5rXZpLTE`DE#-~V)c!J^*nX2vH?ky?0(1j@6N zO4fri^!9GIUGMhWF5GVW-USP{U%04m+y36|f3ek^KO0}%+uy6Q7A#)85U4+&8tqAH zyXY68rd$8JAH@3ncQcLgAu7(lM{)l9t+$!;AI3+Au;qLAZV!ilGBw&Tb=bRiG5+g6 z{e1Vn#WQ=FWg4E2-e?6$|Uop;%D zc(>h`|2(jqt;!&sU4FfMx4rg^kS0`C zXOPzNJ$Bn`_n$3~m?2=!&M;Fu@4oY|m+zStp#ji28ECZKiW&n5uSK}?x457C=R?c) z-1%pJyZq;fCsjHx#DB8eF1zmh*S|6zT-?-Y9pdAA?YVsK*7Be2wfi2s{5^|b=;Kqn z@3PzIu7A6H_g&1ECbhiCBU-!t^I@y62`rnziM0-*;C&)|@$r3s|pyh`{?1{s_jP9XFE*;x$I z?xYZUqC;_ce^Wv*rryy!JT?8{}&W)O_+g2+PJ=5sj0c4yjy7@lE!&SeNZ z&JaW}Ix&zn41xux;mM`F0fv*gfvpu`^gImZ!-&ej&SS97P8h1UJ5dhZ(csQ6aagTr z1)Lc=8QcXW&gg}_W~gCs>q?x_3pg|2Gq?*&oYAAFbj)_Z9^o!3aYoPMXk=&fF6Ow= z@g`2_u6i^OGO$Y+Y+}-^N?_S*U<{*azuRb3YT%a&aIA|A{nY6imt=Fj0L1e^t&Z1p zLr`d5#-LLJt$}f?XUA(M@zo4O%VrY;IPIC{OKBCG<5L20pBe}+Peuym#iixTjM@o6uKt@#wI7H2C2Ku-)om$_gv6Fv*(YD znL*sKGB&uwIOH}(bQ`uNuscdDA_jXe$IeIz=BF8Y{-MYJCy7AiF;Z#&WZ6t#XGgb_ zLKPkl!G04Itbk_*AWsC~0v%|EB~J$6LKO(uiv$~N_eri^3PHtH2R!5I2{vmE_Wj@JWq+uwpp_x`*QsN4NERLRAg zL2CP4$~P&qrDiDkRsi<(=E!VQ7f4Coj$CSwvB_1rw5^*Xmor)M9O?szp}_ z-i_Q^bK=`C?)oiJi?y%154KHIpZB5`Yl6uh#Qyut;rgY{_jw4i8b^(O>U>`WAS+-B zG@b9u0Mx4mE7=yA6rg?;sH`|?4%7L*4nVf$NfrBN@;%^kd=sd8=PRjH@NWZ^b-u(N z%pJ6~`S0P;F`TFAOfrhwa@)zM%AS%AE@5M%ZGXZx$80(y9i6~vjcKND@!)6*qx0Y~ z1q?T2W-wAaC4u4IhW5bVSTTS-HO1f+XgP#rR;3WL78iy~#gqWn%p6clY@t2JRj{Y!pGIYeVfhvj1EbPPV>}+&`a%Q*#ZoaWBL$E=Q%}Lni!U7EZ;RCj3$sPQ`~! z_|+I59*)}mcE7%sMDsZnHM`f7@Nmq$(30OsqLWM0Fp=Mm;ZeM~EA%)wt=k;KxD7rH z(;j;#hB2)fP1w|6-;LpAJ4`20+Fe^>)M%${vi3oYr_*q(N1Kv;m_(BqI4%~L=tnV{ zPQDk|j`R&hN3n7l4hJ*M@u?0bMsbW|&I6;k=HD4_jy55=&o=Z+XU0rz&GBbuyp5ON zB`obM z8)!`^dj(C27)R!eDYNRk6la`rr!=QfUzk72Gw=xa?NN+{YIL67!OTvovaG4f>Y zAdxt@w~{!=cn-lOBm#syf18=GxP>Kjyxa~?4GfJnaWcl0oB1Y4|2bn;&6EH7v%hTb zx$~aOdw$&G7s7}zLmJq?%M)EYbeI|KBm)0s26J_D;<^?78!< zKUMu8yvK&Zd${=|B`la7U*K9?_bgmPApYB^Y`*!IA=-(WUgT&HVUJN}2v=me;QZx}-YJ4(d(Tb68e0p`CC3piK53 zc@CQLx(r&J7FySM={UKb-)Rj@w8uv~Ztabd6u-HAk=EPe@^y#y%^up{V+wG7>2k*G zd&z2%9<7(ws#B}>YF_-suaU=J=z7EjJ}(wdM~CLqpQaq{AJm!5Yh+<@orhu_6;S%q zK;1tG+UIUMG58BTerT*QAOCN#^cRq{{&$fFj1HNbisswDXlM9;x_w|5c3t($7#x@y zUgGtzo;x4^PfGN+lkw}kPKbx>BCk=pG$`4%6{RWql^3ZQx)?RV^5O{M0uyGqH3OxBIqmk2J1w*gJ{)XJ(cz-}UFa?LO1~%^saye)h}8ZoB?s zm%r&TH(V{iT$PEOH3zrpjnG@<=;lT9Iyv)?t+rlc?mS#O2e%8IHwX6~9yS+K6Clkk zhsKt@`Ji`t3@_H4+rYhSxD0_i7<}B`=ztYQ#E+QUMx@V&?ClLUbR>oPlTcs7T>Sv+ zsJTs)|K#5|r<-tp z@>9?J^gsTyYqqxNI4Z5e4Q9EVgr{0gj{(2h;OqLaeF1;&Ts&Ur8qs|2+_^z1fm~yd z3v4-LBw7(6*Ba!)8j^MoG|w~0MKvUvG-;l1kc%rwvsHw=z#zA+A-&Ia2H98Jc--1+ zMK2_1ZR<_vqx=^Uw6^(XZxQt3xp*|E;^B12!K?t#irrSkox{wJkhQH^AMUvsc4~T9;Km*ZZybb zf0jsy67p`!9$qD0vtcewn$Eq+P%O|m&$+l&aISget0v^z(tV~o*S0(yPwt=F{;7E= zs-kKJ1Z3}lxn=@UL;Cy=nti{01&Li`H6Nn()LVo4-T5#Ei@-qk{STv`tWN;0c0;ZX&7rQawq~p_&0-tEULstUyEKf104fHK_Oc3_-(g6}*PC zP|R700~elG6yt~d=X@P)bN;W>Bc5fnr7d(jOG!vReK`>MV) zm);kz%bJJIs8zpgk?zg)&PXIv3&33{rhmSYLVZJI(EjZR`f3XGM-~RfP4q_fwG`?P zEeyKIs=l5={ppWEx3#Koq)>nQW6YFLlA6Xf6z^cBLLj7=!K?kks+Xm{lTh{2gDKyywDb($OkLETzwQh}rmEEf!6L36?06Yzi^Aj7w1AewE z`B0DBD^}oBLQVPU-25DcQ3jRyGeTh(NLt|__vKvk9g28BD9*6FIN4kxqMC%{e9yPEF#y7an1bwpb6z5qMnE zyfxE<%M2A1T(!C~UAnujqN?jM|wzh*kW`Mc#q%YV`Hr#~`p z*R{tEwB*$WgYW+c7<*U*=4^vmC}QmK5SVieW|4@o2SQ-ZHJHUB#vTEISz|EUiWqz7 z17@wk^vN6MmI;75k5KZa^@VLapHT9~^@XjwU>+6#V9G25B!%>=0?4**o|*XrLJI&1 zCM*a5bm2TR=?94B{s}0o1psu>JU8D54rBT>U%C(gnt~MCszr+OZ*UU3Bcwo#e4$1xu^LqHc z)?iGo5)*P=HxILRK+N1dk?~V`s9ZnKeBucZGiy&Eei9GJ4F*z0+(?Zb5cHo^#B?WL znwtz}I}u~2_Q-Uz-MPk2xi3ru32L`kr0MiBGIab~=a~sGaArcBY@qqod%MkGOesrD zDCO-2V|H7K3A=5B!Nke712=a2^{;o^mFLc<xum^ ze+P4;>5FC)%f1*k@$Pwcc5YC1nx2Zqi96)(nP(>F0MZ;ifrU9cK%30&+#aBEm)qGo zF!vfvA8sWVKz(+i4%B^wGWJWUzTp4^O%ssmj%+AFDdz4`2XfDC*AQiC32sWa? z>|h+4ufCa^Yz5T1u_%druAf{`HjV9g6$jQ-k3*QfhVIdurJCZ>H4h zzW3Cy@83$P)qU@&Vc)-HUOg4(Jinl&OAF zkE9<&E++3O+05k=qd_#z@j?GE(oHi6poJpUPxnFm$W7}(a`XEnS2E)V^kWR024^Na zOJ;`KfcyVg@~hqcdgosyEFZ`x`4IRd2#m~1AYV*?z+);9!y)6{Vrzk45V0{qJ0jE zQz!WV+0(`KEjG>OIu?=B z1r`|B=ZuifVkq4W0b+Wg&$q3~cOwtU2_p}jn;0jgbSTPsa{%F{-U(Y!x~uY*JRs-u z9AvvS!-rgipiH*~05-Y3WX$HGC$w+pAvs&*A>RhZ2^k%Va^4X@KN*v|l zlZE7zfrgBC<&2QfVkqCn0Kr3mji#$-A07Sg<}o>ABqHTKj1zJ?6eZmhKtG9OoO0-t zaBmTm(w?q2jf&UrL&euB2>8vz!<;o&hJQ}#w6g7Y}zgo-$M zD##N76sSG(`{{iBBn!zY0}UCU${8V{#ZbPd0|fWL+J0powZM05vw+LBAm8PV0`#*f zI^;2N%JN(q7I$%!dOpKSyEbB92w0rI{eiZhj_fb8kX)@m!#2E>Gs0F_3~k4&4$_a; zgW_`|bQq$e&}(@>N)|cD^?HVPsT_hby%7L-VW=Cm(c$OKJRoQC9AtVc!-q_SpiFNE zfSIY&CeevwbN0KO$1#xRofI9im^dYQH-?8?Gov%cmh5*WiDe+kdnr05L7bAjAHq28 zx-9n99v|cpIgckH(T5p6WFiEm`X~VKZo4Jf`Qc+0l9L4*vVD>>LOP3~e4hr$Pq5UA zFCMv5AT{;RilEDxjZFJz5-PHO&RHR^$5G}lI85liT>8s`Q+8v{`KsWQM`+IZy5P`I zH5;jN&Nmq+9M$bZr#$BBm>u@4pe3S=-!V>BMWCpN`~0yzl?5)nL?s*KhmbwV?aLWj z1%r|OBBQ;GX3_3&PA9DW%c$Ep?jj*$^A0F@aRWV)Hu1m!OdF^@mmI`nE;VbPk%+_x zGfqhBP?Yo#1`^w5CVMDnNOjE^hjE6~E;GjAoFTQ!jB!ND2yK!M!$-1^D;;Z+Pzw#= zsGN}&&bP;-bBI>9AbAYKD@6(cT4F*)dpMr6!ghHawTP1l z)*he21Rj6lT2eeopIpRT;$$Stm`HpIXHnu5M~P46u%f6b#dh-33Jx!9$yrfwczY~4 zD;cNH7KKKYrx&qWQHY76oWWVFD0rf5k6&W-i^D2K@zQ4%9K9%>v#Q|eMe&@~jMHz6 zLTA*oi&(8F#6(ff;Vf2^ep{4tIjm9?FTJMV=tc3IwFO5nisziiI16l1XsmXA5vvu2 zm?+8xoW+W=z!qg4hgFK=r7tWvdQm**qJpCr#d9uZoQ1Y1c4B@>5v)~(sHn=NoW-iL z&{kzVhgGWLr7tTudR08<@`9sR#dEG;oJFoGv>bb75v)~(sHn_rVis#(IINRE)^wW&?)*@J|3Q?;gAmfCBI26_6AqEo5k;y*H8B#Ga#v_~|l_Fz2nlotNf-lU_`Xdij zD&Yq_k26kQ2{&SUf`Rl(c-bd8L#>2oJjEGmB|PKloI#_Np7}IXdxnQ9mGGmSXBj82 zgd3(k$3S`|yzKLwp;p2(Uf>M15}xs5&Y&Sm&wLu6y~IP6O8BA8%Z!s(!i~*dVIaK{ zUiMYaP%GgXuW^Q23D0;vXV9?3UoClq$10`pVK3NQO9XQ-v{jL$ejErn-%o-=6Ffon-L=K6xi zDy8tll`k15FNGU#eZ@d}DZK30oS~M&Grr*rwG^K5ZO)*f21-E#t?ziOQVKst+2`NU ztwLC3q7(LZc`4i=YhMP^OW|er;|#SFp0Ph?sHO0X19HapZp=w{CmhIQl~NE9vkvWIYnS_;oNlrz*)c*YUL_{roj)(Y|GFkV$m0}kB1V#ZiUN?}(K zdJl}hyQNeB`zV1;wP9!o;(@UM#$^EOgiiR*$#GIxbCN5-$?*a^I7!gtj`ANzmlvECP?vFMz72vdXc^6Rg9n( z*%Pj21hvSXa1A4l; zSJ`Xc$p~tdJ>f1!P^;_-8yP{ZvM1cl2x^r*;hsovcXZgVVs1)*clG7RV;FDxD77@i0v%Zdm@KRtt^EFC)!pjXw;8lKAtX;s~1=lKkvR@Ljhki)gAdiaYuT&t>wzm&tZ zs(Sd#Ib5r%hrg1-X)fW)hn%jzahuV(VIS~GT!rtRut}9FK1?ErBd&}obtv4XRmb&zPJ)uJvRb-J3 zpsHIV{s|gr(nAp5gYe#a?*YOQ-UEauytjn+-n^ZAMV#ERGS}(;q?T|aB7b@E-Ww-l zc;y1&tIWV_ z7YJWv2Hr>jQ@(Sq-nUMwd6jwQ|4t+FD&sFJ-m4{kmHC(-Tp)av8R+q!hL)(|P ze7pf_Z};Ms_JL||_tKX3L27UJ!j|^IYH#JO8Y3aN3SaFqf0xEUu?9FQ6+v^`4?YfB~ZSs z`1`tXVhCSWKHhk>M=vYw6Vx8Pth7&5d-Sr>K1uD-%S!v?(wVXR1AVS!ti8_UL7$eRgTjM*`_@OY#xR9980% zl?MrPB~ZSsI9{12hVW(O^vK<&}XO8Y{!M=vYwi_{*yth6sK?fDEKy{!3N z!4g&Cmz5_6OC?agtT<0uCWi23<>M_^d-Sr>zC!KM%S!u7wMQ>2?W@!ty{xpa&Gvtn z4ivsm|Eqi>@RL*8ysi>UZw1zAB)_svPkMm#9}TOe^|fvK?QDC43$(ntKCsaRT3%lt z*yI8&udomN>;f&Xu@7vPK)$WveZdx|)V#>N8*bHzyvTTOuuU!Ti_FK|?gHV9%)ky8 z2w!9dcDg|LA~Ued1;Q7Zf!z|wH#wdy>~T`ftIV6@UX94BjJFE=)DpkSe9ZkW5WdO` z9B_f~Rc7Fz3xuyS1HZUH_$o7SNCNqu$9D~fomBHG^ImyGBl0Taox@SJ#IG_R^Oy^S zuQCJ2T_Ajw893nr;j7HRuPzY2$_$(=0&=*0N(8*Z#edIa&BJr))1|w3adE(Xrj+f4 zEl#-gq0Wjozox|*w|Xy__lw4l1~mQ=o?=~I^b#(?{&AS;o4gmadF_oK0VJ{oXO3$j93Pi%_CHEdv=vJ#(H>PA4awo2*Xx=T@J$h!L<% zC+G_wB)IZr`0H%@+G-W37-iklNDn};0s|@MCj|M6KklA|`+LM?` zqz~e+NZFA|J^n@G45~qI{OS{+@_*j?gHzhGs#JpY)I>!yPsa6XS{lE92)z9B*S)9 z>5!Gb*JeAZJ*AY#g!#}`QQ@mN2!;n(w@dpf-Mz)#mbI+X)7wj7wLnYN=K&-9aoCl zxl}u+9~u+&lT!VpL&vqIe%{r7n_}^v_9v(CDvBRE`Miv!>sY4|Lsg!9CF|AFx_kU% zZg7E?-QxorU7%(6_`oI?XxTkJ@UsiF>>eN3Tm`=P^6O9ky}ii!yKjqA@FKg{xJsqh zc&jF=*VsJyHQuI{mI>5&dgViIcYZ&Eynl!D=U2G+fgkVR>HPTxE`IFC`*$_{{LMi2 zd&hQ*z%R(+7f>}WtoqeJdrEinb>goE+S`=*OO86_pZ?z`0w~28%}>`N>GQF_bT=vd zEk_4Rx&3FNdZ>fqZTnfMyuVc5^!_*fW3~1*Wp}DWUTc31&0xBW!!A=@30(OL>xeV8 zy&iekqdw8@sw8o&O8n)sPrKu~>^H0(cT)Q=fGU=*>Vzh$i!x8Xre7;d_ilgb`ehdq z^V^G)En<6S5lz%nK2>q)%jC0W!#>12?ff??=bQqlo+f-=1{3wXhKyNxGVy{~_(m$f zySeD3T4YWpAm9;3-iBFXMbX{L3wTD%)MC+%C3TK|o>t9*E_^gY4S=jw*fC%kbh$Pa$(p_;HdZr9E zIUNXn^`}q&Xqa58LsV#kDKd#ORQv{_Ba?R01v3L}oQT8MmmibpOY1|A=2B zlCNm7Q`+OIRKhLMM1?a?#x1QZpMKq~J8=2?c9~P!jat*$Jee%AHxfy;NQHBM=dt5ONKRudJ@JQ?>>Wodk=;N5cm z7GCF+_P8pQaO*Wu;mnh98!AiV6AE1ZX5Q$O_P8pQaGNwy;mnh9KUbEVcw014@ywHXTPsWBGfH0mR@mmG_Pi>Vc-u8m@ywHXJ1R@#Q%YWbueQ@k?Rix! z@pfsV;+ZG&c2}0h=Tw%?9w)WuRk6g|tBHzdp3K`Cp1y<%#(S)R+i7d{enjT`Q6A#RY1dWP~*LS;~v9Mf}Ik7 z#mbJ1I#U_Ce?wB95@$sK2)~DvAVd=9TaVF1qH-vqu8Y4!;o#zC zW%&Brf52Pr{PliI1c2P936aG4t#ntIhMtn?XCg|OpQentqe}Y=N{_=&(_QhGBz&6g zl?Hs8?6>dUS0zO8)AT_6B?_OWhou3Zrcd(C<&i2Oil3&(;xAG7G(F3Pu3bLv`h6Gu z&2Z110#@;zE2;FkdZCF-YkE>X9exy+KY#r-K4bY!)+;ZyUYtD`bBXxcWeQ|=W#*g0 zl>YVy%v?@yy%aH-OU!pJQ!ukDGv7B&UAuhy4Vd|U{lQBCv&toAkN>PuVEOX%hnq}u zWo9p!I^|C#zC!bK@9h*2 z1v0xbb3kEg{6(JiO8!(1^isrRE-?qWOu@{q%pBY_HC}8m^QUr%mjY&$OU$7z(`1?} zGlyr>S6}8E3I7p}{HYw_lvbjo5^$s@GOy{$xKWiQb--74=SqKV-}qFH_ELLbGnX=B zT&6<8m6>CkrY;pSkGpYB35ZN3;CM|mdD)Y36PlK9|5EXC@l5nm0IYI}ILT$2NONW8 zNM4Brz=TxRI|KacW&5_^4%ymk8VwFn3d77wr=E=DEP0M%b60LIb zTZ{!x32;m$+(Jz>aoLk`iz>@!-=^0Y$42>kf3cI=^Qu_lEzv~9Gf(C%tt?-ES^dLm z_Rn%Hb5eU=6-&J3ny7f@$-EVnrEzM?>&tbz(n;-kRV?vVX`c;?Bx4V9((y2eid{+yLB z(;7(%{=y)C9c@;j^=Xuu^encBKR=1ek)OlXrs2E4@UJEscaLo<1SDjVf4lgbq=qAt zc2tJ+B@9x&Y3x*?J&Bn_+9m#qlpUG0r!u53-r{}6UimmU#e8YJGDsxMzS3P$8hVE8 zFJ<{@fX4eheW(NCEq@N6)q7C9<v$fQd>QrfFa zZRq(@k5+P5V(gbi9upzJAd@i1OM8WB=oxb|%b%rR`}SGa@9fi-zvfTL$3gj|yqY4D zFsDm@#!%0gGnL%E8*X~`qMa3iS7Se7(|FAqkAg^|oGaZGrJ-la`BHBA^3aF6AYT9F zq27z)^uZVzGrTC^XBuDGj(p|hNn5@@IIe1n0P}jxV z{#Bv(hIre*D)ip0yxsmCPdD-mxg`Rwv=~~AD@7!I{(mdo)s;5%{Q19K%5AT-`A~Pn z+wMx6-n*6e>(Bm(zs<9wjC-o!`4@*B+cPO-tAGqBMWd<+Ta{ z44K4wBmO3;;mD-7O~Y5!;cDad`c8#_giP|k7k`t~aAeYlrs2zf{0jd7cpgbT{`1DS zdwvPB0#<6!vO}A?{a3m_XsSu%W2B$gXj-~;C(?clxR;Z_{F@dcgXt1`Yo6`3>(-ukix)lbD}>;~$G}WD|9mi`wt$N425)1uXqb2O31`j{i*{yfgv^4)>| zy~Fqxu@=oc%LE^DXxs!RIvam}KHr2UwTQLooK06f*~c6j|AF%~*#3aebpEeX@w)}5 zw`gt25>4b8J_d5rmmVhlz=gBrUjl)(Gpj|bCG+=3%=R%y#&6V^<81l&B=9pmw?(W) z^LH%F^D&3UZ=IO$Z1`1<_U3s(i&%@!+4OoZ^f8CVZ=PRbwy)Art-GTxbqc6ub(N`v zT&4*FR-Tkkrw2`o-ceVm5Wt#u)Rp3IqN+RUs-{8jsH;^7NXiOoCe`lf|9#`NFu}Pug~FnD)a_0IuKcph57oS*?$AVmtL~^fON+as z?(!Nh(BDzhH5PZ&-7Z#Qt2^pGn7(ejKJJdXzeTISaz`zr>BT+ZV*oc1`2{}cY~>yG zmlmy-%sc8KA9G~fQ4c$t+)fCZiz3CKC%jzmq=~H}569%k2 zDWA?4nijpI-c})iHSef*#NR|!chtL0gWgf^sSuEwchvjhZ<4Az>Vu|%_eJ~*ZV#OT zR?8hVz4%O~m+_INn#ATE^>Nd}8zb+iPn-m%yQ3x|gNgW5GfiUij{3qZUvy7Ny`#Q# z3V?b?ZKe|Ll_m^VJ#xyYpQ9)&dPjZZ6yVA)%luHyJL+3a6u9b+`mVINJL-F{@dEuF zHCPFMXW{h zjylfA92$4j@y;f9)CnzOEt+@Ki9Y7gxT8+Vwyup+U%kamRRPSRxXMiW{7w^phE2(Y(iP^D&3UJ#Hs#%|p`WXL?tQ)|M>M^cA+-$3SlS z(!->G65H9zd)(d@t(MGt+&&+3WZdKSJDc3&4z!51Xx`%v`j|uG9`}p0$vy5+i&%^1 zJ?^lNIW+EZ$IR9^E!BJ6aTUOndt5VrNrAh1a~t-OxzEtL||( z3k&a4yvN=0T7`7?xO9=srmOtT#R_cm9(Na}=CNh-g}v9JRbaWtHC|gzz{I`pV*oc1 z`4xWPY~?-fVT)Ev<~{C_k2x~#agUu%?r~3A#9B1(aZi2Bp>dCU=4^70d)^|}qIr*d z;bRVsd)#Z-n#Y#S&-9xXtu0xi=`;P-$3SlS(!->mt#G#T9{0XQt0nUu_rb>;8TYsz z|7GKpqU#rYLUND$p+&4k^B&jJ#~d2>xL(dC_qg6IVlA5YxIRAS(74A9$hI!ur2i`9 zt3Q2(ACt&)V4zb#E$(uXN}u9En#jPWC*{*mQdE}oVt4NLnf;hV-UCCt1mGt{SvDT6 z8BEBbE>tn$%Fy93rS9qS8Gi06U*ZTA08A%djsI!ZR+n#@$;2EfDG=evyisB(eQ50Q(_$3Z>lB)hvu6m7Mx$@pYE9Mlo*#&>2o(j6N1C(kaqPL-nh+d1ZjM;caQSDH<~k+DvD@ZpLU8D{`C>t<<)6u4;FK80K3k{>!J*3* zi6#FdhxjR##ZHNF{HGC@XhLxKha#7XCI91pAN?->7b?q~665$!1}@ix;P4M9t`Lj; zGkED;UoNthUWuOm zS`Cyfv)*MCik{h^CKQeR0>_PBtAVm>Ho1&K(KbJ;33X$?&vCQYYM^YKEiR)_bk0^a zp>*swXl?Ua4V1mJ-DMPt=Gmbpd2_YXYc)`|&n}lyDEeo&novNUas%!0S`CyPwAW=6 ziWb_ZCe%=;{2ph&*J_|_q603YP;}8jHKB|;}oYc){z(IJ;nC>rUom^$N)j{WOe zN4yq8Etu|?M_ops$(0_WL&sxkLL=GFSsnLU4U~;^!etbSM*3AveAAN~>7>_cplqa5 zE~8L1(rGoJk?gmLobg%>l#O)OWfY1=I;SQylKs@^$Mxkh=i)un6*}o@t z$!j%GHqvF6Q79Veiki?!o%6e)t6r;tvXQR2j6%^!*VTkZvR^xL!)rBAHquR(Q79Ve zwwby$mPNPn2k-Bw0G`dCa{m;`^lf@qQbwdBJw*Dor(!7g&wZz~xk5Y=_s;`O2n~(! zP%M0l()bTG9yuk(u?-$;LU8DUCt_h0G;mLy664qd&om)8w7_$*pak;%dEt~8#|C(* z3Blp}|CLzq?VtD0Yp29Ge(%50gy8U<|5hyc#?Slbol{~Qzw6&?LU8z={~#88%jfU- z9{*M2^rs8H`to;c`q}z_DwlbsrL(Z~+5SNjg2Q)vPqE;eJ-_?t<&^m9_?_Nc6N1C{ zc^|Qq`=_r{VjSOf^wWgk@SdZ;Sjzn~z$r0~?>7c&LU4GuF-R=Be+GLkCRY1rh|36* z`)8<{ST1@04D(tIl>PFf%P15LGh9um82g7xMtH3T%9a`FG73e{j8YSd#`e!>uhl@= zHDg>xp=g`2YC_%E{u$@B8YmlQyvryQoijmAC>`5B6TMagW$#RK8HJ*GCaVe6WB>8; z6tC4l`EFyX%P186Gfhn>AlpCFy;cKd2hDI9g`$OKs!8_GEU(o-*+jElMxp4UIck#q zGuLZ1Q1;P0mr*DhX}*|r|19uY46XLhLYEOJ_s=3Vp^B;+Nnb&HdY^3Ebqfj)`3N@jTZ2zqES`Czqw8~`^ibh(kCNz@mpEX{qfwGa-x{N~6 zNI$6wjb!_0o!4rhY^3!rqfj)`1~s9PZ2xTZS`Czqw8>=@ibncbO=u+BKbyT)17#y^ zaT$f8k+z$u%cqS2)TR6fFn2fw#MT8=X48AWotiUhN3j2o0My6(%p2uMXbSA%jt$sDVW>orn9k*@_4${BG!@FNWb}% zBcqdUI~z*L7Sx>lp~|7o;w@L%2w5j7O{@ZzIy3Xj*P~7y1x2GJ5N+v&p`C*CN)D*f0jLk=bGWe9Dp0Vf~$rZ>;j> z8qgxvk=bDbeaey1VS}6v9cII8aEn++W`_;&DMvI!*tiz4j?4}l z?^BM94x41QyvIKMyu1AnVE#dt$xZ>Zb&!?WG&QDZ&ajmyJxcmLzG^84*)%V;xmG?H z2ibI&Q6vW03^nl`P-7g;^imCz)iKLul!@Y)ttR$HgE_}bHB6SqT$fQMDr26S&=`4; z&G%9blXbDcWt54sSg0m+MIK~}yi~(vQ7m>DWuhjQs0l5R2ia0D)i7BR%Unj8D2U~1 zLOj>{ANnAlu?>tfM^0wzi0MWH!<^ zpK@e$(spM!`D# zvTTqYYZ2?nY^~!y<;du*6V4`s?AI2tj?C^l=~Ir3_B!QkGRRK1h;?K(*cqR4WOUeB zwdo)`*CN)Ct3h_&rWOrJ` zIx;)#u1`5KI_#dap~GyD-ER@=$n3BOKIO>hu!qiu4zoe_s70(Jv%?$!irt62EKTh`%J^`}J*U;5Tc7 z^iGA4#P8Dg;x9?~{`^oH@XeXGPmlj5ABx!vkiVt;i5Mjuhl#%=;rp>?X}~vQUOc^2 z2(O9Xg}udJlJNc4r!?T3FYlbbDug6{*Yy*BNy7JA|I&bOw!Cfzs1TC)T{cksB?;eO zgGvLwx$>qNtU^fQchwN_mn3{Y4J{4jk{PB#Na8zzAH`pi@E%}zX(;#02o*vS@BAah zUy^XoA5|K3wTyOB2&)#$7)_Kou9dN3VO8XstMttJEn;Rtx*xp#+q?pG>S*Qu&p;H!#MOMaQ zC&fJW$`VZo56!YvEV3<@IVt9`U6yM?c<7fEr9~ITN+*T9YE7)tM9JflSS=Rxi|vRt zPKtT#m$jM@9{S}cvG5H^UJvV>6!X|G>op-f^vedZpkHh=Y;;o0W4~dDj2!#tcaAtI3DhU?{|`1;r%y)_{`o&t#l6=EB%uajaPTcn>RgvYZWv7kt7 z!wqm!%wv}f)P(SOA|w{niEX&SPKtSKlp&fB9?yluf>NK6 z9?yuxf_||LH_J&ekNq-R6T;&ekyy|#w&CVFDdw?X=4nEBJR=ed`o%Wf0w={h_RB&| z2#;q(VnM&yhFk2Un8$uuq6y*gj7Ti#7u#^loD}oeFUvI{Jf0Di7Ts_wofPt_4Yx`Y zC660!wOG(Ew&B(|Ddw?X)@nj{=$G|o>D;p6HmJ}BR%FsX+9-ZQ(UHO(I&LZrxUl@b z>}M5160d5r_)8M5X-jEfWi~e4Ruw`L`*NH3OA^|0duc#f<_)()g^sY!|hffB(Wp+h`%JEA@`OB6lC6T`&0-?Y{&iLFG=Xe1Em4gm^a)(6+#kw@fY!z zB(&n8(tuLT8}6_QA&HH6MEoTQeR#AqpbqnfJElTNViz74e@Q|Uo+u3{!o1;rRUss? z1y72T-Ai|&>h#rg7UBpcil-bkNt5&6T;&ukXTS5w&89$ zDdw?7e$#~TcorlU6p3xPJ5Gvu?2@~h5FSs2#DY4p4R_y3F^`S%Koi2_xsX^;Dz@Ps zIVt9`R~~CZcsv~v3#!F7+*2pTJhsa-O$d)?M5RSH+zTg#ylTU})I`bShI=Iz^own{ z*G`Ig?3Xv15FYyFtyuVmByYHPPKtT#m-m_w9?yuxf_||L*WJR=ed`o%U}Unj*p_Dera2#;q(VnM&yh8y6d zn8$t@s0rcmj7Ti#7u#@yofPxfFGDmTJf0DW1^r?hZkUr|9{c4-O$d)?L}Ed|*oGV7 zq?pHk8L0{3@rxu_xG|b2dE9Vg#e#mZ4L8n7F^~N+UK7GYzf3aACoLOp zvI=crMJDZ|DdIO29Vwjti?-5$3(N1zrl}B;cvaKIUy^W5GfD$1v$5f3st}Ucm$SrQ zlF*j3O9RR>Z@4)sge1Nbn=Ag3gr1yN8c>sY!_8MAB(WnGh`%JEAs3bg6lC6Ti&O|n zY{$joFG=XeC8Yt?m^a)~6+#kwahdo_5?XP2X+SCF4Yxvtki4NeMS)rQ-si4w;Rw@ECl z3Ony{Qp{spY}SPE&=*_8g2J#3x7A58kDaki6T;)kk62I}w&8X-Ddw>`c4|U+=#E`t zL3!AQ+wG*7$Nt!(3E}Y+NGzxj+i?4w6!X|3`!yjvo&|{oMPeK7pp#-AyW|&52#+U1 zVnLnQhCA$}n8!vrq6y*gTu3Y^729yfoD}oeE5|h`*5ByYHjPKtT#mrI%u z9?yuxf_||Lcg0CDkNt906T(BkToViW#Wvh^C&fJW%MDEkk7q<;LBH6ByXB;q$A0-u z6T;&ekyy|#w&CtLDdw?X?rK7KJR=ed`o%WfeJ8~{_R9lJ2#;q(VnM&yhI{0sn8$v3 ztO?=qj7Ti#7u#@8ofPxfFV8d~Jf0Di7Ts_!oD}k^4fj$LC662Kl~~X(w&7koDdw?X z-e^L2=$H3q`RkSq_d$g=up*Q8QIG#VpYY&=hN2^d({B+k4Y;uUzO1JTA&FPjOZ+7X z*VMZ-ureDPu8#^KiGA5u{3Qu(*{?L9Ec1rzuR=&-Qw|V+NkUH!EDfm1yx|6^5R%xD zgT-Hx(2zq)0}3*4xS=Y9B(~!)@s}iYIM!;MuTB(V#}iN7SF3CEWP6k*J z@r+0;=oi~?`*f0AvAv~TDi3R;)8}6W!VjlbD7flF{XGCH_zu1O5?4+2-emSBE z;qi<}Ea(^8aL1e!^Vl!PH6c8n5s3x;VjJ#PC&fJW%SlZLk7q=sMK|1OCxyIf!=2GY z$>WAQD;D&NZMbtzih1mp^O_JI`sI>Y{&mZSyR1SRSdmHl=!*CaMMnyE=y;KK6z zvTG`YBwp2Z@s}iA(~Z)=%4}@7n<|7P_T??{mn5|1Z>0fcnK#^R6+#l5@{agR5_FaDB*hI~*OP>^}UJyaniu^k_Yza*g>AD0GHW8QF2R0v7z#i!yg zNod7qr2(awH{5d-LJ}MCh4@Pn`tW6GKpo}{_ezD3#4da-{*r_yd{Y`wgn7fgRUss? z1>cFkB%uS}mj>N%ADk4zstwoUf5>M&Rt=p#E^*v&KZu1@Vdp(gig|2{UYZad`l7d3 zP#Cu1`Zy`(u`~K=LU=s+5esU=He7!v#XL6008I#w=RaaWdDw;<s4ZMd;cih1mnahebwPlv>UYOxJB!AUWX?J`jl!s8iHY0(Wg*-0U<+Hg}eQS!Lq zriumqVjFInlVTqGWx6JWhkltM7QP|L8*ZkPVjlZtmL`P9Ga|8|Uu?t8aZ=15` z^Vk;GH6c9o#SO8bFl@u!bW+S?XWY_+@Obhg7Sx7qxZ6&Od2Eh5nh+k(f5d|Funl+5 zNimQ8abFX{<0+6>P$9PA9y%%Ju|*zfLU=q25(|pNHrx{@#XNS&Q%wkuCqiODo!EwZ z?xdKk9qW54v$M0tIk(J#Hl!Z##&!}W1e z%wxaw)r9bPMkE&Wi*306PKtT#mjRj(9?yuxf_||LH^@mbkNq-O6T;&ekyy|#w&8|4 zDdw?XhG{~0JR=ed`o%Wfa3{q)_R9!O2#;q(VnM&yh8yLin8$t@tqI}rj7Ti#7u#@S zofPxfFXJ>JJf0DW1^r?hZi16y9{XjYCWOZ`qSB%pZnBd?UbW$-XrknC!%Yvf*Z{&<0jy(mt9aenZib!W}x!Ee*J^{Jw0S3L%MCHDCNC z3D>lsG_W!o8*ZTrA&GstNc<%UZMnEKpe*x-TcScpVpA>^e@Q}5E-MYF$-Lo~s}Pdd zkt@VslF*PVO9KirZ@5(|ge11(YVnsObmN-RfNIPeZmkL-iM{xf_)8L6ab0OZDdr8g zUWJgvM%*C&l7v3oSQ=1=dBbf|AtbR2e-?j9LKAK-4Jg9A;kKv{lGuV<#b1)pf!j)h zZn*7E3SrfT+o6dP#|^hrEUXGU?{QMhV_WRjgz(T8d&Gjmuno7@NimO|u}>4iZF**7CEK~;qfd; zEGQD&a3`D;^VlW7YC?EC5fTgP#5UY1C&fHA%4tmqkLN;SL8;h=JL{yF$6h(73E}Z{ zNGzxp+i(}06!X|F7d0U~o)MK6-Efzk6!NMKcSRE=FL_cv{X~#h&@Z;(t~n{@v0tuh zLU`zx8)D%blDy$=Iw|I{Uv6nacswH#3;M-2+-)btJod{SO$d)?L}Ed|*oM33q?pHk zxvvS~@r+0;=oi~?51kbA*e{PXAv~TDi3R;)8}5mdVjlbDsV0QSGa|8|Uu?rYcT&t_ zzr4_d@OVZf7W9j4xK~b!dF+?hnh+k(h{S?^u?_duNimQ8@=g=N;~7zD(GB;(Ng=P= za6SH~d`4u`<`bL|@lQA-5)1mpHe639#XR;)FHMx!_X+x?uUUTIvf=uv&<0jy(mv`h zenZib!W}veC=Ix<{Jw0U3L%MCHAws=3D-2ZG_W!o8*YdSA&GrCRQx3gZ8@wope*x- z`%#6E#HJiB{*r{A98nrjlX=69R3Rj>BS(q9B%vWkmj)DM-f&}72uWKH;x9?)z*(h1H{5I|g|KSF&Cx`O%g!@OTy^78HqXxV27-dF+y(G$A~m2#E!CVjFI~lVTnl zWrHS!$8#aEpj2$bZE{k~W3T+I3E}Z{NGzxp+i+W)6!X|FTQwm(o)MK6-EiBT6!NMK zw?h*pj~i~MSkN!F;dVJG=CNOPYeIPFmpx+P8Yn&Z60YffX<%hGHrxXhLK6G( zq4-M@+VW9pKw0Ju_gICH#HM^A{*r{Ad|Db%lX=5EQz0a=BcF@EB%vW+lm--J-f%Bf z2uW8=*HKj0o9l{+#3}_5_|Ej_)8L6@m*;^Ddr9LUWJgvM*JZDl7v3&@jvHd z8vDve9p(-9g9;&uUD#9nB?(Q~t2Cep^M>oKLP%l@_7Q(cLI?IO4Z7j_IVpry8?L`5 zN*p)b0I{$t?7YWGF^_FANE5b@kB^0s1w_8lbjUu*eH`VAv~T7i3O!%8*ZwTVjg>CnkIzD(;=~-T5QA3a8k@; zyUf&t@OVa4T6DwBc2dZzHryOdlss;@xne=T*oK?uq?pHknXd`qpOjmhFj>Q zn8$uuqzU2ij7Ti#7u#@4oD}oeFH1EcJf0DW1^r?hZn=|U9{Xj5CWOZ`BC()fY{RW` zQp{t&tk#6^ct#`^^own{wN8q8?3bT3Av~TDi3R;)8*aUmVjlZtgC>N>Ga|8|Uu?r| za#GA=zx=ET;qi<}Ea(^8a9f-d^Vlz2H6c8n5tSC*aNC^}@~REDLlY&B8*Zmq&@Z;( zb~!2Lv0rv;LU`zxeP-$Oam$F?@02#UGLhsDD7Y|ObMPKj|W&!d_U9Ln>USWupM(;at8jAM76(1hU7oxh3&-I<5oNvFg( zR_7^A2oBYGS}dr}yzb68CC0Hi&uT(&XwGwDL38Gbcit&6j>UOF6M{o=UK9(8Gw-}h zPKj~s&C8k)9D4JLSkRk!>|J$AjALzH(}dtqo7csH+RTgZhErl3Tl1zS1c%nVB^I51 zzj-YtR>SYM%LtRx?~a;SE_P1jwHhe<<(|tZ6b*ASr817-WXbs2^7m`P12AX|p-y;cKd2YqlEh4RGdf5|6KxJP$F4cR>W!D}^8 zHc?NPQ78|e)Pyp!jo903HBk0ZAD2-m&!NPmL$RONVrVrL`@4)lITi<~35{fHaiG^~ zplqZ;E~8L1(qJ|5O;4VTL%dc4Wg`uB8HMs#N=;}a+l@bZtp>_Q8tyU*<=K>)&`35O zM|!OW%0?RHG79AZm735_Q8tXC&_Qn(Q(P<$0Bw&`35Yr+Tdh%0`;zG79CPm735_Qn&~nM<;j(p zbXv~#S`4kmQOflo-dZU8M=Zp=no(1x1@T<{GEO zIJWFsO$ZJh`;%Buv3X;zb4rY3zpmGW;Lxrc#Da3o8*`&mVjP=wlO_a*Uj11tsMWkN zH#;T9u~WBbLU3r*tzto;=8d_{DKU<1x?K~3LznIl3#v44%$-h&aqQ7unh+dXbhlVg zqIqNPaY~G1gYMOY;LxA@#G)H>zt>`7wJ{I4j4-(|52}gfVkcN$tAVm#4!Mj%(J+VA zgo?3^dBkfqP`1obmr*Fsvebm4v5k4$Yc)`I%?X!LC{MK1gu1bfdD3e&P&Upfmr*Fs zwbX>tv5k4gYc){z&RLgHC{MT4gzB-4dERR^P`1wnmr*FsxYUFKvWoN-Esh672NVYNGd#wh_M*83~3gxNS|7xdRwi-I4k!)lB;I$ek8>y$uD3qsO zYCpM`bKI(aJafrVqx7jHs)xj z#5i{C7)=NcO*>XBDB8R+$2ld&v1P|=LU8EV31UIT=8ZYgDKU=yI!P0PL%U8E3(7Tb z%qdQZactJ9nh+d%b(&aEt9fHicS?+7r_RuX;LxZu#ezc38*`RZVjSCawk8CJE}bJ5 zRB7IrbDa|7*rW3_Avm168*`1WIo!4rhY@GEjqfnk}sR^ZH8*`)AYM|_$O)jHQo^GiL)nglTv)5{%Y@aPI zqfnl4sR;#S8*`i2YM|_(?JlEGo^+`RHDnuer`KwrY@%H*qfnlAsR?Cd8*`7>YM|_+ zy)L6ro_dK%H|Bn?#n5VF9&j0fa$_D;6B@}j<}Y5WfwGYfxr{>5NQc$LH$8b{9`RZY zl#O)MWfaO&FEyc&Y-1kxS`Czqbi!p6%2O{jp^BjucYcaIin73UqHa6x9r^GmR?MqDv4o&+?EGXK%F<(0+#<6AJXhLx4*tcRq#paFq&M7gD z{rX-LfyQ5SZ{?xbtUqYNdD7GE(6Ogj zP^)=k_Hs&mb?nsMnh+cswU1a(sCi@dbxMq5oA%R$;LxT0#eyo$8*_kDVjO#Ppe6)| z79AuOlxW_VgPjuN*q}o+AvpBsP_gL79Oku{SZ&N7T}GJPn8Ve?a zp=g*#vJXn8Yo+4jLRsLXIW}O(b&cu=d~IryJo!0D3m8!YC_%E#+>N28YmlQ zlFKNR=UQq)>Db1c;f88YtUmhRZ0FXIyGR0olf!<+U0p zJ7~7cD3m8%YC;X!#+>W58Yr7+p35kd=Ur+-8QI2M;I$ek`)HxdD3qsOV$zMd*lRJg z+L%jRMxfl7OVxx%vW>aSYc)_d(sGwkC>m*nn)s$CZ_JfmtAVnSR=JEqdFrJmG?H!1 zHD0TMvXR!hj6!+pr6x3zZOnCEtAVnS*1L>CdFrJmG?H!1jb5vPvXM5qj6!+pr6x3z zZOqMHtAVnSwz!N!dFrJmG?H!1ZCj6!+pB_`dN`@I%JtBrZUWdzENc~DJgB-@z3c&!G?Mmpp&3PmFw zHPgpkJAdEhvyZ?3?mzs;v<@00?3fB|cts}pkBi?}bfj>Hjweb3E-t_S`&EUI#OpdK z{*r`iI#n9jv5jjwtwKm*y`B+&NkX-rEe$BvyeZGA5R%xb=fz)=(5Dwl1KKpt$%`t4 zBo^r<@s}i&=;hLY3e8LMiV7i#?Ri!FB?--Wtu&xF^N75zLP%m|-VlFDLS5c04JgaJ zA8)A;lGu~KiN7SFBX5@mG-RHRcT@;TEXTXzFG(oId!+%jm{;R{6+#jl@qzeD658-# zY0$y=$Vnlrnv0J$QQ|ljpNNH3VJA^eig|2{XPOWm`r^4*P#887UpOh|u`^z3LU=ri z5({d>7UF9s#XL608%+q0XHjB7dDu97=cJg&{&=qm;qfp^ET|CMg+0XI_B6_F8lBi8 zKWIY#WWR^5r+g4aVw13!lj7@Rm-NgZK6eqS3ZTT@=SbksjlL{e;SG7+3@&_ZWFF(f0Y;3puSG1O$S3SNSniW8QGPRR~G!#XaJeKNx9m`7xAY-f;U=2uWcg;m$cJ=CL`>YeN5I zybJO{l!tA&i%yDp?2k*D&_5aPvV0H~VjJ#?lVToQhn8z-; zp$Ywy@ovfoQ75+HZaFFDu~B~0g#O8Rx8;K<729xkoD}oeD|a=ae=^=Z`5>yrHr#zD z#XPpl15N0kjQ6nopl-NFP6~O|hI_0D{gd&Y$Oq9cw&9*SDdw?Xo@qk=WW49{LB1i$ z8}5aZVjlbDr6%-G#(O0nM8DXEd+nr{$9{RE3H_7t-pU8jFSg;{IVt9`U*2m%|75%m z@JlQ(xMw~n3Fw&6xNDdw?XMruNMID;Nzmd-63 zZmbGzU_~Zzwgpc?aro3BDhVlOTbe@Q|sE-Vcw#k}DbsSuLbh>OKvlF)}sN(1UJ zZ@8r@gd}$1GVzxrG~x2nfFjHrZiNaVi7mKN{3Qt;xT-YhhFk5V5LRutHJT`K$&>OO zI<6H9tHREEoD}oe7V9)2JoLqSv7j()!)Jp-uLR1$AN@Zl9B49vfx9CWMDhIUp94ify=qPKtT#m0vU=JT%K8v7lOP!yR@~ z%wxM8(S-2OFGov@Zn$Gk3VGFrJFbb6mpmz-ej-RL=oi~?zd9-Av0qMVLU`zxQ)1y8 zlDy$gJ1OR|U(RSkc>L)gv7ldU!<}vtv0v_LLU{ZMBC()fY{T7mQp{t&JkW&j_;W<1MK|0dCxyIf!#&nS z$>WB5A{O+EZMdgSih1mpXPOWm`sJlrK55x-uT*FQD>7*xy%xWr=t$uX9p97&Tv&cz z_Ev?E#H)HI{*r`idS4n?nT-wiL4}aSzU=XTe z{*r{A>|GjAlX=7SQ6VI;Bm0WKB%vYul?D`K-f;a@2uWfj9#|<}LEUXGU?{QMhV_Qtrgz(T8lf;6; zunjlaNimO|F+~%?3VGFrTce4R#|^hu zEa(^8a6dUI=CNPaX+n7Dm-S-d8rLP%mq-V%RFLPP#m8c>jV!`)UPB(WXuh`%JE z8}F6|RAb(7_f!Z;?8W=yFG*;{2c-d}m^a)*6+#jl@sapT68i9QX+Rz34fjNaki;&0 zD*lp$CVW;JP=tBIJy#(lu?1gI?nV}JD3gz$I@Bo!$95U5 z3E}aKsI=&Y8|$QyS8cd)nkaePaO1^-ez6TV!AUWX{W4J#!b87I5)0pu3VGFrTce4R#|^huEa(^8a6dUI z=CNPaX+n7DmyKrm*DV`vlL~EMMJDZ|pT%z|I#Rep$IYby7na|bZBZd4@v63pza-(B zwv`4}W@E!`S0N;^FL#K)B%v*LmIjn%-f+8A2uWM(D(6DouxcHyt$FG*;^lcfPgm^a)h6+#kQ@U-|#5<2iqY0wRK z)=43(+HmJIQR2Aa&WnXrVdp(gig|2{i<%G~`r?vUP#Cu1E;}jau`{k{LU=s+5esU= zHrzEQ#XL60bxjD5=RaaWdDw=#>7s4ZMY{+ih1mnrU zYOxLX+(|Ky?eans!s8iHY0(Y$%1I%w+HkKmQS!Lq-iQVLVjJ$QlVTqG<((#khkki4 z7QP|L8}5UXVjlaY$N!bji0rLZXPgo7PdFnI3;M-2Tu&#(JoZa3P001}j7Ti#7u#@s zoD}oeFMTy3Jf0DW1^r?huD_FF9{Xj0CWOZ`BC()fY{Lz5Qp{t&4AzA3ct#`^^own{ zp-zfs|wCR|q< zP=tBItydu=u?07Xza*gpHWB5BNp_FZMe5iih1mpcbX6$`lZMJosV_?re(wZ zph6p1kxBcgr}zy;M+$f7*sC<)!t(pF-YSG7UR59Qmn2+M-_pR!Y;3rGDug8VWq z9fym*B%vEelm=8|-f$yT2ubY4QQ|L2XvNW`0i~EX+!z%?5*u->_)8M{a9n9X9p(); zUWJgvE}S6#l7uFlSQ=1-dBaUoAtbQ{CyT!%p#!Is2HkK|ofN{V4L3~_C5{_zx>#5h zcHZNpn8&u5sR`ksFJ_4ag<%_Rwv%EWJ7bO}gvXN~v7k0=!_9M2%wu!R*M#tR{v#HY zhi$lpPKtT#k42gg9#4V9f(o$>x5P;?k1euP6T;(JkXTS8w&9jLDdw?DR%k+aJP{HL z>clqODksG}Hp*&E2#@DNVnM0chFj~Tn8#lENfW~3>5y1ZEwOjmhTHC>n8$wEp$Xyf zj7Ti#7u#^VoD}oeFS|7%Jf0DW1^r?hZm*MK9{XjVCWOZ`BC()fY{MOJQp{t&9MpvH zct#`^^own{Lr#i$?3cru5FXEn#DadY4R_Q@F^~OnOcTQ68If4fFSg-MI4S0_Uw+ku z@OVZf7W9j4xKmDwdF+?dnh+k(h)RoYxU)_QdDVtHr-_os4R>BF=oi~?7n~IH*e@3~ zAw2ZU6|?-lWy4)np$)9aqZbTh60Yf1X<%hG zHr#J2ge3OmZSj{RwB?=BfU?XR?yd?UiA{M={3QuJdA~HECi8}Sph8GuM?MsPNkT(D zDh(*eyx|_J5R%xAPsCr6(2Y+^1FA7^xMwPaB=+KS@s}jD;)~LNQp_9fr3xX5jrdCZ zB?*1_x-_5;^M-q)LP%m4z7>B-LKD6#4Jg9A;ohqdlGuVD#9xxofj$18e9mLv&AQ=! za8d}XHe63llsIm2`Hxso9=73zI4S0_KZa^TcsvCX3o67m+>cI*d2Es4nh+k(g2aL% zu?;uUNimOIGD;J|9wCIML>ZFiYZMbQgD0$p))5U^*u?;uFNimQ8GE)=6L%+-t z3*V6B4L93KF^~N+M-#&18If4fFSg<4IVt9`U*>BL;qi<}Ea(^8aO<5E^VlyNG$A~m5tSC*aGRVI@~RE@vnEO& zH{52ipkHjmZE;e}W4~cH~jX+SmR4R=z7ki=d*CH|6x zRyOlOolzkqu@TRTza*g#&y@z$Vcu}(RR~G!!VBUrNoc~0r2$2lH{2x^LK0i> zviM69I`B$q&<%IhNg=G-aMv_Z;<(|ii-lET=RHn}d2EZDnh+lP;+9xY7`EYlb5hJ> zXWZ6=@Obhg7Sx7qxVuh@d2Eh*nh+k(f5d|FunqUXNimQ8@lX@O<0+6>P$9PA9y=-K zu|=L}LU=q25(|pNHrz8O#XNS&b4>`3CqiODo!EwZ>7&nh+lPWsX@oecUqQ<~pSfu1uwg zG*1(Tt2`;+q2qk9;PUdjvjt9xalE>Pnh+eWZjo5no{c%T*eNlN<+(%?fhvxiA zENIR=@zyyd#<4ipYeH}+&JAKgaps-3(J3*Gy}3yffa3+vb!Q$JX4g3BjQ?cZfx2-%hW^#A^8Mav5QA`t4Q|%f-%#yjBBczwC7x zg`#2hsR8L!nq z*+FMrMxi`$QWI*(=HYp-)j-)q7hFc6JbY3U%E&h2C9l;$*+-XMMxi{15|a+at6qzt z)l|IZG6LmTysjoRlC8xXUaNt!k#4$-LeWUK)WkPEc{2XywHhcJ>9)%#l*dwPLL=F3 zyz8|ZC>!aX%P5p*Q))sZ*?4^5wHhcJ>7mOglm}F5LL=FNeC)LvC>!aC%P5qmRBA#a z*^GSVwHhcJ>AA}<)!+LL=FheCf3sC>!aO%P5rRRcb;b*`R#mwHhcJ>8;Bsl!sPo zLL=F#eDAdyC>!a6%P5p5SHH_ASJ+27Er0M@46VjxPnQuW=VdQ7p^JL+=mW?^UDeZ_wD($v`ngEZUl<&}SkXUeu`CZ^(r^Gm3-w;g*4p%o+EUeqc z#vJC97{{*tQ4@kg(+(F4iZ*Y|5l)G5Y}t{T5F9#olvq%)d1H=tN{nN_j?skR(5_>} zf^y9pbDUFR9Gi8#CIp9Gogfy}YTlR=of6~NsgpDzI5g^Hv7k`%#+>4m7{@l9stLiN zOQ(qiRhl>Ebf?5P_UH^v2o5beQ!FUayfJ4vCC0HqXKO-m=+8M~(TzFRYca9fnDbml znB182)x>hK6D+UQK-n(~T}Gj3m_=$r#n{GN?6n#wTV{#ND3oVeYC_T2#$4vL8YsJF zxyvY&Ct7Mk-Pp!l>9rat8)ucvD3s?~YC`GQ#$4mI8Yp{bt;;Bsr(0@5_1MN-=d~Ir z+h@JYD3oVhYC-|o#@y(&8YnwxlglWSCtYen4cW%r?6n#wn`n#6D3s@2YC;*=#@yz$ z8Yuf{yUQq)r(R;xjk(inF|^v4yIe+~+?c!7ghsNBxyNfYP&U$Dmr*DhX`h<-rYCRA z{a&kqvXKtBj6!+pr6x3zZOmW1Rs&@t9da3k^3+RBXe8U1N4!=8Wg{JR8HMuHOHF7b z+nC3_Rs&@top2e2^3+RBXe8U1C%sk!Wh0$(8HMuHOHF7b+n8s(Rs&@topl+7^3+RB zXe8U1=eiRS2Fgad=`spMBi)9nbIZoOGXjV`DyYN{nOIKGuZb(6mp)f}+hE^Qlu}99#C8CIp9$eJ&PMY~GkJ zoD$>MuP-$rIJE04v7lV@#(eFR7{_LPqY1&GSKo>SwVF5PJEz1rcItag2o8<e!>b zH6b{(XdkhlMDxb%>y#MB2JNQ_!J$9Ie0_Db>uO>8-ZOjE;tAVnS7P^c=(MXHb#5X;8V=neu4U~9rVIZOmORBT#P4-D*N3*~Z-CwHhcJX|KyD z6peHMrcYWn=0T^lBNnN&+kVjmc=V)vhmMEDf=kTr0uMVS#_{@&XhLwfx}#!Y-8MGn zF{i{hcI|OZ2o6nqLM$lSyfJ@uN{nO6p45ck(6Oh)f{M)>^R!c99Q*Z*CIp9eJu4QJ zYu=dWoD$>Mtmic$IP~fTv7lD-#=Pj17{^Y%qzS>HQ7?-Hg_<|!6{o~Fw&_((2o7C( zO)RL=yfLpkCC0HwZ)ierXwjQuL5b##dCMs=jt%;oCIpB6ye$^pn0LGu6RVAR*JXss zjd@Q^EEhY$@>&g){qn$N6pDs7zd9I}cm4ePFS<7VPr5m!zo2O> zuvNuJLF$74!QbALp%hr%41Cmlz!dG!ab1?aN{`?8zfHz^`FKTXK7J8Ngbk%VGpJ|E z<}82S_4}@0cKfn>f!U%0IQ&bfbQxtPakh#-gDOWR?faR{OsE>Q!2FGU zVc|HG$$`4ZP` zvsndP^C$8^RVH2YCGqo`&5^J9vKZQ3bNO&r)ZONqOZPRpzxni=?{F11k5#}`bdjs5 zGU+OAh@V$sj(in2#nA35%7?q9?lxCZx_?u5o6lV7zOC+08lUIihZlC2?k~RiwE7mZ z;d#$Vc#%*@_he~%Zx*KJJi|(9nEWK61MYq-;pJgBM^P=rx^F{X+L%WNv zoDIlMVIaYbT|5emywTl2daY0Xzf2<#vt+YGVEdVWegTWyUVDaL%NJ1>TYux zrF*El+kEay_b_z_{l^O%PIoRTzDD`mXoQpSBDLv1KG;Z2@MXe7=htaeVadfrWd4>K z-Ks{^W;nf`V_I?r8_tX$pN-xAp?lY_{;uoy_W$C(nBM|UXsfqAhc=Ipp2oy>>HJK* zKR=mCZR~hC^1H>!ZS{Zd$?%ggrCqwslRE_7R%TsZ8YO zw2*<{w||)ywbiR`2JpVR7QAl;dOk z{cU+$JJm+5o=N$A=JV-^oNmq9(-3cdNzT#A?vN*OzKt3@3C*V`aiKNKCsBCwlenC% z-MW6C-jStuMR?<5)ANegz%SnJX)vL$x=iL4t_;1VCcMG1W8v#wtAX-;%?+1PDBjK7 z|5smp{>@j76T{Cx{jU3;yM9@`k$KRfIcjS%UF$=i`p6UV)jn$4zAbL(p^y+dWO8KJQ>%kvizlq%V#gWozfmx zr4p`>CMukHGOllB>C*U%gpWV^_@6#*{7Z*34+BvKJEA`7SzG+7PI*S8D ztdhUa;=oG$oZr=UTsKIB_E(5Vy1v1sySloDp0904C4c#+Pe1z_^%VFjFefKXm)|fBM|MLi0O{kxpqtEK>1ad^?Sm9!lgH-n+2G<-#*<4i!HrT=(TYB?)QfO z;Pge`oJ*06ibTnhlSs}<1<4>8lqgZjL6YPi&!|yVBUP>aIqf;U#_#+5s>U3%YCJU` z=9Fq2$LuWb|1bEcD~OWA2#m`8HT^XDqlcFkE(z zN_1bCh2iB-v&ZdYkrytEK=3ez#SWWCk<~bkC0X3BFBC``25v6jInlx>I1PhXYRNo? zq{SgDOVYMnk6D~bv{UEhOi8b0*3ln2bzZ?#l=G~jKXmH6lBrTovM&9pQ|DDo8AqOl z@h@-&z;ylp)u%~imZj0H3#z`Yak71R+qK?_ItkY_Bz%JE9~>a&L9mB!`$z%VE|H%Lp_ki&Ct>)usjdiU||f5g%SK>xa=R5=zb^*n*vJi zSfht+u;9*Ea6e+W>>icqel!b1^(22R)MH+_Fap8D7>+w^9z|B;I8J0SmQfl8R_jS8 zS{MbVVGyS*na7Z{IE2$l8W&0!L>7l#0shpf^BJaWid*RD#qHGjEK^a=^VR4NojRXm zs+5zgOMmLr`8-p`k!NB23q0BobbaA2JB+z+J8xPqd0{7+hKFokcGxfksm6R>$>Js_ zX%zUjx@v=kF)$WJaLsVpKPu7vk1T9*o!s$l^`{LM+!+h**A185qY~Y3WMOy(lRv(# zZhGOu2m}vfxaF{U6j_bqxShpVAZZx*wz}g)3!~sP4C1aO^B9sAhwvavaU*E&m6i00 z!NUtd)Y{$@tti*WDnjE+pKCRzLL7s^J&{PTOBx*1Qzq#b{qPXkWaGz?;r z2E_mx9hy%`vcCV-+MHI)Tuk-C#Z<^kz#yhMcp3*&<4~px@xO3&#V$EyVulm0jwD?H z1~SvaVjMw>!C7NU4J69sXGilIoo{;dTB2QYIwalNPxbzOg zxHA;Y&zb2JS9yH!Y^Mm&%;HC%FqYk&%KAL1463 z=(AI!K&yROFo51>VI|ow0%W9%F(BY`fUC0&#L?v-4;NkSeurim32mr0n;EluSakq#$yJIe<4635+lRHR@U zDX_dNiEM}(w7Zuj9}bLmxK`a)k%C>M!0v%0vK?yB?yoEv*c$EdIP0N`6zn1ec8?^H z?NEbukF%urN68OYtS35DFiadcK2=P%3@Y^eJBwOB4&{$a$usfyf?FWK>N!_uABdyL zs~qmx>z~0TJR$g6MhZRzfzcbG&rXd3tv>%>LQDK{Z+;^^g#DE~ntvNgPy1n8LjZUT z&0;cWVtDmoITYT&&=QN)HD6^olj6G#=ivOkor12l*Dd|Wi#edKM()e$> zlynr6_Gtd?SMxxMKjYC%`gV}Q%Y)x}DzXX5`GQH`3DO<~>6c9UZjioLkbcFa@1eAL zcE%mR7$$umrOkshuJmgrZNYy+*|mAD#?_AH+VFZckJ-4|aa@Zp7>u@{9nZD+iZwT4 z{&gpCExu&UO_{Hq$hG*IH8*I!b~0(<>7+q@(z=4rLru{k?;XfFD1oVpp*KlV;X7p- z7g0Nl3-xpvAU|=_i&sJh+-3+p_oC<7W(t9`uZqikE7f*i73x`1E&jm~zTJd+HdFWh zsCWEm6*r7ICRWOHB4P4#HO1y1beQaUOx9=Mhin<2uOehB+8CTepulp0B$#1yWwcu; zC8d<7OD;;$WSiv-bV7fvv*)*uobY&Jn8<0$~Z(F5f1=9qA>1xGf)1X4rHCfa&0?8H6!Pc5! z!8W7dyG~Qtm~`m8KFeSoO2+sG*`Q+u-vol~M#W^;phDA4S=3Y$9W#b+&DpGD1=9qA z=@!Lg)1X4rty$E(+|d+Ut8F?~Fijws{-Bs_8dPZdV-__pH<^ZSLi$O^3Z@AJ)9s4M zra^_KJF*C0>gbBMY(JY|!8W7dyHiuym~`m8E6bXfI~wCVcDIfdd=m(^dlZvhg9=Ue zW>NEU$A3A1P5M3^E0`t_O!q4$n+6q{9>}8R<&LIUO$T+XV46TM{Y5d^G^o(@P!=^W zH<{v%|6v^}cqR@!k0>U41{Hc9%_4lI$rNkpn28l!GYPiGHI;oyhsGzeta-7?7fb1+ z4i#(@2d<|SlTCvPJ%7!j=C!8JcW~|hO@|7ei388mipicqg`Q`!sClW$6IcGTI#lpX z9C)5nO!f>a^gN$M%}Y(5*bH9Kp@L`P!1H&-WY3^N&x=`vFEg3qPIJk`3a*(1+sm5D zzNACrD_PdO)Z~lr)T=sFuuUAeUQxPb5Qwf6UO~s%oQ=#dt zENWisXo_!{+d5V-O(2-wQA{=sDm1;DMa_#HP4PW*Psa+T2?W#oipi!yg{BX(2w&;w zitn1gOt4^^QSg1JsccL-bbgd&&C4B)v5Ft-Siv`eVEaTd*)^!p^l26~3rGBNINag> z*0F+V0>Si|VzOyaq3QE1YF_SWitn2jI#w`EAeg>XOg0TFG<}st&C5-upWna>v z@%SujUTpHkQktMc1>3}d>qNz5)1X4nNm82d@3!=up8kao{;wG1)Vy&~r)_ zH7_-J;>tf&hYFsF1J7xS$(})lp3}3ad8x@0`=uE=RPan3c+ONz_6#cY{5Fg5WhPVH zX=a&N!8Ma$J6luPmvm@6C(D|bntbt{I#-7ZwuuARd5X!VL4}?RQPi(*bMV!xd9lR_ z(;^$S#u^6e#fC$3p+x&7T-dzs(H`GE-`Qx#(H`G*n{2dbpJ1@xY&dQo zlxV+&3!B1-2RFD?Zne>(eS*P$o8h>9P@?@0T!=*x{c+d)(Fqp^kZ~BnPnP6EAT5qz zJC`)zz!QNjv&D>fS(P={eu$icXDA<81X;}>u;Bh7VQ%Z_PY(o?Sm5S_i$lT z7||Z{WA>%xL`>>0@C6Te&^DrC};%u&cA4b#Q`K1{4W`f+Xp4O zUq#`Ex$lbyD)`CbH5;||8V37642SkYiS~bTVN(^+9^ZJ^ZM0~gV6eYoIBp-5Xn&In zo3e=Z_|Cg!qec4!gZ*v8ar>Y|`#W5SH4**sy?56M7YC4W7{NVD@*$8G$8euZo5F}g zz<0m{8!e6?!7zZo49ES0673&yVY4X3V=mlxAK7TpKEYuB*l^rFDAE227dC|v?eX3B z)JBW;2?qPW4ae<+678RHVN)3K017wW=QdijPcYcOFdVlJO0<8;g;*5PA9vnYPPjOL zjKc_CTapifv^a)0T-p>y90INYpLGo(ZZO<|Bdmft8FEV?Ha z+(#RZy9Xt@f5C-V6J(Fo_oWjp`ezyj@RcR`2uO=V7{jGaSJ??tbooLZN(=dP;mgFNKEe>HOmo`N~ zBfxk5w>DTDKw`mvmf^U4P@?->6t@4*0X^FW4d}_9j+-X~%Y`nB`&}s+e*dY?mmMjFSqjzmKAp#=3=DFVmr#HN(Mrxk96LRH5~T zuC4z$u-`=XC^{hnPJ4x(JJBzi?c)OKs&HT1F9Ssg(M#9;)-!jh01<$%{VU!;YX{+1tFnjBYcnX?xxG`^DAeFG&bLT3;S=iTqjCM=DhGOFzo`SQ6YX{v_)YA))mpJX`)$ zh01<$efe7w!jIOMXF?Ji5?o)Nt5Df5t}ibnA^d24d7UMFKkCXAUEz5r9&F*kmQI~N zYe{`u-;cWSU^h6j;KA-Z*d2~3c(4Z#_UP1k2oJu^gKxu81P{K$gYUrON<8>355C)} z^Kc$~j|bm_BL*IPp9kNE2a5MEK=42IU6U!B55s!5ntW6YQk+p7+wMjh8?!CSdf2a4yyX;;sy>@-$SI|%9NPcZ04mdo|6T+?L zmS?&QIPXQqKr=W)=z~#Ipwmn)hz;Ah0%0SU6HYlrvo;y){vYHF{ zEzcSmC_2T~WUbJ1Cu&UAaRI;OSuX=cr`VKi5PI%JEy+eMkheUWRH$f{Zh1CKg4@Mg zo-INWmkPY)*{VWizqnd#lZ5c2_2LI1p#>xS62XruRQ8K&#!r$EezavQHAikJgd>LLzQ? z4yaJsFRmpAB_aH1HTgwI#4XPu6)OA173HubgdeRbM}$P&@*Gv6vR_Rf-tzpaLPfuH%k!HgxL>^GIV~i#zJyzzGb&W}i|fl- zNeDk$U(N|hY)J5y=e!D){o?v^K@!4`)|X3J(i(4hs1<{M1;&Hamxds;rB`^6y3!DY zrt~TgQYRmR(8yooLF(f}5Zd@Zc#yjI5QHZFPadQmJ_MnKzs`fy!G|C;@Hcpn`u7lo z_WdRgQuiK$(7fN`!FbCPqRlPOZ4s79f-Kz;VUechmglYri$pcIJoiLcq^h~)xi7*Z zS*zTSR}2v<$27*@s=lKt-0lSBElkT%`MMU z5f)i%Zh4-EaNEG2(*kBBkgs`IqW4Ms; zyOR+rQnriz#YjmAJL)e+2?@VN8Lc8^yVzcQAqine?ZuZu!tYbQQjxM<>@LPgLfBDv z@wJffo0YLDQnriD#W+a_J8CY*3kkntnV=$NyVzSyl!UOO-eQuF@Y|MeRHSSdTZ_q( z5O&mBOc4@!?=n@#%8u#oWtw7yXS{!zE=6&1!5f$vI#w}_>&r~VNK;y2zLg?cV!~a_ zEFG(u##LsvVx%dpGjpU!+{(<=v5IM2Yvw6Nn$l`BUy8*2%mN*&n8p=np<<*dtvQRN zNZiyc*0G9dTz8fzMw-&f^PLolJDa6CRxypM&-aRvrnLSnlOl0@vs}k2rg05gp%`gO ztI$d*68AW(bgW_;SEAL5k*2g3t&t*eqqA1WDyDHgTBjIkN-NTOA(D4H8+5E}n(lWt zDn^*bJDyEaL@N?~gOH9@Oyi2QMKRKpR-~;`6q_Er@7bnf71OvP{h%0W8qZdOsE=(U zcc_Tt$SG*eewIY=OB&$ei++S8uJlb`w@XFJb}^~DB_Zr6rF(=VX0)-}t0HB)n9hBY z5O$Qz{X)Xq$O9@;wu?*qK}iTZTG)RP65d80QjxMnQ02^A^Z#fAK&B!nF;sc}7Lb zc5(4OD+ysoOZPb;;ceu36)D@rW&468gdHu~zYB?MBQNS$*)g?|mlPvBV;gx{isIse zZR8altC+_1<*H(&DXlQqq==T7&_@2DV-?f5%KWJqX-ezNbtw{Uu`+$10|A zJ$k7aX-X^7DV z8X`rp>A^N~sE$=k(|?{%POVwn6w`ej+)_i8{`jhBj@qC4;}v!nNSZ z86%B5K-2Gi=|t;8h)Ms-l4b~$`Y}ctv)>HiYbRPCLVO9vTG9-GUWjo<%G=QKPP9IR zxJ68`q!|Kj6cde|1Bol=T8Fg*p|x|J6^piey%+CbAaVWN;IMWew1RH5V$q6k^5Pu~B(9>H z9o7zn*3m6iEZXy}Uc7^W#I7dmXd5)3jo%C$5r21_GXYKWQLYYN6bBN% zgouUXPS*6=$Hm`ECNaS$xSE+zN>8$I%w=P8O8mWK5|j5US2Ghz*KaJ$TlUl9?wHc8y<`%X_&>Osnb4yCCkylD_`3Le$s{h{H@KRa(1LxF zg?amXOZ>fL5|`%NT+K{qF}}mXvcbJ8BPE~I)ZP<%<`f&*`&MHI=T@{5JmUhB!m5dav;+pVU=(!cG3U9bTG>f10z@s?aJ6iDV-Taam|3-os zf}fv+wSBPAb1PaKKIa0_4i1r#;;iEOFjVNd6|E4%xIi>~!)2ss6<3K7LeH&eofydl zqNN)pBSovYR*V*UZbhrb7fc|Vwl8I*WR)7VuY{gi#pY}b7tm@E+On@@q-Ygai?Kq_ zt!T9v#|5!jz{YF5j1;ZnYB53RxfQJz(|h#k*R%b@K|SG1jr;W+*!pp=f3tu3Hp7XM zC;jxAOGD|;v}6~ng=@h-MYGaDT|aGaem$K2_X&J!iz8~`q81R%c0}E{s2hmpIHK-c z)Ez`~9Z?T1>H(s8j_7SJdK*OZ9nm{n^bUv?IHGsC=v@#kW}*RYec-hUuM~c{!x9^m z#gUVrS$LhkGaP%FNQtk~QYP%%D|+MCJ$$c2CFjV2?=rx0!*36)Ho=l@Lcw>9rkHWiq4QcM>&=|;oxjcmOU?-e z=k=Om&OwLH8<^~ae-CW!I;dyw-fgYz?V-X##y1v4aU}3|eUHBXD3_bL9t>+!=~8TX zlEYzcR#-PVOstD7MGcJ-ejKw~_g-D;w+!Vt#RXxUTT2&H+r$cfnFPx{n#!)EL*u|bV2B|Q=>qq-?O0o;}61|@C&~#%0P4y>oMepAh5b5 zfNa$$(CV@f&@Wfh-A-7n#PzO7dH6MC`t52*epSlDFIdy>S3B}+QXYQAntsFDk^dp( z__N6IcdQ-xpIJVjz3+duhP+~DbzO%jvtk2jiY{`H+8c_=$qgz@?@c8VKZu*g$S-?K z6Z|J}UE+2o+6T4`q_+URrSGUvEEv8SHLovWFsr+g$df`1&gov3z|Pl~^4JY`iTgTM za7-XrK2S{d3@SAJi;3FWk}2*G4|S|$8bL69q!?z3Dl~nZMg986U#IVmd+!q!Dp*Dg z9G^-e8=?mNo|B~ifPwI;z<(nSM-a`D_QH*O*5(R8zw~GthScL=UTJx(k}hvy241`I z>R{p(U@&hyS`Q}I+~BuE>4$NC&>wDOTmJ=brgZ<<+^c==idwShJrE6XMR1k_KO^1b zc&HnvX^HhfjwPH14fAL*tvGhf@o*vkwD&*Yk*M(g#ljxph07VvJj`RH!-|2B8pkn8 zi2p}(L)1Pn_L{hoj4mk3qY+nu0e#_LL5wLgIIJ%{r1uBZwP3IGRY}s}!00+KvN45g zctdL_9NX6dYU@q60JxouH8C1Z{N`9*%!I-?#%W9ppwXf8crEjG?NFTg+7k@q?A;og zXdq_?*U%&bIs3SVzA=!qn`>yYf!=P;YP)si+na`_80eh_>QRNJ8tB~ydanvi6VU&F z`yIYDPq)!jB%+@S6NosJ$qYk^Izc5C%1k4SD`rb`=mv}7w^l*RWj9jHvWjkDL4|v4 zyvA&+=pGdBkz$Tj^gsm;qZ!9st9Tm~IE+Ry&nn(Q1rDQ8%(senQGvr~6br24y+#p+ z(I^&L#rusS45LvjvI_W`1CWGqG?K-R1hX0j(nywaNz0)4;=;~~i|zMLxKbSX0#F^x zEX&J-v{)a@t(2CMuHp^=D^QrMaLBNpbQL!PmR#wOVNvNS?h7or$|1wb(pB6dSaP*P z;_?Eoyjd#5Jl8lRt}##%b#kpk;z9$3QYY6rB(64Ho#jT1cD+Ns*Q`@e;C0Up4*7mq zOFJMpIwZUya7FC^-Q=NIMes(ck9YgqecC_jHRyw0ZSZNz2mg#G)z~EOFfn@T#G1Aw zylsBgR2S`lZ<(E3_Q`)nV{C|bnOM;{l3=`BQ`{JJXuOxp2L7A266{#_=@8k*W;M^3 zIB?ys7;f6A(DQ&2g~h?9F<3e$%YWMIE3?D z+SYTxNByb1!e<>9oN#dr8HX|aZb?1{(&88{aw(*tS06eF4WBh#a>B(iWE{qD*^+z= zq{T5@;nKEP3gOX|t2$P6ClIW!DTeztDm49ri(oX#77sH2w9%q*g2DQ_;kbEFqWujf zga*LIquEfh z9!GPJ$$O>4#@KD%w^15L{QN&H+!=;JJTM#^0V&b`FC#3hxZ?5;E#h2&4Xc(aMRS-3{@hx z9K~gaX~HW-L5$!8^#xtt!qsP_4i)E>`-xGC;qz)#_#%#0qSCzbWxvowVP2W|iV?Xv z>GBpfHe+nCR4SQ;SM6)VvH9`FW-JrNb_36Dv9THFL`(jRh5?MXBpX50Vv;8?X>2!e z2-w(6bfTppFdBw1$&zdcQHw+PhD&p20&iEm1DfoFi(|+*jA4o;`51U(GnGqWb5o7Y zG$&jfL&jkY(=ExzKw8Yh3@%lT%}gCDy648`Tg7nS)Y#18A{dQqY-ZbN(Kx{{>p6zw z=0S;bp38)}H-VQPmzH@pTC&eD*v~f{v*(S?0w&B|2G)Q0?UjYDpfm_^2^hyBk7h&3 zdQ8S*CeLj^Y;2a;D2+okHr)ng7zXj3;n)aBiS|p4u(0Ba%YSbvf7KP#GD~@ljhf1G zPQ^|myjr+it?=Td7fUrZD;<_6D%xSH)+8}JSFReHwI=3|fRXSjt^1TJmQ!4B&tz*$AQ*lYEd#W4n?m zKEq&t-f+yGH#QfTFn1Xt0eE8byDKOSLRoG@ z+1Ok$92)^|Y_1w%Va3g3gE?Nal)vf<>JLkKjg6YhpPY)FMtHTbvAOQWOD~pcY;HI# zPgJzSSL${W!@puvjm;es^GCo)NaI~iCGV(1<9l2d+Y@SR?weTAIFexeKvUc}H#QHs zOg1);bck$KV*~TZjm=}laMRS-JW(RI9K~gyYQif;K|JFG^##<}JlCP(ymCMBLNR<^ zjS64Hmr7KcSHA2kO%&#pi8qYM%?UL&pS>H8-+Bzn{Rn<&OdrA0iD?SMn+$4Yu;JMJ z@`d1`JSL3o2EI@6#Ab*SEtM*xVE{ud$wm;hnB-wh8ruyV04b}8$T*DQD@*b*kQVbW zhD%jr^Rs9DnhhoEF&WdCJhuU{v6*h8G!E6+ z^pK6s48ySz@Wy7Q5f)b5JT{o)x0do(T|v#Vl-Jm(sm$h7>@>owh0E0(FJ5}FRAV#O zVR@pW9llZvNIVdpv4MXn*xpK?U*Zw-LK~zp#Ag?A+mI||a*^T4pDEFOu@O2i6oVi` zaQP*cvM-dOzO$5lp$xUuQusJpd>GA7z%ogF*pEN)vfKtMStS;xy~1!ZtBn$~y3z>C zSlqj@()q*Yx0q^10{3hI=l{Im+{S4;V671U`)!Bd;*v9WHrlbo?pN~<{F zz*Zr_kk+$?V`(KDOzSx#ETlD$4K9D)Qhr(mbum%+%?7f+yJUlY0dW?Fa@lZcrb&r2 zy<&v!OcN9qy{ne;W~!)bmhuWnQGZyoH>i$k)Pb`L+P5(NEdLV^8wV2!ADeP~Hx&58Oo>|Q8 z?-cgjVs3w@u$K&DT}eD`c;$p+<;ec7o9gdgTauMdw8GkXW2J@nWW>T!_t|^lV0K_z zHuv9^k{j%B{`*pLpF5oY&Xn9x#^nwL{xLQ7cf)M7l;I4+TXVSKSbj-~=^bH&h3tyU zkF=DZTS1Mol%H8ajkc7ZS3!NrsNA7ITCuXNr`Fw+6W726_+1t zDL<`(8fPg#t%4eFDL<`(n#ic!4MAG5znf&ElvdT>!KTmqyKfA~(n?B9>trJ=q*Yvg zilzLt3Tk?yy4&-+88+w_5NDx)W*RQdG%0bW-x{Gi(*%V@Zv!Iji~di!4>lYNi%js+iSGEwNNFtC?EL zD0sih{_cAlj9FFvU3b~vEi)iXE7@RLmm6V7tM2dA^;cL7^Q!whg{`z0CRX=%3R`6{ z%&hM36t>!8Zhxn+H5POGJB6*anA_heY@Nm2{!U>V7{f7f00cbhE9 zN+()j?QFKv!h14eVX52VaQ?eea$6nFe_u*&o5T6px+FaW}1{Z)6+)i&NM+`(K}-)Z>EYm zYbmdQ6m`y0UI8iUf~2TLq5kf78?0nCw>K9JC$ripF{_u1u$`#Xi*vzXi8DeS(*-2P5se=&@8C9%JI=!9eC z$o{T}>hB&|l9f)h!rFOkrG@uo#KKbd#NqsRrR1JEod3R*+}{r8zcVHGoN>8BiT&LR z8!crx!?2IMG#tw>DKWjTjIfYharxJl@^dSwHbipvkTl%G~Xjj)uTRzZ!ll%G~Xjb>EthGKvB zg^f~LReuMYKJV|oG#pDSDKV{I8DSx<;__oG<)>9pQm+)>53?o#~cT zDQ>iw;u%(2NpZHA>2T!~XYN~vE2lVfvmCCR;>^wA9K4lf>o?bl#uSU*4_~{CLmAJr zD9 z{LTTLUeJO|9nk3pEx3$>tc!{L;Bqe>%ZWFHcxiS4D5n(;%j+qsv7lBu;?lb|f?;J` z<&lN=tt3}_WZ|7F$u%BXc<)Mb9VheV6t~;;PMFdy_FGJM#v$7qEXk8iTFmuED=np3 zSZs2*LZSt?HFNyY9@=)dInhFeaT=!lgC+BnlNP7^qm}woPFN_epB&Devf{QooLgCn z+u?9-T`6v-;%K*^ZFiRwt))2cHM=dTQru`U#e1x@lHzQ!*Wt=3&fGqSE2lVf`yH;F z;>;c7T;4akyoH~0|KdbriuJau9;rEGQJ!PI?H;z$kYls$Dvu)$h)Fivt^$ubpug=Z z@R$So+pYqSJD|VqD)58@`rEDoPdcE#?JDq;1Nz&p0)OKm+aTh$d)kY~a#GuFewHaL zS!W!U*Hg5^H|<$RTzc0=FxZ^)$in+plIK0L@XnRw1&=JecO`j|lX-KB+wLVNOzGC! zE-bwKKKHUEd9q21xxQkhrBn-xs}5I4wBY{C9Dm}1w%zMav`}H3hHdwTCG(V%7N>mE zO8qG(EELx*hjXW_xZ4irR+i%KIGkHoio2&c+AV0?z3)V8Db9P%152tDH(E^bUshU4 zakhBqaOD(d?vcZlQ=GZS4p&Zb=ALrSY`cFu(U@Yr?W!joo>`RVm~Xq!tu*A=Y`e%8I$=t;-gaT(<=gI8mgLDME#`WRm6lR1EWUQQLZSsXK6Cto zaN2e!IMG6daT>PWiI&V$PFkGuBrEl&oUl+_-#DB*WyMW)IJdGCH^t%Hx>DRU#nEm- z+wOEHT1#=>Yi3wdrMS^zif3ABCB@m|TZb#BICHZcuAJh`&33qQiZeHtb7tF}=R{+Q z^|q@%fSzwro@2i4F0fL_G5tPW^8+mK>q3qs{W=}|#8C6|LXL!fZ>ekZ6GP3<3po<{ z!6o=9G9uiFWuVSmlUI?}7-1m1ea^7TyPvT;q|2cY-9>dSv0f zAj$Qd%!_^8#x^)%O1Iv|U?Jn%*hWk8WRn(iy~#>TsTLNS9j=gQ!EFoNfL`#Ar3N%# zyp+C_x%sU02PaBX=D)Y1X&`^JWSFwh;*@{l()>Me_zOMTO{{1iNig4`DQ=BAH2#^( z($}%!R~zlrp`va6I<{Sk;il>9*!FM{ebX3iXnS>tJb7_Z_TWpaM1^b>2emahcpg?(0y|Hg6#h6vIu^ z7V?mbimky;tJg5E!;w0>k!$hEu{OP$bst{#V}J;q337+JD!TcdO$4x z@}qf2u*(kCgr87Ge69)ay)1@4L=)bMD2QR42n!|LpWqfUT!o6MOY7?hN$|vh2J<#j zN(yy2FkNz#(if7J^rMx&kg}xzLg@<$OZu;vJ}sh}g$Z6VzUB^2uIYfZ7d z1s!H?td!F-ygxOLt_rgNFxLT2bt(Kc@(GZn*4(-ty|i{utETZhO~Z6Qte(iSpD zG2An4A#;_;EkAMDd7AKwPY??j0re%ekcB2z%4QsQHn*UItH9T1GFe=KX$$#I zhsaiKAwBpOvQ#n5G;bl_D^Ve#aX2uUWt#94%82Ef@ZQT}=qohgt%!nH#fh*`#w}#E z3KdhA*4H(X;E4kbzE*3cq?ERF$#qI!NLtdbSNcNAl755I7ZR5Ao0vW=qHzn^Y=V?C zwT1K$TgVnovAhKf%-mKjE95SX3TkefVf_4Y<_E+0Ipoatz_i0TR^PVvaAStg`|pqe zN(bLK7y|?TS?EI|q5`w9lL`8fQ}`Kc87Mgg2Ap;aJ#zvDI_+VCKIDY=G<#*BOwuRX;Wv06Rgsb%QDApW63njApxyB->C^hrfPtYH@jm8+4iyX&2aYEdlP!Y^ zJ%5X$?yCGx%Yf^b7;rly^wBFQ(CI7_i1I%t10|<*H#2VOP{A;9P>{D3lPy{K-;1Iis{HTEfa{kSaC;#1(JLqbhOa(k z0#W`CWuWAg%KwqjGpAVokC{M}{}UM~Ii>P{D)h`LmjB;OAj|)mij=%^`9GHgb4%s_ zf=Oigzf_TuT`vDul3;eJ{9iMPEdMtuQnJhC|Ji@wu}ym$R0RB$*`@LyoF%D@sr*0J zp@L!Jpdg1RCR?)dA09*lK5G34eoDFZBlt>M_&D$X{r~7`lo4K-y!(jz5Pbm{z(@xU zgOGM`y-uA+IpWYHif8B~89vGy?V;E!il^v2^a~HgmQnnxF%SLHL$L!F|8C4fzw%J~ zES-mr@lg9Toriwyq4s$?4;|~F_K7+V9k0;llVYkc{C5!(+<3Lb(j}nACVIFkvY^K* zo8-xBWyZa}ap6j#ad@%|S4xe;Q(U-GY#g5I!j*F4@H7{$6dZ@AyKtrCI6T9JD@DiQ zZx#Gu|9-ux>cZ~~%yI?QvP;*1vYYMUs_cRu%WjS*uazD5n(M-qvg7bP7p{~Yhv&O+ zrR+Goz=bPi$Ki!8Tq!#aFLL2Z*>QNW3s=gH!{2GR?|)I%h3}AE>c#6tM^}KF``&?d z$u(-MxMhyGT5#ECxrf%uEu$+uv{q~xUFo5$*EV|LQh|vJK!I&?;9Ou?jRm&Z5f=(9lc8VR;-P+lX>_ZH z`UR%ZZ64|um_~o_P`|)5`lE;X1*XxTJk&2Rjc)f)zrZy5vqGC)l`0JTwViIfT4L!E zP-DA1ToqZ+W0mdp%x^%t4qwvGm*ssBJ2dQ7X;e|^DCN2O4cGH1#fn_xo*eyp~D6mY1e(ko0 z`UR%ZJ09v6m`3k@=(9PH2O%P&8|unhW*-O zH(o8VbP1@jCmybfEa)xtj05YEYt&eAUpwMz!DXMZ9$G86jE?irTCrtxyoc6GEu#}W zv{q;to#>&pGRx>B53LnhM!)gUT8U+JDxp0G!lzX5AN6_YG%xHHn7#lM*mMV`0uyR1 zuo;fnD=T{} zark=|u9O>xm$`7I;5fY8g)1e;;T0}iDLM|XQgE}WiqAt=yMk)jrE5Uht?_VGc0rG2 zx7L%_%8q-jbKy$aad^E8SIUmV8(g?jb{yX5!j-b)@Fo|olpTjRyKtrKIK0J$D`m&w zZ5pNzvfy9G;4`~Fc=3AC<&VOCbYNX_jT$TNCr4Z@xa_mtLu=)h(H$OIE4GaO?4h+% z%jixItrc2EcX?>7%rd&$Lu*Br(LEkoE3u63&nSEY6!vTU^UwocxKv=`0FMDtMbo7e|6*45=)nW8vD(|RgncfR@rG!UMn;1b;gA&g~s8tE?g-!4xe-3 zO0jYHybD*#jl&mQxKeN&{@sNuCCA~5E?g-(4qsMqv#E;DL$A1kYT2c0K-pdOa8-6e zk7akwlh?|Qd;Q_Um9pdTpDtV}I}TrW;Y!(Y_=XEt%8tV~UAR(q9KPkkm9pdTZ5OVT z9f$8~m_Epg{n|Y*UN5@*QP_P4)+N`dvEm*$;%dQVpT9h`R&E)6=%KY@%jhEyt(96v zAA4x6&@%eOLu+N0(Wf3-E3%CK?V+_2%jk=Y!dIPPzs5fged&cu1tu;4i`pv(&IOj$ zSYWRmaiPF68Tz$19_kmEMnC)S;d2w1c@FsnmgB*7u!s5urqRzm)GsiN4)IXGz%)A4 zL;V8N=r9lU3rwRU6x!^n{PWO}ZoFDz=@L+5qdZ&{S1Kg)8O8;jdk|Qg9p|>%x_i?V1*D!ZV^viru9*UFB2O?Kf**>QM^3s=gH!&6^MBrg)3#p;aM7{53*vvHrtEWi!Of@HphW=$u(-MxVetFT5#ECo`=@TEu-^2v{q~x zUEra$Qp@N<53LniMi+T#t;{mI*h6bYmeD01S}U=PeotuM{_yWs`@^T9yjxplgKlw2 z7?!i;2BgAbN-V1tM(7n4qe8E=(qc|Q8ElosoMJNAYKu9AWUw_BbBf4dYc1v!kiphj z%qbp&t+$v{I0oA&u(VUsZ((h6qLso)I8@GNi;B_-TCANdR$49|?y=PYi{-^SWJ7Yv|LQwW3K}ii;08#9I#kS9Nh1K#bV;%0S7D=69*4EV6m7u_=^J; zi;07W9I#kS96TaH+UR1xbks&`rIfeHV+NFk)F`ozjvHa6jPmtQSgc$`89QmQatUSZ zl*P&gl(AneRxY26{bsRp@nr0@#mc3Vu`?Dc7f!~`2MoS948A4|{!0%};P-@GFtJoL zeei$mCl%xcU=8|R!=Z4P4(sM}mf?4J@(($$m{{FEUjY2CYB>9o4*hTc_kRrN+kenU z{d>2fG*nKC`7@ytrAQ;rtT9j-Rz$h|Ney|u8pc_u2ocOP(K)4tApTDI*P2{@jvg%Crp*vC`_4qs35%t4%p_!wmO!crUl$3O?Kk z*XN8l%z1<*&79v3Z|0F!TAg#W80B!aIY(}^;ohM+;{x`D6Ryu0ahUU$mNavIC(QXP zE3M8sT8weH+MFZzwc*~SIpYd8)(O|=j5y4BoF&bi-wksfZ>7~aM~ev#SDSO>CK~QN znlmn8lbmpU&WOXDzp4i|uF&vsZdZ&1VKI(44oh^sSC zHgi3)Hupr%vt;bXa5bCn#XFdM?0ObBterfyWD6Z}ee%&}kw;c1AIZg*q`oXXM!Up| zcQEymUacE0bZfkL2a}II(OQSKlc$Dlog=PKKH9AJ$m--HxxtduwROh@ zZ=)CQVDhm!+T^fy^3=I)cEt6`N1H7kS)F_&f6!!D>viXje}x~-v+5=hRtU_YcoLO~iW_8di?X0>r zv-(9V!?LSqg@5hT`H)q6v!b>1uu+>?b??;qh*3GS>fX%is8!lob#G>MOe@2Bs%M3N zg&*~^YHwDwNS-iiGpio(t?WkS%&JE-t5a5KXVs&b)vsC^7D_!U{3|?kZq?qbX!Sd7 z)Mi$1!?(X1l{2fin^~Q;N;|8!n^~RH%5Vd#XN7--@7u9zZ&q|?dcmm8tlojsS)+1h z^-eRZi&kl8^-eRZOIjIjQT43wubnzywrX!ybnkh^sLib2g)?8Ha%S~zGplP>X=n9r zGpj$eGTemfS>azhb^g<;y;;%S<#nSrvwE*n=Nm@l%<8>nRyVEE&g#8pR=2b=+-B-o z;a}kk=dIeC72QAHF={ib_u+utsGM27-^}WsRoYp--^}X1R)*UwV;}wuUv2N`y@`Py z{tVxAZ}rZ#;UwJZoXNpeVRnxkt(_idVSbN|w$Nr!pYg=eyYr(?w9fpn-*|4ce#6m19mfkt@6L~Uj+a(%=LcQKE35P7hkeIuN9)WFJC8R;>$e^) z)O&pPf2lVl1l;*i_c7S&?fjts_}uEe`C$h##L+tQ!yaU)(fUnD3w0sG9KAa~>O+QG zeHWFXwif6_Mp&IUKkP+DI$CFb*o}-bTE87>p?+kvqj%>=9my9~-^I)idXg`#&YK^0 zC0{vOXMWh1j1AiU@T++6X=wj}{G-ruCf3a4t*-x*e@ZDyIDZ?jsV+Dlrh}_=>O4Wo z!m{=j{)W^<6RQ~`3C5E&rHpCC`$oyadJ}#oce07qjFAN6DVkEov=mKMvak@mg+DMg z&BSWPNP_WnO(|nqBW5UBc!$1)A0x~(v6?ZGVEnD7lrg<|XDL~D>%4_OIyKwGYQ{){ z@f=MlV|rK3RkF}*zlDcv^GvK}96ybjuPJ3rt@r{Z3;pn0_`{|PO{``dKN4A_DP>IE z@?s?mE$dr&vbMy;YR2(%iSIO}jH#hrs$`+73_l$Fy@}O~F_{pg^kv{0}KVW(s0ThlyIR=omXjLT)=PzTWzCN`?!X!F`TxiRcx&m(lXY9A0e!> z(W-r1$<`ZA+tXUMK?`Xy3qN|i(MGHGaXs5)IBicW+GZ`JC9MV5v@JGTwU4XXR>Ns~ zTGzH|AuVhzxU&6VqgDI3w*6>0ZBMJ)4ke6@K;B~EbW&@m0Z1C?>33>PH)RNY@h+|D zt~AhF?$(+fN(24b9<6y>X`sj1t2OT^4V+@^)0%gc2F?WbYt4H~19#X5wB~)Kf&0~i zTGK*@#yN>_H}{KCnN&lr4;htCb_-7d)i=PuAuI-=bRpY9+Xk$&mX zbiW$@9n>pd(P28`t?O%-@8YC`ZeriKKu76_cAxchuiQa8B0bon=`Okjm(tIDMThB# zH`GI1-b)AFS`T%Bj?xkBhWT^{>4@}jkB;~D;pxB;1xbeqNq6}p{VRAWiTC@Xe59kK zB+JnSzJs(R{tK6ny(u=QUlt@C=OuQ0U-?&X^Fj^k7$4~{FVXVr0^dI5I@FfY+^Vu9}{FOi?*^3<<}#|^(JNIK3->;fnIS8($} zP3sgN=`b(Ra%zF^C@+zp=JM3Jh9?oH7bG3$CH8|e{42P5q4ssAk93%qX!&h{?of`YIKbi(63>yO#~?UOTH+%v0P^n&a(__x8UE4|;(IiM`rb$4IhU9PoOLZL z$o)a#2k*;Eh&w3!{C$Ow#A7uvC^%YMS&;jK!cWUrl@NDO_@Vh~ABm@UVo-3Bx27QX z2ZbMTuPq_&pzxFKbv_ag4aK0~;Bb9G?hgt-m)=l9+(F^T(;Iyx9t?{?!Rhd(g4`bz zKJ2!+gt&vkr{1>sNIZ!agM#Detp&M1D126JTM2Oog%7R$;3M(qTMP=$zke*q{XyZQ zWcTo7u*>)d^XYFE8aNxe9AomA_Pm29qLfk>&BV#*#BpvRHQMJGc|E?0?j|*CM zfOZ!lcVqy;61t}V`3L}eOF&_0xVG;rLIs~@X!{G0ySz7_WgI90g`tH`gT;~rLA%AGN(jO^6?oyAR+LVC8&~UXsR)qYa;d+0(0J#f3epFNf z3PZy+|6~#JhlZ>EZvh(c$pH9Bs`)SfK89D391jD zI21m3I%g@h>mBlSR2 zbYmPIHu}p(t5c2lmJbc5r%E@$kBqQ3)p+^Gma0rOQcpA`KDc>mqt&U#&p`e*oSrIu zQ1i?PYg3Jve{QMDR3r65Q{qFJmo{3RYW#fTmErVM=|h;;Mp&C_y!;zWRi+xL&pyE8 zhr9!c4_pS@XmzUbvy0CSr>9CEunaN6+EnA^hgzyK)kqD~l=v`ZxQ$k)8b6m9VK_Zi z`tW3=5!R*}FF(psm8nK*w5Gzx1@Ikk_@VO`PPjVR^l8JFmekV)EnKTp=dY}^HsNG3 z#^EYcPTbdqi#-#52r||Q*XJBNlyR0cbEd{=yp>kx94#g|Ty4&gn`k)dp27zllbmpU z&aqed#*${v)Iv?R((0U}#T19D%{g*Y4M%-c`0!$y6RyuWb}iE_Y35AL)C?=F&N*7l zbhz4_BloT0sG|xWOw4k^^*P7>Wws^FoT;svW2MzOM~k@*SDSO><{6H9tMH-2d?#F= zb8KW5Sklay`m2RjTAg#WSmbcEIY;h0&9%|T19^XjBc!EP1*1~?I36~A?wJX zjEC<#jFQgXvooBz|7=y(8IRg`I!fb=C+xe7k`C9iGaRh%wkqq4=jnSKrE$h%^u0zI zPtdb?B&9c@Ub{}(ejz6w!$33m}$F=Q*)tbevInh4p=p27s-%fd2>yInk zuU2c8xaQdUH%I6A<0^OB(^`LA=gtLfUpS)fD-Nj7%K$Yi{NKznra9&n`mn!81;Fsl z9b7;+JNU26F3LdBDc(k05_;}L_cfQfAl_m$N6}Ygpy(8v_p3tBo#KHk7f@r5{}T2O z87Ml%mibSi=T6kaU*`g9r}1Ae+>n8yQ*2ak3O#p_F!fwkz(J8ivcZ8lh zQNMbZ3+Q|fkC*SsK+!3lfZZ2*?nK9N54eDi$M9dX{v`uNr+5JMQ0Tc6orXQ)0y>?- zgXG6DP;`ptKTm|7JJDg(Q!b#xq4%3A|62x%PVxBVnb315ItzNv1>poE{sYw)DpWK} z2Olpb!RxFkCVYLch(E;0P7)cI=}rj3wZ?M|J?$}n|5Aq=;2<7Akc zlMsf!WV{Sh?-0V!HcXIV+S)@HcJ+xeOt%;z47V4PWSH&)LKyA=zL8;S)JhU25f7>54kv<%0Gd@&6D%NZGtkK1Ax`j@jZ9Q&6rwx)kMrvx%_kh$|p zAX3-#FBgyi+5v@+cg65h((RFSe>T$pZ2LfFy5bX!PxKXXS# z%64&Gx+@7`N9)o(A>mEUeHAI&#bxP%B!nF;OMeLo?`$5bNZBr~N{=KV>}XYbEF`?W zd7>g^yV&47m4vXP7Uypv;XTeX6)D@rF6X%~}uvjmH)A#-?R4{{Mv&l)*wGTb|E#tn8SYo*{}6Q;coTP$`Ow3-&$3 zbgW_;*O%dnk*2i5jF2MH{EXDGifLSBMkz*`(mFF*ibMzWg^pEB<685jVx%dpHeX4R zXoJS+Sj9B1IA1G9n$nsxR*FO~G)~7Vrg7aFuNY}cE6)Tjia%=@zEfeM3KcB_2K(A1 zNpM5Z01xLVLK5p1&xa?gP}wh5?G#A}KdRZOLJ~_BPl>0gP}wgQ>~u*8KPuN5LK3SL z&x&WNP}wim>bH^*epIQmgoFw;Jj*v*h01=hOy@{K_)(G06%wk^Zn*BuQ=zh7tkC(A z5Pnpj3xtGr#%_3CyikS8esODDBnjb1TjOFOp{=nSe$KQ+h01<$Z~RUY!jJaGr9wh` zV|YgIdlf4C#m#YsZ+_ z?T%{{BRu2oxK@g2mFb47%sL&bn8tNxy<(&(tuz~?h?bi07~V!5tC+^cW|Ly1DJ?gf zrHIy>Zn)lT(XonYTyeH4Mw-%^vrUR<(FqUV{h(tN)41&Xs2FKV3(rqdL@Q5sTzR(Z zSj9B1Jv$U5O=xan&Egw^Pb^ zJU5^VGzSMqltQHta(GlJWD=XBgJVh|)7YFH99IgN$ma0igi^>jEh=m zgIYK*Cb6l7%Ss{B*wn%mrI3ki zYT>F<$W%79aE%nrK~j7WH&?D2i;SE+=+ufB+= zal-uze(^=Bv=i-Lx423s7V>&qM2!<}TAe!Ikt*#(o7P>fk}nXvKKDe_IN?qOzv3cQ z+KG0m2V5mzXn39f5>exX+Y|gwi&SYR+MXV9l`I&jm&YP%oN!O-)cJ{2X(!r~o^q9W z7ym7y#tA#&PMx1gm3E?D_&HaZ_27kw8Yk?5J9U03RoaQV;8$E_R+iTyYMik9?bP{= zRB0#be?MytZ!&!6nl);$h#DvCd*PQ+q)Izc=R1U}oYiiqj2pAi@^zO4BiW~L5RJmYQIw~CRTRI9V3h;Ga96k)awRXpQe*&M}4Ppa3sQbc!U_}uC| z9jbW7o3ik=KRc*ZlK?-V0F zX(wDNMRY8L=Lz5IP{lKz3oTQO^rSs;xfIdS5T0DF(4mTFJR4f680ks7<0>hl;~_jv zSgk`9&v-txMlsTp_Q|zU6t=zi%077NzhU$rcl=ImdNrtEQAQtxVgLjFzVGMC=bHSaXi6(~p``&a^)Lq-3-} zg=b^8n_$g3u2DNQrJQM%`dP_nnF>$I?li%gb6lx*X-YZMTD4os{)wCRTjArCJvvtL zMGy*muVSR@Kf^~X`-7-wpSFI3diH5=?Z>zF12#y$eLm^e(HFo2FZ+wGX^qr1OI6YusXsIow=irz|FqF+TH_{m-Ecasw2j>`!dhD6_zj_{S?bXw`I@U;=v(i$)S#!{8EM(VRZcvhPGu6GAj(i*A3 zma3#RQbPsR){nlmBzwc>L&LNNrmjYa-w80>=;$<*U2RZvB5HJWiph0wk~z}o==726 z-~@7%(ivCq9IZ8W4*0zSUl^UeS~G_)jn2%WWf08aE2A@WXc+`^7^8INYH+QuwZ_f? zznfsJ(V02m_Y#aVI_uiZVZ70qIdp60FhS{z3N#b7#?Ar1-(Zr_nK|Hh8+>DQW)9t( zIZQS>JGy2LQ=!%U^4 zGwnPFIMx1EYwR5GdlqIHotXoE$HHu*Gjn*mnZq2TGjn*mnZsPAqYvEj9N?4ld0J!V zfZt0q-{{O7@LOpX7@e8JJIx#x8l9QLJIx#xDII;3m*)VV?l0CFI|uxRnIu8v$-E4#YuFF|C)L3b_w4Wp;TnN5n$_ODn z_D~~1;R~KuTguyY6}84v-ma^twU+XBT}7?a6rK3up~iX}tY$Ty`ff0s&MKY!ZZyJL zR^#P2S*nuNNNu)MC99FzVyQ}2Behji@k|>}HMTj?YF^W^_79fSnT@I)zomBdabT+eYlklJNQlVduQ+ij)Q97l^i4p+-@ zB~6a$gzgtBt>!pd9CEl?jw5&2 z;c7XK+!2SX!pdoOHNajw5%<;c7XK z+^-H-%W>p>GaQ~gL5^{oJMDz)IgSTcXDn%QOlNmzt+blsXmQTrYB`SFd55dzIC2*p zu9oA-{cboshJqa9o_Em+*K-_Cu`XHCqcIb1Er zk-ILqwh!~+N9^k0fl#f148$XnsA|48@utz`Ha_X#c;S}OMDPe}v=Q2g;2G8zN|?`1;zZyO>q{+iCW5C}Um2mD z2p(gNF+w{LJjeRl2<=4hAZyA$`gZFzs8<_w_pRYE6g)ba%KuDTGJWx=)WdPfG^Xvs zqJY8okELMyM<0CBPEWctPg%}T5#J?IK+Kdx@(LQX`<6=v{yWYIAF-TeVnxeHg6V8c zaa+`(@th=U{kUh_fG|&NB>3T)En<>?kQ?6ZEtY|jSzy3xiO@4EP@vOyN$_$1_JM7!1ABcKCWlW|E_I^5r=Y?3 zdrKzwti>TLOVaj%J=+Ebd+b-2tB7x%D6m~2iDVfxXt$C{`cvWHqm`>3>XfX_OvPBu*(UDl`Yfd29Qj*m`m5CPwX5OCSZ)ybua zqsyioj^!U7liVx<1($$;%NDNAF0t;nrf|=Gt+5osLy_B5$ahK@c>N%WGg;@ zd`XUS*}n!xV_bZWnOM;{l3;vXQ`{JJXncanKKP_hG!DOkchUq)&ItwQQ<`GVL5I%2 zCRy)~dM007o_X6J-Hd7%QWen&z7 zp3utm?A^O%(7RpW4Tk^g)A|YgD_RkLZ_xWO+`Vg82wxUq{%G(O6|p0Yo=Cw^uSx>P znl(7sYeIrY%W#0)w1t1DNZBqPNdGAbVMk~3*M$U6S>X(-vAdxnWxIGbds7m^j*h2q z2?-uJc6keX(Az3fwu{Gc!j8`G9tjCPZ`I{3Y(5{WNZBqvrS(J-!Y)3bCM5VAQkS=|`TSc& z%69STrDu{5cJ$!Zb0OjXn&*Xzl-D8H9=5re@yG9t^vqKCgyio}kg5!oL>^7+N9U70yGFXdgy}{*ew2F}FyR5T7#<1Pryqw$lCqyZA)@XSzCT=dvEIK8b1Z z@)X7Ef0KeR9~wTUYO)OY9+3f;DMFuoP=QWUli-7aeZo|5511zY?)wk{Hq*H}xioP! znUTU^38EM1j?}l1OGjgLbo$qQ-cbKgrzFnfgZjL09UC^N2 z+$3rH&yVTNjBD{c8Su>_177omK3Smxofag)!2cv8T!j~kzxzH!fXyPVPA*LxO%|u{ z2he$k*9!0Sm&kx`6B+RNPUw>nD$r?Z67+2A*FQMny8FEh_)d`lr)5H)oKS&I%d>#W zA@tQN_}>dQ2!P2-rp*>q;j2=x|G(n<72mL{MZmWp1U%MobuwwQL z>vYWb${^USS4?sw6`F2HqJe!sYVH3?yaUHK)J7BZZ5ax_n>3Y-qYj-nCmEb(rc(px ziLtTTVxzt{hrxWS;gWk&qWzB~ga)>q?~*@>zk8mE0K4s6O-><>COc9XPJ;g(-UC=T zKg)n`6B+Q?DfGz*73j1p2?n?JzSk!nmC&5P2qpEe%z~PKgt`{ z%03hG%@_%W`!$tJqYjM^BpJMjy<7YA{G=ZhDi+H@FYMb(9!Bts!=^znHICyD7k>!H zwIS2E9~?HZ;s_!M_D3|uy-|n8N0Y2+>S&e2-Qk#u_@;>h%j1$rhCzdNCz7N&5XTK2 zH;I$t?_|Y0tafPR2mz;4T%LTIIJ%t1aIao%gPQ*@cX4OL-;)b#e`aKEy#Dicg(2M-)YNsDEv34?V5>^6FWnWeo^#!6v6|bAb3qY=6@!acbP@fgToW14F(~K*MG`_;Y>EZ-pxq) zW&Y+${u~UBnJb@hC4ch8C|?F;TfeqJ@Q>2-Yxhe0J!g^4Ff%a4*IXawNO7Fx;J)bG z4jKH{C(Pz^@prP}^UnmB4B_fvLUA-1n!;_-1oyUK;_to*5nwW$tCL9+N0YIA2Yd?a z1AH^jfZp_$!m=AD{w_@v0VdSWTy(PTyp5BOI+ z-oWK_rue&S5(zN*maC%)#?fSU3iqSe9aqvh{Lf@T>j1s11A-nL<}z(EfGA#n9t(L-gUk8kGF<16${a4p`HVwzua5lX}gK2?ExFBR^V!abVsQWfr= z!tXTU?^U=*3cuHcm#OgEDcrLOFIVArQn*(WUZKMIOun@VuZ-c|AJ7NC*jKFLe|8Ip z^zf>#X4?3wHc@<4*Ti6-v|Qjl=UVZ1*C7&Mv5u>w2gcE4eGLCAecX%nzk&bV^&kK& zHZpB=XrgGaB?bpHCwnXmAE|~Atix#)!S(P*@ps2O6X5<6SBL9U9R0Vaa9TxhJ=`Jw z?wjOQLdZxb1q%x`8(T;*kd~ihIT1eIFvg zW*=84mnM!T`%}2}(@%J9ACLjxCNki2Q0S8pD$wbdB>13>&WW(b4~f6~K16`cVXjUt zO&m>*q%c%vTW`@eAJsA6D}!KnOfkukRA_oKiP~EK0j5d>U%lJ6tylBx)}RmD`}U_# zjj{YM$bcM>W?(qK3w;-%z@c1Zf;|1^jQNs^l)Q)n;<6-|Tcbg{t4so|_eY^;!z#U| zL(z~r>^$}eg5@6yVxFi%(?69+KBC}W_qs;JV+t;ELnGo*1sA!g5%IW!i`>$Pcx1sv z?l1%nGeXL7JG!ePl<{~^ldnb?B>bL4SiTz#ru)8>l(L<#`9J}MTxZ}f1r#!!frknx z~1TXpvq0g^*qrjK^B@^UT1kY_=sZhx*FC(ud!R*p9@`g!1_&4oBEm+f^{og5h ztxc%pM;Od*uq2ot@$dw8l=NzEPpQPsXo!rsZV3Xjp+XldxUzgrqE zBd%3~z-olhN2{PftC38QUbXPkAfr^MWR_pG(UM?x=~Wwp5*R?=Zta8GKN&Eff7`$= z@ChX&A(AGIr;X!Gur!o}!qmrWiVY{|FaZ;!Eaw0#ccP6}ymKZd8BV&Vd`v+hw>=57)G6!Zv6tYg#pJ z8?;AiS~Ynav{f~&n!*j*qcyFX$PL=+k`}jY;rr7%$lXXTv?49oRMTrJX4#T)`dwQA zV@vWi%%ZEXz`B|jnv(BhI=uBYFSI3J%yf89)V$D`d_&XWJz4Y6nq%qv&$Rp*75G%m zLvxPhJDZN)(=`vv^H{k)8+y;wJgm}V6=N z!aNo4kvputU|}sEnl8SK*rz^^bvZ8gNx`6M+%M6nL5`z^-H`W})|SS; zqp)=Bpu5bwMYuPIJLtIckP1`h$l*>3e;~v0lp9B2AL@WxH{ej^99DQ)JMl#Ehyr-^ z!|9G{v{OTj{#c`{IyzRyMJ0`=S~#xbs+Ml0_@_BOX@F0>aNzn`5vj)`8k1R6QJ-r@ zt|?&9lfKXpyRJmalLg+aErCB(;LCAWTK=-Ymm{vke_h~v`u>!^KEOQpO^wLkAmBTI zZ)-&Umf(-gLH_9)ack<__@dxUjp)c<7EEZ8d{;wm&N}!$;rklW(V3NcnlwMun9iHB z6ux-)vBuogkxM&!7fN;}Mt29|=8<5m=y#X^fV+M!2(*z$* zyzD)2Q;7X-2MkU{LYPHN+k`BISw# zZw?!QUzzcAtd$>$FdsZp1-VZZd(TXzQmrakxm*#4l0BATji1z=!!yL{IvTah$w-h% z{PBvH)fox-H5JgW+vttbudP{b4QJN6nq^K-Y%pxTpHQsMTtPTne6o)E6~tsJ!BZ7a zRS=M!y#i}vJA}I^OcH*xWF=w7p~P=V7|p|38@I)FTVYpT z@X5g*gDXui8b0&p-C6`p+ zsdz~_A))@R05iEv@P#yHtGndrgt9U{^BBB0%0)}qS>fsUXgF0%Cd4zRB}VFFweG6nhg#9~V;2@f})C3xtd@z6UwHGEzLZ5M({4!$T^Nu6;}J}F>L z^RP1ZFQ=-Yr<|yy{AI}!$^i%EuM#ZuOIF6v|GEm=%7RMD-;}JR%s422D`3eub$kr_ z(^b$@PE=ApQ?i7zDD!s-7J4IpxqAax0Vu1OO*=v_R6BhAbDy3$*D zQ02cmh+5msLMATT8Q`Yoz}A(TG9lSQV_bC*quAmsWb2xpp|%AMZ2eYKx|1zT%GVvl zD7H8Y+4|kiP}>3rw(gkRoOh|J>`AuJZ|-yuquAmsWa}^d?)_Dc<8C zMzO_N$kx4fhT0Z5uytQenV4*06FI{{jADzkkgb_^hT0Z5ur;fu+?H(NYwXz$Via4P zg>2n#XQ*v~16y-y%A{lqE8tuQF^VnDLbm4F8ERYLz}Ebl(wA&ud0gNiMzO_N$kswT zLv0Hj*jl71-Ge-^Y3aoLu-F8&c*-fr(GrWT{X{(6JfPw9&ZcIT59bTvtnWb^(c(uW zAwx?|zIMb6SbC@;bY@Gap=CCr-4Z7uOUq4uWeE&eTA>NO!;|{Ea`g)Z}YZ%z&lGnb1@r{aUuWpT|sm zC(9ZeU^=RDkfXIGpB-ri9IexY!6`iD#g{0pH{&gSat5;VgvHiwA|7U*)Nrc0i9@N2 zW5RsOL9`f>S;*4Ub_Q)KabW9Nri??YO&sdaeH{C|=WKv!s>(s0o;UeyNi*PRLm&*q zttY)I0%MZS9AiIv*#;Pnj2z_X6_Xzvl?*s~wIVdO!+eQN=W8~g-4W*?M;lFk

No z+Efw7Cr6kqU$+76jyMN7dc)*bj=+GU%@yIMkX@~C^ertpv%^9O7$4>*WX zY;hK{b|%swx}m;3O@2M zEw)r5GWM~PLtD!%)YmbC#D%3ALw7&!VMa5@iOAduCx>A!*W4!si7JlA5FbW<>Ok78 zi8SQwGdn|Jj5(;Z&ua=VVYDyDe(DPcGKw!wL%vSh8ERj7Ej*rv`X5|HTBfxXCHV%_WPi z-9$XxTw!=qU4tX^IF)-4CZwx2z_e54AV1ekJ{!^uIQp$3+?tvTk5kueK)WN(L5_Ym z`IRFu;OLHi9Fz}C2yU?w=32sj)La5hry1z$3p`Al zEt!anEp&1e))EWm7HJaARe#LZu(T|;5iQ0<60)_#f)Y>A&Tl+ z%v{f!@pdyY1DScwVpnDwJj^^_!PB2}!Or{zGv00{W*{>!TI|Y9gNK=yDmcA2Hylx8 z;@n`y+s(ubWaedyU72a{F!M?UpTuS`W4>y}+s(ubWac%CU72a{Ftf3O_pupFlbg(V zyP24Q%)D-~D>DrqX5LV6`cjsygzdm)BkVg#bn>yKW-1o}3lCcrbi(ZeLxWxY$p`9W zn*;H^s5InfyPZLK${hIGp(x$m{XJduN9eM(aDKAWNBQo`WMpucn@4$6OxS!=5u0zZ zx$eSu=WkhY-&#&Urgj@#WhbIxWKRk1Oh&Lw?6u;pMq&aovd`d_MjAAX>{sCMO?9$@ zsqk$Z;hT|3$j$+iuM8yyEFClm^rsKvj2Mn7-tjP_+2TZG>|G~^VGS&pJ7kasvpGzW z?|GQf%yA+z_r8326hL01Cbv}LARCaSmgAJmwE?8mH-#E=D zdlwBZyOU^`yA;55NutR^&&hGYh!-<{wZevvicdZ+8{FVSqv7L92_~oFI>uEi-0CCp z$;UN=Tl#3w@bOy-9?w3o0AIJltv({3eEe>3OCJpyKJJ(j&o8-MZekzdmai3V^%42x z<1T|+`e@Mbad!#6nSJ2t>>exJ>Lc>W$Grx(^wFT<d=UrtZMzNG@=uwkjTS~R`m?kt=5>h2$N4(kuv>3`M zsEQu9*xF9Sqk`5{@U$F-NBFfSpxsSgk=9x4%1v66)+=~(1%az3Jgz@s#eFY10aeVC z23I+WXjIEnB{&W4aNXf)E8c1(CLklv7~IlGgNBi3OK|GG;gZ91R=m|n?z+z#+|o$u zwl64fbIBkz4c6%wt+;O_C!iX6$>1s@5sezzP=a&QV4Z&1inkicP4kMuEsdn6c~ybw zQbDQ^Of0V%Vc$lgQ*~^tnaV`KqB1rqC|xB;9x#=>ZiIagiB2BgsF}(`z{0~;hEmOh zI}2E40%JxB7^D^0CX{mOdIZe7vc^;f4S^ z!Oq|<8{m79Impd!ldt?F1|03F32C#B!MoQ6jN&M7`1hIo+ELo{?^gu68IWcZjGecw zu|GFfKtPD;UqmY($G0k%a6VH~HESGhpe2A~aVZk|8XCpIC9~*F_TOeW<(WZz^`rvj&50` zB+rkxWiw4PAFkIFbX=+tj&WGB)&;e>RjJ77IxkD%GV|bYy+vy-)?}CAcFz;7z)_vb zl;rlwwrrN;#E0u=n2xC;T+PXb@rd}W2QjT0dC28+P7XF$vf%Ccf<%{avNg;CFF1%c zXCez3d(qBN_+k!hy;M+eAtxKdXy4#s+N`NeWbS1zOJOhbVDL4jjcZ(m8$j6~+H|7_ zG3^<7$lWF<2b(Kd@U}US=$20K*4zpzylwFyhBq@0dE4sb2;OQIyltyVD1*2wwB3V@ z;w|MNZ#$eEwYR{6x1BXe~|}+?-{f-%HnHZ-ghyh8BCeT;0In7 z!=MZjY1!o0$eeLOqd82e$l-Th7Q>-fgTF6m z%{8Z7h2hZV2M^QcPbMOJKRP)IcZr4S`>7_0i6$J{ob@oHm`jPs+&L#lZ7#52?tD#3 zy_#P#bHT%mVlE{ja~GW)wK*{~elAGO6)DlI*uVVZVcN{eL}c!glcO+~Sg5&QYf@?r ze(}s@4>O9nl!(k-adOn=M6+HkNOYY_R2&Xpt~ro4Ya$If`_0Z!7-J49?Rr6>D^|i6 zrn=u9NSiN_hJ4*Iz`s6da?^=J5Gi~y2fprR3hFT2@XE&UKzok|F^w5{$l1M44z^aZ z;O)MebZhp8udru$kWsv)JmhVrlcV+)SnxKhAcZ?w*&TLKvwcvTKb?yl-tXoqJPIaU z&asH;;VQngX08t!)n&>>F6X&tDH1!z0i#57TB&CL(joog9U^#6r!jC`oiBOqj!&&%++3)tpE~=2kj6N^{JDxkpM8 zu7?SGm|Ir)s8)k28CiVP%~P7pOxS#^AU0RWgh?D@toAT%7G)wb__&j!u$Ndcx27g_ zj1}(iptjZpjbbmSB7f_=EVaSNgTwU(P4+=ddr!Ea(Hy2!njhDBINUf+?B)D5MpqDX_+an=*sO&96u3#Q0 z`wEVfOv7Y<0uA>6DgIH#@OO0I))8BfNmRfC3ZKM)K=BSHz=WxT^qw+S!^7`8RnQg` zRMLF6WF=X~LHSUE4fIVB%IH1sRY6->P)Ygyl9iMh2jvekOqChS)rVEkQO;CSK3uZ0 za>POTNP-Pb92RB9Jan`Q+RB1T${&@iq|7)df1F@_;eF}c(0C|5R!41ZNha~*6)&kL zB;-#dU~@{IOCBy1d{Rekc}XVuPb*%MPe{mrmVlG#yg#{! zoAD)`%5l1)LR=wHjxz$-H>G=MxHm4~9r%v)J0l!D++uhT8OX%S;kmH({V?1)uX~N_& z|L_l9m4^EG&C78Ua?o$iN6&HH%W*SujK7f_zk4}uL5^E*B*z{9*qo&r&30>(qhsui zmOdJBYwA2|A(Ezx|$zit^P0@e*A9N(^kgCUkst#E8J}*Q0P~c{m z;blPQZ|nN(VZlGr1+o!(M5TXte#1lCLLJ}D2|SRIoSkAw{SZR*+|ZM@@mM*Rsn6^5fj+3=&x<(JX>EL|*tuda@lE?&_x$Ko?YYv%SImI@Cv%E5H zyTGX_t+2F1;IL-%ie2D#GOm9L|J6Hmf?e|SSbAPKLW)SB;=d`dT>d7C#(GNxts2N_ zc1xsD2N}6XB8^(e$h{dE+ZKy(ar}$XltRgY)n7~;@V%%|oGnzA5 z{}i~M!I8hH$@Mewab5NVr&{_vBT@DcLvwzSLsi*jijx9YmR;gb30zrriThIE%Cbw` zR|$t&<0IIw#m9Epxst!h$W->&?%(E+S$0lwTHvg*GwzJQS!HM3cLHaXopIkYZh8+s zqQYa#_=EgBmR?NORDF>^P5-07a`~Gm8viE|v}z!yIV+Jy9c1J=i8N{hC#Z z6+NZ6W3bsChNMQ(6YkE0i>-t?{VwsT*-BwFkkz|0GFgqSbWaYMR=J_?6*$W(U^ZGNKR0C}fkc)IEK4*| z2&~}X(6k91lcEH^@p)KBOp!z)nUxC9LIDA(M;Or6)03p|__Rt#OsPa7sYex_r2+y{ zk1=3)h!0G{cfPAtz!YK%={zpcEQ2^y)^K?GwBaO!8FQ_Um^z6>LhBTsl>!1%>lx5B zd2m9~!l-|u2$^D;Mru!L2FpbZ^qvxsuB3;@y{C(irx$6Y_l#x;y#@olXBjd)6sNRs zN$WZJxv3NhB=fw$vPKhyzzZCtN@WGC7%!@TDZv!dcuAsJ1aYWr;BZryQ3eyk%Q|4n zBo67kqVOyf5Kwwm0J@?QW`@^vz*7nwQrf8SLWvMi+QfjK?x=(5;dS}3sS@#|@rJ;% zLK8*)%^aM_dpXPrTja-P{)ngiTLqT$H&Nu@#zDIEGBl~HC(Lm;v)f*VOdY`^tsMo2 z^%w=soeUc6o!EUl-^Reyu&WH2nu14~Zx$TZWE3>tVi5ItdUbUuCT57;MZ{FhEE3$K z8LSsEklV|U>C?JzPum0xseNTA3X10pTCoL>6!#Y#mShw(-!4Gbrhy6JOQ8cL!`M1# z#=(+N?$|2phnO*;`*yZX>nr`h5P?2A2p{b2?wULh?-qoMKp$4Yx>*V;Rny^;1wn~J zMIA}7=6JV*h0z<1mN8p56G`@?f|FDu3Zfq?P$!F`*B>imzGxtl=<$N1LaPCkp+Q)-e&^BB@DMERKU{$g_ORKXrU8Jbuxu%ZDARVty4N; z>oAFgzEt?61Oy87RRT1tOVq-e^>q=kwGxZOzR`@N7BG92TzAMZ}d0ERs8; z8B&fgkozt{`lj^7XId;@-|K)a#vIc6LE)1W5K#J20b;?hlKoUfd@Zm@?5t)ewOFuo z2{Jeo#jvEESD)KbkwHQiBs$47ag^y|3OD79-*#a<|6D|Dp~NDoUo<0$1q|daCCJbu zo-8qC{i*}D7;{MLvce}RAfR+50caphkM)P$?bRY;Yb6$mUDJ%D7BG#3^nH{&B{QZcCjYrkUPtes~LHuc~`-anhgq?_X0#$kLb(2 z!QP&}KaF(7CrS*2`;2guzD1m+ReX}4QB&bSV_{-u1&tjSWuIk4lZSNShiXn{Mgnp% zyCzpIhC)@$1(fio)VRE*2)8ny%IiDM=XUJ+2|u9=lArrofjw>=M6L;p5?LxW>J%2*vV< zj>F0LXm!12sPe?q+$S`|Ef1%BvcP-gVf<4CzI_#~&9ue)uCD z&sM=$XJUNEgiNKr_gu-6^#&Yz!t)ZQFMhmGgk04?Bh42zLn;ymdM`9FHFKdR>#NBL@W~lPSp8mRq zxaHxLZxnd1JdEF5;GLeHEN?0BPESwxtrAb&uru`ZaB{n?3c7ucsnqMXmn>Otz@g{u zP%wSHWoH?Sy5cm0M_3?|?5={NRQbBgn+3>guY5)2t&-uiSZ3@l8BUvJ#vaXxy%x*O z-ZJF&+I*X2U%}Be5j*bw0_4{Ocg43$hFcTNI8ZX&nqbDklHv5WhWsfeE^JUuSZB&fF1UsS}P^q7uELo}E7>AB?O2X1^c+4Nd?^C|4 zqpo%$llWH^PpXTp^w$!ox6>V%z6izg6dk`w#=YnV%~0iu9sfrSam&Lge=6`^c^H4Tz*`+(T0U3ct&T78 z=OvyxzS>G(sDf_iV=DE6izQ3e8*r3`{)mNy>8~ax`dUa1v``9a*A@vA@@?F&suVA}9@0y{? z6MOm{!_Dbgv#+E6L&UN8-Hkp>2$67rac6<|%ELYVt^)7$^kn(&0`K(nguh4PsT-=T z^u1Nk?Q=|}o_=4+lJy20dcq6^(_878Wi09zTWPA;ydRxaaFi-8FMuw_F8PE=anJ1*XG^j{DPxvB6i#b1<0=n?urXbhFcTNSX46HnqbD_ zlHv5~QxWGG2mGCPSK6Y7br5`CGZjVj-%vGA9iXXe{qZ;BCpF7fH1>P$@ z<5w4WulS6AyudsCG!=0j@Y4qdM{e(puZuxttyiCORf#o8P-t#_Lc&o`97iX48sQ=O zE@vp7?L*`l`Ek;aUnFD-i99Rd(1=k;ybywu`sf7=BXntRq7-_u4n{fg19n<3hYC80 zzEn|zv_!(d1_^Ag@^ZFp0*Sp}ks*peYj+6`@y=&V9H7+q(tj>LKqn;j&|`-Oc9pKGQ;pkenbfL%8^-P;;%)=owr&}g%MGWwuI$G(7# z%{w~a^o6|6zpL=F%&|KhQUI^a+{o`~v{PnAzpv3wnHl|oMw`7N7wp4~4vTBtMI2V2 zJAEQ8$44YO*AB(eA&$zhT{kJ!M+$4!Ou~Mwux7m^>@k6jJprrJarL>=5z<0>LZU@M zV=wqbhMj_PJAJCKc0n2YnZnuyW$fn)Yc_u>&Z&r{-?79WE%6VqzSI$`17s4dC|@aj zteJ>FANX1UjJi?jzR~Eqb`<(sjjroQp-*QtU*!!G;TaW(MHUP9@DSw*6e{s|5}gao z_j$h;;n?3W^ZcMbxB6Qn!j1W(L<^DF-+q!|yG~Q8vkGh0Xu_UTShGG8_PoN@{Y@6< zLdNpBCXW9vs?TGksC@-xNk^JLOLVRjKF<6_hV4p8sV*t3St$wotH8z<#SC&;eeSeq zI={Rk(ZYOe(W^4-nCH%MO<`^GjQvev%@$1-uPdzCq6vHFG`uEZC~x88&zA4f0j?Hx zfoNFJXhhwuD6wwj?*Bdj=vEH>ri?Bs%kN!h6rrdmMz5lg+Dy%WT*eUp@BV(4f=s_P z3Zl!-E@Qr8Ad=+$1xINT3Zio~sN?3SiYtb5t6+<4ppx#qlBIFp~l8iSg7HLT6?)kM+^r%)QU0g8G>Bpv*NEwVJ1p{3_zcR{TJWwz& z0P+i>490^6qj(*Z!B|=_ikCkbjE4$F@v0|-v8-SeFLp8*%L_*F8YhFX5{%)liS%=W zuE|}4{Zpq65C3H#{;Z<|E8Zg>hI>&yueK9WXIkatK(8`b=+BP|68#)*O8WUn2fpfl z%m{my1fAThu9?CJW8vX(32lDlAZ_5f=^7j1I#Ef;%vzH#{bU9#tt$uv(|Y(7LE#R| zdK1uQD5W4jPgv~2PQb&>lO=qxn}6Sl8Sg189=*sN0=i)HI}duV84{3{rwwlDq(Q^T zGX}U`fGwG4Ehc6rez_fuoX|-NgU=PriId|U-0-u)=Z$b%(IcHo{zAg$b)SJW0EQCFJ_VCV4QZK2Ju z7usTl+Z-^TJZv?%g$tnJV_ON9zaQLQ2U|UWOAdBayiz~@1axNsY*P8@bB88taffXnQh4UQhlnNKbr)>&>L<$!(ffXnQg-aY7 zCl!7bpSCFk5-D8H1XiFJ6s~b-yj1v2eA=cENThH*6Ig*_P`L9?&B+rr%uQ0^F7aub zLLiaC-I>4&6obNj9J*O5%n+ZpDFhNJ%*+Hz-P zfJ3)Rg@xkNHibYUg+-ab3KWCF104FJRCrK)+NKalq_8v-Sb<_tSk9piHK#tWBV~dNisaT*QB5t-fQK@tukqVuM?Cc!$bVZ6jWpU zDfw}$Od91+3rdpVasFHis)7Ez{J2#n4fPiUCCTt$-;jc8w7)DrZk0*n{S`q;GCblp zrl1<~o8-r>GHKAiE+|Qchy9imRO5cD{J2#njr?tbl4N-7?@U28_;<;VTV>Mle^XGB z3{L=iQc%qRd*#QiGHDLjCn!mVXMqD89GNn$e?srznC7kh_)o|9Y4pmGKQ({8Ze(EU z^yX*X(+9hU2jgqiu;V;pg`=x@jAZj^);MZ##~5fzNADmpz-q5&5W`mQV~Z(wdM@)s zV0KTwosMDYf197Q=grS2Ml`iY*#01MNvD#3T2n*86&B_Gtbp>1=5eU=c^!-n;sJ#= z5V)lOMa3)R2?_O+5=gB-)D>$0uLwD1L|y&NCIesAOz9wEVc{zYrPnNV@xC|wk;$)( zulm7LZ8Y@9!;o*+yDarJ%zTv^%q4;$%zH_c9sUx-`0+=u)_>I+laR4Gn)+DUo*7>U}0fShIS7O^{3H?4Zz$g=;&uE zsn07}Sv%sOJU_#lZZ|Y-h)Y2Csc<~Iz(zP8iX>!Yp~=r~BmBN zDBN~hYyuoZItBSzVzILwfrpz1GJHy3Y8ZUM_h1on959Wvmuf~<1qON#Wk`2#*KikA zK$wEURJ_axJGzoi+RJNZ)=yY?SQ((r)YHiGzj-cx#0EqoYBFRp{~LCUtIPz!4B!=fPO5BCvtaR=OzIRCJ4G!%>p|KrR_Vy%b55#kQL|w2#Y`F}ERGWvU-BUB z7OQk*af6d8ThuIAd^MBC3ybkr-e~C8JV?96Djiwe=%mUPH47Hs2&5kRyV>+m*+cV4 z^Z!I0ZngowJtGyF+hV2()=CD9ZI6V>G?g~C=-=ChBuGR z{S{A(H%O?zt%3B{J!2=qH^T>vXp26x$-u#ysT}|d3-2gse-~Fhme_aepl^V=q<^U5 zDS05F{=NcEm^_u5nT?96n_^f7@9taBypKB-$oG^`t!lH7{GZN~*XCOT}4yL0NoL$}VXH5C%zcJ{j3ofbOS@E(uBcXnm0uJ@^ zITEfK-dzWMb>@=#Jrz%>0}1teGq9OfQrWR$-B$-4b-^X|85J+9GZN}EGjM2lLf>#| zc&t>jjHsh8*<@gL&CCuG78dT$&>nhKf2x46Qq8HOjsrm^19K~0)@LN-=Vc)Eimq;T zA$fikbi^~2v=@}DEFE!BUYKFSf6l^~`WBTjM>i2kc5%VUssRPjB^fj*L^0VtP{th5 zL?qD%3r-ddD2Oi2py5AH?3*}sQrs$s)2WAyup=$$q`s_XW&;Te56d%jFnEaX7Z1My zSYd=650XwE93hWCjlZxu@$->TjSuRRtaKOeO87OIDVSI4D1pVS`c`+q`G1prf3rr2JgT%E}Q3 z<>xc3S;P4+J%l%Syif%lAzevvx9_% zht~qMueqZT_t*6P`gBKgqZKwxRD5!=$>0VX8Vw(>XE5)+qYw0eH>|MZL-EPSW`mo3 zWHfwi$za}sM;}=7wpwAwhvJiuZ3Z{{$Y}W3p255ik3O&p?y$m+55*@RI}L93kWZ|8fsVoF6EWDecag!b` zV1YbjL>&u~O%~p(nb|_Z!ovF*%DeRF0juN(R@gD2_~hb4gPUz+G<+P+;J90lHo{ZE z5hLu_kaTi!v}R@#2@4M&WoTGhqJ^-0eOyN!2ZBrnj#a#@&q&B0&p=*R*Z}6K6IR@@ zpc0UYPYiChknc>p&*CrS$${}c@0bbMh03@=6wa&yw;2R|hPj!p>zFEZ>1YucAK zz;mQ?kfX0mzHlTMaP+kx@N&bBu)2L?13X7M2RZuIk%;XGY=90zM zW+EPDeiiVzT(KFfjF-*0XGUcpGgmCOFq82xb5+23(PB4PBd^&2&yLPPett9g!jNFV z(RD$HD;OIJtL5(|z%!&$ke@sL(kx5(HR(u-2|MYt@XgPi0#2QZ&b5*mOwD&$anFlP zKvwQHxWY+7qgw6}U>txYADEEuHNu_^K_?gY)l6Z6vG6cMKyermfS<*?! z(tMLIEC~iIEf9oYH#@@gyU+x9hExjjv&do#I~fl*iv>J5&2BLNE-?X~82L(JB%^e66@KO`txlt*|%|jMjxXF09Stj7YXm*1Mc)1Di+^7`fW`)HTZZaNj z9v1L$=*Atn6MN&8R^0O<6Offh46bmJ&@i$}fWsMFGJ<*cQ7i5lkqOAiV+L0kNoW{Z zEx_S{CK8U_y zz5?l{uNm=gaVOzv4-#EfcM{BGWbPR!QLtCDVDR}&g1ct(BhD;eu)@li`awk_qSBD9 z7mXCzQbxnh#=i^=^o{g&4vo--smVRl1}4)_D~6^G3``vy9z*YQLAZO6?yL?>l0G-< zKy=7A|0$*9kf|*SKc*2)2pHKa08{x|dGjNeZ93p71rFi2E4)x51eA6pKtJAk-JBO= z-0ai=TZuWOv`gWW5)e>&D*@;)JK$UzgJQS*II6@K5plf)JZbC^*rd?>orva_fqO+z zUqOr2o6_u)NOjq)MDCYJb*-#K9!N;~Z9*s>*71YtbGsHJg9`YLM5huqaTM|06rMaZ zVPfB4c>C^{KVXeMR0nN2$tBJADqa#!NT|P`fI~xlp@>+HKTx0Bnvp?rA4+smYT^(% zEW+^>iCATisLwqSemUY%i54R9#fTrJFg+AcnH*o)AD&)5E@QS6`Z6PQ7GB* z1nQZ{--KeRJfQ-%T%?fJClZ~6nmANGO=0>DXiD#&`F;V$^k-GjRufcG{Jdl(RmMU2 z3kgg2?=Z$s79m$P&`9%?W=KWCK<~>0nb6nV_zOKUe8vA&8M75LktDw^I7u_2Ao`60 z;eIftvhc0`w{_GPW->{iu6RluNXUO5ft@3?3F4c?@g*!jR543iF-iKzk`0MO#BnAYOeolaigK>P~ zarGDVxvdi!By&lklS&hZ$ge3(SD$!yh)2-NMZ^|LERwpS8A&W)Aa^xE2LC)IJ-1+C zx>km4!OSDY-wIBWj3{VcPoUvHCrPYOzZVf(F|kPSj(-Y!fX)$on)Ct&a(4qVG)N<2 zN}L1mBy^AZyp|FS61rESA;WQq+{a-Oj`K{j8=E0NHYFmSurmdg1)3=G&*EVBq@h0b z>xS7y#8k;F61rbASSw;6H-{n9=)K>0D>hetYzjp@smv2tmT02LKc9oNK%^^v7)%R_ zh^dlUB(zX7SSw;6w}>G$QO1#rA+=b2Zb~tOgqBD&%ODPs2RJGk?TW{*?mD z`I{*6KZ;=U9{E^37=@3CPh}wICMyJ2A)co&M-n2nw zoe?$FssyCEz9vImW8vZ{KnMR!p=Q3Je?m>d#M5=q^ia~t!ZQ^W4ipjwo(FI^7{EWm zzzcQIG*HsXz>5_X1{4woUIvh!kh>?|MlCU^`ITC}WAusUW$t^U1~Q23OgLX!v-;09VhQrp#uGSw4rF%&m&qeLIbV zQ2p3uZ!@AT)z54y`1YEq${mzY?41fqE{BHWZ+$Sq@3O*v^=Cf0c+=o28xaj3Zy8{> z`jyOXi|JLrV(wK;`q}x=U#7$<0F(7TGwwHm$Uw#4Z?RSR8IKA$py1?_hGggrcq%_= zgkgMd+9rgm55G4%V#Ql6!~|sGsKG65G-%ZQF$UAJNCnX^raE2+qX)SF6HSrH!ikE= z1~L-zp9tX8o>&FweV-N)v+$HHvPkqZ%@B$W26CSZNPqY3{5Xj7p)abKCz+Teda`5* z*?@!anSUDk3x-#JZ~tIF{p7Ki4wBNZkkRM9^B~a%FFkG^a`U~DV~nE?Z$CIBJp|ii zfAlh_q1cw;EN2+#?;h#z>l+zt{wMuCh;Rw|oC_*iDkxd0sE*EiS-6ra9%|{LMe`{1 z6wh!vK%*^mrXt!(hL;fibaTT?ZCo&)dq~}i2pF| zHIr{S>IkFpH;d3IR-o%PU{puQL3Q-I$+sMJ21j@NuW_Kr`it-62ruQi(?*PH2}#J( zT_)eMG%i@W&mvGq>WZ&dq&F+ha3B)`q=O(c9Y}Y8bP{Bi1L+BnaRiy|KzakDdCTMd z4rF40+(eK$4&=4~xtSny9mu2rxrHF}97tb)+)9we7KD1MsJbN%Bvc)p=hNK-2NJ4| zzBH%blsS-4b>kYyQU?;MZhQlI$bp2ayQzUJb0DGWZf+pU9Z0CUTN=m;2NJ68)&}yZ z1)*Ujs_rodf~xBn+hkeoKu~p^fIRL%P<7(~S>r%Zb>jh9>p)O-HvzKFfuQPc24uYh zLDk&?$P*3(Rd*{O&sq=~{-Wxhb0AICQOz|~_q+pXs*Y-|fxO^AnyRCkYalN=kf!RW z<{HRL4y36%s<{TT!GSbYM>W?#UUnc&)ltngkXIZ?Q*~5x4P>K+bYjsQ9~K1ckv7?Y zmf2V2pxO6zldorAW>8Z4!rmg>6dYmE+-w6zb%Y$`Xp70W9NiSwgRK@J{s}s4oVVG4 zQ5_)%IofXWEl2UM((SMax5THJa1+2rjA{u<$kHy8Z&|t}RMK9HKpjbp!F>)yESmcr zh*&h=b|7NWJm5gYqIuAPh(+@q2O<{DcO8gWG!Hotv1lH)Akf>8K*XYX&Vh(U^SlEQi{=Ff zA{Nby4n!=PKRXbyX#V0r#G-l0frv%(iiV8Cq8a}ZDi+PFHlStp6**}3y=L-&`x$b{c&vn6VM|>Q|s(Gh_7}ZnALZp;ZvInRNJ z<#WCR5zFTS2O^fwg$_h4pNkxbSU#6p5bC$0>K<|+V)phHELZ9$3Vhw%L!-z%n zDGwu7(WgC(SVo`mFk&5j(ZuL8kC!}*SV=c{7_pST>|w-O`ih4Ui|MN#My#fJ>BGC#Dcn6W5#1a?TF`+SW&k)h?YrNW}(GmtDQkl%87%;Vw*{chm&{~-R>Yp zx5cNEJM0Xmt$04U)1<_Qb}X&C9K`6hkcDdNO*?~WYkXK*-!duj$vrHsyB)~rzWCvN zkDbBv6(8RZm=t}ocF@C!#q}KzBUaaUJ&agh4|y1|zP{&S!~*-ihY>662OdT&u^*Wj zeSG$@hY>62F%Kh_(BmFPtf417j95fJ@i1Z){nW#VW%M%-Bi7L`O^iO;_{zhGMe=J8 zBNoYTJd9W*zx6O;kv#2T#3Fgd!-z%lI}alk$+IR#pI@BwFk%5b?_tCOc)`Pn1@NMW z5ewkY9!4yHzjzq20ABJiVgbCunC||8<~>jJUGzZw+C4lhn(;U#@)fM`tz?;jChBVz zo2NsCr;PNVsNsXXT|M#UA{LJ8R=CAV;**o#4X!p4(C{(if2Vi3h96L=+h{Y@=UTa7 zkmM|h9wXxrnVrJZdisXq@n~}g_b_;IEJ04K6i8igJkAQ zbXK7_L>8p*)PeXj8(bklv1r# zShJcE_KAq?q!$7W$UC=B>VQ>EnM3}cQutVah(HOR76AU^ZWw*f=zymbIHdHf!V4ur zKl5}PWg-=RAKxvx-#LL#W@wUB)_*!6**bdE5YVk*PJ0&DOG>6|s z?$Qxg4I~nKQ{kmnysh(=0>qMq`;)tikT1qX+oKsuE*5RCgp8A4aPHF)R}Ca8+J1$X zTI0fCcv}IuXc*lGijXhHMLVb&N-h@d9SMmK@8O4#@9K!F#?R`96kck@C-V;g80x3p z=Mc{(*m{1b15rs#Cz3;zcv#_~ln_MzyT3o80M(R|!1VJ2N_SMF%Soj`f27gnv{Imt zW%O{IRxp7cSD!m24h(X5LZWkdDURZPBExoRQ>srD)+}qnex|TyNfY*qjO`za+d@pB zCv_keH9k-@6ESKma;U7Q6h0TWL7=o>WkBz6{LL07(64nMD#Z(xNhxwj=^KU5N(}-^ z-ztDzu{qsojW(+`qt9rxS-Bbgokq*QGGi3%2Z)ex_uQp$4$-l?jDzaa44d|e;I=%S9q(v+R6H;||>KP$W_3n5UHUj$&7 zo{*b&T7(~HU(yjzDv(I(SA`c+gn-ml0DAi9@0U&EpYvimyru)SlH`!mZwe2kgn-iZ z4CwCeU@iRQ>Gv|^s3jih-SK}keGU@%I4cGeH1Cw4PS(VJ_^vYKYDOMu-d%8{W`ly} zJrXpIHL-TyTZUZC$Ro}B3XarlP|%zqLE~8yopWXxay285G-nkYso9{QIa`3H_Om7) zUGFbLo+k51b56k#nm|EwZU&{-LM=kM4@1cT| z6$1*I%Ot3iHN%d4c^Pv>BauW`6dWnqpdk9N1dU6gm}^#+F;_GaN%WC|BSjk&L{~}B z_#}$S=Fu|dibf)dK2~s~XoG_2Y5|(spF}a+JYL2;Q6`e;nt~%lfr9AT3>r?7m~7VR zh$9$DB)4ASvsi~#Z49#r>Et|wMxd5#xnv7g&0NtXF1p`8c_k=zF*2?!{?kO7^ngud~j4me7YLrO0xd{$}@P}-0I<5&qD;$;Wbih%H98%h-@L8!rKxtC~&|)B8k?^_>*hHuFb3<=-K&oWF@8|4t54-dovail_T4(-NJSD!?NRtF)gU0XHv`5cDU8#7I^sx05=re> z_$<{RAoX?zj89S+s0Vb!k%}aeI;ikjszE^N5CFaO9)fA{htHVY-jg5KDj822?+Yvx zVifs5NI`0~sDMiQPzP)c=8(!^g-<#_Khp@Qa-*7pSmdIAN_9|}-)upkKGDDTITQ64Q+ zjI)98I<>mJ!UM@IVG@jXADL_t3QuT1!t0lv3Nx`^QGRiZx%KCN9 z;G-oBoZqWhOB1B?r8`ENqmd-k-K%SZPnqr#us|xxx8mVMrcF7Wj3lb>Z{Tjxj zDSRh1rwXrj-aI|V1Pm2nW)0k92oOW@^ zup3h_mXr){JSB|>HG{`fI6qxl1zQ>+4XB4omaYySP!9`OUw6mA5dZz5=9Lp=*db*DK-Gs?hh0jzx zRf#~Nn>N?XHYG-Lzh_)rp0U?`y$so1B=e|)yissc-9;2S$L0cL)}2bb zrDRxjrx@D=V`}#}UY@bn-Co6F$;6jw&4B70NlYr*j*=zH7H}xsP7UML8GGGbRjfrg zEzWP2EG^87^KK1`i!)}+J!L4$7Hc!g%ZupVf}=&_+Ptp-IW0-m!)f=I47()-1B}*&waQalk;&2M9%4cOP>Kfx|Ja_!h3yxNeNCWDdlBKJI2h?{0*4I5Q?P4&Ee_scqbTz0lm%82$ z6;FsqBqgGkzE?n}JyiOiYL?w5igix2;wA>O_xUmuOIhr7J4YxXZyhca99_b=hq+jQ z{L*pSpG$^YGG_czGVIkRv6`nK{E~mnl=I7wFBo{FxS-%DNkXBB3pFT~ z5qsT5WvE4yOS!n&UQ zmT88Pi=|txAl!=h{$xcN@&!{XK3s5=B)8&94T@#NcKMMq)S}6yTvc$iW-RBU5;QKh zB2I-LDzDage*v^FD*JrkcKLu-rrTxf+qO3~;D66tJ} z1n6)aIy(^V8XO#H{+r9RQ++OU@*luxv;>i~c1aSnI1a7d2;;9$^u`uLnf9p9lU6Q~ zppeR535N>Dq4GAu-T0G)&Hv;w9VjA6NwtzBlG;H{f?iGz#X}5fjtS^^Dl5KML_Ebz zB*phNi4`LTiia68u2CE(6ps`UPcaio@u()TV#Gl47(>Q4it$%EXuab_#8b>fQaqta ztQav+{0xu@J;U@zS@^;N1V7h-q?h}PB$3z`iU6&IfYeC^2>a-BQgR`k`ab1o_8)?^B<%jyQ`D6w;X?;gI1tRA$O>J#R8LOq;V5xSBOJc(wvp zbEXF0ufWxesljs;xSB6Dc%A^qKUReKX}{KIzmng7PjSPN3ft_k(@IwLI-$mWAziWcnuPiGfu`2a0lQ@}3)wx`gLWL#_ zdge+%rVi4fiwl=uAZk-#AI>k^$sC=QV~a+uFhaGtqYeeQ^)!;>u%okjTA zWNQvjrN7ch^*-hg*Z^$P0Y@fss4&|VJ_|Jn6lX^U^z}@RQaHKXSwtKyW|7z~&B$uN zK<>>9$$#_}n}D~9h$F`=lH08rSq>P;?a7egcqI+9#a{KfBNZ4Vv`?b548113+9uL62U2OOoyA*FW}J}Wf{l<80gbcc5gjQInO zCg0NmM=5eh>3xOIN(}-^ha({UHBowOY6k5Q^*QVCVMQ4Gi9`6K5+8NMUm-mf!xQMB zr}ckoy1nKmYSz|Ms`P z25%UQpL!7XrYnYZWF~U=nUke(msoIjGLo93p`i)!ITcNGs)$4{YWfx|GVrBlL|w)} z?kfQqoIWko0e-vlbrJF8B8%j{(F`HiU?BIcgv99&^Z98VaK*qOtuqQQrQ%Hcod68W zIsJPb@RS0Flzvcnp+pFj=|=%*re6LPH+s@fb;v`BQ$}6=A#P4f1*1)h(A`w ze9=H8(bWYY^^ z@uZ07=FSl&lI)WON2me?(WeTKI&v`6K3y{8frH6-Rxl>_O-WUXEzomS(5uo!rLsL= zvP9tm4yAi3!RU|O@Bqauw4sRDqKQS4FKb2;3>e70A|QQ(shrId)T?F46J#E7UMo04 z5-4bHRG`VR*PzpEDnq_z;F0F*1xINT3Yu>S(4?O9_ldEFZLVUTYGRV?mXalO0}jGl z1#C(ee@};gw5<$zvdkmZ?FC1O0tL+-0yNakjf$mZXBqM|nMazt3XaeO3Yu>U5RRO2 z=!A{)TV=@8WFBemE;vFHC}{4{pm?nWXD55hP>Uvbq`9x)XwBi!k@gGF;Bfc@@?-vh zmF(>@=ozNHCHLPbJ)=^J8lc~^$E1pn~NEG~|2)u2W{z!egca0hN z<1!SL_2G#mlJK#D6lD_%qQ?tRSkw3#MOdN|BOIfjC@EOf_$q}-`J|+%@3c(HrzJ&w zvt?2~D=F&xEtB$jNl{lTOv)D}MP08jDJM&cx?*8czLb>PVn@Va|Eh@iT_Mn@Cw#3b zvLg@%{ou#{Hhp@}ZS)rnMxqw_-B04vsB=qv_)u`tIGdqkatyi8<&f@P85eric>z?N zssvsTK-HB>;6(vc9jFBUEP$%pl)zsEP<56Pcu4?N7b$_4GjOb^y0L%v_g8YHLqt00 z_Y^tODI%S87Lp_5L}VPj?lVWmi^%xD`}^xTa+8SML}wj2a zBF}6IHM*#P-Y=m>Cl$~+5^8i)0i7$MMn@IUc@k=LRRNtZp+;vF(1ilZ-4$W#uZu*C zJ1k<buKCtmn4j zc(Vb$cX=6#Ju5yuhW^{+VIFm^6$M9hFrd)M9xg!Y;n7UHvSi4IN0YItV954?6KbPJ z3yf?hV5qHDXH4((zA)yn>3duUV%?~*O?4AFR5NQ7KG#cwK&`9~0Qz>FK8ioU!pif6 z4j4*;LrPC7d{ANplwSJho(Z@0cTXGX>*=0K@2c$S{S*CPF`sO(0a2N*wuB3jUKaB3 zvYBCw$$+O<3c{f9)PX0MS8YT#WxC3F$kl6Rio#W7z}4$az%{hnMusN$s*B%mnDJ;S z_JvsHG6UJ!Y_Zvm!o$p#5}prxnxlfPR=Cwl ztJ8e=7;g={+YU6_%gsr(bf`5S*Or|Dwf3HqU|c#jr5D^cL-74};Eg!XIVs-IrlYsv4Fn_Z#<`39Kd@&00M!buxWd3A(M#nwpfc;ZmiaZ;P`2+UkUyg#jA^SNi z+5f6Nqi0{vGGBWs@{|xyXTKQ*c|-PdRiQ?p-xj3(Oz+fb@!YTz)qmjzDWez0l%Y~xyfFo{ zcy&&c^Jga|&8J2=(N@3QAmv8NX~4PL%Vim9o2Q3iaFc6xoTj{aQP6)KaOWRG8md^I2uc8DRaolRz%*omks{ zZ%5vU^_-Nf-|;W;aYjBHkh=hKtj7$newUSiW|ZDA(^(nPd_#B71iMo_Fv&K<0nvT! zK(E|(PAd0|)_lUXkpbnN=_I&S^ft_mv)X|-;ymXh=d)Y$InHASIKSUX@JHz!oo!A# z@Ax{>No3h=m2zjc2jL&wvBjo84lI`|J$TI@cJrvtK9E?9(guF(NG-`+EG()sQ zgF!nyFCY_p;~nwvtMV6$kf#@Er1zp`2)zaay_W=Ja4MG%!)HSg^7JB&^j_8sq1Rxb z_lkf_R+qM4)e%oEkVxz`g%?_cfYe3-=wT@=f17l~lL{n~dR^g#6d@q>h5+;pbWaVl zP(CX(Qmf+Hk>g6LKO8jLN6ugJFPfTtHYq_$n*g%%;8v_k;82D)Rf#ALLy z40&qIBfVV(M<@aX%{K*Tg1jL9mJUR{cxazzzrZ22-3l+X2mz(N3NX?!R!@8Tboka3 zrMI8ZUxw1r@hM6#JNdi6e_Ka8QuO8~dO$>b;!iAbLU~XJyebVGD&ji|FN#PA6!BdF zP`{r#qywH(`u)^<3NMuS_fzi+0RQ?HE93_{;3)+TmFYu;7fSr=+oKGaNZ6huFfprNiPic$V) z8FDovk2F6kI8w7gLGyDB;_t+<1N@?jwWtOr$(}4(T9^L_-6;th=#GWOuK&w26lL|W zZ<;IeNcF3NBSjk&3j1{d8kz8K|NhVaqwC-PO?+MWjf-&$-{hB>$j-N3meN<^!QknV zHu2y8PfT*zFySSUOaqA8$~@DPENoW&KGeoiH&jzc|S`TZY^Qh&=LmuHZ;7 z4GNm)C1{{4ZfUS$Tqr}XX5^9P#eyR>8x%BumY|+4o(!--{H2Pys>~$WOC?L{0tew= zC2UeGD^`-rMZ^^iERwvU8B&likh`iN@~6|+iij@<7Rmjl8A>kxbo#o448+pmQ0ey~ z;>raU$=&hadj9qQ9p9NYzc?ybYJqO<6doUP5L`#$GMs80azIic3;A7UXQ*5U z4!ke7C>=KkTbT7$IEYbgg)C(2VLO9mi#V{g(xP-mTWHZo97MFG7tYkKRPvC8Y^}00 zShk1*TaQ|ljWr@ufWbFBh+99f(1?XRWO%caqcR>@D8Lqz)G>a1m|C%O-s)mTcNa5}y=`6= z(_h1b!R;ok^QJh-qV{&Um}t;$XS7w!LJ!nK-@ysUqcWS0I5V5fE9z*{$xoZl&${PQ~L&EU=!}~VEbW$ZD zGas0I_M;iF^r1zFzs*3!9JT?`QMJ-Y38W!YN6ZwKsrd7akC{NPrD`64Uerx`ZTKio|}_n1y5njg>NwS(xXXKX~Yq8Fqp2^sm$3k?<)el4K={Ps}v z%F9Ny%|c|8g)23)u+U&(;c5ZpJsM_AK;V-8ZxyeQCnVJG_`l*dkFFEZkBTS8 z1Lbhv>dq=?ic2bK-&L|$I^m#vcL7UpJH;;Io;up5onCx;Z^bLr`4y=56~O87yrUDH zZ$=$$lMiGn`^<`0$P*H!pH%<{;}?eXg&C!pT}Pw5-aN$`4P@foU-1fgLPCB{1ss_^ z*f-oaCElV4Hs<=MQS69hWNV(Ar?$sT*qm<=yQEDF(*-^%+SCh3uC?ho8QEOu<}qwW zCTuRMiG#geag_~Kx!8e>Vvy62yCrsp+8Q|U^*~K&-lV7xnI2T2{$YMe6IQ~dRnRva zsbuw`lBG;GIM`cOz$Wsy=HU*{aw8nojZx4~J5zr3--?=9IB2l&@Nf+sq2IDi8JgHT zIGBb*Ftl}c-F#8g#}jFQvvt+JpHtBfSK^-k#>>}p1I`j#+UPxJwlSb-#TS+dR1)A{lh9&X+=qHTqVY%0K8HM20?U}1E(g7yzh9GuRh47=t% zW<1(3#+k@KM)q24WrguDv(JK$$Y1Bn$55uykqAlcH@Rb*KYwQQU(J16bNdGec=^S1 z)&VQ*w?u#9ldXdWS64tlqx^>$Os8MNL;5cslp#}J@JRdpg2TFug60PT)ZgFyL4j?e@OnqM%ek1jJ%pKAU%X>){#ZOh3z zXzD61DW9r%teufi|55_U6sx1mU)4cZJ#k6>>xw7U0}|?|8Q3+J?&{F*TIk=(*e&|C#jiKA?zuCZB z=&d%*9}*4!A>8!}H@QhTu4AMVUti-VJ;?aGjqDsZ(s6UM$Hq^HfV|`Xj!SAPBXUNQ zW1~wFztaW=lVhVx!ri5DH0V0ypu5`&$6Bv@dDDHG!4gtX)!$>#b?pZ<8em2S$Nt|T z2i;67EUXxIR2s4~%Se&!WHju|N#M?E(9JDl(MK`pGLgjR6`Uj-Q4pQ4Kzh(EC}X~8 z8gvT_juPcTw@87CLASUHM%i-EHO0t-Zb?Z~%4yI&P{O=H_n-}|2HnyM=MB1tY@{*h zmf6U9&@H!t)u3CUaWn=x<)C}`|L5*KpyWETEHPAr-rW|^)1#>> zfFxRDv{{*1s2r9_W@Z6kYmZVzph#jG1kh#J;AmHe-h1!8_uhN&y#c)e9q7F`y6=UL zc=5BkduE3{;2}`;CTALw2!FLIU<6e8F6f2jpCqZ1)#9fogJs; zgW5`WPQ(dp~{N-xjk}Y!AnQ zZx3KPEO+(ph*I)FnT3#dhKwMfel&Gg0MQS{d2Dlcl#&m}EQGr!WCY>#7gqOrkOsD; z<$)YOh`ujM$%WG_gu6dvc;N`cnfZVRq4#k(91js5j8bypGz;M#3K?EF!f?2UeTa_6 zV}nP+glsV8Al9P+-VdcCJz)Ti8oqa2JT{<5;_9iChMQ*6M{NrBs+3+7-w43MYXUcN!Du$}dIWYp zxS@JONG`IW>2R?zWkx0l%O2h~&<0J|P!-VALaGY9BP5F+LOMLWn=*|D56d3j3!x~X z+5^{v_l48~3x*8~AEeCC0%O_2hY_@FEO2G`NJuTRpxLnSamtJ=5SA@`W}uiG;~Jqe zLDh)Q(^SzxK!$-Y5}t|gkR1NY1lTN_qQIH(l?W&{p(WtsYl)p$Aw0YJCWbpRTsOXz z(hI#fE8hv+*oif=%XT~~g6VKHQPhi3|9X>$yJisD4fUw#kN0JjB!(>7O%}4&LIa#l zdwLYKE6N`I;Q8Ati|ODn5roIRb7G#$kjFmv^JvPX?{I%1wSzZL1g;K91w20n%T5k9 zP;OTft#Cr1a?CCUy*IV^gldfsAJ}@wBW~|k_N~g;RZOa>1 zNFp$FhRA0}34<-284=1O!Dm`$3CY@w_r%mmYdV~qoiZaEgk=xsM9}7NW7zDe$}RV~ zBA_T!tOT5#C$S?h3eRrNkKt8ohFk6nr1U~BS^!oq6u7YyLbH*JVsNd#WTAOuTx~Xc zaRyRo$H~CaC9*x&0*mt`QGd}$f@x?ENed=ZCzT@h1IEJv%>7!UWZ z%wY{?Q>WGBIdUHviDds#nye5Y!GUp4y+_f2v$ed-dx$7cQ(+rXM z(dzX=YLO$&hM5~uX5@pgY~jWjT56ap$M1UGB&HYIFbXhov&4?AFrLla8o^5q{jm(U zMz;y6MMg9mHf~RukqN@Gg*zf>&8*PGZP1-UYLNxahK0LQW@Le|Y~k(*+HC1u;Ax?I zgw!Gnnhgv0rp(9!VcEic2~>Ys#;wf#LTa%E^Fi4IDKoL4KP7uGf(~G-9yfjTkdRtr zL9>wy52wt?0%1899*Lm3(cm`Y(Il-XJTnpev6vNw)+OLc18X)h$APzan*N7<>xEPu z+#fBVsR`+b|5Qpf4m>QM{IdqyYGOX$zDdL<|6G!0d*CNM|qSFARMoNF;vDW%|^Cv8YYUJh9`8 z^jVUojbtv76M&1)W3scLahx4rSs1M<)Iw$QO3Bx0Vxa?H0v5hW=+=WpvWcBm(xeBK z_7+MzO!$wGc1{zEO?VP8u}eaCCJd5I>~4Y7%fSn4_+XnW4EG}T5K^^`xPY(z~&$Ri?-ACpiV^hh5xU{>u?FJ&DSr)7g`B7zon4(RHtm(h-rvSnD&P?#Mj=T7|AEAeSeQg%&~!oC9)&51|6b_aq)xyAioy(&?}cPc1?_Nbq3B+!hpFp#@HeV2-N~$u8T3Y=n)1P1Dq(&fqP;OOF{c_>bIMjXF55sHh`T|TH{dUrf2aCe+!Vy0zS z6A|>Dh~x()6bHRG0GW?kY4w8pq7)M{X*nv)0^|OW5yaE4dq3bq%!C|w;~$Jtvf&g9 z;T{SZemG$G>>f3cRvjz2;V-Y-{#cTxL#E>fTu)yBu^*4gCc4FO{PhObp!oR9i~m%T zRutbCK>Vj;vWahT9RE2Bs|;a0(`@)dhUe47LI=JCEWD7=tp|%_6E7QJOC1l^MBR`k z7MTbnVB(d8ZcI2Nn|R#-)wn~C^80u$_>DMCI|ysEM?~O_5yylzC=U9j2jWkD_^#B) zx23n@v|La_M9{Y*ju(_s9P}LzgwMImnR46pZk(12YKRE>Uc~W&GKzz~?}4iQCMM6R zeh?+;klymEs9wl6O+&;FLxvZSFdXmW5YnzpOf4@hUp_H4rD~X3`R0>6DtF=(Aryn5 zPqR9aH;>6SKZ}TsiSZS!$??@w+i06SX8k;mDzX`h!R8lPoyexgWSd_`#LD>exU$(= zr;YNZ{Hh37WHlCq*{=(b4S(a2F%zpj@_ppnC`sE&ikqgv$#)^c3r-l0x6?n+ z)Qc*obg((SX6@RE6=7$0=Lj?~F}-}dm8-Y)-R+XY z<143~H=gy~Jp(DS=E=a>94a*pkr1r>Pis;YSs`*}IPB}B zh_dC(#Eh+*s&-h%SALqguEc)crh8pK`-<`RkKQg+MVg5C@B|G(-86Ekl_U+ z49B~~gEW?!fL!@6jgxW#4G$47i#T3LMsdu`eGneCtGg}_oUVwIvN1IeF|Uj`eoR7f z%&UA5ZMDs<2#=etj+3%6H4ibbi8y{tLUGJ%eUOgG@7G@!CS>C=2hpw%@O~^E=>`vg z<%ZPBaZS82O3B62ECjnLWO&gC!zXsL2WgDza6H<%B}&PK(=3F$HDq|<2*crS^B}Fi zH)WIuEw{%>xqya;h<8LBFC?Ql=AAysmKUC{yDLu0#&qT7?ug^ZwB_X^gy|^#p_%Ut0xZelqE6E-62f~DGJX1y=4Dfy|eH9-ufKfbKt+dKjv+}!ozWS(; zECvnfxSo%tOcUP2LJKo{KD5ycR?>YUPRmBuM1+1a;`nh1#X;BmpvpkQMCA(eRFaqt zYp96(bjeOCY9hiu7jgWkgyNvj`=EiAIa@ANFT`otpqhxF zFGd_cD4{s$OFpR8(yz^{&cVxZnhqNF!lcATD=3TF;p zjZySW!h`8YWv?Z$pY{1L{kZJ)7>0cne3*V@_C^d_*yEw-2@5?5+8Cqo5XL#{)z03G zQGNbt_G)8q#V9=c@wBwBw|!L8ytvOz`8!ckwrD6CF4DUp!@owr@FjZBhYVD8VdUHX z`*Bh>pynas2NA~)Nhpr_VE`Iitb_8M|Dz-=A5}9E_T!ip#3dXD{=|nhOeNsV{WMO} zVZ*T{)d9^z)XyT0ACyoW^YaKK*MTo$R8Y{UG%iAM{4z#i_ik5&075?)3joEas6GKk zVqg2PQQP*>!>@1Rr0g}&JaE2^IDTdjiZkOoAB5qi8mUsqoqnO`7%7X9l8vZXVC)<+ z{CJ9wuh$HuR&BH~EHkg>b4lAhNfcxHR7Bk)W|_Da$0xd{55oY>MCLB%UP)p$vY{gK z-Z9IM%s7s`j}NOhY9=z@O!rL^vylxIk@t&Peq_dRss4f#R4a`ke2mWQo0yC5`clr1+FpSquIz65qNmO zyr9F4%aua1wt<)MgNbb|tp(uYs+1eqAS}DMI)aW4n{STQ%<(l+dSP~G0ob@!;6^?; z92>bV0$U$k9Ih8qwF`QqN6rquuJCa~N{(z$Fm`dXftCkbc&P_}mGoP~Y~vOw+4GTj ziDY2rRzbqJ@zHGO4hL?KoknQqPAR$AP9Ot2cL@^CjzhDZdmXsdk5`Tc@wcBn_lfDn zhC(4Yx?d7;mOMOrddR^W>%x@briz;yihH_Vn~G#+v=@(bnSjV*FLc zJ5kNXmUgKbE=kYiAljLJG?UkXt7kJB-5C~pdrl&GBbDdH^p37b0hV5n*peSr-Cj)K zgCmP=MsXMKr5vQ#lGA~!moplPG0ozP+8~hXjV)DHao_iq45E`Wtpa1O$_j!n;;^mP zQc81hq+T7-*N{us>se3-Z%zvC-pHw>{xpvrZcJzu-ynA_-ppZ&{W&4ndn==nxYH~) z_jW=m*DCfKO?A(ECxAT5yi%g2yA^I@)J|c zU`rn+gi>?Kkbc!wtpM^-22yOw%D~mfvO;1@aoE=<38mlj#ntoE45ZkXm4UC%WQD|+ z;;^r;EM>4fu(&4S1{pPv3}qYbju`qi;n5mbZ4BGZcjT zPG)EpgbZlUfHocsG_5b_0JeP0Eq zzrU;yW`X5!HXImIDrO5l9_AmECTcUA>n^@2PU>tG8Ac9Hh@l4x!{HA}fa)UjME$Ku z|In1i*Py3QjXW~84ohi$RPA~e7Saw+X$zRPsE~F(Vs2!a>w9UDP0$WsBz?LWCc(PjuW_{eTC+daJ&G{ zS4cn12@*3~C4J^eA#+)INux5fmF~E44LDgw=nRkwsV9OgI7Q@#nP3>44X1?!?5Kzh z34=ulPnQt|mOK$yIz!}#mJEX}ofQ)5cpXbHTGc`8i);6#IY^N)UkA=E%V zi|Js^DZ$*0IhE9&=CQ$>658O1XOO%9H)k=$20bMhyd|fS7&JUKc&k8LY_F^u%iWg4 zbn<6}VDI*fhTx7_Z0?SPRI0Q_?d4UYx;wL=Vtbwx{N0sPNemhuJG?ugVMJOn+mHA1 z^}Q#DDfZ`tVDH|HM&eGh*xUn_RH3Q8#?rB7P1g)=d><6kWmk~`EIlN#tsfuHW*!dV z&5C^yo1Wl2BBT}=F>Ej&O_`wy#Inc;iit73YA8K(d*F$)7@uU-Jh8?}|4dNpySsQXs5KZL|C1B`dfo|P+Xtwg12Ob$4h8Oyq8zJ`c zxtLyHCJ=#}FC+oaj>EH`FJpMCVb=XulkZ=NfKG;t3JiTM3B-mN&xXFUaDEIxqXK*T z;vCv(dvhfMfOZrQ$%*S}z|YPi-x`WV@dnC8aqeBzIV1KhUWS>V;H}tS9M*E6pcTE&e2`Y!@R1$ZF#|Dqc(Ny`3rYq&p zM`ks+6i1DKtZ`IUgZoEOwUsrF&T8-kvHsrG6g64nn5+iR7DruAS>xD517GKxOU|zf z9+yEB7euRq%YD48kX&rV;Y)o<N1LeyDlU<(ah$u?b$Y6G$`YfFea`wWE zMv}Ff#d&*CLTWbZW%D8x7t4!tkYaC62i`8pXe8b=i@jZ%knlQ*^~PhM%W{xnZ%zl^ zF3)Hr-ZYE7U6GJljf(lKiEqeP$_Q;NzVVr2t3_bzDv_U<;;?M#YLQS}OI)~XWOiX4 zaqMelc3};1?CWGU-`b)_pSFHE_Vo!H1$@Z9e4#d)yCDlIE-9WAuE~u#mE^J*9$%T8 z657~My+*Hy=tqEjgSt77D)#7$!Q?Gjoy4VOvdvpXB3}38Ta=m|zAcC8Y*7ip;O!X= z(H>ZA?hcVuZkk7y+#KAQ1$DNkrQq+boQi0Wc6Z1%3;VdwotxLF#u+gTK7 z(vu=TwL}cIv_2tF^HVc#WU0mdp2~uXjd@b=_H<4qv1fSf@R@`*FgQGFDlfM%&t@RS z?yL;FJtr$9&J>4zJ)cr4*4F}VR9?tHI`}d&@b#jskosZ{`+6y%lv~T{Tj*}k0&YBB z&S8q3IU!ivkkLrIX%?G%&5;^SelCJdkIk3ooM*3R5E*B&3XHuWD>z>Phiz?4D1*)x z=h&MWM6oTa0$Xp%3W+VnVOwt}6zoK3a*JEmcQS}#TUG_O-jx*+TZ+TB-b*NrWdj34 zW~UBr$llLlimiD{F!w=DC9!9CZ1BT`hH5~*xZ*HlAfW9r`M#oU*#ltjt(`PBqe)1Z$gWlNEQq>U?3%+An{z@iw_8RdF{fEv5cjmCO08NS#_Q6{ z1{!8hX1-bMl|jhP5)~NRTUM~XLJr&7C!tj96*J#dkJSO1#!@&ipVq<|C>>ZLZxlynF|#nJlwk0voQiDF z?Ad;FLc^sVYv>H*naX2wkYamI2kwr|Xe8z|i!<-Igw$`|rRGt?@nU+hE3E)aCrIqX z58>I&$re6{>3w>zO0)dUl6e}!&Dkk=khUefkRZsx-loGCHMo*K7Tf(TGaN;s| zdKP4ThIcG4meGRAGjcMLN9M7`GjlY#ha$&5D=Q-QQDl*`vm#0MJ~vSY)+rGEQ+2J%OV$vBCS#VqPhBZ;o>Z47DZWW zp(tOHlM#zD@wg~onxl0t$}aY0S&@!K*@;}973o-%oyZkgk&Z>#iCmc#=~$GV$W>X9 zjz!stT%8r^Sd^W}HCd64McIj5??g)Uipe1V&D|-!bKD@N+Y)Tn_Zi95sNEW09KZbmjda#$|| zime$9_uGgGrLMv-qV1q^odW zG8%C7w#ZK$F@qhwlMwU=nCc-iO{%?{gA}`RI?#A8qmek%EcW((Lb5L$^X>5iF}>K8 zR)D1sC3fP6@NDLz1dazE_LWL5v43=|<@@A! zlD;W|6*~>};Pu-At;DUzX20JhF7@j!QP%34aps`*xX(T zsfve#?o%#q_V&(#itTw)@V8G+B{67t>~PuMi%UM-?0N z#bEL1tWILmGTG)a39(KVYa`{+;X0MhG2OoOaRYelEa1h)MR}aTah;WuQ%SY>oQ_YV zDy3Fwz%}OT4Z{-(V8!PU$ie%Gd8Nd&R(XxeD%{QN%1r_`Bq~P+DoJ!)+ z@Yvz0DXr}MaTo2h45WiQBLi=z%L=J8=CH3b5{lPzR67!#nSm7hvNG^>maLHYQXKYm zc0!>ABJJ87YK`i1vY=vbo)p}jn^Q^r86G=4FQH-033D;9ZaFuc=Vw914m~M2ydbBN zI5a$Vcws`r^1HUssrO$l%3+HAIU(4)IHQrc(=0Z3NkUq>#h5e4?c}97OtCp91ap^V zG!k=~#pbRINc8>$jhM}h1`Ud@${_O20u?A+Eh_}R9EWXPlTh3sTd$OVZ4Odw%;~_{ zbs3Gsnm<^-J|SV~taFUJtvASkVqZoBu5J|hi6>@oZrzj+)R25--)BnAzS4c?K^%&1vg&XI2Q-Ud(8u z-V}??y_AsLL;)Vi^FzLubC_atP6*~UWHb_U{*1#b3CT?qz#Mm+U(I2P%{d{Mdo81p znDb{GUQbA7sIQBhnsRuf09I@&*Ys%h9??Kmh-IayE#m;Zzlx1?`1R+mzu@q-cLw0xnR6;EBQeN zQf$r2z}bhgLSjsD*w;r1Ww2~*al`nrj3{C23z_xA@G>q;OE(P2~H)nHIh<5&eLc4uYaZD&~_ab|V#^eLe% z9kaH$5!_Wq6uUAaFtwY=PdqV$vuaOEsPLP7?(T`VX=x&1FBza6rEi_bGLYC?l(41( z2AkR^BDlLIZogbd_mvSHTsa-M+E0{-T={q211*7HkEAlAeo#~WoLdKFF&S%CUpC93@%`y2 z8K6zsjr44t)hB0E;Ob~mAu+`a_H;}_sMKp_!yLXl9V;WWsdynUZOMqh(s3d`vBV6v zbbLa<*V+6<$eJmXeD1QJki%$O$;Y3n7&svqJ29h?Sko*vcZwx(g{9(;#zHr$T=-AT zAdItgjXi2|d?9!{O%}1%!r<)e^pt{ntDUL#;*1QWvo)gxYiG(LsWs-XwR0>5wPK)I z`*|Dx=t9PMcCHM_`if;>>pW4yx(XO<>OxDX@M_ zU+CEap^k;#7kaKhsAHk`g`O`E>R9M~p%)5-Iu?3g=*0q|j)mSA+F*q$t-%IuH8C3o#e;i})0Y^Est`8cn`x4WMB>-9|je3I8$L?6NT_RQ|QK23BQR9{Rpq=wF) zWkII8$k)P?LQ(xZr;=0^!{eIrrA)ImTFr@kl}8zmxhl=kv>a@HomG;35|fR7lO=Yj z(vg90^E$;@4)da2HLPfawQkI(z1;2DuNbIJ3eO!fvaq{#yDX{s2oItgNJx(!o4Q#J{ z8WOa~d<*<)JAN6Oo=vzWRsdQ5|f0Vz7C5RwuP-m~8VXOI%#0 zJqzkf8gn^OUFipT3@+ds@U5g=i6~POpz^L2*!@j zXhha5i_M)7k!Y&6)U@XKned4@Op!TX2 zGa7<9X0f@`A`)J`#fL5?=g{|q@aZ{BkvU%o8fRoQB6F6-=FW^rBcqhF$U3t=Ha99~ z}=f^h4qUI^+fAdfvsO=1@PuYyWSYBjFoZA(NptWZZFS4v|GAC(x32V zp31@Q6&WdOG-9#Et1XGv!K9*ra?zVC!+A{+ER(UK9(-O~pk=)ZZrJa2GTAL0!`1Ej z0@N(r8a0@`A+IERbqfRCC{x3QJ8#N^W?|GV;dygbN49Af^SnhSx^*=9Wgwn*y|oi` z7LEg5)84c~dzN}>P?9O3AXhkPlbu1+KN@q1ne%G1zVXPQ99^rQ|{%nh)+X0yp+SX!h}J1g?(g z$NxNM{hW|mHI~=i!z|th|z$TmqdPIhZ*eX<%odY z?Nk}z+sXzZwaANR!^kTsGjc&#w(x2KH7BHR4X??7Vk1TaUS1dZi5-_IZ$yMfRaYEt z?>7pmMP4);M&3-Bkqg3dro0tF-8c8#pMG0PE;3>GaPf}7jchQQeY_ii?FUwT2YF9O zEpp+$s(L?VMjq_9R3AprA={3r59L0R(zT1|4MNp483E+Q#{xIimoVYbv>>Zph&=^fKBFCPAIqbq zWwWE*eT!f^6QbHE>mfJxE6}ppBCt7s_Ls?Ke2RC8sdIBc0csX*jT)2=%qz)W-Dvk9 znHr9E56**TVbqOw56SAtHtlHlP?_k)licEPx8$%+&{;SRbdkS@chHpGI~6VzM`T3Y z$W(V}jw}Yw#=p~q`=bi=GT!~s?$HGT!D#oGV&H6@+tKc^g?a_f&1m;HS-_1=^=S9_ zLfkBTJ4Iyp2}NqMYk#zRqD&7*yC>yAv#{$%yC-LLWTSSpdrF3Amaj!4$GwnKi*U2C zY6Ow7rxj>r?7Ee4PnXGNJPp4*$~vO}HVeB(4sOrPE6HZv@cgU{)hu`mv)tI7U4)yB zTO$a&=M-pV{JOPt&$ndS@qxdzpm(+Xcjzz3LA1|wx;&MF%?mR!)?&nh`kbzdM3VUu zL_PMrIER^)KcxkKmtO-R*I`r6KX1BP0{gYxT& zaK$D=K^VQhKr1opvDxqq2^m%1jaaz@e`5|)Y}5(CdA}VD0{lM&eDg*xUmdQsGq# z!akT&D7tQe!b3R)X@oAG`olQ|X{0VHJd!AsQRh^*oVXvGq~52{5SpX!9|U^5Yh z;io%jrq)9hK8a^ik>XHL7{+@cD#>c>uG&zyf~o^Fjtv z?9R%-+l#V7;!JVa*GmG$K7dhMoxYrbbn@k%#B7ii1Yh=v%xji1SS}BiFyk3@%3hZN z+Emgfi&cw~&FC!|p-n|Cz7AkTVCij8>d( zeJS!|OJ0xiE0IuKU|qPcWp-hKb?k3r_HbF>-MIbzPDn1y2t`LO>@;PcMd-$=9A^Qr zd`Wgrp+zTeL+m2(3QpVdc8htHl75#?^-_12()C%#AB5`buN83KdkEzC#0kx3zNY|I zryhUumBiUgqVn1I#Lwwe{yU3%OH}n4Nc@~ArtTwAxqXVi@`5`W93Pevq7KvHGNOYe*Ihb769kEqa}t@h zL6A5lCy{9*1c_5~5}CF_kT^Y-7#!<&C60SLXXGHoCC(ERt8v^$g_Hk1LE)Nc>kqXZ;+$^LP zxzKEwxFuyq9tg`8ZjGR7e`GygqE~2clL19WoCf%}i~PurX0W3>B7&X6@1Dm`kM9)I zi~Lvx*ttt$M{c|)0Cz`lJB`cFhVKzli;QSCY}}hNBNK$>{J1ZImdbi^o99377gCEX zXf`Z7kTN3+gk=j4M$i#Fl~zTB8=Hru4;K#$+{gx_*~cRhxU~%L9w;N+7kN}n zFLGiPVC6B19eGiBHuHD{@29QJl^LFMc|uGtGGi5B=1GYinNfH)vp#}jPJC3G;YsnQ z#PlLFRsm+7me`RQg=aI*MDR+>=8Sq}_*oH9j@if`(MdHid{J!_@E;OO-n zq}ZF&fwwm@8i_am&ag2dwMO-Qo9_&7is{9!v;r)>C9xAfgy)QUJAtd05mgJow}*Ff zkYY`DXe7ooi@m*C2Ito25}}5V{3{K;poE&= zFM@S+=jp-YmjzmqQ^RJzUnS&z^O+alhrSlmiydkOSo=m|C!Pq;X1-0}SnU}b<+|5_ zxUK!J09NcQkb}RSrp*Ha)9717;?kxluRAAH*PT#rdF~=3iX9penA=t4C%%}$*|%Fl zu)W`2Zf|!N0mX(~7kCeeo!GJ6;JqyzdtInCwQ1O^>%HU$~32AnkHN z)}s@H$4hcLsYlIYkC&#j;jtm>QEmEsSr%kGhTr|#+;CEGczI4Gb*Opl@JdS?EXx=A zstiJ#6E1V21bbJ@D%M=cVQbgK6n91Nsu0)XYcmj&aq-2~QJfH*T_EP0^8dGBQ4>qc22_N6(TV>cxfyM>M_YB!4jlUrdi(|Kh+o`9oU zBzEG5Lb97%C3xoPlRACv7NKqvx$<+Tn0u$?QcbB0m)iK>JqYIB_gz_x&J1e2=uem@ zf*{P^ofETp6Z1HK?z6PPvh4Ey45H9uA_j*K$U@d%$YFO6TS^5Zd>V!F@}SrU#ouP* zkph(GGRj3s5H26hi&>|s8Fu@GqtYE~*?@8zesT6>9+dYg$ieFRtdw&aGuh}<8DjYD z+0%K{ES=i#&z{LjWt^IC&|Yvvd}J?ugZ5$up)DrwJJaX!feteAC0WCH3pkvGFDDfD z=@@PdJfzr=!)R|&`)iyzAy|7Qqmg*iEH?LQLc&PM&EatW{k0sX*qjrBxz{rqi8;+; zb8jT1X87TP_g%%tPS|3zsW42x*+DZgAF1$3yp@W$H~P$rfp2F)9c()(_j##0!?VUHe8x6k9SPu=K6SPb|6b#J)=i{B%$~olze! z?KER&x%HhyL5fXT8MxY6R!D4FU2H5XP@?y7cg;XL`EqaM?j|b;zU(`>dj=HY>GEDO zAaBaoKwj-F@&ikj0ns^K`y>R;M*r#ZzBx#-E2jfr`(-o|XPU*{_D@J|8d*0`2(VuPL%3?7?PNemhu8$2$dVf}W@i`W-tc=Gr70#vcdKn*re$SWmA9ha@1m{8FV zR`&(4rNE@mW0U8n zG&i|uW+^Yog0#zY654olV(@rjPAB!KdF=7xlt!&eGz)!69%WocvpB}1CkB(3W_41R zhRHTB%M!B#6uulrM13T2d0r(qOc7MBvMTj5_9wymJ5B6eSsv0&2u~qioyF+A!3pC zCGU#xQsMRScSm^Xi+3M?PlT7garg1}T7184IQSyo7bfV;O6L9y3%PZFz_6Lc2+peq zEx%!v@v0aPaQ%mW7OaA!OKm^VY0*F@%V@=1aa5;iWwD@h?YsDaU;Lh6pd^mydtd;_;?|ZO+tc zRIkNpa*jD7vh4MUWAjX-xU9Vqfy7)3WH-hPDc=Idn=wPmxq$Ij%#iXfV0D-GKJa@BT0U1qlwMj`wAbFPM)^{l>(>1Nc^L zc(j5yc}qMk)oz(8E zhfmV7nHQW#xlsmbFCtY+vn2sZC%-SV%EPr;#;O1c+5t?%W8h}1Q7sMU$>G(+BiY_| zb9!=OeES~hs(R^S26^dXsqoSlbkJYeA$`*h>6>*(-#nAv*Wvt4dhYy9dhYy9dhYy9 zdhYy9dhYy9dhYy9`sP%SPoiS7xLzBbZ2=){Ny<4&=+7mTa|xAPLN%8#kV{ycOBl>0 z)F=ner5wO+hqKK9K*cMMK3BU>AFmr3ZY(2jT`4?y(R|7 zaSnc!(W@?N1>p-cYkkeWiFMQS(W>Tx*DutvLHMqAE30aVjaU#Ng})1a zcm0)a@=BE@G;pZ=mZld`)!x&HF2k46rakwX&-kuKH6zm&Op_(iYw zd+ztwZ~JjQj`q*5T>hS)B43h|jpZ`GUHUsvh|V^SQHc7-Xiu--0n-;7(?vshujZn2 z^)Faif1|>GtvSW!P-#i^dw)^n{z0~@#y82^%qcGD>&INl*hqF(Cb^Wk_H|Qg$L}(_ z)za)Dm`5cfh1$x2An#WD3a(P)A=%-j)z-ha&CM{EZY<~0&CM~Fj;^D=-6q~3{k`>u)B4_eL%-vD>kZ?`@2xist-iP3 z(CGfQ-m>)!W9*LNdGah;kUaUHpo-_kXHiG<Ot z&G@*vUB<_M{jsFnW5{;i{+rCRU2O9b58cLEr50smbx9SAF`5(ha!?$ar!&VG1n@BJ z3L`#RUe>4%w97+P>?|=`T{*k{`7aZikQ|@Ws)Es(1oI53~#%1w?O9zHVm(J!|{u7@qU3AXEwj^zBmIr;MPqZiuJBO=KmghZ;cj9a*&S$9w;aQ*d#mo=%@!e1rQe*Ux0~hCP_?(4Tm(d{{*puY zb@wiWIW2mtF}I{V+NQ6vkPpMPk?vlFU}LxWnA(Ve{A^RLal4RSTGrjCG;n5j_y7|G zh=mLKR2X3HGMEvHuk&$J%9p#n6l9LdVNj8D?~VgQrRJc{hV~FXsz9#wat3x&w$dNq z?h|o+3b&bp5$=8ww?N^3=5P;)xP=PWt51pq9~6O`Y9MEza`>FW9)=#zuN?m2V+#~*C6$(%WS><4(= zbPSV4*z2uY!N4BLltgKB|NIA=%>B{aO}hSa`I^<+tlYM_RkKyYEDevO+k-#vR)@>= zF?(oE*I%t&GdVr7q*iV__!jN{TC00rxBk?KHXcKp_BV>i5X&j%A zHfaJyZ31l)enHq$A~ZCLjn;k*p@mAQKM^XAH5xSC!d3OxQCy@H%f4d0QR|z%#)>|D zdR1S8vywh#5AvTb12SSDLE;Pi{-J6J?or^y37Cg%ZL~v+LjpE0XZbJ=QCV+t9YD#kD|Q1EIMT=(LuU!|+RqDN=X2opyeE%e8SH*Zh&ti>b{ ziS(>n*xNHu?%Q1F&S(PciGVt1whYWSvFuc%20i-Emc#kFs%%kh;9((d%NU|H#_F`& zSZ%aXYi)(=|2KbwyPi6`hLtpR=r`BwqrLiYwZ}+vphoxVv8EXrvj=>Kfdz_Tw|6rF zF0sLDbt-=~diB5A9vv8H;;UR>D6c3}s|yB@sdKuP5}{OUl+hEIMQvnirKhZl{4yd_ zgSm(+P3_ixpz!i>sh16{B&!lIa{+p&_|#eMEIx8JDXy))-;jHtNp`!uiLLS0X%2!k(GFc7At?W)bD$(VWF&FS&wzi92acEVm| z7N1~sa}VnJvpOp4aH-rFrCXD_z2I?oqkH*wMwigBK*B&)vIVEuvnogzd<0nxZQuH8y60N8)lVm%~05ajiZua)KptM zGK@P@_o6vn+yXYYYU3L|x_#o-w-hZ9)ui4{iPj|AR<-I-W#0Vm|F@fd357^ecMw{rUf~)&q-l zq9|gh*4UYyYtA?UagS;@m)2V4L0TfS)@;mM*ZkGW>E+usCVn}ya<D{O*<8%j2N@0^e5^^W3IbCOh;G*PTsf zubi5ol8E+d9^hP0^*uX9Hz&B%61JNg#b2n?L~GtIS2 zBI#9(U4|Apfv#IQ?IX7*Bwc;$fNQur=lR_;t0ecUiD(`pnfoENnvRO>;uH5yWgX1T zaLBQGo!b*C_NY>H`G%_1`n+}3b!#VysE&)_~UVe^tY zwg@*0jPtlQRq5)@o7Zk{J26dtMye(_g2o4HJn(ZEm1G+SorEj8g^|JY5E4l;B`}nF=Y=mZ+=F!NrO*ifN-G8|$ZWeS8&zU zU~!KBw;3>Cgz}?-$%%Z8q{^Mk{>nmckE*EVDSu4}ty)-@-#A76{E z&cx!0>GGPH)zbr$YqnQ+Ig^5hdfk>Y6EhRTXeGzDotRoWjvK=2Z4DB2i<6ZuciQNF zXy{zA)I0;)it=cq+Aa?-Y!9{zike$Fe7V2pwF!pxC` z!ys^uQ3$nv7?$$J5?RsN7jkRo@UVZzF&-gzwdiIY@Bb5$o(EB|iB_<~GatmVu`7(7NF{IgL}%CnE*EQdXGtcKa8Twm{9Rrn5S}xT!2^xQJ(QM>X=9w z8D;O(je0gsGQw%LI4(q=_n3{Ue(BO&v=^jABdmtZFEgZ8rn|~;jmOs*0+ImVUN(ry zETQi;l&1n6)?Rg7H*V+BKsSfiq*PHjAVc?!m{}gurHpPM8>Q3&T}_7WTM@HGgJJed z_n5b()V!`CL-*a7Y5h`D`ks_ppzHj8;F!3lVGLazrio~(ZVMp%p_nWxhjdu}IOL+k zW40UVqlaXlh{;)LM~C!hj!ToQba9O~KY;sOPG|9+b*iaF_s$l(NCXkSbPAXkZH>}c zinFDcMl)YYsiO6O4Bc-W)0-Zq{HE6DTQN1T4UL^QA>&Ihx7u!DxH~Yw#;DxxlB77U z+ZaS(Lv?rNs+oJTwncR-b;49|_Ye}bbf}x~p}bd0#w4dIW!&}JI|Jw(!RR2$zMcq` zhtdemFH_E9cLl7bEGBaVuMtxA13IJ+@VK}Qsu_P$rZ(t6DUo&c^8(6lrR#Gcd$7mE zqaDm&;Z5YK?p#6nkW9L4I#PiCVIH5ZC~Cca9KpGQ2#048a*RX;QI3o>_%t}*sYD+o zrdoCIk7Yy?&x@MXC8Hx$mzhnswBv*{%heS)VM6l+$D>)m3jSwJYIjZ)(nL+43C)v3 z-snh`CPYn6o+74ZbsZbZr!yCig0R@r7Cbx8vNU2kBTb4mV;%(0vaJ4r!2#To7puV@ z71y(cG)XdGLi1e9!)F=oo_4FDvXm~jsPi_ebnm%POqFyaHk2=R zT+D@{UJcuFMeX+`aE80Nm@I1tbVxtyaj_<04V@{YO?B@vIa$^Y`4E4?W2+)(w5i%XDW=NO0UOFsd0cZr zj5d{@r!(oYdZYmTXFa|t#73X4=X05KSwB*M{tF)86kVfFm-NLJymnL1 ztZ--Y6)~9wFxO*u$D>}EpaK2YoPaq2txqN6burb-dvgS2Fcg6JMn^a2uf^%~-xO1Q zaY(%5f$)a9dRjs);ygMhbwe@QCU5_un>V|8SEAay)%O$5m0@2QLErb7^yW!Jjg|{T z@^btiq(nKOQ$@IsJQg}dvkJ$v?;oc`Ih<2PxKBOS*oaFi&Qjj9n{`B9H~t%eX(K{;r{A;nsed3TlU$<0s?e=V z=-9Ik%SHbni6{mQ zbP@6p$E=|&&f+||{*~}fJo=K(JKeo8KMD^8qn*JOiF_ulJ5IxWF_$?qcJmZJN=O;;` zprb+VLdT)$Cd_cE;RL!z7o|y}p2vgWrOc|(Nnm7g>$3>fQBP%|^o+rw zCyOUEcpY+dbUE^k%F<>cZ?m+_4(!bXA4PQP#7 zLgH73`So!ARD`M_588IlA*>8tN&PBQDuNihMhZh_bq|U`8NOQ%kPqQ&AjBS_0=;T# z@`7@FPdPa&@9`nNcgWT+@{)PV=Y7OfD-Hhs7NI|2;(rYP05O&MYEW$6SUK1NF|KTz zPne9%A!4c^bGQX!)~?py#(Qu0nv7)lR&#`yY){9()*&4ydQ`-1Zc$yTlqsW*mQwS= zh78?fBPKqg99GYdNcT7~RXFp9e!tclZntQMM!Yb=Z!nwOdpJ!B1k5#fOyTf60R2?; z5RM#t686%n8I7<6Rb#$@bgllq#1G{`=VtwmyVj5b-L-l z6embI={S(uU>Ug28Y#NlzY-@%QjPA|z^6{Vd(7dSu96<}=Y7Z{caW z(xvA`mrJQxVUG^wD}63{DQ3gBK6?0nm5`X#b!5n1<1_1x0V_)l$+bdaR@RXrd%a^K z9EM@0&he`;H%O@&;eZb1n;drl{Y77z8it$2Qqbaky10-0UgTsIc~XL^OdQp+%KhOlmj}H zA9P#mgq%GbMv5f@KG^2qa6xB{Bg&on^jAXX1ROt zM4F~$bq~Qd93B;#>m3gT-bhlxcq&QB_;ftzJ>yt)te-+3%5pPAjm5J|uz<*Ui>NRS?P|{38M)cQ& zG~Sud-xSg!`a2BaYDoh22P5%rCOwk*fMIAmNJRf*Bt8_MZ&9vr4ABR!kKuQh)wryCXZRFR6^ zfFOa(v(q02iIq~Tw1hsf)-SHp&2{H2#GIlKB@{xST{9{@Tz&ZE%iXe&*#u%C1lmJT zp|AQ>94fVY<`6oJ*P_^5i2^FftSd_9fqQ9%4R`bvtpddz|f*^;7 z8uqH08hS(~U5C(h?Up}m(Vk&t9)eeSZ74OfPKD-HDbZL|F9*QL9gJ$?o8oqB884!2 zEZmu-Xfl;HFz?}Xtd7xW4@{4&S>2povz9M5jTY~f5>0Sb`^b9AhVcE4+ba9x1G-^9 zASGsm12%*oa@>Jwvb%O-g{ou_eppJ(2nTEkKk9K;)mGOh*KEtWbQvBK(mYwPpVSD9 z^IDTDx2>(VRc3vX;xRE!Q&|}Bp!c+6RaXy`*XYp|-I$+AlQN1P6Ozv}kA^Ud@rjE0 z*OZhO#8gih3NNe3SWpei$zXV?htYhh{Kedc3_#21CXUZo5@QD;X2U*rH?DaE-`fb-RX}^c7^~g6P5lD zgK7w?yF?1Xh3@8$MR(0Yioyg!2(-JW5*6I;J}UitWB|D!kqAQU6)6N3RO#P43n>Z{ z2qDnEo(isuSNivhQ?zVc`uS3r(tkima;5*kIH5?*l>UQ5k}Lg(#0kC{&gyVZH>JNP zE&WI209r_w{-b1=EB#030HMxt8pcnvhS#i6Q{Gg4j!#lFQ};1W;&e>yU_yVS@pJbA zAb*>5vXttD)_2I1jyyWm;|^nAKu?;CohBydv;zT%pW(6V7;-yts_SQpsX6U{5ACx( z_VCKp{WIG%|B)MQs(R;0iCS5IqeJbC$`PLp;qyFhX==ySLC5T0$#a5nzVL|6$Ff z)u1bXWhUKIapj6#1R6NmC;o`ma^a)~p6TJM3AG08Q|@?;)|aETbzq!twoj*NCLsAn zM62m>5$st<#4=-6ly14trAawWj|$Bf91&|Sm3V0_)7N`ZNMlvqW^CYeuIcnt5Kr07 zD3f~cuZXFZuTN88!_{k!%U}8!UFz4qE~JU7J`BET5?&zVyWntgLZqVLkl6W;IlEZ7t|Ta1b_ot^H@anv2oTxLp=sSruC3I9?;ak{ z$Y=_5_H=liIaELQ@{fvV!(j0DaY*%6U@r}3_Vtg7e6s+?{tnr%&Vnw^0sc{u&tSwq z$RV3pBcAesPT=71u+D~{xKjRW3Um(j2zG)CLWf1iwGvM$n&QezngppM93`r`MyoUXHS@R+yx-;a4>-O_D4TCIlMfF84U}CbcT9{6^pvNs=sQX^^|hJsty>+kC1* zZR@>hl9dDV0h6q680JH7nqzxVNMkO4_wU^}bkPkZApVFJsL+SSr9s_HQsHtJ zXR8e3Gqgk~zQC;EB?FBfv>@$C%q^|JI$`bYF{Dv%L-1|t#X=azvF{{Mqyj+%ec4lM z(weR99k9ydnn@jys>_BfBo{0ZLZDZDm0!+`Pfp+r*XYSJDypw#0NEg+2tvH!DO6VO zuu_i%xd*&4P0I;8Dm35nc(^DN>y}TfZBI{*uU$)*hU+Z#Jl`&aPz4R^hdF z+gM|B`N}CQkZEs^?-hY^5hXPQ{J_&{;>7UUSQwDX!G}elTtG<;0YCP%O4tKqxYC}S z*mmUQrY zSVt%-0^ERnEhH9b8!}|S^_ZB57$4y(&&rhV-^s~2?N9;oJO7Dk25?f-KX>Ak$Gb?0 zo;3K!{7D%L99AZ_p4qlt;ZNi%{fmP|O^(eWjF9b*=amrX_(Z0Om6YkpKUP=ge5Mxv zgd!9N)UQs(u|hG#J4sZ+YFkwskn;cJLRhDWo*Y7+DrnIjS)eWHdbN8P+|%l&ywr$9yskscIP zXdMgJNIjItbc$qz5a|(7MUUFKEIpb-bc&)x5aaPgVM!UgA!6Me{k^ezJ+KH>6e|=% zy!Db2y)drB(H-ll0!)WsP6@G|k#xLIjOnKJYyqZ2ET@E6&r3S|VW~bbx_7-$1nLmY z(?YnHB&G78U66r>#V;3NIs|h{i1mu3Ltg@$YeqM*SBpR$qIp^f_qwDsJZyqd7wU~X zq(dmHgFtUeDzqZDdp(pI)3=IYHXszg`4ie2r*8n8a%{75V%3VD?l8V;25YeU3zpB* z$I!?#ru*Oj`)+DD=6Cm9e_# z>D_^_H3=3m$7JUZ=}EtzgcOx@*bnI)Mn8!*G-1}^KcokAUJ`HJ$4N*0(A~p4Ku@(Y zptwi=(0n(jlC8DBpbc?ob3*cU)DL;lS_uLd3^^KS)vry2A{C7|76|&-6c<8&|4I+h zx_>esD^2SBK&azLhavsEcD_p2%1A%n7$%JVD0PTMS#5sh30^y8;KV{qb7225c8i3T3$6VKAD1}!+6KfnkZq9lpQ9FDh#Lt z=oPr&dfO2L@~#YKORbX0b_4UW8?Ov%wH+}ZvwZ_!P)!>cs*yQ_?*eVmB|K+nK@-#J z0B(CWUkU|M%3iG?w8@^Z~pRNs9?%KdgCr2gdn5>ozTwHl_cugpA%7rt5#k7o^y)W)z!& z)km=g(qJ2#L;NW=hxlKy(aOKU<_Z5!9jBhjSQCx*rqwE1T(r4!x;DqQVc4ch+2YUk00E^D@#7jbB7jlVV661q_Yp11X?HoqqMQ~W?Y zzPrw&!|J!cz;+L``^fzH*m4WoYX1a({lv1MY4r>7@ZZap(S(Qae^63jtTmSAU#rPzf%PX5)z_%A5=@7rxWve_c#uf;xY zN&)AkAaG5)ib6^yc2DsxJafA07BMzLJFZy3%xcUT&*^HyqFNagA4`m()4iaNcFmgi z6WaYoYnlC4a2rJ$Sz8jbdN)(Mn#~(uv0{=sOLQ?~4S=vk=zPXNru%QZsS8DVTM2sf z(W-*78{U1xvyTEF>CNf-&#??PCFRZ53T*+DvDFszI@^l$urnEo9qkB*U4@XfQDMOD zP}{DaSfMi(t;E}-AJK8jM z9MQM+_*^6F9qQf1XuGs$95xpIvSh^qQJxRIo4*iO~hVbhe?2Gsrex+qy z%%Gs%-g*-CcYIRr-J6KC^-5gU<8Yun^mF{aeAPeF3c&655Z;Me)<19U z^dyQ(eR6!;?Z@Z+Xzk3@c0cldU$Jt0+xC>+V6A(><_mg}sy0Sa8*{eXt5!@-tYaCE zw|33iAECNkW#SC}=5eUFOp{FtKsJrBTvF?C>u z51feuD5d=^by1UIH?2w?Ehfdl!2sx$8w#lbOsY(^bA zjt&{_j3ysX2Mu{flTRQ;?1aT}r)IWB+!JwVOMU2<>d;Aq8Z@x&)WMTUPam66hfbkG zhC8Flr_w<~p3&sfND-#7|FAk?>UN)wgXEeIl50A61|i9|f|74Kd?u-yqjcJI@GLrL z75K#I@Y!_OO7N-E;d4kCC!mCJ26XUT9HcW)9`wQU2uY`)J?O*dldd^RSwI38&_S!f znLvjxq{CK%vw;p@M9QTmRgkIiDb$aPabQbz;Fo;h5<(1W$aZ|_QqodKX86EmbU?Fk z)}(Ve9nv(MF&(;sl$s@uH8qX{SK`2y>cB7gz*U48)R67?(AA`)j-YyibPXNQESw!3 zx|R-U8qSOkU8iVVp24H?e7!zYqOwNE#&Pfl9HizzUxRUUy6|X3A=N=@6zJehbZ}Wq zU4of))128itAizbbes?0LaGKkrLniFgBpvY3VRzJ9!623ORzmk5?-t_hd8U~7|!Sp zJ~*Uts|a_eIizqn2HaixAol$u!Byj{fV|rtG|*Lqy@wBvHFfMMAn!GYbnGd@-KXdp zw~BE0n?qWVaS!N&CiWD?e$XB?P>%f&9j*?M$%$2%aKNurbMQOWJWMOl0TgaJfTE4r z034`qF^I;o)L7j6Q~cFOe=R`I0DS{*+eA)B|C=T%X@ah&hhEyk7?*cfjDURrVuq7A z3-BW`2+gBIFwmQLQpIic|9WwK724HNh>M9&Kd$c-ai2!q=J4=PNs4R6!=#I!H(Q9_ z3gc)TNk7neVT2hZBCBw!3$VZ?@&>`_C%rFe*Pp5p=4i8zhtFMqMjdHA1%XSjVq*EK zDeQwgZ#7{`QnI}RXehlxp@gLM8FUmt_SfmP$%GNQD4 zM}0*&f3aj%kh*G>OQi><$C=cTH9R-uQt8#B6HRJ$5?xfJEh16;LE1?{+Suw}tX}i0 z)qs#G`UA+x0faX8T{AQ7AXPw42_TpcS~G)9X&t5l%&7s!ZsF@dWq?i#K-lNVC6|zV zCX!p*p+CK%GJ#FZG3r3NIu|~hvuyg`qrXkFb}pUr>0G1_WAMGMF|mARa*AfkET7WP zGwC$>Ra?E?1h(gO2+GUz4WhAT>zOGpk)Av~+SU4b8{aUG4OQ{I5O$n2`|ttr{M> zpfPDIsbLFYwYzI+xZ3@r*7lR#%^jBi2wQhTNlpJ?jE7IVTeT&$Mfp75m|cx2kY&76 zdNqKm=@PsJu@wfnc+mvQx?=OxnAq2i3Of)GOJmp(ph|1#rEu&hPMJ7&PFL5TvH2!V z>dgHy@^dqYU;!q4`c%Ox8P)O_mXW1>EBa|qceC*~EB231P0-9V@0|LV>|pZ(vcTcf zUF30ave@>y^8d50TUBvBF`LD8U@R1C2(~f~ z#*?g)1##ppM1Hn|tbAq!69h7jfZDW67C3?$h8zL9#99_tz_+DSS%*L5n+}58DEO=H zCANKYSklBKL;bxG|KL&c#tdKV-H=uvhuhO=H^#Fw`}dDcPcVnn_wV z=8wm6H=*Q(U@WYFwcH#XRpda0dPDo-^$L(T2s|c+RH_?s^<^iO4{DX!h^>wVgA^x2GRTVYM~HYo^gGg|{c2sF}Ih z+hmQp{19a&%dwGu%qtdpS=oma}Sz!XE!0(BmJT^!j@GsXO|54<9(Z5960-#+lUf@qN8r zsa_9J9*Q66O7+EQ>QQ*^7lFocm_C=trTqyRXN z2y>bdOgWEd*#qW&#k@7lj4OUixH1?UX_cB|gFdsqEzHcb))?$XnFkf}B`I(hv2Dsb zbSt$Y_Ym>lW@u2Ms_VN_3urxd7xRdP*^r*aNf7-v))j=L-Ve?Kq=tU{0-CeIBTE`yD&^gb~KN(NlE(BOU$ot z2o5eqms7fyx2_HL5fDPAlj@hz=LTIYoTU+wI`1sQGy;S5CQtR@B{s>IaJJB{yCeMN z3WMP>I`v7&VDtMCiCVK<#*?mbd>L|H`#+Z0X_RLcCik9*ehz;(X4J2Zi&Hxo4Yd(B zyDnf8klw^N-1dl2kvmxasDZs_R^>ndymR7Ta^nXx})yIEBla4ouE0 z&MVzw++$!A+FLKQ8jYR*XO4q{hPH#BHg;@(qaHMnt9RrwogMxB2G@AwXQMHcZ_&(- zxqEUP;Q=$#szm$|QW(z_*8)|t63tLq_xe9~vThiw0paq!ilT$r-o|vhI6Xes-jCaa z)leD^)^pdRMvIs;F&yE!Y9cPbcT`3ZVKAD<=jTu1WRsd%2?;Nnm!v@&W|Q1PYk)~D zf(DypKAz0=Jl>+uwU+0eibBg(&T-WJG1LUcX~l>+pv(l9v7l#msfd7}4X}I02(HX_ zM{?FkDrFJF`jltDKMKcC(+fKC_s96>$lt(zyU(AF9rF=BV~C^rs#I7vGqSR?oUdsf zIs*+r(NSpU_w*Bwr3-DAHnKyg9rVKngqHAM#^h*k%r0eTrso&!hrKTa~sAC~y3sOI#YNuNT!pJ7+8~6(`WCAblDE^CbtSj-C~B6og_S zCNH7rnw&h`X*y6>I9n)XcIkz7+rK}Fb5$E#$@%J2vE|c;rTnc}%0CiI`9~kTJ~cEh zi|~j9M48{ow^|U5iKZ-5Zlp0eeR&Efqs?5tC8H9o2o@)%+8j}jU>%WL8Q3=u^I-95 zaerHn*BID%Z7R@_%V2(3R#Rx15#R{vNTsr!IG=R*GS%uRCTtB}BP3e_jm$84uGc(# zOG*c?a#?>A(+j-d%QfYSOkEHsiaj_N5YJcP=`Zdav@!^22l=*?%(L{=5Xt97;KRs= z77I8S?$Pox6|Ij{ns~oSrk70B1DcqrW9tIT?tH@y(;HBJqbYoW5W^wlYNgz>YXjR0 zY1>)yfTEvTef<8qBHI;Z}n2wiE?P+Go@U^hNUX3+ks7fjX+UT$_z5P9wgmXegjq z`#|~SgGy)&n&k!~84)(F=%W?94^-KSX{+Sp5bgt0^0#>DM)Ms$&6Q?DRNwCq%^C#? z&ImR%*z>}_mA$g3H!?Fd(VpA5h?ZYA?%ES()sq%J=!3zmy(3Zu*WqFx5%bE)8Egff zNTA;+pdp^6W*J7UIi{I!=24lmc@%lrgxM<32qDg|TU;LJt>*LFUB=Us81d8$n<$HT zX16NZEbq7p37LtE7%2{q$aP-0orRU@9L;3f6WcOL-e$=vHHDjLV81{qFI9G+T~{pt zH?;9o4DlOGk(BDL)J2MuckyGNb6NJcDt6@_mK?#tTBc3TWpR#HA%i(lu4i#vxVUjg zS6-nw6-ujw-M(G0%f-4f&S9_!aFrqtvsDstW>~XUS6L<{h-@EDW;1BBOP2c@#ofqk z?+E(wWHt}zrxmwOs?;(Tw0gdjsg7W)RI0@d%P<*Srs<1{SLH*rMBNxA8cC<&}sEAA##h9#nEoQ*|R)<@9Iy}#X{e5(G+~3oivxL1&GfFgt+pfum zC^@c(bGXjFGDOxv3{o-m{?}3o?^})SYZr4H&7U%TmH*p_@D+(Hf}*Qjr2MWbt|noB zVGa4POE;kdx&T{7t0St8Nx4QLV8a1D9)>F!9PEH`8y6?*a#jZce~N>>jFS4t%Jq9+8iiO=6|6wSj3L`Ci@j*eK;&4dQ zeoCCC%Ci(@O26FCA=0mm(d6@MW1jU5T3i3ucJMuva6D$tOuidKAbFJ##x~x zMHF7MTr>q-D z5{B}y5-AzY=d0;{%)1@qI3^qARitF+6!!O;$R(C~6ORdzNG^o1V*Ib~Bdb-i_>Q@h z8nC|fVC6m$q8h|NggH(#9Gvj_K~C2!^qHApDc8UHU?x=BRuJpB_oIR)1QR(~Hxq}S zDJ&*j7Bf6dND;+~MOJPrEKb!Krrbtg*ZA>fuyu}zNaQJ2FS5AS2Zitrju9&Vv7!f6 zTq1jurkTY6cezimq{;iqlA)L?=~vIB^jz%VN|C}#ZU{YTNHRj4?>>0{LKZ6mvM?w+ zX?lBub>w|9BHFXeZgIf}l?&9$Ua`O>LC*RpcCFU#T5Nok<4#bOS^r7L#-Jn93z~I$ z;ChDxOBcmmE!;d)u2A?pnuNq*9VM5qHb#PFGoDaGAFWyRnz58Bwe&@RmmVUS%;hk- za34cltbRE`DL85yWeJC+loCOJiv> zhcuO{D4;{dQAPp5Z|7@9RQGbDz-3jOCD7ln2;MWcagSN;AHzC6&S<3f;9u?@^`!ZQ zi}~^eC&r8%76c=5I8%}=cljZ*0*)%M(8h{*T7KaV`GCbysdVBxaEH1lkYmUfoa=lw)VCd+=*q`KiPr!rQ z60q$S;dDQe|4J2iSXo@q$=Tn=-=w_v5X=Mj&&-`z!zHLQ)4Y7a{viE*Dz$cqIiF^V zgP-Jizv7|m7Uz`$@Ti}pU!}AgBV`U5c;y3!U=OE;qaWDB(aDJXCdLO3!B!4#CzKuo zMJksULq=w1jyHo@vVABhz|wJ*>aw-M7F&m^w@P&^#vL*{&U7Hd`45M!Y5Rr0a91E% z7?({R{%e@@H^uc)a7iwMOa9ed=9}WW`Vd)+*V>BHduP(-1AkyHtUL$?Zq3vdr>Rk5 zwz03ZIHgUE)A&{}Lcdk#YYr)-#oX-J)YKld@2+<~VVr3F=Tbj;h-^;DMi;k2`3HUa zDfL}%n(`fA*)r6-ZnFonW(N)jRdj7+rzN??3wzjaR%#8_{O@bJZX&P~TyGp(Dd$Q1 zp{8-HVHcKl&m}RDXrInI6j6nG#LWITx4WDvVf3t9Z+Wnyf}R);UZC>JrZKw8Cc9?b zOcETE;a(v|66vQs4NR)l(pGvP$&3IuAG0w8seXPN zt)Mrbnwj3$l^Wo0Y>^?W=6N4?S87ncNEgOV$l3GRObTyrQoWi2cs4%i;xHaU6)eQZ1!>7&>kz!q9GvY30TYuEeFccBRUqayLdPxNVhN6zW>I-fzb+LZJ4vE13^skB z3QBEka=y)yh|vT?c%QGZ;*qh!jb7C7vH?KMn_`a)u7o!~jXS}!*q%fD-xQ&zgf}wE zQmjjp3ohq=a&{hVVcEuG{WJxa9d$*MvIOH6MPH__jL*`t35z2gI3J|DK${P_W26pIe-@m%}mNFBCZ3Y9q6U zH_NZs#ZDK?XSuQobB$315}?+*mo@PK0?r$D$^7`vVPq&S0KjoaTwO92{O{JIv`9(d6^d@8JsYCX9CT%<|v2- zxfWO4Sm|YPPS1MKN`%g9GWYTnSOK%N-vy0cESSI$vt+x zpQEh9Dng~Ty^LTr9e#^`uLUL@G>^z!^yWS3f86ztX*l_Lpvd|fRx%7_NGM~Jku7!e zy(ZuH;JaGf3nX$v83)A%|68=W&}LPqsTNB(+Q#q-r+E1rM_^83?jge%AfR-b>eREi z6l}GfqyyiAZ|HiCPA@JsW@c+RVtt}v#pjcJpBa_r3L^xKL1?F{^949ZnnlbrLK7HQ zYb=oACd&0mp(P{HY1JL&QFf%dEUG6xg%NK!)G>`;Lka#)3Ov~7B(*UkC5uVmzAB@;WJe@9`~`NgIRli+ zIbS`5(=^wnqr+9`05uh-=i3<7@$|62aQnqk$fXE6RIGNRyA(`J6PXDxi(z2P#PAsN zaCtMG!6|Weh=GP`>JL|_Kg3NfNoe#T-VM9uAL1GVrDopT00xawpNBuYi9%X(ZbkawG$Y~b42fwi*(Yi9?>+iPbB*3J$% zM-A4_4&a(P&dt}(4ve=|V2uioSEoaqK>oF}13Z1Sc6I=DW$o+$4#1fM1JPjqwX*}M zwX*|l_Y_8O`e5zsz}ne?wX*}VZ@hMP0B5?R!TD=v2jpmX%r9$a2XM|ns?FNjfwi*( zp%VdXX9w2K4ovPt+{fD4fzVk3hH9^!9Z0X89auX%pq?UKJ3HW>N3drH{sQm);L*qF zeXZlLvh|npjA@pahT)K1oktip_ipL!9USaR{WYIE%?uUY*Jt>yv*RNO3hYW{L|m;Q;{bzP{v#nuU8!S)WN+5dCphKGNp-U!wsd2sTN$}j z6G3&4keol4uunN&D^7-K$XJY*ccv0`|`*#Z7VDqZ3DeF^>)|HVZ?O-I8nmP4RK2Na8@{ZnAKd}9^sNu;ev1} zW8`cM4=e~G4|eF6awGtHILe7wPA}s~lu;Gca5Q(HU>2jS@oSvV1ap3_T=Fl}$ot#G;DvzzHL(PiKJe#7p zVMa(mg;E4k>UY#E$pVQiyf>trL6DQ|n;O!F0ilALWx^J=vjBUBFx3_!rqF^V#2NSi(04-l+5>b=O&zld8mLH?e=db^E zyG=R!g*Mw}@1LaAp(66}#|57LleE^fEyl;^KS3ERLHfG-L@JCT=}LsBe$639juM=+ zTiyR_{d$Isuf>epQ=@C|$*jF6v-Y0M+IuoJ840QbPGyN+R-?b9ICt|JVTZ0hjq%9Z zdoq}kD}S!NCxe4*p_g9FYbiL)>ON<)_MVJ=cgA=KOFTTX$MDa!_hjVJk?>3 z{#yp->M@SB_hfi>z-~$7Sq1lz5?R~TPIGwH-ji{ir0>=WZrXD^wf3HjTx1vA7rpkL zjD9@DTrSVHXze{2+<1k@#UihCti31WIK=k^&f0r236I&}{!!MewfAJ?t}qqkgsXGc z-ji8-PsYBMvvwwI?M&F(dopY9$vDqPue~R;_MQyGxYpj2S=4W&@U++3douETy*zia z_MQv^MEHKp+Iuo<@5xN>o!qzldp6v*RB^4Tr|>-)c`}2?UpC=n)*w!1J)0MQhu=!U z^L=$5gz3dge7#37R-i$qaW0uf#IC4QkGZJc9CHuQ`fihGlm#X)9h5iIygMW zcgLPfo=hz}qAr}5<6_<8D##Xbx2d)FZr0wrY1H^K&oBz#+Iu(V4I9+IwfAm3Pjark zck?In-c9PydER(pYI2X9H~xP+oHxeFWIjh`pCr@olKtH>$B>_>>8&arIrX1a#@De0 z9D3ffxX^C3dV26y2cjTRd!A%u%XkyE(X5pdod`*4K2Pm(8_MxrYU&hY~3bvIvS6xnLlw*dRQHl9?=J-Q~UEg zt;&5)CJj%-%*cm&Gs_2O*>k=mRpYZWcy$eZ@)7!hH9U}=Dh;)8lu`&iOn!T8&txn3 zh`V)Q{$<^8d8Rzv%;3#kyjirJ|KcH;@-W|(HIF>W+i!Sk^B_EEG&?`nD(>R*34CU) z7ZzMYRfVq9+s)UCd>vH0mzl4*W69gEzFuy=7AqDQ?`+zyyRxE=FHLI;ngxEs zyKV0>Un=qiht}V1zT}Q24<7h^kNHxp2vFC$-yIy3G&umwvpv1*?3teKm#$Mk`285? z`$tp3_Z#qc>gH4(Pc>nABGVjg$f8xHiI)z0dz*aigR~(&_%@muZtbkpwr6UUCSN7O zW67EijQVWR;f|hf68p!gY(_o13|{j}P{98WU^#-Ntu)YI7+hLvjbuj68GdAYv7GL~ zD6OxFY~Gs0R&NgV3ENh(ZR^0+AD}%eiLI6ure0zlnZT6pK?UkyGhd(^Y~uOEL^iP* zY<*jnW9#R8c3W{~xC2@(%Vyx&#T=i+L`Lo?vNBmyxzLwTJTF`P- zXXd+7BlhPIp0YA;`)%kkN{2*m`Wfk-u->Pq2m0Y4d=CK7mS~MnPs7PDb~Ib6W^2aQ zo{+JSWff&^mcZ7k=J+hPLC~y9UX#V(a_G}?Mk{9R*T7~C=;$*R*Gk!u-01F(Mh}S5 z^`Sc6>CWTfu$a{r!?1|ujo9bqthWNO1Q=jPw@v{M4suR|n>WJsfKx9#4wo8kNmb4b z4VSV_c?$Jdd0)LBZFZ0Py6Nalb*Qg!Z2E$_ zZ@}Ue6YvICg*RyNo|AyLc~y9uE#CG7ye+H3+hXxX6Y!2$72XjRuatn-x4I1O3v#%e zgt)pa?hEp`l7zUrOzsPEx#~l#HL@#rBABfYkMW`H+?g9*IUKnyUd@MBTooRHOQh=fqRnSaOFz|>JpkzfA?C>eTh^KGm zmXq7Md}jjQDryz*f=ac^hld=9+SeazhWnjnIIwSb0^Zh0dOPE7wdp-J0dL!?@Hi<^ z-Ne5n;Pv&c3b3!&B0e_>ag{C%eE4r6#AccAgeP~7Pdh68AItWRtwcy) zPa}~24s|vW($}SSfDHQ77bHUZdesh)LAN@W2wGe(uW#)H8g#BFC{R7I zujNabDwY%~xWoE6n^`t~V$TadL13NL3K4}%m zN9y$wYX&C4ej{4FxK{9l<0hxtJ-r)_hqQXrFHADCkIw@; zcD_8>&O*J!Dbs(Uol#>xp2FRhjbe5?23yDU@c&Q{dh{Q-_>s$wBy*+Wm{wo!$gx;& zdm&g9tA}HGmhAxH<}}wyuy~D^jzY@>J|n|1)-}hd>7@TdKoO zeTS)D|0KmjK+(+lgs`%h#>YvgyeO6eXf z$#tbL^Db1I+%m}Fa;2{Bi&N{@r{0YM;W#0e=T$oyTr}C0x&@?S`oPQ-ZX%p&^9k*F zga&;VUn}-&SL!x$xgYM}hmz$ma(7ZL_}rDcO9b67XRXUr>$O(7g*CJE08GSLdHtm{ ze|);94_84U?Ew=Kb*|z#R>^R2{5Icd4uA}icJ4D$h^^fiOC2PWG+-3JCw{; z$h^sXiOC2PWG+%1$0(U2AoCXUB_<aF&ZNcAoi96u;V2!3E) zk4RveD2 zZ!%wEGRD>4Q5=q|Z!uqDGRD>4RUD41Z!=$FGRD>4Qyj%?v4v&aew9m`;kP>?1VI>3 zP8W~3B5=%Iioc-{27z$5`4UquOpv)pak%;X1N%v&Y(9%ho6q+tE^R`eDkjYB`y&Jm zGN4O~Yq&_kh#zSYr_B5~_@n`BnR#(H0&yC($|#zVY(^y(dS4R$?4~%%50xid?s}Cg z=u*moa!Ta855`IW=QPVdjSKr#S)mtR7Wr;*AahxFc}I~eeMQuhas&G@rlwpTqeK(` zweETr`<~S%q>82LXuhPbF(v}GmAX=2PhikMQt{AuC8EH-Z#ob=GPNR_VdZ5e>{}k9 z!B#~xfOdoddy^x{NGRMDoyCT<)56@G#F3;R3Ii>-I2hGTtx>Ls?R3qpagqU!yCskX z=xvT<4LfMOMciiE?LMLbR?Xa>D5$+$)sxIc+X zT6@`){-=-H0XMMsfj|;{S{2K2CESB3)olR44|>U7fm+7QHQ0T`{*|9D;0SzhtAiA~2naO%CO|-3Nu$EOVX?iB1E$~ls9w`U z!odAqAW5Z}Y@@hC0kie_y_Xs?8yGKH&-${XQK_{WxLv+b5W`q*UmBwXve*dMeUwKU zsHci-rdY$yEKS><->nkNf_s{WsG-BSF?k@rJT6>sWK=1Wq1P)C7?#&yaG>Q32ZZGz zQ)XNli(4P7$Sb{M(cm;f%KVTxpkM9Cq8l7W5D0eDfy_4OH9n%?9uagH3fGkd?CTs! z%ztZnv=y9!NfiO|nF(~i(GdjTpXJCiM^WpY@+JfSL=L}>7z(tU8^MrdNE%q8&+}3( zI^^Fd9CehsdVWWx%(^Vn?9wjq(5$TP=3|n;d{ZDdn$K5r_@DLan>{oyrYi}|w}j;o zq|VSTDPOSkVlOojH;@MM+e9`?4>Y!CMvKF$^W}``(l{xK8I=RzWmamaFj7F5tPxpU zFZa-VkReH6zSGL(Fb?c(HEPPG%%&?mG#_S25}5C{a?P?zw?Sp!^BynNhZ~Uw@_Pf> zI$lM|H%hi#vE0AUPxfL*=+O`n9G;dSe=Fb14#^40Z=|HO!X0tnws@t z2|zO-eaxwkBrsSIQvrMsP;j*)kIm<>0`?ZyBry0DL?EExT1Os>Wnl&EHLgow@GFQw zK*1**`TCA*W^|Ofm{;wCwCbNs;_$18frP-`jUf!4v5Q$=wei>$cpx5Ki#h(3;^^S z9ckKM-(kU7&A#d-`>{jffd0B8TdI_c7)%*#*1d1|$$spxJix!@NUI`euvzWC?WOvm zL()LL*^xCFVz60$zLP-rqel>cf2$*J3bDawettKB?#GWH0RMJJ-V|Mf&n*330^Q;R z<1XRJ7MyldudK*m@@_9#0I=2*8U%YVfPYT_U=pD5Su%d$rCRu4$S2@o0D#{Yh@13l za3=qLFVzJH#E%`OQl^G0Z}k#O4+r+DLowLKx6eo)!L{k1_(ZL5&AJIaTXK;h`BO)7 zw2s(SHCyheax+yv5Et|-3{WBUGe-)8q7|u=)%S8T2cO_mb*5}%+&c1z@tiwl(}2a-Y2QO@)0lj3+vOvAjc6v#`xl3tx*WN5uyWJlP+=ki0%;rtFYR+nY^ zcX)_V*qA6luL$G{m0DJpIvnBP=`MB)BBV)Pz(5Re?+IkM+=LZQyU227oaDuGkt}v-a>aV3Qc&*U`q-_0vb9A95MoJ8 z9^kjdr0td~hx)hs$(_KBJizaWOIJqK(go+=clya4!L>ZV?~X~M4cR%=R9gYe>hC9V zbW-74UR~g&dQyJl!No?Y)u^H~N5BM6qFV2LHBJfvm^}D~;=_Ib#;Ix(uAg1YH^blE zREbVU0O|R*^t0Xu1sM?w%^gf{h4a)=iJ63qOQJ1JesmS!xEisaS z>aZSz=!gOCyH=)AugI}mJ(?vH%;Az2CF z{K)bniwqF+^T$zwMS|2%g;?BKYh@a;3>Eb655!5X4io|)Y4K=S8tk}LTu zMJ}PRqw&oT*D?(^TIJV%vWxJru#93jICSDdJ2O5mWsN!TyBNjFp-E!ljYz=fqfO@HwU@d4*FW8pj5U)Fkn9xNJ1T^VW!UY zvm9RQqb2}{#DVJKq6^JZ`3WyM0Xqx;@J|KOqxGhX&9>sxK57DVNF2!52eNf; zygS%^9O!@6PftLPKmh-9fqZ_K>u}j>{k)HwfE^MC@)rZyY_;gx&CQ-K`KSrVA#oso zC6I+uR6Kui39m-fowHf&oI!^bRH~!U-yy|u)_cV|7IY~&Z?njvwbWg z--^>TtR5lQhQkpB=1qYd3cP`2!MHg_Nw71J1KurxRJDR_OKbp2GsMQ?Ru4^M>Vc6p z(v=13ZDC2QK$_@3R=wN3)DFmjJh1Nwq>&OdLng=Q);oPf#}APIzGA5s*@B^@nTCww z_jqW=E+!e`_X!Ki5#{thW^!@AhZYh4v9L(BB!KQ?u9)Wp4*wA(mME_$T9`w*6 z;y)J_wrZ3&{~CZ_c&QPHUkj5A>qBGv-$cG^u|Dm--zjW!AybJ1juS(?Tpd^d~J+BF)pn(Xquorr50=|qEW7DA5D)-1NcjU zY$NN=57=RU*+)zO4oL&}#z3~PKyzo?6RMH{_^Uo*0&qwgz+ZP{r;5|nxtV=}%WU|D zhvvXS`rDcV^Ss8~k zw}~95FvBQe=3i4%Zue3hU?AM7G#3k%UL1}pnQ62nRZh&^mB653bQ32j_JKgf_ag{< zFy|egS=7mw>D)buES=PZfS~AJ2LKOJGP+5&?mVmq!pn zCaBW?ibR%9YC=FzbcTb1R>>*-uZ&VOY_#-CR+!TN>ab8y`d16*)bV;K z!liDk3#+4ssM2BSfbc;9dMc+qdGzPP7x;;br8664^d zY6y++!4OYr?D;cu7K1tep#-{v5|k^kB7}j&e(P~1+=?Ki8us*XYNC!SOtF3wd@rg; z2ZGM_J8_y(NV}oYVmh)=c55J*b3obUem71^!gNG|d3zvO&*S*4i4dZDzUQF{s%|sx z61voM?h0a;-OMsMdcWICwemWd9%)#0ParENeGD$gwLkFCyr`}uFz*ZG0OxK)-yfq` zJjnf6sI_v9*ZjMiGCzqDM2Z{FYC!RTq7P-T9fU;-DFCcq4@SOgu_GA8ZMqzmfSM}_ zLmmp`f<}gg?dMT~HD5bfkgN=#ei=wa67{PX#iUA)k`z6InP3L{9Qr6C+oOl06eAc; zR7eu0{5}xdrA~;+4$mJ#pJNFkied-EOCB%o66C75SyrE38v3lQ(Jf;{03fFX+`RXM z^Bq~DKQ;V40Y-}e=VbxEb`I<3%iXWu)Ce==PY*a%RA3*MI?iyvdgaXp7_SOAhk`ce z)$UiXyf8!mYXi=DO$GKa0j~>x)@}$DSNdOz0O$3NfL-7M&{>i18cCKEO>q?@Ed;1@ z0+C3~JvTjRzBxij08%0V zy2a(M*=dJtJKq|o37np1D~Cx6tsoF@7pc;YLai4qNNWyjOB0jR`&#=krBTrk(oKD@ zBb(^4F$vVv0T4>>bkOR@;q9r`f%f>q%$!!p>T*{iOOmn}5EOmiMR~#E*jyVaoKZt` zT&<4*SOP<$k}wEV-0L9ZCJ#*NnV@X)-WR7O0SBVM{GlU8WcX@VAYYZm_n9= z2Rkt(DfFR1;X@8qrd2PNa;>@czRCH8wk~-r5kK$5^${It$iLwUSv>QTYwuay*UHHec|5ETy42*2NgM{qj>nUc zpymK_khdqYbk<{GpyqN922VIBEu2TZBZ;H4 z5(5GqS9lOGhcp93Y2V+K%+py<00d3%iJ{>7wK6VnY~acSNfJxol^wY{sf(aNn9Sroo~e%{F?3d8 zFreaU4}v;|rACHq*skfoV-*4GI+rh7!-NtgV&}9Tk8`y8@gxolgMPzlY$71g@kt+o zxlNG9ekzGURB*tpmO`#~`SJ|ib%NPs82i~Ijs#;PATaiGF$7Hc;FM!jmF5!j=Mz~v zX>nkn=8IkoQ;yOSP57l`p5+u7AZYrE7lrp&1dY^<$vn$xGC_`kf7@}AC4R>)d^$Yb$chKWwbe1PWMD&cX9u2Tlm$r8b+-?P zCxK0#u@n1#C#GezIapBl10PbUWR!6Tb#F4uGO8>N6y5Jb;bqW4cqkjwA9iN53W4~$ zC-61F{=#UkXYXWtYGUJov8lzj-0B^?FQ>nukr$ry-~WA@4abJ`)0_`L1>UKL;fDBJ zKQNcai%O@DKH9;f0tAa4R?pVevvzpGFpozf`M>5UNUuMPaW3-io+j}LNgya17wr!1I`1&KwARPM z#~{gaK2oJ0>%*yVojw7{X^uC7gNIFVtGGV@%1yNN(>LHgTFnof3y32uL#=?WkwL%E z7)&00wxFbUWyDzMxQU^20ba^dS^*2#|U8 z4srm2dU&9Hi1;d7FWIkcD)+*g0YlfDoy`Vmz+p`M8EKp}y?p7?ao(=Ds7dZR2 zpxZbM0rD7n@;PFRamqOapz>i=S$r-OFwaK`yw7FQOYEh3)#2MFeD{0!sv*9d@cq!` z(@L?Xgi2r(=au3gxr~A02(ME9V-GKsM|j16?#uq{p!KO!|C~)rZ5K|W7qB_N%Y=8M z8ct3x4D`1aHuNrS&SW<8f4J*JzoXebh9@&m!ZgXeOV`SkGOf%IUR6k=$Co!Gx~IVN ze}=2Yig~@1!&3e3?$MxCIo*RF z&ypWqsbhpOv&&^X+QX>*{FjcNzgWTFE9CF~%kK5vf3<#n_g^2hzWa#>+c%t3e}#9f z>wFW0@2dU{9t-(fF#a7Fp9sb$9lXB#$%m}({$Gc#?@m8%efLuyzdrT%Mxe4Cr5<(c zAIt{~>e4-%`ta$0JD*UNMo00zAK#zmerLotz7OF0Kf2%L9qpb?gZTdR(!l24t#~Pi zw=mbL=vpgsYjUNQ?mZmkZtK?GZAT1l-PSuWxNUHA-x2-2+xB*)HkG#Y_V*@A4Q$ym z2(H7?-wqt!H`up%TmP2L1Dp2-`Tm5!@2UTZS4nc>9OMSQnEIPiF~|DeyA2lpEzbDR z4@{O_p^nycZ?Un$x-KA%9ReJukGOQW5qG@yRfR@l1%YcGsB?SWL39XIUbM6OS!S7bIoW|-G&VX0emh&d#;R7TQCT(_?cd_AJ@Y8`391IQR|Aj!G{bv)Ep2 z54We=bCcsrkj6KM#^&2rL*K@9XX7`fUqBe;1BsA|`X`O|g(mkBI%L38j!H`rR<<3O znVf)C0mm>p-IxqtDoVcy!?skw7)mk_{%EPI--dXS`>2N&VqugU33}{75`c z|7}di)T|^+Ff?8l7~dE>zU>s3jY~sQGbm=0`!O$5CfhU!Ya}l>^0yU1Hlob`Ap&1( zk1x*6GgFsJiwo@~j}Af$E#M`vd`fTdDY>pYNP`rZ;HNQMm+v~phb&G~I!4B(C$Qbd z3K}ky8>L7}k&o0p?Ni)SkYj5(ltJ@^RGzgy&`1LU%az&I3eb|1Mx>uckP34%`|&D) zn=7+RBa{1%YtNZ+WMgdp_?!Po?k zw2^otx&pIQsb1E&FFMAlHb5MVA(1Mv?zdPQRca!Xi*A3#!9iji30s2&6A`(4+jAaZ zQ+K0Hpun@h&Z=Ud0F+a|6w_!6%_kgZ>I{OEklyeS=CM67P)1>~eHF_24ifHw; zJ@n~4F+;LEvxE6*&*D;PY)O7?TwE$nPcBT3P07!&5r*H|$f_I2s>UD;pqzX4p-~@L zDAgthAQ1yllC3shep?*V)tbCt-Y``VBIwHA&mS7}-MRKud%3|pbEOGzLFd+s zzQ5UV0497=qDE$>CfajOOJbZIVSs|b2g<&?6X8sS4kY}jhR*~3(?b^nY1kqz4w<>A zs&WZelZ@?a&+i;Vfk7!+i6``U@X2am!tq-V#%~#^si9V!XrUobZyJ6a3NaRHc-0Dg z5zanxW`(nYxBqt5FsO@j^^>b0T<$0d>q){J3>MXBZaB(`&3G^4NR&~v1X5KZ1JGiW zRcWANv>fs? z+-igjblVCiU4Ano@QNvcLEl2(fX^531!nG$(dfA6+yd%Y`EzVHyfl}nC981clp7cGq^TDsN4!GvB)G2 z8I#M;n-6sjXZbPe{v_=-*^D! zFp8v$CC021h0G{AUs=S(I#0K|)`#Vv?!UmA(O+WC=&!I;_t#je`x`9P{VkU2{tioZ zPkcO<@1B4qyTjIZKlT3!)|A!_VP%=iQXFY?t0k#!tOsHkqSmEwLvj<3i*SVmC#c9q zlFdh*bZgJsC77t<9C7cJl>fk3;zF{>uSFJF7 ziHpvuLWC;&{e?^xht^20S#q_q6N~%3O9Kq2-65Z~Hm)mvKI^5K1(YV_=YHb+sp8)<1C?CtK?V?G?9*inGk6Q$`;p!mj=1d zKO3Sk&<&I=q|6x#FXG2lVz{G-XHv6yqj5gYVC^Ok{j?D0F-4m!^wwgWMVrw}hn--^ z!xF-pX*BD`fF(o9j^=T2qL2r%CgxG~iH6G9SBFN>e|Kp--w!9p{1XF)t!h*ATj5Cs`ZkDU^s#*AZjof=_6`9+gL1$69b5o*Xh zmhqQG7~Il8@4q}kR~80MkI9BtMEKkq9ydMIS`JBdxhBuq5ks0?MBm zVrk?NRV_P0TK`!>)^5sXs+pl;W4H85&>>-L=LiSWVB0<^5G-ov3Qf1eY!xl#JfY~8 z*iz`p^OXz^Z<(f4gjlxUD5R0P^kg_gwH+l?KsQT|aDk8uaq<=xjSGd!J}_VHRbuk} zB7SG%&NI&FQZr5EKRV|vE=^Zt<$C7L#V*y93PomNy~HKgn>-qb=iHbzH0SM#N?VH9 zGdDSQS@0S4Pn82&a(VEb7h<7eQi4{zBSNV(CHrZ?I|CAv*Q{$X>c1jJ(}Juf?+OvI zZwOs%o!(=%F6bN zQ-7N+ap$&D?{AH?Fr34Fb@wx{LwRm$MwXxo*l5Fq4Myvr2v+?!fLNFs+b0~E=@TVM z+{2fO`^FG;YAT?zFkE1$PAsLkwIoOg(9j=r919LvVCIhx1lupuLK?gKx$SkAT@ybPU#`+vab{P2bO z;}J$$#^dx@_mdaLae46&2GdX7(bs!8_P?Lnm3n5Jsg!vRh6a7TU8!CVv51T2(*s?p zzBp~DSscx!`?^w_L1Q$TKF=?QVk_lQ#HnCnAh${&hKx&ETReg9PT2lSc;{2gv6L40=)tZ@}!1^3RD>`Y%0`U|sIXo~qvpBDGi*b*E zQP@!QLaWW1^Z!iDQY!7@O=nA!Hh_J`8pzcB`eVkm36QGb0_OmB!io8K3iEyLVi(-P!%_(+r{bex%PhC!fy+* z-VZx!w1^o2`mxk=$7iPZPVST6J1V1ii2$QktT;^JL~x;41DB8_PKgb}Fq`BSS_4EQ zsSrghL6Etg$5=VH0`93ObOP%B7-|CJv|_}3eI@oH9*27$8<5BuBe*i#9m!cEshkrr ztWS9c{G)ITHNBuCe}9aBj{Guf^LXE}V?M%X3~^Lnl?v--z*%KyIbYK}bOx6AD<@#T zhk-DRRv3kLeot@MboA^2At6$%CoSPwPe)lLllm-CJ|7buTzCk~jq2!xjqdDvkC{@w zTr-z+3mUgl@>Hl|sA5!=>PC-oQDmQS4kYZm*`i2Q5C8;Bw?=p$3C0w)-PY%{&Uld? z6nEyQ5!iP4>{7YCw17|at}++ccUbI4f|drteHNjNCnX%0`4Xm#px6Ue43k)lYHAqG zhLT|l0)nK_PGF?0GXH5w2~-~cjlim+P*(xeAyn5ni%aFj{d?MTmA!PyeEKMsvvBYs z+A>7_&Q4(IJdeQNVBtRX2T^2RcoKywmNKMHm1pKeR2f`w_BvJ%7F{W@%u>40W@#fk zgxWzrFhY_4!WU21-k3!Y3%tUwQtXVTBPIU>8mkfFTqfE}n$1Td4@-v$lMGchpMdg} zWz(4w;tYx&e8}KW*Wy)L^&%06KLEu{@XgaTxEgIG8QRS15A;#tr~M~VQdnOo^qqfIw@=5R;5h>&4Ut` zhU)7@bt&!e4H8Zw=$tJ(#Doxy!m!6P& zPr6e5{5D#_NPKE$dS6#+fWPYqgl?qgd0$OeYEZs3uw)IxR)m+_EPBaK55Wl^~sZx`S;0-0{x zS@dR#)k!x~(UT-wmKSqmG)FMb#UY>GD$jgvo{R<7({}EKbg~CpJjTcjRLlLEp9&mqgo%`yQgo zuh^tGu1igXCn@5a?xqh^L8*;R&bL_-v7XR_1U_Hc9iIUUH_mJs-n2|-k5}xGg#_Wv zPh;gPi^V03^QQ0cpmGgDcE^=0BZ=*q%6U>MNx@e zWNusGAVGFJsuZ)2PZjkn<(Fo0lB_*ZL`bxX_*Ni`v$+3gUS7VO$9$|l)o#yX#t~&_ z(RqD}DrAK$c=n)%(oFnX@l$~ZAtL0JO8aEy{K<6X!`y1y$m5~o2~ zEj`E%GYXh5R??fhQqPGK%DX_q3DE6v(oiN>NN?*(jmAltVT{7kedwG^apF$qfOu3m z%5jcz1v!!KLnDis-cZiB1F;w+UasxxDh(%Vpo_rw{> z6`bBhndt?2+($+m3msJyfL>TR5oh7HaIuVfjUo&8wBsB+i-!?2AXvio#u4eH@J2iW%%{BRI$* z4k3z3Q;^4tvlC%%hciUzN*$P;aAY06;Hwi;S8tRC`U`_gOAMfB@vtyA?+{wo{kjzP za^INZCl%r~QXC#hOV9v95#$rMWW#jy+%h^he8n=lY0Z0~!z*2qU)mzukUrHcB{0i%*|SsT1BbM<4p;2cFAswJ;XoNNNK^eAG1y z!&5VR#_(X#0`}M)zD-9Lv0O1WJ>Eu__9+Ka51(CL2UB0muoBSEIG|iq;S=c&>c*Bc z)}q}#w7G_@U^}pyPqG;C0YGB^S(Bk!3x~nES`_()YkVCWbdc9_RyZbN!NE9b)6v6F zS8vo2o8VLQIY$vDsOC8cYod#qUQJ4oECe@juQ15mS*j_+KdFEf1WUmu-_SM~hoS{h0bh7$vQgAE77qkrg1`?b zVx?LdiL!2v2yl7;*l%`*wUgd3ZYcl!z~AZ&Y-_GDw_0QEOGuqI_S>B?oto&NF6)Au zJEQ6?>sqnS1&DlZI1d+3%wVlk`MJC{N$(47^OX`!Vn6jG2_}9UX92XUx@Sy3h2aO!x3c zGW|8(9jxbd6}ayKcb4^Sh09-Sc|C{I*{{vyl2;LQzfy#s7?>R(} zbD;7Ye#VeWkAVc@x8_?gHWG-3`F$kJ`#Z%8kINWJFn_Q33iVO*l_RCo)|sR`gEa<= zz05TUGEN*Tv((ua{XCfJa#*(Dic5L2@_<_Py(J7`>qTY2sQYF`T{Q zKyPW}*cR@5*}^|i232WAVSQhiA1ZzPx^#p8{a*gTtpbZvpsWO7yLw%Yr#U33Tn*qb z(`{|-mGW|ppSW2v<6~apwq7YI*ZPT@Wx#y>Iz%Cts`b{EK~eKr^LwCQkZ&-*`?d(! z=gjY|BK}qWR7GvHvQrSg7JQO2#KQIU;G0YzSW0f;HwlzifwcH^tNkPaw3Pg={Um|2 z6uixTl64!F(cA5(63$rg%MaEuM~5-*Y?U+HB`NpHCs}!FR&!Vj0^5D^Z5J=F%2rBM z5xrl&N&K<;$bjJ=Iv+)v0l`08H^K}X=tU7}F*8}y9#S6%abpm^FbzLfU$)2xYW>~1 zk!r2ci_pD>lsC+%bj>Ef@559&QBw)_hcFdhcN&FLx<|6O#R!R!*krJuYQ9*Ho@TyS zhrY~wvHpAozO;D9551+z-|6lrRW{CWKlO<}Uuiyx`^25E?jEk~VrEpgbB=(5Eu623 zeQt%b;k6M4$+$*kc$jl#T=K+r<8=`p9LeAT0L%{=OaJE=1Rj%PmE@_Fmjk$r0+32sx%HDFubb=t6~sfmXF=(#${! zhA-0-vxqoe;I&5`0I>#ul?yp(XLR9uI4-Y4y>!oL0I=UDrx7+VIQ=4}6O}fql%H0n zl{J2qYA?}l`&0wnDrr>3e5ah|o3?i30J5cghvKAJ~t$X&8U=%D~8lwT{w$tswiTbO8e zt`LY~3hEaYDw^9Xgrb;&`jv%>6mWyo-^trja~05UEKsanRvikO<>YLWCRzdg)&g0&l;y1e*r>hbBMVnx0@z&hgQqq>DpBo zZPrIxxf(os%bWY8^;mATBMZ>@X%Fabtjq(VS*8(fq_+ z?5-AP9Xml!@Hw=F2sPYK3-q8Vj00Em)a#mxU5t|uKIU%gE$l}u-af!Fx0^?%?Qd7k zbymH$0;U|8nv8VF^(a8OUf0><_;K9aLfl*?Uk|*Mui{C_jE&Xmk%67-g6XXa?ED4ABR)-JX}1$T?&srJJGu-hlJO2@1Fk@K;6kMhJ&)`w zMggCe798|foLz3%fcw)|pwwwsJ1gy9vC_Z|5xWOg1cA!`PS?NAURZ$qU+rL-zW>oZ zykf0^BVsNlh7_JqX^R#PIQd%F$!uX!a_W_4Et_{r9{t>q@Dmg!`a^y!TXqxe>w6Y) zf>Eh~^woz*(M-hb=TiZR)B(hhpcC-wjCut_f7dC&WD{cvy~FP+lJ;AjS-|z066fEc z)(&j6lUh9!jCQoVCin1>6ADu^CuA3<)GoCdv~cPe*`vHG*;ZX=l8jZYH3FbSLXMt@h$}--aX?W7Af7`1to#DKGxn{iMbK)YLSq4 z&vq?FG%?Sev}6L#2tA&L2)VaY-b;XlDSChc5?YKmc2MB+Nhb{wZpCFRzW1=?4O7(vut){aYOorF9efe_wZ~R z;&RYCtrjeJv>uTrpj=^5%yMLp`9n+%ei%c{7py%hOU;L1kYv8J`f2F9tqQe7*`xju zc=M+LcNQ@5|&tYqj%%$ekI4Yv8=yPC2iL1ihCcTrEx?AJN=U&6Z3?&&*~9-6YxQ61vZmf%6ypIkP?bpux>NS2iW|qg z)JMR5$ik^9sQkaqYpg7~x#%o3YKt|q@sFC0s+vw`f5c+DtBO5lc~NQ6YmI>-mlrFL zMpb9Nt<-n5)yF#E;;dFDz^(~_$>JqWb8_`^1ywj{xl<=5TATgseNwTnwRX5mn?34> zxX}D*vccuEOQ2eFM_y+UlG*TVKXNS26q3%3`VyMq8HM98#X+> zA1{ABvuCjRbk#3usuIU`FBE;+Dk^1g0Mryjk1}b9BL*2wxGqH-wc(k3z!AWovA_tX zIi?dZY+oUEdJ`f$*`33TsJR|fu+1&TaK9Tbm~FsL`)1gNV`JLJ&nX*+@R)0dgs(~^ zR!|2;la-1l-)AVBC_JD^3s)`20t0`4$@<%-Wvf=T>H^c>p}>6E>IvmQT$jlx#~e@6 zO>y~(g$?;D4(lr|TQNeDs=+sROhHU6EPigMtZ+FaT2#IsFDf3}OqwIE@mUuX6n~EU zt(1a7`xvj*p}ZtZ_a4FGqTVHQ;x{=(z%e1aIsL(I{*nn64hJ_6&56G1MM2K9+qvipf+uWZF(XsXK&^hA#REUm+ zPWJZlAMSyFIz+|AK>?W|PM-;pv)PhsJcH1#k1_NI2n>VzY=przk6Y|Fgz1P{u=X+f z@^c|_m6ux^^BE-j`4BmSWqwQM^{-zDk!!B&cm?7YL*#5IXLyg|m!fnhZM=)|%TfA3 zpq}%FuSDsHa@5vK@W72B`cTd(IDO3euZHM3$9%bS^=n}=wkrd8=KObr&e51V!QW`aD9gZ>K=rKYK z$;(Eem2W`ZLor57PAsn}e3F)jEi1N+aPuNe#@Hg#HvP`ar1IWqt+#M$@b_LumAL^U z4iWyr%eXa^jyfX7*NYP>O`ar^C<}ETuWq_fx?djS$l-Dzs;De193Lj#)*p(&6hrB7qrlxM8!iZxpmkM8|iF?!YxSJ-2Fk^mCA-}A%oCTFW!4y4i|$xQ>&8gD*)yrib+z;z`mrAn2*N!LXfHw z^Q_M&wOU*KB#t~(ojw(1VMMxHkx@Ippn1w2aK0Ghi2{{@^bO6$4KS5Ltgq^_-`}bf z>&WHR_U)%4oRbTpp}@gsYgfsnbm;z0jeFMYw!a&}~e;l9~Z0X`-UG zRZY}tIQWhuneycg`cV#ia@-#`OgsHkIk}6k3F9#X4N2i9FbUWlS z!J5;;Osd(JVP#7p;nsa&sZ^!W=Yc_7Qb6O_q~U8<>NPGyEnm$yiVZxj7%tc63X{%S zfoc?0b1%J7UA6b;dAOX;ja)GLd=FP2A}?u`MZ+Ssm}x)oUFf%nB-Zeqffq;Ut!5Fe z%Eg9iMqEO|4-zj4h{_^O>?iT90a5ianm9n>+XAA>1Wgvf{@a{CK1ANf3-fM+{-JSirO)pc?-$5E11H#ILzTUDiqL zC-LhpQF%us2T1&eOH|Gg;vk9NbcotFB%)k__^p8Gx&{mllD{30gOUZ}5Q#ShM5Lfn zP?b!QQvvyAm)!4?@dHyJmptH-@dJ||mptf_@dI&&LN-SdB17Z5Lqun0$Z7TWLqum< z$SLnVA!0Bmly_Wy5F%nyVQay^}$Q(oJbqNU)DC1HZ+ZXH|42vW< zHAcYWJsvT4ZWfhvXkDq7dW2UxxH{P*yYivQDIRGvfRa4$4$lk+&NDdj;d!P>aOf+Z z>Qcj6XHimsuUi>foA0gE<-;V)H0pML@Z@Uf|&QZ zA_L2c@O;*NuE^l>A|9;|2m}H~v947g&FsKsi8&K3Bqqv?q*TYu=|L~6w?zF$SOYvS z({Ce8DrZ@o>?{bLd^p0z>xggyCd}rWJ^d~sXvU7qh|;gWkBH))89V`$8Pz2tFfXdt zloiXtj6LlT8e7Tgc_iMjl2`G9waAyb3>i$}F&(9dn%Sa2me^Lj+~q2k{d_3PuWy<8+9AMA2 zbYfK<3fMiMM0k}4A<1DVVP^}w8lmC70JA~F8Pz!sNj2Y+v*1OBoa+!(!)=Jjh4UQZ zfKyy4>XsV(rUTD6?0N_sR6Q`j#y7b1s#^{{fc*e`V<5nRaM%Kq{l;DjTwnw+9MG+m zA;%1kB!J=<8gYz1%yeAGzr9V7)E& zUSEMt5|__;CO#2Yp`%CWCe%arT56D3@culMox8(w+UlkG9X zTQH*XF%QI;`-S-iAM;?08CN#}`Ex$z%`xUdVg9_2c}t8L!BRl}f{*!#81oik{-Te0 zYmE5_Vg8bjd0UKmt1y4r$K2N&)`x8UvoiU8E51Jk>=KW_t_KLsh zP<76LBR&}dn}eIOGZ%{3mrD=bFPn~b&vD9_ST-yLCwl%tU$r6<|I+)f`tYX=H1*9Y zYA8iw8GEq^sodW4R$8 zGim403+lmpowBIPvRm3v%Mwpn^}X;YJ;TLbBLe6F_F)ICR56oE7a|#u3kn)h))pX7 z$m<+PU7137Qb8v70@wZQ9+zcs4UU7U>6L8JFXh#FNnSLJ7ghO&(&XM%0pO&KoVaul z64fIDPEPWO0o<2`ub2n?uRf29bbi%ICtdgd%d|4%g2dWvjHmWae`;GzY^`H+nnOSA zWbAf*nt0wXK`B-*93`q~V@2M9j2|dXDC^v`lyj`%^SsElmp(3N$#srB8XZzjVoF}; zDADOa#SSNgHC@8omrsIXh4B|TxW@QL2CVJ2$X7YYJZ2g>at+7JR^+k=`H@D=C8 zpIGB`bUc>F_-}S_X*&P4$nk#)py4^p2Oop=d;q%9V3J8 zcT7=9d}QUO-&Eu8HN5L%+Ia5oK}d_iD| zqYdd~9GD6tbkv|^$mfn_nL)jBQ<-5!Qciw+P!S1^WoTwl7+Qbq2%a_9pasl;Kiz?6 zp@_rtbV@?q10*2MbRcM95E19dA^pL3+8Mvcqp0ut-*hyim&Feuk?0suP8e75TKdd{ zm)q@xE_7^UG6P`8#ttckMM&x84vORj_dZMjqXUG*;`?%`L>P}89Q_YdoFIe#)4>VV zH?pg1@)UNQ69=xdQ#0eo=OzzK&f_UzC6 z(mx1*^H&8ENFY}bN~o1C5p;z#60WQ~UK%QdJmG;yebpU`cv#^`F(jgLSusI@jfmP3 z4A(<VfsBymCqP`@OF9>lT1xDvtsZkZ&({W$FcX|!8;l8{+Me=+ zpo>v`KqpT>>T+I#`#+dJf()g%-#I^v9 zy)++Yj|dmJJ!-#saQjz+yPPjsn;m-*c#THD+MD2CkI*25;PXozpPK>vAIIq&@c);1 zJqrAox!na`x!euPa*s`}Jv&$HwJR;Qqijwy%~cuRAhYiO*eNDdqui2d77+29?)ubG(iXH@(*F6!Fdj zU(?cIkOpbw;twNuIww~Q__U+!BtQW^>;TH(CsS=S5#g_oOb25rcRalcDH%>X`neVuECZf?STM*?8>ff~!MchL0C%imib!D+5NA>>>_!TP zL*xI@P_ov)QO`sADOgvN1C4;pIqxvlpt~!i81e?!COG6iUMcMS?vMN)i2NRuN_>7u zgI+>SRDqa+u#V`50bHU2yDvG+EM1J6c*|hHMgnlmGL!jXCLEUEIk2rSx@fhQV@3>u zbiqbDbArdUkwbE7+bA_Zv{JB{L)}(YA`6Cha(zz#89`yV#&SGdfLe~HzAOh$|1Jk2 zp+75O>R+B|d6T)QvW$0Rdezy1T(DRM1&6?wW8p#Y74WPe-8HoFoh^p0!R2_kBF@73 z5mPwjNcaDx?oFd4E3P!b2$HJIQcw46J#)^i9jAZjcv7e*+#@10DXFQ6@bJiR5gXwV zWTNV7AF7n7=t59~QdQJQrC}BOzVACE`zo=6#3EJ!S`Z)*i^L-KT?nzwcdywsyJqj% zbAKM0I%jl_$na<1{qD7E_u2Mr@o$BVcN3xrSpS>POrS+P^kteGAop36e)B0n8gI`6 zG7H=IY>k^mr_7(xiv%6=KJn;Ze#n~`?Amp?D?rigWH-2Q_ikwkUt$He1Uhi^AWmR# zKF||Jv`-F>z<=G?+x{(Xh|xZ%Ism<$9e~4R-rZuJpWc&AxfMHLB>Vta4OwH zTKnvDx~H%;3&mP$%Hu;`?@W2c;jZ6e%^qu2|HP}Nox0`&Fum*iAvo>eU|X-#>7-m% zJ&yZLl-r+sl{2MuGTNv>FRnnT0y?daiB`QWx2&_ZtSecwZqS+Ip8FEd6|)Nl$s@lM z+nS~0F0(7T$PNV-?b3|oSgp{qIFXEfS{dus>`}zHO~x*2^b;Eq&AP|Q?qX-MPx8Lg z0)9hs*CN=IOh*4&8I9`4eNb|L`*&MX>4`HMeFUnJeN7t(#xP&c7Q%c3T?pe-=U$Qw zV5>4Wk{#O0V4t(|R@6LMkl*V}u6ji@*{JPCn}sqxmSCpzg)r}>$gB`nVHcQWev_K?5&6LmT0si?G`+)2Hl-MPuLEclCg0jPrL);yZfs zB#ZHJl*VA01QqV@BvTYd7QH1h22~%5Dw_A7YE0vRl+pQ}x1>_3%hF!pZr3NyFzQIT zSmKMdT{Yl-Ntt=9IjkKEPh6N6fiVE2@b>RS7hn|_q*m2LENr73FIr=~D;xAHS)_iU z*_~$E9NU#*+9BI5uxr&^hzI{`H=Kuur1iopDu23?)DLuFy63Xrz!~aN)T>72;GV0E z2HgvF?j~^2I3-=Q(4l~Cq>l{UBW)V_NB;H>(oX^pxrB~QpRq*aeQ^dFll;CC>kiMY z;&DMXCz`k*i0B#qjr+=tNLH5cC8u>}G_-`&|c;NQxjT2XlZ{abRS`bV#A{ zJUP!cac_xIbb3U#b1%jpQ0NN+<=?41b2W7;)LbDh*)wt+P_lf_5(?f6%;N@l&J9tx z0e8P_T&iuut^ji}c21hw)N_@dX14>VR!epl7wKubku&sMAbPk>;H|~TkJ)03nu_z| ze%bsG)NMj`n$jp=TcF%=a#H^H^ z)et*k2gGpYitmdhysO&vk9^qD4`YFi9Bi%I?f&H{o;!x*gZ#<$EQg*pl2$Htkkx+Q6LBH!TtT$q71vvVs~S?H=MZINDg1&?G9dOu9@P8k{gZ19&}gW-QdIh=v0Jni%B$N zY4)JQAiEje_t*JuZy$X0;XiNFx--TTShFJuzw5bc5x@1hYZ1TyxoZ)>3A$?$zZ1G^ z5x*U}YZ1REx@!@?$-Qe4wbi|Q8NcDZdzl^rpxQ$ORC@@4Y7a3`?I8%NJw!oOg#q5) z1OAPjU!=DehugbX*t~x{+?GGLrzs`6I)c|d$kQ*;Lt62`>m9x;eE7syvTi$AM8_MW z<5*2aeNg#RX1MfkGl1qPu0uuCciU|ZY!~U#l52UwbyD!t)-V}i_~-C{L+iR|F&#b= zO8sy4i1pmw3LNm!iNbg}O@UKBK#@)#`fGURk{r*Vnpa}lGwN?Qz1u?-6FbXn)Tpze+#sgmLh zev$ooJ&8Bj9m#|6xi!~6f2^0;yKM8n&EAzga_2QjHrBn13%RrJvva-Ok{efFD3Lo; zC9f9R*qSJycwN9H|GG0t+9y~R_&R?kZ0%V#QSP{etM2>LD^BmCJl^xR{_rUu=F!J z&=ptNun{BewR6o#|DsEqYMBc|AidBWX2m$Abtjc>j@4D^Fl?PmpI@k(V^TH1TjV%l z(9TwbMYYFM59~IJ zbCa67fb1-iqSG)}OdVmSn9!Ls)94w4MhXowg;k_vq>Uo$1i-ddUSgS>n~^pOEp1>G za|{J8v!z$001%WR4?_~~OKYy_UY1+>={8V$(wLt|6wzmqfr{QVgBByg;L{?G+jSUB zFyUDE2vf(MOCEw@5xzV}klCH)6$FDi+zc8)CU8%VXTit}ds89^rolV}mrMe3M+BiG zm^`M&m^&lP=-BN1f(H#V=%Idc41Y=GsV1LJlV`Z@(x;n`-UAg9z;3GcbPFemeS1KD zVpR?Bk1^h?E~g8FYPdkL(TZ6g&qcN8*U!#O?d%xMPn=#Kp{vB{P-D&UCfSegTn2{; z!&dVvjrN+crpm6#&aXpAbroSG2jdgCIOP>axZyaRxbKUHUGi#(;N$j%g6>Jffgc7j zNms*SohV%g=|YJq-cx`Y13baxD2`X>^qCgd$lkyf9r*rFL*#=*^i(8~|68cu8TrT@|6N+t|92#1EPy&c!LB;&B`8G8T2Pcqg0wkSQdPo9U zT@^xApjjPpcKZ(J$n6GbUqUbP-cxA>&7mZ^{E>Z;bxXefLV znQnC=)%-#$;Q`!;P&pu({zm)Y6RByiY4{WEf={9*!6xBPvvvm)75YkkvaKF9rOn^?<+MnG>i3^gZp~WwC^(SC_Y8cdbgQyS?5kV*)?2+$sL)^D-g#|2n^;zk6e#(2#HSEMcz7rxB+ zphJJ!bLBe}Cal0P(In;B87&mD869-+9==1(4#)ur0~^2o4|{F+TKnsJesx!jMXB{# z{9^Plo%b&ebQ1^FZEY=6MVGRHlOYyo7F&(+ic(F-MaZ$S)WBYz$qwGR?sK!}Kkk*u zjCq#I%lN#@buq97U}!(^vH3S;%ttNJz4^QDwIO4^d6qIiYZdV73=ZzJFKXn1HMuwQYROOE#vfbMK~W4mNd{&zRHxQ zp2s^F7>QS`BrUzgba-;9>{%f>WQ7X&BetqO*}xtw8*FIg=$J+NWtU&UR(i;_7XFr$ z&+{wFzo@~)P#HsQs`b)<_*~b6wx)tJ>hqsgzO&zv-=nt1^aJTcRadmqRUmC1uGvwtUl@ywI)oXpQH6Svkh_5yoI#4*GB){P zGoE^e-hVv^yrk#~B&8iG6^wy>f#2$?lQyYVR))!E!A1O{*sF-w)%f;nR zw;g?gomQ^!KvWi-=?9`xFgy}ufz^43bI1^P<5Fk`V{;=5wD} zepm(JNZP5$N0~kfDS1tlpwVlqQ8c|&YD_Jeik?~Bkktv}%@$p8;%v}qKKvpfZ_<0( zB-9l<&)|;dQL0q@59j6ZQMmpt7Wfix_{32~vOq7U{JdGbM`slAQoWDG5?cCa2AvRb zpPa(s<^aTI7O}a$Z)^T$@^5K};q*{#VtDVpdHjmzzBS47!2iouTlcT0A+33&CW6%z z7rr3Gkoj@{U4<^4`AQ6!TkGya8XT+v@mE>IoadmcXZ}+bG3pU?ne<=Bh;{Rx0~5e~ z{r@>e%+59D&2?OoAxr}I_3vu(yRh?IV{U$S?ffWi1>Jc;-GxJ-uVq1?pIA2==l<`q zzz{?Z*ewehpIt33iMKLwap#6!RP`oEwKksgGiG z)P-G58V}NkBwZR=qOR;>E|5JMkns}nZp|4t<~*5V=*kWzfgQgNShAVo!5v&ptCCXX z)~sV*|BI#|IY4-gqc01auE)l&25MFIyU{n^L7z?6`hFMa(=)evOzT3kjtOO6LZVaQ zt$pmgtjU{ow3(UJNX^5`8fAKq-aQQj;)F`XyAK`Ost5IK=omYJ}DxhO*JK|wz z+t8>(fLdbnKkELSVu3r&PA!bCZM1Q#DgGPXm@4gD2%^SGF-embf`&YZx>C~mg`i;% zqQ>+5{@JlM`a5Q|sC}zEgz|Sm05R{cM^MHt??;HDR;Ol<$imbsbSj#7pGsCfLBMrRXM;_1iU5!uFe6jCg1}WI5s-71L_TW^`5bhrqRp8^n`8w z@IASWCvg2)%Z%$y&4qi)>5V=+d}x@?2_M!5=?IqD;WQzQA)Ygc7 zR7tk#CI{$>^ynyARmPP4W1?hL4O514*Y)lam;`X{yJ`ZpRN-a~W)Yf;U1g&S{nx%~?+hlQ$Lw;4zzOHm|} z`81eYtX9*Eo9iCUAxErO{xq6xTW_`Iq)qbS&$n4lZr%;5B4C87{AoB?^S)C92HcUW%MA4s|10dn2zQYFFz=etyi>`W^936#^{ku^c*pdynR z=tlUz-Am}Y3lb7$Qiea01UzkLb`s%CPa>T8NrZgAa8_q5#foZvxzh;w%92K`CSM)C z-1&++02TTV2e0|VDK@jG0WdD()|~PW_^fFP2t4 zb#@u~HaGB;?MI0`=#uG}bbres(72@npLXaAsOz@TZ+3$CH*-aW`JNN)fuZkZlLLLr z{#Oj_zhWj6=@HL)$tR*x3lvG(w6e^ByzSy?$FaVWw)tbqDDn9zyt;>`yoeC}c47N3 zo{d(+G{>X6Zg~!cC#lxWH~H%K^xZ%Z=B17zLnX17=jX+T0Y8_rvRzvXGL!(Di$BRQ zo>j@&cT^vpaXvqNEBfd}Pw=@Tv5(@62-8@nwj~VmHi|Q2$lOk9;V^HbI4gpTVfT_> zi_Y69&W<3h1r6bC6z4<`9Kq&U%r=U1BgkkSt7|1r%`S@bBFLB`F&Au=DK;{a;aBCr>5C3NZ?TzVB?GU{0it4= zUl2|#}z^Q?N#B_^y|fE-!%YX?kNML@FZHx3wC z<-Es8MQG6BK5#@>f^QPyDLQs_;%I^bvn!H2v~rMcLt>I??Fm zQ|7_A?=GX?=9D#VNt#&6MSGTP2gNo?2W4SXP5QRtVBA+cO2PQvptjku>0w;8ADw{> z)p#mBWII{GQXAk-(HQ%s%xhz#&e4#G=ESV)E=hxXZj5jpARw6I5=Jz~G5(Nl2RF0a ziIOxNx2zn(-QH_CZ61v*ef3wV?1$@IDmJ3eVwsn>ocqU_WX|ZIj>>F^kaVF(-+py?x54z zf}i^Iu(vycm3fHGpZWBlmpeEzI7I0`_vxhHXJBNI2NaL`bkeWWwvYclFMWE@n;smYL%VS1u}{~%=s~1&{-09m z(+%a`Dx3eSAX(+U%GN&}Bx~d9r2HA5j6Kzwe4LV>4U#o^gOZ;Mk~KM>wfMYG#}#f6Ur?#xn2N*hMU_0^H4hu%msINPPCA)|U-8K}uiMvic3AhSPsV-?oy;Znnoq{C zrs)i?nt*-XC$HOKQKfQmz2Q@dTT8QPZ~JsT45xK`@aQ`#RgJ)hO#Sq(Pt}9(A!FAk zoXWd(r8;Ogrso!9-Jcr`;9lGI!Zh~jLg7AJQ_BD$8ro9*gN@8<+jE$+YR+Jiz;})q z2EmExxn_g9zWZh*C$Q=_S7gFS?3a<4#mzADi!-@GvpX57{Ua$l;-IsI)a)OSku0*1 zBo53-bh4174i>3(qdPPf=kjucKw)j+h~sEvkwFkEh&6^DB~UEj#(G({sgCVR zdGu3_I?Eg_G7Qf{B7ue5RXfkJ%n^Pdw8wlHC>0|ZO8aLlA567%a!xi(A}bR z1S{xdk`f!_^cp$%p->4gunR>{RCg&YCH6HJV<&njebiigZj|+B7b9Ir|xrn8D1fHE3lEt(l(~ zss1s|L5o*t&h#I(tk8rOTGQAv)^OYVs*3wy*{OPoCAv&-%dc$Y zC*C;@{LK~52^}V!m#RdfG^vDwbg4=t_7X}s^t#r;W%%iz1oemOobjEfXsPM5I3Z{d zT%rH)2O0ARDjG?`l0ceiwO=H&$ubSPlD|M_)6L9kQrslF$yAzWI9x2ld}js!XS?`c zYZlFeV!lc~k`h9tV5TIIf~k>23g$vc^O2$%bDeRboQ1#O!3Ha_=@~NwEk~Mn@vVo*p#Vg) zc;tt(BPBe0SKk3=b%>_I6#!52JtUfO`D0d)r zhE}_W*7%a7i?dd?sqFJi&8SE8@?5nx)y!7=Co)IwpYZpHOGGawPMhNu{x7-1{=qNP zYT9pX*P&87i+NN)`M(6Ue=xMlyB7`qGNB%ys#oxT!ty^r^8DZB0%(rYPLYcFhYLgg zv}Ir>c5P{A(_jIG?v=ua`P>Tr&rJNUrIC4FOB5%WNnT>Q$}yR_l|(4Y%u8Mv+B6Qq ztA!3{Z{e^B_<{Z_rIt7EV@fYIxsy%h>5=SXnFEPa!kL(CYA#*1ouRYSCXT?*jkrhQ z1W5E)W;xtrJC)&n$MY2~foV}x?!3}?uR3pdx2v0OE0+|7xo9%L3X2!t28n-ftz z1bb-KV?V1~48}{{&6%hggmcsu=jL!;DONLBKAKUb{iprW;{8D)uV^=m zDk$-RAhAZYywZau9}E(C7r-k1AVZQr4ib3}fLVh@CJLDay}rI;|=q9ZZdn}$x%nJ%yf}CN5+ssbEcg+N5yhU zbBqj`b27`=g*@_3a^Ri9DfQ+&9pE{i>j_E($El2*o2W0$2lMSNu1pe;=NaUDa~4Y( zccyEY!&p5(OrLIyHy5$)DJN9trZ`eB2nG0*-2|L+dtnI2Z2!*f0vSkL$r98Rqu#9a z0Yj^=3Ni9MIJSC%-mq!JC}?kVBJG7q%q~yPPK~##J1){{uz7B$g0i?N4^B}Le?TxU zCruLzlkB0J^F)WNrdF{$x$Kra`9d)W-OWPNd{1KAj59)){YV4w9uMahvL&Eb?Vd;g z2kXZEMW(F)*?n&$Kt}~9C4m146#;o{<^$cc0;A4A9uCi$?>PagUIn+~ zuW$m-RZcXT6N7EPUk;xY`}$w?>BJQRsMqnD2Q0+tv>)$vpN_l*^1LDM4WAAd1?k*j zdDEwpfz`I(vB$lYw|qJqr~sz>@wNw$fhrvx4H)>2PbULay4iO3u1_ZeRXTbUkblpo zlYzCi-80AwNRj@&PiF%iz${wDb{r2N16{gVt4iykC_1=^$UsSFelp$AWZ+QS>{>KEDail9r?Y_;VE9SFM;<^1+H~Jd``D+Gfi~Uu)IRa)WS~v={jtOC zF`i^*?;rR06$;KSK2`DZITLhhoy^zs$W8s!i|tWm)5#OexHs3|E#5_Ujv_P-OGKF9 zGpB19I#i5&xXLEQWxGmUlhGHzknL*4Mp<3JwVCvttT{8@2#*}a#|hWhOniegpVd4J zs&I1d#=SP|@^vhG`^y1R&Fu2R($}>fNO7wD<|h?Pv2kspB>)saP7mOT(9ZiKODw6sfB@NRO#Go``A=Y=`_~^f}N2rBTXetvO`m(j%#qNcfU3kyJ`# zvyzIXVa-97ZuXjEiKJp__>wP?RD8NwNyXBz<{(Qqd(E*#Qn56A$(KkfK24FjnuGM1 zn&b7T=9u`S)EqLu(c?=l`3(CUOC*&N319Lhl8U99l~gPZYYwt>v)3F;Bo#};mwbt& z;?vDaDwc*d2U)t=YmOz7ilyO8zC=>-X^Pa<9Hht89Q)d3n3P2G9GI~BV{|%rUTm}X zI+n^Rg%ZB!OJ$W(*}SY`Ygm1-t((36SSqX78oujGWfi|}URJR+tU}n<&0dErl~rsF z-}j}mieHngt{P!YrXD#Xsz+$xqNZQNZ48~KHn%s2jq}DBs1uWhFttOo$h9wQKiP~= zGwyN(6H$u~S9@x#;ffAQUK+JnT}@ey93d^M7PCoLD!+EIOn&otmZs~mJk4$ISh=+P z2d>@B+<|X%xy8AeM0ocH%DY|fRtmNj;n*f9pe=n94T>NY^TD-(`R9SNUlZRr$lh;r zDQJbX((Peowf)l3#U?AwLbrx=Yj)o5s7`k0$-wZZmEonfRP}6oX2VrS%QF(N`(0%> zonlp=U8H-=R9T~bvk%RI>xnX*8OL?eC{ub(`Cj&8WDQ0pBBsPeHXO!sY3r@ zv&X)$m#C#nmnrDT^n2qydr||K?9`lAp!Z-!e5SqUvj|8!cyG)Wg)WitOJY>=tq`c z5rb@&I~fx#gUi#RAVtO~7_WMx0(iq&lfQR?UTnMa&1!Z#7WkdFOW*R+?20xhc}JAY z*;Q@W7-E*UaR~Vz;#|G>%~Gd9W(8bF7+=O`VlvI;R=bgJJ`l5MX`8vgjH5Xj{h1|j z)~N6ua47qpK+_)rO>VVY#r?&8QopRD*f94vTpVY0yHs92KxGyQ$r8D4@xi*dZiQ$u z9J%x}$*2u}UP@Ns|8f@XUp9Ne;y9}+7lArKYW-BY9A%nH$Nhe=?*Lk_Pfk*`1xqAt z3|7PC+Gr6;8-04djXs@iOs;!hJJ+0bM@%mAFRUfTDeq<#h`T~+kk--d*rOO=(o}Vs3*x9AavPGAULt%0Kn@b;w`S~V^zjEoaCeg|B zO%eaerLT_V`5uVBcImRDP~_3XLH~bt>Dxu}SU`pJwoAu(@1X;*f(n5D%L8H$VhI%h zyLdq4LTY3I_!|$1d`N4!0Qg%Eh@41^xB&R72Si?^Ra^jUZ~!`WKF9`b*8$>d4#9^@ znH9B^h6QHd+nkxhA&~x0-1X)Y%~hc7Ih>-w2=g1KX1N3?`lk$j7UwnP;%CQ! z-`nFyCp`D)M8x~g0nTx19P@ok;cx)t>{^qXQU1HH|6hDE?Y(Kzf?R8!$@{klXtxta zNYKA9-(0)4f#Ycz24lYyNKcGTO?4w~aghIi19?M>BPhG0vBr9{Jnz2!p1847QNECx zm$CgKf&!aD25-au5k=?Rg-iw6JHk-o_V~tl8&|3Cm|ZP@WCmgv%)7PYd^1J{#Vg(& zhBo>fox!-yf?u~ySAv{kfHSjmbheJ;pe389nj}iVnKLelOgPOajnA%|@rk7SN_%Y> zmnO#{4eRXe82?7VnJcL2*B7>*vr|tx4RIz{?0KGGHb|ofcy}K&@$`XC1Jmuf7GalL zn>Pt!2V*z(+>>E3_7w5tS@Up)XKiB!Ll&%kXst_*y=9N~WAyu}DH5)u z=JxysUl;S4e?|ut3@uL4aVY*R0}kHVXDeS-@_7dNuzd~8)|a5G=HvD=IMivt)bcU= zTa2mO(xx4-m93R&<7Jz&Ma#tx)K5u^wIsqKYu^6i2$>BL$ z=KTxBt*`A@6WC{x%gP4c++0TpdI826IV{}6C`>Mrb{&Q^1I_H3=DZLSwvA~h!dW^W z$vhFJqfSrM8Ed*q6f+mO;^U^b!vE#Cv43Iw#w8fG%r-x1OfZs9!_-JV4RVb$8GNxb zn3~=S{fEspe~7iF#kN+4N%U(`Vl10PEjIL|?^DDj<8piUvVVuB<-gE_*;c(dg^NzG zIhX3rZf{Z0(<0w6ccS6`bPr6h&CNO=Xx;Ix%nrT zGBZGbVoL>Zvoq++OUl^JwC~#vM7VaTcq9_h1@*sCx1s3v>8B^KHLGx6pJX(S;l@>h zlFt2HVnV5ay;^x<6d%e2ldUEzHuamjC-5+zEN3CwR2p6%A*r}OzBy*@6K~@(=F!Ee z1$d3OSe;-kOei?fC+8?QlT+uWrcBsm%sb1a`vU@%eP{dRh@1xhnlyl4c-_} z;(yc^y*Nlz`_d?cE(sF-HEn~`s$Uu;x?9)=aVBhE|Fx26u6RP|G&vTK#rnirT*^E( z)uL-lTFt)x>oV9zJ{H%3-@@4X)NFkRe#=@rx9U?n_{gQc_pK3TGC)wKZ;KFfK)8F} z=+Is25p(D|MFdfII4&&{6jMF&iT?!h+PqQ%9=3*8QRl;X^7}w-tA`qB;wxVJV)KLSB$XqW9 z=_q0x@0$eLiU`LzGjP8o&|cd)WP$r9fwtnu+0M*(KoV#-2IFLK1|FCM+SX!~1%5XP zwAXvCw!njuK-x7 zTjUXGq%EF?MIM<(+VYvO$fMFoQ$UDYQ<6ugk*0*IRf{|(jWk76mB2hUjWlIcmB>6U ziL9BkY^oBP$ET5|jH(iwC!~?4jH(ixC#I36jH(iyC#8|5jH(izC#R97jH(i!r=*d# zj3ho!O(Sg?NqnA`M%prx_&hz0v}Gjmc}5aBWXnk6^UO5TmXXBgg^Zl8&#LYh)qNMq zbJgdfzTK7bysCO!K{b608t z-rua#REtNF)cZh#cZ-I|w<8`-1!faE=;1gDbaHOh9P)W7pMwsN%MjBz;Wo`NlEL)# z|A+yY{FrJr=jpaD{*tK1A@_JdBLg56_X+^r%M5@%MBe8CSqAzNdA|UtzZ==WpCTVn zfM%@~WB7CAgMz8M;j767e{6h`Q+bzNj+r$Y5I&_L8AFE%@+%L?F?DD=K%NdDImQl+ z0ri|mA(Z3%43nmjX) zg$xUwp7gSZ(0#-i41F+s#begxVd&ueS3PEGZe2E0^hI=daHW$ST=^jbHzVy*7LeEAn`L^NRztxDS`+&|vBd+mB9;RU0$7a+3J$ z55tS|Ccfxp={mfwr50y!qx5*iCF4E)pI?Y8@d3ZJKZP?UkOEtG+=o-$yh3NvtI zlmSd7ZIKeF_mlx6RhWSjq6|!Kp$ts+lmR1En1Rz(2Cy2Yx&`bf+S2Abp+f7=3$3qh z8S87kSZ{<1t-n-R@9Q5qiw4uyx>_0FHPU%i3u>~s`e)j<%x`l^svF z#ccwAS~DN-&`XO*$J*sdxeV!hosixZk=A=4<>J(&w@0LtJ&dL+ht0{cN z`lHBJSNLUEP3bGvdlaiK{ccHJ@hi@ILrz!xB{)s_E6$%QPMq#LqTc#mI*fC=!)SiA zi5AsNy1!T`RM_4;sjR1t^A@n4XiHn~gbJgg0irE!zY{97{)5o^E#ZF{Qa*m1P@(moD(f+x z-2$&JSWA0eWC~6HuHBHIJ=iz;m$T zaTQ6|Joa@5&moFOz0zGXxz`R{hbk@#XD;8and}Pyp2I>O6Xa!hxXHtXM~X+nt!o++ z6|m-H#lj_@?9@r=b2PL^qq5gsuu~K#M?pzWi381fs^a8`D9I@?p*c@eoHja2vikVY zyr(N(j+BzD5-XZhHsjM9igediGE-r?Q=4B-B!jvm7|)!k?4$@PX{L=KZROdDQAd-F z%g$!nt`)Blid2VF*Q73_{h$`CQ=g_lsIY0h zQCZK0yCv*5#2xwu*&Hab!aT^C3RL;9%&H}KZW6|<>MajOtS}GvsB#z`-wZwDYz~OF zwEa$~(E5jz^{9EaL<|vaY3rR(q4key>#^i-V(H`BtoLa--9)F6ZJ}6U9-dNpKy|U* z7I*`QwsZ+Np+f6_6Ix&05&=Y&X!!{8QiU0iyJhVN#n^9K6+J?s0uDwf^g!x&^mkuV zj!@Nc*G#U;1lQ{^m#G%ZaZ%L;t~V5ytDd@MvXuyU-c&rUqUf5(zRuuzOY`_wwtFUd z8^QIq;-YX(jhvEYM{fmq-U)eZ5O-~oL>ibrjhKqMzQ!sy>IvdW_kBN8oHnuwI@Ecr zKDIRPK7T@I!%VeR8cSMhShm1LEe)13P$PL95koDzSUbAQcgBC#y1i$%?Q zfa2w-EXhhT6qlOwz>pIWTAq~a(17)zh*d~!Y8sB0g0Sk!e1TAx0FrRjS8v0}0<&QzEXhVpDRt#w^#V5f|=|DauwZSKV@*7I97Xz%^;PPFGy~ zd9IvUBx0G)2$^anjRI56GM%NEI0EJyQ;kt9mgkwB{20Kpbd=cHO45{m2hm{V1=NQD za85)w1`7%;$)}STI5(ohc7R^!Bn-}r=q7uklSnvU(Qzb{Hckb@1tD3jylE;Pu25t& zf1Dp#NT34D)CgB9X;fn)#nSG@vvmBC!p7xQiisx_bKe!QBf~@@mg#E6goYsTt|XaA z#4=r@n7H{X%VmTt+qH^~=L^f_kVGugbsnZa@1ikG zl|=r`tf6IlNU>2*xnu@O#4UEH7e{6?%1s`9h4)h>$x+!sQon1N z!2Fpavw>NfE{M&a$AqiW@2|;O*1jM-A60}Do~6z65&8>7#SvPXO9km;n#=@gc{-M} z(e=0@NZ0=l5;+rMFXaG-2y1L=4~fi5b7q zpEQ7bDdIG1r+eZY6VBg8oMshuPn>n(d^zGY>#2L2$5vwls(yXrB-;7vwxtC^jCI42$s!P5!t1J7r z6>C)XrAT$@zY}um(l5*D%KtOPiJHZ%xy_F#bn8s%yH{SG@CZ#JYM(##liu9BPDj1S z`$|Nfv`JDJ_f?Fjn{~e3b~3-tEoCD~3gdo?k=vmjIgPBa?yp$6v)xn9Nm3XO2pM~{ zl6u|3c%WjWZg)>6LQwb)QhZVTWMWbZH~7eB8x4{b&Vvr zMt&4Q=996+(rJp3z1$NO_WEq*ko3Ng(SW)igGjnNglB6)66EdP}+>@CUgf8#rMVyKYcG-4tjs-4zv(qwEatXa>J(O zeh7k-JJKG@a~KKaIE)UpG>1>9<1OjL2@a!+?VuP@@!Rdx31o&)5@Ip5#oLn7dO++0RKwzEGUu42Oj|%nA zGjaapU5_(ik57@+Wk{ypNP#cDNV)#P_LM~)ZYPZ9<4Nh-iug2?SCnORXg+B)Cphu^ zP;lxBDN*kVpyXv_@9i8Cs-V2xv|}ycB3Eaejc~&mQVO{M?2&G2;*hT6uOx*{*)r5^T~X+@e5UhWEpoO;sKqPmdrgb$6{NFDCf|! zm8Q}QiRqoJC~|(^L!&V3AoW=&Th^#rWK<1rdfF&$72Ps1gerOE7qR8_&-|-sy1VA$ z&ftDaU1{K`vH|HVH|N`9J1^jX)zR^BR5LAm|Am%CsT{9V*f(w|Ixv`YC%;v`gM0<* zpzmCzPhA0`VL>&RlcSo;5#JD^MWNs-rGR3dF9p#UIh>{5v{$F-L~dzgv-|qLr$~*} zw&KRM#Vz;wp^kfiG4)LEBK~a8Pwzy>jNSKV^nlNd;~N$9(RfufV>q}@v8(G|SOo7t z#r)4*uRE~)_5&lhjsblFT=BN>Jk zKqKwne{RlO1L`P7*+C#q8=P639>dKpd>k7t?hy_*O00;Iu{LY{b7O&5v(3N|dB;A_ z5O0G!Q>dCa)-bnP)XHhSRk{c0IMItU15GnnQm>Ws#G>~EW=36_(MzX{pD21QU~HhI z-VCwmJ(Zcc+mR@b)m*rzF%I1)>Qj63Q66-y*y*0dLXsA0RbiQA$i>DpEj#y$v~E6g z|17WDb(|93N$a+fo?LXF$L#cyr`&_M>FYnAVRrQGS!}po;7Hu~JYk_y6gnqEEe38f z+@=Ze73SdHxKOS(w1&_3ztmtd?L>S`ynS|^vnPq;C~&b(HJ>QqbHb;m|s|Q zQhoj3{~UGhLm)lL0IvtI839S#4WC01T5UTq1uP>p(N5$XQ|6>t_trh&A+X((w&#BCm zzs^iel1X8b$AkpcVFmwZOZZ<)g1`Cl4Kk%-5GuucA(p{h2weGuqPM+g^AGEhKRu!C z2eV7KlnNjXQt*^0&_jocNTE+4e_9K%OxH7xIsOe0M;)u7QkyPK-xA z?*;+r#TaX72*8~h|I=nd!|5g%t5pl;BPF|?ka#!vvWG5-EnKcF?~+~avh5N+QqCB; z-@Hrq)#cdb4%;r-w=2hv1Dj32bxB{9%jUbq%jNUk;!BonwPev&OO`Ee2rlQJlBHWM zS-jPf<%`3%OWBXJwaej4mT#?O`PNF7Z>?nc)=HLdtz`MuN|tY}Wcd!2EMFXqj@Dqm ze`WhbXiBC{r>??XJ8A~(ALs?G!ax;Qcq{N+3>GvR0UF?O+hqyx2)*<8(W>mDHQY`8 zu2QpOtfq!BF=inQGe*f6CW~gqN4I zWg=NhJ(28cl|=fg4)nM~sDt$*64wb0xG{(V;Ye|ryU(j)-A1zz@HqXl{^kVl?W0AM z?&Ye`f7sjR59@7G&KD0^YjYFD)47S_h}=YRLT;kDfBtx}67!4|{C{sY()?kK#1Dyu z_&NLNL`7lms&HMsY_E^lY%eO==TjKprHcB63d6&Pyk4Qg*gheO^b}<-!n}h2bDsHM zpJn{S^WySsY4;wERm_4Jcx+SjX_2mw3`V~d{kfx zx>Du57>me>P`E4Q{1|0oCj|EOKl@+%N%65A=34Wk_&VcG-^OI@X1Tb*GGmWG`Y2v3 zEyrpp^X*R#_ttWSht9mDvQe*3kB?$*VsskwXq!JTn!aRqBGJMey`gi28yvSlM(~ZU zY=P9ROrh!TE7NI{!T1(1o_R}~@1+Ve@Ntv@EGgOSuLPOW=qUq6sxSll|2O`vCPmFH zl!0bX88A|X88|e`z{D2Hz(h|OFj9pXI3~)#QqNJ#s~xFii;qz&mMYA^$tnYjt+Dp( z!dgskZGmC{F&eP46_J-J%*9#xxmcW<+Y+w?8%5l`WyeVtX6ZteC9co7Ow@W1bT{1n zNowzfi3Q%SHxB#IPrE2$GSyruCaR0Tv?*dTuWKnLdZ)m2al~Zan^H{lN`UE-h{+Uq zDJCjMFkPycqF147I*C`%U6xPhVzL~k4I1!Xu6T7wC870`4A5MI;L|^GKMP+-%5t(wvv*i@2>XOpf9+ z3y6w6x?k^!&>nedyMFuKi-ii{ml-Z=TuC+#Z}2^t;j?)u$;UwkzNa#L5=bQpO-Y0C zS0Q6m3rEX?<)sf%$pUjWWf3t$aAV>d$|h-WlBXz|?gy=WqUn(A06#cK@lD07n-Dpl zFngAMKE0O31gE;p>n*JT4N*zEZBwKf-&TyKUsjTng{a4&S>K6R8)YpeR_>)~)^{V; zW-qMVJJPK0MXVFOuyQ|8v%Vj(uI+`D`-GbHcZyZ@=}H!v>(y!M5AvzGf7c7Y^zgKf z50#D}*zCKkPa4gCHGH(uY%wjIM=kS*h}K10DOwY5iuR+3)&)i>S`!(H_Tz}wMMf!F z6B>&4lZe*69HnT@+o5PbRkYcN>zdn#oZ|j0pIe7qIRz4PO2w`V&I>Ja@+> zoP)_J;9URa;PPCBNH|~FC6)U`&TOeYw`P(rv+?KPnBO$ViiQ2?0qTx8eJ+fy;lRjB zU0l8?t=l@>?WsVw+nhT79|yi8{ct`e-)Y9YnWCGYS^B&+@w=~jtPHFj2EJ*T!XfX~ zIi`2*0%H}*@;b#bUY}n2L~%AZL|fVgPN>iaH|JU3wG*rkc;P9w6)LXGj?sJP%0yTqbNDTN?IwUq|JOj!P&K) zj#L@?p(34VO)q_#bx2nR^rKC*9bSb3p~6>Tpa0Ic1sRN_ zSn7jJHh%pd_S*0@K7Jf~K%zq^=)h?oY~GO7y;yIA3a!5=w7zPN+;Rujm0m`ZFu#hL zu;7bCu~cCOu81-)v}OEXMKJe}0V7qIf$v2b7~Vn|815+pMyfCax2O#8@lIQ!2n=!Q zEGV(UJlv`Cfc;@xq7W8|w|owqRAC10k20_&uBE38l)snWOBH6|Cn^K=(HV0R+UBi? zh_P%Q)zRGk$g}(ntS&uXMwuJAAwshn;p+f8T z`|tfAp;@bM3G0crwDnG?(E3A^_4KBM-)ngog0*0#B2hye^ME?@^g?2Yb7;t8ypS0x z74T37!E;#1V4+SX=xfG9!sjhi!$%E$z#p6o1YaUw$;5kz9z-!6tLuts7>t}m; z=ush$8RK+q4>Z$A1oj*q^4QTv86qA?fa#csseI9Mj~-0NMoi@kziLbWIK`wo!d++2 zbyi{3@tVtZNV})9y+$yd5HXpaVJRl+^nvL_#YEkra&N8eNP*|1kf-F^Z@V<$Ia%>Y zx25ZRncf9h&Q~m47bT}jq#m);BvEaor%5gdIfv5oc}Y&LnKb8xA?I)poE)c`^CHE` z^;OBdOO2&DHz`i8yGn9O?WH*{R-9aqmE03Cb$!}3sjE;G=}n4M zSEyZ+x*AoH-W-y;8nq0msZtf`Eg`9|Qp>Q~I#to$8qxL?Rkl)9w6{gHJ;jx+RTb^+ ziZ-lOyY_;rRu%CNG_kH$yXSTFs-pd2MCn=sAs@ASKrEXPrKB6e`_N`g+X95^4D;#hsiTz5p2Hm9e&JlxiU&%tD!V&*t z%6is#Z^*)0$`L|fYTPN>lO z*R=I>&85#WX5ENpm)i1jaqol*t$$ZpkGHluxCNZgyru2;QiU1#NM*nUkFCf20xeT9 z1XD=l=C&&nJqDM-0oHRsWalS{ayp;E@0^O%s+^*^(Fgyh`{OG(OGa~`KSb;;Xc z42NHZMX&lD$7@nm^xcz6*(=f$6lqZQU9P|ZQz-+R&R{)rY+$=j49FM3YAgGTP#IF-_fqcT!HfqivD^6O~Ud}p5Slb?ocuE`PsUA~Q2&18tO+!#U&uesb7(E_KCoS>v zCX9ZmBzaMH!WTwPg%LmC<>uBIPsU6gY|vqpA$wktp+~hU-yN8%XLmTW>;qm_ZOwWi zWLjOGX|-i~F=WDwZ?3P3jH=T6LSwU+BCbSv7jlu)i0iiz*KiMZ4O_046_=gREtg3n zWZ7QPY&?rwl8j_5*Q*iNNXcCC7ctBAn&RU5+Hz)*h-G>`WGWjHV3LS`-)FhSK{>Fg=9miu1O)8SoT3kHrx}Lxc>Kwj9p(ko67qiDl+zdX);v+ ze^6xHSd=CsDO;K!g=DLH@|iRlABSXUGI}x1wHlv9biGAKRl?)bh_1Kzs7io*rs!kMx=CRRXehONY+D~sHWrqMMh0Y zX~TSLa)hG7OR^@_EK&8PCT=h_NDrtVw#It@NX5i+fQkAx!9*gK=_t)a6MrR{AYz%0 zR!lGzA3@4dv5e(9R&jCul3q7C)UAMVmdfIBnvAkop3LX+ctvJ%S(;5}^n{RZO?lhE zCQ)&&A~W+gbTn{ls?nHJce}bHIO!gF6=s-y;U{K-P%fE2FXA-kaQ4L65YF=>PIDq> zPn;9Nc|pW!&Iag-bFFY*7;&22_C0Ynh4UiCNe7ynZ{(#pSyVVTDNZ{{)KkG5Sz*06 z!-{h#mcYBPUYIY*FyrKkB{0uB=1Viobi&6Hs39&^U#7TaGR7V{T)OyZ_N*num**4n z0ZBcX&g>*E8m>?pXojvQRtO5;m5Og-s=3hP3(TUzd6nX%=r#+_OM8|@h4X5~DaS(f zly@sEyw@t;xT3Y+cKla!saMt4TzM2$wbwMGmsMXb84O0&A^_WKd5u5L@S zx(fIDh*ej(rCD9{-=J9IDz_ACQ0d;NSTmJwDcZ2wy(z;RRJ%Pe`-=DG40llR_Q36{ z-di%+LAoQVT<_Uju5i8$FGv-)nDRpt@aDJpXF;p{~GxM#)EM#P*JmF6;V&%snquHj} z3*%~G{3K+=#9F$*#U$@ac|t~3Ibi8K%BK;hS?Jb_nN{{GufdBr%_`BJIEN+g`}~h; zTC9b6u^tUIb8W)9uV&@Rww^r76K=w}U&Lv)c$UsR&$;5 zqWL#rJWw&x1YA!hLQwd=tN0MIJz7YT!gx@~*kc5N(M9^fA!F}>?&ACq#mFBVdU7L4 zO0Ex8jQrK1Cq|MK#={k3R5F?RS85$Ks**=k5xKHCBIML%QK3gmr)$%W3ps-}tt_c;)sBx? zml96CT{|IST}nVzT|}LzSnU@i|Av-wLD;sPqI3E>d2+lSeqO(wt$=%WUbYScDDD z!ggdB4HK^kU4n~})z{B$pjV&My3I;+>+n3;2k7ifdu$9jHx&@ruFbNk!s?dJih%Fn z{}2=yS?9{knBd9=Y4bs;;DHp3^&g%@zP1>f9p!O$o=|%Kg?P9DB}86){QvNF0^^Oe zH$_vlq;gL;LPMs7PfhGh_}oc>`Z-0twy{7^n@(R%D&O2~kBvjM_QsW!`NrsYd#t%& z!jiIXb|uqaRsq}k$*_%fFi`ZQK4HMgAqqwH} z&&{fCpk^m<)cwN1HUmR7grt4$)o07qVy5e3SUAkVJ=KxIenT5hI|69%0z2s=Q0+^38Su4z=;n=j=ddXj!=c`>J*7A%oH2C9xFQlaa(OSWW;2ywdZ^7(JqDe+K)FT2Ktu$Z(D7>?0;Xj z^|F7r_168{+5N-ok)eOwbGNUqT;JFKMcT+ZJ-WU<-k2KQ8Gd!E===KrBc;J9^e*CE z!mGS?Tl~%Lz~3mCfeQWRTWic;ef`@jq59N(u@Gj}P?qALo9LHP$v~a5K&>yYKe3Ju1V{ya{Po zAJCpyoT&qP2Y$}XHfIn54Z>~QxYurf^UaOu@(ff4Dtqj?+a9~`w#SB*0~GGd`uh7Z zhy0C=U;XNaUE6;LX+-|${B(V)Io93@8_ZCT42%q}8XO!R?(6@b=&cyXtAO~fPqha6 zw)&sj=>9jyW?FsyP-XtawiN* z@8I9q?f=<;whg_InT65uaWwFi&!dXiIIzvi!IfXwp7HwK{Cx0k!sKE5s^ZT*bXtA7 zh4;D}epOZs-U5_ivS7ZP6mSwE^k(~r;)<`CJ$e)hzC@e%~#M z*rZPF>wm(MK?&8OWHJB4UHU<4l%MQhH{V>Ky_k&H7Hzmj(NCa$Wt2rUNO-1ydUm`y zv9ptBxQO z)VY9_^fG+~|DA_R_z@vr=pS8}oo?2txe1-f_ZvvBa^N3#+5L;CGg0T^FVwB=_SE=% zWBodMN5hf9=haUIQms8HAm0h@Cmby;Ms-kE@e5qp2T= zskvpXi@MlwIH;44$#N41h@2n_ocEUI_IF$7Cgp zk5Di_J`NE>*&UnN)Pex%#nxlRRudqT@@8)R87a_S$mIx{Ea;XUEAv4R)+G^R> zrjPLNU5higdhfm4lW1x&WUWur((#?l_@Rn1(_p(jJ-67Nqdwit0_HIK`m5-S?1VaK zZXPEv;Z1B|fY{exYqxjWu*X;T+^gOC=Wi_R_P2ju-*b;$cl#Q;b$$Iq?e;`Oa(4gZ zXbZliE28Fi++#rg=v#InTBc*ZJV-i%lWHP`q-q_K#Cqg%88g#>d2sJx#dy?mS=(bdkys-D2_C(i zmuR4MGlHW^@E9@0j>9qMWX&PTW5pVkI>Z^J)Z?5%E_ql9AMb5a>BCO^1nWTRb+Z4= zUUCqhXj5jfe%RVvMdE6RlHQY4vJvLg(ZLByJy|>7CL_Z{PRXZnmJF>gg}(mN?Q?6Y zO)|gw`p;TUXQgZZtH1mD&!*&>dgLb#$mKi-fs!P@FHWHuI%hfEbKMEgzGVElgfHgz z@df@1mSd8^22mxp+*)HSxsZ@U#vS=cL=oF?5g~_*kX$^_zKM_{MM#7+b6!lyRRu`O z6(cVp?u`mQSA9*? zU%7nUy79F|NYQ@P@@6q|NR(f_9Fsh?4SR1apdAudU9%ittcyHF?>gt{T0#~%YDi4I zjtm$oHo#O&h?MUw=g*r(CJc+Q-#6GIBdBg+bFW{{t9J@~Ff8`oz|f*-9TDH&h^*DC z1*9Wl>rI3#%GHQidNU!5@-!lb-m;uOqNd|&m1w_}kVV>8iT2x;&#jv;$k1xZ`t8f< z%V=8nYSDcMzb76UR9ZpJb0;C!6d{H4E>rT#^BGoGPuy*=s!qvbh4)9x@qws_)xFa9 z5K?(G!&!p?9C`N=Qk7>G2~tMh$J%T75H&kJO%vx*VPr+{cC*L>Bw~PMc_`c0|KM`| z{8&IFvGiklor`kr>XV0-+iPaitge!HczI*}LbD(vu9A3!%6_{7B#Ovn`6nDtgGEp& z&Yv>0C|9n2cyu}K92phXs4Wh{^cM`Zy@E>IY%^30c#NU$HOXU@7w>U~;`@pz^gO7P z)e{VD6hK|@|B|5-MNqNzNrt+{C&vKSN6Qh&`5ezcrM?`h;J8nmY|pYJP?0Lu#Ctqg?9bY|HU;vxk|G zFmY~n-Xo~C#jRH%qK*%gGYywhc!NO4=7Rz|j&qo~`r3MZ!EvB`h~s#dKGB@ObQN_3 zuoA)g@`NzeGE3@7D;Ar!?*I{+85yM(2y-7RcutDoj**jVHA+5Z#oTCphtaiR;@AYs zp0fgdGJIsJ;Gg!wKmWsq@eRA;yVw9dWiq_&=MrWp7h|eLV9q1Va4yEwhrpaqn2}tJ zsR)6&fH13aF{TCt=0d`(&c&Fj515MxQ_atqohATk6QlC8R&{y1m{IwetGe7>vH}wT zFp8!Dlp|$U0NO5HK_h=acmhCS+=Ku?m#v^dKR`V8S0FbR0MO+t?06qI^y#%eJrMxp z6)R}4pM}v=Dc>szLr#dO=&4|?B8@b_&%*S`9~!Sl5M!A!>Eu7OacbNT;g2Z?F~oqwS-olH>0ahH{a`IL}>A7_vW$ zakk&Ef=2Mb;2*8ajq73ejf5dxS&Y+l(+Z5*0im(G3JV#^gXQKG7_O5h8nr8k4B`Q~ zg&>89TRGSP!TY00=yej;+(wu+xfnCFho;+2;gUJovY-HQY(Fqadg=3#?#2J%3K{?d zM+0J&L3%2--9Z>~WftRHc_(40*s>T`YRgl2Lgh= z{(Dx?KpjLpURUP3@jE2%rFW6Cn0*&r7VleOM(2dunU*JNd(^-kboZ~I!8w3DMpruB zm>r-8s5rL+C|l%av<}RJgsBeZg0P<2zJEVv6q%o;syh20TEXLRpy*$1ydR%K<--ia zYP?*S8Jh$42*W6-^Vm!e6|kQ$Y&-!o?J8hDWfMDq*wJ22-9YtNe@r)LwK0`-Q*MoRgi&7)jQPeeP&uLMrNjr+VO7+)T zlzLSiMO`QBHzX>a4a?rS@_EK|Q}#6hN!YxgMGMPbL|xgxs71xX+_D!@XYfl}w6N?& z)Rp~jwP<14i>NF6m$hhN*^8(v`&YDRVcCnQEBjZqXkpols4M%|R$x8=(L%EVs_4}u z!Rsq%$W8%;e>BF8ym2U}(s$Xk-Kr#G8IxOfldF)m4pGPhHLQmJ*~2-D4X0 zqB5w5(zm@V2Jc#!#`4NgN9xD;5P!#uQy4hVaIUBf_aXSM9o9q0j_;K&HR1>KJ#?GK z=$s22r~tV9SiAe4f3wT(N=g#KK|ToHcLbAN5rmToAlUEErdmx}r8mE@IL8aw2QZw* zm-;`We%18i6gmO3RojMvD$kXC>#kWE?@cV6rhp**HH;$X6pWz+VvHogzlCrV9liLIV|SuE5|q zc%G|AB!J$e(W1pGxmc2CcjB!s1Ca$ z$|yy&U`2?8Rv-pVSA`<1%wt&J)gh#fJ~1Z4RJeLPZS27?HxfWC1_4aXq>Q*W5wMz;8B;lerwPk5a_RA(xYaKW+#moR1BL zeSD*XpiD&_ua>?kO37E}q@eERP{OG*7*=^LaT>IY_r{!z( zf>3#XB;#~i6f1qefxhg8(d2NG@L(n}U#${_-XF(OPO;!v^Ft0sim~y|I+&Y@hck&* z^Xl-ORHD%QNG#xXeRwZQ z%2(#ZpzZxo!l^SD*7rLH`7)+ju^ZOb&>ZR?WD>2;pl4cZD^Y0ueJthl3XU~@7{hX2 z-iiae8mC!52GyP+G=gyBXOT?c zMWEP;`+SZDp7nVr%f0-dm2*j^k=r+xNO{m1vY(e|t>aO&t`A+bcBUjvClV~M=D z3?vSVCGw&&kT_gRxR~Vr`w>x+bzKyaU~_?RWGJB>C-Hbx2uZokQ63%P6HasZV;o*$ zge%A)e#?%{B-%Vhk*Guw568t)E?{&`)U_w(u$nIl5ol;u~g)gA>))wV_1Pxg!;0K zOxh_Tb9qK4?G%x@B9a+4PB8=XD>I2jUSUyq<*HaJ^2)IB%GEKfz$-$1O-3f|6_L3% zBa`-u$Xpl6j99PmG~V|ziA7#vQF!J1u~g)h5#yEXV_1P#g!+bzOxi0Vb7Mv(?G=%^ zDUw-by~1tz&6&g^udpb*a!V`~d1aOH%B?Z1z$-$1TSg}B6_L3;Ba`-u$owFZS#7*h z;}Pu-Gl@lBVNrPHj#w)4%4*}4J7ZXZSA_bmj7-`qB6D{}ChZlG`B5aZ#(IV4U+&2y z7I}q5;gx%1smLp9j92c9VFg|h>iaV?X|IUP0~wjLS48F^Cxef~({s85_i&t)?-DNu zk315|IEPpiD6pC*0_D0Rp#5nqk>`v+;%Bi$o+|>0pNA6MaT%y^ukFz|slXG`;rT@* z6MDk-*dB{OX-^34AiKHt;;+;@} zJ0Nfccfa0^(+XT6J(u?)na~xs>-ByFO1na6e-}$6T_F-5#1ctYh{W$h3GQ{^TN3xV zK8(`}Tp`_+KSVO2D{O!3qX?9Ch0uN+OC(((5}(8pNmq!(r=bLQHQ);FXnhu^6}UqB zDEs^?UPy#lCT_6Tgs!litbHR;+7&{(Uo4Syg-GllOC(((5(k75+u1%RuTD5HPAhN) z3!;DZ-AE>M#dfB@c~AsOyFzFWjwO<=5Q#%#iKHt;;&7Ju^6UiW3h`e$F_t?VSiM5u zc#p_SwjSYgU}QN=mI2a7=18+|A~XoGVa$Q?8NgV=4ZgMH*u3PFB_RVWIW9-qS)$Nv z$%zg;B$jZ4Yb`k`FF9pN$N)=D&XIPOC^TDgngb7uCEVUwOHR*APFWH%z>+g^q@5)S z&6b?a;7MHIJh@H_dN-FTO z^cQalMFKC|j_$1?B<*G4ye$$)dRYW+j|7rl7J(l`0!c56zz-vVq?bkDjzECBlro~Y zGfFD(vUEl73Pl1h+dlN&Atdc(;rvk~ko2+$+!F~Ty(|LvMgmDMi@<%6K+?-1aK9I@ zD>|_M9Pj=E`nmOQTpzOlun#J%cPx(erjEsrRibgJ`pC-Fm(V<kdS=uhv+y>{Eo|2#~{k2NO*cRU&hh(ip5UGj?nkQ-;3@39b` z7iAj$cnHsnF%5qrgy%(=hW|2z=f#(XKdIq70I;j&p9&MwUX@Y9uL1$>RXf;uIshcS zDtym`@RU~t{%iq~X}=pLKbu;dyS=@FO&wU2QuJM}`S$uS)qG6$ogr+NeD`03^LCe8+_Flvf3Q zYzR+zRp7^k@RU~tetZZ|c~#&iXttH4hS;VHKY{PYl>a;w14&~Tn1kWuQHVM^MqGOut}AfVl9XIst=07 z0qs^hpK?_INV-+{t`6ZTw+j545T0_Yz^@JADYpvzx)7dntH7^k_?I!E(8hmsN8pAi zCC9IU7`g&Ch9c})j{!kn|4ktz>syaEbK5sZ0vYed0=Gm08UMxtw?+aP561$xMFJTg z#{#zp0^F?Ge!&l-lmaJ9Yxu)ZByh6r8{82>(oPo6J0pRllSSaJNFeEC5x6@NNIF>r zeiR8Loh$17dkFcL_5Spy2}J@g+n&QuLrB`o!uhjEAn9ch_<1Cd z^s)#%8VMx5ECRoX1d?7Bfyb0UFuDDBkYGKm_A{B9N9LuU&}ijcJHh=+oopPdX1GJD zCj%_|RLyaR*ryG4oR$WRk1p7avD^iECQhk(kMgM}eiU|2G1{ zclk)|^Knv2trCUW7a}oHD=1d`TLIxCe5Cf}I4Px8i9+owk(j6z6svt*K=|SwseL0( zN~u+%Q2S;iCTa!6YTscHE^dr;z8gHxRj7oZ?L95PswAEDyf4X^IjMPFRbIFHyG&wA zp_Ycy4`M-4>~O674-BiD!;W;H=%X;fYE>_dmVv&H13W8p2-ft817Lr&)x?X;J`EG{ zHHi!~eHP%ICPuKPef~AgL6LSk`oyZ@?XCMpDfzmb6qM~3N;qu>!|L|;5ITRz>f`m- z2gFGUg-#9{4~%5IN`qpZ-*q4-YEMx*C`!rK=%k?V;84QpQ|bW#!yN#pPjG){pkg+-h6(waL4uBxBns|Zq(P2Wq zCXs=rV*#0b`OtOHQgSXE|L=eQ^-Uzrnww&Ozyr_Nwl-w7TMoD?QnPoG5xr{MMZkCFQGhV$gVMDB%<;eWy7Hf=9B*FWu>3O1?G`g0eFL z{QpPTdwolFtx3M{2VC#Hu0OZ>_80@j;Z^iKcOG`r5=&+RuUeB z_Z|svh4&!5gclwJ!b-xMJ9B;!Yt8sFzg1^+k8XBE>|d_jJ7Z-`wl)F@H?;4Uv2-09G-9aAldoi>TH1Gy|D2m# zpl$c~z-AX{+dV$8#Rb}Sj}Lt70&Tm;2ewv$4|?=|_aE&^&ab|0PQjDxp5rQ&p5yJB zsGei<*1B3a;NkA8RY%DoIgLq#Si>=|8D2cPjK;LKi*tBT8fbql^OqcT%Rl{pKm<^VF`6H)Mbg*fVCk+Y{4Ga^ zO1bk_qWV;a#oO_#PiALxRMa?bXWCC(qpv`}PxCx_w=9mcG6JB$jj!yZaxteuL$Q>E+$)4}Jb! zag(~I0vvI)4lbA`Q7vir-*^x;vE5o~g=5MIXQ}vY!ok`3j(rfWor0mF~H?`rt zkMQi}*G>QbnBPP1wuFF$Od@?M{+fhvI)tbU{rbHRQXT~ZROn1%CXoh;zanKvzNSHy zA^rBm9{57pPuC50QfF8dOSB=HsBq@VyrGrlgZFykg_WPfVIp*9A(BYLOLxU->6tRp zkse#Ls1o@ROo;yGKn)<{05>UlRmEueS4FXo8k)Gv1Bs`4A~sq*p8C?pbSTIsGZEj>e~S8^Xh^5mT% zAMXr7B0*-B?h4Y5J z-Wg+o1esrWD@0N=U{MzPrI%HofA_xpUXR62X{SgkftF|@vuaPqEv+p5{_@d3;Ma)c zD_Z81&bTU-aLYAO;mnh9D=N#oz5Dh9F28QSc1mYll}fm8G*RKqlW{96OTYAj1}?vN zS2?9Ku1Y1`YE4u)^JLtb%JS}eef}MA`A)UgDV=duD&f{?qQaRc8mx05>as#xOf z(L}{FPv-5dEUmApES-H$>ddQRiML-970*1Gcc8MgzNqBoSHnRkb>>yE#5<&kif5k8 zJ6u^>UsUq)%i%jGb>>yE#5*1J_I`gVn;vLsS#WPRlov19W zFDiKUJI_x#sWY#NCEh7bR6O%!-uIQ|{no!HlUJYpE{Gpg0S(7Nt@r+|dkjMfc3S)u zD?2jkY-Q;8AxZgd@Hr6x!tWs^2$94&U%D$yOV5-GrOaDT##~edoMJM!E+~DT97>=c z#b1)}AI)4U4R~pH&)@o&RS8i!lu%d1U!w3|j$ADb{I1B~_19DhQ8|=Q*Tr9=aBy+6 zGW7oF&-jMO-|x3X0LXor5J{Y$N_T~6=_#3hCZd%2Wy+X4s&u}f^m+JY`dR!X316nW zr2$_i`|Z2;R0&c1GTj${iNcrZL21C3>79IYd8kT=;+N@>_)8SNOuuDApPp~``J|`* zX1K>r0jqfBN-BM=o@gS|YER0i!;ix9$KJj170Yk3o_VSL;_Q<#mx#|@ra)#_X1*v) z>2H6)%v0&5mm(%}iTTQ93TAd?=Ih$jr{_l>f|>8vZ@d&Rt6XCC|4&*4mM=elxMrFw zGY7!bEq^KT9h!&DK&OBxU&;8;y$UhT=aag`-?Krg#J9n zrqjXWGVq?Yog|5PsYuuEv*X&FTYQk z>!ko#8&lg926SKf6orzT{0T*hb;+ZGo7S)!I(JXGmpQ33uZkt!a!ph`^JLzN%F??>^$)ArKfCg^ zlRERNSmJ%7iHc{Q%v)JmTBoMGzFeoPoYa|D#S(9|CMuqJGH*>~X`P*tm%l^TI;k_S ziY4AUO;kMdWZwG9(zo|NRJ{CleuI-b^Qu_lZPY}?Gf(Disw~y_HGT^4+pP3RYa}W7 z3xj+Q*{VYO!zeT9QEU@`eh`%-KZfnK;p0E?uO?b|j~yxmBxI6*r}%49%aKXDDnt4f z1}Wb(cB{~t#7rXX5r0L>j!fED8PYdz@jhd}d>ou&zO8>a(Jwpzbvivka z>;0a7szc%}e-5DCdsw{X&zH1&k5t}%yiofwh@&FlO8N8n{5;5{OFdTFt4nR^`BINp zavx&sfZ&7(0S1|bIa%5(OiRz0AF}*j`n7NG_4(MoZ25csw0s+Bf8ftD!iiXDD63J@HppkRACF?pKDsy{aFZ$jjn^DxFabCDcRl zSE%gBsK?pRuU9(C==T@-DVHZsX=h0)!JcX&(`rw~J*zE!(vwpEpv!X=0vIxh^+NnL zs^!R}m$ji+b-3EPy}nW*AR&|duf<=JT8>P5QyY5xr5FAI@H~?G|EH~&dwvSC0#<6! zvO{a#{wv*2HB}S&InvK-)Rw;eh_oLA9^fP}|E7(|V7kPCnyHD|lP_|JSw85OzEM8t zjeC3k?jPzD0P)kL`3Wdf2{%j=hO0aoH@vX)`+NMDNS-SroB~|&YU`Ij6;cT|QWFKP z<;l2FrKJ~7$nEAd+H1T({URC^*+l)^#Y$|;mAPYJ>fL%)(|_HEBd`3tj&0K_aD8X& z_klzccbty_T>CP4ytCncoS)(eZCWEaM-zFXk2x~#&y$=j-yQhhJ4|j98_~S8Oz|;? z#!c`mXXDS$=bO;fHn9<%v+1g*`ItlFKX9H2+wbv}&i{2Pez)MPHmxIBqKQ1)$3U)q z>C>bixNx@oOCYdz=C)~#Wd8n$c|PXI_>CI#oh|>K1b(F#w26&q{*Hx(KIYK)trLr! z4Zq6K-aIdE6C2Svo1X6_KIYK)&GXC6)+-&=x;yF$r+`{kSD8x4uQg%7%9HZx^q{ur z9d)G&0j$2Gt`dKZs_v+(YlGfV*QgMX>O1OM@z&Ylj&*P zpsAWz-%&T#7Ty@sf5(&Gb8T`GnC_06hzus;X3f;Z`i{EQEFbhsNxh?Pa|(cZN3Bx{ zw_Ov4t3Gqer&EQ(qIcAtP64j`w#=WZzN7BaM1iaBsJlyxyQA*$8ZXe_QPVZ{tM90L zU97}bchmzg^=>^s?v8q}O{>6iM=hi2$vxy_0N0581Rr*`@{amlo7PC?9rcKhIWq33 zN1aXXsK?sGMl|oJ$9>G9aYsGjY;s3E*(Nrkc}G3vV-Afw>S@@1k1tnwM?KS~btFqP zeWlO(7|69ReVQ&^&pBIpM?K%BHIjKpz2IYxj63Q@XOlbXk8NTjns?MoKIYK4qh5A4 zxuafb6C2UIqh9qfhsGWChS_>`Z@Z)3bPA|tb(N{~CBCHz16H1tPv;A@MenG$RS019 z9rcd*YgBbd{kb;i9rdmX0ja*D-V=XKs_v-wYXk3#_!rzBI0dY>J8F9JnM_aPLrvAh z`i}ajw(!QtJL)e^0@K}56OqA0{8ckGvA&}|G0O-2Qc~}zPn`mw-cjpR!adW3;i}J^ z^6BR&3X9%RUpNK0^4l_hs``%lQWFKPx}&}-E$)u`+H1T(e@9K%Slm(HxLAp;?x>&r zXSU&cx1Jw&M;*|nRbaWJmeKU&4)igAYeas62RU1LM;+XzHIjKp9pYn-j63R3XOlbX zur{#~%{%IFA9HBjQAaqN+)+oiiH&I9QAhchL*tJ61#G{^m#e&^e%YpVBug}XrN{Uf z$h9whn)Krq&Q{)0$F*sVWZqH7`PAO>9K-jylQ592$4j$<8Ks)G2LZ zBbs;AuYAm*aYvn=ZGBp&zIuzBp#qpiag~|$^_?mH467U|+@ryj((^<7_fq+c@N1_K*TzFE z@xIYW!E1RkZ)IWOeToN0tGrer%cE_(NM;jtwTl(l?8@AAFx7{o^%J|kO{>85J+4pN zIqU`>1Gq+H@-TahrY2k#UdP;%st{`?gJNMDrfE)yEtf_qc7&Cil4Q zZDJ#u_qZKC=Fqsu?S`#BB(1;Fd)l;)WQnHlu)RJ8a_vi>CjFDx&Q{*z_P1$`WZvTr z_?RQ(9(T~$9K-9(UNs92)ny@0?BUaYx$3Ml|nnM}5qpagRG;w$^E>-s4WH z0H)mI>P-6jo)W*o_*ql9OV{sfgWltQP$3}I_qfyIuSwNC?o4gqoeKB3vrYl4?H-q| zjLCFq=QLFl>wDb!+QM5E?{OEL1g5*kB_e}~cu_MovA)M$HcNGUS-(K9I0Znx=OiA+ zU&3A0gyE{sobu^6K@=9f$6a>{ac#W%9(O|{1+Tit-7GA;Pw^gi%WD#y{SHmxIB zqUkIB(#Jrqed*JrpRI7V@*elPO=~3c9{0w_92xhx{{MOFl%mfEd_Z!K`?O7LMDrf^ znU6U%?r{U0P4006+r&mR?{R~C%%O3Q8CxH9xhm{Rxjd=Ec& zl`nCO3IL`Puh#$S+UogXolMNJk^&Kq%o`_$@+UIJI|W2}PVF=0RDw;=gwXI`$W0Ur zsxkk)<0PlVIJV+sO$ZK+I7KYz!~Da*UpXblu?eSYLU3roX<|VK=AVt4?vxnE_M4#z z!J+wPiUsFa`KLQ(IVHyBRQlS@)`Z~j`_$)%1!b3iDu1q1VjO#Jo+bo`j+-wQG+h3n z`~^;laqPB*nh+d%ZIM{eYWZjK7ds`!vCo!hLU8D^rDDnd$RU18WtmfA9RF#=<(d#2 z{-MYfV#)vb-&?=S|AorePKj~+Cj-CHgy8TGD6SNX{WEy!U0*J;RbGpU)xV#&+GT{9 zTAFTuESKCaYrWP0WxuR*8HJ)@)~ktcxpK#B@LB_uEwj;O6pEhNq$U)N{Q}3$ zUTc7|Yqq$ILeVzgstI*tzt3^2*BYQ~oNX?nP;}0AHKBCuH)!qfS_725v(sf1issp+ zCV6wU+iML_w$C1yQ7HOnubNOm-Esr%^I8Lx9kkzN6p9u)peEE%xBMRGpw}9pY@$Oh zqfm6wVKt$Qy5%6FVT6pi$~n)s$CH_{JYYk;zmPP>dk(MV_1ghsO8CUVwm4Nx}H zIhRo=8tJ^6&`9=Ej~Bew0A(XxbQy)Bk$zMY8p-}Wu}fZSfU=P;yNp87NLSQ^M(Up5 z4PEtG1C)()&1DpdM!K#hG?M+=ksDrXfU=Qpx{N~6NVm<@x3w(#mOprZM+NX~{*?Qt zNT!$R&yq4C9qCh~UwbNsa{t_ON{1`NXX5_3uL+@{5gv$zZ&6zRp~gd}#5lIWBTWbn zUGR%oSOqQIuTF_^?1A4jAvm&IgI5+&_bz665%;V~8dMhxZ&q z#ZvB{VNQv0e7`YV6N1CLjS*te{WH>QF|pb|qg+Oq+&`n$#B#~|=X0+$K-n)}xQs&4 zFkh+(6=VNU$r!ISK-n^5T}GkknQ>}D(b)bO@3jUfyJmvRC=_ioQB9~D+dq@M)&OPW zOm-QCqI0IG38iEE=PR!@K-oJ}T}Gj3o@r`A_1J$OHr;CtP`=xk;W7$E|IAbq3dr`) zEUz^{*+H{iMxkh-Ick#qGuLYkP&Uy#mr*FXXug_c|19uY1C)KV&}9^gMp`5$-9L-H z7DKE3v&3Zt%KfucO=u+BKg+z<0A(XBcNvAEkyfaQZ+i0n`Pyp@P&U#xE~8L1(n>X< zk!=60@>&CwjkMZj6pBV#qb4+x?Vq(?Yk;zm*13#A(MapnghsOcv%zZ(P&U#=mr*Dh zX_K1JNVb1Ad#wS=M%v;s3PmG*t0pv(?Vqh)Yk;zmwz-T#(MUVZ)brie0P0!(1DLy< z0%H3DDzoXm-)_wrweqCTl77>PTFMo)*GnBPl%I?{XrId{5=&^mn)q&|wM`Cqse#FA zIOsCUL^T{z6RV-cJnW?gCY#|qmr*8~;fR{h40#kC^-=?q#c<4Jl!; z`Wt53`DVNn$PNpkfYGCqB%2k(9Cf=l6 zQuq8Kwpva%d`iLGPB)#6b(F``tv0cV%trdjryLobblcfbO17Zxw24h*_R`Nj z<;ZBJyUvDcvKe)+O>82wo$mXTBcq=lI2#Jew$#Hmv5Cx%dgN1%jF$Sv*-%q9sD5n| zo5*ac-+aoE(N&L~4P|Ak>Pef}L}p(-^(jY2V?A>=RF+Mv=WSvWnXUE0ryLo*_0rj7 zU%hG*o5<|0*FNRQXs6vQ`bLO1g{t@ly`lW%G^xQsIKmS&@x%0aftOASm8vdu1|OuU)d zq9z?=-?oVj*lLh%^(h5&kZp4|)=?g0+uOt@G8<`!PdPF=X{WQHlx&dgY7?8t?4{j4 z<;ZBJJ%e4E%nt_Il!pHeah*+pkV zhuI+eu}y3uv%@a=lp~|VE;}3FSmi->rA=%iv%{|Xlp~|Vt~nbz%m&%@HnEA!4!hw~ zj*Jew>1^mQ8)UcI#3nL3>?facWOUeVXG4eCAiL8hHj&w3Kl_v;qr>hx8#>Ge*}XQg ziOdeW?^BM94twBi=r9{(58K2hGCS;%PdPF=?6KM2PXDw|&-cn@^hAXY$Rd*###8Yd zjE)pezZI!8@C`_7n><$`B=J@ILi{BOuh*BQfiKn;>6Hp0iLcVv;x9>feZDCTcyZ?K z)BnH9hhp{w8`5u=3TF!7fpydFO*4R|r;#WO&K@S6B494P*hgxBAo(tsCV-Z_I+ z2uXa^4H17y!s~5lX~2suubW{ige1PohKs)>;q^75G~mURH_b>DLK0t9qr_j5@Om0u z8pNB5##RPKtSKi^-Z09{OU6SWpsr+OS5v3#XR=Q9!&@j{jygq=oi}p`*f0AvAw2ZU0kNQ8 zy4!!Y=%kp(emSHG;h|p+iv|7C-TsS3C&fJW%Mnco5B+kqw7i3nWB-!yF(-vQi=_>5 zToWZPc~U<8hl*lBzt}$~e9}oVkNt8=6T(BkoHk3hwhebig$}SHldkQo_zguzzOr+r z0T-6vmz`H3B=M>)h`%J^nl6?GR%UC%{is4nVqaboe@Q}HUM>wN%e>*Ps1TCalvl-H zlF*aaN&{*#Z@B9!gd}$44e^&GG~~_FfP%~$?v@H6iS784_)8MH@pfrIHRcU>M}?5Y zUi?}7B?+x~w=|#>^M<>pLP%mG-WPvKLLWXT4XDH1h7VN;N$kQ$;x9>P!e2@QiZJ)! zuPTHjw%~8#FG=XY$E86x+!H5-uxi6S)kKNohI=L!Rz>cL=T3@wY>O9~5FYyCrC3lH zw&7kmDdw>=UTZ>lJoym|YQr{M|NlCl{aA5!%ddTZ_)}>({n3Q*&>f$N1?6EIZh({G z>tlZm)P(SO3M3X(h;6vRPKtSKks+E89?ycrf+DdEH_S;fk6kic6T;((kXTSBw&6xP zDdw?JMrlHLJQorRO2vLP#OF?mdF+)hG$A~m4v7WTV!st)jFVy>+hwdKgvT?Y(xMw~ zypuv+wc#dcqU3SIO%x0I#Wvg|C&fJW%VbRm5B)MlEPO+fH{4fFih1mpshSWT&xpi= zez6TV-AOTz?@VTBLU`zxnPNe|*oK?sq?pHknXL)o@r+0;=oi~?bDb3P*e~-mAv~TD zi3R;)8*YJ!gt$>WAwBNp_FZMd~gih1mpb(#k(O)7MN6`8b;HjCd-bfj>Xu3Jh2E-b$<`&NaJ#H-pW{*r`i+EyA^nXL`C zU4@XuzT6@Hl7zP0SsGB5dBg2eAtbRWcZP$o-`O z1(`S80Tn_L+wq|IOA@;AP-#Fl<_&jPg^Uy{&-r%D5gFmJf;RR~FJ!5_q5lF)&tOM`B>GfoO&)rLE( zi4w;RcTOy<3Ony{Qp{spT+oE@&=(iQg2J#3_oI_y9y{ZbCWOb6AF-e|Y{Ok~Qp{s> zT-Ai|&>h#rg7UBpcil-bkNt5&6T;&ukXTS5w&89$Ddw?7e$s^ScorlU6p3xPJ5Gvu z?2?}~Av~T4i3N3H8}6QyVjdgiz9xjnb0M*yRBXdNbW+S?uRPL(@OU~T7F3IExL=(V z^VlxGX+n5BBPuPr;hs1ti5J|nU>X5Di?_%otP!x@n#gol3lOf2XZ+i(M%6ki|v zWuPX6$1@_apkHjm4R%t@W4{d1gz$JqBo_3GZMb1hih1mp;hGR0&xpi=ez6TV(n&Fo z{W3}u!s8i{SkN!F;XZd#%wxZNp$Xyfj7Ti#7u#@SoD}oeFJmjVnMaohWp-0F^}!?gC>N>GosR>8}5vgLSD7u&T69Mal@Sx z3;M-2+<7O(Jod{4O$ZPDa#1XNLy|Y#k4}nt?3YWL5FXEn#DadY4R^&!F^~OnRTIKP zzg!aw`o%WfbtlC<_R9@T2#;q(VnM&yhP&mYn8$wkNfW~38If4fFSgeoez6Vr+(|Ky{qjN+!b88jHp^ePZMZiobbu9^ zw2%7#xA}wzA2bvlDV%z+gbE>v9XV3`B?%2Vsx+V=^M)I(LP%me zelGr!gl_zzG@u&uhWk>5ki=dbBmROlOjZ+~cu@T3Mza*g#CzJ-%Vcu{P zRR~G!!b##UNoc~!r2$2lH{28zLK0i>EAf{kbl}v|pc`(QlR{Xv;ihY%#BsyT5DTlq z&U>5`^Vk-%G$B0n#cZ*lFl@ukaZ=1P$9PAmO3fsu|<|?LU=q25(|pNHrxs)#XNS&*P0L>PlUvR zIWCGA{O+EZMbip6!X|GTQwm(^vgD}@C`}caNC^}^VlytG$A~m z5s3x;VjFIklVTqGWw$1T$1@_apkHjm?R8SjW54Xvgz$JqBo_3GZMXwYih1mpgPIT? z&xpi=ez6UA*hw*u{qmhAgvT=?v7ldU!yR=}%wxYC(}eJNMkE&Wi*2|QPKtT#my?#St_mTE9eGduB?%3A zzcipA^M-q%LP%meJ`{gRLN`7t4XDPv;eJseB(WEN6@N)WEB;m*P>OlOJyszku@Rq$ zza*g#pOyyHVcu}hR0v7z!sp^INoc|sr2$2lH{44VLK0i>mH0~%I`DOA&<*#-Ng=G- zaQ*+geAZ*t(CzIK#|`(XSXdQy-s7a0$F>-t3E`nH28soRVH<9clVTn_W3VQK$CDqi zpf+s74Run?V{;7Cgz$L&BNmj0ZMYFmih1mhk(v-5Pl3dO3b740+DS2wE%Lc0gvYZW zv7kt7!+q(bn8z*|qY2^hL`W>C6Weg(oD}oeDC0FDJe~`Q1*KveZlaT79(!eyCWOb+ zA+exZY{N})Qp{t!e5DED@rxu_xapcGdE9U_#DadY4L8$CF^~N+OB2FF zzswd3-;m@DH^)gakNq-N6T;&ekyy|#w&CVGDdw?X7HC3vJR=ed`o%WfA}7T>_RC^T z2#;q(VnM&yhFj{Sn8$uurU~Kkj7Ti#7u#?voD}oeFJEgycswH#3;M-2+)5|KJod{f zO$d)?L}Ed|*oIrzx$y*e@G2Av~TDl@{G_o17H#stvbU z6D5xuZi`sZFSg;nbyCb@ziicn@X#+i%<`|>Hr!4XI>3rd+DE&@ZzwuaIQ@%mr2!X~ z-;x9?)z)Ph;H{4|>g|KSFUC~5|Av~V{hy~?g8}6=?VjlbBo+gCHQy{URLTtl5 za8k@;i#*hX@OTy^78HqXxL=$U^VlW7YC?EC5fTgP#5UYxC&fHA$`efpkLN;SL8;h= zd*-B=$6k4^3E}Z{NGzxp+i)+P6!X|FuQVY%o)MK6-EeQ56!NMK*Z;rIXGHeaqdU%s z_$T|lai59>{bC#LGbhD7_R9cGl-JiC{W4H2d_$5q+#n~#Jod|AO$d)?L}Ed|*oGVG zq?pHk8Kw#0@r+0;=oi~?Bb*fT*e@eBAv~TDi3R;)8*a3dVjlbDb4>`3XGCH_zu1QR z(n&Fo{W3-q!s8i{SkN!F;l?>B=CNPKYeINDBN7Yx#WvhTC&fJW%Op(*k7q<;LBH6B zo8qLH$A0-r6T;&eQEAZ)H_b^Qui9|aHBs`o;bw>h{bCz#rjueG`(>6Ugol2aYnH!h z+i>$#=m0A+X&=oOzoF;kP?mYaEmt8Vu_;%Gza*h2zb*}^$-LpdQ6VI;BUg&QB%vW!l?D`K-f*i` z2uW>#XR=MQB4Ssr$Aysh1iBW?xdK<7CE5_;qfd;EGQD&aHpIU^VlWdYeIND z5fTgP#5UY%C&fHA${9@vkLN;SL8;h=JLjaB$6h(F3E}Z{NGzxp+i(}16!X|FKWajF zJR>SCy5TN6Ddbff?usT#Uh<@T`iUU1pkHjmU2{^*W4~P2gz(TWH^jm>BzeQ#bW+S? zzueM<@OVZf7W9j4xZ6&OdF+=vnh+k(h{S?^u?=_ENimQ8a!(V&;~9}y&@Z;(9ylrH zv0ol)LU=qQ5)1mpHry{xih1mpUo{~-o)L)!{bC#Lv6EsR`{juygvT=?v7ldU!##6S z%wxYi*M#tRMkE&Wi*2}>Mf@cR zt@u@GKq=-8H&um@#73MZ{*r_~oL(AGhk3)zP$49-3ulVIB%ujsl?D`H-f**32uWfg6!X|6>op-fo(PErbz&QCqmyDD8)cIwgvWCsv7l6J!)oD}oeFXuHOJf0DW1^r?h?xK@o9{c4-O$d)?M5RSH z++`<)ylTT;(L~8ho|I2#L}Ed|*oM32q?pHkxvmM}pPu+1haTRR~G!%Ln2wNodQ5r2%D`H{2r? zLK2(u7x9-Q^yIIl0X3O7+;1v`BzELu@s}htBzeOvaZ=1|E^veOW zbbGsP#2s`>2V9v-6X}p93|DzlzDw7`V!`F*cW2)@CC2gUj%Y$~xVocaVSBdb+%c!b zIF{#eO$ZLXaDA+PtO-!J#&2l-))x>Ca2#W zHL+amoXBepQ1;7Rmr*Dh=AN2RF*X42d#wS=mU-YZ3gyv}nou;h0v~y;0m`oV#bp%A zQzSK^Zfpwv=CuYW8|SghD3k|EYC`GQ9(?Mx1}J;ynae1YXG>~A_1GwU;k5=R+vlar zD3r%cYC-|oGJNf|1}Hn|jms#MCrYGS$A36|FypzN0;E~8L1%uzL=Vr*j`^I8LxEpyyu z6w0$KHKAy1W1jR{1C(8J%4HPF6D>8NZfs-z;I#%Q8|SpkD3s?~YC`GQ#ysn_1}J;y zoXaSbr(0@5_1MO|;I#%Q+vlRoD3oVhYC-|o#=PXU1}Hn|vdbuxCtYen4cW%L>a_+a zo9LR$D3s@2YC;*=#=POR1}OXJrpqXlr(R;xjro(;VraE7Z@Y{@xiRmk35{eM^JlL$ zK-oxlT}Gj3qwlN=htpUnL`o(1w%2O{jp^!aq%P5qmUTQ)k*~Wb8wFW2~>6yzYl&4;5LL=G6eBreQC>!ae%P5qmUTQ)k z*~WbBwFW2~>5a=Ml&4<*vz>a`YUqwevW@wv*BYQ~q|aPNp*;0c6B@}j=0LACK-oxx zTt=Zh^%9eA%pqQjq1DD5>M{c5#vG<5G?H!1;a+QivXMr(j6%^!qhadawlP0Msk1d9I5g@Uv7k`%#+>Vv7{@l9rwPHKOXrIPRhl>E0;j|{_UJ-Q z2o5c}NGvGPyfGI$CC0HqmuNz8=+C8M(T%yxYca9fn9E&8nB15v)WmYJ6D+SaK-n+f zxQs&4Fe}xBim{Ek%4-c!w#;gmQ7F%{)P$n3jk(rq4N!K?I+sx>Pqfs8y0MM9!D|gr zHqJ(uQ7F%~)P&Npjk(!t4N&&Z7MD>dPq);B>amTv)oTq zwlPn7tpUnLI^{A7<*ApN&`7p1fACrZl#O)SWfaO&FEyc&Y-67FS_71gbk1cI%2O{j zp^BjuYYcaIin73URBYauubdL&*srfOAvm<_8?m5V z^TzD|zu4iEeW`OVzV*Ae|Eb#_d%yK}e%c!A^;BY||l{5FEO6s8~>?d1DT9N{nNV4%dX>(4r&6f)dRebEH#Z z92<0$CIpB694!{zn4fzsCRQ8s3zrclH|CdWV!7A}me(4f?3b}Fqfj)=I5nYSY-5i1 zS_70VGr?sP%Cjsrp=fMlPV!mJ%Lh0DX zobI&-D0^py%P5qmTWUh}*v6dYwFW5LXST~IlxJLOLIK&voa?m)C_8AL%P5p5U1~xN z*~VPpwFW4gXrap}l;>S)LK)e{TN=Q0ZA zsh672NVYLIc&!1-M%w5y3gxMnn$SqLF*kdy0m??&;xY>5sh672NVYMzdaVJa0m??&=`srCsh672NVYL|d#wS=M%v>t3gxMnn$SqLG52|`0m??& z?=lMIsh5~^V;=Nc46QciA(s&-H|AkAp^!aB%P16$blgmD_v!vg&-dQ` zaNQ z(-{>)66^J>_)8M1^;~H{vF1&AUWJgvPQ4)hl7v3JSQ^l#c~1VQLP%nfUJ`#vLWy23 z4XDt(B(JCtlGvVC#b1)poYzVNdNYs6>nemKR^|=ymn78X&C-Cf%=__{3L%L-`IGod z5<2pBX+T5f>3Bzlki>HQS^Oml#dx`hjp?|X9L-(0{ z5Jh5>aDbEI>tmM;)P(-Yc!T7Fs1sX*gPj!f*eF9Zp?@;oQ28KA#fIQ8C&fJW%5Y8S zpNuy`K8R|u4LH(CF^}ysN)!4grXH_1sckNq-P6Z$9PO_2|xUu^1q z<)oO$ewnHX{gd&g$p_Idw(_PsDdw?XW@tkHWW1U3LG+6ayjf0)dF+?jn$SNPZ;pHr z{bJj0u9IRO`(>Uc^iRf{FCRp|*sNRNq?pHkS*Qv9lkpbG2hlIK=oULE=CNOvXhQ#F zyrty_b<8buQpl^O+;UCmpNzLcK8Sv?9rv}9VjlbD8%^k+jJMi8*sX2Dtx=%^tjMH& zv{wA`2P3U3KZXm-@5|P!5R!OR8^kYvFw(~IW30^9hTEh zA44_f4YyZ?ki=fxCw}>Zk@lA#Ln-DBcR+=Z#6~) ze$a&e$#|#bgD4E!aA%wp^Vk_@HKBhp-Z}XoYQr|%c_+m@Hpc}`=%0*tQ9g+BunqU4 zlVTqG` zn$SNP@0olM{bC#LxszfZ`{jiu^iRfnDIY|?*oJ%Mq?pHkd94Zklkwij2hlIK;rjot z_7h9_?QHjsXGHe4HEHSZE7E(yPc`8_b$Yz%Cziy5ez6TVz)A7-v0nyiLU{a z7Ts{4J1OK<8}18Dl)U6g`Sc&$i3R;)8*Yq~VjlZttR{qqGw2Cs>E5>CCaTZ@R%Fs^ zVUqX_MMu7}$)y1omfx36Q6VJps=g9`Ny0TvEe)*9)`pv=LP%m?P8WYk!ioBf(txte z8*ZiwA&E^nOZ+7XXX&#`18OpFxH&3>BzELn@s}i=qR%T0D9F6w=Bp5r*p3UtUy|_m za0^QVsxfc4MJj|O_Tpmkmn5{}lG1=u%o}d03L%M&xJ>*d34OS{G@uUihFhURNMaX$ zE&h^(Cj6!}pa}DZTd6`wVhgSke@Q|It}YF_;np}QgjE}EttLub@}zv1uIt3Ys<87O zC&fIr#Rg3X4}GywEGP`yaGRVI^Vk`iH6c8-#ul-lHf+Ov>!g^+=GdwU;h{UWi3R0h z8*aOkVjlZrhbDxF2H7bVRETZ3T~3O5Y?0lX5FUDDk62J7w&C_VDdw?D_Gvvtv0r}Hgz)$iL}Ed|*oM33q?pHkxvvS~@#lz2i*C4wP6~O|hI^!mlE)4Ai&)Sv zw&8wtQp{t&{H6)vpGZ&V0L?92ZDTRzpX%jjN`(3YQ;29#yqaG$9VlGv03#9xxolLJcw zYBF!QK`MkKcI063mn1agkkWvH%o}c~3L%N@I86K{3EeonG@u&uh8v+mNMbLJ6n{xV zD~>7+D8;3&)7RB%uk%mIf4I-f-ho2uWw>q z%ww;7tqI}rbVw|y7Ta(uofPxfE~_*lJf0Di7Ts`boD}k^4YyVkC660!omkK>w&B)0 zDdw?XHfTb4=$DOR;Tw{?;Wjxb=CNNkYeINDBN7Yx#WvixPKtT#m#vx*9?yuxf_||L zx7|rGkNvVk6T;&ekyy|#w&8X;Ddw?Xc56a-JR=ed`o%WfUMIyo_RBs^2#;q(VnM&y zhCAS-n8$uOs0rcmj7Ti#7u#@$ofPxfFW+fGcswH#3;M-2+)*dRJod{mO$d)?M5RSH z+zBUzylTUp)I`bShC3w|^own{@0}F$*e^e5LU`zxvu640whebqg$}SHllIYh@f(Vc z6z#SrV1g69eGRqB?%4rQ)xg!<_&jSg^| zl?D`H-f)jq2uWok%kn7|5k62J1 zw&4ajDdw?125UliJOvU9D#SM2P$$Jaw#YC|2#;q$VnLDEh8y9en8z*|sR`lnL`W>C z6Weg3ofPxfD4%OWcsv&p3rfW{+?P&@dF+)jnh+jOhs1(vu?;uQNimP@GF}tH;~7zD z(G54zNg=P=aFaAq^0?t9iv|5+8*Yk|VjlbDD@_Ow{W4W7d_$5q+%zY}Jod|UO$d)? zL}Ed|*oK?wq?pHknWYKg@r+0;=oi~?bDR|O*e`Q6Av~TDi3R;)8*aXnVjlZtfhL5< zGa|8|Uu?rIa#GA=zbw{-@OVZf7W9j4xTQ{tdF+>Enh+k(h{S?^u?@GvNimQ8^0g*} z$1@_apkHjmt#ne%W52A@gz$JqR9bYyt#MMwt2W$PO_V%txOHMdzu1Ob@1&T=e%YW2 z;h|qPo8@1%ZMZEebbu9^w2!_OzoF+CH|6xw%lDBP?mYa?NK2lu_^b8za*h2_mu|JWZrQ5RR~G!$OGapNodG} zr2z$*H{2l=LK55Yu=q<7y79ZxfNIPe?uZH@iM@DK{3Qvkc&s#_6!V5Vu0lv+Bc2d{ zNkSiF3E`nHE{O$&VH@tUlVTn_EkLN;SL8;h=`^8BykG=A%CWOb+A+exZY{NZv zQp{t!Jkf;kct%uObi+M!Qpl?|+;dHoJZ`ubVnM&yhI{Fxn8$v3r3vAoUtWuaZ%Fcn zd*h^-$A0Pmf8;YFdu!DlXGHuH&WOZBih1mp z!I}^r&xpi=ez6TV)JZXq{W44w!s8i{SkN!F;YK(q=CNN!YC?ECBN7Yx#Wvh%C&fJW z%jcR99?yuxf_||L_ob6!9{XjCCWOZ`BC()fY{QLnQp{t&jMs$lct%uObi++_Qpl?| z+$2quJZ`wjVnM&yhMVG~n8$wkN)y6Ezf3pFzi!)bGgRmRD>7*x%@n_(=t$u%U1yaB zTv&czHd}>|#H*Sk{*r`inp+xJnXL^sPlb@gzML=ql7x3-3rYjZGH5R%x4Ys6oY(1&YF1L`nuxOFOoBzEC?@s}ht;fB(HBFr0Z zqY5F3Ex1YiB?%q4xisj8+v21UR&BU%HBsWY;kJr}Rbl5nPKtSKi|v{a9{OU3SWpz=3|||Y1?q0s?Y&e zWYRwRO#FtTBZa$k9Z(u@VflU8Kovp~uWFF^OA@YWaA{y=wl>@l6+#mGa;W%A654WD zX+T-#4L4kcki@1OA^wtto*Y>kP?LGXjZz^bu_H%|za*g{KQ9d^$h_gcP$49-9lsQR zNkTV{DGjK`yy3>G5R%x72`Hxso9=73@ zI4S0_KbC4jcsvCX3o67m+;S(yJhsRRO$d)?L1ICX*oOPYNimOIvQiVm9wCIN0 z;-rvQZMbhWQS!Lqwu%M)VjFIolVTqGWxFPXhkn^17QP|L8*ZnQVjlZtmnMYAGa|8| zUu?teaZ=1;~9}y z&@Z;(jyNgiv0sjALU=qQ5)1mpHr#P1#XR=Q2~7x(XGCH_zu1O5<)oO$e)(P#!s8i{ zSkN!F;Z8d#=CNPSXhL{ABPuPr;m$cJH{1oWpkHjmU35~+W54{U3E`n% zu9)R-+cw-)6*|C*Oxj1+#BV4%Qn*Xk>!kq~mfx4%P$4Aos&0zEB;lHFl?GO3Ys3Ad zLP%m?-WGpJLR;P`4JgaJ;eJ*jB(W*)ioYbGC-0R8)MVap_f-funjld zNimPjF+vl<bPKtT#l_{DK9#4nFf@-l1 zH`PfokL@x|6T;&eQEAZ)H^WIGui9`kHBs`o;bw^i{bCz#wv%EW`(=(Mgol2aD;B;X z$s2B-lVTqGWxgha$1@_apkHjmEp$@MW4|oYgz$JqBo_3GZMY>)ih1mprJ4{P&xpi= zez6U=+(|Ky{jx$6!s8i{SkN!F;l6QF%wxZ-)P(SOMkE&Wi*2~oPKtT#mo=IY9?yux zf_||Lx6Vm1kNvV<6T;&ekyy|#w&6B9Ddw?XHfch5JR>SCy5Y7sDdbff?psZiJZ`wH zVnM&yhTG<(n8$wEt_k6xUv`=0-?VMG-70i|6`8b;_K4q5bfj>Xu6s)ZE-b$<+owWE z;#KVze@VhM9ViW~%+`iGs6t3$Umg;FNkUs5E)6Klyy3o6AtbRWkBGk{p(l@)2GnHU zaK}^#N$kku;x9>P$P=Xj1(`S8Nfkm8+wqk6OA@;A`_h1F%p2|p6+#kw@wE6$5?b+0 zX+SCF4R=&33Ony{Qp{sp+|-2d&=N`VMD}h$H{7RA3VGFr`%Duhj~i})SkN!F z;RZS>=CNM}X+n7Dm%(D;8L#wmK!ou{O79LU5?f z?P5V~=Eb+eDKU<%xl95i_X5?UWa?=lKS z!yHf(D#ixjL9aDH*)oS*Mxi`9QWJ{CR^WGDYk;zAj<}3Md5WYa)QwHSV_s{3vT=^P zj6!*!q$ZS(?ZJ~?Yk;zMPPvRidA6h`RF93qAH3E8W&50V8HMtgNlhpqTZU)7)&OM( zopTw5^2A9^s3Dt&7rfR0WfNU=8HMujNlhpt+lZIE)&ON6U3M9T@*GM`Iux&ZErwQ8 z@tVsBlwgO=u(=lrOy20A(Y+bQy*6&`M2c zBwLlQz19F_BfW7Mh4SR;clqQB`$(tdr(TPp)wul3WdzE3IY3QlB-@t*z19F_BMovH zg`$y$!qly8V-9mlCt{IGyKT58z@sPSyL25P7F=R}7dX->F^<$bHq zKX*!uW7mG63BjRhzZ46KHgC)^PKj}B*|C}s96ENKSWvNfV~%%9jAOq}(1hU7t`o(A za?Klal2c+Fn{~1#1czRoA{NwY-k4uGCC0H+r)olQXw+$9L80c2Io&BSj%_+a6M{pR z&J+u(G;hpVPKj~s(b<|199ndaSWu#QW6pI-jAMh&(}dvApYz3{8*_ozVqrKlv zxiJ^1iREG^SYB&@vR{_Cj6%^cOVxymv5mRRYYkAg%yO4eD9^Iggrc#H`L)*?pzNA& zTt=Zh(NYuY#x~|EuQfo~IICSop*+`86H3Q6=31{cK-oL%Tt=Zh-BJ^($2R5$uQfo~ zJ{w&|p*-VK6AH*S=4P)oK-ocCTt=Zh=~5GF$TsFyuQfo~MB7|Op*-(W6UxXo<_@nl zK-ot-T}Gii^%9eA%-vp#q1DFR<1zx}#@wqWG?H!1eO_yTvXSqD3qsOYCMuTM20IJE0Cv7lV@#(eIS7{_LPp$WmES6_++wVF5PE2qRbcIsF#|J3b|z2Ew~zmreJHvLo+&XXQ)`V~rIL6zo>Ilw9L)v-qh zYC>>m(LrKCiRO(t*eNlN4LU>9HAzbi=AM3tpUn@ z8RaqxMZ=6%6Dr0w=I35(fU;%2a2bX2EK5x&8rzs-yw(6^*Nk-;h4Ms8O{g2&nB%?H z0A=G$a2bX2TuV(T9ov|byw(6^?@V?Xh4OSuO{gB*m|uCV0m}B7>M{!D8JC(+K(;Zb zd#wS=4w~UI3gt$t?J^4Gd6$|{Mz%5MdaVJ+< z@LCM5Hs(T?5hyq2A~m6rY-29=S_71gw8Ui;ibh(hCcf#(8*`c08lY^X%Sa6B?UEoot#5i8xF--^#S9e@2tlQSc zJmHiW$F4o83BjRhPl*LZn>Xh7PKj}B*&j3^ICSi3v7ln}#ysPc7{`7+s|mrOUC)UH z<(fCKtwWfY2rd7vg#jBU(^UTc7|WgfYVLV1>@CKQcr%wN6M0A<(w z<}wQ9iI$pBH?}dKc&!1-#(C;83gx+$nov5nF`s*_0m|Na;W7&4>6V&MJ+?7ld94A; z_Id3x3gsD>novNtG5i0OopRZ&v|Hz6u1fs)-~WengZtEF6p9x5OiidE+n58q)^Me4 zqJb`>P@Z?G31ws(bFkMMpzNa|E~8MMdWlIl<}k0t&}w52cNu|lV~$W08p$^1NUt?O z*+`>YMxkh=(Q4wGp1d(X_gVv#jr4`fD3qsOYCA}1}Gb8vdbuxr(SA8BiY9M%4-c!Hqum=Q7BKn)PzQ| zjXB+G4N$%-n&C1EMI+5r6B@}j<}9x@K-oyMT}Gii^->cW$u{O(uQfo~Nb_7qp*-~x zlWxofUW=jC#$4z!0_DbBq$V_yZOp}9Yk;zmmbi>U(MYTQ>is_NfAT?}*8fR2r}P&z ztp&Ea_$Wv{@jv|SO&LmoHFe;v`V*#Tm#!PK)GK}d*8i;;8|C8_rT+XyBoQ{1_ROH3 zDO^Le1c#6yN)(XHO9F8|Y&y zbYxVSL^&>ga?FuQCurzbT}r-1os^Gvyir%E>|SUM7yL-$1*P;6&-G6@fPd#wW zHk(zzHNPXDsLG^kz9fELvpMoLUlv2BYc46Y&#dj*NOrLux9L z@;CQ05juhxNu1}Uo0zO;%F9YlHAPH5^LeETIPLA1LkaX+{1qvG+KhT5hEA`cR+;kC z_5T+|C3gR$!)vH?f2!^duc6XCfbLeA;G(KRFxw{<&YDUVq=`6Z?O0U(9a-r*zcYA47-FkRHZYoznS{ zcz=E{Q#;u4bmVu7(>m(^+=Jm4V|u4_hX;e=o|Ww%{Ju}O?tQv_lB(tXZs`xj+w<9- z4R|Zn(b$bHrHQ>4eUxl^1EN09l^Y^6Otdmp&(>-=!Gbv9Iwr|qkzpCvt_?HxY@ zAChwOW7^RcsK09V9&u-9$3OR=_-WFE+STzhv^}Vt$Pa379q6r>_}1_8x6;1OhVU`D z&ypU~{*IraeoSQ|Kc)k10bb!-zw4gAdIvi@{<#OmPm>j$XYVaU5pB}`;_ADPn;mr@? za<=yE^GSL~mfjWNjgL*wD_#S?c)O>;gud!BnOnFr^qQLR2FH$tuY0Wl%J(%lTt=aI zH*@b_eDMB)R@4x$Tzd!crQM{44-=;Zgdoo??1D|@!6Y|wQtZg3}GryI4RDL+X zWq%_5Qg~~~hqkYOt;IeceQbn0%zjfLU?7tykHueeT8?}rPb$N|{kX^98!7)3&QldS zlbA`QXX39&*^x=lD?^XIeGQb${e^tIGY5%;d0DzEN=wg>SC#zn`~UFqN4<@cfAHqD zmpY^BT%x^knFMo`91Rcz7;Z`B7W+W&crH}fS+li;+ZGo22_?m)wq22GSDfV zaaAhe25F+gnJ420SC*cwzesrdt+)T_?biRgz5Vtd(^6Np8`bVv9a^b9KKQVX{&g0I ziC887HjBe6@qNCk?YM4)2%WDGk#v0{OLuj3Ej?e`s7mhfhj-uWjry=3(-`fw&a66^ zaG$$OMT9Fu$CxP<=%{Cv-C7Xx~cP4szfxtdOArq8d9_T{gxKHokTbdrNdAo=td7Iw(ikD_+x$FZn3 z_wJRxL8^z5Z!U{FsKKKs)9FDhX;0RVq4MU3u&lE7slOjC4R}Wrn zukvlz+74=mC)}sg6TYrJX>{@CCwzTvZ9ObLfc&!C(540WI+@@beX2&om%*EATkGpU zaDK&YZqovAolM{@K2?L^%iwQon|)!4&M&sD9n=6`rW1Z!d$N82l{Y_x?X@+3%kUB8 z*V&GCF?aw)Ht~11M{u|;SM%x2^zUk8>l>(|=kL)Y?P5SL zvWb4QEmza&%=BZm(Y|{se*Q*1-boG~f#lO;IME?nKZ@F&AIHhsoWG5#hmpTqPjyg( zM^UEJgZREZSwDu#n;*iN%F3cl527~PT_Js_OV_i7v-Qm_K74VzbUjzN@SNA54Ik*z z^?c!~o|D>FeW**<3x$)9yf*S9=|>yP*DI}Td(6H1mTy`wcal3inQi&>Y+mV*wTGbY z{Cr-m&8_F8dKCF(b*)_t9z&5$kKlS+uIAI3={IU)>$$Gz`DJypT@2_&Hqmdjr&o8Uno#fyVNIpG=I~}t1qp02aar|7H^EXKKF!IalZU;4Z6lFR+h^qb0+CC=HySB`El&o1_Am3HN{_yOY<&g)Slq`4IHfbMjwRkejgSXV<_#(=y~)d8 z!NE=md59(65RDYPmM8OumX;p4KKlv|b5abnTmlZ)NC`}y3>;BddJyFi41Cl>C*A`63H7@g(`}FBkbm_X*ne0?K9XGfBmky-Yc|9L2rxR!B>%HE+ zb!7ej6ZU3*R~1X2C;TT|dezMXICZ~W-N{4gW#)Mc>q=h#;V%3<@$2 zf+#b{EFcIn${>R>h)gQ;Ad@n7tjLI!F=amIQ)PYXiQjkqGGoWijFo$_Hyk=sd}EHk z@!Ff6yh@~howLaWX|AuB5bUXy%q%9qlU?@Nrk4zj3~~eyzFsHg!z=jiA)R?6T`Rgk2Y4ASPR0$ zelkp+SW@A{P8v}>F?rcjmIx;%iPM>Q171ja!SK_uGbTjSvTt9;U{*hCB2Nl6IH$8& z(iB+o!?ofU6Dim+1$O5&k?l}}cIUIC-yrxj73&e#j0+}Guwx4BE@~p%p$6?PWl8@* zoyiS9nEq7<$jmMr#DLdtN}sJ71v>q%1aW2L%U#y$uqv|pN>&dY*l&0zt$_HU{#6$% zBrcOMooklLGa?;M>Ux$9@28HtZJ6x-7n@GWqDX_bv ziEM`&wEH7Vh7VvnJkGjnA_Y69!0w(VvK?yB?tYf^f1~xo73+Zw6%1Pr93L7cTP78H z{+UGs{*lTbmy*BK-wSSu0INq*oqZsVCQoy?Z@<4Mm-K|-GaV`T5Clfgl|DN)3bcCr ze@iX#Kl;lX=~3dZSoADu(#4Gb-@T3z#1#t13CdqK+o zCeIkYE2Q{u8bHebAkRq03Mu}B29WZ<=`zxBLfWVKw_nWzDe;WQ3+anV3NH_S=c&pj zBB~v_N zk<_Nwt9i^O)J~LIe8FI}1??oM#aFDk5sR-oS!(emYi`P7?G&lS*Q~igi?vfp3r{DF z7}%~W_&n4!8;ah6l7kZX)G+iWX;t`6nJz`t&f-EnLkGxD-Spy>kO8-uN-w?WdA3k5+NRnCD`pOt&OVe!iu|{F4roy+FtY z4u4%Ns3n`d%9=n6@C8?lVj_O)50q zpGD2f&8ApQ2W+fh+Ja#Ey>*QT&&=lNw7U?sq9NSG(MJP&5KRGSW3rjs9@W2;CjL^*)*xp^T#Y|UTgY%2iN|e zY^dPba^QK=FxfMy(DPIlH7_-J;>v&8h6IE0>o!&}Z9y=-VVG>1RA_oL zi<%dkP4PW*%fLeocC)V$nmitn4p zHdZigK`?z{m~5I?I#>0KKu zn6@C8jx|g+O)4}UmqpFX&8ApQ<87>9+Ja#Eo?)_SQlaVlS=7ATWQzUL2R2mjY&r0p zV3_QgROtC(7U3&RrdUfKxmdw9lVCg1QrVYuXgn#)nirdVv6Lp;P{Fq4z;%jYvT0JG z=f_#pyw-ivF$b>wpV&~rv*o~Zs$sHcQlaOxENWhA^2C+@QyVIHwj6j)H%#_SD)gL@ zMa@f1p4czVw4s7$%Yo-C!(`8-LeJS*gfBCh;!ZQi#R{&O1lzfm%D$vS<9S)uywv22 z@6`D=RIqJ1a9v=SY?@T)xd=sr2Q>#@{hAkBoiKgwqu$uUV7=IJXs(oK|AiDbuRGi0 z+viIkE!wv**e`LMv`7SHnzg7yH`s3pv+!fdPXwklf z!G68tqx*IO(61 zXunemo5J7&C9J<)K3cSIVX*(sane31(SElSHig0VSbuwbv}oVLV87RK(mpBCexDRJ zg+caMe*1l}=-#s6e!y|kJt@)sdnv@4AbYI7gF&?DpJ^DtAy3K?kQRqxeN?}tJZ|* zXs?uL|GN}6Rl)Z7#=GpJMf(;8`zwx<_DPBMSEaBi3%191-ZdXB+P5&+Uw53ePfE1E zA%$2I?2qrgn?blZfQ-WkZh2A;fwVY=+fv#T1`h$>0e5_~ID!_20sP@O>7SHne^&~d zMTw8OaNoV>qec4`2K)PtllDo8_79}6DGav9ci%%FE!wv**#GG`X`hs6|Cbatg~10< zxbZ&n(V~3|gZ*R2N&BQk`zKO}MZx~K^F9s2#Q|g-M)1s&atNfwF+7*jrZ9L2xB|S@ zGo1|LZE1=YN6^ABfRT=q{_Ta}oKOmz!r+53tiMq{TC{Iruz$yK(mpA1_M@e+DGav9 z`Wxe;Mf(;8`*$5D?UNGi$4X&S7-Wy-H_iu(?kx-M;~gj6lM>zElR~Tsvd8LsKZq9n zGYtdyz>{(Wq{SgjkkY0sXarb%ANpW%04)ptA309iCndU1l)|Pe=%@#GpGiJgbZ=R3 zpX@m4o|Nc5MGBjuAa~q*KK8+)d&`3RCytZuNr~=LrLZXqa>u@JnhzG;TNd0ub)0lh zN_3wtg;)?|kGtNCAX@a#Gz?&-C*=r8i$jsA4K{ zu>HcIWZbIIdMS%K8tV>ez08Jc)&d9XoH+1PK;0kWm% zrY!?*8p;;78PI>N^wNp`iRu<9pi>%r+icZ=q7yRUv`y)y zQ?K+;-}yWC^{hnPJ5JII?*qh?Ue%Rs&HT1rvpVNWWZ^^(n}}$8M6aYK=%)L|M&qh( zD*N&J@>mnfkJguGSu*I2o>I{ho_CVL4jJs|*8Q!Hwr?BsMlTuc1xFS#*jomB!!d;n z_L0Fp-MWvG!53xlML3F(!Ixz4C3sv(249xJm%DWzBZIHV;45&%AcL>U;H&UJk_^JX zGHYl3MrQ})Xq*b`Bte$OtFTH_2juBJ6;_GrfK0uw!YWlAkgE?=SS70ivNb`4Rk}JL zUmvQlN>~SE>?0LcDeHioO;ll(v<}GHBpL3dvepZ-Hd%#L)_OtKrl_#WS}(}j$1*JL zy*^QYr}xLp;$E+P?FR8z&`*^}er+KRI6Tjj!UNnb&kP+1-iv~PW^ks`CnHv%(<~|A zKBl?lnXLmwCthUcD7|!|C1$P^@Cws7&C`LR6E83Gm0mj0;<7*r zODAeu7D<7;<@sC(icZ|JELM8yL=DRqQXp@6zSM!D6E`bMlwLYftFlxIq7yeLtCU_kQG2pl3gj)%8XYJ)aclCG(n}|5Ox8+)yyaP^ z14SopO4cjAbfT7IgB0jno{c6{G;42pHfciI@h#70CE=w4Z+X5pp|T&Z7F#r-{Aj({ zswA{vq+cS~W;zRQBVQ<6BKAKUzC>Dv7$~*=0gyKVCn+ z(}eP)6=b)Ps9T;rCRFz0Rb;Owlpn1l`;Nz^URK@%$b z@rrUt6UvX)l*3A*Zh4NFP}z^yl^-;r{Agu4swC=`=a>nV{djdbt_kHw>&po#(YHK5 zno!ZNz2*5y6Vi`wc}^+`tuN`8=adPR{dj#jtqJ8v>&qD>;f4fnd44vbvLCN6XEmYx zXni@KB?I`DhgvcCS70(oeQ63pTY6CjsVhxEXi6{1Aa(L72#x%&GDv-V3PKzIn+#GH zpMucD|1N{n!>1s$@RwzfI`|ZX2L6f+QvaTU(7s=lLF(R95SsUEGRU_)DcaofTvuV8 zB*@YY6;^3#Zh3C1uu4>O%X3SGRjQg>p4%#{lGWVu+)-hbuI85K4;5AkYi@b&s<28~ zbIWs2g;mm;Tb}ze%(px#Yt1ds0~JM>Mb$_ZP++#F13C~QVY{yH$b4@5aS_0ncg?DB&23`UhyOAbRw&NAx zZA~aUS^-8WiM%m+$3)6@++d8>gtDUsV~mo>yOVcKq-@9i#aK-!JL)gSDT%yA8E+zG zJ8m!D(}c34_Tqgdk@qPdm`K@L85DyF>F zEHI2VrPby$EmHS03vH}o$}7$y!)Q}lb3WH1byKt0#ww<~?tEbwZAvT8ms+ImY?jzq z#gtc{rH0X_wEis9B6WMS+{P-Vyauf>j5eiJXr&gZdz@7^Rx#z3XtiOqDXm3ov`F3P zd}U)5Q(lkO8b+JainLCN^xe*S8!MZ(_d6R5qfGgZXQLL;ibUTaWMdUmUXeB%Mw`-# z^tBdo(}VXtTWqXi$}7@V!)Q}JTS=mUzKz^rB7vi%pf&qe6UndD01sdEqa?i2H+|hM z6DiwqQoqxLvZIvlRuax=W4Fgd%66R2y_!&Vl+1lfBHPIQCQ`QJrTu^=lpQVX-z$l1 zBM+KL*^U?WLz+-_w4@(a64^!`F_E$zFXumKLfO$`epE?h8+pt`%67bvAJ>GkqhRb_9WUEwHKFWi z(f&nAbQ^ij#>$Ru8+qO^%9Gp33tGgB3$~FLZLDI->&qp>Xj58Ye$^scVp1FVn~haW zd6oIyFxr&Xnaf(F+Q=(5Rx#zZ=Bi<|DXliwv`Dp)*KMp~$}7$d!)Q}lb8c#pY9nvi zSjCjro!f@drnK_h(IVAG{$XPkQ(k@U8b+Ja`g2cWmtnLitwoQtNVSoVZLDI->(LX#Xj58|o+^=UBcIt=*|cpVpBqM*avS+p zZ#>1K7N{4kNU4n+X=4>rUXk85j5eheX_OXm(}Qi~J2qA^L)lUXTKT3 zhe5PH1bzuV@}wIAy$}5NH#b?xeDXoe@OqL*UJ1rYGGHXiJ&pq_VA@9YpIx;H_nj zC*2TegPH53velgzMC(J~jb^?l-4JNIS>U9y{rxP6)`!5`&O%SRA<*Wt$Vqie{CO0w zkD_gj7YD2x2e-&ycrh=M*d~7&#k&{?uaipx)(?bM%B5aROJ!=Emqqa|2Ewc5@__XN zq4jcw7pr!9WfbpXAiQR-3Rpi7S~XXDv1+l`MDZ>L!Yk)j0qX}sYv)=oR&DpXDBi_D zc>P=-uzn!4f^P6))rxP7;#~}cSJ6!Y>jy&X=w>fg?fKVHyo-VGTDm1*{Xl3n-Ri}v zW#1OXyBG+ssNV#v9|*0f+r3z|@jIe;7X#sS_1l2;1EH05rxWYeepeK)52S7JzYAD5 z5N`E%doiu7somcb#k&{?udI6m)(?bM)_q>gO(@<1?2qDI41`zK0|Dy?LM!W`Bp%v1 zVrZwl891!|9yn(Ln&u-?oxCUxBzy^x2=h+X^x8+&-%BQ(;A2uPOem$tMVNEhn4D05 zFPU)iew1oqLh1TRgk{TqQvJPT!duQMsTL-*$($Bp*_5AAe=nKvcJi}S3lrKv&Wf;X zyMIxCFPZRGaZaj*32hGNMOZf07u4TNCcF(?lxkr@3;!h%maX%z>hC2JUgCd~YGFc) z`tKqvo8!ys?ryRDXfeJa!n(n|sUszywyC|P z^umc7+1paUZ+vWF@90R;ir@QxD800zcmG`}ptpZ&Qt#!6|WNSD!sI#bz-a(sFrS=jufqUtr)NL(u!7#_k=(Z+b0EA{>6OASclg2wb#dh6XBJ+kFC8adCQ{<7v_uF8^Fm0aGcu+gQw~T3>hlc({FTu^On9cDh(ww;J;nz$&?i6v?B|Ku@iQ%-|9fY zi5PI&sr1>YQJ~YVEcjRF&;gyDXWXN=zubil=m#!Q0o_m+~zs6*p}QZ}reF@9apAr~teGYQ6r zEhUXnhsH;;?6qOk2Xx?kf6$SFCqZC%ROz!@qd=<@B!ISK=-bwH7Rii+w3rax0Tupa7X|Yn*yQt;q*O2MAs{{EZ zElOSfZDR$;76i*XhRL2ug{FT9QD*fGarl>A@){|1jl zrS~ru_PbHIoZ-yFJjMpB8VIRz9OIPue>OKn!-jLOi7UzYf}%Vcbrl%Ud+`<2m@A9Xe04vS`;%#hI@?*+IeHZJ{X+3U+V{ee9rMAGgpa4hnX23r%&F>y%L#eK z>}U?%U@@HS6|`LTBE=l9=#>^!xW~q8%=L=iN%0CP=6OXQRNye0am@FM7g2%3XcP;) z;w4nzFdD^YUhy(2a2SnZp;x@pDAF(*#UihGwNa#DG>Xr?0>0(|BxxLtWN{$Dtfql9 zk|k2oF@j%Q*jaJ0T^fWd#gQ)n)v?U8vOGwO^|9PbX({Qc?f|d?mC1^LOzTNcbu-|} zl>wO+m7eOpz>}*2GOa8<)h&W2R|h06FYwB{r9#bfO+exr0~JvxzY0iPXrNH)ZRbqWf+?zui7UrlRi7vzS3gf|4Ps9m5NBNVF$-YE6)Zhvv$us8aR zc&%S2e46sw-}$5(o8%oXMsFRiX-~r2=37hkunzc^*(qgj{wEt_L%hqyipETW@pqPz z#;8N%JyJIO-?Wur$GX>s$d;ScJYV9#b)R9RX`@2V{YI1)2cO1#*#nkPH?Pq^4oc!* zgZif}67MAs*-&v_#KF7{8%EBnQQ^Ff7*T0n`LaJ)qA;&a923OAzWv${HgJ7E?t?Tp zm)y+4>`pjN%#V~f!ykq4wKt)i=R(Ey^rs+N@)tA=;G`$T2w00lI3=Y2>N{xo&>@4< zYl|NzoerXhgCz6|cIAy5}iuFS)slr*dCXxQunuIZXOO@&{48^kVfB7l1T93|N^c zR%5CjwPJX7!!$OJT`V4fAi@5LrCM*+q485G* zyc!k0h~tf@G_QQw_bgGES0+9XL~c%cynv0(1RpGwN@n3z`_OS>ezLLoNC>&zz_VLy zY$gWLlE0u~0Fyi^M!;H3@?;_9b_0iijm?xGS{j0&VF(|4QVfB$ID}86G71K{hs@N-1n^rm>kGgo|UyIE-P2C*>GOi+PwSrKYi&Wn)G6+}O-E zjPz|An>kVhqtT7cTpukOw=m3lp5vr>QsSKF3t{d};HAf@y7ZpE*w0%f@D* z5auoe>p%VW%A!zE8icw8jN|i&7DLH;OvYj%&usuVHedKCjl(oHy+&jh2Jxli#0W@< z_Dh_wu;QxAFZEQs>MClPr=rHjOl7&GxYJ0l7A{vSqIl`WGL6m3fR%}2J51G@Rt(RT zo5toV7mG(ANO+ajTB`MC9U8BbGHy?(v03k8MPnwxc!Q;+ac*ojNtteJHro){n#Km^ zk&jlsHjFfF8=Eag6qcj9>{d%erKpH+Btd-vH8$IAs5r0OPwX&^oL8g57x7yoD$Ofj zcBdr@^UB0`g2>GYH8#6_uv99Ug<9F;I59uj*z6TTZZ~pcvoDC2`~?jI*zZX(0@h-Z z4+tr@8@aLhK8TivAZQrEK~IVyuoj1KNJ?{O!i~-0AY2?n#$gOcJSoQ@8=D`bl)8xUsq5qcjfF*!0$o%|*wF5y-~ok`oqI+&ngzl>E+;FjY1cHP#-n3Nf%{nx` zC1u>6P-Ao3#frvEg7F zMp`kkv3WlT7srrs7{dpilw%+*=3#=An#Sfs8!Ni!#^xi#NZ+=xnJ7i6<4E(y#%7X_ z7L8jNWLvay*egt^N|3Bbl?S|}(DLR|vJ z@o7Yhp=3QKW4e&%Hh>$O89qwmFpW(g-Pp`@oEU*@Y-TxOVa3g3gE`LjRJ`gcYL2I( z#>Px#uB5orNUs(ySM#EH>BTaQ&HR9siDEl^r52KSI6Pwm|59++0Q&qAkC+$vAdP{a zUBqoevyjQp9Y_8`iSCP?FnFN^1Q~+Mf8i}!wdN3&yWi^ufC*)g`&WBT#z7~AGC{eX6iZ5P;UZw?#&W+(k~`}7#@ zjv&mHBb(!9X%IM6&bOWvrNdgRot<7o@rC{RjOsy*1$hT1eDBA1!4#!@%u#oX9UJF}(+zu#jDK`R_dy=T=b%Jr!qGQHMMg z=T%Wh1O>huRGd~to$yqgRz>~j zsW`2QIw>f4YO{T8tQYPir+k#sst!1?RcK*I>uJY{w2}>`^^6l1(wfHxm;c#Qaat91 zuBGss4Rn8Z-Us6Xk}M46g5%nmwo07oMJEhr+Cpj3yX2{8riS{}Q&9mK>NihC1!Snp znxYnkj*+hTU?r=$y}9Z*oz+H(S-s|j<*eq*U-wiotC_mtsbW?$b<#I)XZ!jx9q-=BYTXiki_3dm3kG({~6^>?57U?r=$y;I+X5vzn2f;lnz^A?QHVW!h4djwA5`5xcFVExvv8*eqU;C zOTfkNOwDZ*T<%b~zx&2VOBv2E>?7M9C-O^5Oz#dSEM!+*{##GQxmDCoPsN#4)GklO zc~#VILFEpG`@20pT1sn%A+38IC(=qvOzS=;ETmOke!r*Uv?}U=r{c6K>U&ScX;suA zLFI0U`@6$FN@+Fy9c=otzdPbMkycV-T7PiDLR!`3k9sOjtD;V{R3G2p{pf>n0ZA4L z=qJauGi{YP)00jZ&a{QnqIb$u(M%0>+EY;h8S0Fuq5?A1Sxr%kLjBz@K3K_WZg0*x zPG_}IVph*PVL7Y$@)tZ+%xb1Cda9V!OkMI+F{_#SO;GTD)&1S?KFC=${aqj3-(7Z~ zNGsW3TCX@^N~`Vf%=NE&4D)LHJA+;G7$(;CcLuxeG0d#(?+kXsV_|=1u$vwW`#Xc( z@>tm48SJ*l!v4-+e+W!;CEVZL4Z>VGy1(mV`n!9c6s5yfSUdN3wTImDqIIoI&TTr<};r?!vkCxJ!VMyycjuUAmC8l+>6Bg2{EzYM^j7xdtg01Uc84=$6S=wi4ZTpq=_oMc0Y zmlhX*a#|6vvYuFt1+_8|m)^Aurj>D3L>At+np_=`g?Fwd*FPv$AN zTAcDWFO8?%VyU>k3Ak{|hT9%+VPzR^N5F-3Ww@P&quqkG-CaSnmg2nEeCJ7%;zo-p z-tDE86laS)0as3O=Jp0$ImMaV7jWeiXYPRH^1j*Q1^k@*`yk3Gw%e|Gq~@SUWsc>x zd&o;uj@`CvJPrpSCfRMf20Rjg@wRKg9|ADmb`5wm0OM`ffX4zb-gXUmJOJZu*MKJi zFy3|z_>%<12Ep6z$tcd{WVYS>EK^#tP6e#2C$_^k?dd>Vde<_TY|cbv;eD&gpChvH z&ei1Eh%CH!HF-{wd2`}z_k0khblYtg7G8Oud%=@3*`&o>U-Z&as+Gm1fGZ?galdCy zK5;?Y?&Tm_s4z*xwtK~sdCIL8r+n2*<0-dTDz0k*7f#u5*8?uBEW_OhxUjAacgt|J zThO+9JBZd&ocEeLo-`?Lw3y;QytI$|=s=y?`sHICJ*{uAJh`J(Qf=cK-~b zoMOA}nkOCp@~F(Q+;$&%Y09zNc8$m50K_D_ZP$QL0x;fo4fr$w<89Y~&jK*sb`AJE z0OM`ffN%XD=@c05W!gx*?Y7~xI*bg!c-uALC<%%Ug16mwqBxh6*>>&oEu#Zg))U*| zn|4efF1>3ROmlxXA`9S3i>2cF zB;dj+8*XaAg_UKvX#p43mEoovj&=*$c4q|9T8i^tGt-kM#f=tIJj+WfDb5zN1FoFn z%*_e7a*8uIH{i-C&fI*-xovkr5akrxZP$DN{h3E)j^(zy&`Tl5^!s$p53scK9Y(6^Kjk z0tVAcvpOOR?*mP)iO9k`L6cuaWZ}J_$#s&w_?*+iqj9kjZUqgC}LONsGDO z=%uApD~nA5S4gztwj^$7KlsN|Lz^#NYQL1Z`K)wn5Tz;0-&?UXklQ?&rmVC$k&^3@|_1bI`>~*=$L85f52P z%q{8gMLZ&8!}|@U-?7Fo{Q1F#$X0G$I1lE)^{8QlDXP%(m=P5cDlU865^+KWal#UA z@v}q!(GqUav&2bB^yQxb$2Y(!6Dp=IVUW4gnvjVD4d(5PmXy-gUh-$7FC?wipEdeI z%3A#|Mqfx+t3NOFP=Z5;rEiYtz~587;DVGh`2}3~3bZI>?V_bb-jWV8cge~Mxs#Xv z)iH7YB=ehN;v7omO3U;PwvekqloDgM5Jf|3u6eRePS#?2u1hIz1h8*6d)N&ZE7~&& z)J;oC>%4{Bk}|!8+_s^jZQere7)F}5TgY80(p$(q8zN7$g*4e~w~+gWk)G`q^1z6~ z@>7?6Xo;x!6!DiJpuV^f!JkKY8Lz-SUcfEnnGKPx z*+P1cU=CcL8%CI-3O(QYKk-xy)&pYkmml3bLR@yFCE|n%;%!Sr?`1XgQI?2SL`962 zL|Q1}{sgy>F(y<@UAw-%s|lGn&|u!iYDu9Ehqsp;XY_@nwfgZ!Ur1T2f6wR(32XHq z2z|SVLdI|lnc#wyGqZ*C9?_yuZy#Dp&qh*DzA8%EKPnyH>_lasZWo@r9b8v$)0pSoDlo=GsDZYgPaq(g5fz^z777CDOKl;G zT&$GMmV_7ab4!W2B^_J^zCKgPcm<{{0|Wk6=~E(Dfmzro1cS*b{fxB^ zl$;U+PTwiLZ~_H7?G}Q8&331Qc0aCV1W~zr~_Hru=W~KGU$1Aa<* zz#H(DwD57>|NH;Z(ZPT2>l>J{j+otIw3;+({vH~VTAhU=_2%_2=!0Y zMd&1hHlGwzh2g)8m>kBdCDvX7YHUh`n<7hktg??Id9BQ(*C!!dDKrUB4dF_uNqAZa zSBg!-pN4Ry+$20bgewIn;Ta)ZDLDzx4B<-ANqDw_Umr5KKUH1&oq;)_pjvkAHK6R~ zMz|@vq{p(G7s+d7C%xu}aHZ@dydZ=tWhdd!Lby_P5?&a>m9mrYq7bf>orFIR;Y!&_ zcyS0<%1**xT6oZZQPrjIkX;hR>qSRbfSOwxz_#QXHCEiRKwK@j?6W*VYvq>F6%kr1 zwv4Wf&|0ZwbXA1b3N53nBeYg#8C?^hwIa*tR}oq(v5ca5{SBg%;hYZ|os#JBUUppKM zs%6(+1Iq45gqyNUdMvviB6+Rsq}S09u9TgGkA-lh>?C|Vgezqy;S(WTDLV=O7{ZmZ zlkiU=Tq!#VpA6wj*-7}cg$Ml?RbA@W&P4Hg(a{y4=6()fTXKyWEADI{t`=PO`6WVY z<(AQN5n3y@jGm9sTB&99LWI@|Eu$ABv{q&ry%eFfBFpHn5n3y;j9$(t{O~pQYw+Ab z+pk@T!leRJ7k~o08o;^0vKkBQS|BbISSC}yc0EGl0<-9i2#pKOqBkQnE-;JUiqN>g zEP6Xa;{vnjod}H!%%XopXk1_xy=Ty7SEUNWe(io3ua;PQ38=9L5pIes>9NWlM)F#j zNv}UcxKd~m{wstlr6%D=AzUdo2|o_uO1Vk+NeEX8PQp(^xKeTweip)&qLc7j|5thl z6;?DX$YxWes!RRa$WTx%yY?DTc5g?xDZ8Y{vKtl2Yh@?B-U;DK*-3bG2v^EZ!ec_X zQg#x4H-sx?C*iRnTq!#Vj|<^S*-3bO2v^EZ!tYyn(0@_Y(Qh|bl+eDz;ZrL3kNG@wdK3-|%w7NrY(@Z6fhjc>*vvp26__GZzcwpEg8~cC*%2BP zSb)xn(4fEqbZ&$O1s0(5A~Yzl0G%J9L4gJ6f(Q)?EI=0;wAoeV=b?+jc(ugZOF)f% z9^t0Qk{+vUaU`#mne_T1ge!$6;V(nDQfd-j62g^Ylkn0Iu9TaEmxXYp;3T{}gexT{ z;T0iVDLM(SGH|o0s?S4Lhk|O^wby{MTNB}??2;bK?yE>%D?916HiRo>C*gG=Tq!#V zuMgo$*-3aq2v^EZ!W%=lQg#yF6vCCVlknycu9TgGw^*1y$bx?zgU{@4jpFs9%O8bp z3t(GvjT$TNn?PJGxa_k%LTlxg(H#+5E4GY&8=|5mr?izDD2nd=b`(faH+u51z=G-5Wu;>vKkBQ`#@YMuuP_Y?O=q)1!mDh z5gHemMGr@4TwoSG5}|Q{S@eepjSI}8M-cmuTvphDKrV64&h3vN%%|%SBg!-KZkIo+$4N9gewIn;a@_y zQgRYL7s8dIlkf!tH=C;ZJoI8HsFq!O4Jf-y5pK#Z>9Op7jpVhmlU~1taHZ@d{Cfyj z%1*+UL%33Q6220`m9mrY)ex?forJH2aHZ@dd_9CKWhddA7N!rfxL>;!#p^|vKMK1Y zz_#QXHCEi6KwK@j?DI#2*2*oTcO$e`Y#F^5p|w)W==}(-6*2(6V_ zMi)nDt;jO^MTFK$ETc;a9W(^~-RcndG*otL%X}~_E)BzSw%mbKSVDozz4qNT9ppYE4#$!PdIqWNs1qI}=wH^zK$6@O{78H)dHYlv!De1Sc zHU`m3;j}nZ&L)ql(n(sZoy}faE*|OebpRI2M}k`duvkD6+!}zz5|ZGy04x@f1iuNu zVi`$rdjJ*-NrF29uvkhG+^N8J`-AT-!Y@YI6@)9r)bdbF-+5FOQ_^BF?e@}gF-ea- z0az?13GNNRVlhc@UjP=1NrL+WuvknIJP?4zVv^wZ0az?12_6iYD;H44e)L$md@}Zv$I8W% zv6CJvmrlk`d8}MG8T&b5@V#O1HDT~ydUyiAC+w_?wM8=!|0jM@L0#Xn=X5kzSW z^zDx!4fZ!Z*~4pb2)Dd6y?5vv**un-!P^0cZ=PQ1bt!Ro9M_Sij9;YoM-Z(~8EKgE zT~E3xccj(go|jgq%og_pt~O=n9ypHb9G}*B7)0w+MjEF4rzhQ%=|PRZytF!Hws;h9 zwJ9_A*m3mM!sg;h5Uo!cX_)d;Pr517XC2SHv^r(Bcph-IDKq!h|7}ZN9*~XXg~yoq(%NnYq!9dojJ2J8%Ub6NKw?MjYn+t|#4`UrcZ2v0hr8 zGh2)cxZ0eV8}GQ6XwJBRy%&V*b4DEI{JtmMoL@?F{=iGCb7qSP0au$db00eHWtuat zU>^nH`kWDmIZyPYoAb+Q&Xc^fI%l?+9B{QcGdIO?uh5)v3Hvw**XN8l%=r^fx;ej+ z<~-F)t8-?HX#rQ8GjpFh?p2yI{-d|)LAX9=#9_`eJn82AYMS#*FRjj*EoKE=ZO+Wi zc3cPbV7+h=n-j(BvrZR)Y0nKk=4mFx!#l1we`jYZ$lLCV)EP^Z46jHdFtFY1>*YT z*=BP@RwvKoR!gR}-gfTzSNPF9uWl0I)$rGD-M?{auk6-+yHmlO{S|w{ujYAWN1*J0 zuSmDbw20fQ;$ORU-|5xStY~H4<V#MNS@mgV^`lj$h0@Ln{|XPCdv!D`TK!HswVTz8@a^wT70l|zW>%-Y($DI} zW>#mcGTp%1S>a#d`*yrKnibudo^@(BtC!$()~SM7z0}O=oLBl;z0}O=yj7-KR68sD zYq#zfygHf{-FseiYB#Hw;mp^mf?2)X%<5OK^s{=onbmJrnQlVutnjbhy8rIg(X8n1 z^0HIAS-sM&`xU1OX7x%ltE*n=XZ1=mt7}%7ZZqwy@UQTN^IjdzitZn8IJKMAt8hT> zRKcuXZDw`LEB&lqZDw`bD${M2vrm79ueJ~L(ZoOxe}-?m_xj-4a1!oy!Q|koFuQw! z)=v+#Fu(gwTWB+=&v+2%!}(FC@zCr2{9qh^dR;U>>^A-iw88wa-+1J-al_F;9mnH9 zAI^_@jwfF4=LcQKQ?HBWhkeJhKpV^tJCEm18@C=E)O)=3|Cl!<1j6}I_c7Az{rsT+ zc-!lu`C$h#D$oY=!ye=vr;VGC4(dWi2l{Y+)Q61m`W_}jogL7Lyz6z*{IC}p8)$?1 zVK*|)Y2$XJgZh#2fj*ocbtLb3eGfN3=t5Dp!ui`IOZC9{2pwFdTldLEmX@^_@HeEUxLC~?NihD{QpT88 zyibfQtvBgsa;Lgj%@|2Ao@OayOiR(HMwS+W7w`wBrn^|p7)damVJTxwYs5?=OYhJZ z@MDBoE><%}5{zeC${5p|caD*zx6TXrqf>KTtY(ZP7|*kmF{XFbd?QQE_6vB(w!p<| z#{6l_XO=R?)QT@OveXa1fIn=y$i-^L{E^7#mNLfFEiX2*)Uv*SCu?80Sk0I}m-y0B z#+Vw~B}SII%Jjp*OI@sH%pVRcvy?HWo^!d8r4A1srNaZY6+T+?PB0YMO2-*@P{M_} zbzfzLynx{fw%SLl_PmCzah$cMRqQJ(q-CrFKSEgRqg8ue$<{f}+S6LL-U?|kOFw$N z!AGn1yq;}zoVBMFZIcz!lGcH1+GZcE+ViURwd1Tkt!rDXkQTNMT-mnzXw{zAwr!5H z_O!a~FhXtw@)irHlU73wK&yeCey7#+GKSC>@3NZSMgzU&cUIHKXrMpaZ8a|%4fHsB ztmY-7fm4jVR`asaz?r~4t9iv};0}Ag)x2snaKC!MYC7o9I42SA=Dv3-mukrML8r3G z?tp9`aw?ndj^-@UscgcVj`)aE*_3xc&X195*w6t3`a=VV|F3KUkH-S4X!%H7V%0TZ zK|K-jJyK6-T;ZZ{{ucsJ7Ic{nUf)lLe2*X- zw9cOifv&Q_c0b2-7ujI?Y(&#OgA461v7pOr@OE=9gLc8+LZGW`u-)%5-9olhJ%V)5?c$>l=qep-_c*4zNC(qTBAV`3)4zjy8Y{X?2j99r3;7;FI_M_$ zc?fis4z_!%Z+PV{(!un|h^D*f4qQs#jul;|gKwxug?y9_y0v~M1iDHG+l`LtF4DpD zn26?k`}B0+y9G&?32E>0$HrHPQo{H9<6@+%q_mdf3w#%8Y5Dg;o_kYlPTwy`y3PxC zd>_PD2=hV>>Vz2SGB0fTVS(=|FU)@w^3d2P3vw85&?MmF0Enb9IdS^ z$m2obr{$|kNH{3`(0p}_@F|`e6rAL(DahkN;YZwGm5^{y_(}KL7~w-hH7GbZTvw3C zgTl|H*O!oRQ26omh8W?4VKpc?9o|@w$AiL$-8Pkwa8UTv+vXVIlV~+4IFA0hAdd%y z&#G-HA>p9#p|!0s!bjg~P;maetssvFg^!wjQ$oT);WKC3V}#Gz)u7L&KH+Z~+RJ zdi>O;1QdpbtNjl}C>|QF_eTp*xZvYQMJ1pxG+gtK7om7)xa$9uprLOLg^#3~|H==f zPWoWbfEpG)h&tuC)R9RgTnHZOc0!n-`S3|X>4T>;o^mawr+&5+-_XAaBR=bc)tT}w z@h^_EGo^d?b52;BDPR7)rz$gL>Vl>4Mzu$J3hAN`R%gmLxtAPgXG(YDzdB)UrhNI| zJXM(~Q@>k^Zo2V9qRT#5ohje8UU8hADcxURb;8%0r4%n8EvIdlIq*OP9})K<;& z((0VqVt&BY=FHpz$5C&UK6Lmj2-oM#jm$z%x;aySwa81Wb7qUr1Fkk_=DxICCw)AS z_h&dlTH;kODzlH{Vbjt;N%z;{iX-3{XPHwv9jKOjm3PLoq!oeEU$Jps>6CPIlt&1s zMytHaJL6H&>Okq7@qB2FQ_{&$c7{Wtue{1T<4MrkK^3HgUvpG;YXFR<5+9~O@K0Cun{T8qC&Uiq-HBdTd zJeS|*lyoGYo#8nC8?W-tcnZHgP&#KkeBa@ebnc#=;mrM8uky}#)V?!NI%hm#-{q8a zxSpNiVEsF<^3HgkzB^DlXFNvVE%&;|aurX7y7-XB-BBVOy4wdSzwjn_0m$$Gl3P_IFkQ4By-#1$486|H|x~4iugEHsZX}ODDRoxgZ66i_siK zU(|u36F2XdlwLaVfvglzV~_t5_BS0UI&sVVyV6T1>ftX-0kzZkuNSW9K+%aC)vHP` zo%jiKDWE16|3%n!9Vj|+dw4_Xr4#k5H>H5i=kR#>mJSr1_yp{>(n}{gj=LiTbUcRt zn)MGIC_3>0)Lo^QPIMY}PYURC3J;R+>p;z0(sE1NOheNM6RsN?A6rK3^ zV>O}tXayOkB(#L2e^ol(gvx%rioB-@K#%T+J?zGOj~;j!>&F>hv^n0h2i$% zV;!dZfE0#%fKPOon)MWhMt!OdQ%9Y`&`nR%VQzaOj$nSDsZ$FP&)JSuF*!e_5jgMJMiGzEXPW zME%QJDUkikIvprFasRSj>7^6(FB_yl_AeWCpyBD!2^G!S{^c7@NIULdwkruQ71+P*Frl&^uNL2GLiy2pu~SKC!ASkf zE)y#I@tX0SCX^qo8oQN5^)Gu&sO-lp$6ie+KUzEXDT(S|_M1@IkJpa_noxeUf_$$e zs((3XLS;W*MGk2~`O!LZL`vHJg*G2J`p{w8hEo`J;iEcCn{W!l9(+uPX$wwa*nyAh zFm1po4Eyg19j5I!g<<#oQHS|~X55USfB8v=`O#twL;rG8hxs923`75NN{9JzTMR@0 za$1MEe@SC&`j<0Cpc4m~``HLo>YD!LtP!Z>HT}ykMxfHy^e^X(Kqav0UoIxWYr{G_ zN4z#nJ|TF?M1oS26f`2gY9f_ds{tOq6jVugX==Kd-%X@!$1BriO(;8BnXV{_Y-O&R zNZF1TrfZr|cC;{ER}$IJ+%S={9j{9_HKFWiUAmnQXq3o#Hd8Q%n@lIWJ_Z5t~) zwoT6{!>B28+w+bV@#2Dg&uAN~nDY8E#xUBHR+x9SNHsrWZLDI-tIRmVXj58e#%q!4 zfZnsQiYc!(?;A#&(rWX87O6I9f{j&7dByqAFxr&XoR73f^+FSEtYXUR&LqQVQ(Ac@ zOA-I9Vfs#mDJE33Oc?BIA8SGyf(CdvM^O^4TRb10YC>f{uG(puP<~XipDGELES?fi zH=(j07wim8C_gIKnM%Udif6^MOsMR~wK`i9%8x2_j*?KJrf2!)no!w~%XFS5lphu8 zd?le8?S<>k0uw6xafN=S3FSxixll=HXY7UN#fwa+?8jT<=bBJ{v^6eP651Mj;pa?W zm{8e|_r@PLwmYPu6k2l9~sXD$@&BnYA`nG39k;onf>otu*Vkh?bi4 z7~TdOtC;d)v(Yfxl$M)KT14wjFI;an+gQbvSDdd6qfKee*`h_X=%k15w%S<5l$V`t zhS8?9@O-01wDR=Em1nz+RZMy9*~aX2(MpyPCCKyf%V_+H29 z)PUk}Y;aJ=O@9pEPO0O3Za^1k4h{|*g-Idg@Q6|9BsNC}KNy8hV{>+J)F^Z!o5O=+ zMxj&LoE{vPiuU9vO{EiNaze+|L^@#}KkB%eMkmbTCmmOl=!7|()NwV1PMEMot6J!UGo)X1T-QQpQw!&e!lV##c-|;< z5}R7MU=%uyO)XqB3Z2NN7A_fuPGwUIzmlRkNa6=^b0z$yqWIIC;x00E%iX&Fu2s#F zrB(2kZrv|Sl}QNv>WhjxC)~f_7hkl>I??`hO{#QaA+Og})H&g%)vfytt+GzEY2B16 z{Q|-3b4x{?6Yf;-D=u1PooJ`JBUSo^hS&KI6?IOyJ;Cp^Xq9!M?dhIW>4JfJxv!$m z3HPLK-5+R`b)r4#p;Wnd@t-Q{oUjw_*8MN7vQE?sKawi99z0f2=Y&0Qx9(50$~sXO z{8Xyk%JNJ_ofCGy-MT;5D(gi3?^^@Xn+)H%ZjBnLqRt8XUif7ct+Gzk`HqsRV6}Tk z$DLVfdAoHVZFJU-o8B=>XO;?BJKxoD??vfjW#=K*$ zH!@z1a6Q`Kf;DGekv3Y&IMbT6$;fC?O3#sOcEOr6uS;KB$~e=?w8hA1X-ZGTZgs($ zGp|nDEM=T&efq}8Xn{)4#%_1PnlrCaJ1k|KX_flc$Y_~LPs#3d!J0F#RJ$x?oN2B4 zPRss|oAwLoXi&!-Dex$9W}O2#$=L5RT1E@8BIL0Y*uN(IOc@4tn%fLd#aLErcQXOl2xXD^i(CQO#NgjS_yHRJL!Yf ztnyNL%5gTUv>2Xt!dh1O@@G6%$tqJnd#aLErp|h*l2xXDu@tZJ__^6RAFZa9*ZK2~ zvuUN3{(=+M(#n^==&4FtnY!euN?Muv)l-$UGWDCKcnibk^LHPurj<9b%Z{^YrETnr z6V}qom%r+%N?Mt^=BY|rnY!+&N?Mt^VJX_5)2G-seYBcZ-l1z(`qq-{4WAE5zUFH)6prW z)WJ#SSf``YN2!Ao$ZlocV4~A`*JciroX*XmS2KsnM(0$ZnPN454*2~BA3L3! z1Ae!`Cr;<)(7Tz#RHyT!YvwS`=;-`8R~(!`e`+;;4)`4j)1A)E0lyz%hSRw@^l9cW z)9KtC`ZRNxWps3=o#z0j+Ow_3&jG(@VUE+eIpB9J%yl|9hZmbU%yT+7hZmbU%r`pv zz%9=KJ~>}tHGU5Gy)>UWotp!GE6qZub8~p9nZqKdb8~p9nZxHsM<3=1b z0l(qq3#W5)!0)&D(&^kBU^jtpta3UxhnJf-W%9r2hsY+Iv+T^K9R+-xDsY+Iv`r1-_rj4f>TY_jcukEq+R!`c@ z^3nD-FRkUawfH9BD%owh?EzQGZ_DinxJrgw?pw#`wZu9jow_BjsEmmtS@-myOj*K^FrQwKcha!e<5-+O5_ z$82#h;A%N$?ohzha?IS}fUD)0xg(Cl!zTVZ-XDT+J;!`jb<~qC$8=nG%uA~|W{cwi zSIaSTCjzdPW9EJgxLS^x`^j;5@&q}?ZSG_cuIHE!u1!lRyALnc-8508{g{Sc;TAU2e$2>Y$CkVRX(F9u&T5HGU5G#gn(3&R=Z=%;C1vxjDSr+=|?BIyZ+`n_H1TjLu!H zd6xOE75Pa(GXuhVPUvOvdKuXMX+^(4x=Ysnx`yhnn>)@Qb5eoMC+9_Xg6C*hX0%AgpXLx zaj~K$lVCd6QqmT6Xgsf#4fsdj&Y@|Z*htPdk=V4Qz;b~mTEnD4yU&DV=zxC74j-^w zXd)#$qQGvECWKw1LA%d|C0B|k0HZ`cMcfd@AWh} ze5!Iu5RE+*4aQ47*}7*f4q;g<9X7mg=kR2Y{pxZPiLF}-Y*%QawM-hcTPY+%sBrMn z%2hg0GD{42tyX$r1qyUp(+c|b<7dwB-Tsvd#72aG&swQ&ZJIc`tZTzVhw%FyADvvU z00%RfCPxk&{IE(rmb%~G9RxbDAh!+i%2;8I8rMQ$;n*r~<9 zYpW(&x1_;YZEGdN{?$2*N-sT-_>Bq0ek}%m+cnYpB@O!RBuTFk13L%&k5uVc5xaDN z%zD$qfN7D>5SV?Z0P-RQTJ2T>*a_jByrAN%!PO78@zcHjg-D9Sf=4~G>yD|*#*-?&D-l&8N!Epl% zdyN?IkN$7=9V|MWcU>&>mLyn@wG=zIIy4@aWv~|0dV|Z`coQMhmqlj<>FU)i;k@9y zr;+T48uXih68Kt9_&@NF0W=)V+V-LNEBOo*KCK+2A7v?CKgICclQA?5wv}P8iHlE> zf2OO8b}sAT>K_X&UY??O{ZHB;%!h`LshX+-u?I8YGEM1QA5@^zr>)?%;RDlDa1WTS z{vP`f0X8$Fx^-#dXfm@6gE1Va;>&?+|11-UjamwHN=s(3=_8;srVon=u1kpDBH7g$i_9*b0XKCmG=?yh!~$ z_8|gnK9}m&rHP}-;x_ymbl&N;!aMyhbRf2227JC$`ql^)=(MC2^z9rxBst-_yHp2a zCuYEDnbNmTs6eOXSwQ8G`sx+(?*$tKz+|P+W(%tDRc&y{Kl%NNZ`jo;5L*xe9&4n! zHEH5Fjj!4;oI+P=QXnTEXznzR3tz`tQ`=V;>^GX17$g zE=?Rw_O#)@4fsdDzJn=mSSx#7EH)D)81A!FYsxw_-rvgLMeILdVBa?fQ=ww99EifP zz2;#A-v?|v2%*Mt9F*eM;kY(s8ux=kE>;`?lVE??QqmiBXndrVHBB9@a=1JEU?Q<; zOM&H4O|*tdgLcPSNpm2M8#-(j*1x4ntscR_R+ORG`%_tzaM@ z1Y?1olYftG5&$OWg|@YTC>mVC;PB2t!v>5<|IKOp)y2q39%334{C=|-no1oy-+Fz} zzxw}e1bj!z-v>||4c3~3yW3{ z4iAJj8Kfv)|Dgz`Gg*GUn~}=P{3(_4IT#$XRQ@HE^2ryce3F!%gF8pSKT6N9-Bb1V zoJBFi%)k_%Nqw3l#c`4&2ch#Y$lyQU6gF?GzmtueerGm~afhC&{vMhz0VdO=noTf{CZD$9VXu)1-ib|D ze~(Rw0FxO~-I_FUG?~faq5tIL4O~uVslSINOn}L3sb&+5qsiPhJeXd0TuJB2Ka&Nm z1N5>EO?q&cFSM-zMDh9yL{O~*?lPZArCbM`a-mepb-*bXOXc7J|Ln{G*L9z%)z0}$({(qN2)0V>u|e@;Ci@C{XH^aNB`|@xLrkXJ=~%G9-HJ<J@z32Z1zfZ>(a#0WM3N|@UJ&zZSU8C*oGPKIiU2d5h~E> z`&RH;C!G^vjUQBhk9~*$n?q9Fx-@Y#IoyV!Dm(kDw)u#S#a%#^Op-+vm{Lkuu9*|{VIKL=;52e7NoD+gP{pO7Myor>& zhyvn*CWKp~LAy&r0Lz^{7IKT(yXLTp>iRSwuau5F$4O0*4tX<+vT)G!e=;-_zu)5e5mrr4f7%wmt2o@gx_f9QUt+^{#fbrYu+gEC4V9Wc@@EPo2MpJGRw=z zGffD)b{TmtB(MFOcA*Ze>9_uSo4f%{sN_c&%x`5;vn!Iug3I z5SYEA^z4-sn99*C7&>?`Tcv-uG)6~4s}=&Qca@&4k^-&93PJm-rJn{FXF?^j{Hl%D zgs^L0wFxMJ0SxLjY{alPhYlUmIlKpaLMcdyw3Eiu#)&Ri8cK`8)F)X=3@7O@0h6^X z=Kw2rijP*jb0$7^oOW;XF%5-~kA4IH1}7MU2h(6VNbY>h)zrC#VeZo%i1tc} zv!CIFeyLUz9OJtGJ%_t=Pq|G8+%nI- z((LXXa7a>{-wMm|PKbrK(nom(39pJUl-(-F*|MWUh}BM*%8m|NO>+72YdnQTM~?s( zsI`_F)=3}Oq~8Wx7sdH~7EYHg025vxuy)Fg8duE?ff#Pn=ms?nW@Aay<$&lyFsMz1 zYeWNUC>-487#h@`UE!(Q7OSG?!&95F)kkUA;zmpqF~Tt5ZH}`;{U2$N-#B5dZ20oq zJyj_irgnG=S1Njd+!PyA-+BtyDSD2)Kw$l(q+?mVo*P#ihj3&KZbm`=Iz2<(^+ z6mx?NBvauMg!D zFFbJl#YFu35noKEAW`Quku!xFtfcc=66Z=>@`BNa*%JDTMsMGDcF32E-oE3k{x_rV zKj@$N;{#mhe)o#}2?BlwaM>&Jrv$Gy2l-dL;+3|z@q>b^UeS?1EO@QC$Tcr{Df{5( z3D>=(qgQt7-(2Q~*YtWZTj2)}H@)V?jy&su&2{c%%}^+`jxrSZ?=>D6Tho+546VD^3y*ED_e6B>uF7ucE&K2`3a9v?igC0tvsq z9eq&pIFRtm+wlrYo&=J%k~;dK=DF7NqL&U2P~ZBydUfFOtn?!;(MyLQymTWCqhC6_ z1e|^tQTe6g%Z{={@ug$p9ZM8nIwrYhAm`0XH#U&)OV>9^#sw07>EKmq zt};H5v@hL&r1>CgI*0db7x;7{H^Bwz#p@7F7ryZ_3oqY?7R#?6>F~Yxk(H%aP~IK- zYfp3#zKHVH&_k0Pgs-E#FZ9r42f15(4^459yTSL+)C|4RZwM`X>Bo$xnGogQ_Gyek z@;}u?PCaTc@zb>=e&dKs&M^A$Z6oxvvL24L@+}dr2eVy}Ys&PV8HHKRu~eQH>2PNA zvaA_TTh8eoV!n@(w_S_`4CV_Qm)%*3_MbUnIkz-6xcov-6*HWvMV<;5CmvvGz85R1 zS56R~Eq>vnymyDJi;|>5S;PSV@Y_JyWYiUO5&)b zpC(}h8!VNkC3N^wZxpft*%+T>*yLg*<#bNig1SDPb&TyyO38>^+;bI<~CA?tj9^`;jV;>4^SP zlo2(ept`EK+}mSn?%Uln)A4q^9nrVnnf@q`5g=hCg$ZK-0muwat#){>Qk8HW;Y zlQ0^Gvo=nPZMVX%yx^0A9R^pLU^IN}N?`iRN*>SNtpm0;b4c|)g-?1wKxt0`gznTI zci8YH-`+ZCD@rb@zF+Z@azaA=0|9KVKda+AzkPMkQ_oyd|FGf-^@xP}{sauop4G!G z+DCQNmX~Cb|G45M`Gkc00RhYfpeI%^q#UfHo_r>g{Go~`FpmEbX+%77l@ zC?ED0!d~BlHloFkNJ55|n0)Ps8L;$FMd-|yP(u&fh;~byge*N`@+(VVz|y0d&^t1D zpetXta0>7-57S~xB_d->ogCU)X2IO!nlx?X7VbCW{?LiV*b_FQ#h6G!ww^Tk+7vTj z=@}+8RY*_Eb`Nl$iSJ}tW&=z|RSt5r+~l((&48m7nlLn#hrIX_rIlv9#ZS&acAmA^ z+D*j6%ySw}Ro6G1nm7i`=N&|gA(@3Ny6 zau^q-sEIQw^ z0qu@B2RVA%)Ldr++8uEY zaNo+FTKCN{+C=++qXT9dQnFwAJKS zj=+GUZ55#-cQ!08w>yY-PbmwT+F@s?Tm=qn?W`%>TjC4pb~%VKY;hK{wcE~6+seJ} zy_&*ZX51gJxZL9)#<0a%$ktvvLv1T}z4tX`2ED!@HLI{A`GJjSaV3(FseLA2dtwGI z;D?$pJlLO`RR=oXejCwZNhBdlADMh@i5al;aYf+9z;7BlU?bWsaT2n0(BxN^a(g< zru27qmv?+$+lUrdA_FcF&O_erc5)cr@(s;Bn$*>k_YSZ=m}$maT;&X8X_m#-ej*+fHCw}n zd-|v4W`%Y&$40dH5lP61}E!Q4VkqOt1lvNcRCi)=)TF_DC9EjIbu6f+m94;muZL=iXj|xg4?B=Cd~q7`^@yFJ_5}`nE!7md z1?$l8<`b$w+F%Yy`ii-CYW#+of0Y9B(o<&KFkfdN>rY$k;H1FA_A?cH5}U!$vCNFO zn~537%yNrenQ8Dav!a4`vl(petu*89W?}|1^Q^_L%rtnId9H%@uo*0gpEu*}W?}|1 z^Mb{$%rtnId9i}`vKfqAFPZUnGcg01dD&uDW*R)qyi&o_&$(b_{;C;oHxo0Enb$0K zWv0Qy%SXVQZi-3iP z^$I%a*1_SSu7TtOb+W;M_+C^R^0U#-pgd&`d~H&c?(Tt}F8UF=Y%T1cZ1z#UyD}LW z+~Vd@9u*Tdw<==uEjHI(`0jk075A;>1Y~Nv!Buu58b)@M;Lc3OfOjAsFUgxk28pBmiMb3_R zS!#EY2ZvuWty8>H>R9@)S$#K$HMkD3_&#ohO|LWxNIu#8+TgN7iH5lo3QPwk*alWD z-xyKfMPieQZ)>LV5U{ZDor26~{3yTj5q8kxxFZ7~IlFgNBc*C3qtHzyy5F3b*=*eDd+T!7Y6>X!y8oYTUo% z>v9A82&a6laI25VCm(kh+|oybhL1Z-@Qv&PcV~B5;Z`4!Pd@H8xTTK<4IlTE;G5V7 zRwFa5aI25VCm*v6Zt0^z!^i9r+>tsAhPOFpywwS3AS?G;?9vPHFf+G;r(T0$Zk`!$ zHMj3ZA+S78v)N@pd!0^DMB~m6_Ci7Akmikb#>^I6kq+iu+!20=h_x z4X$z$(YQnpC~$LpAsImjdeDmdMsfl&vc%vjBM}WF50&85RKkxkJ#58WjpUZ{h`}w5 zq;~SC0*50CsZP*rAF~m@8JUFYWvR(mh7tpH^LS0jwS&g{gpC-(Qm&yVO@3`D)zVX% z&>Trfm4p@X(n9dFl6Wg=iv8EX`jjuIpf7)stT!oG(@ zClBw|Oywb9;bA>Psb<2N1vY^jo()#mG*R%$#YTh6HY6H8HkII;*$2KA+H8eeeMCO_ z*kW)?9}OBlwkmKqA;3=m7m0bqa8INE%woQciMn49OVW7E|Xt7 zN{jy8ia;j=(rALd^PUy<-DE!1&K`rSoJ2HgW^W0mRuyhe(SP2z!mU0cpL~2^a7!Nz z8b0=w;55vKwm*vf;+}1Cs^=*X#!fUa0>GBmBlX201r3EDtK-) z7*>v(fOa=A1-bd!Vpnb&JluR6;B8Lle#ahVcb+<99B`FlA>VV<){V!JNT^ z!S4;)q-+qA<_|7rEQ2W%8T`@9Vi*iO82rhgb!USZ27Y!iV;M}D$lxh2i(xSEVDPj- z>&XVOpLfQ^jAbxoB7H-uWg>&Odsz&FDLd_&7c@G3 zk?n<}9(OvBHg_TodArNbP&i`_D(>!r(l@1lB(-RM4(c8k)aFg4B6l;rEQP5*)D#+gWfUQ1+_U;smS3RFH7Mt^WgAagVrgoF1p8D7c`c`l!_eA^RgHY0}l@8 z7qocJMtDRIxvvG*=CVjfKJWK46;34=UKbS9=738!8n);bdYCqsG7(u^k+}z*9JM)dl^-fd;Q)-NJIr(s`=~a9IvH7f#LZKf6in3N zqb70WPr@kr^kZ$fv90EWWOivwF4Jyg!|>xKc}N;Y7k{D+H@4xNkPJWBlFKw4*)aT+ zNu~ocqKeVspKb+?ZCRuw&(E}FGfgueu9p>b9I6qHv01X*1+}?VsmSRHFH7Mv^Wbo$ zMQaY$WS8M|&$F$-F`dek?Jcn2 zZCg#cA$!9f#C8udhPRZ5yzOvu)ZPLM-gefc8?!fTKkV`#V|Yt>$lGowN9`@J;O)Jd zbW`?*_1GQ{GKRO5hrI1|a@5`e3*O$ZNgbl2V)XsM#f;%DXCiz1yezf9$b-QT4O;4D z@wG4eUCdYpQzkO_k(b3VD0=M21}$~9_yU*%E@mu)DH9ny=w&esif((TpfyK}a`Ovc zwtV7Y+Wg5xWbacaN8v89aCr|Gq~^GhFo%wN#KW|ilZnXOQ71=XF0o+lvzn9|3~!5k z?qS9-mlBb=FPt2;InnOEEJ)!vlBhc@P`>g}Z3cBRvUtqRQw;QM%2ed>J1U#>r8e3oMvBTa!|&=9kQz^DtwWONq$bc_&A0PIQf53Q}`KN?cZ~Uw-v4ZRTVm zGIznrQJ70C)ZA}1DP0YI@ytaJGlsd8h|FDba@6L;WxZUG=s1h8- z)y_~DV-70qT0x;BR>BvCy5Aj0n=g@ueBCz4Paib7X~!Xm6uy`PUw1MEbr?=~Wn;LZ zy~~4`#*94V>~1FqTPs=cc27;ZIeWub*fTxI7~WDI@;1xKQF{w4c$;02!kMh>4y&j+ zKB&!~&P5LIb@LP+1rsjkTEuj76<=C2&j*d^GUXzd^W8j_OL4PyUqNinaOIjrpS|CM zv^kV{$ln4dN8v89P=gC=656UbN4Cg=jNvWiA#aPF9JRN=g0}~1Qkr>am50vzpoba5 zTuMadmN+?Tb7Bg6s30}Rzw$*5w?Gejm^O1V5t)0$$x)a~EY#eiC5euN33J%eJh|SS4VG`RIPkWd) zi!u=ze8$O9*h?&!TUL`g#tV12QCseU#;})Dk-rsQmfB$C!Qo1SCfgu}y=Ps}SPoMv za`>E=#c&vSaQGr@^r^%yjFO{L%j^>ezmkSQW1qzz4C=mUWlh`1BwTk(w zkx8B?XNel=SZ*Kxj znl?o5DPuL<{JviWZ9zdL%@0ael4Tr}_a)e1|5Txj*7IQ%w3P*wl=qjcq|7)df0SXW z%$Tk|u7Zworjqi3l9iPs4$21;Y`AYklo{jDp(4G`UGiM=aG>C`I%>;HGRc2l@sfN(LjH>coI?8rLLRrb zU)E7uUXn@vtBRN86B6>r6L7Gr87KP^F1AZL8J{4reiDQ$lHTzF4E+?|EkmON(|QJb zhr%p|TafSSAQz&qPyA+lNvCq0tf&xINR;Dy0qmdJJv`DIC-4q@NBV;ijvj6@JctZr z;>VgSTrd_keiG1O`W@}Ao;0C{_Vlv};OfXfb{&S7%%P|o-Xg6WXxWE5XnQa^+c-8b~4Wjtoiht=nGdch!pMnBFi{DoJ25XEmxnLBFrF>6%x%Nh(qMnf1o?t(UGnJS~1CY z!o7yiyZYp3s{)o9{y^NDK+Uce9~W+#)C?ytZ)D^+$RY+GZ*pid|M(=@-&^A2n45PV zLhb;k+;3+j=cX8PugM`jv=k}c5jZt~6u5U2ZhCCRxGrnO$I&aVEn@<}$?Lj|OkSr4 zuj_Nj^vWqV2%P1WaT^6r4QYj?O#+8Gn`i6-x0!JRQ~6i#&0I=h~Pkd@#qRN$;4 zG48OySw&*p5rH!>-BB`Be^8WtS!91F*{(lirM;R2k>c0MDyXcR-qeo3KNbC?Hy6`#h`Vv284 zbJbtS$do!(+HW~z)mch$QQ(XkOSnq{XVh21T^2Z_)g;^%#`VN%#n^vUd>V@`R$^52 zfTmi#mXTa^ilJ72&mpVmDaCC=&GIlLHHw~awy4{%^zD1)=dtvn`DX$Zf3Coy z{4t7aHIIYS(hg!c%{gBMqJ(G*l!Pgyai2u92;xw=UxurS)~OaKY+2bFyO6Pi)8hA; z;eCUP+#gQzVf{W~sunP(VQHaRzkt^du?V zK0To$rc@%4)RPL&QUL*}rx-9Y%o`@*JKv{Oz!YK%={zIREQ2^ymT`E-^pPZk5p%hY zm^z6>LMs%Wl>!1%D;dx=WoS~;La%?e2$^D;MrzM#2FpbZ^qv=xuB3z z?x=&|;T`$0sS@#|@vgwKLK8*)wH)l@wH(HTb@F2~f5cP%^#aTJn<(;c;2@oP8J^tL z6UI2~*=;OCrjFo|)~15PdW?eRW(E!Q_I2ONr!g=zY$-#grr?q0)`G*DjDqGi22q=* zS67E(VuaXUL`=oZBEcP+!Fmw`xt$D|F}?fNv`j#k+Es?4pt#SV8C&p3ad*LCNk&2Q zy#iz{8ki8i6xvfVjHQES>@6APimkG~j~SD?Z)MvwztRJS2=voN_)u?m*Ob9{wjdk? z`nU?#m!+UmH618f5R^Dn)WHO6ws$*N7_H$@8MAdWkz_w9I7v04Ao{5Sb+Ra0{oyj^ ziv}Wz9w|6Vlu!^onnA{}IxgQdwe`qfF;hxG87+whR6Fmm*>d zB^F8jsu@WvU?6uPL53&uV2L5?HyyCWm_u3@6+TG;0i{a`KpkO5tUs)7FBcJ8E3ruI zie@CWfPviA1ZjE#>tWcqR)%cB%p=9$3r>=ZC}`d`-0Y(?GXs6v#hMsHZZAWwX5^9P z9R){fHYjM`4G=M6R;p66QIL5uA2*vV+cf zAr%P&z1Jl~9|l=fgrZ*E($k@k)tVvo_;AP@8sfE#l=962@3f4Be@o$GOAmK{Zx^9h zp1P$^=4Q4=GgNtEOMgd0-12bBcMH5%9>%XN@J>rlme&<{r==(SdWolI*cn=S*ty+M z1>H8sRBCk_OO~uR;L!3mDVRRqvbl^!U9p?NJuDDOc1yugs(jpKYXS1ES3aV$tz zlHs)9T-f&&WBAsN(15WJ`=E-owO=r)A?+(!s{R@UwBHXUEF60o_Xpgl?Jpv3<4uQU zKGF;+NEpa{tRddzN+}N%c;{jz{J{e6T&jdWr0}uHVlDbf5sAgG$JumX=2Oj3#gEPP zu!gwB=Z18ozYUe^muzofRtzL8W$jtYoEn zV;maJaS2PS;cD{M_uhiCh-#$PpXTh^fwZym(t%Bp(tD|Fq+#d+{}^ccbXw3 zc`1ETL(GOEQ+{9It%f4;KPY@`_hBjhV-bqwDH?v0j9bx9nxV=Q8~)E4;+BU~o+|KO zc^H4Xz*`MpT0T?Yt%fi0XC1mz$yJo2J#Fl>BNV9v^tm~-#5OF-7yV08oArdw)ZZGg&dAOzDQQ)1H zo-E&4;GLG9@OMc(HAA(OzPk##ZH}qb((fr*vfhA0OPHx(dMQ1tj78mIDNPld*Q2uw zj#A~N^qd0ZU9X(>-jd;5vCNoTGMsCc8S^wFwpuKu=a(V3)#laZeFaC?L~OYC7a+eT zxG63u8E#E5V`0f~Yl0bzN`}*Zb72=NhF(fPP{rEXFE6DZELp1l(o%YfgoPDmTuMJw zMBK)k)};??h7=?W@#%1uhIp4NrF^u&I~ObAA1mysMd7M~l^Qw82DKI5M*@Lus5|4e~*+G#4{3gBl94vpU08($ZL%37&D=c*EO zlAzGo`mBVbo;Z$1@&dxc^j*$y+}nr9i}K^7A-_n-6cTw!z@ZVNka#r&C->6}7)I&P zUY`_ttqw*x@c=u`m%{~}L|?C{L0TeVV3h;NvolC5}j2j z4wdyXTy-g(YJ zZ319Z{b<4IxdWM~*igP?-={c78 z&=Nm@^|g*z4Iqt@k>@A%xz*kp5x$r|OSBM)?d_Bd+jW{!omN=0 zMicgo!kYD&uxAyvZf~+U=Q5V}HL?AFUVR=bMXf6+OWM->MWS=1@OI{}GHh2$N_9bD z%}Pnw-vl;ZQH&rL)#uI?P5YOZBwCn{SM;(BJLb7@Tv1rtJY%mata(L~#cK*{UeScT zeL7x~Fr1h0@v-GQbbzZx9UvMJH0n`zDoU&yx%$5c06LXJ&y>+YW%<49%pw%^MDJBJ zQk$h2kjoh2|IOddR*)GtM?o~%Ic3aO3`CN=x8NvELP2z{26fyRRdK{{UKMPS4OG&d zU$V3?;h=nFE<%3v%h7{$w<48}tRqj=Sm!Fae}6fbr% z7>^W;;x$eNV<{LTU48VpLD!V7p@C`BM@IfU7$58Cz>N2}hv8O~_p9wh)R>-da-dZi zEVSn*1&JPqo0=Z~=)hOqPZ?p)lAx2Dr)#D#!dQ5CMnap19Hb2#H(h2UTqi0CnOSb~ zrJu}zr4*Jd9H*Hb@TI`81bIB;?av-A)pC1 z&w0>$&5(esykKxkCk+}#UNpe<1Z>H?WHB)^@yqR~=Y&RD7<{>4_DzXraKmGTuNdLB zqDMNF{MDLS6uiNr+^^NpmSSg#*A1Ru=*(MH@`ifg(N# zSJW0EQCDjVVCTrtE#aDBEws)Gw>e-wd02073l~7c$A%ItpC8;<2U|UWOAa)VEf=LY<#I-c|rR(lx-@^6gf*%>nbt!w!R6xBwd0U}p)A z*8mH}U3IY417CyP6|dBf*I;h}#B^F>@gbc`0~V(qo4bgCuHjqxi-~ah4U3Io zBL&skev1t&B_8$mkp-^?oRS*8xBuAWmP3xsJz#RnLC5AEG`Zy+q0K#{xm@#TCZANX zSn2wUnv^(@sm?zwiMqZChq^wRV3X`C|CtG}uY8e$Tzqb^lM{)Dn=dT5dF3TFT=_3e zu65;W?pG$)y7D#mn8~%Se9b+sx$4S)UB%ohkHqQ9pD2mCzWK_32N*rqJf0rz`uD%a z&4`oYQ@+T}vrP0)zWGQby29UQ0(3$QSMw(hbx4Ju#iwlwfkXXZuS z#HVcvfkX=DGl3N-289b8njjT^6Q8yz1QID+%mh}T7!XrffODn4yf2qaRtmIn?fLw!kwAG3KWCFJsi4GD$Eq0wkZS>Da^_QR-hOZ?&Z); zQem$6v`rz9NMT+kumZ)Pa6gA`mI@2Rr)>&>L<$QtffXnQg$FqFcT(X&@oAevAd$k7 zOkf3yLE#Y&b*N7LsQkE1BhpCZF+pLKCJLD+Qc(5mC*{YjGO2GrB`8UTd-t*wRNZ^I z{J2#nb?_B}l4Q7xKbL~4k3TOzZk0*B`~^WtGThH!PC?btUy&cT%A~ITs-Pqp?(C~l zQ1$lJ^5a&S)ZgC_lqADF{_PZ0U4D)HxK$=~`ga5+$#Az{mx8L_ua_UU%A}sZK~Rzm z_x;T&s5<`^`EjdE>i$~=CCTsrup&Ez+tnkhX*EIgc)&>8(blcvYxX<0*#&<5a8&UQkM?^|1*<|64nwc#mEG*nvLyeA5OWbAf>W)zJ?$Nw{ zey9N>@XR_G3#>-qm^E^#yt68vE^dQFX=iI7{kC>|g&juVIYzWapV?&K-kPZ$01FFq zGqihfcp&vYECA+JK}SDRNqv6F%GwbJ<@++MX?DZYhq(lFo(kKu_uB}^Ly?4xEHL@m zjby;m!c6F$O5Lz~+Q4935QWoDi%fuHNT(n_i!FAxBk*wZK!#84PZtJX@I6?B90yDz z?IoI#Re^!tLmATD+cnZf6%dA?Fcd#*gdJT;C+$aSX4X$wcvu>s&Ct`x^WQucKW+n} z5j7Yxng50r;}d3r;D?d?7nYvRgzt|w5EkPz>gdYPdXRRDRXVcxoRcbB)GSzhF_Sul#ZFO+FL{u5i&Z+Z__C8K zThuIAd@YkE2#XVh#n(MZyTvLUSzP6$$`&;X7T?UIiNa!h${QE@Ef3Oeu}Vi4-*!@E zi<$+C?*>v2{cbkhRQAv~()^#O!?iZRw`ZgxbL-4B!CJ|Hv5k>1g@)3`7X7_tBp#bU z&26#)(O5_5#A2n>Q)ePyo6RiISHXaog zYFJNy+>6BAyQ>biNJlPd@2+@Syg@?!Jq@H^_l%7M-wf|DqAmK&CIfqGrgi`Pq?-!3z_-Y z&Y&D+4s0E;DfKGckv!<|tJS!}KjiS`S8%vZarmD&eEBt88~?E656z&-ekh(V!acze zE9^E5!KbTn)ZofX!Dw8E&r0yLcr%83gU^jTg}WC5*8LNX6VSDrqlM(P@K&%lUy>Qjs?jk3zutV zwve!}a3w>B{xt26$pKzoe6`pyogdJ%~C-sMG zW;T$p@bE~64h0YK{o>&nfJcq6<3ZBN!(%lwdq`M#Sel{199zIZ_jnz390)QQc%tHE zeMUn5$qWp>SUx-+Qb!$mK_>a9D_)joB;=pTz+j6T0fxF|b<~j;WRhQA@v=N4A-^I6 zgDsZFP`9#DKbL_cf9mP_qxucB=c}M2o~fk$LdnX~5eMZLGi*pI zW106-6?Bv{m6TsDSy?&ap!`aPHFG%s(nENI$E#J)QO;CSeywC><%omw>lubk>NKl_ z_cO0D!j8J6lm6_}^hf z9T$>KCU(}$>>*)cVONI6rFpb~iE+0Pbu36WS$MBzW(x@m3wso_S)WG>m>l;SQQtyh zlZE$drm_&Qu<${K#zlIxfC+M+5p^s`Hd*+vW@ZZs3k&-*lvnA|17^vOtgvH3@yW%< z1~=QtX!tmg!Ev=7ZG^jmgGSh~A?f7eP|eIH5*8jl$S>0MC)mL5{vN`NEN4 zz|l!T;E9JFq5XVs13X7M2RZt|7;tn- z5aNWyhA{V?HshWjm4WP>vDm^*#>3260gqD?o53u2&Ww9zR0cA0-eLnNb8n{elqeW=9x)7nlIgkV-**7Fuj!C*$E}k$?xM z*$u|u#U{XWqf(HY2Q0R5lksr#pnwOXxdCASUSa|~H!20WdB|c5HyIB%4-0rOn%!Uk ze#8WLZd3|#^QgrZZZaNj9ux4e>BbGY6Kmt8R^0O<6Ofh14X$vK&@l3Z0Ea!eWCY{x zlUCd_A`_62rwpzzlF%^nv;c=2nq&k6?=x21Ga?g^k!1!~7)fXtSuVhQOOvc%{9R!q zJTp28*;#4wg(1O!rRM{o`3j_)zGlSV;!MH|9wfS|&Lo)0$lQxgqF}FP!Qd;I1b5Bi zN9>us#93G_uQ&W1T4^E*+D~6{J4o({y z8AtDPLAZN}&a4hjmOj_&Ky=6_|0$*9kg0VFKduo?2pCx}0MqzbdGnCV1|9H}0*CM$ z6<#P20!o__U;uBuZuX1OZ#L_It;8Hs+M@7D2?!`{O91+12kc9uQ*4(XN0s;@BCeN! zCygBfn-rSgiD;e-+$n5a_a<@dPV`U|BPeRhO388qH$M>qw?OKcs zD&YGPol4lmQN#~Yc*^jkzW$-`_T6!Rz#P4=4%%{(OPU{6yd<2EP~V?`!^8cdh?tH) zQlHzJkwJ1FOLS6d;t)9?!toV}m}L*D&pi=-IpQIS79#P*h@Ye|-4suq5?|RL?p{7E zW42Z%Qkf1HoTM00DA|z&>gnTeLNQeyRRLQrQb_AFiB3XI94eouFntF!wf9eaz5spt ziz;ZV2`VXmS+bHUTgc`g%%mU;y+Qw zY{g6@$!`iy(u^pGeycz@AB>?ae5?Om9rcBoOwuPSo)QNV@;^pk=O`_L_#|R&5wR5$iv(}`$FK(I z9L1+eFJK^dCm_Q^)FYv{mx6VdGcdZDB?+FzQD3X z6Gi^}I7kyjI^u`Ubbk>sRWgf&7H9@*MGWK?GK2=o*mKdP7OBroDQ1w+Vu@xM#3Awk zho}89))~6dgYsijBH~G5iNLZz6Gi@qI5=rIu1C;k9+n@Q`6Hh4KO(T4zlkFMqa36c zdWyx{WAbA&f5cP%r2@iD2^{`B**Zg-?l3WA^5bG9D_YMRX!i{--k-=|c?J zmm@?Moql7f`R_Ddv_WNs5jEAS1f;sMCPQ6g;o^BfhyFyNX1t+4p(bJCg*s?@DCuP3 z#fl0C3JC+R05}p1;EyoyY8^BUlyoxiT1ABcg@l3C0MZ?Dci$~^B_=mdspT_9Zy3>N zLEH>iY%=g>&4dGug@v~jly(e~2dqZcSm9`b-@-xdjuU4-xp>FmDjN|EAMYCA>b}#I zS!*%N`%sg)UNO6GrG5~qAIt0wMzp2+nN0=XSTj|*gA$6pSwYF=@JM{t2Lt>TE9_T) z=97!923OgLX!zJ>fZgg>GTSYtSN)2)Q!(kW^Wi^FjY9wi>s@BtzXT!!6@RzIR^?|r zDqxR-lTYfBp)ugDe6JO5y%3R4PTn`T%1Bg$j}HuR+l9z7`z&V5g~-hPC6iZW7>Pfs zqy9CZqJT`r{t%z(OBO(8p08ZY^m`ED5cC-rR9vZ`WTm1y zI_qWON~(CMrSlfeqtIPE!)XJJjyQLWHh<-7JbtqQu_U~{4JD~^P%$o=d^V&RD8MC) z5Z~H?iTAP%7}F8|FzywTZ#n7+z459==oB;1H5)LdBjlhu`rYJPjyi**+y2+sQDpta zcXEW6^4xAC#eg7a%tfWUd3bB|vT@$UFx!IY4eA$b1LVA0RgqWRV4-)+(xQ zu>%QJNBjA7_P~LJs-rK>>6tPI5~^-O16krgLe))dAP+f^P<1ynkcS;esJa^)$RiFU zRNYMtloi;dD?-X>N){=#(|*fCIGU`fuQOp0)m#I4 z)qylsM>W?#UUMK#)ltngkk=hZQ*~5x4P=!AX{wHDu7Rv}AWhX#%{7oW97t1jRC5jF zZ4K$fq&YE62v{Snu>mckugF28?>i=6kG{;Hr1XWoMYth2!lb#@28`(lImppElW#e? zALbk2O=iT-3~-dn(sLfF=_5`AY#(o>p;Y$`Mv`Ylja8wL`<6d9Eg}S4_FXt zt)l7i(kYPCF1W zX`XQ)V$wY8K*XeZ&Vh(Y^SlEQljbiDL`<5$IuJ2wUT`2{(!8W06EJDUUqZ#CdD#ZE zjJ_fVjlNe*z8-y)j$_um z-9e1$DP$p2ci0&$SHwX@-Dy(dJ$bm_yvu=%?Tc^A@3u3TzT%Df9E(CtO7zBi9f+7d z=Q?rV)~r#K*aQUp92xo=lu>uOrHxJh?qVXIuJ2^F0mlgZbj8SN*F}GAPR|G+C^-Gw4A% zaWGkIFe!0!68EAT9mLqScz1G>ox!vf_a`@-lz7vQsdbBk7~2-IP;G6sGnlp}hN*R% zNr`vvVQSs(K*sjPH}5;_45qJm`@YAd=$*B_9!5;A?|T?AyMEwd#Pqt)!-)CyLk}Y+ z*!>x%%F!ojF>`?co;E<9`!I{68+4>h*|V=4J@_P>>CdnT>jF==(n;5-+amK@l z3Gl3k5fk7!4JkfX2gYj$kaIJWd<6kuUKpz4i%m<(v6~q5A}BS#FLAdIIdaY7AuKQPJTDI+DJgd$ISno z-sKt|pi-yNW~tA$a={?U*%CcY#vw8%g{SxQ56A7%<_z$?I$+B%hwyV1J_!KZ@MglvKO+!l!p5?LtGNu-HGWKjyI7sg|y zvsis@i{#hDKOoUbB)uGdNea_(tZ-d$`1c|8c@&AKFw)fx3@XXP5}ibvj3~(?GOSKk z)Ttg-Sb2t`#x70Rt|5MG3@6DR*8#hZm_z=bQ20~;AW(v*5}^B5c~IwR^|@0`fk86Q zNOV$ZGD2jT4BOR|QY}|lvzik2*@*3=7Xl5+Gq=y_fK^SIL;jyv_*j65KnY$D0RC|| z^u8B$z*7nwQhG_@g%Tm4^s)f-#Dw4D+% zL4LuxOGjKakf><86<%sh2%X_Q1>mBgckd}ez8Dv6uVyH@ShV*gB;LG-2O&Su5m$}x z)%Pj9)QWfJ9|15tK&#JT9!;?H{8$H~k{C`Thbr-a!b2$`i2OHydr$$YAtiz7@dHYC zNTbU^r9gk8(dDpGpbuyCNE}u$fF4nwJ0%Vba(Gmtb9pI_;(jK>c4>(A44}t!AQm;=P&5NEYAkZ7tj85T7q&s5v?ns4cO*Wug#q*%9f(Tt zKxI;j98&sL;j>bMfYNsgU{`ETcT%Ixs?F%{HQKD)jQ&BR<*&>b1^Y>&2V=7fTVFpH zp;$>`af{2*I}&JAOQ$qLRuf@RPp37+tEiOnOo4Z*D&fxwd^aE0M>jgJBe67P=cjBQ$}6=DZ9_ugSwxtn+oi(Tf~XyHDY>R)c`j z{TVQc%Z8a`fetuIkwZ!g6+SC92q-Pefa(0?G-i^;I^ZZp4kHTq$g~{m!`Ejk1@ucyhz(OHL zk^dzQHj_qFKr?w+2TYB`A(dAYo^=8OO0Q->Co7?Cyru(=Qsj`*>k6Nh8U&P9Wxxbh zLW5YX1CCPUkkT6ppOqQ}l-|sMiL8Wn@RklZN|8fKZ!3IOY7kIblK?as$X6u1qXV`Q zb4cl3g-=RAKxr)lMpy?E%sTn8sS@#|v0h+Vp@|~@1`bZ*{FqiY%8$+b5l{Iy2`uMt zqR79QgVgq>#hStpzeNX3jl?09tqRXN0Rg3L8PLf}VPM~`BaT!gk<<=_&r%HnQadwX zLXtv1-K8UrR3wqqZiUZM4FXc{Wx&KFg^s#MM;xh0BB{L!pQRcEr1k;OOYb3=9v^(h z;P#>XxK_z{(%3JsP>50F|0o6Nszn7<+Q&LzYcPjY4k&!m0Rl<~1)wu3q0SEJfTt8V zr1Xix3nfB8=~Dri5S1{v9o7L)DR4;Xh{6jcLO|)L08ETZ7~DS70Z%D#Na=Hh7fOVH z(ia&pZ6GRP9sQ*aI7*R2N?$2_R%#GXI+g$W67Zz)wZJ9?iX#7s6r2?E zV{rRMer)Ftc*_5+z^42ZMgH#*?Cu_DUSZkITjc09Ka`=UBQ_N@kFcN|qMpH$h&|u((%;{`FfKin3xWHkFs(mw2(@XwkT5cc}n5SCXoS(_Sta z_LUTjD(0B(+u8PLdW^NinUyVw7+!QXtOnvgt~imZSXGB9Rk+fP4A4wJ`-*| z?<_-6*62)uM;HFCf+Iwcol?+i$_kKk3D^#$y{BZ@mq0LP3C6VUPVP)$X)?PC`ZXG< zWMWRq5`_yADBZmp#=R+gCp5PTwkW6WG_Pc7W$sS*X;|z|VYl`EG8T1>{?y40e?h^~ zsnM=IKE1nRKNJ>N}C@P?HJyiN9YnFXY6zgftinkdUy`L#V zv6SK)kT5b)Lhz`J%LjUaEj@MT+z<*DS9x1?yGKip?a9O0ShMznygQ<$1l} z=px2;vZ?_2#pATAONLuCX1q}{ympeTzgaT8c9Ixt5~DfaGa*jTSnIx1hU_MidDKAO zEjX#}A_|RTZ2>atPNiK}GOW5&j17V@t$PAb&sghjtYWcb;>)zALv@ZOCKYW{$r5D? zI23NPhVkr-weFTG)*_rH=dC463-jc>UBlw!jL~vO8H%#S+>G+_B)YTUXwf(~?+|0%d)#X7JpMweI^>tmP7+UZ@ zQMQHMH)Z#uWI6@RCN0$7bH-+!y3lDDXevmRKXVI)SZr&EUnDl>2nQ>-6_l}UzD+^YxJjy-0;6FI9fIK zr>_c-b1|ucIPI~LVP8zaI9@Wm{**LMXa@JEu-5&i3btH?)SUsg;EB=~5l_ zn+cPtnOv@TsuF=jGr3X$-HH_HuhuNDG6m~*&5F$=j7qotpS&T{)Xqd)WctyA|1#PM z1;Zxd?FB~{F}9OC3XoqsPJ3s`aEr!_yGn-FPLlPzONQ4@5@S|m&?zL^){VQLSnAF$ zBC&y}^`Kx;>zJb%<3iOl2JPZr1>pl$&0YH3BI3(|MT~ixq2%HjtN9ATFZstvd0!dw z1p|*1?=Lt?l29n(0u72~#9DV@8EVnwQZ6buS~He&u>^I-tB8T}fg<861{M|aLCuhQ zgh3IPC`c?}cyy+S_;Osnhc!dV#nL^ZAbb_^{mG+c$QMjk@v(xVB>5^X)u32LESDcI zLoJ$I$|nkr){NzRQi3MLtB76Ur;3QH7+7=_pVkbiM;PMM6FCYJONcM5mlY9Tj?1@P zGn8B`-3kTas~F~^m1WFVOqcQ5f}=F~GCrq4v5;Y@{CpW}5#@5eP;j(pEa{69G%;Ss zFdw~Cgj~r$qYL@6W=KK85T8!KCM$9 zqZpsk!PPrbL_EbzB*mke#EKCE#V-Jv)H6aq%EAX0Ao!&YB)!~TB#FenQUquv1f-5B zKv+kQ7pu&KrYlSNj%zp;(c?Q^`L8t`E9mhPUHAzN$MSjn%`W^K4WHQDTF{I(W!&HY z{kW!w7T&+r@EaO9y+_!Cf2ZL$HgI}jum?Y>;WssKdZ(`k{~^PtOzXZiG-Iqbek>yK zB8wdal#5w(QGU{lajERU;4=TLA=Uj-netSDFYlI0{F#iOmVRV1tS-(Lp;(@>jWLbN zb51kHrSbrS@|;(YIC_VL#VTUpf=t0MxN%F^j?@^z#j@XM36w;X~;gI1tRA$L= zJ#I2K44bnRxEeJzc#Z;BW2Oe*tH9NWsljs{KIz7b~z+jSPN3ft_k(@IwJS&_&I0plgy?uRL5t zVpZx@CUG*6s`C*|3Kg0#Xqig^nKncla~<@99&)+)co~YCVsg%eAfbB+4k5eW=Jza!CEgyIl+H-~u- z1^bz6)#r{#+B{h&(OHDIP1fh|H2RfBs`qh!zye@{4mdKALxtI>@L8xqpg5Z{pucBI zl)}#C<|5)~F^j~uXhv28269_7B>(6u76IFeh$F`=lH0BsSq>P;?Z}Xkcq9#@#ZL9P zBNZ4Vv`eD148;6Q$dxrqdo&pR*2cR)oHv zID|hW@li+o3hCh(o69O_cV|u6qJiGHv5%J_Ai{!r53?bKGAorbw#NiL)`AHpc z#lRu0?-gE3#gX<00T_{E`j0x`DFqHG{iN_hi4Z8$&jQd4z5En6TGFXH=qY9{sh+NQ zLOCL#entSBk(kvn%Ac)+o_gkz`nifH)FTq==LK-2o3%0M|5AoLW#*CYuLVb_0tL+r z5>)(f`fpXtRb?j0UMyKs7dQxC60pHk(YQyuT!uVZ=8@`^f+IwMg635Til@miGhEXF zR}UOg`(5FsR-74b`)^^WZH9-zbifBA&+SFX6-$SE?$8V=#|L}v6p$HRX^#hE&s}BA zQ)D6)@a}>mG=V~O-XlQjJl9MW@Z|W&)hvk?Lh%gOY!RLw$DR%>DCg*irxQq2sCyM& zC=mh$nkxX){@6Pde-I-a%$ipPJ;6jJ&G{uu$Oasg7bIBcXczyaDVoc|A`(T_gx-92 z5m_X;NHdaPz(8)XfY7=Lcl+c1fKl#&GGv#sbCh|c_+Y^il0ZRoi3X|R?V&2xq8gYa z`*6w9x`c!9BMR0X3yYEF(K6)A1|F$CR&bOkp`f``fVu}K$BjIUHIJ7ePm_71`9#4H znm|GGNd@Ac=ngmHPn9uWG!RMj>4Kv~2?fz-BxuU5{3hJ6nZ2wEy0T0q-Q^`q3Ihk_ zl>#g9uj78nJQ^aF)=O`0N_PK&1RDpu%^94w4Ihbi*C>e6Y!DPH77*qPE zrYgk}=;bQtRcWG9*Clcglp#-+d8E3r;0RHmpt(tahP(NqVrto3hCEH? zk>-|yBQ$}6=2ij1mNPb;uyEd1hCEH?k>>V-BQ$}6<_-;t$4anwva<}eXo5$Yy9$oh z90?6+w*U=|gddO}_Xo^m@0B4>lX;}Mr{D-ppis`e0z?}haRG*z?ENz2X)=#AKPWgt z6DVlz(;yy+!c_KQ6>O1BYlZzKOAGT_;UfW?Hnn$Bf4r_?KKr66; zUR2%qzxmrsInp5_9rQd!j&zDhC+&sg$OI9YK(G7Ek%=NQ@o)b2T8`WxA~(=pM~>Vm zA~*ic-`@UDTn=hC@fHUY;2k;;n@!wXEjiS1?o{|Bf~;sh_e4P7(C7@Y>pfF`Y&K3N zkjN|njuMDMV73Ta4OHZrBcVnU70`Pn)M%svI#)uCW-6fbB-CiA0y14mMT{FQV$^CM5HW7Hh*7(JP{g?5B1SED ziHLF2MU2|+!y?vm%Sb%gfY$p+8Hz0{-aLl(+vH&$HLgbsj%Z*&p^-gSfYi;SnRaQ( zkT;Je!m@U zR#pZ8eY;K{#Rsr3^E|5qhLYfr(sK$Qlo$b}*Z-+!(k%ns(?|Pzx~I{*DtmhWNdGIw zlT|h#D$~)Ha3IplLLOF|8OE6mczUBC3<*yixPy7qMr2c_tDJ{iy=A5-Ttx<4y~6|? zL%U^kcuKE2`2DUKkCtLvh-EG_ke#&_o82fp%&aTnd9$b4Dp+rYTdhPsaW@#;(ny1b zkBt?$YiiG=_}f$1LD=LV+TElqWN5RUq4E?su(d@{MuxiR8-f05>b85U4e(6q9OP-6 z$rqLc1CDl7gn_2J<(u-IHXu5R<7{p}AwTCJN4rdZ

No+HDfl_}e1)p3RnHaSQu> zW_Jxv>KN_&M>^MeOY_ue-h7Ow20my9n%B$CNwu`EH6PcOodLD>p_5=j+BT&Z+&5it ze>?DcoadaB@1xdyj`NrS&Ode%Occ)1V-K_gug7`LNzMOJm)0mpSI?6oW~4se%MKHqi~L`$0O~)>v5iQlJldj`5fml1Dt>6B)Ca9#|Gx- z?ZE4Co^z7(FIw|C&SM5R|I$f7KRnFeY>fK@RuNx~fxI5?A}g6c)}GOE&pBZKxR)Z2 z2IKyKHTl-wGVlyG%*We`w2Q`A&SanIA1WZiR$x%t}ACBggcul9KVCTk~1Ya|T#H zWhLlu_S}SZOiQQRkz-m{Ny++|)_j)roB`I)nh83)=~&&sB>HVZTF>-On;!QKJ5l}T zu9Gr$VN4k+)%ojFFpF2`L^*$PQqp*8loQwL*XyKQPdN=4D(8jkQ*g>z=0rJvb5hdq zW|R{Pj*Hhxxt?+wGE~k>*Qel=v&@NdUba$pcTJ^so9-ezF}Gi7M~+!4m6Qr|wKbnr zhMWP`uQ>_i)ZU4?{r7g{^;pkI$@*>o9B*gjy#cukAjf*l0PA;H31~#=4I`bEA&ob5 z_Drxl#SN3ZX4oLQryb~(+s;Ylp4pmDxHdAN+_RhnH;dMWv2k`g@Oqr*oaB5?Yd*($ z%mC;2Itl(xI!9xh+m5^*>p3Y|pVyktu^uzP`g|ur$9U--tH}GtfL@Pzk(S)w-=5L2 z&pF_KftNzI_YQpTw{Q&Tb@|U}$^WAEjGq6P1O6ZV=iZUYqXS*^b^+QF54${_m@yvH z5$&!dk(s3mKTaVa^|%21FD!*g_z4~HqymYgo>X`tMF>beB>??>@n;b_(2AZeLQyQf ztT4NdG*Wv;GlX1&f!;C=8U4E(C;jVxjvN190Dd^x%uV<>1P(OuBjniva^u7Vxj90fD{q+-WGr!mcsP6Mn^oUKq9Gk z6kbRX0#fe^K>uL(v@i;VyVtd4%#&jx39c(RLJ}y5t{0%8c;)aF*#;f(^a6*}HY&W( zA_SB+2|(9icWjjyj5e1cPmOt`x250+MWCR$Re&bR1LE6sAnL_U`#kyu4ykQdc%elI zDD6~$(T?$Y*xRMUH>W7Q{e*rQN=GNAD820DZ~pc@9qmZb8=L4J5$%bOSYn5AuMT)s z8aPzM_Z40gkq{{22Lhm;pW3Gbo>F>#>O+MWO8orPegWX8Z!trDqywH(;82-9R(PSr zPv0J5Kp%bII~0$9OhEtsqzIW}nMP`#Y6iwji{qsNnN8i8x+kgJce~7C6>3S)#5cc(sMl2mF(a+bZ;S{gRin5-PNhkHi=@&aW zr^}Fg0V0n)o+&ueOM`;uSqU2Kic1>I80X56s~LHudA{IC%?1U{UnHofiw6TN5Pz*= zt|~K0_Cm>$y1+sBHwl{@%Zi!gVi9pg1B)atX@(Re4CF2=h}e;5Wvx+%w`VkIARgSt z4Z^Z2*5W2G$;R@MrS%C1;S~i;zO`&+6>Ad)lZ2lwS%vVVApC-W(d%0V;-Unj?2A<_ z3g;K5<(`ztr2SG!6xsoYLchwezGk%Gr*3W^EUL!Cp|Pw@I%bmS8zoE10tewYC2Vj?EG%04TV*K9>h6b91RklrU2vpmlO39C z3ef1lzy6Q^`PaPNfHCzQ6Vw@BBLIW%dJwmMV4)EUdC2fuCr4#GvQU6^CaGiM#4xmC z<-Fd-jO{LFB6}OWET+GP2ZI|;TIUUMkVWlnaxu}MeVuWwVkR=U*~?-YYYQ8UPN$+a+wMk6$N(X=g_jbA_2n!aGZr6b25$yCiHR31bM~ zUBz5sW|HuGB})ne2jM*u*4I6060aCBmhLs8u6SmX{QEUi8i-g}_>iH0oYFOwUS*9x zag#87|FGXim`b$b;w#U+)r?EBPA@*ayW$n< z{0h{23gC>m-_eQ2H?xkm$p_)siRR|FP>tJ1~T#P zt$2kzAt67v0*=lY>L2N!8c$IK8}oeB7w%imyh%}SGCin3 z10(#BCd`COs-SN;QpxH=B}082Z zK<&vf!Lb-drwNr@rKWN`HC9%mAUY39^0bjgbW(bj4O~Q{ zxk0VF*9wgq80qDWb!_~sG{P+xDij9$iE(tn}i zDS05F{$d3jr7sPng_j(}7(O@)nR(gHP&)z#wqB_zU6bf_kA2;7vkC*?t1YN#&* zyv#-xU-L87HWL?CU$3c?dZ$dAk*wm}!KxP27*=IAvbx&OR9j74Sbd|W_6`h={8`UA zZx*N_9{F+e@s<&d1u&arWRvl?Yi41%!NTa88amoHW%}^sH0Z<2J8iJBOv!xY?%kGL zhRwu=-?avLc%*A&`fxMfC({^I){Tjc&dsLVR8f_g?5`gyt5F7>2L;(+r0MAz=~Bf& z-ESNNIaVQxtW<%$Q-c0*+@~3`dbRr3_g5?o13jhw5>3aO$FFiGYiuV7Dl%# z=)iE_&*5< zn){yS4h#+Q^o#qfJyzJi5(9}(w)PraT>$}&^6z6X?S736>t8%5L#Dpqk@o(A!@7)u z=0^fFFwp!ULf&HfxQcnIiAk~tN|w+KI0zq9uz_yAw?(HuR0n-&=92a&6;Fu+3H47E zkefXE-QhCiD+eCw9w|6Vl~B+;DnPW^7;75eI($}!JWb}2=H~@RXaWVzuNc%%hZ(3% zH9t<;Y$0OVa;y%Tx{6E6$15IdXC&0WmOwJa>L~MxI_Rn=E~$T0@uYe{Lj5EIyT;R5 z9eS>X{)W<{TYqnbql0QoyGTJcelX~4M51Bk=M1LPG_WF1?wqp1!ir%>r6D_~jTG5V zM#Ijz1n!`k>Ehpkz=(goj71-M6z$4H691*(B;kmH=&uSi%;$`8EiRNXUo;R&^tXbe zL`njvGdslka%Y zhaQcg)9Y7l;7#;ao92f^!#{+(R^g^J2`6-ncH--6Jko=VzuU;p38Ni1HfwA=LImV( z|96~HQyGynnj9ZplKAa5Fqj-4T@vmNjiXN2Av@ijRyfvr-O8Kh({z@Qf~x*5gRW~o zpm70aW^io(9kSESvckfOVMnDQJF|@x*-l2o&fEm~u{ra;IBd(v))QbPtp;uhTtf1FKHA zq{4Zf?jaj#bh?LaWZmf=v4K^mdsO474|K{-_m~xqwO+S!)O$)n4Q;7G*R>zeXmC$v zaBTmbveP|fg@qNvj!Hvzo;FfsI~ff-%M*A))#+B0vFM}dbeTxvD+^8%jwpyet3bNb zJy*tj(bValFE~n+JKYNkRCKx*t6-EZJ6%(Z-05B_X-YYDx|d6s*XdrdfmNq_wZeIw z?ll`}bh_7VWZmgj*}$sPt=2f|0~2JYd&3IHTCZC<>OG~PhW4gG*R>zeXmD#XIJW-@ zveUg|g@qNvj!Hvz-ZfHWI~ff-n*(^Dd60adyKi#*vIuu}TdG(zB72=?lKj?^6|@Bo z!rK%q%3`Uvy@>dtV3Fhw%}|2ztErs|62BD3z0Iy7;>&?Wa=SG{$;BtE-V=}^`dM1s z$l;6VJw?Qmi!74cs~JMB!JsnV7m(&W4&-o)@Ievr_?hW?q zfGY+LX?>*dQYtDPWWZ2AJ@0tS^uBl}9=@=#k&36(frR=|4eVxhbk5J}V2gU>lKSTrPpdabsDH)45vux;Te#-Kd!~+6 zK~r2(N&9%oV(El~^4A4yV3;?3!jFQTu;Oj{oPaERV{i)>K*Pwl1vvY_K=qvwZnF{T z+4q0~a72lRu}MzqBO zv&q7lnyD=S3kzopXg6CxXE+bl#jSvX%a3kwYv7A`Q9_Qud7VkLwg@mn1=9Vjvx zxLEO6KO-T3sR9mnb5lSiTs8siCSnTmam8X+RvJ9qTrJ_*4En}3E8glQTlwAKmQIq9 zJN_T+iqLjA4N=W1Cj1qfhj%)N=%!gwHUEewtE^;HMR(bWk~M7r)ihI3Xj}>Qn*S00 zX1SO#999X*<7_XPaH)ClIaknvN$GH&5go&uNJ6gW*9n9l#=^-0hBhbSDS|(uwicT4 zHaBG=^0UZF!j2Rko*vBbuHcFO2v1AQc)KT^h&(-HCCQ!y9-baeaGDaDdTRa%Pmh`L zR!>DD^0d@Sk~~Q~JS_u!aAa^~xVfgogMEDiyki~CDlNAW(U!Qcu#%9W6(%2!Dh4dA zEC}6G)ni)E8sTV0d}EqZM>;uqu4WcC8Z10KUqFWkh6eaIRWWkEU;^4IC8Z!IFIw!v zOTfd;OC`KFnZd~YvK4Rj5)+V>R}60Hq(Q^Tt0lO9@Q)Mu#CZ6z+1DIMtDT&N9KCL5 zC{0BUe62DlHzr@WiCgVJ#_|=@kgqrF42G|U17B~J6l#{!dXq8S?!Dz6Op-hog9U^#DclC1!%|X(KaKIO*XdG z%)&&2g@x?}wEzF-?p@&QoYHjhovJ!>oH^$IH$A3X&zPR-Ze!AC(mhp`%EkGaIVyWs zrE0ovYVVNllbNklRis9xs-`YFdQ49c1VKa)1VIo4K@bE%5ClOG_aKP-EeL}1Ue;RQ zyKZ0AoS8YJ$M1()-}^kzdcO6o`*+#;3r*Aq-5-diSx{`Su)$|K77$Ao9&n)ff+_{t z7J4ucO|zibVBsO3=~zH4S=i`7)thD1%RC&2rd!Z2ls)1zJqzkpvPT_g9sE>JvVF8E z5KXh7*iZ_O`Ao+GVyP4!cc7}%pg!XXFP4@)F(LEKF3ZVU)qtlpET4xx4tRs7{)^NVi+N>XTp#kNUKvHj69)!M9=18qys|)r@R}b~1}1SKh?N_a z0%@}Z*m&KeJ1zi8Cf-bd_0w?n3SU^KhCnXf3PhC+<-)ZgMZm|~zCdEcV9CjQ3AB-& zI2YypAVAsiE{i1rPCf{+6E7l5a`T}Fw=T~|p|G+NyFjXVseHlE#{mh?kG@QwCSdre zO+nwWql@&J7gI(emnabc7du^YVnN}kIKDJ6{Hjm^8k49cyZm6P11SL(zVhhCgF%vs zx!t(wfwjE=wH-{zTS!Oy!E_Ts0!$p^(GwFINhXdnK%C{k18eZYHZ>TUMI0Z9DjRMM zm25C@g3mM#lAOrGdZ*D|C2nPlRY3Q_tOaozfL^`zdoeCc*0+Y zU*v@Rj4c}EdWOxQEE5dnw^%}IYIKHF+-JJ6XpV{qS)S!^WS)qkOwX2}I{noyekf~+ z8;fSDh>+89F zGudGHsW5mbY`Kf6oM=G&h#7z`bwT43NBqDVfG%@E)pJ_m^Rvbme6&b?Z~F2u(zvVS zr{F+yMHrcQtgO%{dqo(UIIT42d}SC4pWs%PqSBoCRbgmlRbti@z)Fd&Q_WRoC)xGF@XcWL*LbRi$esq>X;f9G@RnAJX=Mx(X*7-?|1XD&%^d%aZw07L@b#F05Dy z?*dpKQoq52R2c}C7+l=d9t0kOR4RB?0dk`UsWuS&z&Su}k`SzLG$zp^`(`(!i$KiX zR2e8D6u}yYBufBMQ~_A=7n8IQz+lA(&>b!)X&V5*Di5GLU69v`_4%y}BaJ)EmCy37Ff#FoP(Ina!_dSj zLiwEU2}4CIHfO#*43(|e6u`X_TdRLklipgr&kd>iBqlhjIw>Ahr~4g_tWJoc>a;1VM9BC} zhoiIAD9ZFL0isuaXjH1AVd-r*7Ryuwcyl(zD^7)IKDK8e4XS_^23AuUA>)Mo$6{*iJcq;rFpZYz}(uhR7E&l;0UP zB-}O^J0R0IXhddrXT~tfrZ*ix3sMODo)yt>j2jl6!PyQ;HxS`%Nd%&-d2Il#2^ny9 zPFTS)ra9#6T!)fWKz2rxr}Ltqv|_WQz}?cAisLWgk;C&Hny!eVVpaGYrl`C8^s4jk?pHf@t@+eHzG^5wNn^d)4#*TrE4$Cu`iuS*1_xj~Ja zyg9Yp2`L|5rB^h_|5BSF@aP^= zuQRQ3La{6r4RXBBW{3{lQ}H0rTOE$f6H%1sZ4#t%r046` z+JR_(#DUyyx9~DAmD3#p0G}J;lcSb+rxS_grC5;JI-4PKLkykRT>{e9qOzma&fQKV zmYrfjcK6r}ksV?vyY&K6_#0hEY0+}88;WJ9d646M4o753D9ZDG2{QGC_Uksdp=h2- zeR;s)$UIGbc~F8(yP(PFLvARVXVNYi^ic~h^HNvw zaSdpJd#kxZwpM@no$s$c5eNq}wdrs@H~UPTy}*JN?CeQsTi*JT?o)0on!6%G)=xVe znJ=O!(=8H|t83G_QiFNM3r4fmRLJ*PmnAbM9Oe9+gcZ!`QjL1vjYacSM9B69ha+=E z6lMCN1l1Mv*;1u?$&E!bRYb^itHY6*B8oD7S%L}$_1HX54qkC%DpPwFhE+uoA=6hK zj?5HMl<77HRD>H7M-Fuj+B*lYxhT9RAzO5~gmMZFgbS z6#|8KSny8Jn=T4&!X(Zrm9w{8RFyo0Zz@)`k#F46lEQdg@gBMti>xS?o`>7jJ+1hJMYy*l1xqjwwWTuFsJa;;va2xpCMOhUMYvW|7 zj$gPa`1S6j3IPb_!SDef7v;1kfT7qf32QNZAKv`>$_+)Yf#Lz@YlkBX15s2M-$)QF zH+iLsSF&M zd<~9H^aKfm1)9#8rkwM=U^Hh=#O4ZNcPDNFq*lhLf(s9mdu)P zl=B%92CF!oH7ybs`@v||h6{P0>G5RdjHKMpvVg65ojWZT&-R1y+%*?+U*hqs+zCm! zpJM^1Ow+m32y(6;jOVVoko$Qa&&r*Ul>1T(sPm@geZCut=gd6F_X3Aw*k(B!i3#e;J`B++NUf~Dhxoa-uex=8=a!+d5RTfaU5O~52 z2d$NUFrK^S0`F>%XXT!>u4^oyE_dqDu60B4oS6stu5vh5u7INQzCnYU>ZY{7JFP8s zEo!yEx9(Sm;=#-v0Wff5fU8YNG#R}&`~Bz6)s*?A}d7pA}?NA>VuSv(tq@pMDB5IA}`B$8MXc=EIWFts=p{*#4gqVjDAnorG8O?oZ{QO?w@nYa$P zdOo629$}HU7eXYlQh6~LAJG*mfTfp0?2sRBZd*Ngee+aPP&CDRIR;6$l<0t~S0Wmo zF~y>SdNn|5Z99;QisruCB8ZWkDHSmGT38|A3pr%#b)S;2Z*Hw^R@abf*BepL2;LGY zaJN0C;`>uPa`>i4%SnSYwRkIrN%xlsfxWjQ8lF4FB6II}q-;aZyraou-n%hOy17IM z%)J-U@XRR|nS0+O<)-MLI^i43AA}L<#86YfxY`j`@N6-Me0}0krU+luJU@*<(tQ~j@by_(!Slr&^7W;m)Mx9a7VGkj`Bwdy zCN<4nVSqBF_TzL1?rMOiuY!DI$zqVBuY&~mymj*93@O=t6K2bwg-Bt~?eT)@9uqBZ zjt+&xm&cr!zTb3Afa{lny7zRv0q5|l==}Q$j{ZqmUb`cm36~k#ZC8vLa zkCyoh{h%^4Nlo!}b>g#SG8j4CBibG?8_Ir>2jq)T;mo%j{WE+TU4x1$UU@`pE%s?u z*z78*Q)y@VwDClnoJu>(r&UuUuSlhx?b9Y84Sp1{v3&pi{et9rxx}YUL|Sz^?OdDI zTGw!pdTpVSCI;t);;Irjog-Z%BLKBvX@G0nXEfD>^8?^`gOu4^5MoA~q+~9$nbWfe zwdERrp(bwB0xk+8Q~`u4sStr8xH!nS3qdoe7?#@v_(etdK|<>zgqMa9DVBr?Sh_68 zw=HP~Sz2KeTH%4LY`v)_{GRd^F^sYmtSV9nj9nSgu&pK8lew!Rq?D@TWV%Jid zNi!yOz}f1EhGWgJ$lHw$skQzW@HG&%Pe3j2rU)X-b&ZE^g3xhQMzblGKHz<_A;N3A5&!Fa!!FvLH0nx!=(F5guvcI z5e?6sVv)H=3@L|Odu<0#%QvW&L7nfT!Fbq}qX3pRh1kZA#FLrFYm5wIFARS zDMmCKm{0gj+XP|B!e$!^-I&==p)TynU_8Y}q5wvo3bAb~3QuO9cHk|E8M>dhB^XaL zV-GaO#+i(1`PVAgYY0N7IsJ1rRkGY`owzZ4-ng3orW6$W+D7 z;-vsDJVCK}TLU~=^LR@hoAmjynM&ZfK8#X*YwZ)VS^@H1k@f0(O0+@L-#J0^SJehgRhG&Ht zeo5i&ARxs}A^~pR39)TA3Qum{wc)KTt!-12QG#Zi??oUfj-(8DdOxgSyD}W|^^u{} z*TH89>)Oofg$9U^Lt$koxr3-1zbyfVb_D3gjX;x?&jh%6S`&D||57JJUUmlKDP}AY zaPxUcK-fv})%5Gnp1~@t{$hRG729?qA zK|**O@v}Q2%nptwK6}2yhOGjwzBHVl7>K4^nOen$LO981IwgQuI{lMvXkBx@MLp9? zqrrkuSYHhDaDr8dj06}tB|x{GFq*6^G~lT<^;2*!8^$KJUZmQ3dKeHc6ITP=EDG|C zAB#bb&hQBJQ}TsIb3YQNp^Kv!<;&UK)wu{IP&qTE;yFq#m>|-tZ|;F0dME)OHPjpE{!14 zE22?>%YA-W!MoVZp-X*%M=4CNt8LUf%rud_Fp5dHCX~S3vY3izPxHv&MINnH$7x8W z{^a5~DBYse0*{wObv%=XNiHu>h)|WVlY!lV8u@jh6%mB;=hh)t1#8fbM4lI|_h0dF@( zG(2yLMc!`mNQJhXeyxcHn{R0;sxscDn7gVTzR?(jGrU)e6 zrjdaneJrftnPUzW?gbcE@#Uo(%)1aTo;*a}169uIk6H?&q*_euFPxHv(a~`d(zNtkwUg}|< zk3iDh85!{QLRi6b#vJnXqEE>gU*oA$c_{)J!Izc+Ut7ZpzAxgCua`YawlKZ*=V}@> zo;r_LVwiMii4a(OHKO5pQ!Fy~dO~W;(|r;6(PRDQIhENP5k$n9s{+QhhZPcE7Kd!T z=~3zvTU26iMG)z>j0)I#JFMW@Vh-7Q$D_b65$e*Sp7q@bBHflz0bB2d6+BzaAzSZz zl(y-0b&dL$I;bQ2Ac{%1CX~S3hcOk;p5~Fkk31Tz>l1^tCGv3;lWtHbfx#Uy70;mN zk-^VGG;=F}7N0v~5N*$0tf*QI`6wZ<_jyDlcIK&ou@l1z#+S_@TPJyx+SZ(2@!(qG>dr2XgOshn0|@~+uy;vR%6RmQ zkkREK;(=gPZ8%Y#yEFWmF{i4oX<$>ZnNYjg+v+HBpgC_*%*WK~e4 z(4rnR=XV#bi-JZ`m6aA$(OSXd_qUB=6NxkrAtMB64F?WW=hRh};wv z8L=uSA~#1xMy$$-$eO6gh*dcexg{zxVpUE=ZjFkJSd|lz+Y^x*e8i-l{!7y-8aeI= z#!U^@-{jD%45k|qsK0lH1d_TdGNpQZw}Izc!c+5mA_(QlSw(s(U}=3=!I-i+Wb0m! zqNmmBBRcnm0qLf+26(zZ$oDKIQ}YcT0aiHhER&ic(I(CVQB1lop#;_*jH!6;G>?kx zA&&;Xo~?g|l2#8JBZzc!Mg^=r99Hm*F^6nD;!#=(`Z|=4r6t6pF-W?xL5jApIC?(F z_Z$&}9KGNZlFp-&dXE<)kP%F28F2MdSi!eN9P+i*qrhYEs!!u@^1mELq`T50VCt11 z-}6Kavh=D?_(g3&d!im=TLdzKDJ=u8UJEPuwunQ%-Y^t=I22cYS#z6+#_sK5K-iS4 z0iNCr@{J{nL5|+?2u)4ai%M^Y0qKsk1~_^r$oCu(gB-o<5!4Hqd=nWr)!vIi(p@Dw zpz(f0!*ixsMds#vq*}N+n7qnG-QI~&P`W)K1^!Nosdxr8j~t%t z(HinCEx9%|x8+|NSP%uJI}}pj@RXQ}=TP&=;i(?2wxv~dHvI78X<(&*RWt9a@RNj#VwiMWi4Yh&BckD1Q!FyK*dxKdLSl|K?9Ys0(#<78VD7Al zhG$N($lTc;sR1r_1Kf?|_R5bCE{UVk4N5VvcurKuGijJ)^IVVEiWVE1vn@@nSUabw z{-ugK!1G1{Pd6Tvhcj3@va)w7z80O+`JPm+rchItbmsho;RPwM^mDM}!25-9CC_uh zC9lgoYJF>4!Bk@2Z@wrBO7|(Gz~#j;70;vQk;6-TS~l@VQ?%s~$O!JV40yXVtl&E% z4*9ywqllR!|02=l5lFf(BLluxgcUqr%pqS_coh6Vr1>@nf1~=!C@9^VkOFsC#Z)|h znnw;-dNlavguWQ?-E!(Uua1J!9SSLMcuh>jbEtXb@LG=spWii=j-P*76~m>pjxJKcAMEqki&+7$)6ZA_V4EM>IThibdvbwn+H=1g@C%js`A@*F+F; zXO;>m+!9u>d?g&Rb*o277TM}c`M1R&>BbTraJDw0;aQW5_1irXES*(}(X{oBFd*HR z)&N&`2Kk;RVo+(V^9a0VR;FmlepeKe?n@|vwYy^~o;%GWgZFqeUN|d*G$^c(V$ux? zB`|nzOvN*(d1UZDkEU16$|7xL-=Bg?H)*MX%?)uS&uGFWs}J~8{5}Y5GbpRHet$3p zHG);C238-6EBRIpm#l8|sI-7qK6&x}a14{~G7$ock3=*)e~Lxs9`#6S^{nkt$Gjc#bgz~IieA=XIAk~dL*@k)@4Zj;Zt!`x*{F_Z(=f^Aa~=^F*4iU=lFvsV=?0Aq zxO*Y2;8|l1`Fhc(w2Dar^*1lYFe5lKLSSucM8o&SEHd}9M@lvd;D$Wi8uc{nxIc!gXrCYS* zz~!59CC_NWrK|jwN5!>#QxRb;^cUa7p+5WV5y9!c1JdCBosm?%b8vO&Oy2cmXrnK4CsW@QyE8K2?dY(A=gjEB-6xN7@HAtKI>BSZh;&z41We5f@;y() zprSg#5OVY+Uov{a)3mseFh2}Xj{K+2T^W!#F(_e7Sqw6Dl0!&FO&ETujh-AvjNmHK z0apux5{@f5@}6c0^mruJ8UBN}`l+-QMln%q0WolQdQ8X|ba_;Aiw$jR8@@}>T7=L8iz zQ^X)o=X!)(YlHs592%X@3nP>%_d{UHk`@6=OM`sR5;4fq`5pn@&Zaj)`Uauq)0F*! z7)IIhUjF22kO+aX3nLnyHN_%x7aI~aSgiigS*T8xD*q)Bgm&hCV-LF=DFoh@heeDv zJ9Bb&sZW7+tDJFvaaja1vNf#))-Df=_|}L+)~+-ZXccw&hF=!pf2xvEnOzkIM18q3 zU~6Si!nm>+Wa?T&$kEqM;0Z7Kzq$uVzE(vsQELG)aCcoy$QX2a+xydCO4;n{#-)zHlpFji88aI}nHE|*5TO695vHH=QTMei%y#n3<6XVKl zZYY{Cw)%} zDsf^DSV27~iS=zg6B z4+W_QPIunZ+n53~cI~2-85%t>`*2(;XqLHT_K`R>{F+nD!=oue!B?GPLYq>Ag0DNp zgdR%~3cm6b6M8&FDEQh_Oz4Req2Q}eF`>;VLc!OcVnR=*2nAn(iU~a(6q-$xSB><;PaiRlIPPf$>+OKqUr#=pE*?5)yTk38yI*muEXu${hm(b zMBb0rmUTs2ZKl$8jBM z`W4=fDTe**i0jaBSK+?B9x0zs;yRP@CHTsU(Vf?)o=zLK7u^l<()qI}NH>@8wGdKJ zRd>czyr!ag)Kb0((@cxzJ&`ZtDD5%Uq$xKg2R3&_mBK!eNk+el5=Us#j)AY^I_XW? z(fKB>lis8qow@&@_uO<{G=TIbZD8D09Ua$6Z_#&rChh1P8`nv1(vHr&xK4VL zc65%5>!denN9TA?r>4#P=zJCJAf6C`=%x~G&PE1W$^5W_*F=~@?c?Nx0=tH_P4v;O z2Kb^8eCtNP+Dp@(1?fO#GH~A^A`5m;NtH}ohZM;C!bG6927codwyptNX`Tk9+0W^5 zP^4r7THtn3R3~xjGRfr`J`pw|g-g2ni{q#fYzi^3d1h3{x2c(AbBQ5N&Ejtsv>x1+ zJGhy*eR#wh9CL<6<}P!1QTzcwhKx+3kI zn)a%6x;)qzLHgG~KU! zARRbb=d20NA57ItaSjSp<`0Dhl8<_pkEJQi##G!Wd?$)v`{6XTuxrI9(~pGd_E$q6 zje|yEH~D_(rl?NXsQHrUV__nF2!~oDe}Cuk6xb+?YB?y?C*n$BtHh-eeacYrHPj;f z{11Nk6d!Y;;qB>AIBd@5gR3n8uCXJ~GVd()-WL5h}HlvF9-Ra9b%B9 zR~!QTx*gXM8dhEnMAN(|HW=CFGaVO*B@3^4P<=vbXm~vgNH?N2z{?v!zGo*XlhIqSMAN(|HW+!!XF4trONH{b15Mt!r}^|dp>UcB%?B6n2Dpw5LX(g89I$!8 zibjz41JN`W$y-$)_)N!xd6()V2ij=*F@90*<4|0=aGoIKu1O0(S?maK9Up|IviKwb z=B;Pv9-)`bry(Y7HdooJ2aoxg!-TCIwU0x+*3LjU?E)w|ocZTI(>Za((s_UBK*oiQd z4V>E1AtvqUJGbaO=CKYl`ORx;{PO}~Roub)uIOOtIG^bhHe#u)kN2S|MV(}ELVy=9 z=!AEY;o+xcqpRJM(_pF)oYolDgVI=#qGgIDz^3v!B}~@qQ+SpbCpV|2phn?VtAWyK zaiy@=WVO36Otn|Lr^i8~Fq*7(7e#f#HqC1Hj4&}-Pg0LV(~`v_K}X@((uMLpa|F$> z`$UB*#aR)NWM!(RG-sy+N8>-y1oul)^&;NoYWJKJ0c*8;ZaQ$Z&dqA~yi~mu=X$lf zG%S#;P1S1m{8Zd1d?$)f;1{H+g}ol1dwEZOHhG5A>!5KC3OCp}!^uQ9k|ca$gE;UK^1y z79AF-XU41wlJuJ(eB1N77-m%dSPT4JACU?A0~Yza(U5Qh9Un?;YQ?uzk{y|wA_!&9 zdqvCB0c$shHHCPHBC)`*7ZO|i(_Z62w% z1>d&Q?|?xop+))HG+eq#TM&%io}%TM6>Ktmhew7cpR8DE0)J-=lWsH-0+Z_^8lFML zB6D|pBzQXH7y3%mlK!3uL|Jnd7`i$c8F02ftl$}A4*9w_ObISHLRsDy;fEF;A^!ay zKVPV6R6oR5MKk#g5lH$aGcr&v4}=xGa$ydY%R?RoI$ra#DSv%&V+^C5IV*5|`iT%& zdpM%uc~dMh_eg}4dey9KAB`!bT{lZ%Q%oVWLJyw$V=;x$NpID+U=&3Lw-I5joOHT*+o+V=W7pY z#xIu8ILIG$d}bu<2sS-oF#PNYn!a^gg-+r*U!*0MOWf1LIL}8xBiK%)!0!t&72l}h zk;4}~8ten;-xnB9H-27tl&9g4*7aHKruI9_@_=^i9km3mE4JWHLMWu zW$wtlZYcHHY<&&vcsi4^H^KmA%A1q9Do|S6g9^r!#h|i!%O!{p3{=u!^mZ7bOgTNi z%D{+#rFVjS*Ag?x(z`)Iu%{1X_gg5CM_rvT^4a4PE5dfAh$N zb=K|+q3Zf81vu~H17!Ea5lv@)LIBLC?!NNngop%QJj(h#Gu()1xj3QG>5*del=w)Zh!69`#h0n#_6h_p(omKvZQ3_o#^s zRF{Qe1-Hh?Y18R0C0p;zniho-sjiF&m^vfKcRewK>hWTq;7pj#3?oLcluVb-3i5qR zX0mjyAmm#c;hCbgLQO8G#zX4d&Wk~mE5EI~LQqyqBO=0@#iH^$KSGMNeM^Dw*j^Bm zi1Yygi3?*Ak-i`xu`DJL=@SAH7sVtZeM3Ov;+RCFj|fOy5|fDZ6#Q<54- zvz^Ogkn|cSgrLS<9uaYCoMustTM;3p);O)eHSUU-L|TorC9aG~q}4cE;;NWLT8*maKYMd=`bxb0y#@Q0r#3a&coGr1+m6%?WEwr|%2f+B2%ylu0s&d|ZmTI;Tf*N;y zM8mCdnngA4h6pJ#wF_jsI;IewmMq-kK>7EP)p`jZp;;dW zq!~#xfPZh0@7Pfca&(_VFnjprW9jbk{lR#eAEN+vHiX!Y8*vBV0S9ijap~UhgMnz8 z5yb`@5BW^T1Y)T?HagIntlHeB{f~zO(KHK+4Hh2pnT`d-l7&YdXfxcE<|;y+&8AQ| z&4lKIi^l?7#|ELv$KwvTFdd#fU?Vgac_J83b7B<0%H|N;@xpjA^P~fxfDEe;&^#9NdZ+7y2#7*8`}6u`{0A+}?N@nq&X2c9dKlHo^& zpAQ1k+!zUP^FoO2xM4iG*=pc;`^a>_$$kHq!+@|IR|EXK667007K0qU>JezCUTxS= z-@h#eNq3d#fUnmg8lE%7B5$vIq@*`jKXCL$43h3G(E)GUBO0DJIWoNIkqRwp+@_J? ztzbOel~MppZ->~PAH-8Zz2m|8VMOi$Xn1%x21&P+=zy#DA{w4C#UgL-`y_hUkiF5k z@j(nSf;XcB-ad?I_}-XB-aZPGYS|l&Cm+Wkqwq#L;B7}lBkZk~ujwZq3GQ|)XEeZk z8V02M(i-6EvmoE|L<}meogqR4yyTy2Qy-Mz{rxo9i0*_Qc>E$oE96wO$?umQd5V6` zi^ic{!Fakur2y8x3b8#;h$k~&dvN&LGyG6)@;DInwcn(`(w$jy;BW4bzCoZneS`2^ znh1M6+M_1Z34Y4+m@p#Up%wvi#|HVHFJe&f&GQIm_FGB)?Quasx}jtWe0+%Q*)h}L z6Ac`G>w>?jjmtLm-~z4NPKrUomV6y3rIRBX#+bvRl3L)CV1cE-z<{f$QzD2FoM{zM zI5n)``yvk6I?bmfgRmOR7e+B7SWA?^-03kD-<}-M7x^?=d#RG6N_IvRGlIcH2@Ecd zsrUvJk4o@Np9U3D*`qQ3tO#NRb6N$gogG&2jS+`zE%7O^R#UcUct0nC7{QiS0bA#W z6?|L7AzSD96ur_bA4?gS42T0I83C#;T16z-=X4>!>bJqrv?Rl@*IXQ`vLT8q8Mcm z9(QuTcN0(plh?+Sj7gVACRh11n5LNDG2!2ZyDkb+F2_ebCSu_6`k0RIQSr#*4L+@D zTBGsEKl;2n3eq0!_kK-jBvRn;#+ZulQ1Qs&&4yN=4PWRr5ri@qxXhjs*t;dHV$9hb zvUaOWNv;SyDn#x0wg^NQoO^LqE{PC0TN~DJoyp63yGzNnz+R31HUrJm?}$K@Gw+55 zm3<-uzU~YwxV{vJN^G4+F+ZWhRqd`IK$n(X%~V;YXDJbF6DaDW=xO^fm zW}NzF$n8@J6-TV;b?nxDYrJsU@j(y4j>?765^ z#HoG z`d{rV5dv%5A{w4I#UgXBc_df~C3`qDe}6rONjH}Wfw?y#8lE}DB6Hh4Qr>=XLA+P- z=1ACdv%WBxerp6x&%C2TC-Jr~l04C;9}Ija3L3$7A_acmjj8xX--4RBNaLtqm z6v`(-zE>ucEfvY9KEZvN@3RPG1XEfDT8 zG(2x|GkT#%$`_`oce80H`t&d$-Ivw?SBrvt&l54Iw9fDdEd_28G^wEd=fzP>x-X#w z*3OKnczvri*(oI@wVDo~wl4msGlGO`6D$Ijj;US-R9CG&QMk33%I)38@@cA>A2qqIwB7e{*(Vqo%ysE+SaGs))a zC^5P~q06B~_$7%O<0`RbN?~}myck=MtmDxtsh0qq_Em4drFK3S-pajKr zYfQzImdm5Uy3M0attr$RgR}*`Hi}6%D3rk9?J*V4pyrXmJ3Lxz{V(#<@@kGko!*^M zOu9j#1P0f|R6K*4M+Vm$8hpzaJ`$8XVtKCoP)>&0;*~GD6kOV!U7&=35l%Tl6nF zk#NZw78Kk|Hp7&g_-4gc8xkxvDfzO450#n3zvAFSB_{E&I`~j|N&IUD4^JAH?u@@i z^|~7imsmoCB74K(m@-o+s%zUFP_Wc2**9HAsN5{ZTP`D1au(xlmk}yEi}Cp|eDtO! zmo4IFyc(L}nX2Y&?O6TCPs+!R6^Xz4t8#!={-pe`UV0UA76I9`P( zbsXuzD{0Zfv(6*imIcy$B;{&GO9CXG{K>@1HZ_bguN**ub}G@}HgLYsR$J2)C)-yO zZpl^_^Fsq&?XxRFS5?G=1tj9ZS|Q@&N6@bxAwFS*_{0(7lOpk|5zb%7W9P5qvGdpQ z*!k;t?EG~+cK$jZJAWOYgcW%iR+Fi%4K1UsAc(CAl^h19!~)q^AQubN#sYP*z|>fv zJ{D-e61WOW0DkRov;_dr;FX8t!7C2OsUKX0`Q)46_w}rt$^*G)#;j&jHdM4!w{y<7 zHUu+=Y6k36Ti!c$asuE>D{JV2d^L;4|WuAJlH|N@nFXQ$AcXL91nJcaC~y8-N5nvBF8H$0(AxOm6eg>RgvT4 zBgd<;#yzJCJDaWimKXT{MF9pTSX_dUK&;MG#wtxE72=yoAy)loD@2;0eVm-&_;39Q zLaqKX@mu}d;P=>HsV=W3cMvWda{o%xld)-^phc&{o6)*I7u}~j>S4=>^hL3D5o;Fz z(!P}Zo~Hf6toB>(_g~)k!}T~vo?kZmEk8xNBo}GRS$ewkx1bVTp&dgdnlcT4)9bgu z^mW>F+EQM$T$o(_2R7FKtIB_yKE-@v%|W%_`il~tA4I2WG)S)3r#QZ93hb3kYmV;9 zc$YHPzfQn@e1q1lE&NvWXr9zrWwX=$jK;wSmYbVv z8)^5=D{~m@_T3lvv;p|Z>={tt#7S2n0I_@ zy}>&2Tk8#$R^M80(CPkby+zv@tg%NFkCR8ygT%@I22DIJK8iLPCy$~LLC*yb9nMjU z7U+BfcM<->d*A38{y(VgR6ysM0#cI!x?Pj6ZLH1yR!mDTG5#A{;LB*ahJzaN4Y3*3Np{x4rkhGz`X$=m;veYWdNS;9@XX@!~s7G&)~weT@U zeZryygG+ON=NJ|Nv`o86i??K_x7F4avyHXz%Mzp24HwtH|7C(MD z8&|kdNBclJ+im)6+u#S03k}po{ma&|u|A)AsqI?6wmA#!8#^diA=lMFlmE|Hnjh-Z zt;aia`P$|@ZNvVyoH8`^o%#%>z%vg&|5silssg)Eaaz8nZB(Nk0fSYFBEb=gBEhKy zMJD3J^_U~k1)6|MQMwdECas;Vn0##g|{p)8b4(-;p)gCwvhVEaK zS5BM^L5|<$$BX%FO=E3kIl8cj@b#A%x~jag8q6utd$hTOvMoh?D+|h@siC>Nk`ZKV zy~H#$Ysh{Rl*YY*c+K?kD%OBAyH5giCV;3OU&Yw~W`o8wWB#ffCt$feARFwMr_$ax7N-2XGsMxGKg?WEkQe4&uf$ZodTgNDx=exJq?W zDEMd)I6(oa0NLSV5?B>KlgEQN|4g0;;`}q&9K<d@~SKLL(D5j*1->yHMAYrTV9t}f5B&|_0jtF-p-z`0TWZ{Oj)Kh zGiJUyEwty>+G25R!h)mZK;(xb!S{>BY3g{4iVlXyMfiIci;XSK zQ}N&Op1$70=s%e;KQ6*!w>c0l=HT_De0iqi&x)|e(J-YspBXbw{|SXQ2$;##Q~VVA z!pxWJ@;_ky2#8FqrieK^2~o(I06miPfzG0` zYEov*uT?gX#$4dYKdM~dNL6L^r0U7zCsxDZqf{1fILTtas;cqhCskF9pE!9!^`uD? zCRa>?EdCh_63zt`CQN`Y?T*0%crtKg;)Ds~;n>l149^CRRafm-z2C%1Rr^gCh8ZqJ z@N6h6b5SZMS65G*1U>Df@sld{n=qkrV&w$L?1V9(U4%`eyj6VjlfzCao|r_!g?Ul} z7-gBBk}&wRsc274j;eE4C45>EPz4|hdSMbZg}`N>9UCt1GpNK&8R%kPEDqa+f2N3p zF2PwMZaj>1A=$A`Ulr(sR^s=;l$53@$gl-z{E#+Q7$qBRTV{LzSzW6!N?16 zi3tX-&TFTM6-iV%vD(5FNjP+!u1vzl%}AH&dOU$vxEqg?68Mu# z8$M8Ij)O;ayk}gYy@e{gTqJD;Y3y+KZcGc z;`;cpbUewzR7=d`_!7thFRaSnR2>@R=}MkJ{3wPlcggi7%6q2d2KZBtzc49*e|`f0 zmSnd5yd*PrOeS+Tq+q3!D`w$6r?#$+uI?kcTH8Ag?;1jE=Fj2ZlFaT+C7H=CINvqY zHfPH4%$Z#S0-9?s$pG&lqwB!o_MYyU-CYB@uECCh?*5@Z_Vvfa&HZgjW(H*T5~TF`lJr;#FZ;Wa z%$^Xw(}ah5RB7ag+J}Y*3HxV+U0p26?BQVZUA>(iaQz`AnFp)k3`+&y%1>wp&N;1_EL3EI7A8IGr9}~RL>C0NM9};YC7pty=6cr5= zDZJm*-Fp}u(Dmi{!%8xHL)Poy2!UGL2L`*K4h;9Vb^XI|*C5xIatN1XcFrovOqbyN zP-kr`;2@gGaIUR?&vj}Y93er#Gz`tOLGusiD=tBBwKb?5xFwm!p^{9Q%q=_AQ#&xA zEH}7>ka{GhPOBj?0-N2AV-#D_5m#egRNjN zmFpht=KN+kL`~IpT7S(o%Rxgu5Kz9no&U&ZE1?a8eXwq6=lz%M&6)m)WH$V>56TY@_CxI> zDK5#)b4xPijuh0De1DfJn{pD{adb&$F9!xWs=jAm!t8!5H(XgLSkD`Jp}if(*0`6N zH7|^88HVbtp?ntWkK@{GM6-PZU3J~Poef+djM{p91XbHg=gQr|t`oSG8!fyufbAm5 zl+R?`i4HK^Gm!0R9~^|bFteK*8zX0&1_8VrOl^uXJImI=}$ZFoSMtp}wGZMSU>)`5KYuUVAGv|Wp! zGXPPE)!itMY$VJ^>lgDtCBcP(_TItS>U=o=g=ccXNEloVIJKJ2&VjB$9vHYAUw0Na zb%|{lgre^0Q8k7u>gKb#pOLt1PgnbZgmM+koWpHgLVeWObA42{r*E)JW&1-o?~+XG zd4BPYoE-s45Fr&sFDhA7D(u1%W$2Q{b&oGgSU5sja=BB=ZjZWsq?7 zOoicDz={h?GFue{Zr#v^cG8t*q3jNY=?DNa8SeJxFY^hiH?`1Jz$nSgx(J3N_zN9q z`G!2~&nBIu#TrknLoN=ote)7SaRr=y30HoZ8TX(Tn9rknxqlw2C$-RA5BIz@DM@`E z)KywozCM}Dd>hc!Tgac$c|H%w9ZuH{LXc`lIU+HEr-v zo+~Oy3mh!T9I~n;^8x&|2>zWm*fpSMwE((C9n!N`IP@SM!U?mPp%!QM^$+S?Dob5|!xJT$}@oj3T5eAhsCdymhkCSyZ4alb3`Xlm~r zhMD%z@IV*zK(05w?DKB+PpEaEuXDHqr;5STS-8eG*Vx{BSVPWd@cd`VEk1*(x2dntVGqqs0KpwZZa{_l;X-&g|*# z?Sg~4{*JqY%LFqeAkDkmvIHrI|H5#5C$}%7#gO)25r#**J=byfVPp<&?;gs{ZqN4j z3=xb+u*_YsGK92|qOKosuogOkaC^gl0Ry<_CC-$<_bA@8z9h2-{<;YM?KpIJCj2jx z;f2_YJd|*0Ci8ZQDri`EQkctbpL^jrAdq=P-^}*n(46Az_U>MSaOV5mSCUx{>G>Km zs3)I%5*r|nCxIP9^R#TVXjk6P^LW%kTwD9EsN^7-$*4YNLrG>cq_mVFD5s z;7P;Wt!!VwP{^%nJZYHmGS>nJ>@`!C-v1R(8Z!?|@AaxDjbKmuhj5BeRDi~oA&j7G zbJwq^1h^$`+?GsQbeY1bf#jh*+{tmZT=N?DhC<9-V?L9Wua{)j+u6ayp&M?MS@Q=5 z_rKwRu|#124uGq-dtf|m7tF;!?;V~hVEch?4Y$4?!#`(tW5pVnqr1AR;9yCnaL1U; z=KqqR&57CVL$iuq0|T@0ej)Y>+0sm=IQS1Ru|8b?H8Zmq{_N=MKXS19u-?r5A~7@b zC8TDyA38WQ^W!r33l>V5U&0?fFm?^~WRAr@)!$ds;l5$WDDyNQ=R^s3>22@r$yCB0 z16{NKVOX_DZf4c*@s12$1^iSRw380_Gn3(Nx95Ex{!AEGEEHGt4@xq-Ag$xwdQki$ zI0)Ushb5Wq@YkjAZ$s}9c|3FchsF2$h@+Rl5je@>5$!$0T@>ejC-X5^&ZR2e(+$hC z;>>=6u*AZ9$I$S6Djd^g$O8{cYz2wA(BUkHcujp9eA5NCfQEbc6u2H9@(E1cpq!U! z2seL7X`ich@;qo693c@?PjSG4v%G&yW+jv^?nnLGTynh7Rdhw^LjP~Rp!D}~beOO0 zwS1ft&q9JO^nU{@@sm zLF}+QVZ*Bf?w$Ab@d9ukI98HbH>Q;K@^Fep`9QORaf88dERz`r|3bH4R!S8D8!JP4 zU~4&pZL_Zzr&&Nb0up*=vJ3D#AhitsC0!VU;ZMEp{NTToX4XRLB={F1MHp(xB%Z;{ zfxg)q&8=bO?>J%rLoKz4UG`r~sXs$8jGPDmALuA{z@Sc3$7Yo^i*@eiina65#S5(I z|BX+S#2|uV9qqlvzTqJf!@mc3P%MWK%$k3T7Q*ZV3~u=1 z)#Cn*&K62=^7zUMx{!x;&px!hr`SGgU@-GAz`AD-7rU@Uy{ZyJU9f(aoS<7C(UrHM+xOPpD2M=@)btO=4^=04TVz!~R1MRqt-=Xi8 zaMQ{BK`Cv_VqcE3^c1Su5|n!~e@2G)+Ow28cMA{wE3aw*qHiN){xAXJ(w>BCvHe;@ z^Up|iJAmJTzfjeH+ve1__sqm~i^brUu=%@uj*?M3r`R^9_K2=to4^D5rtby(w9WD4 z+0dH30)`4VFyc{JHoMlQfgLf8g3VQHI?J; zKPaUQ4wS`mB-uH2-81_tVd~xrt0$O{Sf$ClT~S^|gvVWY&ksv!06a&XM(e>%xFZg! zOr{+EEy?u%sFc=^3n7Kh31M~_xiA`kTuNKS8iQY{N-2yP`;^l9NW$&H;AXJ@pCvdf z43zaNAn$tYy)PFqYHDm@PHGLz{JBqw5co8=0bwiXyLot3kmt7R$NKO<}W=Z`PVtbi1br8H0#^+Ga~aUml}90K)yhr3enKhjJWCYZ zC+q5@iS=*~tSeDc?Nc5wv6Sw|Uk*pq_?Mg<7v-!;+#sZ&TAzZd*(I+8g_2Cqex;dy zD9ZaGbwq35z|cXkT*9?1ENozm8txxz9q8_Zae~X2>&x^1vy|>^B54ki@<$F9VEL{e zYJ|fX?s_u&m(sm^BVRkGdngNX-5oGr#eaBU8248$4zss_ob~j-hK^GC<*czg$al=@ z>KumWD@l?Y%mD{*xtgq@YZ>k@!0^rw4dA&EoZI{4n$k=Ggdc-r{iKY8Eo_l?!?-u3 zZ!K{B%hi=;S^tbT*e}7K6$?mqy~5Z)!}fN z&O5M_CMK9s-(VBmtb)6s2M%|^(+B1zD__nvZKbp}!V|ZVx^*yaa-lRc4_shj+PGGj zmEk{(TRW{ZGY4=_csRX5z@=4vaA{_Lbyj_Y)ZC}ROpR+0uN(WPb7SL^NO}a$X#Ous zGs}!XVHSLqwG(DbhYjLp1R44<{1=um|C?(zs|cJvKd!EgGfFeLkR08f6M75(wv?W5 z@bvUJ$M&}WT`4^cBVmQEf!W=?y7hA;v7DW_AJ)m}=s=^boC zC)wi>c<4~BVlTk4zCk`+UGiKvcIzyq=`5@KylbGhtA{FJ$KhtT>(42_J-Xxtu#j0; zZgMIAkf38{at|d%r}e@O-NVTnU-QX_`JhG(DJPx!S+dwTOWKDbnI98oVK>i}WL{ik zs$bV^9* z9ofFwvtfgWpgdmg`A^WYU`zWtl7*J7kj;HV-7}A@gLPv=zK!tgckw^NcnQ*BJOOzS zntL=iF#}{pQ}1~Y+IbAGgbYge`Y;RV?wtjm`TFq)(>aeTg+XJ1>Mj^AfGSx&v!3I) z9!hX_cwhh~+SnV3sXtGi=N!*%3-QBq5Ta{%efMFr4hHdoruG4@DSV07p1`w2WE?>~ zT=(E$SLZLfyLz~Y`D!egUz%Adi!3{<3uQ6S~|>Xv94Q{HF^3Ey*liz(a`1p|uB^Z%ePiLe~rT zo6JK(T=}-0!lQqbMLDpciiJF+8bhktQe%`Aio2j0r}Jby2q#(Y5Dra24}85 zA-RffJ+m}(fGTggEcst`4|UAKEq-`dih$+tU)W|iyEHRj0cnJ?+9yxQRxII;*<_pa z@LbO~o&#%TnVU08Fly;}yg^`O)SdJicw++p`5_rve?IrxrY!j8yaw^o=cq{pJuND$Tsb+Jbpxz7;j}#{L^Bz# z#j|dL5enq6`(`=SG2#P?Qj*JQk6XcK3{J9qK3ncA%`DXyk6h}WnL2Yqa`!cK7c?VK zq`KfE#TDRc@xgi?lRSJfm-->d!xs8|ytQ|!IWwy?`FidG5H6!u0cdy*_95J@kU_3I zdv4%%j*ue|(a;MICvf}XoDO(^M^Xn-s|Fx0k=6%!0VY6t`r82ebClta;J+oA{U74J ziU5*O++g?FSejV}>GR=VSRR0c*}STQLvZUA0NdfO(+vP0u7k&spz&M-$KdA*;i0U- zjso2TdH|2K$|GZipFwj9La5yY2y5Vf$TjCfcc zdX?8Ow*Ujr3_hX(cBeocJ=|IrPbS5lZKd?=vW;$P$LFNg10qNEcFY>+>+Sw^a$A$z z*@o9bIpI8I*xnE0Ri$jN#H29#5nTnC}}NP>*DDyIl7+7YyRzB=9>gxZ-9C z9MgO8d%nwqztqJ|AEiC39iE2eo|<(RzRwe4t=p1?Z}MBZ+$tx3%v)Ph*Qp^qE|1;8 zBfkW;WZ|I^*hQ%AY43-5g;nx=o%Z>JH)18LFwlM2VNmdL7xbraqHs_6Q!Z*z2rXk3j^ikvs2aNwE7DeOQ7<*f~~_n zgZLb5_aLmh1BR>NF62InhnG8>odcT{cf3c z_bj8^Ix>fZSaT?BFIgZtM3_va3qTZtGqt*;V=3aYcLn z`(?BzD9faccH%4Q;MEbKPS8m-&gKZ}Fg z5AT}Rk5jO=Ik3%du{ejdf8ys5+d^OUgEHFLkZx)^hPsb{^&YKQ)#evfaGq&y|I;$s zg_9ImIe;79!4lBPKlE!cPGBu)IS}Ac(I1u3j7zH0kT2vm!lM<3i1vzgoku9XKTc3? zV&neImou$U?I!Nat?+uF;UJ%^Y>*UUQ!?-fqg49!&{4er_2Kervm>_Uxz3ZoCbhk$Xo8iIAV(?bQ?td9T+P5mW z9_?LGMq8$qBn%XK3j|Ipli~T}ib~ri(aT-BKEdqL?LfI( z-*W)a15|GYIg>9`)B{bYs$j7y1r6tf#A0J)6mc_`?6i&B6lG?P!hTGg)x} zm!5@dgUwqF<3ia|Q$~+^STJ)c-=~7x2tZ+?ZqJ*Ya!b%iq8W|H~SB1H5ZJWJ0UBvFC8(l8V0}i$)dw5vh8MoU&IML*t9y&{ICDRY}aBv;)#Yh6NSbqmsYkg`^vY-dUJnSNH zrhLJccG@RY+nT&oCGyldQg)uwK4yxKifBkHmZj29Gp9$rSbDHB)-HLHi~u10asn)u>v{Oz;L=&qVZ<+|YQ z4w`Yn)=+<6x4LJ;ZFiqOo}g*4uD=$PJ>ueg} zp-yMX7c|jf)Xu>&T5D<)^|J+tkVl z8QmCm^zc1P660J~p6EM-Q#hMz>I;oHIjXdn*>&(@|AAG|{At%i+K9n#$?i zT%;a#G=$*__Rb>ToT*^kOm8v28khsM_9VX5{levcg63 zc`Z99=oEfw&DLe~taF2C_;_>(U2$Fz?Ri%HD4^G=5{CV!1cHOfBz7PQu8gSNh2DLFDwSd?Zv`P)_zl{}J*l$?Un3XNJc^YSu73epZ>mcj@TQ@pSKs z{+yV(8;^F*ZZ8fGA`0I)d(k-r&)a`t9U701;C~lJnuIt}Kb6lji~6g1p1TluSVm@Z zTb5Hf1WPhQ*Ko~7D3p_GfVzaZ8{Z#Z3Bi_{V4&&Sklj}CVl06`rPmNH=d$Z~VJuC7 zpVmISAE{<_y!zbddam*FAkSGt-LtFd)js@dQszo^3|<_-e^e6z!el5AEseYG@>KaW z_Fi2^FB>S20D|_bbN-(o25%bzWE1>FIS=-CS8~pHfiQ)ojCXCR;OT&RLy#-)vKx5= zOl3g(I9i{LF1V?T?r3VGxScMIvd+-WmQicZ{d?qd?3%L76792NpacHYWw8!I{h};z z=TTC@%yUO(b$%GqH2R$8|`p0{&Y9AImADdG!iN$!8vc(s6jp z5%8&}p1xnz>-T*A7jy39%X%WDIuljyT<9TPakPlG0Cjd!u-=4CmspgG=CM$aW9kT$}t9uN+?|9~a@ zXE*-en9T3NAMm7%N$&yawIYr2^&*Y&dGNL`{15(7e38cZN|8oBeC5F4F}_ZuNnfNf z4(}ouJjTmK8sqR3s}+Z5_DmY%hx|^GMt-MAV|{FVYx4Mx-%5U!*a9$M?6zfGhuKJ>>nf4)d#{4J42{!Wp`_;2>M`3poE<0XG$$M+Cv zjPE1Ts6S4mG2SfF7%zx4#&`a}*54)47_a+NJKieN7@sN9sNW;f82`0MV|=biV|l88MH=-ti8RKyiZsTz zi8RK`s%-t;L>l84h&1w-i!{c+JKpB+Ez%gT6KUi(iZsT1L>lA$B8~ACB8~BtB8~A) zB8~CQB8~B#B8~A~B8~Brs%`&^MH=Jpi8S(eiZsT5G{NSN6KRY;ILVH05^0Rj`D;7A zP^5`3(wP4yk;eG%{x6%qhe%_5qexTvh&0AunPT&|i!{bJW$pN8k;eFfoE={%(ipF< zwd4DXG{zf68vV73G{#>PX^d|dX^j7Wb+-QAB8~Ankw$)_NMpQHq%l5Aq%r=pdRu>n zNMn4FNF#rVNMn43NMn4JNMrnUk;eEtB8~BJ4R-#MMH=JBi!|~Vh&09@6lsia5^0Pt z_#0b)u}EV)cd#9A6lskAa=INqM5Hmk=@)i_lq>f zkLt1G3q%^@8~g0|R*}Z|Uk}*v86u7G@>xKNV@@?-FT@ z|L8cIKUSnEf00K10+Gh}eaGAUO(Ko)EhpLWts;%_u_xQ{aUzZJZ6b~NZx?Bd?{=!q z-$SG^{xgwA{$!EH`0t+P@I@Nq?};?>cZxK|e`lf1-(93J{#}tq{@x;u@qI-a-Am^27KVk;eEsk;Zt{q6Cle{Y4t%D@7XPt3?{)UyC%xcRM4|!}#AVPSO~k zE7BO>e5M`WA<`KC+1YlyN2D=6d5Imb7io+?BGQ=uR*}Yd?i`!nD$*GL^gKJh$I>K? z@d1&h^Al;}Uy$H2UUp%U#`q5|PSO}3E7BN$N2D>nQ=~C|=p{CPmPliKK%|jBN2D>{ zc&W{wF47pkUZjz~Mx-&mQ=~DzOQbP=z-6|6PNXqDPo$AQU!*a<_X?XoR-`dLAkuVx zB8~Awud?|=B8~Cih&1x&i8RJ96KRaE6={s$C(;<-DAE|;D$*F=Dbg7Kqm{P5$s&#M zzY%HVw~92z*NHU7H;6RGfA?xze-Dwy_}Cll_&AZq_`YkLxJYCC8j;5Q*N8O64_a&U zXNWZE-)_gpi8RJHi!|zQ5owH%yTj&Jh&0A~@3iAbi8RKS-et#^i!{a;++)WViZsT* z5NY%WPvTnlPkJ^aX^i)aH1gLzV8_>qG{*OQ(2nmV(&TTW9bYZd82{^s?RZY4G2SWC z=&whlF@D4&Hh-B&WBj8{cD(ViBu)B{Cu!7QD$*GLqs?}_AkrBBdy%H{6KRb9TBI>P zSEMn%_DNfRvq)pS`YAh}6KRZhK5fTmi8RLV+hWHzi!{ay&)D%EPdDc_q=q_};H3X^fYPG{%n+X^bxwX^gKGX^gKIX^elm&DP)R zwIq%4IUdFX^bE9w#{EE(ip#6q>;Ztq%q$1 zj?JGg(iop9(#Y=@X^hVmX^hVoX^iLIwe=fC8sqasn)o7(@gKZr^T&xa##==i`2~^2 z_#GmR@r@#l@sC6r<2ywf<7d5Z=f6y(F+S@9J3b`R7~lItJHEe2WBhMKn*572#%G8$ z#t#u`j4u{xj4u&sjBgfcjBgQXj1PTe`&%f|7+)&V$X_PX7@z#H&2JQGjDPq4uy-c# zaaHx=zhyJKXC`fmprD|FfTG|7 z1s^E*01m8MUkClIqm4A;#e}TuMzrSu_fANr?^%yUf6-1!{be4De)7&q{V^Vk{tF&U{1136`cLnY^#8EOqCaNW zq`u2z(SO%t6~4!!KWDe3|95#T`dwa<)Yo||_DjbEjHsUf@!KidSO1~@yG!)sKjm1$ z@-xt51-3K)Cnu0BPk?6$pQZf^&l5f!#&S&DFYs9O`ru?#C$|gj98HK$LC^I#b;t9s z@Cw8H!*4<~p#M<+mGrC&_{YiNDSm0k_Ige=f zE5-e91N}~<+y2D;0kGZw6!#P1L%sNqgYEnx`V=hX-#{S3r@;s9KA~<;!|Pyv^%OVy zouV@}E1|^qo`A20_nz(Y{~6fs2TS;0h3)>Y@cr<2x!|cwg}-wo@ex-X-w!;VK>UA% z?N8#LK)u?Z@V@X>$GP|qgYAB@#3$i1Sk%jaA^DjS_-_w*8Ep5P#eXKyuM3zjvqfjD zaPjk{tmvGx97}%dxq(Oy`bm4_(?ju3(*MPP`OHT2@M`Cu?;Avu^N#-x-|L0{A3HOj zobB|lg6)2@E$^8a;y$eMzjJgXdi#_3X9s)|e4}}vA^rzoyFV>_I&Al&g}G8J-ha07 z?Y(PMzmRlFem{oZ{v1zru%mEcfP5_V^(9 zXpiLs3if@Agx3z+{deJ$;fA-n{H}sud9LF(!;`)KeIac3cg6p8u-(rU{sO%Gqt5?# zV7p%@`k%qi-s|+w!1gEg^NQUp>G5d>Y~Lq~|MozCX27?=CoXW|-wj{j@sHrYdi*3@ zTva0baL(g-@LxUdgS!?v_iNx|mpDEPzHFJ}OX0^nz81FcA0)qD zfsdp<-bAtN1pf%O?;k|}416K_qv`LW--m(6zJCz?5%B%*i0Wh>5dCZ!n9NVgdo1A3 z!1n#R_`etaz=`|5_rD~(6JWdF zC435ek=g$eUJW1dbr;^5u-*R>{Y7x!Jx+fOob&i|u-y+6_jki~|4aCX@Udn;O!x_S zzQ?=$2jP2s7+mo9c=#h8_rYKEcn$mwkKYC#{%x1u|AH^__~Y=c9^V1q>+yrI-Jg^6 z{tC7~X>YHQiQoK$m%-K^L);I;*8W2H?Xb1C5dI)+?JI;o1zURx;cvs%enR-Cu>DDV zuaX6(`3Wxx_&ovN16zAA3GXLx=ai_fo-m|6J_%cUFwyV%(kNPkex}hM23vbD(H{$c z0)2zgFM+K+nCMS~AN2HR!qy&4^zVaTK!1_(e=Th7!9@R6*xD}%e;>B?O2WT_t$mWP ztQQ!wn9}t8`8V|TC*?EaKP~D0T!!a+^UHa#wYQV-u7s_9o$x2&SCihO2u8~5%doY- z68-mK`;+)yE(?0|6J8eZdjq})w)RpI-Y;NlA0_-0Z0(_hU$PJVZ@z2a2f=4~JQ=n> ziGOv#9}D;=0q_4ZXJ0AtO@=!fWeK43KOeUCm7+ftJ`?>7MqhvrZ*u873w|9u(daLN zAMn4fiw zt^J&^JTK5h>zSq~|DB?T(A%HHzxV!@ba{0Ie0IRM!PdT0!haZEI?bi`kMNDt9q-23 zB5Us{?hl5)H^b?t!3$?OJ`w)l8yueuTYFHIAK2P|3SSCadr#p{z%TRK?;UW#{Sf>?kI#gyJ)gM$Z}?~4^Y88O{}!D8@4yS!IQ|8^$m2Thp6&AZAlTXi zO8CdXZz?+fOJQs8BKp;^wQmuAD}4CH&i(u0V?4eNo(;<|E%kjn+~w*2AAAyQ>+5mY z+Q&%vPs7$8MtFCQh|YdrR97(J9SB={7|}Pux1c}K=;y%J9!B(i@b2%A>JB&hQMeHX z)%@~axCyrH_j=g=q<()9@M}08dFyG;|19_m9{0ju^!NUmx* zx$s{LTl-4M&lK3&Lkcf|&$`07UkRTLGtH>-Uk6{}>E8)o3U?X(rSLC2{m0>7!Z#cJ zm*GpUbm2b$UkdY&3jbI9@mWv*5BL^%xzX=?2+!vqcK(lm_k!(s@CNu*p1un{5Y8F@ z{qQ?H{d)MFFwv;^FN8nl=|2Mh4{YoE7TDVVNO^q|-u1tux@V35hv4U7P_>6A;1}RS z*}swY`wVRDgT(*dhf@B=9!U7L@N@7A6W&zV{-nNp0xpVwZ~sEpJ438@WZ0MRWd5ZK z$NPbA4gB8{@E-#{j@gV#YkJrKWC;7QS*t`#x^nL}N z03U@|%IgR4QJ(&{@ay5X82vwB`@UEF@6UtB*MIK(PlWCJTG1a1Kl00{j$vMfzX<*_ z465==XjN$ouifL?N7@4%7DKM zTYCrb{}{Z>V=nv&H2huR5dx9&sE04`^lyMKgg{}KMG(LW2{Y~J^a|9xJ^#q#hxqdx++ z@6Sa)4?gt?*Irh__Wif$-wLOxZjK1z7MBgvn~lVJP)PxNzO`@T=O54P|3gxA3KeV*{! zVf+40_)6HmuM@r%w(sYJrM-WV_I}qc(jIn>?m;iS0+#nvKY|b1Gpd*QOZfNjWRK;A zSewWDFz_t*_$WB%v5cqn{J*qkd7hb#o-VA$S9!m(7?vU>`bann^K2XQJK)J4UkOk3 z_&Ru|$G5}875l#rKHlRW!fhTu0nhjNS$LtxyS|?FlgF=udp$l1X0DCnI}Wx#89z#} zwf~Xwe;?dV|6YV686Q3gKkN1HZ@|yNl#$Z^2)6b$;{RFrY{pyL|M#V^_BQr0qMr!w z1KaVZ6}I*@qF(`@i~dd2i^TtC*xJvC{xbO2*wYM}_&)<%`xw!G1HPF4Pn{|M55d+x zM)bdj??7+Iw+WM+{fp@LhHqnhu=B~QVf%hq^wVJbK3G`V>shoX`~GSndSTl>-vnRc zaRI&#mhzGI`!@Jl_$tHF9{VEgU)tjp=!I?j`y{-=p%)pY{0ju(h`n|KEoH_b1N(kKjLh{1?Ww>i^^fVxGFYT)k>GmY;>n!w^ zWqi8;wm)eP_runHPtx;K_z>pjl{k|2@LSm0--*7iIf@RT|F1Cm*TP-Dartk7-}QUP zlE1F~NFRfu{x6B5`aOwX%5xTa zVOxF+;LBi~MN+;i;43_R3AR7U-+Kb)Yj(3^L^Wh}N2gCL!@y`nQBzV5({!OsGAHnATD)RF@fk^&W2map?@Q303 zjQz3oe+A2CNwE0;IC^1QUY~}qf^B);7KHcRfPVqo`%5JJKLz^TrrF%;@%aFF{=u$1 zn&9(2ZiDajcm-_FZ%g>9zje9iiS_8a3`>7|Cv1OGzE=c%6KwB8k?_6>+xt(1e+=96 zyuwez_WZ5zOQ+Mm23-1I58LyzqMrxb^RmJj*q#p)&cpk#-)5iZBtP%<^0N-TWy#Mu zu>DDXE)V$Qu)QBf!oLl+_rVC?6S)6Tz)uCd#|+Z@YL~x*VS9g#gf|Pe_n8Q{!jB*7 z^0NTG+xmL7I&$`6rN5ao_NA>sas>5H8Uib*)QvPQK{x1*s)9`X{|5U=8xm>SrZF;Y& zbNg9e4gCK&;HP1GzEJWf;XO=v@8w?!FM5M59bLZ%20R6}=MSy_p;MyzvrPFN8@N9? z;5D#4UugY5f&Vt+|BS%>RRMnmw&xec|AVkS&m#PD*q&bzeiF_;h22)GNj=P_-5AMK0k z<*`A^yDxCRKH&EU{HcKNg$r+X?d=z^JwGq;{XKC13TepZC+VFGKfIgse;jP@rxX7R zV0#~(@X4^fUrzWm__lqbI{8eOtUqKuMA@qOTITch=q=0o=Pj`PN&J@w{N;du7Vyr; zTHm^T9s=9*PLiI<@Gjo^;u!cuuYBeO{?h@khu`&1S03lU_Pn-)&%4gZp3fHk5PT@l zbCN3IPr$E*Uj|Eg+yUF4dzYn(ew+TN6+xyyt{{p|dA>xWHot|A77I8uwD(2T|SySjxKsR%y$dmHjkw~?lt8n<3$g8%Tm6}Vf&NvEChTmTt3{T z=lw8y&T)D_41dq#PrzN?^VIF|+dRGpeml&ziK>qW;hR1Eui#I?5`om$GqC+h`u?-k zk{+KL;3MAd(lZl2-s1)E9C&}cNqBv*z5hb$V-;-gyAWOr+xsnq-woUQEQF=}FQ9y1 zLwL5mf0y!=^h)_&iF;xDJaxnIjGsQEw?E0x*8+Y7w&#azd^ZwbJ)R`KCj$2qWMVfz z3GWp!dq{EpOoV&jkKjh~e;oXjr|*SdIoY{i0o(iMB>p^X@0$~TD{SwV6TTF_zd5Sg z+k}5TZ10y7{T;BqPfl3M?_ToLfO}hh51aCl@{{tiEba5V__sgF-){n*&~CN5J=6z$ z9Bl7PvGMzU zUu**-dw+n0xAQ#qdpvyuZ0`pU{ao1I2OvBM+w=dz=fd{9zpyIb6;VBr$L0Gd<-3UV zNcnyg_x7jSU%)?yc?TD_pQqr*VJUXW&(0_CeC3S?`@)C8yBPf;@DZNA2|f~*`9S=? z0k-!~N_rQ9*O?p zb&P+sXPMt7!S*NhI~?#Q;FsOt!v7ka^Y}ry=<%=MkKE+kKMU7+<@+BCIDg>rE8sJ{ z@|^^q^C{=Q4St7LzHfvt@OTs+@XGf+@Qohd0QY+3{RQ|=kG~E7z~e{Ye|Y>mc%on4 z3)%1YcwczM=UjS^fUooT4RGD(o&F?v;8w?Pg6&Vr|Ehq02JihI=l=KbKCoS{{}pcZ z%D=7?dnMS8m#>7c^Yll+_P!EnpR?eTZj9=dk_Z_O=EEO@B~79~75*RidFC0>7vMj8 z_4^k1FR)z?oDU!5)$fPkSHq{6@Na{%dOQPu!sEs8PTqXB5^nH#9c+IR|Lp<)6SnsYNqz3q z#rubkMs;`LN$T?u_?T;4ey75-VTMViZ->wE^vmFL;k%7~6>RS(lJMUGpM0%*|NDOU zI#|*u`rBc9Uy<y zh4+A^z3kUb`e0dh3Lgf4+q5s?$?&}%9|Pa#@qF0+q`o@?mVP4N3-|;7O8!<<(J$S_ z z3ETUIB)m}n<-mQ&_Xqlre-`LNek#zvga>_lzmcTpm9V|9L^yO`FB=2qC-u<+Km0w{ zoGGth^8 zd7!^B;5!5UUckSFpTF1D?>__mzATLF{a2Enqu^5>aPH^AD?C00E_hsq?N7?<9RXh! z@W)|$UzWrt`~AdO{B48zsDB3D4I5rSM!>vLN++OTZ5X{B*!CKRM}tTEI&J9u4@?fNu%-!GNC* z_~kSJKmF4JUJ~$Vz?TMmOTZ5X{Ip?PUoU^7seJyC`bQnz?X{n<|M0Fa>hsEbfni%8 zr@<@G+x`{SXUOLT@rV4uKz}1VnekWFt5V-9_*a;J_)Uny{8Z~d@;xb=|7!Xlc=^9A zh(GKfVR}Oj+wZpskM(vOf0*7s1o4IC^?!}S{O#1o{qkP>I6UAJ10D(ZeF1+i;2#G3 z55u-T4?R`41o^MD=VM^`ewwsvX)p5w{R;TK=%*U}>Og-ETu*)uGWv@>{oXr0`OlNy zgu?uU`(f7a>L*;(dNp3{vlI55TCdux@cHn0X1)J1_+t2CSOO6KZ^IJ}e=5*_2mWu* z{p0Z0Vac!f|AS#0-t+JwCO@LzH^uX`sjrt&K8L`^Sw=q|T zxGUgXz~=`1;ec-o`1=9>8Se1ne<9$#S0?ob!;3xl69YaT?(y_p0S~}$w0iPC0-tJ` z{J%Ni3*oeVV%8@WlaN6Y%W;KM?RA0*(fg z`FTaahX*_@;1dIWQ@|qubGALvUM~vx!vTLb;QIo8EZ~0x{L)p)_zn)ZG2mkZ?hZH? z@LL1EGT_ez{LO$L4)`|#KOgX(LyX6!zsq=V7@YNZx?$O$l=<*Dcp3YPc08E}f70wv zivJ~sW&cs!r{R~g|0m;#a0#Ae8TW7Z8U6bW(@m87tKqY)d-S)%SHgCD`xg8Ot0%li z47VBozl1+!_4xli{G?^vzu+_ay|P*_`<0U31L3Ewd-yQ;II~`s{LY5wSVq4TZuK}1 zbElYEpG$aWz>DEMP5AGEPlf9Yf5;-3OP2upa9zY`4aWOxPqkf(nu{0Ka8f_8raynCHKFChLu0C&K- z-L?KBFn5-y^Wvhv4Za^%>4EQue+}FEeFA>Y^rb_{vvCb$>GaLHL*0ms$VU!%xF!8UJ5| z_rd;nKjZ#8@Fe(9!@q);z+^*}@00MC;iC<|Bu9Qd{|CZ*VZVHg(NBgu;JJp|;CFkx z489MZX!L8~7vK{Op9!Dz8vXuH%KzQ)Fl@{3O89K}mB#(&;49&S4c`Obh3iBGk7n~uh{zgo9JPt4ds8=5!PR@Ex*0tU&FS1j)0%@_;`5tMyFp6AK-BT zKGNfN!LvNR3VyoDwYSfRf9#u%GU>Sk?u375_*?KC?3XSu{4o4WxZdz@;N4r?dh_q_ zVKBv`^0#N6`=el+pI5`p9yh{o@OTc~4%_y!818^&TU5$>C44PhG+c%+o$8+7-UCmX z=JInRybNAy>iaA3C#F;0hJOIxKSQTi*0;ZdIa5)0y3tQ4P#&{*KV|BBKlnp$i0aBl ze+azKZ0G2ofx5D)%{%^up!xIfZ1V0GhX!w`#*~jbi zx>8?%g|CN?Hs!ZF75D48QQZ^9{r>QStx?_k48IP}w&~{;sgGv(V)z=PZ-r;KyYaOf zJ_)|a=m+3m!-pFlgap~17oukkKcE}!>}E%AA-+@_cY=E z8om(T4VLsi4PS2j3r{F9Uct8h_ke#7A8*{h0-n{O-+xMZy%xR@KGuXk1HK=wH+&-e zBz%V96pW2etUm+36qf!c@xLGbFWC0K|ADWD7a9Mz!+(TdYWVx`3vj*RKfFfz;m2Xy-%f&m4)0>zuZDkBaPgl3cdl{n-wQAH z_|x!7@E=V2?}AS)I`=<=Qy%{fPQ!0A?q9K<_5<7XU<-U$$+fo*_+(h@dnNs+!n4-8 z`E)h>3HU~%KLfsaz4Lzw{B@6ShM$A4GVy-{zV>wI{wMGw@KHwpH+XmKf9?Ff=jn_e zaD&nB2d{zccySc`BwT08^Ei0dGu`@qA>8Tl$?&D{{wBN(d<*;$!)xGE-{RIQZ-Xy{ zA2Z><2R`>KH~wA$-vi}|@;MAX%;RSGNcfc|zE=2D*p}}?_+t2Ylb@5}N6vBU%N+aye30>f z27JJ|Zhp83KJT5_d+n^-$A7_(pYPVwSHqLu9o5}x%L9Jxd))YVJKPNKXY}8O+u<7w z{{(){bN_32ulKt6ccS87?eWXtNwD>Q7`*GnZv8p~ejRMy){JwyMFx&{2AD;Cmw>o4%_zk3wRRt(KAhY{t9Pc z`~3UTvl!1kejWTYY{#SN@L`{I+zBs%bCKyk@K<2lzfOZ6f^B`Th5rfH8TapmUvi5} z|CR70c&*Xj41d(q-wEFXA8hpBfqwCc1kf8Xx(qi`qo_^4I?c?WzFY~#Be zJ{A6!(cc75y2F*%o$wNvY$*Tt!OdTC`xC!_&-}9Mzkh+R_ITH~QU5S!fRz7z;A_9) z#^1x?TVSi70bl$zw;rDlPq@oHFP#j(2mYW*&k%g%*O|}E_&)}(x!dgryc0h49v9z- z;9hERnmEUvY$szC~@LZ#B zf|opC+85!s!Ef~V6gUm5{G%_xYdn4zd^W7s_vkN&AAHdDr;owA{=n7e&G5_NdXvA~ z;dWt@o^Oi(hh6)95Y9dl)h#sce+b_K+y4AB`1|lwqyHnk`ww0G(YZWN!nQtN4ljdk ze>xIA6;|a-{T&0J2ix(k1O5u!ZNgs$AMzttUxRQ4W?EI{KL-C2w(b3V`0Phrey)Ib z{juw>H^Y+QYZttKqwi z{)h1BpQ5_!4F4}Y`$^aScYYV~!F5KzADo75{*Hn#hi(0w2tNW}Vcfq7zWC3szDMAz z;meHvY`F6;Zh!eA_&)eVQ@mB zO?dBycl{^zZTMO^8%>DY%a`F%*tU-!z?XXZC*Z4LX^%2qPdK0cCGJgl`@zrgeL34+ z8sN+Mo}4Y;W8m3*AMP#2{}T8?_$P)3;79mAoXyYa@JZNLpJnv#5%LeV*`N;915#Pk4`a zC;3R&+EedMd{bfjeKWC-S^&%a!cu<1C&OcKo#9pRS#X2lHSjeap9SCT@rCg3JpKT@ zH}=cc|9`_%J-!ZJ?(rAkGd#Wvw)e$I`W}LZxZj54M3SH1!te4}E_35ozYG7_XQ!Q_ zm%%u$*ZJ8gdId~gV?B4xN311cJ`$#_)zf^G|Ecgnp1uvP_xL3EDp>l9#Fv8UOZC?O zY4B%Z86QQz27VMKOvUTrXJJ`Si2ee2&z)R)u7LN3Wjq!AP4GmRG%Nl(+y&1x{2f@n zA9sY}oudcfXFdKQT)%Tvzuf2_gU8?%hJOz~?D5}V`99iwqmM46J$Sque7DDY!Sa2x zHsgLjxYy$Y;mbTe6n+%8@i)WA?B@7*_zI5~!_RyCCb-Xh4`!d8c8)Ue8RouZ;WBLR zOAQCPCnWK|0L%S8`x^HG5#Ci8$Ep^d@tN!^iyDaUx0*nyy#a%^${IJxKnr~OotWj6F$xHYGKYZ z@42hizZtgn{QF>mdI7xrblgjPaMUo+Sj?nz1L<-)YAAzIshlpBM+>P^d3Z|8;MB=8 z#>N^;QBUuj)&)^dIo-cH)tMQNQmO1nwwz7pQl&yPzkN9wCqi6R$mW9(jVRmLxjc13SI6R12T4tM8Z2fq#d5wBc=W`|^Sti% z_U_)rJvsnVBt_Gf8BCAn%Dw5*YSOcIPN9&?_NU9){D>-@#cMOg!CZdb{Cs|O)YzXN zDV0^>>OV{6Vs>Oz)Tl*X!StuYa?z4(}9rr8-Lml@FCN1kE;8tmMDY%Vt~Ii>mgqowJ33Qy)1{0Tk`#!DDZ{ROsqD%TVe@3K zAmOP=oKcyF(GtxdNPv~;BrKWJ-Rnh94K3+G)SOZZ7rl~BsVbfBN&UQ=ZaFrV%7$qO zRN2P4qosM$R=rN8nnd?<^4xur>uN?yQ3ukNR5iCE4ct=M&8eO;W65x(re&iVTCX27 zp;g@1naqkJKc?=|e@C2Egvkl=7$TpOgR(y3N_l-vSPNJX&)|>*Y}Ri%MRvMG!?=v zs`pf8Y)h+NdyPw{eJr)Gt25O~wXUQ%ynHB?{2<-Dq~~&}(bCGzPIl}q z+qk4>ZfZ_{IlDGZxsD7J@=|w6v8q`klf{u~AL3K6J5$P(qa^77+A`_tA-84LvThp5 z^xLQqv}H@INs=-zCe-Pbxy%W<{K|B$BTi#`*JRZcmk+9ynWO?yO4_3=iA<{7yIOOZ zbllOjE3#!fi4lm8L_j^|e8CrtR7=9V+-PY?>Xg=~^Q|PNeQF8)nJo4cGMNG621#dr zK>Dpj-knJg;9yRUthKY6Drbtt(Sl9B(~_@o)%ffh$ESF!s*BxA-?jr=mibvk(mPrlNf#N%270r@HnXa`nn*UUxyv|T>^G~!%^ab%Kix;w z5>%G&@#)aPOQo0zR6QO9n#HAl6XO=;drLPIJ%bBQ(D0J7BAEm!9%NGX%*PbHu zGe4ahtl}dUhwiJmRU+$-7ObBATBWDzG$%yX-LiDHJTG5dm@bu>p^NI7%QPSDYawkd zAuy$pkS!UJCb^k2KwQ+ehMP9CU#NPr6PQkIdr=-zdKjMb^0=#oYEWxU_YY-ctkAN~ zbg85qo5FFd`;KzOq^I3%ew){6qty(Kj%-=4uMA;xdw_e4-^_xIANFMwQBV7_YEQ0! zW0kk&Qch*a?_xtim!lH(=2xxCWdfldOZCo!N#CX}b$KA((l+CH-Q41gAIvwiH0|TN zJiD{7>X+x}IU@sev*prIcCZ|cC(kx2%}}O)wan06XSIoI^qQIyQN^NK31z3p1*29c;*AEn%4TBm;9!ZR)aLh-!n)!XjnUTM=2jy9wzTPZ zUN<+^ex9ecaE%^&)itnaX-8|ytSG51Q!h%|uGV;gkcQAz%;tIaSns>_#3!)GDaZzz zj-cn{p5Bhu1#WjRl~SRzys!bqJ~p7rHX5ZD6C0c=C||VMEoMtv3w})d&E(Ry9LSLD z6c|m%NPmLjCNIOA(rk80X=i1#F}Il`M(lC3+nL?*+{_5WeNp>ZwJ2ZC4w{`sCDPpsD=$tOw)g$n4d5=zAwByPP)Mo>SqOrAHI%LR|B zPTM?=wkMa#6sq{LPhB#xNhstnoz1Pxk4;tsXB8jLh203)kfY{}2GhJL!L)2Nn3fF$ zvn;(jv!pPum>;I-ORM7aZhqsAx4JjCsi`e;-5p!K{cjV@rY-^EJ@3toKHM4i8kTI7 zC-Dh!Vg{5v`Nezwy*s$d#?DP@HfdL>Bt1 zrjGqriOUzo?y3c1l3Y!t{jo*UJ*L#MwUQrExv3EPZpU$*5Nr49DTd_;eYl)iGE&aw z$j#0<8?GOE|f9@RlIdAi{l(hvwvlGa>cjkg5-(FZcn?oMcOr*D`nlL%jPT!q(QYR-J*?VcDb-S$l7H zVi7E|j^1vyi)lPp5oy1RTY2pg$05#=66=cBDX}Xno8rl|PhVnPO|5X{OSG$A-qPum zc8nC%rXZ881X)#K{j`kdr;1{WTK|@=p6LMEYut2rx}M9st<_!?o3@LFIc#{eTvf%R zItvV4G(GD_`iF}7k?iSu=VJ4-G#bBm+{_+rJnHPoJ4jM(M$6uO2k+axDMP=a411~n z;!<+1*bbn^w~{eUs9AsUh@LH~3fTpfH>9{tI@08{{)ldU_%hGsn9MY428kUyk#lF0 zoN$>CdTw0+Hq2fpGVa{0AbaD=T~g%S*=Xc})H?KKo=ZJ%_#yT>k#T1VA`Z=CDE60@|&-kkGI7l#Pb96~R&@Y1>h%R5J-Gp&GEU1L@2T(Eiq? zdGpoOJCrRBq}V(tuWw>cHzT$eO?rB1>gUm~oE^#N7&g^cW-VLlsa5jWXpB8J)n_hS zlK1P`#?i5b{Mnru&a3x-YlS57*uG@dYsNs*fzb-yjI@NENs?$C>^*F9zSoRqMkUkP z#zK+TIfeCYnCi%)_#{z8RfP$+z4;24R;1jyye!JBi=9@HYS$&@M7;2a_A|EL=C6{Nme0OFQC0&$9U@bMhs9!h9mNa&(Z6zj^Jv zj5U%p@N8p743l_VRm)45I-)qu%O%nE=G9UwGawCFYG^}h>z}5f{mPE%de3JSh4RxX z`+nl3B-O^2O>d?+oE_0KpETMH=~W1%lGoL}t#c)f4wO!&ED2mSF#EUG#68obOgX6# z25u!R$y6!n+KH8W)l3$#;UV%RBP-=Sf~?)e)3`e2Q#_~~%cw@p^snwIq**iLaXgg_ zJfhQ8*}r;zcGb`_+I6urT~vl=qEt0WC96;rs0Rv9LJ?Y0Zy`t0Ii>+gHE%0z8&Tdn zvn7_^CucL<(Pl#I%8^JWav4NbosT0=^hFgIAs5R%yu}z8)y8~UI$FZAVu1IrHin*c z*>e97>my|?NN;n+kuRE5;#P~}eytoSk{sy%tjkIb0BR>l#tl<|p3wHnSZ80mig#^? zBcb{g zp`xYWM~5>~o`o^hGbI}(-IB*td&mrkNF>csC~1ktx~L91r|Z=!*lK-ttVdU#3y?U2 zD3Dn5$51mWZfT4vIW~MT7Z_Pmh(^cE__Szrcx9%zcu-{{8gs==U&t3!Ds4GMV{!B9 z9vvBxO<|QAVxV$L(U@wi~3~{mm5l6+25w%mA zQ5~6qr(>kLO8Mi(X+L|WIu2!3P?W){n%H-5=E4DaBEpVW4X4IWh06D*61ccHSB

5IM^s^>qYg~}Er~a+c1&KD zi(7f!ksBt&W9(AIWKAqgtkkY*PnSv2 z3XRo(MXEzB*)1D;0da4Zo@TKr19VcxlA}V_#l~LfPAwLcw0DSUY+xSSfmpI&I~5Aa za42H>4n<}j$(M9+cwCriaSznQXcG~M1?Uzw^a5Tr1p4W#8n8_;D5(o;FSmQJ!FX=a@m)kPz z>t5Q{(>JG^y~)n0^ZGClXJ}A}C?O z5KDavhFGZgED~=5WV6(nCB>V>N)%I2Hui;~OO<^UC^5;~D@r$hTCuWmA{XasUp0v!JORaMyS)GEr}v2p#0s)|pOWc3znI4v{dQGo3qY@QsoJRIvU8>5l zvQnPRJ8Sd!5oa}Y(_F=kgb;fO%0`lFPa63-_T{>q)UIuq6D1s{nTSr_3XG|T%s2t= zl|j`;q(iLMij1a8V{oqz#`Wj6*}a6Q5T*4b|A<`#WyMSX=IO!U;>mOykY>@>m&@qm zD6U<^65pA!atuPWGF|E{dMj6PdA%^ zE_I>8B(ls@+Seyzx|c{LG%{Yi;UqrLmhd*pl#~+3q2EA}@YJtouB!e5or&8_H4&Z8 z8;o_z)8%qDC9`Rm1YcponSf4hW-$*KaXVm%E0X9kc%TvKt7u&&kRdsP8k3srjYj=#-p-We@lXdaGCG_Z z$d(FXc@}1Fpx8XUYO;KVNsfpr0w^}O43w&d5Nb>to0D55#(+b^eSL$!nStFD$pN}f_=A25`6$g;=f&xO^O9#VTW=+tcDG)9qaoHM_>N2ZAO(VRT3 zDOBN^zx7(nYBY6pE{T*whbuE2xUP(5bvnn!iOy$bDX6aKKT1~yP|e9W0S%|i`piL? zR~3fQW*gHhOQ~Fz18u3n0@)H=s}{1^#*UG-J!^RKsalkUtUsu_lGJj}nRT?Or6ysj zKh5K>{HMM7A_2oEc=VAjvM;fy~-$KP%~#!`aC*XL`-VC}KGSZ)XQiIE>XV z=bPfmBcV`F0Byr*_N>;DJkN_fX`@hYk7EUaWV6-6qM4Ybx88;@0iCeEn6DbQD2ST} zTNkU5aqc`!k7%l<$23P18?RHb;U>E-OeGTUP86)@jNd>S=UAfEy9dT$KSi)IK9PY? zowbVMKa@`;>)~06{8^1btyfc_=fLN(+9^q;d7Z$6g)|7BwWIaX>0axz%|PY=8gXSi za0(txWSzwUd2OFL-a>3c4&pFcHWtSC4s;l8Cw6q^+4l3F?nquNZp-w`*%(Q3DANI$ zDi;SmY9|wPD)uVkVtQSwIMy8Le_Nte z$$2%dlVN{2FjA&lDv207+fwojt5^0yHbeZWTI(VvOzlo#x25j>h51#y0TMsU%e4;1r-)UYvKu1xaU{Gh&lL66_2NR5x?J0 zRH-X4SDgI={i*EWcvZwMmen&Fv|*5{x6LS@C_t@mQ|GO%+L6{uTedp;x7L_J)G9sH zdTTf(D+cQ*lqGZ6n=Y=(l%*Mx3AWEFvZx(MLyR5hr*ydsfPBi~?s!yk8tKd(a!1W7 zH)bWZ+9II3IzBdDCFG8t#T|=y&24TNsP1C%lHLtENm}blR@7UPDuL;j-c=Mmi|197 z%2x1r**33oJ#VU?NVk(lhqp3&j;3!dJO}gxpRfgUHzKG6(QZta z@ZD+q4l9Yb38koG;pj*&8#L}pg*IgzURfKuy={4eDd%`%(j%YO3?x-u5W|!!@LNm!O@%mt7f~e;SZ!b;^T7;~s%GvsyQv$hlj{ z6*Ja>{OvT9oeVlwY0%fJJH(7YEv;0Ac4yX%QaLsxWOigwL3wPvBJp$M(CKY?*bppR z7iGCmgNWlu%XGjbca%97v?l5wT$LRd+ww7lbD>+;B5VLA>8<4)ndi;jXr_D2Cf^f^ z`KNSqPi4np-?NGZhjS!}kf`@$93XwiCtc+}hldBDpVz(L~nH z)Oh?iXPETgv`Bd;+tklCP*X0?77zdPL?w0ap&rnc8`cy39Q7)DZp4NoJ!*~+C`UYQ zWO7Xw7?jjl|H26Ga}SOYE^1^`K=ah=Po z5${GPB zaa&jY_G(H`5O~5#!pq=rUT?6(v6Dbu;5LvFd$pC4AY5@YNb2;zUS>#S;8Y}WrR%y{ zt<1Efq}ZzE?SC%E!$?B|Hws|2u)d*TviSwxNSA9qgPD=FI+?njR#L8}d6|mqALbUx zxZ;F#LX3JKyH*EhSXZ;F_mMPKIbO|c_Uayc-9!Mz4D&>?rKz%1Y1WYp#(~E1u$T_L zu_-x{AC#u78=c{>%_J*{nogOs`L-qpxa!Fs5wNmBcIJ~F2Mhf&@Mj0t+lrI@b5H8W z%iS+JNNJcROl}vFTjnHhs=Zci9TqA?8gV~vw9=2{p94>=^Jz*Py;T^8=j%^?N?Cqw$0a~YZsImAHf^lUVD zG@Bd1xTTm~If@N&LqqR;E(7S9vvz7jdqY=4Tf>5exeYxHGuk^Fmd@+SPHEt_v$p2x z0zLevb5287d&8Wg7q+x4Sva+M$-mhe5jNK)k?4h^O9BUpMQl_PQjHN|@u*_c*4q&_qUuBBe3qao%@G;Lg4 zAtZ>k6YoKjBDFo5t`w8?N}-wwE5!Zu#MPD3LScI45c4B1Z6G`c`32 zG*X!q83HQY=K6W#kQ3A2s;ct(LRH0Zegtcl;`(Zyuqcu5{3)xCi{mEL1VyH~MjUIyZN|$;taE#o#@DZ_a~*6NsdGtclRZ|=VNb@p>k9)3 zZe3|@uaNaF4@6wMQsJy6m2}qDin)vzI=5ojtMn6hzc%P!HMeXozuy22lZbs6c#4Uskz+?OsW#~cAt=HT`ZRo zbv7sBN05jgPR6gk2IA6>KG9=fjAZ5{3J2Lto4V#O^qJiM6r^}&%1>UR!>FLl*B}z< z5(D^zOA#bewnRQRl89YN5}_l#|L-dBtjSh)BK&H$t^wjRmjN`kk4>mpW^VjEj>pr9c;!ZeD-zuXt0Vsvf-ovJ?1 ztzs_9E^wGzRo*Up@vkc&p+Af*Hbr7rFvRUr8*i2p`nx+&JHohi|v{&Ay)jJ zFjZP7YX)CJOky37l6$7rwR#C-YG+FA*-DF{Xf=CXPpoEtYaQ#!eY-Ft#?B*QscXbc z`ktMx6$Vzio|qWLMmH&O7P_9iN*X%kA;UOPFK?A?t}jrQxkexXh^4K;ellR~Y%9+z zSxNlvo|UaS@h6J5j9B%%b0_MyaC1t>(h}trAr_4nKmVR&T*)jf^ZYJ0Pq0{E?A`?wnPwyi=CrnK;z8 zKJrJxBv%Qnv8`|T8k@b!AF5@D(Q6EtyxMb`aU|yWjcL60e5ZA$9%n6tXFK(qe<|(A z{Mo~w-dZn_M{lh+o;)$zc#JBK1C<49o@cq*t;T__ zib;LaMe^3;K(_(k$y<@FKULdtdfk1;$vcRxYp3U~67^xEigJpb1h*kq1W|bxa)p!N zCge)}xTzTL7GxEKy_492UrTf;bB(@eW0LCvtstm$aicnx)vF?nJ!EA55S41coE6pI zn}{W;h4NhuhuHecr${`Bxk^KvR5=oz6bETj?&HKMlBueTEyLKK`*cGrQd3v#$lRhX zT5M6}eh}q34p#n%rG8n4H`z-F!9Dh|h+#B7{$EWP-$*Y?>|80x#AmFWn2@BK@wuvm z%zVPi$SN#;t=zL*Of+pVt@Z5}E0vYDzBbJGduyIRe{C%xFrR?(WNOUOH)eTK^_?}3 zt%a*6q6}z-Y~*^fUi*bLD+}6+P;fIzynfuIAAk-gO@`Q4sg=|lA>I>MO)=eBht7G1^hA;_AA?Cbq%QvHaHmK#1+TNtt!zrBv>m5qYLDTXe%x_ zh(oV-y@66DzeFJ-p5E!&$yNSCXN4E{2 z$_?GI%58U85#h#PO|`P|ZtS*tS=XERdAlX|b^Dq`+Qn&@bdgoRsoM|6P5F}DE?zWL z-qLN|hj(;~Tpk$Y&IA2%NAD(NUm0A8U{zI`yn6l!#v(1VD=9^OUX`FqD>w40&0Ohh z^NriBmL_jhh|^l-K84E9nA+34;c01oiaM04D%77I=7~TunD`E{fL)#Ncf7RV@8nmN z5xBV>pwGJSs8-qYHK9W+#~tvbU|>o3bzK5dGXLAUR_1?MSIO-8E)!hEw_N=%xmF$p zROkLA9r8zf#7{sqPu;j=lSD-Ren90XVdEpw?m%>W99jkDe|wsdS=K7?I|?}bT(%ae zLXwiK`ej)Zi6<^tk0wk}x&y0=+>`g#i=*VN^&(l^%KpCdC09+v*EGnBnUuZ!L4i(| zh~>bj5^)?<|Do;=P$D+FI2NmKEzmj+Wk#y8s}ixDSM>wa47@I=B#E~Tu`w=7k}B4( z=Db|&%8U)hMAs9C2D-6|5{S)nePL{ztA)u!EL!G{uq2oRESeK0>!B#NIJXKlC&xa! z%psz&SYon9F~-LYe8Y7cjAyp4MB|(=v^rg;-jN5Zh;5mZ$NQ|h+Sx*@8~N?`HX0bXre&op$i{m&Jb2QDmvu(NxhJ zSH&^P;Uw#juA+}7c>?~lD`QV;k1NF@b860G&bP&6jxt&9wGRwRpf-t!dXx)g^@$lJ zjyDd)W>yEq#j^2nC*?*)H&L5`QOnfg-27>e!&uaZVJw-WFbYfFi926l&f6i1cY!dE z(H{)lqDq1)QVVn5mDJ_0OW5}yDz0`~!6EpVqJ zRhaEvQo-u!P3zT&t-kbY*?jm{Ver{sk@+9}joEziS6GkXaT^j=XVXL{+XLikPWZ9k zq)we?P(zdY60oOCe(2Xzh!^iOzg80mq8g8i-pv|nUi3cjE1oDENuN2r=_D>YxaduO z+E-lZJq_N@$W>UC-*(rxq&O2{xi=+oK*6CtcM!8WQV^3q01%@x_D`C08_V!&!WJU6 z#@gD5Tw8@FrOqbY$&G1u;?@~==ZtqBpnu0v^3r={iDK`PP241F?{uY|$h4P%ap2!2D=&DG61g=tDba&!-dyp@ zg<|%`*n~)jtuJ&{ZfHUTTR^oVno36hMY&g8K&m`(321hJrWX$v@n&JQZ(nTW%NOq6 z|H%ERFHN>A9{^B)s|c%H|F4w(<^M`harJ*yDUFi#k@^US(yP`V-^;G!HAn0jhYcsL z{7>9cQtkTHYL~AjKHgzI_fbVAU7V|75*po&5+YgPCLM{y-r}#FnzgcVW+-+d4bfiO zE-h0IMXC$tZQ7KBqI{Obrb#5`{&4fT0_7ngN`z0B@IK;U-g+88;fD&W*bQkFl0?{S zhI^kVP;R{s6ezZ>lx2hcJb{u|`#6D7*iREwzeHV2gDccim`mnT1K5=CEG`q5wu;EM zVD6y~?^y}Ad&pZGq~_n)Bj2*Z>!S1`e5=6B=`JzE%*tcB5@X)W8hS9h3h`)aEjOD5 z;sU3_X$7eP^?h`)TG3VyxE#m~rblzi)G&pex3Sdbg15P>hfDpv$~J%_=N^eO9lQFA z|LBVjBZd9?HLd|3hP9N3VfBYR@Txx&&%#Qgo|Cy*nwy#_GHzB&71WoPWi6Y>@?WK; zp+UYx7X`9~a;2M}7t^GMxFa(fT_;V){3BIw{!~+;*=S(ZskRoqd+Oy|EfRmq<_N27 zZcCEubRzv#n~0}JcS=`*obPoa{TS$2KY!^bIK3!Wc*5^V{+lS5$dW1~5OKs{T7e{kM5?G$fx%!;kzkMgKEhds26%Pr3Os=A2dzcZ(hrd8SD zmFZkct{;q~qBH8+K~v*$i)KoNz`w*N`zJ+gxFsC19iZi;xRy)gT!aH!Bf zpdO#~z85{p8XocaFiISOv|_$}fQ1kewzkUoLW6Y_MY}{%v?u@LcRUA4^k3$`^7<4j z^pWz>^{DCvv)mL{Kdo`{^!ibC{dN6}`Xg4#>5BSU(eIr?|6u)7=kk zR_Mc<7dT_NlsQFAiqzLAr8UU+cS=V`k!oqmx@~w$%iz?>Gx%g(KEeWKi<=L2>8kZi z8%(R#GY6*b#khojH@_*Q3;m_pSy^nZ%NL~`4rI6wXn=Yzw)9m?{y=^Gqz z$rb4fbPVX^yky_Aosn1>4|vKVemO-nzzCJ$B_x-}=2P;_DCrr{%2o2sH`Z0s zA2}IEhl{&mW&fKfop9px=~F3+ae5-lf!Ul5Sj#s~F_~+gj>EV+QUN;82-gns;4zSy zJ(%a)w|i7Jv_g7H|I|rSwq4VraHOfZrZrynnx{{0nbp|phR z!)n-<7EhLds|?HZpG1#oY}()lR^wi_F;`6sGpo}5>vfm(Z)@>BzfFu1-GEdEDo|FTgDR~Rr*4@FN z9XgwoA0AAt#B#lq(esPyPyNNgdfOj*iv3)ype_=LBK2vEt(z_X?FM|EXNHZ94*1hs zrcd6!2K=q9@2wl~fa`-{<%bPLuY0uZLHrmV?EueVyqXL8tbu;+0n*& zmE}zt>!(efxt*=+x3adkZmhTE?vM2%tBv)wvA#CeZGpTE14SWv4q^w#(I_I zO&RN_P8rzF#`>+S?X4T@ZMpkny~t`~eQm6-jrH4Pte5T-j`d2W#(K=lceJryWqDJ^ z`YBT;Z)aouR@U~`jrF$N{jpwTwXwc7*4M`RZ8FwNcM8XPB~xR)I&!q5jrJzfn=;-{ zUpcs)*=BBajc?tE@5eoj7+Ni%xMt$9(!g1e7^^Q(i9b_9DOYx1c9n4I# zl*s$0%mY)WPub4a{mC-;SD9-jQ$bDmvqC~yn;dGBLv3={CX+*=Uxjl-Qpr@|1Vh{> zFkC9^xU)rE0Gl#pOrJHQfBQ1`*`_UF>mDPjBxT&m!`51D2C2;;wHag^&mgvQjX#aV zE`rAnk#n=ljy;>G0@#$S8zw5p5N(=TA?FK(JN!hW%3#yxnrYkZW|tYhx3WEK zA+j7=%^)mho8||hx=hWt$+MM$u z%sIMyZP}D#{8o9`QJSq>-rA>|_`_gU@Ne_D<4R#uW}X>S2exZ7XIC0q{s_FyCm+>D zH~7#KC%ZNU)uy1@6!cMTR%{DK>Y$Kg(%N}=>&v74i_~`cF=*SLkNucNAxF|Mh z=9xZi2YBp>i)71JBinKgs;sB+XQQOs+PqYomumCUi!d)GyV;h_P(c_~<|_S3&n+K> z{{0_`bO~(A%#?24-ma)jJ{@muTiBKpQd}$J&qK;dZThKAKeg%SMVNk6@7l6iM|-W< zd{dvA*pX)%RREhZ(F{!4u1yZMvLS5CX~tH`__K_-s7*4pNv1Z*ya##~Yg(YG#8ojx^!gq*I%8YLm{3GwE#k zp3(V*r8{f#{8yCHB$$+-%qG9?QTsA*oJ#)sxHQTs;NEB6l=3e zZC2U#v&xq3pEXwdT0v&4oZXtiB>iuH-%MCud zC?~ZCm)aCln_{;86r(%fmOZwpj#*{5EIqPg&ouo~0Gl$=%$m7ju;{V7dnW>X; zA7WCH*xD>pn`LUV%!@F~NaxzJNk;jsVhqq<+`+FGPzA6lvrO}psoV9DnyqXJ+wy6~ z*2xBD8JcZvmZ{A$wOQuHm}Tf(TR6*z&nmM_IXk>#Kg*~B*pyjj#D#we zz}B{fZTW-~*UI=4j&f3)Zfes_ZMu08rW@6}wrsM|US+CTUn*yYQ}NM>9d4qj$p5BH zGcALI+ne!OMLGP-o@**n5zo}xrkQXxj z#r$YFJCfO&$z$tQrY;4+U=b^7gG6nRs0|X^WRQsalo=d4vjYRU%(`?jQ)=oR$`%Jw zU2IvbZ<<%kWV(A7_cZn7N9FL1^A|;#wV9D}Y83-Vq4cjCHj=3bhK_`?Hhk2EkJ|9D zO@@y|zuL?pBW?Tv2Tszb*f3>!*V8!l?YMQym)Cc}m5Pn$VRXg^W3W;8SU zFMKL7(FX&Bmexjy+6Yk_A-2f~p*z%O4iUzae1Nx@Ne`!1jt&lHw(5f1ty@b3$q2@b zq_#G8)W(k5*s)EB%#|h($x2oxpl#Ci%^LixxZ+Ih= z%Qr*R+QH0lejqb@FwYyLJ)(}0!f3g^H9tJe>!Z@qQB-K2Hn5$2tHb60UuA;hQV>iM zv7$Cj)TW8rG_g&liMUVciK1^wDO2o|alg-L)N!<^f4Gz_rSheg9d1T&8Q+vCVdl!| z+uM}j3gBNhC%7bplR~Vi%?h9RO<8eHo!-Bl-F2|F^}TiTL|pRz(NZO>%@MUZqBcitlQ}~5r!Ac! zx|g=~G|lP$|LvX6kK{%b$2|d(CE}1n4j=_-4k$s<&P;c^e;)R*ncYYcj1uiE0l|P( zZM$cz?QVB$_bjsl32w;+t{gaU$T5FHxB*AR0VFO+`2&#n2Xdf(+BIb-DN-d_RK3ye zO!s@$?Rr)Hz8}|f+dhj<&&F?_u(zUBiuekZxJ=<2E9$Uya4{ddcF)f`{NBnF;$x>Q zEkwtF8^8_Vh81pzl#=V!XL+(;rx&L@3)xjVgE-%=vPYxBmK?;Foxr>r?jc$CSfE2h62xbe{?lL0{KwpajsS64Y z8V?WwhyX;eLWCx%WGGDaX;Mf80w1H|@~H2^n*{Db_1{9BQKo>8j) z6SKH+*Dmu<{Yw_Kj`%N;W7^MS?@Ridp_ljjnH7W|gdc?8itw|9Qgt6&ne6YLdUu0H z8nTY!j~1b0r5?lCHY@aqahK(u*g)(->_P0Uh&@RsRqCmY7I-#jXHwlU%YM3XWtmTG zko}PTko{J&pQMwT{nQo&)u`nERULF>?98cxPX;g^?9ymUh4=I|%uB%G|!PXqq^=qO2-`%9vQ z8M=(h{ceZv(^cMEEW+Vk`fE5HjP4ExvkzVurOLlf6W?^7hK!}~3ol>0n9Uqp0~pS>ndXaemldDbK<`2CLGP{TJxM23 z?Wv7w{c4TME8oe3*GYlv z$p3hX9IFUP1JKuEKrqQ0G(& z2#tpUAuWo$z_*>M(zx=H3>^cYgNR8yaqMtI$3XPOijJ-*&}g>+dH_9u9#-hlPOcV4 zI+_rkB*k#*B}Jsbb?7l0g^r!dEDb&K_P?W0yF>`01Z~qAZ1mH4YH5GAqZC48ebaC zH#CT-b+9mx$Br!*MD%?jL2O^a0XG8*00n>oD=6R@C1c?J`Z6!F>S}W#oD>7-swjPf z0E<}%0gGhe*r{)(^KEwKb3O9%na|V+;t%2v;%`O#X+CvJKXXyxe}dKYqNrBkD zvMhiW^t~tN>P6VTF=e-ONxM(cMXE+@Q+4ODju(>p%ldT)UQ;uYmw9({6&kV*4dx5i>dS_+ZB|nf<1Sa1i4C+Lv>&wJiuRLq z>Q;T~!FrERe)X+-L_^lmdo-Fj_LUOD**4RAG48V76C3C~=soDY6}>0vB

WUT1N7 zLCv)A6D&6wzCOHfk}smxQT_QWc1-m}^nDe4#P*eH4>yDSgZzX1TakaBQ5^&j9s+?F zZ6jO;_Kg8`*g6oH3nQ$Wh8)}L zH=S=Y$*)IV)_iIN(Ff57(YGS{G@m+DpV^7*lS|F`Ci*O99nnXFv18YhF`aKS(XU5d z7JX_2(Ff57(YGS{G@m*|pV^7%(`(51rusZ+9oZib636!Sjc43U_nWbog`ZhL`9b+X z`K>5FOQ;U%=MJL%sD*8)V6I(OlSdH{Ol zgER*U9=HeS0CWI4*rEeZs?UUj@Uz8362(azWh)O?4^8MgbQp(;i*zubeY0W`Wwhu- zdjV0;5ikN60gSN62%d7ELkZEM=0v{rloB*>9Yzc%BgYOkFnKndc^iZfbI@8r#KZ%1 z06G92EYg7_RhtcuQE{18q{4*v%V-l)VB${;ACEwgaUg-~&;bpQW2YHdnRzR8;B(MH z2kZel03Co1HtB$qiqqjNOOkc^6cuTCa{d_qI}1kX)Z zmSmVTexig&u0s+un7H?4s3bC;dkY|GW}(Fq<^qfWMgSxBFv7CRh$8$g>g7n{=Xa&> zAs@X`)_mpWfey2Iw*U_@11)qA2Y>^>0pPF)4w6&l}sEKg1!oJzGU@-B4wL4G}a z6utH6?XzL<=!f{h{pP_aI8M^#{xU+#WszQsXR88jQt>3)u5$5soo#FTI*)~UgJQYW zZok~(Hz-pf*e~7I$?cP?}efK{v1dspN-tLc;cE9-OPVk+-e!Ffc-Z@j+{o&cG!F%7U zo7H1+gH6vh=HTVOyc!(-E(pGXZU4fPL?U_#|Nk}q&*uU^!k>koy%v1*8~Tv`65IU% zKf|Ai`sb5>zZQ_O7e8Wzev1v_HN^KRY4>u|6XC;MxwYMI9=slWNM68yM7#e2t|NT6 diff --git a/User/Module/Chassis.c b/User/Module/Chassis.c index 00e291a..1ed3fe0 100644 --- a/User/Module/Chassis.c +++ b/User/Module/Chassis.c @@ -21,10 +21,10 @@ static int8_t Chassis_SetCtrl(Chassis_t *c,CMD_t *ctrl){ if (c == NULL) return CHASSIS_ERR_NULL; /*主结构体不能为空 */ - if (ctrl->C_cmd.type== c->ctrl && ctrl->C_cmd.mode== c->mode) return CHASSIS_OK; /*模式未改变直接返回*/ + if (ctrl->CMD_CtrlType== c->ctrl && ctrl->CMD_mode == c->mode) return CHASSIS_OK; /*模式未改变直接返回*/ //此处源代码处做了pid的reset 待添加 - c->ctrl =ctrl->C_cmd.type; - c->mode =ctrl->C_cmd.mode; + c->ctrl =ctrl->CMD_CtrlType ; + c->mode =ctrl->CMD_mode ; return CHASSIS_OK; } //设置控制模式 @@ -42,13 +42,13 @@ int8_t Chassis_UpdateFeedback(Chassis_t *c, const CAN_t *can) { } - c->motorfeedback.rotor_pit6020angle = can->motor.pit6020.as_array[0].rotor_angle; + c->motorfeedback.rotor_pit6020angle = can->motor.pit6020.as_array[0].rotor_ecd; c->motorfeedback.rotor_pit6020rpm = can->motor.pit6020.as_array[0].rotor_speed; - c->motorfeedback.rotor_gimbal_yawangle = can->motor.chassis6020.as_array[0].rotor_angle; + c->motorfeedback.rotor_gimbal_yawangle = can->motor.chassis6020.as_array[0].rotor_ecd; c->motorfeedback.rotor_gimbal_yawrpm = can->motor.chassis6020.as_array[0].rotor_speed; - c->motorfeedback.rotor_gimbal_pitchangle = can->motor.chassis6020.as_array[1].rotor_angle; + c->motorfeedback.rotor_gimbal_pitchangle = can->motor.chassis6020.as_array[1].rotor_ecd; c->motorfeedback.rotor_gimbal_pitchrpm = can->motor.chassis6020.as_array[1].rotor_speed; // c->sick_dis[0] = can->sickfed.raw_dis[0]; @@ -126,7 +126,7 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) switch (c->ctrl) { - case RC: //手动控制 + case RCcontrol: //手动控制 /* 在cmd里对数据进行处理 包括方向和油门 @@ -137,12 +137,7 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) break; - case UP_CONTROL://上层在控制时,底盘速度为0 - c->move_vec.Vw = 0; - c->move_vec.Vx = 0; - c->move_vec.Vy = 0; - break; - + case AUTO : //在自动模式下 switch(c->mode ){ @@ -150,9 +145,9 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) case AUTO_NAVI: //自动雷达 // //这套是全向轮的方向,一定要注意这里的xy方向 - c->move_vec.Vw =ctrl->C_navi.wz*1000 ; - c->move_vec.Vy =-ctrl->C_navi.vy*1000 ; - c->move_vec.Vx =-ctrl->C_navi.vx*1000 ; + 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 ; // c->move_vec.Vw =LowPassFilter2p_Apply(&(c->filled[1]),c->move_vec.Vw); // c->move_vec.Vy =LowPassFilter2p_Apply(&(c->filled[2]),c->move_vec.Vy); // c->move_vec.Vx =LowPassFilter2p_Apply(&(c->filled[3]),c->move_vec.Vx); @@ -182,16 +177,16 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) c->move_vec.Vx =ctrl->Vx*6000 ; c->move_vec.Vy =ctrl->Vy *6000; - c->move_vec .Vw = -ctrl->C_pick .posx; + c->move_vec .Vw = -ctrl->cmd_pick .posx; - if(abs_value(ctrl ->C_pick .posx )>20) + if(abs_value(ctrl ->cmd_pick .posx )>20) { c->move_vec.Vw =PID_calc(&(c->pid.chassis_PICKWzPID_HIGN),(c->move_vec .Vw) ,0); } - else if(abs_value(ctrl ->C_pick .posx )<0.1) + else if(abs_value(ctrl ->cmd_pick .posx )<0.1) { c->move_vec.Vw =0; } @@ -202,7 +197,7 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) c->vofa_send[0]=c->move_vec.Vw; - c->vofa_send[1]=-ctrl->C_pick .posx; + c->vofa_send[1]=-ctrl->cmd_pick .posx; @@ -229,7 +224,7 @@ int8_t Chassis_Control(Chassis_t *c,CMD_t *ctrl,CAN_Output_t *out) { c->final_out.final_3508out[i] = PID_calc(&(c->pid.chassis_3508VecPID[i]),c->motorfeedback.rotor_rpm3508[i],c->hopemotorout.OmniSpeedOut[i]); - out->motor3508.as_array[i] = c->final_out.final_3508out[i]; + out->motor_CHASSIS3508 .as_array[i] = c->final_out.final_3508out[i]; } diff --git a/User/Module/Chassis.h b/User/Module/Chassis.h index d5131e3..138cde6 100644 --- a/User/Module/Chassis.h +++ b/User/Module/Chassis.h @@ -118,8 +118,8 @@ typedef struct{ const Chassis_Param_t *param; //一些固定的参数 ChassisImu_t pos088; //088的实时姿态 - CMD_Chassis_CtrlType_e ctrl; - CMD_Chassis_mode_e mode; + CMD_CtrlType_t ctrl; + CMD_mode_t mode; ChassisMove_Vec move_vec; //由控制任务决定 diff --git a/User/Module/config.c b/User/Module/config.c index fa243e0..b4acbaf 100644 --- a/User/Module/config.c +++ b/User/Module/config.c @@ -8,19 +8,84 @@ #define DEG_TO_RAD(x) ((x) * (3.141592653 / 180.0)) //角度转弧度 - - #ifdef DEBUG -ConfigParam_t param_chassis ={ +ConfigParam_t param ={ #else -static const ConfigParam_t param_chassis ={ +static const ConfigParam_t param ={ + #endif + .up={ + + + /*上层pid参数*/ +.Shoot_M2006_angle_param = { + .p = 25.0f, + .i = 0.0f, + .d = 1.5f, + .i_limit = 1000.0f, + .out_limit = 3000.0f, +}, +.Shoot_M2006_speed_param = { + .p = 5.0f, + .i = 0.3f, + .d = 0.0f, + .i_limit = 2000.0f, + .out_limit = 3000.0f, +}, +.Pitch_M2006_angle_param = { + .p = 25.0f, + .i = 0.0f, + .d = 1.5f, + .i_limit = 1000.0f, + .out_limit = 3000.0f, +}, +.Pitch_M2006_speed_param={ + .p = 5.0f, + .i = 0.3f, + .d = 0.0f, + .i_limit = 2000.0f, + .out_limit = 3000.0f, +}, - .chassis = {/**/ + +.go_cmd={ + .id =0, + .mode = 1, + .K_P = 1.0f, + .K_W = 0.05, + .Pos = 0, + .W = 0, + .T = 0, + +}, + + +/*上层其他参数*/ + /*运球*/ + .DribbleConfig_Config = { + .m3508_init_angle = 50, + .m3508_high_angle = 1200, + .go2_init_angle = 0, + .go2_flip_angle = -250, + .flip_timing = 200, + .go2_release_threshold = -550.0f, +}, + /*投球*/ + .PitchConfig_Config = { + .m2006_init_angle =-150, + .m2006_trigger_angle =0, + .go1_init_position = 0, + .go1_release_threshold =0, + .m2006_Screw_init=0 +}, + + + }, + .chassis = {/**/ .M3508_param = { @@ -47,93 +112,31 @@ static const ConfigParam_t param_chassis ={ }, -// .M3508_param = { -// .p = 10.0f, -// .i = 0.0f, -// .d = 0.0f, -// .i_limit = 0.0f, -// .out_limit =10000.0f, -// }, - -////高速那一套 - .NaviVx_param ={ - .p = 1.15f, - .i = 0.0f, - .d = 0.15f, - .i_limit = 0.0f, - .out_limit =5000.0f, - }, - .NaviVy_param ={ - .p = 1.15f, - .i = 0.0f, - .d = 0.15f, - .i_limit = 0.0f, - .out_limit =5000.0f, - }, - .NaviVw_param ={ - .p = 1.15f, - .i = 0.0f, - .d = 0.15f, - .i_limit = 0.0f, - .out_limit =5000.0f, - }, -// - -//低速那一套 -// .NaviVx_param ={ -// .p = 1.04f, -// .i = 0.0f, -// .d = 0.15f, -// .i_limit = 0.0f, -// .out_limit =5000.0f, -// }, -// .NaviVy_param ={ -// .p = 1.1f, -// .i = 0.0f, -// .d = 0.15f, -// .i_limit = 0.0f, -// .out_limit =5000.0f, -// }, -// .NaviVw_param ={ -// .p = 1.5f, -// .i = 0.0f, -// .d = 0.15f, -// .i_limit = 0.0f, -// .out_limit =5000.0f, -// }, - .Sick_CaliYparam ={ - .p =2.5f, - .i =0.001f, - .d =0.1f, - .i_limit =15.0f, - .out_limit =500.0f, - }, - .Sick_CaliXparam ={ - .p =2.5f, - .i =0.001f, - .d =0.1f, - .i_limit =15.0f, - .out_limit =500.0f, - - } - }, - + .can = { - .pitch6020 = BSP_CAN_1, - .motor3508 = BSP_CAN_1, - .chassis6020 = BSP_CAN_2, + .pitch6020 = BSP_CAN_1, + .motor_CHASSIS3508 = BSP_CAN_1, + .motor_UP3508 = BSP_CAN_2, + +// .chassis6020 = BSP_CAN_1,//禁用 + .chassis5065 = BSP_CAN_1, + .sick = BSP_CAN_2, }, }; const ConfigParam_t *Config_ChassisGet(void) { - return ¶m_chassis; + return ¶m; } - +///*获取导航地图*/ +//void set_ops_path(ConfigParam_t *config, const point_t *path, int8_t path_num) { +// config->ops.path = path; +// config->ops.path_num = path_num; +//} /** * \brief 从Flash读取配置信息 * @@ -142,11 +145,11 @@ const ConfigParam_t *Config_ChassisGet(void) void Config_Get(Config_t *cfg) { BSP_Flash_ReadBytes(CONFIG_BASE_ADDRESS, (uint8_t *)cfg, sizeof(*cfg)); // /* 防止第一次烧写后访问NULL指针 */ - cfg->chassis_config = ¶m_chassis; - if (cfg->chassis_config == NULL) cfg->chassis_config = ¶m_chassis; + cfg->config = ¶m; + if (cfg->config == NULL) cfg->config = ¶m; /* 防止擦除后全为1 */ - if ((uint32_t)(cfg->chassis_config) == UINT32_MAX) - cfg->chassis_config = ¶m_chassis; + if ((uint32_t)(cfg->config) == UINT32_MAX) + cfg->config = ¶m; if (memcmp(&cfg->cali_088.gyro_offset.x, "\xFF\xFF\xFF\xFF", 4) == 0) { cfg->cali_088.gyro_offset.x = 0.0f; diff --git a/User/Module/config.h b/User/Module/config.h index 9ba1c14..11df62a 100644 --- a/User/Module/config.h +++ b/User/Module/config.h @@ -1,14 +1,16 @@ #ifndef _CONFIG_H #define _CONFIG_H -#include "Chassis.h" #include "can_use.h" #include "ahrs.h" #include "map.h" - +#include "up.h" +#include "chassis.h" typedef struct{ -Chassis_Param_t chassis; /**/ +UP_Param_t up; +Chassis_Param_t chassis; + CAN_Params_t can; AHRS_Eulr_t mech_zero[4]; @@ -16,7 +18,7 @@ AHRS_Eulr_t mech_zero[4]; typedef struct{ -const ConfigParam_t *chassis_config; +const ConfigParam_t *config; BMI088_Cali_t cali_088; diff --git a/User/Module/up.c b/User/Module/up.c new file mode 100644 index 0000000..43b1812 --- /dev/null +++ b/User/Module/up.c @@ -0,0 +1,253 @@ +#include "up.h" +#include "gpio.h" +#include "user_math.h" +#include "bsp_buzzer.h" +#include "bsp_delay.h" + +#define GEAR_RATIO_2006 (36) // 2006减速比 +#define GEAR_RATIO_3508 (19) + +#define CAN_MOTOR_ENC_RES 8191 // 编码器分辨率 +#define MOTOR2006_ECD_TO_ANGLE (360.0 / 8191.0 / (GEAR_RATIO_2006)) //2006编码值转轴角度 +#define MOTOR3508_ECD_TO_ANGLE (360.0 / 8191.0 / (GEAR_RATIO_3508)) //3508编码值转轴角度 + + +// 定义继电器控制 +#define RELAY1_TOGGLE(state) HAL_GPIO_WritePin(GPIOE, GPIO_PIN_9, (state) ? GPIO_PIN_SET : GPIO_PIN_RESET) +#define RELAY2_TOGGLE(state) HAL_GPIO_WritePin(GPIOE, GPIO_PIN_11, (state) ? GPIO_PIN_SET : GPIO_PIN_RESET) + +int8_t up_init(UP_t *u,const UP_Param_t *param,float target_freq) +{ + u->param = param; /*初始化参数 */ + + /*pid初始化*/ + PID_init (&u->pid.VESC_5065_M1 ,PID_POSITION ,&(u->param ->VESC_5065_M1_param )); + PID_init (&u->pid.VESC_5065_M2 ,PID_POSITION ,&(u->param ->VESC_5065_M2_param )); + + PID_init (&u->pid .Shoot_M2006angle ,PID_POSITION ,&(u->param->Shoot_M2006_angle_param )); + PID_init (&u->pid .Shoot_M2006speed ,PID_POSITION ,&(u->param->Shoot_M2006_speed_param )); + + PID_init (&u->pid .Pitch_M2006_angle ,PID_POSITION ,&(u->param->Pitch_M2006_angle_param )); + PID_init (&u->pid .Pitch_M2006_speed ,PID_POSITION ,&(u->param->Pitch_M2006_speed_param )); + + + u->go_cmd =u->param ->go_cmd ; + + // 初始化上层状态机 + if (!u->DribbleContext .is_initialized) { //检查是否为第一次运行状态机,运球 + u->DribbleContext .DribbleConfig = u->param ->DribbleConfig_Config ;//赋值 + u->DribbleContext .DribbleState = Dribble_PREPARE; + u->DribbleContext .is_initialized = 1; + + } + + if (!u->PitchContext .is_initialized) { + u->PitchContext .PitchConfig = u->param ->PitchConfig_Config ;//赋值 + u->PitchContext .PitchState = PITCH_PREPARE; //状态更新,开始夹球 + u->PitchContext .is_initialized = 1; + } + + BSP_UART_RegisterCallback(BSP_UART_RS485, BSP_UART_RX_CPLT_CB, USART6_RxCompleteCallback);//注册串口回调函数,bsp层 + +} + +/*can,上层状态更新*/ +int8_t UP_UpdateFeedback(UP_t *u, const CAN_t *can, CMD_t *c) { + + + + u->motorfeedback .VESC_5065_M1_rpm =can ->motor .chassis5065 .as_array [0].rotor_speed ; + u->motorfeedback .VESC_5065_M2_rpm =can ->motor .chassis5065 .as_array [1].rotor_speed ; + + + for(int i=0;i<4;i++){ + u->motorfeedback .DJmotor_feedback[i].rpm =can ->motor .motor3508 .as_array [i].rotor_speed ; + u->motorfeedback .DJmotor_feedback[i].ecd =can ->motor .motor3508 .as_array [i].rotor_ecd ; + DJ_processdata(&u->motorfeedback .DJmotor_feedback [i], MOTOR2006_ECD_TO_ANGLE); + } + + u->cmd =c; + + return 0; +} + +int8_t DJ_processdata(DJmotor_feedback_t *f,fp32 ecd_to_angle) +{ + int8_t cnt=0; + fp32 angle ,delta; + + angle = f->ecd; + if (f->init_cnt < 50) { + f->orig_angle= angle; + f->last_angle = angle; + f->init_cnt++; + return 0; + } + + + delta = angle - f->last_angle; + if (delta > 4096) { + f->round_cnt--; + } else if (delta < -4096) { + f->round_cnt++; + } + f->last_angle = angle; + f->total_angle=(f->round_cnt*8191+(angle -f->orig_angle ))*ecd_to_angle; + +} +/* + 这里id范围为1-4, +*/ +int8_t DJ_Angle_Control(UP_t *u,int id,DJmotor_feedback_t *f,pid_type_def *Angle_pid,pid_type_def *Speed_pid,fp32 target_angle) +{ + fp32 delta_angle,delta_speed; + delta_angle = PID_calc(Angle_pid , f->total_angle , target_angle); + delta_speed = PID_calc(Speed_pid , f->rpm , delta_angle); + + u->final_out .DJfinal_out [id-1]=delta_speed; + return 0; +} + +int8_t VESC_M5065_Control(UP_t *u,fp32 speed) +{ + u->motor_target .VESC_5065_M1_rpm =speed; + u->motor_target .VESC_5065_M2_rpm =speed; + + u->final_out .final_VESC_5065_M1out =-u->motor_target .VESC_5065_M1_rpm; + u->final_out .final_VESC_5065_M2out =u->motor_target .VESC_5065_M2_rpm; + + return 0; + +} + + + + +/*go电机控制*/ + +int8_t GO_SendData(UP_t *u, float pos, float limit) +{ + static int is_calibration=0; + static fp32 error=0; //误差量 + + GO_MotorData_t *GO_calibration;//校准前,原始数据 + GO_calibration = get_GO_measure_point() ; + if(is_calibration==0) + { + is_calibration=HAL_GPIO_ReadPin (GPIOE ,GPIO_PIN_9 ); + u->go_cmd.Pos = -50; //上电之后跑 + error= GO_calibration->Pos ; + } + u->motorfeedback .go_data = GO_calibration; + u->motorfeedback .go_data ->Pos= error ; + u->go_cmd.Pos = pos; + + // 读取参数 + float tff = u->go_cmd.T; // 前馈力矩 + float kp = u->go_cmd.K_P; // 位置刚度 + float kd = u->go_cmd.K_W; // 速度阻尼 + float q_desired = u->go_cmd.Pos; // 期望位置(rad) + float q_current = u->motorfeedback.go_data->Pos; // 当前角度位置(rad) + float dq_desired = u->go_cmd.W; // 期望角速度(rad/s) + float dq_current = u->motorfeedback.go_data->W; // 当前角速度(rad/s) + + // 计算输出力矩 tau + float tau = tff + kp * (q_desired - q_current) + kd * (dq_desired - dq_current); + + /*限制最大输入来限制最大输出*/ + if (pos - q_current > limit) { + u->go_cmd.Pos = q_current + limit; // 限制位置 + }else if (pos - q_current < -limit) { + u->go_cmd.Pos = q_current - limit; // 限制位置 + }else { + u->go_cmd.Pos = pos; // 允许位置 + } + + // 发送数据 + GO_M8010_send_data(&u->go_cmd); + + + return 0; +} + +int8_t ALL_Motor_Control(UP_t *u,CAN_Output_t *out) +{ + //电机控制 ,传进can + DJ_Angle_Control(u,1,&u->motorfeedback .DJmotor_feedback[0] , + &u->pid .Shoot_M2006angle , + &u->pid .Shoot_M2006speed , + u->motor_target .Shoot_M2006_angle ); + DJ_Angle_Control(u,2,&u->motorfeedback .DJmotor_feedback[1] , + &u->pid .Pitch_M2006_angle , + &u->pid .Pitch_M2006_speed , + u->motor_target .Pitch_M2006_angle ); + GO_SendData(u,u->motor_target .go_shoot,1 ); + + + for(int i=0;i<4;i++){ + out ->motor_UP3508.as_array[i]=u->final_out.DJfinal_out [i] ; + } + + out ->chassis5065 .erpm [0]= u->final_out .final_VESC_5065_M1out ; + out ->chassis5065 .erpm [1]= -u->final_out .final_VESC_5065_M2out ; + + return 0; + + +} + + + + + +int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c) +{ + + if(u ==NULL) return 0; + static int is_pitch=1; + switch (c->CMD_CtrlType ) + { + case RCcontrol: //在手动模式下 + + switch (c-> CMD_mode ) + { + + case Normal : + /*投篮*/ + if(is_pitch){ + u->motor_target .go_shoot =u->PitchContext .PitchConfig .go1_init_position ; + is_pitch=0; + } + +// + + break; + + case Pitch : + if (u->PitchContext .PitchState ==PITCH_PREPARE) //首次启动 + { + u->PitchContext .PitchState=PITCH_START;//置标志位用于启动投篮 + } + + + + break ; + + + +return 0; + + +} + +} + } + + + + + + + + + diff --git a/User/Module/up.h b/User/Module/up.h new file mode 100644 index 0000000..cc81c4f --- /dev/null +++ b/User/Module/up.h @@ -0,0 +1,233 @@ +#ifndef UP_H +#define UP_H + + +#include "struct_typedef.h" +#include "pid.h" +#include "bmi088.h" +#include "user_math.h" +#include "ahrs.h" +#include "can_use.h" +#include "cmd.h" +#include "filter.h" +#include "vofa.h" +#include "GO_M8010_6_Driver.h" +#include "bsp_usart.h" + +/* + 状态机 + +状态结构体,触发标志位结构体 + +配置层,-->config.c + | +中间层,-->up.h,统一UP_t + | +运行函数,switch(状态) 运行相应函数 + + + + + + + + + + + +*/ + + + + +/* 投球状态定义 */ +typedef enum { + PITCH_PREPARE, // 准备阶段 + PITCH_START, //启动,拉扳机 + PITCH_PULL_TRIGGER, + PITCH_LAUNCHING, // 发射中 + PITCH_COMPLETE // 完成 +} PitchState_t; + +/* 投球参数配置 */ +typedef struct { + fp32 m2006_init_angle; // M2006初始角度-140 + fp32 m2006_trigger_angle; // M2006触发角度0,用来合并扳机 + fp32 go1_init_position; // GO电机触发位置,0,初始位置 + fp32 go1_release_threshold; // go上升去合并扳机,扳机位置 + fp32 m2006_Screw_init; +} PitchConfig_t; + +/* 投球控制上下文 */ +typedef struct { + PitchState_t PitchState; + PitchConfig_t PitchConfig; + + uint8_t is_initialized ; +} PitchContext_t; + + + + + + + + +/*运球*/ +typedef enum { + Dribble_PREPARE, + STATE_GRAB_BALL, // 夹球升起阶段 + STATE_RELEASE_BALL, // 释放球体 + STATE_CATCH_PREP, // 接球准备 + STATE_CATCH_BALL, // 接球动作 + STATE_TRANSFER, //转移球 + STATE_CATCH_DONE //完成 +} DribbleState_t; + +/* 参数配置结构体 */ +typedef struct { + fp32 m3508_init_angle; // 3508初始角度 + fp32 m3508_high_angle; // 3508升起角度 + fp32 go2_init_angle; // GO2初始角度 + fp32 go2_flip_angle; // GO2翻转角度 + fp32 flip_timing; // 翻转触发时机 + fp32 go2_release_threshold; // 释放球 +} DribbleConfig_t; + +/* 状态机上下文 */ +typedef struct { + DribbleState_t DribbleState; + DribbleConfig_t DribbleConfig; + + uint8_t is_initialized; + +} DribbleContext_t; + + +typedef struct { + + BMI088_t bmi088; + + AHRS_Eulr_t imu_eulr;//解算后存放欧拉角(弧度制) + +}UP_Imu_t; + +typedef struct +{ + + pid_param_t VESC_5065_M1_param; + pid_param_t VESC_5065_M2_param; + + pid_param_t Shoot_M2006_speed_param; + pid_param_t Shoot_M2006_angle_param; + + pid_param_t Pitch_M2006_speed_param; + pid_param_t Pitch_M2006_angle_param; + + DribbleConfig_t DribbleConfig_Config; + PitchConfig_t PitchConfig_Config; + + GO_MotorCmd_t go_cmd; +}UP_Param_t; + +typedef struct +{ + fp32 ecd; + fp32 rpm; + + fp32 orig_angle; + fp32 last_angle; + int32_t round_cnt; + uint16_t init_cnt; + fp32 total_angle; +}DJmotor_feedback_t; + + +typedef struct{ + + uint8_t up_task_run; + const UP_Param_t *param; + /*运球过程*/ + DribbleContext_t DribbleContext; + /*投篮过程*/ + PitchContext_t PitchContext; + + + UP_Imu_t pos088; + + CMD_t *cmd; + + struct{ + + fp32 VESC_5065_M1_rpm; + fp32 VESC_5065_M2_rpm; + + GO_MotorData_t *go_data;//存放go电机数据 + + DJmotor_feedback_t DJmotor_feedback[4]; + + + }motorfeedback; + + + + struct{ + + fp32 VESC_5065_M1_rpm; + fp32 VESC_5065_M2_rpm; + + fp32 Shoot_M2006_angle; + fp32 Pitch_M2006_angle; + + fp32 go_shoot; + + }motor_target; + + struct{ + + + pid_type_def VESC_5065_M1; + pid_type_def VESC_5065_M2; + + pid_type_def Shoot_M2006angle; + pid_type_def Shoot_M2006speed; + + pid_type_def Pitch_M2006_angle; + pid_type_def Pitch_M2006_speed; + + }pid; + GO_MotorCmd_t go_cmd; + + + + + /*经PID计算后的实际发送给电机的实时输出值*/ + struct + { + fp32 DJfinal_out[4]; + fp32 final_VESC_5065_M1out; + fp32 final_VESC_5065_M2out; + + + }final_out; + + LowPassFilter2p_t filled[6]; /* 输出滤波器滤波器数组 */ + + fp32 vofa_send[8]; + + + +} UP_t; + + +int8_t up_init(UP_t *u,const UP_Param_t *param,float target_freq); +int8_t UP_UpdateFeedback(UP_t *u, const CAN_t *can, CMD_t *c) ; +int8_t VESC_M5065_Control(UP_t *u,fp32 speed); +int8_t GO_SendData(UP_t *u,float pos,float limit); +int8_t UP_control(UP_t *u,CAN_Output_t *out,CMD_t *c); +int8_t ALL_Motor_Control(UP_t *u,CAN_Output_t *out); +int8_t DJ_processdata(DJmotor_feedback_t *f,fp32 ecd_to_angle); +int8_t DJ_Angle_Control(UP_t *u,int id,DJmotor_feedback_t *f,pid_type_def *Angle_pid,pid_type_def *Speed_pid,fp32 target_angle); + + +#endif diff --git a/User/bsp/bsp_usart.c b/User/bsp/bsp_usart.c index 369a7d7..4843fac 100644 --- a/User/bsp/bsp_usart.c +++ b/User/bsp/bsp_usart.c @@ -9,9 +9,9 @@ static BSP_UART_t UART_Get(UART_HandleTypeDef *huart) { if (huart->Instance == USART3) return BSP_UART_REMOTE; else if (huart->Instance == USART1) - return BSP_UART_VOFA; - else if (huart->Instance == USART6) return BSP_UART_NUC; + else if (huart->Instance == USART6) + return BSP_UART_RS485; /* else if (huart->Instance == USARTX) return BSP_UART_XXX; @@ -94,10 +94,10 @@ UART_HandleTypeDef *BSP_UART_GetHandle(BSP_UART_t uart) { switch (uart) { case BSP_UART_REMOTE: return &huart3; - case BSP_UART_VOFA: - return &huart1; - case BSP_UART_NUC: + case BSP_UART_RS485: return &huart6; + case BSP_UART_NUC: + return &huart1; /* case BSP_UART_XXX: return &huartX; @@ -108,7 +108,6 @@ UART_HandleTypeDef *BSP_UART_GetHandle(BSP_UART_t uart) { } - int8_t BSP_UART_RegisterCallback(BSP_UART_t uart, BSP_UART_Callback_t type, void (*callback)(void)) { if (callback == NULL) return BSP_ERR_NULL; diff --git a/User/bsp/bsp_usart.h b/User/bsp/bsp_usart.h index cc8d13f..cef04b6 100644 --- a/User/bsp/bsp_usart.h +++ b/User/bsp/bsp_usart.h @@ -12,7 +12,7 @@ typedef enum { BSP_UART_REMOTE, - BSP_UART_VOFA, + BSP_UART_RS485, BSP_UART_NUC, /* BSP_UART_XXX, */ BSP_UART_NUM, diff --git a/User/device/GO_M8010_6_Driver.c b/User/device/GO_M8010_6_Driver.c new file mode 100644 index 0000000..626c84b --- /dev/null +++ b/User/device/GO_M8010_6_Driver.c @@ -0,0 +1,108 @@ +/** + *go控制程序 + */ +#include "GO_M8010_6_Driver.h" +#include "usart.h" +#include "bsp_usart.h" +#include +#include "crc16.h" +#include + +#define SATURATE(_IN, _MIN, _MAX) \ + { \ + if ((_IN) <= (_MIN)) \ + (_IN) = (_MIN); \ + else if ((_IN) >= (_MAX)) \ + (_IN) = (_MAX); \ + } +GO_MotorCmd_t cmd_gogogo ; +RIS_ControlData_t motor_send_data; + + +GO_MotorData_t data = {0}; // 确保 data 定义在此处 +uint8_t rx_buffer[sizeof(data.motor_recv_data)] = {0}; // 确保 rx_buffer 定义在此处 + + + + + + +/// @brief 将发送给电机的浮点参数转换为定点类型参数 +/// @param motor_s 要转换的电机指令结构体 +void modify_data(GO_MotorCmd_t *motor_s) +{ + motor_send_data.head[0] = 0xFE; + motor_send_data.head[1] = 0xEE; + + SATURATE(motor_s->id, 0, 15); + SATURATE(motor_s->mode, 0, 7); + SATURATE(motor_s->K_P, 0.0f, 25.599f); + SATURATE(motor_s->K_W, 0.0f, 25.599f); + SATURATE(motor_s->T, -127.99f, 127.99f); + SATURATE(motor_s->W, -804.00f, 804.00f); + SATURATE(motor_s->Pos, -411774.0f, 411774.0f); + + motor_send_data.mode.id = motor_s->id; + motor_send_data.mode.status = motor_s->mode; + motor_send_data.comd.k_pos = motor_s->K_P / 25.6f * 32768.0f; + motor_send_data.comd.k_spd = motor_s->K_W / 25.6f * 32768.0f; + motor_send_data.comd.pos_des = motor_s->Pos / 6.28318f * 32768.0f; + motor_send_data.comd.spd_des = motor_s->W / 6.28318f * 256.0f; + motor_send_data.comd.tor_des = motor_s->T * 256.0f; + motor_send_data.CRC16 = CRC16_Calc( (uint8_t *)&motor_send_data, sizeof(RIS_ControlData_t) - sizeof(motor_send_data.CRC16),0); +} + +/// @brief 将接收到的定点类型原始数据转换为浮点参数类型 +/// @param motor_r 要转换的电机反馈结构体 +void extract_data(GO_MotorData_t *motor_r) +{ + if (motor_r->motor_recv_data.head[0] != 0xFD || motor_r->motor_recv_data.head[1] != 0xEE) + { + motor_r->correct = 0; + return; + } + motor_r->calc_crc = CRC16_Calc((uint8_t *)&motor_r->motor_recv_data, sizeof(RIS_MotorData_t) - sizeof(motor_r->motor_recv_data.CRC16),0); + if (motor_r->motor_recv_data.CRC16 != motor_r->calc_crc) + { + memset(&motor_r->motor_recv_data, 0, sizeof(RIS_MotorData_t)); + motor_r->correct = 0; + motor_r->bad_msg++; + return; + } + else + { + motor_r->motor_id = motor_r->motor_recv_data.mode.id; + motor_r->mode = motor_r->motor_recv_data.mode.status; + motor_r->Temp = motor_r->motor_recv_data.fbk.temp; + motor_r->MError = motor_r->motor_recv_data.fbk.MError; + motor_r->W = ((float)motor_r->motor_recv_data.fbk.speed / 256.0f) * 6.28318f; + motor_r->T = ((float)motor_r->motor_recv_data.fbk.torque) / 256.0f; + motor_r->Pos = 6.28318f * ((float)motor_r->motor_recv_data.fbk.pos) / 32768.0f; + motor_r->footForce = motor_r->motor_recv_data.fbk.force; + motor_r->correct = 1; + return; + } +} +void GO_M8010_send_data(GO_MotorCmd_t *cmd) +{ + modify_data(cmd); + + HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_RS485), (uint8_t *)(&motor_send_data), sizeof(motor_send_data)); + osDelay (1); + HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_RS485), rx_buffer, sizeof(rx_buffer)); + +} + +void USART6_RxCompleteCallback(void ) +{ + + UART_HandleTypeDef *huart6 = BSP_UART_GetHandle(BSP_UART_RS485); + uint16_t crc = CRC16_Calc(rx_buffer,sizeof(rx_buffer)-2,0x0000); + + memcpy(&data.motor_recv_data, rx_buffer, sizeof(data.motor_recv_data)); // Copy received data + extract_data(&data); +} +const GO_MotorData_t *get_GO_measure_point(void) +{ + return &data; +} diff --git a/User/device/GO_M8010_6_Driver.h b/User/device/GO_M8010_6_Driver.h new file mode 100644 index 0000000..d6b418e --- /dev/null +++ b/User/device/GO_M8010_6_Driver.h @@ -0,0 +1,116 @@ +#ifndef __GO_M8010_6_H +#define __GO_M8010_6_H + +#include "struct_typedef.h" +#pragma pack(1) +/** + * @brief ģʽϢ + * + */ +typedef struct +{ + uint8_t id : 4; // ID: 0,1...,13,14 15ʾе㲥(ʱ޷) + uint8_t status : 3; // ģʽ: 0. 1.FOCջ 2.У׼ 3. + uint8_t reserve : 1; // λ +} RIS_Mode_t; // ģʽ 1Byte + +/** + * @brief ״̬Ϣ + * + */ +typedef struct +{ + int16_t tor_des; // ؽŤ unit: N.m (q8) + int16_t spd_des; // ؽٶ unit: rad/s (q8) + int32_t pos_des; // ؽλ unit: rad (q15) + int16_t k_pos; // ؽڸնϵ unit: -1.0-1.0 (q15) + int16_t k_spd; // ؽϵ unit: -1.0-1.0 (q15) + +} RIS_Comd_t; // Ʋ 12Byte + +/** + * @brief ״̬Ϣ + * + */ +typedef struct +{ + int16_t torque; // ʵʹؽŤ unit: N.m (q8) + int16_t speed; // ʵʹؽٶ unit: rad/s (q8) + int32_t pos; // ʵʹؽλ unit: rad (q15) + int8_t temp; // ¶: -128~127C + uint8_t MError : 3; // ʶ: 0. 1. 2. 3.ѹ 4. 5-7. + uint16_t force : 12; // ѹ 12bit (0-4095) + uint8_t none : 1; // λ +} RIS_Fbk_t; // ״̬ 11Byte + +/** + * @brief ݰʽ + * + */ +typedef struct +{ + uint8_t head[2]; // ͷ 2Byte + RIS_Mode_t mode; // ģʽ 1Byte + RIS_Comd_t comd; // 12Byte + uint16_t CRC16; // CRC 2Byte + +} RIS_ControlData_t; // 17Byte + +/** + * @brief ݰʽ + * + */ +typedef struct +{ + uint8_t head[2]; // ͷ 2Byte + RIS_Mode_t mode; // ģʽ 1Byte + RIS_Fbk_t fbk; // 11Byte + uint16_t CRC16; // CRC 2Byte + +} RIS_MotorData_t; // 16Byte + +#pragma pack() + +/// @brief ָṹ +typedef struct +{ + unsigned short id; // ID15㲥ݰ + unsigned short mode; // 0: 1:FOC 2:궨 + float T; // ؽڵ()(Nm) + float W; // ؽٶ(ٶ)(rad/s) + float Pos; // ؽλ(rad) + float K_P; // ؽڸնϵ(0-25.599) + float K_W; // ؽٶϵ(0-25.599) + + +} GO_MotorCmd_t; + +/// @brief ṹ +typedef struct +{ + unsigned char motor_id; // ID + unsigned char mode; // 0: 1:FOC 2:궨 + int Temp; // ¶ + int MError; // + float T; // ǰʵʵ()(Nm) + float W; // ǰʵʵٶ(ٶ)(rad/s) + float Pos; // ǰλ(rad) + int correct; // Ƿ(10) + int footForce; // ԭʼֵ + + uint16_t calc_crc; + uint32_t timeout; // ͨѶʱ + uint32_t bad_msg; // CRCУ + RIS_MotorData_t motor_recv_data; // ݽṹ + +} GO_MotorData_t; + +void modify_data(GO_MotorCmd_t *motor_s); +void extract_data(GO_MotorData_t *motor_r); +const GO_MotorData_t *get_GO_measure_point(void); +void GO_M8010_send_data( GO_MotorCmd_t *cmd); +void USART6_RxCompleteCallback(void ); + + + +#endif /*__GO_M8010_6_H */ diff --git a/User/device/can_use.c b/User/device/can_use.c index b48339e..5d48677 100644 --- a/User/device/can_use.c +++ b/User/device/can_use.c @@ -12,10 +12,12 @@ #define CAN_MOTOR_CUR_RES (16384) -#define CAN_GM6020_CTRL_ID_BASE (0x1ff) +//#define CAN_GM6020_CTRL_ID_BASE (0x1ff) //禁用 #define CAN_PITCH6020_CTRL_ID (0x2ff) -#define CAN_G3508_CTRL_ALL_ID (0x200) +#define CAN_G3508_CTRL_ALL_CHASSIS_ID (0x200) +#define CAN_G3508_CTRL_ALL_UP_ID (0x1ff) + #define CAN_VESC_CTRL_ID_BASE (0x300) @@ -41,12 +43,12 @@ static CAN_t *gcan; static void CAN_DJIMotor_Decode(CAN_MotorFeedback_t *feedback, const uint8_t *raw) { if (feedback == NULL || raw == NULL) return; - uint16_t raw_angle = (uint16_t)((raw[0] << 8) | raw[1]); + uint16_t raw_ecd = (uint16_t)((raw[0] << 8) | raw[1]); int16_t raw_current = (int16_t)((raw[4] << 8) | raw[5]); feedback->rotor_speed = (int16_t)((raw[2] << 8) | raw[3]); feedback->temp = raw[6]; - feedback->rotor_angle = raw_angle / (float)CAN_MOTOR_ENC_RES * 360.0f; + feedback->rotor_ecd = raw_ecd / (float)CAN_MOTOR_ENC_RES * 360.0f; feedback->torque_current = raw_current * CAN_GM6020_MAX_ABS_CUR / (float)CAN_MOTOR_CUR_RES; } @@ -144,49 +146,49 @@ int8_t CAN_DJIMotor_Control(CAN_MotorGroup_e group, CAN_Output_t *output, CAN_t *can) { if (output == NULL) return DEVICE_ERR_NULL; - int16_t motor1, motor2, motor3, motor4, motor5 ; + int16_t motor1, motor2, motor3, motor4, motor5, motor6, motor7; switch (group) { - case CAN_MOTOR_CHASSIS6020: - motor1 = - (int16_t)(output->chassis6020.named.m1); - motor2 = - (int16_t)(output->chassis6020.named.m2); - motor3 = - (int16_t)(output->chassis6020.named.m3); - motor4 = - (int16_t)(output->chassis6020.named.m4); +// case CAN_MOTOR_CHASSIS6020: //(总线0x1ff的6020禁用,怕和3508冲突) +// motor1 = +// (int16_t)(output->chassis6020.named.m1); +// motor2 = +// (int16_t)(output->chassis6020.named.m2); +// motor3 = +// (int16_t)(output->chassis6020.named.m3); +// motor4 = +// (int16_t)(output->chassis6020.named.m4); - raw_tx.tx_header.StdId = CAN_GM6020_CTRL_ID_BASE; - raw_tx.tx_header.IDE = CAN_ID_STD; - raw_tx.tx_header.RTR = CAN_RTR_DATA; - raw_tx.tx_header.DLC = CAN_MOTOR_TX_BUF_SIZE; +// raw_tx.tx_header.StdId = CAN_GM6020_CTRL_ID_BASE; +// raw_tx.tx_header.IDE = CAN_ID_STD; +// raw_tx.tx_header.RTR = CAN_RTR_DATA; +// raw_tx.tx_header.DLC = CAN_MOTOR_TX_BUF_SIZE; - raw_tx.tx_data[0] = (uint8_t)((motor1 >> 8) & 0xFF); - raw_tx.tx_data[1] = (uint8_t)(motor1 & 0xFF); - raw_tx.tx_data[2] = (uint8_t)((motor2 >> 8) & 0xFF); - raw_tx.tx_data[3] = (uint8_t)(motor2 & 0xFF); - raw_tx.tx_data[4] = (uint8_t)((motor3 >> 8) & 0xFF); - raw_tx.tx_data[5] = (uint8_t)(motor3 & 0xFF); - raw_tx.tx_data[6] = (uint8_t)((motor4 >> 8) & 0xFF); - raw_tx.tx_data[7] = (uint8_t)(motor4 & 0xFF); +// raw_tx.tx_data[0] = (uint8_t)((motor1 >> 8) & 0xFF); +// raw_tx.tx_data[1] = (uint8_t)(motor1 & 0xFF); +// raw_tx.tx_data[2] = (uint8_t)((motor2 >> 8) & 0xFF); +// raw_tx.tx_data[3] = (uint8_t)(motor2 & 0xFF); +// raw_tx.tx_data[4] = (uint8_t)((motor3 >> 8) & 0xFF); +// raw_tx.tx_data[5] = (uint8_t)(motor3 & 0xFF); +// raw_tx.tx_data[6] = (uint8_t)((motor4 >> 8) & 0xFF); +// raw_tx.tx_data[7] = (uint8_t)(motor4 & 0xFF); - HAL_CAN_AddTxMessage(BSP_CAN_GetHandle(can->param->chassis6020), - &raw_tx.tx_header, raw_tx.tx_data, - &(can->mailbox.chassis)); - break; - case CAN_MOTOR_3508: +// HAL_CAN_AddTxMessage(BSP_CAN_GetHandle(can->param->chassis6020), +// &raw_tx.tx_header, raw_tx.tx_data, +// &(can->mailbox.chassis)); +// break; + case CAN_MOTOR_CHASSIS3508: motor1 = - (int16_t)(output->motor3508.named.m1); + (int16_t)(output->motor_CHASSIS3508.named.m1); motor2 = - (int16_t)(output->motor3508.named.m2); + (int16_t)(output->motor_CHASSIS3508.named.m2); motor3 = - (int16_t)(output->motor3508.named.m3); + (int16_t)(output->motor_CHASSIS3508.named.m3); motor4 = - (int16_t)(output->motor3508.named.m4); + (int16_t)(output->motor_CHASSIS3508.named.m4); - raw_tx.tx_header.StdId =CAN_G3508_CTRL_ALL_ID; + raw_tx.tx_header.StdId =CAN_G3508_CTRL_ALL_CHASSIS_ID; raw_tx.tx_header.IDE = CAN_ID_STD; raw_tx.tx_header.RTR = CAN_RTR_DATA; raw_tx.tx_header.DLC = CAN_MOTOR_TX_BUF_SIZE; @@ -200,13 +202,45 @@ int8_t CAN_DJIMotor_Control(CAN_MotorGroup_e group, CAN_Output_t *output, raw_tx.tx_data[6] = (uint8_t)((motor4 >> 8) & 0xFF); raw_tx.tx_data[7] = (uint8_t)(motor4 & 0xFF); - HAL_CAN_AddTxMessage(BSP_CAN_GetHandle(can->param->motor3508), + HAL_CAN_AddTxMessage(BSP_CAN_GetHandle(can->param->motor_CHASSIS3508), &raw_tx.tx_header, raw_tx.tx_data, &(can->mailbox.chassis)); break; + case CAN_MOTOR_UP3508: + motor1 = + (int16_t)(output->motor_UP3508.named.m1); + motor2 = + (int16_t)(output->motor_UP3508.named.m2); + motor3 = + (int16_t)(output->motor_UP3508.named.m3); + motor4 = + (int16_t)(output->motor_UP3508.named.m4); + + raw_tx.tx_header.StdId =CAN_G3508_CTRL_ALL_UP_ID; + raw_tx.tx_header.IDE = CAN_ID_STD; + raw_tx.tx_header.RTR = CAN_RTR_DATA; + raw_tx.tx_header.DLC = CAN_MOTOR_TX_BUF_SIZE; + + raw_tx.tx_data[0] = (uint8_t)((motor1 >> 8) & 0xFF); + raw_tx.tx_data[1] = (uint8_t)(motor1 & 0xFF); + raw_tx.tx_data[2] = (uint8_t)((motor2 >> 8) & 0xFF); + raw_tx.tx_data[3] = (uint8_t)(motor2 & 0xFF); + raw_tx.tx_data[4] = (uint8_t)((motor3 >> 8) & 0xFF); + raw_tx.tx_data[5] = (uint8_t)(motor3 & 0xFF); + raw_tx.tx_data[6] = (uint8_t)((motor4 >> 8) & 0xFF); + raw_tx.tx_data[7] = (uint8_t)(motor4 & 0xFF); + + HAL_CAN_AddTxMessage(BSP_CAN_GetHandle(can->param->motor_UP3508), + &raw_tx.tx_header, raw_tx.tx_data, + &(can->mailbox.up)); + break; case CAN_MOTOR_PITCH6020: motor5 = (int16_t)(output->pitch6020.named.m1); + motor6 = + (int16_t)(output->pitch6020.named.m2); + motor7 = + (int16_t)(output->pitch6020.named.m3); raw_tx.tx_header.StdId = CAN_PITCH6020_CTRL_ID; raw_tx.tx_header.IDE = CAN_ID_STD; raw_tx.tx_header.RTR = CAN_RTR_DATA; @@ -214,10 +248,10 @@ int8_t CAN_DJIMotor_Control(CAN_MotorGroup_e group, CAN_Output_t *output, raw_tx.tx_data[0] = (uint8_t)((motor5 >> 8) & 0xFF); raw_tx.tx_data[1] = (uint8_t)(motor5 & 0xFF); - raw_tx.tx_data[2] = 0; - raw_tx.tx_data[3] = 0; - raw_tx.tx_data[4] = 0; - raw_tx.tx_data[5] = 0; + raw_tx.tx_data[2] = (uint8_t)((motor6 >> 8) & 0xFF); + raw_tx.tx_data[3] = (uint8_t)(motor6 & 0xFF); + raw_tx.tx_data[4] = (uint8_t)((motor7 >> 8) & 0xFF); + raw_tx.tx_data[5] = (uint8_t)(motor7 & 0xFF); raw_tx.tx_data[6] = 0; raw_tx.tx_data[7] = 0; @@ -256,7 +290,7 @@ int8_t CAN_VESC_Control(int id,CAN_MotorGroup_e group, CAN_Output_t *output,CAN_ int Byte[4]; Vesc_ByteGet raw[4]; switch (group) { - case CAN_MOTOR_CHASSIS5065: + case CAN_MOTOR_5065: //将期望的四个电机输出值分别对应到四个联合体 为了下面的拆分字节 raw[0].as_array = output->chassis5065.named.m1; raw[1].as_array = output->chassis5065.named.m2; @@ -322,12 +356,12 @@ int8_t CAN_StoreMsg(CAN_t *can, CAN_RawRx_t *can_rx) { CAN_DJIMotor_Decode(&(can->motor.chassis6020.as_array[index]), can_rx->rx_data); break; - case CAN_M3508_M1_ID: - case CAN_M3508_M2_ID: - case CAN_M3508_M3_ID: - case CAN_M3508_M4_ID: + case CAN_CHASSIS_M3508_M1_ID: + case CAN_CHASSIS_M3508_M2_ID: + case CAN_CHASSIS_M3508_M3_ID: + case CAN_CHASSIS_M3508_M4_ID: // 存储消息到对应的电机结构体中 - index = can_rx->rx_header.StdId - CAN_M3508_M1_ID; + index = can_rx->rx_header.StdId - CAN_CHASSIS_M3508_M1_ID; can->recive_flag |= 1 << (index); CAN_DJIMotor_Decode(&(can->motor.motor3508.as_array[index]), can_rx->rx_data); detect_hook(CHASSIS3508M1_TOE + index); @@ -348,6 +382,17 @@ int8_t CAN_StoreMsg(CAN_t *can, CAN_RawRx_t *can_rx) { CAN_DJIMotor_Decode(&(can->motor.pit6020.as_array[index]), can_rx->rx_data); detect_hook(PITCH6020_TOE + index); break; + case CAN_UP_M3508_M1_ID: + case CAN_UP_M3508_M2_ID: + case CAN_UP_M3508_M3_ID: + case CAN_UP_M3508_M4_ID: + // 存储消息到对应的电机结构体中 + index = can_rx->rx_header.StdId - CAN_UP_M3508_M1_ID; + can->recive_flag |= 1 << (index); + CAN_DJIMotor_Decode(&(can->motor.motor3508.as_array[index]), can_rx->rx_data); + detect_hook(CHASSIS3508M1_TOE + index); + break; + case CAN_SICK_ID: // 存储消息到sickfed结构体中 CAN_Sick_Receive(&(can->sickfed), can_rx->rx_data); diff --git a/User/device/can_use.h b/User/device/can_use.h index ff1f5ab..182db2b 100644 --- a/User/device/can_use.h +++ b/User/device/can_use.h @@ -5,16 +5,22 @@ #include "bsp_can.h" typedef enum { - CAN_M3508_M1_ID = 0x201, /* 1 */ - CAN_M3508_M2_ID = 0x202, /* 2 */ - CAN_M3508_M3_ID = 0x203, /* 3 */ - CAN_M3508_M4_ID = 0x204, /* 4 */ + CAN_CHASSIS_M3508_M1_ID = 0x201, /* 1 */ + CAN_CHASSIS_M3508_M2_ID = 0x202, /* 2 */ + CAN_CHASSIS_M3508_M3_ID = 0x203, /* 3 */ + CAN_CHASSIS_M3508_M4_ID = 0x204, /* 4 */ + /**/ CAN_G6020_AgvM1 =0x205, CAN_G6020_AgvM2 =0x206, CAN_G6020_AgvM3 =0x207, CAN_G6020_AgvM4 =0x208, + CAN_UP_M3508_M1_ID = 0x205, /* 1 */ + CAN_UP_M3508_M2_ID = 0x206, /* 2 */ + CAN_UP_M3508_M3_ID = 0x207, /* 3 */ + CAN_UP_M3508_M4_ID = 0x208, /* 4 */ + CAN_SICK_ID=0x301, CAN_G6020_Pitch =0x209, @@ -38,10 +44,10 @@ typedef enum { typedef enum { - CAN_MOTOR_CHASSIS6020 = 0, CAN_MOTOR_PITCH6020, - CAN_MOTOR_CHASSIS5065, - CAN_MOTOR_3508, + CAN_MOTOR_5065, + CAN_MOTOR_CHASSIS3508, + CAN_MOTOR_UP3508, CAN_MOTOR_GROUT_NUM, } CAN_MotorGroup_e; @@ -77,9 +83,10 @@ typedef union{ }Vesc_ByteGet; typedef struct { - CAN_DJIOutput_t chassis6020; +// CAN_DJIOutput_t chassis6020; CAN_VescOutput_t chassis5065; - CAN_DJIOutput_t motor3508; + CAN_DJIOutput_t motor_CHASSIS3508; + CAN_DJIOutput_t motor_UP3508; CAN_DJIOutput_t pitch6020; } CAN_Output_t; @@ -98,17 +105,18 @@ typedef struct { } CAN_RawTx_t; typedef struct { - BSP_CAN_t chassis6020; +// BSP_CAN_t chassis6020;//禁用 BSP_CAN_t chassis5065; - BSP_CAN_t motor3508; - BSP_CAN_t pitch6020; + BSP_CAN_t motor_CHASSIS3508; + BSP_CAN_t motor_UP3508; + BSP_CAN_t pitch6020; BSP_CAN_t sick; } CAN_Params_t; /* 电机反馈信息 */ typedef struct { - float rotor_angle; + float rotor_ecd; float rotor_speed; float torque_current; float temp; @@ -157,6 +165,8 @@ typedef struct { const CAN_Params_t *param; struct { uint32_t chassis; + uint32_t up; + } mailbox; osMessageQueueId_t msgq_raw; diff --git a/User/device/cmd.c b/User/device/cmd.c index eb45f94..0a1f114 100644 --- a/User/device/cmd.c +++ b/User/device/cmd.c @@ -14,54 +14,44 @@ /* Private function -------------------------------------------------------- */ /*Export function --------------------------------------------------------------*/ - - - -#ifdef dr16_t - - -#else - - -#endif int8_t CMD_Init(CMD_t *cmd){ /*若主结构体为空 自动返回错误 */ if(cmd == NULL) return-1; /**/ - cmd->C_cmd.type =RC; - cmd->C_cmd.mode =NORMAL; + cmd->CMD_CtrlType =RCcontrol; + cmd->CMD_mode =Normal; return 0; } + + static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd) { /* 将操纵杆的对应值转换为底盘的控制向量和云台变化的欧拉角 */ // RC_dr16 , // RC_r12ds // -#ifdef r12ds_t + /*乐迪反馈值转换(-1 -- 1 )范围*/ - if(rc->ch_x<0) cmd->Vx =map_fp32(rc->ch_x,-337,0,-1,0); - else cmd->Vx =map_fp32(rc->ch_x,0,310,0,1); - - - if(rc->ch_y<0) cmd->Vy =map_fp32(rc->ch_y,-260,0,-1,0); - else cmd->Vy =map_fp32(rc->ch_y,0,312,0,1); +// if(rc->ch_x<0) cmd->Vx =map_fp32(rc->ch_x,-337,0,-1,0); +// else cmd->Vx =map_fp32(rc->ch_x,0,310,0,1); +// +// +// if(rc->ch_y<0) cmd->Vy =map_fp32(rc->ch_y,-260,0,-1,0); +// else cmd->Vy =map_fp32(rc->ch_y,0,312,0,1); - if(rc->ch_w<0) cmd->Vw =map_fp32(rc->ch_w,-308,0,-1,0); - else cmd->Vw =map_fp32(rc->ch_w,0,291,0,1); +// if(rc->ch_w<0) cmd->Vw =map_fp32(rc->ch_w,-308,0,-1,0); +// else cmd->Vw =map_fp32(rc->ch_w,0,291,0,1); - cmd->key_ctrl_l = rc->key [0]; - cmd->key_ctrl_r = rc->key [1]; - -#elif defined(dr16_t) +// cmd->key_ctrl_l = rc->key [0]; +// cmd->key_ctrl_r = rc->key [1]; +// - cmd->Vx = rc->ch_r_x; cmd->Vy = rc->ch_r_y; cmd->Vw = rc->ch_l_x; @@ -70,14 +60,7 @@ static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd) { cmd->key_ctrl_l = rc->sw_l; cmd->key_ctrl_r = rc->sw_r ; - -#endif - - - - - - + } @@ -90,19 +73,18 @@ static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd) { */ static void CMD_RcLostLogic(CMD_t *cmd){ /* 机器人底盘运行模式恢复至放松模式 */ - cmd->C_cmd.mode = RELAXED; + cmd->CMD_CtrlType = RELAXED; } int8_t CMD_ParseRc(CMD_t *cmd,CMD_RC_t *rc){ if (cmd == NULL) return -1; if (rc == NULL) return -1; -#ifdef dr16_t + /*c当rc丢控时,恢复机器人至默认状态 */ if ((rc->sw_l == CMD_SW_ERR) || (rc->sw_r == CMD_SW_ERR)) { CMD_RcLostLogic(cmd); } else { CMD_RcLogic(rc, cmd); } -#endif return 0; } @@ -122,15 +104,15 @@ int8_t CMD_ParseNuc(CMD_t *cmd,CMD_NUC_t *n){ switch(cmd->cmd_status){ case MID: - cmd->C_navi.vx = n->navi.vx; - cmd->C_navi.vy = n->navi.vy; - cmd->C_navi.wz = n->navi.wz; + cmd->cmd_MID360.posx = n->navi.vx; + cmd->cmd_MID360.posy = n->navi.vy; + cmd->cmd_MID360.posw = n->navi.wz; break; case PICK : - cmd ->C_pick .posx =n->pick .posx ; - cmd ->C_pick .posy =n->pick .posy ; - cmd ->C_pick .posw =n->pick .posw ; + cmd ->cmd_pick .posx =n->pick .posx ; + cmd ->cmd_pick .posy =n->pick .posy ; + cmd ->cmd_pick .posw =n->pick .posw ; break; @@ -147,81 +129,68 @@ int8_t CMD_ParseNuc(CMD_t *cmd,CMD_NUC_t *n){ 这一部分没有设置具体的模式名,后期根据需要修改 遥控器模式(RC): 左按键 --- 右按键 - mode1 - up no_mode + mode1 + up no_mode mode2 - mode3 + mode3 down no_mode mode4 mid auto_navi(0x09)雷达导航 */ -int8_t CMD_CtrlSet(CMD_t *cmd) { +/*遥控器,上下层通用,按键控制,统一到cmd*/ +int8_t CMD_ParseRC(CMD_t *cmd,const CMD_RC_t *rc) { + if(cmd == NULL) return -1; - if(cmd->key_ctrl_l == CMD_SW_UP)//当左拨杆打到最上面时 强制使用遥控器控制 - { - /*遥控器模式下,右按键三种状态分配*/ - if(cmd->key_ctrl_r==CMD_SW_UP) - { - cmd->C_cmd.type = UP_CONTROL; - cmd->C_cmd.mode = RC_MODE1; - } - if(cmd->key_ctrl_r==CMD_SW_MID) - { - cmd->C_cmd.type = RC; - cmd->C_cmd.mode = RC_NO_MODE; - } - if(cmd->key_ctrl_r==CMD_SW_DOWN)//遥控器控制模式下,右拨杆上时启动 - { - cmd->C_cmd.type = UP_CONTROL; - cmd->C_cmd.mode =RC_MODE2; - } - - } - else if(cmd->key_ctrl_l ==CMD_SW_DOWN) + cmd->Vx = rc->ch_r_x; + cmd->Vy = rc->ch_r_y; + cmd->Vw = rc->ch_l_x; + + cmd->poscamear = rc->ch_l_y; + + cmd->key_ctrl_l = rc->sw_l; + cmd->key_ctrl_r = rc->sw_r ; + + if ((rc->sw_l == CMD_SW_ERR) || (rc->sw_r == CMD_SW_ERR)) { + cmd->CMD_CtrlType =RELAXED; + } + else if(rc->sw_l==CMD_SW_UP) { - if(cmd->key_ctrl_r==CMD_SW_UP) - { - cmd->C_cmd.type = RC; - cmd->C_cmd.mode = RC_MODE3; - } - if(cmd->key_ctrl_r==CMD_SW_MID) - { - cmd->C_cmd.type = RC; - cmd->C_cmd.mode = RC_NO_MODE; - } - if(cmd->key_ctrl_r==CMD_SW_DOWN)//遥控器控制模式下,右拨杆上时启动 - { - cmd->C_cmd.type = RC; - cmd->C_cmd.mode = RC_MODE4; - } - + cmd ->CMD_CtrlType =RCcontrol; + if(rc->sw_r ==CMD_SW_UP) cmd ->CMD_mode =Pitch; //左上,右上,投篮,设置好的 + if(rc->sw_r ==CMD_SW_MID) cmd ->CMD_mode =Normal; //左上,右中,无模式 + if(rc->sw_r ==CMD_SW_DOWN) cmd ->CMD_mode =Pitch_HAND; //左上,右上,手动调整 } - else //左按键打到中间,自动模式 - { - if( cmd->key_ctrl_l==CMD_SW_MID ){ + + else if(rc->sw_l==CMD_SW_MID) + { - cmd->C_cmd.type = AUTO; - cmd->C_cmd.mode = RC_NO_MODE ; //雷达导航 - } - if(cmd->key_ctrl_r==CMD_SW_UP) + if(rc->sw_r ==CMD_SW_UP) cmd ->CMD_CtrlType =MID_NAVI;; //左中,右上,雷达 + if(rc->sw_r ==CMD_SW_MID) { - cmd->C_cmd.type = AUTO; - cmd->C_cmd.mode = AUTO_NAVI; - } - if(cmd->key_ctrl_r==CMD_SW_DOWN)//遥控器控制模式下,右拨杆上时启动 - { - cmd->C_cmd.type = AUTO; - cmd->C_cmd.mode = AUTO_PICK; + cmd ->CMD_CtrlType =RCcontrol; + cmd ->CMD_mode =Normal; //左中,右中,无模式 } - - - } -return 0; + if(rc->sw_r ==CMD_SW_DOWN) + { + cmd ->CMD_mode =Normal; //左中,右下,无模式 + cmd ->CMD_CtrlType =RCcontrol; + } + } + else if(rc->sw_l==CMD_SW_DOWN) + { + cmd ->CMD_CtrlType =RCcontrol; + if(rc->sw_r ==CMD_SW_UP) cmd ->CMD_mode =Normal; //左下,右上,投篮 + if(rc->sw_r ==CMD_SW_MID) cmd ->CMD_mode =Normal; //左下,右中,无模式 + if(rc->sw_r ==CMD_SW_DOWN) cmd ->CMD_mode =Normal; //左下,右上,无模式 + } + + + return 0; } diff --git a/User/device/cmd.h b/User/device/cmd.h index 3780e5a..7e80722 100644 --- a/User/device/cmd.h +++ b/User/device/cmd.h @@ -1,21 +1,3 @@ -/* - -该任务用于接收来自各个不同的控制方式所期望的控制指令 将其集中统一化后分发给各个模块 - -*/ - - -/* - 按键控制逻辑 - RC模式,左按键打到最上,右按键启用,中间无状态,上下各代表模式1、模式2 - 雷达导航,左按键打到中间,右按键禁用 - 左按键打到下面,保留,未启用 - -*/ - - - - #ifndef _CMD_H #define _CMD_H #include "struct_typedef.h" @@ -25,95 +7,29 @@ #define MID (0x09) #define PICK (0x06) - -/*选择遥控器,else为r12ds -更改遥控器时,建议取消相应的task - - -*/ -#define dr16_t -//#define r12ds_t - - - - typedef enum{ - RC,//遥控器控制,左按键上 + RCcontrol,//遥控器控制,左按键上,控制上层 + MID_NAVI,//雷达导航 + PICK_t, AUTO, - UP_CONTROL - }CMD_Chassis_CtrlType_e; + RELAXED,//异常模式 + + }CMD_CtrlType_t; typedef enum{ - RELAXED,//异常模式 - NORMAL, - GYRO_STAY, - - RC_MODE1, - RC_NO_MODE, - RC_MODE2, + + + Normal, //无模式 + AUTO_NAVI, + AUTO_PICK, + + Dribble , //运球 + Pitch, //投篮 + /*视觉辅助下的投篮*/ + Pitch_HAND, - RC_MODE3, - RC_MODE4, - - AUTO_NAVI, - AUTO_PICK - }CMD_Chassis_mode_e; -/*该结构体负责接收和解析地盘模块所需要的控制指令*/ -typedef struct{ - - CMD_Chassis_CtrlType_e type; - - CMD_Chassis_mode_e mode; - - -}CMD_Chassis_Ctrl_t; - - - -/* 拨杆位置 */ -typedef enum { - CMD_SW_ERR = 0, - CMD_SW_UP = 1, - CMD_SW_MID = 3, - CMD_SW_DOWN = 2, -} CMD_SwitchPos_t; - - -/*遥控器值,使用CMD_RcLogic函数传入CMD_t结构体*/ -typedef struct { - -#ifdef dr16_t - - float ch_l_x; /* 遥控器左侧摇杆横轴值,上为正 */ - float ch_l_y; /* 遥控器左侧摇杆纵轴值,右为正 */ - float ch_r_x; /* 遥控器右侧摇杆横轴值,上为正 */ - float ch_r_y; /* 遥控器右侧摇杆纵轴值,右为正 */ - - float ch_res; /* 第五通道值 */ - - CMD_SwitchPos_t sw_r; /* 右侧拨杆位置 */ - CMD_SwitchPos_t sw_l; /* 左侧拨杆位置 */ - - - uint16_t key; /* 按键值 */ - - uint16_t res; /* 保留,未启用 */ - - -#else - int16_t ch_x; // X轴(Channel 1) - int16_t mul; // MUL(Channel 2) - int16_t ch_y; // Y轴(Channel 3) - int16_t ch_w; // W轴(Channel 4) - int16_t key[8]; // 按键通道(Channel 5-12) - - int16_t offline; -#endif -} __attribute__((packed))CMD_RC_t; - - - - + Dribbl_transfer + }CMD_mode_t; typedef struct { uint8_t status_fromnuc; uint8_t ctrl_status; //取其中每一个二进制位用作通信 @@ -133,56 +49,95 @@ typedef struct { { fp32 angle; }sick_cali; - } CMD_NUC_t; +/* 拨杆位置 */ +typedef enum { + CMD_SW_ERR = 0, + CMD_SW_UP = 1, + CMD_SW_MID = 3, + CMD_SW_DOWN = 2, +} CMD_SwitchPos_t; -typedef struct{ - fp32 posy; - fp32 posx; - fp32 posw; -}CMD_FOR_PICK; +/*遥控器值,使用CMD_RcLogic函数传入CMD_t结构体*/ +typedef struct { + float ch_l_x; /* 遥控器左侧摇杆横轴值,上为正 */ + float ch_l_y; /* 遥控器左侧摇杆纵轴值,右为正 */ + float ch_r_x; /* 遥控器右侧摇杆横轴值,上为正 */ + float ch_r_y; /* 遥控器右侧摇杆纵轴值,右为正 */ + + float ch_res; /* 第五通道值 */ + + CMD_SwitchPos_t sw_r; /* 右侧拨杆位置 */ + CMD_SwitchPos_t sw_l; /* 左侧拨杆位置 */ -typedef struct { - fp32 vx; - fp32 vy; - fp32 wz; - - -}CMD_FOR_NAVI; + uint16_t key; /* 按键值 */ + + uint16_t res; /* 保留,未启用 */ + +} __attribute__((packed))CMD_RC_t; typedef struct { - uint8_t cmd_status; - uint8_t raw_status; - - uint8_t status[7]; - - fp32 Vx; - fp32 Vy; - fp32 Vw; - fp32 poscamear; - + uint8_t cmd_status; + uint8_t raw_status; + uint8_t status[7]; + fp32 key_ctrl_l; fp32 key_ctrl_r; - - fp32 forsick_wz; - CMD_Chassis_Ctrl_t C_cmd; - CMD_FOR_NAVI C_navi; - CMD_FOR_PICK C_pick; + fp32 Vx; + fp32 Vy; + fp32 Vw; + fp32 poscamear; + + struct + { + fp32 posx; + fp32 posy; + fp32 posw; + }cmd_pick; + struct + { + fp32 posx; + fp32 posy; + fp32 posw; + }cmd_MID360; + + + + CMD_mode_t CMD_mode; + CMD_CtrlType_t CMD_CtrlType; + } CMD_t; +/*nuc数据统一到cmd*/ +/* +该任务用来处理来自不同控制方式下传回的期望的控制指令在此处统一为通用格式的控制指令发送给其他任务 + +*/ + + + +/* Includes ----------------------------------------------------------------- */ +#include "cmd.h" +#include "gpio.h" +#include "user_math.h" +#include + +/* Private function -------------------------------------------------------- */ +/*Export function --------------------------------------------------------------*/ + int8_t CMD_Init(CMD_t *cmd); + +static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd) ; +static void CMD_RcLostLogic(CMD_t *cmd); int8_t CMD_ParseRc(CMD_t *cmd,CMD_RC_t *rc); int8_t CMD_ParseNuc(CMD_t *cmd,CMD_NUC_t *n); - -int8_t CMD_SwitchStatus(CMD_t *cmd); - -int8_t CMD_CtrlSet(CMD_t *cmd); +int8_t CMD_ParseRC(CMD_t *cmd,const CMD_RC_t *rc) ; #endif diff --git a/User/device/dr16.c b/User/device/dr16.c index 8c8dc81..04454d2 100644 --- a/User/device/dr16.c +++ b/User/device/dr16.c @@ -12,8 +12,8 @@ #include "error_detect.h" -#ifdef dr16_t -//#define + + /* Private define ----------------------------------------------------------- */ #define DR16_CH_VALUE_MIN (364u) #define DR16_CH_VALUE_MID (1024u) @@ -132,5 +132,5 @@ int8_t DR16_HandleOffline(const DR16_t *dr16, CMD_RC_t *rc) { } -#endif + diff --git a/User/device/dr16.h b/User/device/dr16.h index 0eca50c..2b99679 100644 --- a/User/device/dr16.h +++ b/User/device/dr16.h @@ -12,10 +12,10 @@ /* Exported macro ----------------------------------------------------------- */ /* Exported types ----------------------------------------------------------- */ -#ifdef dr16_t -#define dr16_t + + typedef __packed struct { uint16_t ch_r_x : 11; @@ -49,5 +49,5 @@ int8_t DR16_HandleOffline(const DR16_t *dr16, CMD_RC_t *rc); #endif -#endif + diff --git a/User/device/motor_control.c b/User/device/motor_control.c index 5bcf876..560da9f 100644 --- a/User/device/motor_control.c +++ b/User/device/motor_control.c @@ -1,249 +1,7 @@ -/** - ****************************(C) COPYRIGHT 2021 QUT**************************** - * @file motor_control.c/h - * @brief 3508/2006电机初始化、速度环、位置环;6020电机初始化、位置环(相对角度) - * @note 3508位置环使用的是增量式编码器,没有绝对位置,注意它所对应的角度是M3508的输出轴所对应的角度,由减速比经过换算得来, - * 若要修改对于的真实角度,应该在CAN_RECEIVE中修改相对应的解码函数。 - 同时3508的控制函数也可对应相同ID的2006配套使用(但注意相对应的角度和速度值可能会出现问题)需要修改相应的减速比 - * @history - * Version Date Author Modification remark - * V1.0.0 Dec-23-2021 QUT 1. 完成 - * V1.0.1 Dec-23-2023 QUT hks 1. 完成 仅仅对原先函数进行了少量修改,增添了部分注释,未对部分参数进行适配 - - @verbatim - ============================================================================== - - ============================================================================== - @endverbatim - ****************************(C) COPYRIGHT 2021 QUT**************************** - */ #include "motor_control.h" -#include "CAN_receive.h" #include "pid.h" #include "user_math.h" #include "device\device.h" - -//3508motor init ID1~4 -//mode 1:velocity -// 2:pos -void M3508_motor_init(int mode); -//3508velocity_loop ID1~4 -void M3508_velocity_loop(int16_t speed1,int16_t speed2,int16_t speed3,int16_t speed4); -//3508position_loop ID1~4 -void M3508_pos_loop(fp32 angle1,fp32 angle2,fp32 angle3,fp32 angle4); -//6020 init ID1 -void GM6020_position_loop_init(void); -//6020 pos_loop ID1 relative angle ,this is used for 6020 angel range from 0 to 180 -void GM6020_pos_loop(int32_t ecd); +#include "can_use.h" - -const motor_measure_t *motor_data[4];//3508 motor _data -pid_type_def motor_pid[4];//3508velocity_pid -pid_type_def angle_pid[4];//3508position_pid -//position_pid time interval 10ms -const fp32 speed_PID[3]={5.0,0.3,0.0}; //P,I,D(velocity) -const fp32 angle_PID[3]={25.0,0.0,1.5}; //P,I,D(position) -//velocity_pid -const fp32 PID[3]={5.0,0.01,0.0}; - -const motor_measure_t *GM6020_data;//6020 data_motor -gimbal_PID_t gimbal_motor_relative_angle_pid;//6020 relative angle position_pid -pid_type_def gimbal_motor_gyro_pid;//6020 relative angle velocity_pid -gimbal_pid_control_t GM6020_pos_loop_control;//6020 position_control -const fp32 GM6020_PID[3]={3600.0,20.0,0};//6020 velocity_PID - -//*****3508*****// -//3508 motor init ID1~4 -//mode 1:velocity -// 2:position -void M3508_motor_init(int mode) -{ - //get 3508 motor_data from CAN_receive - motor_data[0] = get_chassis_motor_measure_point(0); - motor_data[1] = get_chassis_motor_measure_point(1); - motor_data[2] = get_chassis_motor_measure_point(2); - motor_data[3] = get_chassis_motor_measure_point(3); - - switch(mode) - { - //velocity_init - case 1: - for(int i=0;i<4;i++) - { - PID_init(&motor_pid[i],PID_POSITION,PID,16000,2000); //velocity_pid init - }break; - //pos_init - case 2: - for(int i=0;i<4;i++) - { - PID_init(&motor_pid[i],PID_POSITION,speed_PID,16000,2000); //velocity_pid init - PID_init(&angle_pid[i],PID_POSITION,angle_PID,1000,200); // pos_pid init - }break; - } - -} - -//3508 velocity -/** - * @brief send control current of motor (0x201, 0x202, 0x203, 0x204) - * the param is compatable with the fab data of 3508 - * @param[in] speed1: (0x201) 3508 motor control current, range [-16384,16384] - * @param[in] speed2: (0x202) 3508 motor control current, range [-16384,16384] - * @param[in] speed3: (0x203) 3508 motor control current, range [-16384,16384] - * @param[in] speed4: (0x204) 3508 motor control current, range [-16384,16384] - * @retval none - */ -void M3508_velocity_loop(int16_t speed1,int16_t speed2,int16_t speed3,int16_t speed4) -{ - int32_t speed[4]; - int32_t delta_speed[4]; - int i; - - speed[0] = speed1; - speed[1] = speed2; - speed[2] = speed3; - speed[3] = speed4; - - for(i=0;i<4;i++) - { - delta_speed[i] = PID_calc(&motor_pid[i],motor_data[i]->speed_rpm,speed[i]); - } - - CAN_cmd_G3508(delta_speed[0],delta_speed[1],delta_speed[2],delta_speed[3]); -} - -//3508 pos -/** - * @brief send control current of motor (0x201, 0x202, 0x203, 0x204) - * this also can used to control the same ID of M2006 - * the param angle is correspond to the output shaft of M3508 - - * @Attention!!!!! the kind fo DJI ecd is incremental. - - * @param[in] angle1: (0x201) 3508 motor control current, range [reserved] - * @param[in] angle2: (0x202) 3508 motor control current, range [reserved] - * @param[in] angle3: (0x203) 3508 motor control current, range [reserved] - * @param[in] angle4: (0x204) 3508 motor control current, range [reserved] - * @retval none - */ -void M3508_pos_loop(fp32 angle1,fp32 angle2,fp32 angle3,fp32 angle4) -{ - fp32 angle[4]; - fp32 delta_angle[4]; - int32_t delta_speed[4]; - int i; - - angle[0] = angle1; - angle[1] = angle2; - angle[2] = angle3; - angle[3] = angle4; - - //outer ring angle_loop - for(i=0;i<4;i++) - { - delta_angle[i] = PID_calc(&angle_pid[i],motor_data[i]->total_angle,angle[i]); - } - //inner ring velocity_loop - for(i=0;i<4;i++) - { - delta_speed[i] = PID_calc(&motor_pid[i],motor_data[i]->speed_rpm,delta_angle[i]); - } - - CAN_cmd_G3508(delta_speed[0],delta_speed[1],delta_speed[2],delta_speed[3]); -} - - -//*****6020*****// -//6020motor_init ID1 -void GM6020_position_loop_init(void) -{ - gimbal_PID_init(&GM6020_pos_loop_control.gimbal_motor_relative_angle_pid,10.0f,0.0f,8.0f,5.0f,0.0f); //angle_loop_pid init - PID_init(&GM6020_pos_loop_control.gimbal_motor_gyro_pid,PID_POSITION,GM6020_PID,30000.0,5000.0); //velocity_loop init - - GM6020_data=get_G6020_motor_measure_point(); -} - -//6020Pos ID1(relative angle) -//this 6020is uesd only for angle_maximum(180) -//ecd encoder valueֵ(0-8191) -void GM6020_pos_loop(int32_t ecd) -{ - //set positon - GM6020_pos_loop_control.angel_set=rad(ecd); - //calculate_relative_angle(-PI,PI) - GM6020_pos_loop_control.angel_get=motor_ecd_to_angle_change(GM6020_data->ecd,GM6020_pos_loop_control.angel_set); - //calculate_gyro (set-get) - GM6020_pos_loop_control.gyro_get=rad(GM6020_pos_loop_control.angel_set-GM6020_pos_loop_control.angel_get); - //angle_loop, pid - GM6020_pos_loop_control.gyro_set = gimbal_PID_calc(&GM6020_pos_loop_control.gimbal_motor_relative_angle_pid,GM6020_pos_loop_control.angel_get, GM6020_pos_loop_control.angel_set,GM6020_pos_loop_control.gyro_get); - GM6020_pos_loop_control.current_set = PID_calc(&GM6020_pos_loop_control.gimbal_motor_gyro_pid,GM6020_pos_loop_control.gyro_get, GM6020_pos_loop_control.gyro_set); - - //control value - GM6020_pos_loop_control.current_given = (int16_t)(GM6020_pos_loop_control.current_set); - CAN_cmd_gimbal(GM6020_pos_loop_control.current_given,0,0,0); -} - - - - - -void gimbal_PID_init(gimbal_PID_t *pid, fp32 maxout, fp32 max_iout, fp32 kp, fp32 ki, fp32 kd) -{ -// if (pid == NULL) -// { -// return; -// } - pid->kp = kp; - pid->ki = ki; - pid->kd = kd; - - pid->err = 0.0f; - pid->get = 0.0f; - - pid->max_iout = max_iout; - pid->max_out = maxout; -} - -fp32 gimbal_PID_calc(gimbal_PID_t *pid, fp32 get, fp32 set, fp32 error_delta) -{ - fp32 err; -// if (pid == NULL) -// { -// return 0.0f; -// } - pid->get = get; - pid->set = set; - - err = set - get; - pid->err = rad_format(err); - pid->Pout = pid->kp * pid->err; - pid->Iout += pid->ki * pid->err; - pid->Dout = pid->kd * error_delta; - abs_limit_fp(&pid->Iout, pid->max_iout); - pid->out = pid->Pout + pid->Iout + pid->Dout; - abs_limit_fp(&pid->out, pid->max_out); - return pid->out; -} - -//calculate relative_angle (-4096,4095) -fp32 motor_ecd_to_angle_change(uint32_t ecd, uint16_t offset_ecd) -{ - int32_t relative_ecd = ecd - offset_ecd; - if (relative_ecd > 4095) - { - while(relative_ecd>4095) - { - relative_ecd -= 8191; - } - } - else if (relative_ecd < -4096) - { - while(relative_ecd<-4096) - { - relative_ecd += 8191; - } - } - return relative_ecd * MOTOR_ECD_TO_RAD; -} - diff --git a/User/device/motor_control.h b/User/device/motor_control.h index c2158e3..2bf0589 100644 --- a/User/device/motor_control.h +++ b/User/device/motor_control.h @@ -4,58 +4,20 @@ #include "struct_typedef.h" #include "pid.h" - - +/*󽮵*/ typedef struct { - fp32 kp; - fp32 ki; - fp32 kd; - - fp32 set; - fp32 get; - fp32 err; - - fp32 max_out; - fp32 max_iout; - - fp32 Pout; - fp32 Iout; - fp32 Dout; - - fp32 out; -} gimbal_PID_t; - -typedef struct -{ - gimbal_PID_t gimbal_motor_relative_angle_pid; - pid_type_def gimbal_motor_gyro_pid; - fp32 angel_set; - fp32 angel_get; - fp32 gyro_set; - fp32 gyro_get; - fp32 current_set; - fp32 current_given; -}gimbal_pid_control_t; + uint16_t ecd; + int16_t speed_rpm; + int16_t given_current; + uint16_t temperate; + int16_t last_ecd; + int16_t round_cnt; + int16_t total_angle; + uint16_t offset_ecd; + uint32_t msg_cnt; +} DJmotor_measure_t; -#define FILTER_BUF_LEN 5 - -//#define MOTOR_ECD_TO_ANGLE 0.00231311936 -#define MOTOR_ECD_TO_ANGLE (360.0 / 8191.0 / (3591.0/187.0)) -#define MOTOR_ECD_TO_RAD 0.000766990394f -#define rad_format(Ang) loop_fp32_constrain((Ang), (-4096*MOTOR_ECD_TO_RAD), (4095*MOTOR_ECD_TO_RAD)) -#define rad(code) ((code)*MOTOR_ECD_TO_RAD) - - -void M3508_motor_init(int mode); -void M3508_pos_loop(fp32 angle1,fp32 angle2,fp32 angle3,fp32 angle4); -void GM6020_position_loop_init(void); -void GM6020_pos_loop(int32_t ecd); -void M3508_velocity_loop(int16_t speed1,int16_t speed2,int16_t speed3,int16_t speed4); -fp32 gimbal_PID_calc(gimbal_PID_t *pid, fp32 get, fp32 set, fp32 error_delta); -fp32 motor_ecd_to_angle_change(uint32_t ecd, uint16_t offset_ecd); -void gimbal_PID_init(gimbal_PID_t *pid, fp32 maxout, fp32 max_iout, fp32 kp, fp32 ki, fp32 kd); -void motor_speed_change_low_to_high(int rag); -#endif +#endif \ No newline at end of file diff --git a/User/device/vofa.c b/User/device/vofa.c index 0d584cc..248e161 100644 --- a/User/device/vofa.c +++ b/User/device/vofa.c @@ -30,10 +30,10 @@ void vofa_tx_main(float *data) /*在下面使用对应的串口发送函数*/ // HAL_UART_Transmit_DMA(&huart1, ( uint8_t *)fdata, sizeof(fdata)); // osDelay(1); - HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_VOFA), tail, 4); - osDelay(1); -// CDC_Transmit_FS( ( uint8_t *)fdata, sizeof(fdata)); -// osDelay(1); +// HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_VOFA), tail, 4); +// osDelay(1); + CDC_Transmit_FS( ( uint8_t *)fdata, sizeof(fdata)); + osDelay(1); // CDC_Transmit_FS( tail, 4); } diff --git a/User/task/Calc_task.c b/User/task/Calc_task.c deleted file mode 100644 index 0631191..0000000 --- a/User/task/Calc_task.c +++ /dev/null @@ -1,64 +0,0 @@ -#include "Calc_task.h" -#include "cmsis_os.h" -#include "user_task.h" -#include "chassis.h" -#include "remote_control.h" -#include "map.h" -#include "usart.h" - - - -////·ѡ -//void path_select(void) -//{ - -// current_path = rc_ctrl.sw[2]; -// if(current_path!=last_path) -// { -// switch (current_path) -// { -// //ǰ -// case POINT_CURRENT: -//// chassis_pos->IS_SICK = 0;//sickλ -// path_state.path = &path_current;//ѡ· -// path_state.points_num = 1;//ȷ· -// break; -// //趨 -// case POINT_LEFT: -//// chassis_pos->IS_SICK = 0;//sickλ -// path_state.path = &path_left;//ѡ· -// path_state.points_num = 1;//ȷ· -//// chassis_pos->sick.dis_set[2] = SICK_PATH_LEFT_Y;//sick趨ֵXḳֵ -//// chassis_pos->sick.dis_set[3] = SICK_PATH_LEFT_X;//sick趨ֵYḳֵ -// break; -// //ǰ趨 -// case POINT_FRONT: -//// chassis_pos->IS_SICK = 1;//sickλ -// path_state.path = &path_front;//ѡ· -// path_state.points_num = 1;//ȷ· -//// chassis_pos->sick.dis_set[2] = SICK_PATH_FRONT_Y;//sick趨ֵXḳֵ -//// chassis_pos->sick.dis_set[3] = SICK_PATH_FRONT_X;//sick趨ֵYḳֵ -// break; -// } -// chassis_pos->POS_IS_CPT = NO; -//// chassis_pos->SICK_IS_CPT = NO; -// } -// last_path = current_path; -//} -// -void Task_Calc(void *argument) -{ - (void)argument; /* δʹargument */ - const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_CALCULATE; - uint32_t tick = osKernelGetTickCount(); /* Ƶʵļʱ */ - while(1) - { - - tick += delay_tick; /* һʱ */ - osDelayUntil(tick); /* нȴһλ */ - } - - - -} - diff --git a/User/task/Calc_task.h b/User/task/Calc_task.h deleted file mode 100644 index 2f16765..0000000 --- a/User/task/Calc_task.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef CALC_TASK_H -#define CALC_TASK_H - -void path_select(void); -void cal_task(void); -void calc_init(void); - - - -#endif diff --git a/User/task/can_task.c b/User/task/can_task.c index a6081a8..d557f43 100644 --- a/User/task/can_task.c +++ b/User/task/can_task.c @@ -30,7 +30,7 @@ void Task_can(void *argument) const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_CAN; /* Device Setup */ - CAN_Init(&can, &(task_runtime.config.chassis_config->can)); + CAN_Init(&can, &(task_runtime.config.config->can)); uint32_t tick = osKernelGetTickCount(); /* 控制任务运行频率的计算 */ @@ -57,15 +57,14 @@ const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_CAN; CAN_DJIMotor_Control(CAN_MOTOR_PITCH6020,&can_out,&can); } if (osMessageQueueGet(task_runtime.msgq.can.output.chassis3508, - &(can_out.motor3508), 0, 0) == osOK) { - CAN_DJIMotor_Control(CAN_MOTOR_3508,&can_out,&can); + &(can_out.motor_CHASSIS3508), 0, 0) == osOK) { + CAN_DJIMotor_Control(CAN_MOTOR_CHASSIS3508,&can_out,&can); + } + if (osMessageQueueGet(task_runtime.msgq.can.output.chassis3508, + &(can_out.motor_UP3508), 0, 0) == osOK) { + CAN_DJIMotor_Control(CAN_MOTOR_UP3508,&can_out,&can); } - if (osMessageQueueGet(task_runtime.msgq.can.output.chassis6020, - &(can_out.chassis6020),0,0) == osOK) { - CAN_DJIMotor_Control(CAN_MOTOR_CHASSIS6020,&can_out,&can); - } - tick += delay_tick; /* 计算下一个唤醒时刻 */ osDelayUntil(tick); /* 运行结束,等待下一个周期唤醒 */ } diff --git a/User/task/chassis_task.c b/User/task/chassis_task.c index f3b6f7c..d9f8c87 100644 --- a/User/task/chassis_task.c +++ b/User/task/chassis_task.c @@ -47,7 +47,7 @@ void Task_Chassis(void *argument) (void)argument; /* 未使用argument,消除警告*/ const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_CHASSIS; - Chassis_init(&chassis,&(task_runtime.config.chassis_config->chassis),TASK_FREQ_CHASSIS); + Chassis_init(&chassis,&(task_runtime.config.config->chassis),TASK_FREQ_CHASSIS); uint32_t tick = osKernelGetTickCount(); @@ -70,7 +70,7 @@ void Task_Chassis(void *argument) osMessageQueueGet(task_runtime.msgq.can.feedback.CAN_feedback, &can, NULL, 0); /*底盘控制信息获取,目前dji遥控器*/ - osMessageQueueGet(task_runtime.msgq.cmd.chassis,&ctrl, NULL, 0); + osMessageQueueGet(task_runtime.msgq.cmd.cmd_ctrl_t,&ctrl, NULL, 0); /*锁定RTOS(实时操作系统)内核,防止任务切换,直到 osKernelUnlock() 被调用*/ osKernelLock(); @@ -85,13 +85,13 @@ void Task_Chassis(void *argument) osKernelUnlock(); osMessageQueueReset(task_runtime.msgq.can.output.chassis3508);//清空队列 - osMessageQueuePut(task_runtime.msgq.can.output.chassis3508, &out.motor3508, 0, 0); //发送数据 + osMessageQueuePut(task_runtime.msgq.can.output.chassis3508, &out.motor_CHASSIS3508, 0, 0); //发送数据 osMessageQueueReset(task_runtime.msgq.can.output.pitch6020); osMessageQueuePut(task_runtime.msgq.can.output.pitch6020, &out.pitch6020, 0, 0); - osMessageQueueReset(task_runtime.msgq.can.output.chassis6020); - osMessageQueuePut(task_runtime.msgq.can.output.chassis6020, &out.chassis6020, 0, 0); + osMessageQueueReset(task_runtime.msgq.can.output.pitch6020 ); + osMessageQueuePut(task_runtime.msgq.can.output.pitch6020 , &out.pitch6020, 0, 0); vofa_send[0] = chassis.vofa_send[0]; vofa_send[1] = chassis.vofa_send[1]; diff --git a/User/task/cmd_task.c b/User/task/cmd_task.c index d155116..23df6f0 100644 --- a/User/task/cmd_task.c +++ b/User/task/cmd_task.c @@ -46,7 +46,6 @@ void Task_cmd(void *argument){ if(osMessageQueueGet(task_runtime.msgq.cmd.raw.nuc, &Nuc,0 ,0) ==osOK) //nuc CMD_ParseNuc(&cmd,&Nuc); - CMD_CtrlSet(&cmd); if(osMessageQueueGet(task_runtime.msgq.cmd.raw.rc, &rc_ctrl, 0, 0) == osOK)//遥控器 CMD_ParseRc(&cmd, &rc_ctrl); @@ -54,8 +53,8 @@ void Task_cmd(void *argument){ osKernelUnlock(); /* 同上 解锁RTOS内核 */ /*将需要与其他任务共享的数据放到消息队列里 此处主要分享给底盘 后续会添加和上层机构的通信 */ - osMessageQueueReset(task_runtime.msgq.cmd.chassis); - osMessageQueuePut(task_runtime.msgq.cmd.chassis,&cmd,0,0); + osMessageQueueReset(task_runtime.msgq.cmd.cmd_ctrl_t); + osMessageQueuePut(task_runtime.msgq.cmd.cmd_ctrl_t,&cmd,0,0); tick += delay_tick; /*计算下一个唤醒时刻*/ osDelayUntil(tick); /*绝对延时 等待下一个唤醒时刻 */ diff --git a/User/task/dr16_task.c b/User/task/dr16_task.c index 58d1662..d465e15 100644 --- a/User/task/dr16_task.c +++ b/User/task/dr16_task.c @@ -13,7 +13,7 @@ /* Private macro ------------------------------------------------------------ */ /* Private variables -------------------------------------------------------- */ -#ifdef dr16_t + #ifdef DEBUG DR16_t dr16; @@ -23,7 +23,7 @@ static DR16_t dr16; static CMD_RC_t cmd_rc; #endif -#endif + /* Private function --------------------------------------------------------- */ /* Exported functions ------------------------------------------------------- */ @@ -38,13 +38,13 @@ void Task_dr16(void *argument) { const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_DR16; uint32_t tick = osKernelGetTickCount(); -#ifdef dr16_t + DR16_Init(&dr16); /* 初始化dr16 */ -#endif + while (1) { -#ifdef dr16_t + #ifdef DEBUG /* */ @@ -65,7 +65,7 @@ void Task_dr16(void *argument) { osMessageQueueReset(task_runtime.msgq.cmd.raw.rc); osMessageQueuePut(task_runtime.msgq.cmd.raw.rc, &cmd_rc, 0, 0); } -#endif + tick += delay_tick; /* 计算下一个唤醒时*/ diff --git a/User/task/init.c b/User/task/init.c index 3c90daa..e06a809 100644 --- a/User/task/init.c +++ b/User/task/init.c @@ -46,7 +46,9 @@ void Task_Init(void *argument) { osThreadNew(Task_cmd,NULL,&attr_cmd); task_runtime.thread.nuc = osThreadNew(Task_nuc,NULL,&attr_nuc); - + task_runtime.thread.up= + osThreadNew(Task_up,NULL,&attr_up); + task_runtime.thread.error_detect = osThreadNew(Task_error_detect,NULL,&attr_error_detect); @@ -62,9 +64,7 @@ void Task_Init(void *argument) { task_runtime.msgq.can.output.pitch6020 = osMessageQueueNew(2u, sizeof(CAN_DJIOutput_t), NULL); - task_runtime.msgq.can.output.chassis6020 = - osMessageQueueNew(2u, sizeof(CAN_DJIOutput_t), NULL); - + /* imu */ task_runtime.msgq.imu.accl = @@ -77,7 +77,7 @@ void Task_Init(void *argument) { /*cmd */ task_runtime.msgq.cmd.raw.rc = osMessageQueueNew(3u, sizeof(CMD_RC_t), NULL); - task_runtime.msgq.cmd.chassis = + task_runtime.msgq.cmd.cmd_ctrl_t = osMessageQueueNew(3u, sizeof(CMD_t), NULL); task_runtime.msgq.cmd.raw.nuc = osMessageQueueNew(3u,sizeof(CMD_NUC_t), NULL); diff --git a/User/task/up_task.c b/User/task/up_task.c new file mode 100644 index 0000000..7769574 --- /dev/null +++ b/User/task/up_task.c @@ -0,0 +1,118 @@ +/* +上层控制任务 +*/ +/* Includes ----------------------------------------------------------------- */ + +#include "up.h" +#include "user_task.h" +#include "can_use.h" +#include + +#include "vofa.h" + +static CAN_t can; + + +#ifdef DEBUG + +CAN_Output_t UP_CAN_out; + +UP_t UP ; + +CMD_t up_cmd; + + +#else + +static CAN_Output_t up_can_out; + +static UP_t UP; + +static CMD_t up_cmd; + +#endif +float aaa=0; +float bbb=0; +float CCC=0; +float ddd=0; + + +/** + * \brief + * + * \param argument + */ +void Task_up(void *argument) +{ + + (void)argument; /* 未使用argument,消除警告*/ + const uint32_t delay_tick = osKernelGetTickFreq() / TASK_FREQ_UP; + + uint32_t tick = osKernelGetTickCount(); + up_init(&UP,&(task_runtime.config.config->up ),TASK_FREQ_UP); + + while(1) + { +#ifdef DEBUG + task_runtime.stack_water_mark.up = osThreadGetStackSpace(osThreadGetId()); +#endif + UP_UpdateFeedback(&UP, &can,&up_cmd) ; +// GM6020_control(&UP, 100) ; +// UP_M3508_speed(&UP, 500); + +// UP_angle_control(&UP,0,M2006); +// +// +// VESC_M5065_Control(&UP, 20000); + + +// + + UP_control(&UP,&UP_CAN_out,&up_cmd); +// UP.motor_target .go_shoot =aaa; +// UP.motor_target .M2006_angle =bbb ; + +// UP.motor_target .M3508_angle =CCC; +// UP.motor_target .go_shoot =aaa; +// UP.motor_target .M2006_angle =bbb; +// UP.motor_target .go_spin =ddd; +// + ALL_Motor_Control(&UP,&UP_CAN_out); + + osDelay(1); + + + /*imu数据获取*/ + osMessageQueueGet(task_runtime.msgq.imu.eulr, &UP.pos088.imu_eulr, NULL, 0); + + osMessageQueueGet(task_runtime.msgq.imu.gyro, &UP.pos088.bmi088.gyro,NULL, 0); + + osMessageQueueGet(task_runtime.msgq.imu.accl, &UP.pos088.bmi088.accl,NULL, 0); + /*can上设备数据获取*/ + osMessageQueueGet(task_runtime.msgq.can.feedback.CAN_feedback, &can, NULL, 0); + + osMessageQueueGet(task_runtime.msgq.cmd .cmd_ctrl_t , &up_cmd, NULL, 0); + + /*锁定RTOS(实时操作系统)内核,防止任务切换,直到 osKernelUnlock() 被调用*/ + osKernelLock(); + + /*解锁*/ + osKernelUnlock(); + + + + osMessageQueueReset(task_runtime.msgq.can.output.up3508 );//清空队列 + osMessageQueuePut(task_runtime.msgq.can.output.up3508, &UP_CAN_out.motor_UP3508 , 0, 0); //发送数据 + osMessageQueuePut(task_runtime.msgq.can.output.shoot5065 ,&UP_CAN_out.chassis5065, 0, 0); + + + vofa_send [0]=UP.vofa_send [0]; + vofa_send [1]=UP.vofa_send [1]; + vofa_tx_main (vofa_send); + + tick += delay_tick; + osDelayUntil(tick); + + } + +} diff --git a/User/task/user_task.c b/User/task/user_task.c index cbfad5d..bbf54ea 100644 --- a/User/task/user_task.c +++ b/User/task/user_task.c @@ -66,4 +66,8 @@ const osThreadAttr_t attr_dr16 = { .stack_size = 128 *4, }; - +const osThreadAttr_t attr_up = { + .name = "up", + .priority = osPriorityRealtime, + .stack_size = 512 * 4, +}; diff --git a/User/task/user_task.h b/User/task/user_task.h index 8ed568d..db66cb3 100644 --- a/User/task/user_task.h +++ b/User/task/user_task.h @@ -15,6 +15,8 @@ // 分配的频率该如何给定? #define TASK_FREQ_CHASSIS (900u) +#define TASK_FREQ_UP (900u) + #define TASK_FREQ_CTRL_CMD (500u) #define TASK_FREQ_NUC (500u) #define TASK_FREQ_CAN (1000u) @@ -36,6 +38,8 @@ typedef struct { struct { osThreadId_t atti_esti; osThreadId_t chassis; + osThreadId_t up; + osThreadId_t dr16; osThreadId_t r12ds; osThreadId_t can; @@ -60,16 +64,18 @@ typedef struct { }raw; - osMessageQueueId_t chassis; + osMessageQueueId_t cmd_ctrl_t; osMessageQueueId_t status; } cmd; /* can任务放入、读取,电机或电容的输入输出 */ struct { struct { - osMessageQueueId_t chassis6020; - osMessageQueueId_t chassis5065; + + osMessageQueueId_t shoot5065; osMessageQueueId_t chassis3508; osMessageQueueId_t pitch6020; + osMessageQueueId_t up3508; + } output; struct { osMessageQueueId_t CAN_feedback;//包括底盘,云台6020,3508,5065,sick,can上设备数据 @@ -91,6 +97,8 @@ typedef struct { #ifdef DEBUG struct { UBaseType_t chassis; + UBaseType_t up; + UBaseType_t can; UBaseType_t atti_esti; UBaseType_t dr16; @@ -108,6 +116,7 @@ typedef struct { float atti_esti; float r12ds; float dr16; + float up; float cmd; float nuc; @@ -120,6 +129,7 @@ typedef struct { float atti_esti; float r12ds; float dr16; + float up; float cmd; float nuc; @@ -134,6 +144,8 @@ extern const osThreadAttr_t attr_init; extern const osThreadAttr_t attr_atti_esti; +extern const osThreadAttr_t attr_up; + extern const osThreadAttr_t attr_chassis; extern const osThreadAttr_t attr_can; @@ -155,6 +167,9 @@ void Task_AttiEsti(void *argument); void Task_Chassis(void *argument); +void Task_up(void *argument); + + void Task_can(void *argument); void Task_cmd(void *argument);