From 990905d5c4cec8638d4eb8e019dc79d13ad36949 Mon Sep 17 00:00:00 2001 From: Tomo Sasaki Date: Thu, 2 Apr 2026 17:23:23 -0400 Subject: [PATCH 1/6] Add Python portfolio demos and gallery Introduce animated Python portfolio examples and generated assets for the new bindings. Document the gallery in the README and cover the demo generation path with tests. --- README.md | 27 + .../python_portfolio/cartpole_swing_up.gif | Bin 0 -> 571838 bytes .../python_portfolio/pendulum_swing_up.gif | Bin 0 -> 513484 bytes .../unicycle_obstacle_avoidance.gif | Bin 0 -> 604772 bytes docs/python_portfolio.md | 35 + examples/python_portfolio.py | 74 ++ examples/python_portfolio_lib.py | 698 ++++++++++++++++++ python/tests/test_portfolio.py | 49 ++ 8 files changed, 883 insertions(+) create mode 100644 docs/assets/python_portfolio/cartpole_swing_up.gif create mode 100644 docs/assets/python_portfolio/pendulum_swing_up.gif create mode 100644 docs/assets/python_portfolio/unicycle_obstacle_avoidance.gif create mode 100644 docs/python_portfolio.md create mode 100644 examples/python_portfolio.py create mode 100644 examples/python_portfolio_lib.py create mode 100644 python/tests/test_portfolio.py diff --git a/README.md b/README.md index 825d4f64..dcd56fbc 100644 --- a/README.md +++ b/README.md @@ -39,6 +39,33 @@ Several visualization-focused C++ examples remain in the repository, but they are not part of the default build. Use the Python bindings for plotting and notebook workflows. +### Python Portfolio +The Python bindings now ship with a small animation-focused portfolio built on +top of the same solver models used by the C++ examples: + +```bash +source .venv/bin/activate +python examples/python_portfolio.py --demo all +``` + +This generates GIFs under `docs/assets/python_portfolio/` for: + +* pendulum swing-up +* cart-pole swing-up +* unicycle obstacle avoidance + +See [docs/python_portfolio.md](docs/python_portfolio.md) for the gallery and +regeneration command. + +Pendulum swing-up: +Python pendulum swing-up portfolio demo + +Cart-pole swing-up: +Python cart-pole swing-up portfolio demo + +Unicycle obstacle avoidance: +Python unicycle obstacle avoidance portfolio demo + ## Installation ### Dependencies * [CMake](https://cmake.org/) (Build System) diff --git a/docs/assets/python_portfolio/cartpole_swing_up.gif b/docs/assets/python_portfolio/cartpole_swing_up.gif new file mode 100644 index 0000000000000000000000000000000000000000..e79ccac859563db9d5d1c6551ddc04ec7135ad83 GIT binary patch literal 571838 zcmWh!cTf{f6Ad9if}~Idq=epk?*RgYUPVND7ezx;M9=`Cx6l-n5}JS_0-_?KQbLtp zB=p{U2V1`1H?udlGxuihpWS(Tw{MM%4OP|LyQzhN@c;nj*U`Vr!+)0t|1S3bUL5|t zIQVmM@b~}z9_4)N&-w1<+5Y+I-tXh}i{tIf!_~8s-LvDJljGgf!;OQ3?LYhT7yFCn z`^%^ME2sO*d;44Gdy6M~OQ*YwC)+beI}3-~3)_2}n>*`An^Omyvj>|qXRCwzo3p#? zGdpY3TPx(v#gVOr!S(I+mCe<~^_9hy`RSF#$)$yjh2gcupKJ3YEA!*y3-c>80}In5 z^OFO!Q~k5#!Lixt!I_!<>8T%+Q$6I##fgr^3DVDrf%%{9^JA@ZV{LO|t&`(@OcHZFx1yE)JGcX`8L=` z>g#Fk?)cu-{)N=~WuS@pZDj1r&`9IJ@Q1#k_q_wPJp=E$``>o;z3%++{p+We=185<)I#|1J+;0$xxP8R z_Djv%s_NGjuPe(d%8N@&iLq}#M^`uEUVkhm7UsWvk)2og{Q0x2tgMKt58)Lb9+tlk zEvpYIsl^u8-Xp%dQ&@95zuNo78_(P-*XNZ^ITeoCucn`}PClfYd`SB&EhaTJEhQy2 zDLFYYF)1N2DLyeNHZCD5>S9Qp7p*)W3S z!wm5U1d)(*q2M&3pj5&CEHFhNFqIFRg2X2C-v7^%Y8`I8bFja2FUZ&bzNhb9SI^tG z+I@as8&7or9~*4VNlCnS2=;tLx4dwzuw~O^hvW7@FGYV{A}{mRkDe>L^n+ z9b*-3jEWXUQNvJP6)mTtFQcp{t%8>NXTo8$!UqoYKqEeipXe)NNWg7YYI!L z3rea9NT~9QtMH4dAVrmUMU;4i6}ctUxrG$?C|4{D>}>UQtqkO)WvQtE007@52tfPa zF8SXA{69?qUQVCvls8te$-DH~QN7$H%wRpRmil1*V^BX1|0TZ_WPr^ltt; zj`|9ZS!3;DdjhkBOJ8H%au-3sw9xEx{pycgg*$V7pWm+!67`dL%$piEM=NdLxb!!D z*q*5M{84EB<>T&jWAOG||Cdku^DQy^e~tdQetZ>>L}3^<`j&y-Dbu3Yj@I?5N@F;-cK6z%`{^W))xA#Pf9kt-~|c(UawZ zp#3r3%ty?j4~Y*Cz|o8`$VdXc4xH`WJhFGuDC-I3;0EDoFT`&t@z!5P%eY>#dbhxJ zgB4_Q2Q-K=miMimK;X3pb{*oV8ohXPWD*9E*il@$l4(6$m;P`UGnynhv!S1#EU*Y3 zPN6tZuShJQ{9+6ogGe-S9f{255_Q=3OFCK}*S(%ncIxJgqZQruS#9F2BtKPUZ3~i zM{r|XE=@=z%1Wi9K;MeHqht9k%2o7J0ty+POBJJ8CO@Ec;KdBq6OCXR(AvWWgXxf+ zM}${KK`(T_a8&a_)h~(6rffxql64r7q0)RwSjG>2oicVW9^_}XPZFtL#ZM%3r`T>l zb?xz4i`r%R8diB~c3H(5rRrYhfxktEt;BkVMG#`Wp>jjrq(`my;z4;2yI%Ib^+3Se z!hKUaNst{xD>a`nm+o$+2eOFC;_lhx)&9kT5vY6rQj_`BinJW5qwvb0L|8~_&?p0i zM5C$U!KD)Tb;=5s`UkLtQ0)C|+sh>`y7F-e=w9kn3M~Hv*Ieh<3=Z7Wyj&nq7a%R- z;;&YO>N{OoIn{BKcsTGQm>BST7bey8w(m;DHMq)1b6am+Z!7cVdhf2Mxx`5IF%6-& zn0ZAU|0_vFSJT1CNgNnur4)FE;aEHEzGj3_>M&iVZ|vw7IMIvOBoC^-1Jyh0iYNR_ zALGEer3VeOW7L!MQ=`HxkaUi8k|j~_Z;T+8IVvNGN;&0msF|AK){9mYnhRo58r8u^ zw~sYyV|t~hwh)G4A|F&l<6o<)>ANj|lSLr%QE~V?h)bK=xI@;82OJ1|5ap*eO%xX3 z*C9qn*Lzh!R>UdU zS)ZcWU-LPYF!C!*@JHvn;X33vVf`WqK_)r|noAyauFTlU;mT{G$ZkmD`*er2>T8~* z>4;?g_VQWZOp4VIYN(j&ZdBl{F6Qnz$wnoHkt(#0q=mYpgUM=RG=bbOE2(jTfQbUL zCH*@D_v;MOwUUvFxpOB;q69Oa1THo91c^iiiD=mx)htf$l$jn%$+;AohKLkSR#!%- z|C6N_JI4R`7bv68B*HVMx$xzqkWo}fovL24Yhal*0xjwr8f7Iy0LL0>8D^=H_!Fj* zMpN%Lg?Kaxz%<315Zt>PytTPrs!Sf06RZ_b>cxtnwbmprAEXy4QAjtzp371;5Lxl% z_6V{qN?KHpb3t-IoKBBg@$WJ-2g2`~lP;IN7xFd5Vbb_{>1Z@oU#-6vCz9=HAI+|K zhdQw%=EX*z`QhDk65j^uH8DT1`J}ec@pd5jBSPAaVECZ9OuOh2lK9b9&BZZR98(8Y zXTOfb{EfGvYqMKY4Xp?2Zktb7Wymyt$ORqpDPin>I8&lyXjwJi$|Nq=$Onqm1WQ@) z?*1BX-W$KKuZUsG9)-31)2{{c-3??&CU41Cd31PVu!#yVb+=^Lq`}+wK^qgjv^f!1 z^44{>)CiB6M2eV&?$b7o(Pz|*@{1F%1um%(uKru*{xXB$pwy+KMCo$w?Cz?`+{$nC zXDR1~zH@=I2wW4b;4NiMn10aoGaH7kqxe;Y8l~{RWUAn8Q^Zt(^nNb=i9!~E??)Iv zLcF_YW4Li0Eck{lx;iPSQ*O#f_RBayCwB|Ui<{EvRqN7cGGYZjTGolc!2Nl4QkJ}B z1DC?hmWVMAH9TMG*Qk2k6klf@C=k{)yG*~6c|qx?>ZMvp8WoYC^S1)J(>!YhbU#Hu zXr;+J))`A#=2Y@}PU2fak*i4+^rS?`Sa#w+S!k_1p7k%WlUF`JD)*m07ftJKluODG z_03Ww)2Woxm*>~5SQ^q0a)F$s8?o9~GGp5NQCHWBxpdnuCt3rUvdhMV5gxabIyU2# zoZO-Bmd1za4i~eXsmge74Gu9J&OIcp7nt~q^@;4oNjfq@u`4m3pu-A*Cx@v@jFxK8 zguC@}+FdPQvW+{?2I)T0K!CLaqX*6u(AfaJrAANlv7z~jM_sLA3hx#u2)`oeU-Q5Bt!O3jWVC^9`-gGAsq~Mh%$hJ^#$5K6hhBxFm?GV0D_mYJ&~J7uxMt@ zp3K8r$X7oI{<~xX-TMR{BbPV+Iqh(y&7aM0bwHY%*~F+?-Jy;^ngoiZYYZ9nRr=et zkJmC|A3dh?5h%;+cgRj7NT3;oD{6JmH)QP~@wS-+@2|!Ii4Bx(Gz^AHDi;21uDAG$%?MxV@O+_`vuAL04YX zV+o7mxrmC%h=RAlt6Oe!ksl&+qs7Trm9gN}XRu!=_=X#_2ysKi9Vd|+quv;!NsiIJ zh(WRA^;Gd_2fSez9+QhVX~dh6@fH_&EB06$)mS@+So^S8hum1l##kqEtjk5L8+)9G zYMhrtoKIMsUv8X#W87VG+`Wr9EPH&AYJ7-8{DZLgu-y3Y#`p+w{F94#9D72vY69LN zAucQ-AvYnZF(HMVkVd&kAh0LOwc0ymK!pSnIS^Mk@QL^gnqe#01pzj>5X7LHcrAnL zTn|xl0RKb7C>bvXsxy67j&MWLgZvUb{HV*Y;pYfg*-#R56tF}#nW;DtT$eOQrIL@i z>V|`_0_al|p%(~7k=lpsQAsp)Ni7?QH7xuOAZ45&K}tX*d&F>Hf!DfYor$muz?B3X z`0WsE%z%;2FbVFSLRXiRfCT>$1@C-F3DSk`$qG}~rAkDlzV1$9a)*%@VE9bx-$be9 zFvO}~oH!P?g}e(XSKW%L@?sQJ;qh*d-EXorh1hQ3fB<&9}%5A86O%;F_|~ zlOb5ug48`zcBNmHk5_whOT5I^iH5jDEea@48(Ee7Xr3XC6$^9UXE0$w7Z#|u(LM7YWIm(Kh~O&n?nHE0k>xBZcKM;=wzB^>NS z{Wlt6dr7r{H1aIW#&6t}b$W1|{jMC}3G=nVd=#lndwVH(B_p#p9p zVJ10TGg*lg>?;lcOzSAa_!92^f=ZbH|B02h#S1ZWR`yZGbwa}{D1?geoC;48d=#l* znho3|*aCH_w_9GyOtHAhLM!Ruj|5;`LJ1nany1-97q|C+5%*4xf-HMR3AQPlc5{RQ_}*sK6!;zh@_^1XD8u**Jjcz zqQ{S+#8(w>8|n9u2%LXDWg&!?O`n$t^Z!t}MGp?PdRI+T+nvQj?KT= zf%UZ&70`JBf}=*))WW)&Y*%Z+yt44m!etuIxvG_J{CPpOM^sW9s#8OlHovaCFprYzR2p_>#G0@(r=`33h=uFijf4@yGNvOOQd!hwrL zki?o-8)csA2zFD%4DsDd@*5hthBL2*yl(i|7=4L1;>?ii531ItSUKO{&AwKX19@c> zU?_*K^8wjeY9Ov@m?$ry33Q5G$8fdo;79g2pqT`+L7N$WRlhcC~KO)E{`WCxwXIj(&$()hrC>jMSV@LVI6y7hyw>WvtycQxA~ z9@{M91bbjBH3bJg!OFxhz*4Uo-20-43VlQE?(TTpbl6bMtp?pk8huwsv`&2jQt7TB z5xu?D)O^qZ@mF5rZ~qX?euTbFquk0iZ4@JU_xMtf&Bf!g#c-AK2RIdwDO%Y39@GiBmb6jD33;j_p z37c7T*iy9h@-qhlwuJ*nq4e_~S376E{Dmkkew>oUkz8&@Uolhk>m?OJvBWE)1Xl}R zI)KEZ=;vkIU3Qp54(OK<@JlP$JGV5R)Av(BPwT`Duo2$RPN_-}*%NLwyVw%&A$T{=^i&X}bc9Nx;q_B0>xl082)&ad%59yluS0?k}N2fn@L!LWw>EE@2?qlIA z0O-JEAC{8wrb&n~*KAZBisbm1qyS}9`#P$}%@yM&l~9YTH)hn;8Z+y^=IjRD;nPx} z8%vuWvyU8iC>VGAI_@+(?(%osjr*sE)=w|zpFWX4{R)2ifBkuP_UFC7Kd}YOdRS11 z^TdP5iLio+@UIgQvlCDLPT;u7(OP7@GdV7joKQf1CLIGO^ z^OV$is(bU)+Vcki%6|(M=)Wy6%q_qyCVxlHojWg_nlGLNEFPsUZbU9HA20CyTSW3K z@!y+boSWy|n-lpqCuT7xkv7XEEhoUUEU&$+xVI<-Ti8uqX0ljN(_YlFn3v&^Q_@~R zyQ~=An^los&>2|Pa9K2cvS_(Cr~6OL$Ys_3$*M!zr19ReIc(KgdtRz=*8SeB?Vi}p zCu@F%Yx>_-&F(E(!`AMnEd^T4dC!UYKUoheT)#4~X7O*8Lwj8uwjn9KA^ik&_;x*k zQn-=yWHw@N_1@lk5NvZpYi--NLieroBUQ+39?;(_OgJ`)#K! zjf$#eYiMt-hG#R~W!FS{+w0y2SbI_k2eLcZUEtYU(%xHf*;{+Ew^6va^=)rwZf_k% zqkshrYwwe_cB9gEKUi#ErtO#2?2n~xo5@d#qi76kf!uCX;GzTi?*|O?2QbP3g7=U~ z=a9wqkZthbnk-NcMWct@Klyh!60lDk*#B#BG#;=$ntC(@Juu~;WNtZxAdclJI>(Bx z$I4HSRf~?*zaMMPA8S*NHFORn07q!b3_tJo&nLU;Pv#}x31)r;+8qE;I;VE7r}j@z z9ny~ta3F*EQ^5h|nSi6Qw?`x9XTt$!gQ;f~vnQhblLl6xo4n^iI_Dv-r&jv_m!k9H z$dmWdXJY&NLf=o$`p-o8C(Uuxp+y%--!DRRfY$HM3Ge3J2Ir&So#f1~#k||)=9#p> zU8GQskqiG3Bz%|%RJEjAz`>UhU^KMq!-t>?Q5LBKB2j0zcZ0x zfkl97?%aF5~q zigjIb>D0_9HF{m3^^}&|v7xW7`~xsR{e_U-xYW&0E|;9j6qCvK#*Rt_x6bd)eT|Hl zdi)HT`vk|-clofwgL@AyyS%YgZ=BG>Qh^Uc=#GF8d|9VToG@LU6-GxN){R+o+!KlExr)MS-gVkoMU z-}2vLZ97aV2=>yl(3HsO54Q2herZ3(A{n*$`b!#dhrBSLaX=EdU(!KK zzf#0a^UH`Ioo3Ztaa5WTqYfv@zRy^YXSw{M%%I-mb$%MXe-*`s`oN?7U1zvT+V@i5A;G=ChZ`Fn z+Uqd&7Ajva%dl7MlHT?EF(Y=phlEuo(E7H9lf$B}2zWr$-`Q`&Yroxv$~d?~FpQ3!m2Kge-4~ zeH0;jA>%l7fPUeR)~?;>(LF8rZW4aEKA0H3v)`pdK|kLA_LOpC%Z|Gx3TBWn2uX1> z1YU{Krv3^?C7aTN;`v*1HPfG5?R)X}?Zq9$2Zb9-bVpL-OQN zY5UH1R`=A!2Cb}(L$l1GS-6?d?9IBVrhWWT*$%pbLTbh)_9L0kNo9h*R(KAtk*p%n zs*uWLkJYo0?2?rgvFla6)-@wJMIm~Bwp4#`Cz+~FNW_bugvnqRJh`G86E(NkN(@WJy@OwOkNYA37U3RPATSJubwFZGG*8q7!?4V0}N% zj=A5>5Md>*FZP*5M>z%J=nS;Y`ZsRt-fzk*y@N%J0Jm>cwK8a?!ml)zdE1jn_yiwP!YFO_W}8*l|*++~e-9ru8TQ zg|t}Vx4P0bf2UVRx5^i?gV@&qS0WBjNPBXZ;uUW#r6*44}RA4@L!w2TF60YA1RvLRv^-*TaXeh24rK~}YyywQ7fVEJ=Ng}e| zZiX;Jo}~-j@zNB_Lz=zH$|}}Gh}nWF^f)n0WyNW*x3RT(tYGlBKMQi7)Q!D6Wks4Z zS`d}l{XE}7SCS-rUG7MI24!@rBdBPl8l!n0pXH+vSpe1*V`RT@gLF}|^i^BIul-eE z`Z1PDC5}`3&r<{F6$!+zsT;wNFw_&Rzv*5g3)JfuoxIIN8te%JuPs|bOp&_vjq{g% zCSPRZD6SbOIWi|Hz=b!{aOO^&XRPPdh4`;b2T7hHfQnrgWulPw#{O14^b?VsaPMiFMAK(FY;bz$Ebzd!|X&*<8Eu8zQ@jSIy|;5BVZPI z81{VdDhK^%rM^mcap;5Kzb=!r_a3(2bBI8d!dw9)33XH15Ad?0peugBGwa=G1WSOxD3w-8 zE5$0_-fMgCS-cV%kq}HQ^#$9@#+*XK!0@@tKVr=)O71|w1v07ySDX`ft7_Nv_3yl2 z|6cLyJUTk}x}%QTQDa$z40txXLR3j=dx6lGF-^6Oxt$t2axnXb0Kd1CD_FmR3BG5K z7`aE}xIMRMBUI@krr$j<#VLd19|PjmE?A=~V**>^?{7p;guiNe{0$+PB;O8Xb|ccr z#(~14>ciFd@92`P-aJpxeU{L4l%@WnmqEt!v-48xC0KzGqz3>t#z7#C7^J*g>#JaO zr%|PAA$rHZKj>E}r~_gQ66kJkv`TVi@-nnZM?B*zdx60q)i8R(nyOuIUK~Ddqll1N zQ!a3~9q1xa@z)7(sfP9+3wknR?F0nR>rLvb;`)kro4f9`DJhb$kVN6eat$vMY$*Xk zZpV~CWLY387^Eqfq`*Q_x<=sCBr#n}O-r>^BBOn@mouxC=uY-^f1!AJT$whK>((C?W@E?Yb7|qAd;o4vr zt!BW=-Wjl>Z^8hf_2Z-WtGWu(395c}@P#b|1htGX{KTKgM2r@3i()*$g*S9PCUr%O zbw#dpJvr%m3hKtObVv1dF*-!?6M`MgS$p~;)!qs zQ2d}f9n?c$>B$i6$yDsgLic3b_2hUNXQ6?t4wyJD&3F*R$RkcJ7o*_SnbeF?>g$fv zfY7u6V94GQ#okhMZ<$?hxmWM2klqS>Z)LVg83{l~=y_Atlb(wQCB@{=kYKlPj(0ls z{um#9>3xs>VRYC@IH0CEGI8`$hi=e#TgBAvpo=6;T}*#`T`}FiX-dFo`VjG-W{l@E zV?ZxxzBF_+=Qn=~>FW~g{Qd_lhaoy5&61tkY*C#%%r&_)Y|UO~R`|YQd|x#P=jlc3 z)@at@#Y2yYV`DP)#up7`YmPMZe^WFE`|*J{%#u=yDGE4#{$)+mQ4oO5 zBW`I}dl1ha$^v~w0Eq_0EcU@uBnPm^YtU&keD|*9uc$#lDtc8C4>B2CKk2U*xANJD1&z@Bix4~e zGx(Tkh<;aZH6;eLBnuLF69rYz8_+N>aKE8lNu}=?YJZ`L@y%F z-Kv$T-vXjFeA8x_hgEa6ISTYE_NtT_=w=M4jRsIlbC})FHEYdsIxHHhv|5H^^8moU zT8g#)cM1ZKO?;5;!p?&ttma}$qhMPL3P9D;$3b^5#v(Ce;4U8?6#gG52ILRo;Ikn2=!_PhAQ7La)BX;}T#;9W_O|MAXK~>y@ z7cJujxZf*I0bz?Nw@+>U8FpHrXdYv_WB(i*>ozn zpwF3zHF%*|Zst?lcOw--p+}6dIRXQnS**RS2t)Sww8%E*4v#&^8Rof)P#d3v*vH<9 zm-rIR7P81~YadKsdM(7JX3^HF|s;b&4z%j;z06xtr0hc9>o{| z6LSq>AJ9w|ycH<=Fa;USC0&B4RULhX0Ev;1ZO=GYa5QKuw%nXa8$e120O@k3^2;50 zzD|9P{NPFhN${fO0Ni?RMJ=6!t1*~(!aXq%h6ioEO-GrJlWwXe-%>A`?&2mWULOH9 zIh3R((g=Y7jj^CM<5p)DGYnA?0D*$Z9kJ>K0W)u+X2$#BJv6hSv(wL7?0gWjZRU0* zxw_BEPCk`R6o4$w8-sk3>db6Dd&OgRxd7T@FeV$TyU74p%kF;V9fvJQoC!!&3LQvC ziYY5Oj~@&!#j>ri&bQZ1r~8@ubUXcsgy6jYYeeC!%!zIbW*jFI1As2jk~v{07W6A> zk2`grX5Nxxp6VY%kCvGa4!?Lk@sF7ezyascIK1`N^>rAP7YpR2q$>Yz4?x)kc;;3? za5CJrISqvb%vu3zjm>iwT2qtiz2j(UA^*i!)0o@R>cYn50vAu~5e@E7GYyRe1U*ho zkOh5mS`={~GeabS-c!x6itKlm^&d2AvbrO0F@Jlr%pn{KS8iWHE&w?w~J1Z z9u%%;ONxc0Y9YPM%8^X|;WcLrHAdG5OGQ9TJ8vur-W;N)Nz}w3)2~n7*77X8zO3(K zzyrgn!)Ai;kTDiocK;}lc-&=ZDkP2m+1o(^VXjruQ%`!OM|Z_K%}iPN4XrnAVzy_l zYz!#Lksu2Q{_B`mJC{>yEXV+n#~_XVdf}noy?m=~dxo~!iDmt6Mo$uTyl4#(iN4oY z8```o7Ggn1R2kSs-o4eTzpD&PKJL$)00eg*qPy3FL@ez%p=Ck9BGbTv$cBK7agE%K zn+{-Gz4zbm*8@B#X!80K2m&gR;Wil@=fh^7q~a2H4oxKfmm0MzA%cD-05?i_9OCge zUmjY(2k$sN#xs|(f^Dg)J4*l79LnO*<0d&-cffj&Tln71fW1wI?=*n9 zNTI}bHs@B0OyAS!<&3#J?LFwg-u=mYdmsG(Va}{IJI?@jO$U5^$iBIi-q~)xK337o z*8Vyuu$(E>MAE)}@o}l|3<1pT9A3W7u z@2bBG)-ZChoRpLx2WMg3+3gRXxee^FCXV0pJ<(?Jmd2mwt=T;Y8HqdLdVXRY&jKTG z6p)2^5`bc|0#cb#+b=7mGDT#=J$(`YQb+5&xKfw-Q-%6jO@~s6=sh9T2eR^KzRycX zTtZ#%g#O%RDe0vuP!)tRg4B^hW+u@fn>g&#ax4FGo2}@Je!-28)Hh7dgP)%p+uYE^ zl$%5c%)NMM-*g^Xbnfu_0p|1Bax9BID*jGpsBlT>Ejj@j_WKkl;X$zDncP+ zBm#6Gc6(9hx`%e}g0dgp&556pzD*P65X0s6OV+YDS0?eVH|=6RHV1rLUOEwdH59;c zz!p}-|LNYVkM1Q!ex*-mq;EdgZ4Alke&{rJk^^4fR!mg3JkaMQxVqxb`Hm4q!Sy-; z?<;OC(E^_3{Qh(UvZf8GnEUk?GXvZVc42$0aQ3^N?#~<6i0IS%FJuw{ZYNX!?p&e8 zW)>!z$q;IPhV;{|_S`4*7TszU2_55wj7W*~3PWbih!P(jQvk)kfmI&go`#H9MEu;p z+3LHE!9`{ak>4964#59TrzN6g5HZRp%dXgkrxJ_j{{hC{4?Nq`z;>%Zs`lq+=HWIn z1c2-Wx$H@XRg4zGCAs*)_CEd2;J;tAxcF3ucB4cY3rJ|_Z&O+@6@ZpW((eG-hNp+B zdvr>s<5+==|AN>(`8rb|0v2OnWP-jPj}eR|NRYZWTl_}--OVGRzFc|Vk?PyW!UOs0 zw=#D&k41)vdhtwB{wJa%WhT$1XE#~a8AZ5R=dj($o4RQN9BMOJftmWMIv+fQZub;( z*3;crW3XW>c1(TDHQ?xfBsSL^etxvO{cv@QnJ3*ii)!ypK5jr6^GO!L5g}!I9k68L7Z{wlWjvLiE(zNu$!dP@n;xt zK6)8%EdE(A>)^i@Q^J+Vt6pxi94j%`IeQim6j}MDI3a}_Vs!EPSqG|22%S#86})BB zrEsiyubN0fC_SyOiM4nLhr;drjSLQ0K?x%bOl;J{(w@nX))^prBaY}BzS5ZA*&=NqlZB#P1z5D>6_uNGJNvKp{M)> zy~d6Uk@K-+eUOj3xE@}0h3++nQa#b|Yc_cMZPMu?p}e=FMd%&J^`qq)CZ@;IO=?14 zq`&Oef2y{tQeVL|u)8l2ia7iEIX`M~+KVfMk*7*&C74>AKVFgZosp%=eJM?16xfvR zV7+C=-u#aZEvC?7pNG|JQmhzm>}wo;N4fV(F1WJ=!bnWfXF*m6>e8|t3n=huO3Dpt zy8clZ(!H8fXXvSlH~C6WgH=$F3L~*9xCqf7x$`S5+dph^P<(GBgE8b+(B7F*nB1U` zRGzvmfeta$Q7tnafed%|$tCz?FQ?g#{-^QjYaTiZ60kKq)%8#fN$!;tQ1Y5gz4AtR zCF4rJvZ0H@=xWzv>IG$mFDazDF2N4YTu`SRKvl0o6-_(A*>7U3-?t(6arr~LnA+aw zPo|f8vGVUzW*t(W#Oddyc&RFcZWc^`>H{fQJ&_6Ln1;nuArwIPrkIs(#JE1D6?;Z4>)e5ZL=*$B ziMDg78`~X@B#h$-YN;RsN9ADx)icKTtBZ!$_kR?9_Yq2D=0QJE9mOT(7N^iOBI4|` z;n4S$2J@P-d|F=Izcn!g@ElH%F`J4}Cre8kY0VeKk7S0nRq|@d0L~6?vA(M`I=Wkz z{>04eDx*z(R&3z?a%#Bo-9>^>nYEly=^Pju^qu{5Feb2;zV8_r@KH7f@rXr8 zp5oE#Eq|=9JjMlx=wQgGWfHj0#bRtX*-f&G=kQMP(k%&NfOWn_PENvf6{-6?h2Iy1 z-xk(fo@BP;Tv6*wuu!_Xq#cn4x<9RH76rqb;@MkNNs=PEXB{bWW21Zow+an`Cgw*r z4JC(K6Ty9vGya>JEjL7 z?pk-nx_;e=Z#b<6s|hL`nPk$ikCip%<>amOA_zbO+J|1W!j%abdu53nSOu_`r7w#W z+s6+$UCFzYN(aD28b|A`q!K5{kHWIhSK-e7H_L8|^|O&8Q!k9cEk0Z(Gs+V9Yi?A~ zkx$RrVn5V;y?6KhmyStVWTZN?ct5furSS}1%y50nI1gBB%lI6LY`AR+B&tJA2Knwd zVjk}F3`V1r06N_E;Ce{U8ts{lc z1kXKbIl&ZUB4+V9b~5XQuAL7p;LiwO2jQ+I{av><;l|D@P6ur>K$rBOpCaG!Y~g|W zhR{2bF&(Px#`UE=YmE90*Z5|TjBT7g)nd_|#WpE)8p~}{jX#=h9YnN>YRa8qJG4Iw zD#&kVILeoQd`;uqpSCETiAN3e4e z#w~0lpPJ8$(=!o6(?V}nYT;ju90Fgk-EfSDr8D7Jvd?Wl>p$rMo~Xtoxx%jezS)mj zqv@yLt%C-hC5JIix=z7BA(@!!+;cXxb;v20O51!jn!V1R-Wmo<(I1a)mSaZtp^uXm zS11{x;XfHaC^bfXTnI1^o}d|)vI2kI9R@xZi@;*$rc4n5;VVx%R5y&cmacr~B;86e z2glF9Ed`(vgMynMKTUJ&#ooBv8icL<3^_79>O4;yd+Yz@d1k@y-p9zjm?Fb^W=M=I zGV?_&+8R>@wM=0=9 zz2eA6&RcUiRVv#QWX-7d!kAtdgkkdrX9|=lzv|c+#uDIV-?+{pMPrDQ_JgkS4mQu* z{Vy^~;}horR=&*z(*jS0y#_lkUrNLeJEb6-w~IjYzn>WKmcA31Mdzm- zvPQUX(6;XhRBcW{k7?uaHOti24=Uy4Q7*Z>0Jr3b1AXDf7{J|9ketVFcixHH^NXQH zRN>vxG`NDui5RVkVK7a6xvP8S==x_~0N1o$HiHr$DPePJLx}WR2=qA?q>HtXTPQU0 z;-&gFMD=kYPLdr^#>%z=A6<9xAQz(4 zTn$lI4aaV<@}p}2^GruC^cm(*xI}%Hc@#UY-kE>Vd6BoCh^*ni-{Mxb%dRI2u$Mzx z^<5o1bn#G3mp!;ujZK@;VjCsR_o|`W?|P_yChM&r6<9oVaR|AgCA~^F@hO;uz307_ zg?}wex{XY0V45*(T&z%M`LG_`15G=bpf|+*SBeA#Gb$|HLU2+*Zgr)B356`;w`dFn z#4Q9a97=V7BTJ9)EqNsu*3j7wN2@;i@za|g}3vzb2*hVzI%Gl9r%>KBX)1#8-C`Z7MFs;u6 z>LN_tz#CWrTmFvet*eow*zi@>g?h5yw!awc=Dcl(KwxB>go8e-7XaxH6(F0ehlJl6 zSte`rfM>Fc`II=Jh-59Wq}9 zrFm#iiaC9K@Oo7Rx_wEv#YyEf*CW|TzsfnRPY{vPLjFF!gV>5_AdUG@JGWO0U5YPl zb*omsh%rmNe)G-i(PlUsZ!4#1EL$f~vDl{G-L%F;7u3?$GNVVl=DzTl0c${cIAW)! z_do~47Wp^ABWPn+McaSn3#YXWr4`<;>?SFCQG)?ubPoE844W7nbeo$$DI%VaK33AO z#FNc1O?5i?3}&CWL{m~}WOjoH!xLFM+7?9ep8Y3Jt}1iMHgky5NYNKRXqO0y(GZQw z562f%O=WQ6`x^_aQFCT&oe`<-nm*`Cy#fijc7||}$Rcl`H=L0^R#9xRRL@_>LcEp< zZ7vukSr(&RNv#;RRpAdRY8J8~#7XZiS?4;xhS5?tB!L3UjVhVn0nJ7p;j7gA-!PGk z3LLEwFSUP(18F3_v>^dzl*v=AJ8d|tRCu=ophQHl@W7sz=vypOzocGoTH0Jio zznR|}n`XvY+4N8Ri-ov(B??xJhE=xI`*ao`uAwTKb?G~}E=9i6(^890?-}3TpJ9}m z0gz{aaAEwOkT~F=2ghi@BBX!83VNU{`ASo=b_A{1+-B0Om;aO2T^!GNxD{v7713{F ztvD!)zU}A{`x_CHVHlu?8`@{@dXxbYniJH;-?S!YRLNHl{Dcka?U6qB*xq-B1|3NO@LMgwj-m29lj;ML zCgSD`?OfF$?gdJ_EizhdL0=_|%8Vs|Co{L8w>0^YhgIc&g<4G)eY-pZwX9p)H4=*B zWJuaibXyn=Ai?Ai+{Wx2GSMmH;AJZ-_Wy)xlV;K{M)0bHHWNadswxd~r5)+jD$y7N zZN_i#qi^5#*kr?pWq8_ymEcT^e+}jf-0TFFNiawUve2TB*K2%<}22ULF z-;WmGPa7feZ?yA!y@N{XX-h`iMo>!-NpwVN;1|*v5BfM{d4`QtBW`fa-fsV*+UgIA z`SrU%O}hvlS^@FB!kZ#ipvu6dozx?l!i#;%0En&usB@sNJ%*J~?SSmGPx;^^F)?Rr zuZ+ql1bNi1wHDM4y!_BQs0oj?!rmZ~6CFO-=f@+l7_*ISsZpe#trOBQEL?r5kRZb+Bm7N}Drl4Y}&~?$Kq#vvlAFL7_4Bg@2%05<1f3NardSS)1G!7Mvid z>5$lklLtUqb-ccqWVC}!G(Sd0n<1LD5qL)X!4i3w29E9_ZCjK4F2!ps5h%yRn^q_# z8wSMn%s2@tNo%h`117Zn9VNEFQ~wdPj^am86=faGSpIx{?T8o|eM&9jF}kL1gK?go zEb3vSm@ZGOO)P=PE!8|{k8?i?xGi+unwU4^5o#`Q7Atz@LAQdbJgFS9f9Gxh5Y5J? zN?289z0gwP4O&QxechLXx8nj3@8`TPCGH^?k1|>CwhB@%SIAlpIUYIy-EnBRJB@PD_=FK z=t8|(RkKVr=}UXkrCEzpwXwT`yJPGYcQ&)4LxSP75qkl;dhWof%YA3cq;Jmab9N-J z!{ox-GZG~-qa;Lf{4&e@GH^;V`)zVF;lk)J>%wrVIFR1##}I~a3gVYfeZuGK>kPF~ zt<80+Lof$mgf9zt@toRe(P#t~G0Ny3{k*-@w_Prnzf{YB)m8GrlMb(QrR-nl+I=8o zwKB3VEQym%AfeLZ*vTwdUvSmU>Dw3$jY=VdN;x@`Q>wmUYL%g$WXZ2;xqATVM;&F` zae}V?tS>Gb!aA}o?85%=Yp(W77k4OHi#xA$1bOP#gCp@g$$69yYAC`N9je}+*VOsU+T6J{Era*ZrX|oFq_5#I#e<*bjV{ z-R3%2%Jyp;9G|zS)&feY&)wO<((6hxBYLk&&u+d9D$AW86ONZ|K7FtD=z7&0CO~^+f#@56q)$aT zQ$(G4u|z!0a)p1DHF%V!6x?PrCAv2ox%Wo8C#q*8N+Se(D=%(J|nT5@*)#;u?hHz6=gd5ZG!f%Z2N{_A|!e z+HDj_@a6YyK0?R=VT5FNjN8zgil9z{KX^#%h~P*Xcn__596&XZh}-;HJh`}^78DXv zU5;QCV&PC*pyzTZK(o<#?#{KRJk`sS3n8GAOm#FUQcJpHvP|J%RHj#;nkG4qs|b1d zm%w4Z!#lrG`Ei;T)!6vsZX)C9Qj^ZNZnOC}T^rY!x-r8}wVdei0|)Dp_b5Dd`slJB zpTs~B1^`IfxV*VD4b8`L8|%gd0ydTt5q<&-Ezta2ms9!+r`a-tvIl&|&s;v&*@!)g z@~$?0QtBC1Q`7Q&X|XqiFz@oMmGt&aEJGrpM~hyUzg7aB__tr07D5pWkLokca>jMQ zyrl>s`(*5UW+>g;Gw%slt?YaGGT6`ejj!owfEAhJL{E`3^8 zi~_;w*oH(|AgyEiAwGY8Mu^qM{lpMKv$|pp0tUF`X7HxA%rT4vnHeH%jdMv1p)I&S zz~D7*@acy9`?Oj!#4}117_&3l$C9K?Udoh|RnJXBKu@3)pFy|V_+8g_mzKoz#Ub_g z8S*1BO9G(n2MU_uSiJY=wjb|DxY`;{N*oO7jYu82a)tUw^3Lcrj*l8)6uvQzYGfew zQ)6sGf&3Dx%PPg?}t3cKPnpNn9LUtxSdYQTwSLO zvsu=(d@^}A_N~HZ)uOo&OL91c4q>inF6ND(6VbK{DY8e3$*K^I@~m{&ARp^~Fj;XU zZJD>gw>f>DX*F!=upr;7lP>4(ElFAW*2?@Ydw&M1y4NuC;z=Zh)&Q=R+As5lPuAf$ z`cFRZYp1*6qmba|!Y@$?;sZdg+QqFm0+XiO@e)55w-Xg$W;;n5e|$rI4i!|trkT0Z z(Rnn-EHR`zsg^Q(Q*xQ@z4QCIw3ioBYijGGl?B$OsI!YK{Y#5mr6&*_;&GoQ+AQ!kCr9(l^?B}2^K%w4{BF_b{(w@ z+qA&;6W?FO4w97xI9k5DjLXCT9#|_mtpA?!QmX#zsOkX06Mw$AL(8=o!vnQNT9Blq zW-^beuAF{O*L?J6$*FGbPxlSM^`AArUu!-+G`MS4HBEf+F`LvMxL^DZ?qosdAtdXm za>4{1_AUTyNiAPdCS8&DVn1B2{L9GwFM-F;zudw8Uh??zsz2;CiHk!sLEE(2P4-LI z@_Te#(5YWfc*c!KA)tO`o171EVu5;r&==MOq0|b*y68}}l zjs9JBKx*MlVuK9D_zzRuUbO1$fi3OR7kgUc{2*gzT71B986jx%!|5C*eE{-?F2H&N zlyolX%_ks*$74u{+l_yI5gB7*tUna3nk+<%d3e(J`8B~VVR>^D9aFNEUnxfkUM>;r zKJR!`#%46zoumZvrY$DRZDm%4qcEePZI-2hfl}Vh7d>0KXE<21^fw6=V63FwOL7sk zNYYPbPgiA|8U1dFg`|`f;11_(p&IbWAQr!nip$`DQej}oe7ujk&u|Drhb(s?ey;h} zuuFULZ6X!|#pnS}-CH zWPPwkARfMgyco)pL?HfR`1^@1QVh$XNFsocr6fqtHr|yvu-AEIwUZeTSITlmhY7b% zVJG0H5t;#I-h&LiC1OpP$sxb({u{m<7}=D9D|Y!)-7yB4^$D;<>Lu+O<#T}L<Qdb643EG;}HJ+1^jp$PrkxJ$CK`*Y4A~T zX%Z@rn)PoN>8|Z*sfE4?*+&TW*%Lr0@YOWLBgjAkta?pG#29=kfb**yd-G!uS}?6v zvhh&1fCpKT^^D15n~ybAH3K0-@;iMC+K}-2h<<##6#AJC z_dl{hEe=*bO`o0q%s0&s9jd7hK?)T=mf^I}L>;WU8SHMvJg4Kb_ijRvrmwkFRno z;O5vhe{@>8+g_pl)AVg8gY$cu#OV*}z606RU|h70(c1G`E(tpI8<=%RrKUCji726>MB?+1@+Y_@8Z;%)`XHd7BTK{d9 z7X$gXmL%LJsrkbgn2 zcapE2po_;&11rx9xhTse7LCRmSjxh$UBDr&WKU|m8xMG5i2d>Tw{X^1i9jydHwFi&Azw}L_w{_UoKIQq%>G?F-%LdwJaS6I7d7{%S}R!| z5G5t*L?10K1hR0T926lhaZLZh^vi1dDFXqiuN_^&En=N z5rbMfPa-wjQz3c1yY5Nwo1J-KziETaK*M`o}uLeKZR-Gh1*bTljb0|&g z_JlskD1d~l`0rb*N(v4+fn@l82-N8R6OR#M;Tzp^u<4|ltz6G(L&iU%RaUAqkoeBB4o?n^nz!LUjF z9x4lX@Ex`cp1zV-x0^SXiNQVmwm{t@w(Lxx;C68Bv{OOS>;1hiNf)o5|GiA7y*YZy z%17SY1GsnfC&`uUV;0R@GfOCdJ@$~K2tr_co^b!>8RTze`OW*y8(RHkabBK$2)1xw zvw31@$BEtEBhvGpxM2*_$|%riQPCZCv`Ro2LSH(F}At@Ru6XJ z!#DLXQNb9x9bO?(!awF=0gcd|x7e|KjD>L>^oacu&^Olx;W4*H#%%(APT{K!oORr{ z4rV)#yf5UCKo>eD;)xxe^MraqU@l*wOadA^p8chTF8&3B!EEfTF?2-ZZ2sTi0tSM? z)<{njK+jdyDopcje@-fz?0|>d0!(f*t+s>y9Yk_WP)MyPAPQi6TlWY60ROsK35f=n^`~(zHz@&L$))AnIFBZfM9Malr9vh$BrQKjeQWrCF zU6lyd!L5t}78^FL?;Fz7v%D)5;)~A}J|D~E*~*m+R6z=4BkTmYDA^pVq~OIMwxXi9 zC_x-Y7{K?dJjEOxldvegunGf(;yWN+5m4@TpJJGuz!rq9IY9}hR9K&+GLZBksK`kB zM42o_#nMhCo>J7ZncEjbSip+I1gi=qNn;LJhf?V3F=8P_2Kp#Le_e40clDSTA}Pj# zkD9c#Y}GoD^q5WNAqBE<);C#-fBHyx{SA=w`{{*6>ho>&i?&u-k;W}aDuvHc`PC){X>tQev^dtV z4D6m5P@dLWUb`!>~U#vmz9w zY34~>7IpJsx&5|LcDjA?EW7!f%9||84-os-1P?as4Md-qynJFnokLJaU@GeH@V(A6 z8-mzA`zNALyk{hCGdb`{dOh$F!GDdVi)e3P{|kpHL(@RlIz{ zWMj*{5F-4Rr{3EIIv}g~!2ZJndp{&+qcxLsKWC4~qfb<}Q>TFU<8Cqu)@$$GaR+Jc z;Ek145&R$2kLlif;H69XZ+L+7b-3_6;R}#@QI`*&TuKUEx))?!`$)K2pK;URd$N+w zg-}8w9u_EizpvsJpJl5_QSrop$hIgw3{6SxFs8*L`ZS_e)?RcpfsA52NFSF><>y)< zT%uHW+K#w=Q(pW?QQ56SRSKA0*wvd3B{#AGVgU*+G;Z!RJkK85`Gk`$;L$(J4{)=7 z*i8XI{^T|!g+-q!nho*L*|I+r3#?GwG99YQ5f&eQ=D$?ppSR`D_fl=(f$IcbU`41{ zfo=U{tLm#4NYywLvu5p!6FFgL)l=5izWAV$&p|(kUS})5ZZd&Ew_X(3hTuqjHBSdf z@ZwRm)vw5kHO%a-3)RFAKZmw}!-Qz@Cy0P-8z+i7Gt6k ztHv5TPm6N*CCCFNH2Inqgjum_p;Q~D`p)I>lT=m{F-El5MR@lA+jNB;vy2s^#z75|6nqy{n+frBKX$nwBcm%)R>a^)X#O-o{r- zTg(ZaLb2g}Z5^Sd%owr`3rczvExn;eW?FXW+x8{7p26J?HB_vL-^K0fmpnVrT6C=F zozilx>LpUM!$5=X?mJuIR@hr^$(B@8sm4&zCmqtOFt{>nbOpA^XW7+%xy-4pOrxEz z8+J!MgU;5z@ID>Dw|)&`YtD1O2wuzz1%6Ksk$cfm>9JFZgKm{gr>2Tb3R){>Cls&^ zNt&grO(H@$QD&KCq0#(%)nuSr1@qeM*xDZ*+8UXFT69`%L{0RC@*xb>)?81a9H|Vn zpIvkI@ma2<2VK#?+rl~%8zW*@V76DdEnP@%+5xdpqgif18iSMt~r zKM0U#qOGGwO0mB4qSm~n7kXzmprn7rH1IGI1{5BGg zjCZHHZr5PWS-eZT7&;w&n-{z}}<(N#I9=l0g>i zAZphqJ59bj$l0LxJPphDIzAxh9>d8Y%1>i$hxJkDGaoAd2N?fxo4}fE}-qi|coF z9l+-Pj}Z)?vTXAsn*qA~R8>_)5;U{)DN$hyZwpli*yNwzQ*SY;YLRH>+f| zvu07S@@mr{mqK(CkJ)P0hIMkb2G#a#_t%PZy%9__3Lw=Z*T@J^?vk6a-1mm$63SC( z=Wa3t9elIo8*o4-tg`85Y^h|RaGqH5wlc;aIdVUr;Z1r>^#|=&NNkS%-JfE{WHR3g zT4XynIQ)`>GOwV0F_{0WN4n4(X}_`3o!fmC#En?r(UV=ETHmaYz~IU6$`oQYd!lOY z090ou^uMUJl|fi9kA+^>Zqi}n*MAerosjmjTT`+HuTQ|cQL%|@=DliIBlx}8Ur&3R zob!H9FrPd(JITIcJ=g2gd;EqW6z6_#^+u_BU3NeHOWQ^}-s-DOyE_iDEI%yP>+yo; zWC}qhp*Ix+SIseWaW+X!J#wLS92quy6_VF@tYLj2_@wmGzKGy~2nd5@Adx`fPz>c= z^R8%tqL1+i5w|UTL3?!yMx0ibbc|rhXc`$=Mcx zv!!0IceR`xJR|g#o`_*T{jutyNW*Y-hyR@b*WnDY^4ZCHS4>h?*h)I+w(Alm|B z&TQ*~;AF#RKE(>ewW%nfKy7v^p#fq0%?OzX;=2)++Pk1AliHEeAfp})O8^xT@bq1E z3pXZ>=VlnfP5~~UxM%&Ad)M8b-X8@U)8+`x@|7j2c=}RT)2ZaG;YoQecV@vXH^sY# zx%_DA4(5Wl#2?=1enMs9XaE>7{CI6scwo8c$`$+&k3`NjB3oB^0klJXi_Sz z+CGZfd;luB8I2vdBSz{q%2T(R+|sr__bZa@-KTMQq5t(!-{3(GbrUBpj&n>A4s94x z`B6Z@Mt-{-IU%vl%j+Tw(m731ejI<=tokKYwH#sKSu`to%uDlWH_QCZ z@?e4YU=&h^IL%MF56gTdy5xMM!@vBZV&dhd`#`+!md0o|`QkY5;14B&0G^j~dWn3e z9g!YEZCkmx*Xu0Xcfm@`%6``!tsAeD_}q7MdUIL!8>jBQ+vhPDkNW_ZC`@6lxOzvu z5dwPs7AxZd3pk#ho(%jQxs+?z>noocqxdH6g++7iuxC;Q5v#ZJcS^@oj@+=%-ZF8Ls#M!6JB z4GsJtnSX1mCzuWqQe&P^*nixIh()lH@y2Yw4JnG;38#DS8+|ld+R@R)?<-(Db}bt{ zm>%aDCBN3@ByPLR| zS9j04Vx|hd5<+(K`^7C|CStfE>5{F7FH$4bts)K66D!JO($c4*D{M7e zE|`!pK9mxH3`WPkC}!uY(9r4#w~ROT=Tzx~$otP^jJ_xprmE1gF`vyjG%gietI&H* zKa&geE*J9NSF+)pE|&Z*RCpd`ly_*%+!sm(94S}GIy6?m*bv;^uYA}`vQQr@QY~dl zDU`f14;BEy?A|GmwMj0tje6IUnXj1F5R`nRSJl_L+S^wO7fGd$+qlAar zDz71gikWojQ)nOKRXMNR-`fFETKgiV8!m(Av2S7{jBoFA#6Zk1XQnDeOBF3^T->sj zKli+EY2>IhAnR=ZaQMLdyaGrQ^ex86Qvv)n@QIP{r#M-zVo2wJ^*x$VOoG?1dR&|3 zhI^e<70hg&WA{-ELs#j?FqQBueUyjMcmTyo<<9&0Ck!vYFtmc)Xi#e=F_0IxH$rHG zUyO?vOM%QOPaBo{cu-i4#g+BSexH8t%3@VWy#^g%RI4fQ=RGRT%7Z)NQIMbYsf^W0 zhXNqD8SlRDo|z7yjON4M69Fwm*Jhrd@5j49FV)F($lt7f?t3uL#D~>eX|#*%{0R*s zj&VEG?YzTe#Qm2qY$3$hj1lnPqu`oHPk1OYJ5+V8l6x6DILf|)~X&yq4r2^OF)?7>0@xf8zdRlxr@lktJbhFW%}h8Sbw0PUIM5u3b1lEQ4cxai3RH z;dv7#m3pFJtaCT@dWk)ISG`P#+)+cSYNj}7yu@PlsoYcZiHdt8Wdh{R27{Gz&86uX zE8}}Ia=Y^n{hF#jKlo-{^mR_wy`}15jkBFc_-E>v(>gYe?~Y0li}DMnwMnmBpA0U4 zo+8Ldu72 zBQ2U##hJ4ns@-4VcK91vAI}<@tlXpXEVig@&ibp0v2k{X3ki|J{X&cfZ)kM4**Q_4 zD< zMPuNjl9S+2TGzR+>O(b?5_G&@`{-NMtml09EAQmH-RnxfI!0$zPwV7(zS~Y+7RgMW zW_9ZR;I!-f`01xpg`DNDsLjsYZr!tpC7EsC*W#1eKhJve-tC9%oo(D$-gb&)*J9+3 zcCLahqD{Mw8Umzu)?jC?WsgoGm!$W8ZC^~aR`h(H44kv9J8v8Na8icTJ-lMNh?BoL zRfs};XHvXcmfQP-4Kk)IMTYO(eSIzM%;Q zI|c)XUlW!GlZXeC?g!%t!Mc4x6zU;Vj)KxyxU@ApZFz{wKnO!d2s3RcwR$LrV<`MI zgmp1QIXRS9JoMg7C?{8#kb2k&MHuo~7)x>(b7L6cOqd8!xB^%B&*QL5gYXNl@bjeb zKMmnZ`{8;-5%&s#h4PP71S3q;*&jNxn`cBA(?&cdinQU1v{R3K;u!ffI?|~;(q%Z( zZ9me3D9Vc~>bZK9w_}t~bd+CtQ~(!6v^DG;1GNIMy2wKhuyF4U)?6&~cRg%IAAIi_ z(Ix_Zgn>pove#hYv3*h5!!c_FL>K%-W>}J+)*u!`!eURtsC^vkJR;Uo9{M#Hh%_Yh z)(4x&lU!PZRSa*3reIl%F}*}_0)L>!X?QHbus8DTm5%J9Sh%$(`%iu%`HjPR5^J9jivCw8BT^px9&dZ*0vn9R(I%nNOC~}BxgtxD>NEkpyYvbna?GoDNmlcc^)VU zABQEB=EQf4&b7-6$?Kuc$e!wDGD4%&Gt$m4#%L08ym^24%p_+h0iK!9`_1PqhG9 z)rmwEoqknL7T)cy@3beO8fKh#wSDN);De9pM_{RhC z;REA!=XyA4gP;wlU=+N{U5P|A&{Z`sj5RQQYhWR5MBQy<(`w{!Y2bz=T^BxZNG<9{MCol|3jW5fR-F{A%NV#d2_S4yM) zKTb?v_diHX<-o`PL}I!+TH0G1Tbk->-q$zQSO33|n5v4>in8LelKkSLf1H@;n%1zI z_K@nfu(I0xTPh|eD>E}ADW^O>v-B2>Nli_CUDX;`-r`r*{PG_&ropSQ!6U!UHMhp` z7L3WRvdgTnz6E1a%T|J^|ER?w ze^D_3f&XYRKK`$~ef|Msp1tt#eD>lNjB)dLerv{3UB2Yow$6>f3YztkvX?! zjC@$8Oh|@gaJqQVTaj1)m@)VLlKFg+_`GAdz5g#}49erpzu6dHH|M7=p7u{&(dN4G z(z3TUj6I)_rH!Mx)sz2ZWAu$5Y3ZA(X`9?qF>)Gu(u&&uc49=N)dVG!`Nfp@MHO$I znERp%_inWq5rtbShDSj5)`|HKAx855CBzWn02RdlSNsLZ?Yy^p8xY>r|B#4;maeEy zs1B!)nZ<;0BG$x{ef9r4{zA^4sh`VKAhJiM$dd%BirCKh-|?4+XoKeq7n=Wtzd$A5 zBc)v$%Ofl-&<_?v=zHC{O>510+d;o(nEnfYfv2|WgGIa})TkbXKS=5qeNFXW_=|`g zvvI@2{Md|DW~0v5dyguk8YkC&J0)z?gfarw1j`ykcw*hQNFJ%VrH(``P)kvYA(;A$ z2zwC_k)*WtfH*J*Z;N^DlPb4r1)MHnN7u#g{R&0Bb90;gCHWM%_74OVVe|<+wr6R5 z<5!3k1b;*=SlT#S;hVrbi$YlO-bNTgai2hin3bJQamYZ0Qp95CLy8*I#0YWsh4@?j zP$d1(u>7&XwvDlk zQJ*yeqPP){LS>o@-i%C$AY@>#o}wjM9G{|-=ek1C(LjYen74?ffn9lvXKEPn#vL`P zT)qeG+j+qRhg506B#;3EmA!3U$I$qG>N; zK~eok0`5`D0zC5K%KZ9|IG%61&4`_^N@v`LBx$ewy&+e)VJ1+NQ>EGGr_qZ3Ym2HdCH4H_Fo%`)}_(FFqJ{bGD>-jpto%wa_vQ4NcJ<3~V$21brD>(;cbo?C6!rMtTD*!W zip)tnZQR9N^K@@JDaHj&#GUwv-&wrhuK)Bm^J9@fXq^u8y8G-Gd>K-*!vr^_cE#8I z+z4;b#A>5r#@-y?*T)a%YO6?2_rMt-mHStJR;$3R@*X!&{B%RPd;N5t+L=j+sAlO( zmjyAIVXzRWqk-||?LnEAu`n!hvOChu;KNdAZ_i1rBg#;lO4lCK8 z7k508i9qP`tcFY((hH;SiYkNO>{Cd%hC~4bi|Nq@pZFL}hh#6064|~Rk>hC$E7BjM z5h2PUL<4v`#5>HhO2zD)8X9tw73#i>1{`7|Bf89$mJoPF&w$Kfu6 z&Zet@5`+yg+iQhbCrA%8IR5)7=ph(r&Pys&2BqkAF6ekj! z-Q|Wz2x5LQ?A0u^c9;dFc~cMZ8S+AHD)Uh8_T@^laKIjXN7K*uS@B8um`FnHdtKwB zxm-p=>|g1<0VnAhSExxO9<(^ZT-+50w9wwlUWTa*QCGQ@Xd*FtSL%fw`8X5B1>zz0 z7@56DE8_%eH+L^kjB!Y8>AO?ym&m4fi}HUBXXZ?!==;(r2M8KBLQS3T7mhx#<8Zw@ zs_KPgG>RT-E-Lq)<3$DMhrRW%Kzm7F_!7lvY(3c3y^jtRKo+kC?>Fp>>9gUgAtM4o zP{HLa*beDe{U>WgjTNl3kjDcBk$nVP0(b6)4*-vdR^9O|qr*iQAG=2vx}_}0)3A@6 zbS1^GaWEE&A0a(;HC}_07bRz(mJ_ zOSHZplCi!~dpO=GoN~WsuQ-f}Feag?paaDK^t7G{sR<}DcQjtC!2Y|A-s2%3gvN{Upb9C2JXuQyV@qH12E5@y`D+OTdR1&B&l1NqP?1 z1SMM0?2xWl$1ub;%vzZ>$-n>(IMZW)j~VrJ=iF{>n#S{ z`LJHkar)Htt`zP9lh|`orgw8_fxBFs>iN@}D9Sp%ezjV*gQF-$UU7!wuJ`qNFF#NH z{nLrN!6x=z@9E(#S8#vNr*83=Dcs*H91cJ$4A)m?!2)g>J)(?Y03sMtPNj(k-UcQ_ zxBJmwX*K1c^zzE|`9O7j@Lfa*xq1kxNbts)nuI=>78ydp6-qh}2%iHO%Y%5@f_Y8D z6cq6F_``%9!@wq?!NwrN{4i-peF-$xZ+&Qr388@vENKRG`{@726IPD~KE?ZohQT)p zH|d8S1QXgd*n9`shnR@nVjea~qCI&S$dvklc-XBDqd@imZ{W$}L1^nUQqC|SF&Z#< z49C8taw`w@5Z5QqW68fH=Yp3zv)H-P9+PF@|o{6B&R^rO9GR#AAyc z5tgU4HJph0Pl%Qws7RP|5!IWw5It0NgirzXO zzP152JOGR3r?6^Jv1h)*>jT9a?eDVzBPdMUicHvs2tqz8_q=K(UvMKhF*Gd?^e zYz)r;l7VykGU5+1ash9{IWm=$Gl$Y)i1!E+OlIXsIxpr?p@d>Fci^fgin)~C2uV;? zk!2T5DcncZ-A>h;N!1@iRmZK^&>nCX$etlVWZRcnbwON+q`WH+oz0}0HG603^=?7q zwgH;sgh#yZ3E#wFcv6Ytwfdlc@?jPH!Cx~0w_%0QY%Yrz7>A9)_sZ!glW&ngv~nZb zN76gFDFk!Se1b774!;%oTM-|A!IgyC)dblVcz61+x zMiyc+Qb0C%1PX;9n?i6>VbfEPg?@=eelDpOVYUWz>LRn&3}IC-xQ%AbTO?@BCtGQOezcT1;fgQfrskHNLj-lcos8BA_CO^$$&P4;fXl@ zmpl5Ft=8nJ;v|Ri@CE)iHke#P`oIhgs1F)qFeh`Zn>9 z`6PvB3-t~r+{MOHBmrWvaBY&}8*9ATwy5v<_YZA-2-q$L5YSdtfgz|s!%izIe7IvrK3Dj7LU=cbf&Ce1y3C<%j@#baL~(p6ZO(p6ZgT&w)%mO#Lfyl zpkxo2txIH(WjOvCpjVk+M;Yh{FQ~HmS!Sm`Lw&R+q7(pM)`S|av>66a2AH<=$F_{7 zx05*Dp3@Pwd8mk4N3(MIKngS1}-woaS%V@bt>TfZ@SUoP7jGz))^OxxtSUpGd#F&nN9C zu@gW}2;F@#9+>X=iL(Lv6H8mS@n+-r(v2ggw5dXT<&< zDY@u7mvc4fMu;q35I+(zjI_CT9;&Plrsf}&8_^R%0+rc;yjXk_G%$-X=mQcVZta*L zt*p!sY`-48Dh6~*DpKbIYIA}zi4Dfd zE$K-p*)XV|VCTEe@^{U$oXJi5iOyo;pW`~y-!-F=h*{~Wjk)nsWl(?q)K)bFXfO(R zrPHkq?R3@jKq7kOq22nJWnsLwIpVp#DMY-^4{c1bJrU4=7+-*x#!Ux0p~>uqSY@1< zdofdG+((dv;o{TT?b3wHAjoli2$7o^%!{e&of%;NthkI$DnG5b=P2(xW}chbS>rk9 z%^9&*%*gn;x#meHftiD(DSWay{WWbu9f%9wlz8am9CFIc&0zWae4fn$Fp1R8(%_!k zd|v;s3!jc`4fSoIoP+7}tnjRJ!R+ZHX7BjVGbf*&P>Vi4=!~I@n4PY0FAV;7x^-yX(`%G`?V)+qUDly>7voi#~cOB4{1b4{?Zux;!~UHJ+H+%`H|up{TvyD=i28S zo8^eLWrC8=cW&tFbfArHD{u}-PQfhk(Oi$Eet{)(`74B@zRGb^N^DE|}8pQO( zY7hIoBZ?T@KR<_EjmB**EWFaLenq{_#PytMy-j)5;b>}fjgIQ}iVpkg3%t(>H3%K( zmyXocFoTtt{&n#5q-Wfht`~FRHp?*rYhb)p;9ot>SIl2!5R2U#@0Br`mek9Zi2OCW zYaJ-`-e&EKFOM5mUh*Lr-4Lv|dbaTzp}&)3)fH0)gNmX{c8sW6Qu7DG|b!8 z;VTYD>jaxyk^O7lcMz8o+eP*pkCHYCL*@~MJL>Bi0&di@?ue5b+QN|$19#1bR@Aod z5Ra{xExNz1Dv@jf?!3|_lln{5?S>$8r>)f4WmRUe$~UI)+A$5;19@TgENSuY?X{om znH}xo93NBuMRIrbifY45$jdw?Y>V5@N9z;|ABKW1j znLxGbj`*8PyVrxwVc&U}^y_N~mhy{6cn}p-4?){Yt=ofm^^1Ak0)P>b-d zrH0qi65$e#V+!`oZH@>Ej$EdXzy(-yn@JA6-z!E~;)YEpfo;;Gb{g=-Z!Ytezd@E(#_u{cniRS z-%s_ZSzc4A!s#9KXl$&`9H)05_Wyz?{Bcq^bDBO2(xVO4qtb`b`{>a`K~G~IQ(MQM zJEIoPdZ^>;5Uz3;1Ur9Rrca|NH%8^pbLA8ZJ*er{5XyB_p06*>6*eDDA3%RN$A{=8vu~R|-bgVTsHYdQ>6f#QC_(k8*eYJeZvxBaEl0N?C3i zlCL1R=?mwO>)qO$hQS*ng>4TVvR*x^M5d#yUMgF@GvkH>Xv67KuPaEwSM#JPiZ6dd z>Zk&l$pHN^%krUMD6?{g{-$CifuD%BDP&7I76K<5>W|DXjb)Mv`tSIQurHazr$^%^vJ`1o^qP>xs>|jl<(rkYfRmZN0~R*EW^L?Q z-^%unFQ0JNH1o$yd)q&Ll*}#MEpI`K7pn4y5slZ~;xEND-No$J`_e?jhpxp|cPfLC zvEC(uyxKG^jFo@bZY)99D6Ob=77Q4aZO$4G*Mk z6{)H-rrS4ar2f4-`f0bcQKJ|JpP49{xl=f!alaS8sqpY^p=aU3+w3v*#24XQEdp>w zA@;}QiWHf@H6cQJGQXu=xJ6}_r)r^UhU6$_9Q@L=n1+gVCSUd}T-Z?K;lONl=Omua>i_5tKpV&A|@X?rnGbBgY#N@~JT%FvJ61qS_&iqHw&Vvsk5BCn0s~6gVE%Aj) zVXoyEHE$KsB}}9U$vwlGrn?IX!tWea!p+?(^Hm6wADDUc-ZYM5q$6Ik;uo+-D2$5+)G`^{AlA43YMAy*i;es}eKka15PfKElQ2RUW4%td3Jbg)r(7Oid z)VjnIPpRnVkZ(LxB@bd1@5S1x92okPxZ!BFYS`L>?-|;ZwC-jVl)v$xVs~xNx-9B( zP~O)xqS5p!F=Lo%cWG~RZ!2rmaK7M9)423UzG4u}WX*%~EarFasjjxGIHS1Gxry`^ z?5(@YQtZ{1SNm|ZKC^m895_JAYdY_DXqKrf-nZj|IqC!6<`0tGy2-$&VwM+VE-_f_yDZV4A(%htoQ2AkHl@QUyXfMR z^4=dMYF~u>%2~=^$oJ3(l?JI@TD>2R(v)R?IlK3z-i?HZNu+X zZ*F#pHj3EuOR@g0j4-OXe3f54&*X81^7_I#ztyMtSyQjy*#}W7+nCNN#CvZ5d6&Ow zd{s8&Uh<9AnKxrrv@S;zkn=>ytAk3B6b8O{$zuXn zK5w#qEBEjIT;FRWTnJ}Xot5H20oH(5S`5y}KbG+)YcxU4pzjJC8by_aS<@P0?!MOawZ-1T7-?bnOI7@BqO`Ul(OxE%li-qBQ zgKXq|5S2K=L=27v?w4-HTom6UgFi~SJtou?Txd)$4=`8TK2n9Tnifbj0gLHwzJcBK z*=I8X7oms!^f{wM9i=pIheFXtocjz&agtN5uT%ttb-P2#uMCtbJPqGnbbn>PT`HX% zgkUWLMk$uS<9Oi+elgmZ_%aPhc!nn{vJ9>q`%yC#F2?3xij+KV7)=<&%i=!XQUH{o z6_K_C%yj0Ox&ema+csR!XyGCPuISW^a6;ZcaGlsBdSz@1y?{=?wle$eOTSu<-KsE6 z`I6yKk{S$AgsUbiy+MI+T#=}#t4VSaxG-BKnGsGTZuDd%1$dmSoMX6r_+%>F?<42Z z&rFkz0JK3FnhM>{Z|$N1QK}Emz01p}g{&v%+Kk9DRR+mzHJYUh<1*b$K-J+!AF-)! zMqC~a8hjmV@ElHb^?Oxf5u;oQR0e0}o#PazwotPI1@fB8a$*ZB@0upFABIeH0=L2Y zhv54duGSuI4ni}?tKo>-3xjgFV^4RA^OWd{y#N4E6(7-W$9AlM^d&YV^GoSU?_eO3 z>{X0=lpFDh$AI4!BSW)A%GpA5n&-23OcvwT)k=9B_27Cm{)stDL%%qbv~itXh^l7?Y~I}Z{l3!ck}0v>uRmdHPgj8Z8eSZUUzY60&a;-m))*<4&9$?q{4IP^K%^ke@_=zJNo8gyR*_^bXTvf%gRPKs ztFntdy*;}dDRcN&hps$e{~Rj=B5l!fH;9h)L)(^uUl@Z`8TLn93)iT-A1P*45j7@%H}qPqt0>exFz z8pXd9uu~qLm-VcRhgVAb08%fp>%C~QuPw^CfD%7$7#Gex+qCQ3t;gx9vCo>Nn8|)t z3fDJ8iTt_$zAq^>Dw){#;{MLo6TfFHcgFpGe(vXAyV<#x#z5SWS1RdVaR__6Gva}( zC5OuFH&TDBvbme#_m%tcMBB7o z_L(9_TOK5b1#bTMY0##Am>~5-8J|93xz#ZF^UqAsNn+gRr$BKAlA&BV2qIU_Ih^hE z0U*3B9Q^>7gmzezgun=Cb|p|QgS-iRaM-2L31r2uiTxvk`u#jz6jw0}s(4VU5MJL- z{*E|3H*$&toTLS$CW)0&YC{8MEBre`(+R9Rx4QCpa5?#Ckicx0W2r?ptQaU(Ex{_Q#7I?A07*J;8ii37y z>gaYu4kSRf4hN;2nl7JsRF5pa2eAh&B{Ku}yPjWl(a9p|8C8-oo$;9FfX>WOze)l8 z^6RHS=gY2VAzhmJDYNy>dOJWdIwfW!U>SvszCF-DK;H0o=b>m%GN!AeziZ36g(y@O zfDBQ$M7}QVF&tE_gpyFb13fY7vVTV`=^6er1GvuybPqxPp1bSpChn@Qurm&(U&%}G zlxMV6Il}>{V=BUrsu0fVZnDT1jKISaArFD*x2Hg6O0bM9QV9hK`dtmj72^BVB~qpS zP+C144ws+hA?N82;{=nU;=Z{k+>k{>?$42@OR0#`7r6<;k(4ntPk|vSV15B$9kj61 zS!PO84RZoVQ-U398q*Ew?{LOEOW~yUgQs^#dzT@t1;8fFWO8fjl)NR3GaA|Z(J^Jf zd+RZ!3~_<;sv^96?3c>{DSXt!)V0g}CY(3P+K)h*g2pSVL7I3P+QEt8#7q;-8f=vJhSRf&!(1DY*> zlTsk|^IFO6WhSme)8RTdjh3K96gd*Dld27T&j?brFPM`3x~v`jxePci0LCnQ{*G1u z2K_Kqqq(JB=5`#@%1E~Jt}S6gK5Jb!6*(9R7-Vz-=AhzhQOYNSgr~A2Nk!60+p#hV z#QOZY%?cg4>0eorMi3=>CEFwUGw|IBiXuGrp8^P6RnUlC{1s!|l#G57RA(`9gfv9I zLg9;R421UANXiVckno+KH6f(I;3E9k%JsoczenTdllmwiT#nUa`_qNPGe$_<-;mx~B};M?4jOVEGf5iZfq(=y*czcE z+w=zAQjByF$eWBALlg3d2WMl6a2>S%SYDOkEE>HS9vy3Dq~SWgCIi1)6zNkR6~G7< zK1gqBA2_lZ$e9_3?;0J*z*YSsB#LSRc`CkBM6b7xC)yf>S81f##H#(tQ%_ZK7UQld zNbN`&J*faQlcMQY6yDV<_4df8JyT&)QweZ<2k|^dcM~*cM7SqkSP2-x zI`u>lNdIRv!Ot{DK_gZvlS2;V9moDWV!&4+A_t9)?AI>e&RKW|QRa%KSuy1~F-2Mu zJ@^E^N%9*l=@$&^7Q?jKuR+q)6T)`B#`JqRRSr?ZUl!dKt0^5IfrHEh?ZC|( zkJWd6#C*?UnDAT|t;ocmn8tH?D(KQGK|)i5ej6~;SO7@Kr9ka$y#<2b0ND`-u%eFj5agsHgD66=MtfOuPq) z+X33m?v1*W%?#hP3NX7TgL^w@zk}Eaa*sTr8Fgs zlQ*=TWeD?<2R>1AtkiffUKlwu*}x+Yd`h|#+P3Q~dPm_RtlJL{zdWaA^2O5t&;kIS zuC8W{{-5dI{MzkOnSV`98zr>&^Her6E&Y@JUTu6=Oe>w9i%Y`~`J!*@iPcWcy0W%S zd-(<-$}>;fUX^!B?03IF^NC9Iyx4~gq-(s|AGju+&(-vjaVA0f3m_+!7r<{{(t z{-_%2^u%#Y?Vwq>rd{`7N)1I}_+&cmpi^OQ_Op9){kyW3gPX+{q@v1f#$Oz6zl!NiJKVhk3#iCHXKQ&II(G1F6Vr&EcSr;<^p zQg2SBKb+pLJC*4>m7PA7+d7rMIDJ5Lra*J1$bF_Hd8Vv>reb=g>U1_b`n@GJRQ=i6 z2P7`VBAECUSlbD#V+z)l1oQfZYS5e;aGx7Wo*Sv3Bi^#pykU2>@hvd(El2v6q@Nqt zom=#sTTY)_ZJk?RoTs&O_6NjB%tTUY@)fcYcom7@7=cxf4(%$zk1&xoH@-6~RTk!8 z8HI=o#ESyYkH%N;KU9U;k(rfO;d$#5xmLay^(%DFC@k520o~y*fkz3Y|L{$SD+qlF zTdn%ALg>)=GKd8-K+ju(d|3#*_)zuI6&>}<5qzV)7J|@!iMSyNCF2R3jxj0+o8`v% zrufCsK!W@HN{|sgm*BV$F(;$jOpKtEGjcm$nf`9 z2_XfFtk=R~*O9;rPt2cq?9a`<_AMu5ZDr)e=+U>k1Tvms#7_eD-apuXjI3QI^sgs+ zj{XrzOW;*i;kEthgvEOH!)q${tE)D1&C{e1z`x<^mj7dX{pZL2)y2`(#rLa=!>hj` z_Mh|ZtJAHE^TVJ20pYg4n0Kw+j2eL+th8!|lcW z&H3H+*^AYl{~L%svN7MkGC#IFJG?kIv^X;|u{b}nurM?~_jPt|U}k1*y8HjxVlR!h z{s)Ua{2wfK-{{EhK+V5e?7{x_zTWnMuIBEJrtX%{b7e6tqvH+3qn`({HD5=n2Zk&A zhsyf~OM1WFD(uqEp8rZ=SJYIOmw&4GFBEoVV|i&&NpWG(hy22P%q_vr%f%!YmcGl% z%E)+|p8h5+E$tRx$GyqBMcJ=Q>H>>uU;ZVpKYHg@d*)Oi`0IdMeC;3P`y$}E?~7;N zFFbDLwWrTt@;Wj9R$lAHzPm8+>BGo-g)lG|(8xABM-sx;BJEK;{y{(Q-|)3Kk+^L1L-yPXSY{}b z*1zFv9Z;otne{56_d^-2{W-*DVGF_5NyTzo2p%!Bwx4ZlgLfdC2}8*Wd(C6wUVn@F zj~idpMW24={bcLp-EuVhlt_0{`O)@1FLl7z70eXwe1x*V{Lp2DKk#5NJH7<+D0~6$B<>cWK|?)Hr_Nm98kyRJeJtq&J!C_fip#5+K)v>Q|t@5GqkbyZYZJhlVbPL|(FX~o`>R18Akj5rAcivI0!!D@0EV@;S zY2S#i2S*Ftj3-UvnMl@SU_eLx-Gz_%y4>YZJH(pSNKcS$y{cPmdST-OG+4XJVcC2h zTdB)N=W%y_bN#fg#fLbl3U{MVND)pWRx@O58q8EiFv*9GWQj7qr<=t`S%P45sfP|b zm|ODHN*KHw%hKUj`KnxF?tZbDu`#|EX~}!TXf}%95t9xo$NDer=<{oJ=BCeT6n@z}exa<%a^`#2@rt@RKrt!Dp5wvk^M3Wl zX>@A!cLX%$i>gXZVmwKx9bV#8sDvc!Ii=@QIe&;^XHHvW3J&$RkSKZZ_Pt0TuY-P_4@lk?ngl1D1yH}^imo==2^5hjxQ=2Cauxqlq}a!>yc2HwMG zejI}f>S6W#EOoo*C)S1}k9KmJlSZ81(@r~&ei~l8@G~LS4VA~ZHNz!I%}Gt0pT~UB zufEUog#KbLkCo^je2vu3XQvtHSG#|bh(`T|uLm^EPmm5D6{e{|ET`Q|36lFU5l=gHT_Zh=;4_1>X!m@bQY*ePML>AnuIh<=`x!X5cyC?yy2 zwrWS3I}(Z86Tl=|Y&6(0oHF;6phgDSzmk&|#(KuelFGt1h)7T%&lkemp_2UuAWiZy zmM+YRZ?MlH@?Pf%=9BC9kjQB9D(a0h+Kp4C8OxC24Q0G^R>$SO2Q2-8Tgt@-Wb0N; z^2~=A*K03!Qq~r4aOto*iRnmCdli(g`LNZypyUUkA1u<{IpP#uBIpxG!?8-pmUI?p z_$bgPNVo(Hijt${L$9OqV81ws1Sv-u7+}TpaXnwH^`2B(?}RbFb4NNUWf#L{$WdZm85d)(xWrVy}Pae8ofBiPzh$vYr6Q_bFCC1h6#88prhnn1ML zKg;Avj{C(r%F1uu{~UkqJSg`YZK6;=WK_WEtt>P|3IAq5lQ2OsX2CI3 zYL>MrXIzBkG_i7@mhD#r@+)|n1HjFxgfIUM(Ki=MDMCNwcPB$h?DxujBm3LsfuMrp z$!5}~LYk|djk6byqz8968^~r;<@TkNqI@goB~q%vpPM^L8~cArY#nCy(|)7Od;eee6Is`OulKYE|XHHWv%1 zZ7c_6EQY{A{t2le4=&Y;`-Xr*N`lWqquCKN(g!#QJ#G(M61y3W1P8*zAMJ~=tOL)# zk>HX}Qj&flqVsBD$OS*23Ckws-%G*9pzk5SE#n!4OP`FAvKXmsJGs{@lGvKmk#fHJ zp+H2@^41{=6SQSh_vEGG$$3>KQ%s&2e(6xqkI#<{PP-;%eBid?J>WreIG;-aTDmV)cQBR z)>8SsA#=k$^is1NwPzKSo~Hwv=@6U|A@l10{WB~<{>IRTox;1yU8-$&5P#5?RPG&u z`j3L-CB@zAtbJYi<2<1uB5&da)GAB(Br!CE^tt5gSJOc|o@!JM6jod0EZopqQ)`DK zGD}t{NP$#W5{eur{-F=y5r!5zhRATgqPQmw1&}w1LVSIRhiaiP1=86gJZ=o|65!}L zO3b1NS;GK-a)?5c1YKG++% zkdW!)LVl7^>&MCZQ&<&KcuGSlLP&cEaYEt5&JFPkXh?c`8u<840g(!>NNS33Tn84d zj(KB2$I@azwqpi$!ahVIfIEP@#1j!GisTli6eZXNKyWS$`&zDchw*3QzK`p{@hFEk5 zD>{8Lhy^HVQ4lk$Px%WYHa1J#JT16`jeXXO0j^@;KQmeYxZ5l8{4a#3PJ%HnaT;i? zb~K(D8bj}Xu~X@X&NcA0V6&*xqa%M}-qxpwUV;zW)6cyh(X%ndoH&RO2D*60;p4oS zO+ql64pB6pM7}J(1BBZ}Vb7xI371Ge@@WQDR78PFWwwQ4_j`CcOtE4R$HQc}_T5TqF`n zHttCoR+Ym817AYZ@I@Gj*KqHW1R!D4L|I+(FHcc$R(+kG_B59n0*c(GgAf+1Ag1aLITGp+y%Z=yiq z-2j27nxU*vbk!%;x1g}~j|#+^4s*m!?doN$&|dwTeEf13Ux;4}=MGw?ynHjvy9LLn%?u_;Js1%v^B-wW4eui(0!5ffCC5FdR` zqpb6lse66}dbwBENCU`*)`!Z}XRmy=<0QiEAcpfpt)JGT*KuPr8=lA3J)HoxgnUZV z(s0H!yp1Jv!T+4108N56CWaHnls3G#X|zkJ#Z#}{uMgj=ckUpZ5+NaAYaZ5WzKuJCm*T#>!70he`9y$d z`rOnKOIa88v~DGndM*~{rn+(a3XbDRIOW;qUP|3+!_IuaZ9E?|i}R^Pp$5<3^YuLZ z>k*9*ar>mm=ezvSde8O=P7-xA6O6wjF~8;IYQt1wBhagsHVAIHM`NSa@V29ajZuR! zsMQhCguB|2!PdabsDWstW|f8VxY6l6g-XhHh2wwb`b{IZ-?ePq>b3#Iw}Db2R2T?=aQt|wfq+bXe{aJBP|NUx%HZ`VW} zE;$f5+U7CnPl|%RwCroOZ-V`1!Igyq=81#L`h3)hzj0??%WuWmJ6j*0z~Y<(>&U+~ykd&|^{wW;kEI&epO zaS>IcD6L?|egfOx5S*d;W`9fK22jr6w;)xHAnNy)&<0Cd4^e2@yJ3@>&JeGGX~nN+ zBx*HU)P}6ky&!15C9Pc5$a68Q!{`7o2OEYnOsFH8&q_@o1KW0^vf1k)^s2!pp?xUO zMK&aDciS-$enFAgXCg8JQXF_~+f@5|)GmL-2GL7&3yE*EY5(kxxlD}OtzxB^w7zgb z%>XdjKa}GrXo~>ta1az{alC;rLPwP~jUDfM z?MBrV1f2?O0z4TD|08=lI^7{aOUl$A_IqYjbmpNK2_Scz#H%Mg_(g2Xq%7kcS^m)L zj@eY$Od*q^4vH#maqjEcNHQ_?q#JaRk@oW4n3F-zjKI8j-YgMf>{a3nSY)Y}2XLi-$}iD{@ozHA6Ek=r!?cN-bIV&ic35;zoGO@v?m8M4-wPa zOY7F&8+Vev!4Xw!@0QI-sgw^Xm^_&1vY~5Cn}I3o5QB043TpG=DHpFVuJV+TI#hN` z#QwTeF7eP|DJ{!nUJjJI!^t zt=lo!7DpKyJPX0uN%#6@pty{?y7Eql69160ycKH6OuG?GB_srOXx+WaAS_LHh}GZ_B+`Fk4QsYuTeSMl zns^`uJ0d#%?ufIfpx89d3=58Ln%X-o(mvv4>-suO0elb5h^HoGfnnySe1u@^@pA#z zP&todRdtI!0*_5|peLo%MLE?cU;&ZuzL9+$vH{KLDj1h zs|518C5oJD7LfU?R#IbYr6gk`ZVCkwMBf08b=v&K%@U{yA zuLIqj3*yAfx3=e$Oyr#h*l&lIFx#I_Y(D^opWB9x$X72~+UwrE-}t2k6MYZWO@LOm zK@H!pro8_}Fxt$KK-n&|AEOJ)zFj}&K{4IZ)78BFxvkEiqYw9FhXk=k($PM+yiFpq z{`mE8QpAr3IKNgI$qR43L+76TQA|9Rvi(h#xNm=aMGD*Mcnz(64_&&h{6cz7e!QTY zII#Ab{VW@5XYmJbb@ul31{l>^Q3%DQ`OWt?zJ@T#htnF|;%h2F>+W=eZ))-X;OqQu zZ4RCL-CR{e8fi4Jd(BwGP3;VE_oeQ)Mq9esa=e-+yj3%57)7=cSkcpOA2G^ohnjx+ z7}mUp<<>nJf8lG>NB#>FsTi)bcZKqly<@z0s@)e`BN$98EIvx(fly*Jb~ACj3{Pw{ zVa3*e^GCvHC&`W_R!T&ms)~vrjQjh_11O)JtYLP9E9;%i}x#B8*-m-OqM_H(-qFFzkO(e zMwmqe)#v={4mXQx>@xCc3ZkM|9$(waEe7^fOSZB3#y@^NUdYMzSctwd7a((@_ke)L zzAEn*{z*j#A_hFbTOlxrY_Ybchj(QRCJU>;)Wvui)>tW>GoX_e-x`x7p6IgOkjh3& z%->s!P+@vGkw|@5-zgxTY4b^_E?#(k{|_A|QGQeLVr!zk8$p zBt%b@rY9z2449$XQ?Z{i09Om7bITpFPwubO7Qeq~XrR8~f(~Wg2WuHBTO7aN$V2DGOI-Sa*%S7Uo_`psjPdweX_q{IHl@+K0DTj zowh*YSn?i_EjosMhEo|dj?d9ApZn83N5d*-4Q)=n?GQ=Q(Z&9uwSM3&^NmW9GRF44 z{C?7>$j!#5=#xw2lUNaJ_$JCcQ^US;+Og>%+L&#g!^`Gak~7Kuo*AdE3!mm*7f)>e zCaTq^>4^J)OFdPenyetv?N~aW=8@X&Y~dFN_UZg%sraX&oi6vjTXm^NNlpiKEB=^7UH3qSj~;eiZOs5&~L;cTKx+w_YLuZ=$;rC*-3cdkcdLmnD3{ z(E&S;%vE|^ynVI4B?mme6j5GnALCPbzAVoV#kBmFRKI} zaIE(35CD4C8sA>(+!@XT{Yabl$>W`#g+17 zBnH{&I8O2qST9AefHuu}sB9FnlA}7=PHE7um#4%lMm)%l5f7B;+RyF*R?5|mc_M%Y zlF9hvfwriN(TeibXwV}&29}dvXCCil$Z9+jf)fqPz!%Ms9q{{|4kKiDOv7zh;B_C< z5YseZ&GiBD>J)#qMu)LRAY(5m?FtfX#zaH3`)Q)3DXejCR+0%oTvQbPJuZb6Ql6_E z&g}%`gTi-(>JiAtgDx;RT_e`X<~xcXqx<Pbi)WmWh>)8vHji$zFYV?ENU(q zhmo~c2_F~=BwP&x-4Sg{5y6%LK^hk$v}<_2f}pmV zRk9K)giM5HDB7@k+dzrAhC?r+#9HY*(_uxILrKm^lLn+$>5X4z>wwh?ODc;MUa^d6 zU{FSz5B%^pNu)Fd8# z=u==}wfE#lb9D4Ja;-Fd#FxkYI}_4PFOlea=?DE`&$A~f{N!E^+G1_bfw-x~Fy{(! zQm-PwQ;Vy)hsN%=ANNdzV>1Q4KY39o4@@ z`ScbhwRmmGb{&5RB8=0RZB91PjgsUQLMBQ-X~MuLuqVdel5VI~?mgO3`D0PFk{7AN zCMshA1Eorue_V85G+;B9s^A2;4kq)Q>MbE>YR<~*S!IoEkJNZoJ~zQOcTdLf{W;3S zWexSF&AG30o~j3xC$9?G&xEtxRg|J~7r{B7!Smy{iMfaE{aIHn*BYmpdH&SkuHI`@59dcoxVg*dZEYyA~DOuk#l+Oc$Q!fXd zLWf~6OOfwWKNZZkmF|8r=oMe8N}?>Q2PN%;<$C!7eZFj9C0xOOUxzvkg}FYmr!Y1)8x9e73=3#rs9n zzLYEVTA#G?vchkHZB-I=X(XH>C7!`oboI3@O96xWgsj^GVL6b+&msML1S40-$I_Le z_W=xDZTN%H+fBgfCa?_y@=^=+YQ8N#U7jY8ovcbk>_{OSlfMgBM8H0dn6=?{H;aZM zXi$pIJFOAej&A+dw2gMQnb#E3*WG8D`j4`#(Gi!)}yKLNyS7J*R_-xv=9I9B7Nw@rL2A-WYJJ-M7NhWz9dO4c zG;LP+*>AN^7749u;2Wvx(3$QosXp!?cFq;GmqF?kRqZ7+@}cO$h}p350Cu4TVWHoB zXdZZ6e_!^tr1WppjZ95+*g_e1Xb0q5UnD*#HVBCr1h04YVx@W$;UJW~K-{|8_$gd{ zfgUB?U4rRfUXhN#bfNTxQYi)SX2Rs!%OIH{ER1+m)kM#2!ZXn-Q9NCr`!%qDj(29D z>~5tqkS2sUghd743>jw4gCA%{_ZHnw=&w2A{N*j?OI1>fIisq43hi5@Ci0RF?D-{1 zA=4r`fg>fl#$N5Lx-Mx?Nh6vL&7+m$8QX0H+>TDjECZRWe8rw>Sp;byZ0OPHYO!$D zI!sAqy2g@CdvbbsUq0{bH#O&dB||^pr|NrkQhi7t$OC+k1XL%Uyv03bP{J+B7#r() z20FRlbrU)eJ)1ADUiIch_mJyAH0y8Fkd4BOHi^D5a(O~}lt1E?TbD&UXv-3)wErN| zPkB_o;p|jlRGGlTzJH($+y+&djlO&QTXD2B4U&m_MhQZ5av(Gw?6}>>6AoLO5Pp-d z7f<`OYA&llMV@;O4mk}08~|&iwWjq)B6-x8^=S_l6anpR5E%fWTykK|K*TmGVDJI= z7i{1+tSBr!LVxh`av0X5@6_E&(SoF_0g|K;hn-?e`H&giEx4?B`vGcni@@!#z{75^ zmL~9bN&=CN0stz902;ClA%|sYBdSKa&3Yw##@v0>##0PqpaYRBI(!D8pFG+r&kb(^ zz0_X+9*gxHvc`0mN{wT;RkeK#CoIP$9E4+63`+fatkcKq^%Dkbj0k!3oMiRnvVa>t z$fOA{$3aBP8iY^o0rzczMax)~De(lGz*uffh$iIeA(WUf&aAKBG6Q;@k(~M&Ej%~8 z7^|A+e<*6JO|K19muoSln*5eInTG9g`a*hQFv(;OFpC?tc1J#lLnbdocWNO`xKKm= z5howVafMCnQ;{LzNRdgfha5_6FXHhZMQ(OUw&_7b8ZA(E9%Uyj>WGj`a~mV9 z0R*A#k$N^p#Sv5d1Rq1&=Q^uk2phA(u#U>qnZhAJajjvrnMKzTLkJ{}Jjr;S0ibte zUUhDs^YGDT3Q(^l#ykhg6bR>yX&Fc@5)lBA`zQ`tVlEF*ueZQqb zJb+%&5&}Tbuk*Mo2ze>^?vNeWGAIvVwfvoBLkB~i`@FI4H(b`w4xW?-T+S0+%;1jm^{!PL6_qlqw zsMkV~Z3hIoU*E00v{Z<)c`Ti~C{Q@^hly#2z|Qh^^X@&(m3yz$iJ7y8W^Bbt?>jId z2MKZsq4*M!b|qckWH-Ob9dq;@d{Y=s9%4kcQmreit*hKoRb~d_H!7({+Jit+BJt~* zCZy*fTnn}9IzQrE^3-(+Hwa-%`ga_rg%=FfHjGU+qB&L`zSu|%22#G-c;rE>t&7BY z{>XgFp@H=t`_jhaLlYb7P3#N_gn84h0_X>gC0E}Nw%KfL7HP2e)=Q7G=m0NjeXRd?CA&7>T5fI%Kn9pvggs{ z_nriMIC|?+Ac|ro37z$+o!^@QXyvyfH-S^LmN!vp+iCspSr z-p#qQn=7%Kr?#7KvRmM|Tlix4L*#Bz+HP^-Zpr7}(%#*&sonC;T^-%o(o5G;;L|+X zz3igU3bnl&lf7EUz0WW9>LT~*)Akw)_ZmO%HTCW_|3F&KQt=E&OZ5{X0GSw80-S*S zY<+yYT>>v!x6*XR!_lY9SZa^sG)#Y(v2bdyM2tv(qz@1M`<1&0DdW<9JiE~S{!PfM z;>;54K2tPfnUwnkDWsYW*>xB_#SBxbPrbRlRhvmWz`~gdY~9O%ZcLBDDRu~!uMb9m z9_e%*rAUIRQg93#-eOry0|juy+M^qDfT(iMZgDWeFWJ$BE2{wBRb~hJ%qB%`DTNzb&@h;Scr6UOGib$t>eTRr#F#E>eyKDNBQd=@H!1_fh=-Toemecy_Gl1XOuH#dA;hSC98r_6~P;_P0*{1J51#pLp)bf9xbL z&9AS{uB~jZ{2z6azs%15?_loKe}=gut^XQH?jIe#Z6NRVRsVOJ+dBNEbD+QTwv*i3 z)jZJtxxJi;XA+t^%F+|^gm*`M3igK6u{YU#;n>T0a7sjsc7`B+h1 zS(;PdP*Gl-THlfMxjnw7HSSYO?8oM)%7)Og`qGjQB}D~Ag}DWPcaq<~&q{xnecML< zCye~M3B75ajdSEL5wz=hwf7{&0Z;IwaXl7p$CZ{AfhT12f(f_F2=;)Y#s>o51 zp|>#CI;GG&x!`q3Xi#uSVDM|dzkA5fU-)}^KmYd_vT0JmKRx7Im8%{5UL!hN4H~}w3@Xo`~Ont zj@mRh{mMoJsutz;B@pb%HBABYHKL1K8yJ9xbE0zGcK=fznW)h?o!faxS&b_aUJJDx z`yWEr%;Chv>|UvgiZ#dmo@nl}*-y^nC01WeTxUZMb87=O-EF2nSM+}7;vuEyZxpxy zGyjuE=2~ldD#`Tia~4?0JhR9KdG9sFzvYqd+e!%h(za|2{IPw{cc#R0w@+dKhH`kM zConrQ<G?Uz$&mVGif1UCipGzt10Ebj0`|o~Wd-DA!YUTRyy`^u0@Rk%6`vf3w%KHwalWIjBcM+uezis7~~6%$+rF9{P*!7qr*@1fy%{yh5kl??ES z#V(*{`HCxpst+?pQ>68!rN(%+-ual+E{mQ@8xtzy(W`LkIf(t#js>&(e24`9`HAwz zW2;TJwo|P~$B}KkT~ZFFuYF8Q;9$P>0TUUM%#W|}Qy=(*ll_Y;UxtHgX#(O#TK_e8 zv3Oflp|^Wm;mYAm+q4P1zWtosDh8czHt>aCF+XN^{}c9=&j$>#c&>obTe@{?L*zY` zc?DzkZXKOm%csz1cyw2&m^EOy)hBL)EA9Gnc{_W>2u-!|I=l`k{i;zyfunYO18`y* zNk^!DwxR<+_A_hk9`qw5Vie@ZEPnN-o6<`FT}(i+ex%iMkiy@=^MO&Y2RLdzTCd`Y- z;D8oIPiW@EMOG!J{b80@o#4;)Z-S0k_IOZA?KJn>K%-VdrZ3oXqGK;drPo$?^{<8Q ziM?#O?=OU%rx4K=IT+dhQ1>C_;xN!6_yNWASQN*SMe7$;UW@H4DctL9jn2mldt(P2Bzf|n zR1u{mEj=qvnj#zNbHKW$Z=)Da*g-#s6`-31MyFFTCS`F_ttsRz-1v~=&Qlh7kkR4s zx37{0dk#=KZnNS|PYUfJx~L!myR;tq1;5QBC&gO_s3k01<|zLqbWpu+GX5Lw0H@1dTh}C(yi#7s( zF?Pv)VT<`<`7Ky4r%0XfC&_=K?7rjKe*C@v6A?iq?;tjfS=6R#wxU)QHA{`6sI68@ zQ57@xtg2Piti9E!SwihSYZTQQjZvet`T3mhIp5#8uG{rHx9j(xzvJeX$ou)Yzfw8C z`Ap=ROw%3+6Co~SnY;Q#aSinL>15tnN{*qSDU$BRy(?9>p;|V-lb?!B39c9O7|hzY zg`{9mdnUA)gk-pX8a|BLgPgO+Bit_~4Z`z-^u{_z`wB{@c!i0AD6Z z3sb`n6bS_jMA{BqXTZEK;0-M<-v-Mb>0!c&0o)A76BM#aR1n1Vt|H3k9?$MQqj`sn(u(OR?78}YH+{F5wm|8rW>*6k4B`QE;5GF0%zS2|ujgIpHQ z1-IYZtR=d}#)MVQPqg4WtUU?*9nFBMk*6xSv-?MyNy4enb&HYNN+tSfiE4q@{?s2H zjF~)Y!q#aj$TYvcZGLU_oMD|M(wPk-{d`E=oGi>r?`_m?I?j5Ud}p!m@xiB2z%1l3 zI%^%}mg&?k&rBgpq4ovizzr)l(84Ekk1+KFpV zi7CMLto500t)qxa=w>V^_?1(&yJL=hnhsN>jHOevT9Cty4(TgkIe~}MI7+T>VF}$T zqy2|dkS_aMx4ONsZq~U1bLKlrerEg@br=?Hq}f$J^v?`$JluNYQL=Pqa;J`+xnc)1 zch4+%-yv=OYEAf#@ohyueEfM?0>iwMk^ch&+f@(BB)+mY4IE)=+nd z8RDk}$2SQ=WjjhAhi=_&*B+bZ`?C#+Z_>r^p zN!!lhX{2g`FIV;3wmoNj$t!!8laBuz9{KHK@SM-f^A$up@wD&W--C?*D;_xr1f^eA zS62`Vy5y0mnu5-ZgJ7pYH#~y$^*}?O{w^r$%d0f+6G%jl5ge!3SrY8@RjeK|_%f?q zwUS}kp!!*bWjlpkBY{XjA)y2W3t#Z4dhormEA<-!KnHenB^Z=QqQVd48@k2e~Y69(C*@f}4vr9ta?!)yCOBTt+>z_gZj0H+3U^=r7HOsGm4)iDtbqN(P{ zJ%$}^MyNw@1=#1b)^I4PXha$hBp2td5eg*0M|DFfIQ7V}N~!!FX*fE^N5CkFgbP!Y z>S?$tf7s*Nsxd#n7^Dh-EtXHRcz8*LyH6?FusTZz5`i6Q5V>7F$Xl3`e0 zd33!q1iUKH$R9eQ6iP>c=YwJ&bH(Q0kB#jM4VczfL1rx1_QmEf_H#UB_K{LT#Q)4JT9I*qDyXx_UC<* z>|709Twzmigg)`0BEwSFGNhn8BX1#@k5_0UQYglP;J--VITNJ$LFO$eQYmEkz&As( z&SWDc7Ka1~D3@A0l1_JyE-MHTO<<>7rK!%Luu-BqC!qou5s_k$tQ-UtAKjy~0Qu|k zBVw?!Zz)&yQ!&=?j9O64EY&^<=?Dqwua4KCeJWvl+OYnBLMhA$ni8~64Z?uKdPA*9 zI3C>L8r6d=cQILEl}*;t{&3QUKxrG3sNx)>BMAsRlGL;RT9)j!PX@I4VppsWDXnN} zObTBpI7*FFk%K%aLDm!{a{^gb5E~^n6A(M&ScDyMjLL5GVZH3NQ-H=NheA)44qA7g z0ux#t1eduFe@Gy;Bfur^z+Xlx1c*VNuh5W>v)ircz3mSedqdGR>WAs4()YZ!k;B)y zmIc~RUFeW>@S=T7xEcJKx1RBzm0+4w2h5#$uL8`So!dve0FP|!40LXGjM31U@_i=JJLnWaQ zIsyzyxOC55Ksi-ghr`0t*UZzNa1?4{N9W`)jT5tDZ4#sNKzBD{7bISrM@I-+xj(5 z7|NNFN)9AQBoUF@Ut>-5NFLY-l5RnJR@IU-zZ(gnzF8UAV2CNDQZw+rOh=hr@20hoMY6&QoSP$3BwYmRM$q*o z*Y2i8lSXdCXbH^;brhi76f$g9BkSD)d03=8*~fDYle_78zhMcwt-aA7niHB-s#@dL zYeoPl7~3#@u312griyHV%=&9|E!2{A)-5k+7MM{+-lf=Z)~IuC*_LmMiEbJOp!;ST z9lF2|v-X|OO)nCf5_OwhbJP0dI6mtFU#L4OdYar4n$m+lxbC;ZXxm0epzy(uW(iG= zBrT4esbZ!a=I5{%Xh5{Nv(m83xijS(rd`nGZniU%$PV)sYg7F-pbqFhqKA2W?#k?J z8wsi%0U8rOcbC|9x^lLzW77Ft0L_@5w<;}R84RZKNnEh*jLsfNb%%b8rgF9MNt>X&d z2rvUoi7@;d`rgN@y_?9!h(UY_xUMdP!6l#zgsnB*X13Al&Ai*6P5wXnlSS?s2N_23PmJ%}oVk28#zjCxVNeI+MVw zpCiTJQE>L-6?C?ofq?*ye1)L^sn3r4eX8bwi22Yr@$UHm4P~~^{@B{bgUm0?hZ9pi zhvoL`WHKpj50P7c-V4y^%S3rNk3d%OIr{@=E*fgB44w*IBVzp#oOo)FA+ja)T^H2I z=RpeW2u^$id}+YCYP-PtzpnN?R{-WekFqLicf&qr6SGh^G-qOoWitQl4(1%bm8DL?&cN^oCa{Bkn>p!i+c-ipVnSN{ z+8h|U+mnusOck1Xnm_y)`|-LtU^~P-XP$1wF8o%E;m-BTnJ?^SEXpK$m~3@4!WvI) z4RaP2vm!ADsy{nePw5Ua>n+W=)|Nx7NA4#!Mqe-oYfVvLU^qqfaW)14VIW|M`I#ax zYCbmxnpLDkI%Y9|UW~yK8*k9edk0qy8%2UUVb(~~H^P9BE7RM61qkV2^U!?xE?|_v z)YA$WYLAB|Hu@@F{xJJdk-JQ{mQHU$4>?DL?Nb>79xW|;Nie>E(k2pF8%;W=C^1W$ z$QiHlr8cs`?p>5dED)i{5ghxaoo@IcwwFq8G%|6#S7`a5d*}gX4ly?A;xPxstX%w& z&l*zy89Pp~Cm&qa_7F2cM!FKASD&=B;w?3K-(#F|bp)5V5`vsz;$X1LK)oLXVuYFQ zwE+bdC?(c$?rhXsSJdD|D^2I3y~~6>=bCsRL$N=KB@RH}Wa`%js4qd^g*8PH!Q(dI zz=er65C~~m*S)=Jvi}uZ zZ2+dXX)NAvGW_G_7^sS4Cy4{~CEyzsW;w)T{o}B-J+M<12+^;eLv#+l`^d1o1Zdtw zeNy^%xuYH0+lhzo8YFH~S8s-pZbCS_dLN=p%6FEs>6YPpndm)zk9lg3=}nI<1HJm! z30>(Id-9|^2g8)zBB(t#py3O{_#YT{;fo=rC%tuzB%ZE9_L3RfkEdgP0c>kdR6L*An7P5 zd-R)c(7s;c?q4&exjz6ef<7#}^8VjLdA;c{I#HFaO~m+b1Y5%#Dz ziiz?iVB1bNtqqtUj^#+d>g687Iu9?^WeUumnI%xPcYGDoD*TrI9vn$0%+&ml$uwXs zpdI}ZffQ|LrY6$q>0DZWwDwo%J%0jMM42SxflqM^Z*HAQudd!pyqxy#J-`gUehX-i z0PcU0Z8|_a;`dmay39ww8-b)3IYW$%)QDcqC&JpFp!{zE9>T|P@y*wNk?L;0+bWq$ zegdyvqSzIY&GEq1*zR6oB-Rp`A%3|KM_$NQpHgE#Ckg?1Z-0?vrhdmQ<@x~;?4QT? z{vdPrgnlBO+Zk4fNXEagN>MuQKQI!`ow*LI8T3DST4 zpoh%JV9<>3U#rTK`LGX4Rq3c@ zQ1{(@r!s0hX)jp$&q8 z>hVL#OqvKJo3qTZ=RZ8M@%uYJt}HV>rC}RxYU+%BDNq4to?czChm2@OWIz1lcf3pK z+3w`)qk0q{Z4K6bm?s*RENQv3+a9KIm;c5ITty5+&baWtq%ym|B5xUFE|!(%NXpgR@f4PqZO z+W#=EA(W#zzzEJeY+U2&0!8^ricAH~LwOf0hd-60=>7RMMUn4$xW~{3KhZYtZELk} zJdigKn3QRbul_BPPRPB^PDQv8^}_|n8$8Q`Yn37{t4QgoR<4OD=jYMWzoTd8uDlcZ zo5|r*M2+9paJ&u|ehhnTUT0`<&$Wc71W)%WkB2qGn_G;Ub!#-#RBJ%j&}XCGI2y)X zcirfUJd&Fm#f9P`GXqKGK7J76I%V6{Ric8xYARf+=mXWCXY*qMRCQM_D#?EV(d+@1(jjKw-L4zyc|x=^mju(5gZnt`pdj7*Xxp~WTu#8eHxX4|F*+T7M zVM%k74p+|m7%kH&z$y19XUA_m0osHi!f*E6V!jsja<(8FBJR#Tq&a@b_eeRSN0htz zhZU>5c0h*Vx7Lr&3AIvC>9=XBlp%@SrY z&@&{a$(=`KLF1mIg(}VEv3OoJDEPJewlmUGe7e6B(r*aw^cPuQ3WGdTtlzu zMa?IzIYd8rr^?6;bV1cfIvVV9gt;#}?=Q6L?5*T(Pbfj=K0Kl9eX1g!pO8kS*ssjP zuULm65+761Pi0GKHdVUpm*Qj^3TqUhuCCN1i{sBYE}GQ*u8$**8yee)RuqQskW1JE zvLe5I5p@nJ%|r!UHOm7eBX_c8-eW4Bx9qOuf?{7N_?tj`ITV<*M5MjpY!}0xdO)sU zZ3umycvh^_G5SDa@hOj&t^YN)m4t--hS`Q496^aMCXsqZrdyBZyJRLmuVLQ$6Rta4 zF5`YcqZ3$?H=I}=Z3eTUG-&E&ns(Q&R8J6CChuW?kbgPWqlIRXCBTsp@|ofzqr!bh2L1ReYGDv<#Mbbr01qb zJxTb=I%yVzv&gHdr3w@E`Gl))VrA935^BfI>8?#qLn6t@GIa00w^FwUa9imyo?YD5 zIkY)bK$$0~O0~cEuB$^d+H^>dp&0Y>Tbc-BV*tH6`cfcILg{w6Bj9nj)?*22L6<&* z+JE|bBtaT!>8)DefFQr!3Fw^f^u39+3Ry|!73&O{z zWQfCi%G8NGG{!8WL7#%Z{3>yU?F9Aec`O|x_4Ul@8$zYIUOk4x&OhztZZ%&?Bl)0K zGvprEt~$>lFx;=#C2;F5k5ZIk!l%PC7%A)YS9WGub=7LG?2~|Rv8z5BkFw~&UIntJ zlc(ySqYZKH)+;jcH~R0wU!&uDmboZ-Rb_gXr^UVtzJ=FKfD>7HgWd(zXH z3vU7QCvtD*_PyiQ7k4~L{4_xMPx9AkHW?B>*nE6nmU?7T!*QazMydZb#36)bA|YHl z1q-w+{}IL@DD|tI>G!0JI1}xL+YYCa^6xc}6sarzm>@+2^LPKMjA+~bphq)rV8h(l z_hRqqJz_k+=}i&$_B%T1`bB=0wi@5{8W^kh{6p7Qe|-oFJSsr^@i2VJHevM_lBk8G zmH#FbppJJxSX|nn>p81<8~EGH`j3akyNkF7W0$6gPkxnM0n$3xORK~)j$m15D|Sl( z=pg0kP|i`DKMXwyiCLdWynMG@F~FHEKw-h968s^d8f`H1wvbW9rEQ243C3wQ9M03Z z@KurAJZgY8^0j~T{)F6)M*IaxJ|3ST8!gX!x9KW3&J~Jr+6oUXR-iYeqMU>d`A0AF zOGH2wrgLru11SYHrH)>Wk`tX+_f{ZNVIW$LQ;TZfi<0OSiT{oon}AZR7Yj($3kHM} z9if;VvM%9u>Pc~T}84D|HX_G$I>B^Gxk;IDny>LETbk1245 zzGRE+48ArmC-Y%D;t|mAJK1Yr+yk_#7^_@23Bbp7Xe98rmHIMWLDD-aK%Fn3=657Q zYa8we^&5dZ?;G}qIp0YszMja`T#&<17>(mIhclY0t&}4HDmQ#;s0CU7Zq~W(;&FRhKu~O6MF0RoHgf)&u9WRcWJ8$7o4l&gB(G|$iN=kT(E=+aTpA6(H_e41!fmxL0e{6H zvl*dCvd%V^UwnsUCt4Hp=DTV9O)qFi&keF`?Fc*UPT5$2LtkW$QZvbT7@*sS!@m-U zVu&3>*o^?-4({tw)%08~IjPIuxSwY6dj>ex`tBWr%gc{24EN}GzKJeQSFbRQCc_2C z6F`H~!p)7UQW}j=&~!o_CZ=)yODUccD($F=^D)z91>L;#BU6>i$@C zp?=HE=dUW@V|H7Oa!tlx`Nk;!`V7Y0eYBK^b1uvg7u5nv?Z$WQtL|LP9oEBrGpx zQ@4y}nI@6USEK8jcO<8|s-_YxU>xpoimIjIqm$96!7Vmmo2C0sL7+5?7#TaNKt-I| zi`W&sM8L+NeQ{~hT@c7Y{FyLm&Tc_mhY3$CZqX(FP!E@kib6@s^PbO;S88ZW8&T)g-*1BnRXg?RUcaIwCXl<2mnxLTw5Ig<7QeC&r;T@2AAiERsU z__v;6xOT7Dj9412Pq-wp#S%7AZr{02+Ptv?xK`IF6`{lmb7+6;nohj0be$YRdrn{@61|u z4?Ns~VeAyAOgwQ(YtZj0xU1Sxt+_KH=!s)7g*JN057*`AX^m_PASZQ`PnDvQEN~a4 z(Ie(iCvU{k3y8RO6xAMnXLpVWn|vBnmmhRL9B0;~RQ1>basC35{^B0v^h0R!Ln zRG^aD36iAT-ZUY0A|(2ktD--4+d-XCr)w=MsqWY2$;X<0&=@jS7~PKB9NB+rjKHBG) z55*Whduklm0Dbf~kLVZ|;~Hi8ZS-!A#g?D9!@g9q{1WoWY9%7puw`j08ZZqe%(rx8 zglTNy(`IUh%0E5dOwyrhNal*reeeyRu`6lUGFbkW+&*18DmgIvE}sSX`I~~~Zw71dBOtIvcXhv4aY)7Ds(F!suUQ_(Y<=S z0%wdgxmhoqq_!PF(2l}y<27=E!f66YU-7W(Er2H9eB6!kX3a&`x+SZ+v%X z(H{DvI~=D=|Fsuqe0eB&I%m2QLIQPn0#d9$yW#EzLi1cYkg!$0sj2pkhyD_BRvy<7~wj*1Pmj|eCU;#$Y z3>_$uCn9>TIDSMYp1%K+nc{s|(GJ#XU*IKVJ&*=)i>K>P7I{K?7Vf1p3$DrXb5_^;MAed=#I{!+99lK2`7Jd)Z}}&G@E~?>{|=cSD>Z>t!4m`L%AH8MsO(TXJD? zCQ@%1aogfliq10crM$M*)Sf>Q`8e^B*&RBbvC0 zX=l3>#5ft2Pz3QH9=CRbc(mMvHSzxCLu7mT^W-)0tcdu#k$8T2FKveS=Ns|w36V&F zvj2rflEC}$nk(@AVtu)#^w6~ z?_ipQ{dk$VMOoX^3|_rt5BIm!{V!cIs0HB_J?$4%X`nIu^yLJe%c94;Kl}0NAB0s3HttW z6_+mbySM)3mN6DP!3i3t;KUi*oeuhue?%#Bp3Hi$MsPOsPlbaD)@Z_SAT{Wi$Ufbe z;93ktCxnPn^&7^F44T+z(|rLy)ZPZ@*Aw(Ou0M*DjAcqrlCyK9Bg*RgJxB?qzuBGl zN~&7&q^KBoZ&JPvT;32FtDo!M~){bj^OsWdpIp2V#)!4)V{sag>+ptUihxs0frAz zSH^UGMj???WP68c5YjI+8v8}2RdQ@yGjnugfJ&-Yag-#@>oz#OXh1TS;l*`pMaC5G zvPXaeLUuxA@{Zp~kO6esaRE}Jd|vXW!J)QG@x%IbmzOq{hE^9R zHWvE-yAeLMG=FJ?56)i#;d84qpH^pjre=nhr@NOYJHJeJeVOc>n;Pt$n)>er!oq0l z+(_Hyz54$iA@u)8gs_GGZxO=hu7UrG5PCbB{uLq2RHU^0M}$y6I9f9>T-E;{K=`N6 z&22R$o!yr}cwT#N_Q(Is4;t$$FY|+%s&7rk6fSD|wh&yohC<^P#wG4^onoTZ13{yFK{N@E{Bu5*q$bauA69S9M^Sl5dif z|L^v|!_)KM?ZLk}aP8yEa@ihSc@iDq>R|8eZfoySsdw|Ww3N+5yUX?dgm7$5{Kly>VtFDoSuDIhS@%Z#DsOHU;dD zKBy;@toTMLkG6Jcr??Hyh!Wyj}G2cWt}91_`%-9v>@}beg4HY z^8H6T^_1#IXLb)H`aD1jl=QM550yK}x@ojzb<30{A%8R#3a0Bg!*X6$KOOK{T3zl4 zp_;9K2OJ(WYO~DuUW}1+#rp2V_KE z9S*ocuFC)qp_oGby9`{0T!x!R#w$@m4R}K@I5rJWa#0!Z9_M_?wex zClK;`qSCahR9rlG?pHMBPiB>``in@Zg6PY~K^t0>(nsd}51&RRP;vd0=v5;s;sIw$ z=Kh3?_8j%3bgj)#88K#?CEv2|yn1esg^E0(&d_TEqTZr5QolwZ->3nZtiq=B`2qKx zz8A#JgKh3{2=e4B(>JSx``|7&7nq?t6k~;tB)m6t-olAITLpE~PRLo_^(!9|HGnJ0Z)9IP*eLwaJQ~&3HMmT9{Jv=lA^ym*Xhn*t`hTg*WWL&KM_J zHu4(-h-D1z!NVXJ>a@8ZYivjMnA$vU)kMD_$2C;q)&q4;L=7IhUP$*S+7>fv2X9x2 zeDFBM1_KWl#3xiIlZ!_)QY3K?_`0wSD&UwYCEyLQHtE!y+SgyMRy$w>)w6sbgU0L< z^tgDG{pL&q3UQgZtsTZWCQMNJGh(d;hc>5BZjmyKVknOntl7yHDWCBx{~1r6ReKd& zT7e=On>ikI*DRrR_RYJY%1Z}eGntSS^BCOL-nJhBIl7#h!eRT4V-Zy;D+OkLV&u**;Zs9)_(nT$aM z-ZfwBOwEW6bpK;PRo6P}56!fL}^So+RTH}o&+KTI)*2^*daNpeu_*p)tOME(9!wD?sN@Kqc}1v#23^H#S)Povry6jA37{xFS^tX`hb*0iuXEku z74*X@q+P{$of#+?Cu@lOdHxYn;JpJo-jW)`g!E`c&&p6*e!QEY7U$Xux2Bf% zn_iB4;8wC*?<62Lp>mv>&snfe=~sC7oeNksOQP)3GlzXF96#-q8Lo~i@5)L(-K>#^ z*Ca$}t#h%S;Wcz>l3ow4^U0s}>&Dfj6lrY;nw<@p4A-PKDxlDVv!Bg}Ef~7AHYGC7 z1|4*2(`N=ZrCZL3myeTbGrwtllUq0&_8qRxJ{kOW^F$V8p7n-OVda~$!6zyinV?+f z;@5l^Two_^3{`6;SXERmocWYI&9aD*$=olT4rc*MyF5ab!6G0w8VuIi?b7ZRAveWK zl|I;V%3mol1{}aQR*(qS6ilbn6jhm>qBCl`nSa)#kAtApfW&vx`)ZI$9b4N-m}J1H z9}ZMSw{_W^^pqP1cf`_?VBPq@c&$0Q*5$JI-x^~`_!|GHc2OqyDp;zKN24_TgdZ(8umkzs}^7Ntc!qoEX_Ms6^_TZ@YD6XzbYqM z(Q0p%WJYADWhi{WKBQzMr zDlbfMx%zDN)|OM_CRp@Y$;5OZAwGC3lU=9%LKIB=+3+O$u%5g1)pNqeY)fGOto*_1 z1fM?_(TW{>T|>-CwB-wenbo9i1O*=tFIZ6$9EsOFdMojwXothK_lm?e%oAE&{0N<@ zJ3u@v9ZA{0{pmsn)Bejb?=Zugi+6=^Av)d>>$Bd?R*;|vV)2Lzh_OKg%+OMz5jncR zT%*mLkvUm)z$Mq~j0T!k0!D9OzcHd_`jETEbT!t`A!8H;ITV*iLkT&8u{nsGAV~2j z!gqz1%p?fx5u}=`DIB#7ZWTzL6l6VG0`fh2Rn=Jqlu=L?DYN-i_I^@nqem=T3`jN;DjALE?N!%x2?z%<;Bt5_Zv{NQtN;kG zBNEy$0?j@ev49qRt_wc};MPH*qQ#-cYTTWJCM9L=AYUV)0dWTYYY8YsG~fLCH+)QRZXT=9f89J-N}{xKcC22La(W(jP3qlj3ss0so? z@j6h3r=lPwMe4%y2-HW9;a7ZETls;HTeecPggbnm;88__aLfU*>?4f3qN4c$T@o6-1K7GRys(4+`ziJImaU=~z|sK=#Q|)- zZdAoFPfudu9+6byQDy`LI*mj)foAL!9t}hlF+qgt;cLWE3OfL@MnX#&guq+{D669H z6hE)*!&E#@q3MhtI5lO<<+7X&d3Q?vdxh~`8kw0Gseb~3bRt|@0B|56?j(_XTS=yO zOjM10tUGJ8s|N5Ath#Lh?FRELsyS#TAVnCOx zt45JZsU62BU$RN!xEa?DU<2|Q9V28YN5NV-kEPLol!@+z$#u#VM+^R3`cN`~9BBa( zG65Vck_^j~`bx?`c$|U;o+-UEG`;DeTL3nE(=LV^ zmn<-eQXnko%ED0E;^bW;M<6AFo5h2wMuWF7@>^S7+!6opNTNThJ4zZKAO z!0Vi%V7X$#*8Ni9Jbx4nB$u=kf>=5d zTLx~|Ix)S9D(yEdlkFjs+A8VZe_uXOw(s@EDz|h}&c-K-;iVu`Q+oL?x_qn7g7*Dl zFF^oHRk7DyY>zBlXJNX0h)b56Uz<}Q1%{QRbGSNH?uL|`V~R%om`Y6n_kqeyva+Qg zC@!Z8FJu*j`qrpix!L}Eka$(tSUJa8)pwg})7(r}=1RCcqi}N`88W6_={?JWa+6cd z@AR6DuLV@iD9XD4KPzJ*F};YqxS(&W@zLm^%kWu|CKRcDW^ zw-;|B7k?jbrdXR^Z(#j_Y`@NvvksbD{Ki@Fd>(bvztL;8VA`~K#jDnpv?aK+dRnl$ z;#?uF6qRz9sfD%nqhAZ%dPAQkz-LzLI@a7FfAgss%2^)ZlB;z<7QRkz{Ss1jKd~CR zTI;#`d|$3%vQ%M|DA=se+0tDN9{l!xd0WBLw84PhH^V0uJy1D{<5Vw?d|Hl#)-{R98*I$ipEupWC4uWO6IYzCd07P8G0X;DV!^S;}1 zkj~oW)BXJ%WNs!8D~cnN<7!Ork4J_gdfk?!wVp!C?((P?r2st}8!WT0UJ@5bjT$Kh zIAa*Ni7tS@5T4YwRqAe`TOyte(;ru6^KuY~4(N9X>C;2@QIqyt?DtYvf65Gy$)QHo z&f}@9`#yNp6$vqF@6ek?18&is?W;1*maC ziI;xv8x-rkpl(?}wF?2AY(rG}Z4Gn{^NS2KnJDy+kFJSLUY(uGi>S{5<(;_&U#_99 zU$lHLLy-hg4voUxNk~Xm=-=#cWtgF=6h=Y*flvjzn z^u3uCVLK?~`FLf>n6vvxo$iFDUe|W#=Zr=Ayuk@Q?3lXyNGp2suJv#`_5(tENEJ(6 zDfm%yiJnQD?1T-bYe9dm*-V41M806U{G>_KHf4YvV|5=Hv?5_Dr!Q$8_o(in6mO6n zntmNT2F`(sNWc(16Fcn0g$&w8FQUyP_=2Hgan`(iq{V$i zJ!eFVvlXx&h(Lb0r#GA4HdpID;u17|N3Z0f6ku0mRQ8{{TitUfYhGC#M;c2n0Ygro zqe6Fph$Z?1p`wVg1+%;|r1gSX=QvD!LAjGmJ$hoGjknaL3&}a9nK(2s+(z#m)p|$#3pnvhr(Wx&(*E?t7iH2VP0o2hZ?Q9R4j5Yy-yc01;;LdtuAigI z%76!1sKlrl(h55AzjB4b^utTQ#nQ@yu0>k$mHLBWdc6e-%oKwNdd>p5VS%b&T%;py zG#4B}Rkxha7ru6E;S`}8Z=>502H*h<-P@z6{i1S~T8b~UL*_s)VL?)a?!F@34LIWf z^MW{MQPOAR_aDn2&#Bd4tcxPom9fi6%s@ov61=nGY+!{JGi=&AY;u#fyPW>BAd>eX zlhh(|dSDIkn9O!*0Of8taxkfV0hlT#XgSO2FyGkrXo*4q9r5EgZ`MvW%)HQecZum& z2&U$X5O85pa;IVoUcD|VzQ&rkpex?s4X3m5Un3*^L7BUpctPEb{t;UGT|D=TYvOke z>rFs>nKH43Q|K#V^$W0C5DDKl7stK(0*wAxzK{I@(OZRfZp&jA+Jol1IFPpG^op4x z_O3uJ)wl?@F>)bq{N^rnf5pjb_ws1ai#Xu>M?gNSZSODjCy_mx>OFa6zU>~+bQ5)I zh8z?DhU0+E;jhr@_cd`12XLg-Fr8})vhEARZUq3b1PcEGE<(t2%}I*4t2N1klGuG^ zy$1iReU#pyMrV<#1)XUdQ1f>gEOdYs0pvyKX^0~nXF34#N|?w`l;0l)xAUL+df(w= zKS8;qyn{Of*@wcxrN$ggPehQEKYt=tw`i(Y;MUt3MAU?7Cv9%QwOc5l&}b{Syg?;KGt zuF&bC$7M=8$VU*=3a%{oW={E)T zgc6D8#$FszGadACq0ebeub}Kjk(optAVm|oG&1O*fDpp`X|IYkdUs@)`2H>eITgsz zifBb!gEreyrMGCUSq|IvwnX;df2CO?+5bleC#Sh=55#no!~f6i!P)0U0qkm^E9KnS zeN9|1c$|betf2P+XxqJ&moU`9!QereB5Uy9+XM2sKTbY1-@CQs-oOt{?&M^Z7+j?+ z6GSF=gdusuU<*dOrVan0gZq4)u{3{Ok;Ix5t7L^fr&58W6i-`vOLO#RnC$=49?%7N zh#lArfKN6zu1_$;V{b*q{i&}#a2PMpeyf(%Y^9wbZD?jI?M_2f9do==1ED&32?8~+|*H0GmV4T`L;Qmt5{fO+dZPQT4 zVC1J;-_kB-hIW7LF5j}KFznRd5M!XFiY%C>i)zgW*$hbM%XC*_D6ULaBnR`P5c2i{ znXy?^7%GTzT#n6F*;459$ai0r4#iYa#sOMk%UyCJ1#>ZZ)*r0=e%xucd_1__Qc!Fo zuE7~GNSztXcfJuNwAR&md5p!0Hs9K>i(j)~J=z0(4LKh4ju{7*)DnLqL7RJfeU_Gs z*4{}%J9l&Cv$pWd#9A))>B-`u0)C9fNa&Az=%_da?-Ax1@qmE;6rNy6%S~#a>7_QJ z^y7dNbCt^JLyU+;)I=H;`Sr>3_my~BWO>0B*N}(_tLN_PtFoYSAw8ds zsT6<$4d zI|3@wq>9pe3%&OaD!oe+6$NGIo$uUp&9(Ph`}_9TW8@%bdCqb_;}+o|jYf7spb#P*!KO#a)GNJn5I zp(aUF&hy)6e6IM}gFjIZ3!;YtbKh+>|Jd(sRujCr)9UDEhvEFQ6&An<=nN$n_UwNX zpPkp@(ek@0`!H>rASoAV?jdJPixqoyx?EXO_O zOZGCof+u}h&NEmJfLH2LfL4|CXIk$;fe%(5@uK4jkLMJ@q=WQbP3FRMl53b$?XY5@?y>HOADWkM@odrMgQd^DQdeZv=P1fM7uqqpWL||dfA}9< z=3Jvzk7;ZE&>z}&yt;I3eevlj1n^ALs|2!X=Nk z(VAlRY z%blGh+?9Oj3TEg#d;J*AR+T{COsE(SG?0H2x8-3Yt%X|BPpPEXMj)%S9B=z%wM*oZ zjXNnMy}Pay0#^@A-1jMWI4T0EdUA_ZENI?ruYTF`^Yu@xx;C<&nDMk3wg1FWvM_Cn zYDX(Zra$ZMkv7$vLb6aQm7TaLGM+RP$BHVf=Oy1CL-}8Y1u7Znq??@6dEsXd4aDW( zHrZ>3cxKGf-IQWuoC4m8#}dlf@}%llREnOold z*BWfzRVMZIvlWm1gk(2^;_v2vlY85vbB5UziF|dB-=;=LeFkjWMQ8HfJ6+9&HkhR{ zXxHwVY?4R6uw)_bl`VTkWffSbnM|fmw!)hd zS|0b=n!3}W80M~uGR@JfkG%@txnvbby}?bazdTb~A1!(awFo7-h0e1}K7DK#Hibyi zx-HOe`vvkX`+>UJQINpv(vM(H$lCpl_6;6SD+b_9yl2fVngndb=eo}zQ|@*kZsjq~ zk{71j*v$#iv^S(SD6+Ze0sX8*Y+uHDgwB_(D{jZGaW*CeO!g)U42SA-S+m~d?d!W&N6(e)rc=fcs#R)ymCZ|K6FLK$M*W{3L?#M+3uy@jWNT0ad zsS4pI2V@ys7tCDd#N=>(Tp*bY1s5@&X6c7HnrR&Qu9q-bo+$~xS45Qr7Nh{2HJyi@ z#z)=QzHCXSN92LoeDM4-HD^POst?3e8;s%fBevUh)$#&Kdw!dWPCW^MFTEcbN-R%y zg!+0mDd}t8YvDJpM=|S$yIz&}^R7IrUSui0J=pZ+(bCIf|A=6F=jpLG+t9(6*V0s* z4Zb+erDyS->FbPsiTHpJLDpsrOuU%P!Bw9b`yxD+5@U6>ZcHQ-01V?h+_hmp@Ege0 z{c4{-KssEMaPf`zS#?_5J2oP8loZnlEc4q6t2lX+Ud(86(5d&Wt6MV@;m_cK^eTHq zO`$-3e>A!i(3)cw6n?c#^Wt7l9c9=L^&zU&Bx)aaSHLlSbx!8K1!lH5+CAL&>-TQZ zW|7;2b5YWDvXdgf@#9k$)tq*^Y7Wxb5*DEyms-yc5J(@Mc-@>!63yf9Rd* zg<*Cd=vs2KWWge+{pUm-;UyXPB~{qtpKMkx{D5DEVrJ^?M;SZJz_ss9M|z;b%TEWt z>A^Oho>k9&7dhYOvV1<`%{=od&+N}}d?M~(@iWawUmC7QPO*#Klt1mkY%O=c61A@y zwEVV5#N{fy6>YAzS43yFukMGEv@%`#V3!Xd7nb0&gWF#(Bl^kT4|I1HIwz7awqAO6 z6iz^hD4P2W2`1!mg#aA3F|PAvjC2YJ5CQ>HCxa-+#u;w=xGBt23on%8a4;-qA*e+! zA{N~8fSrQRA^K>ewyzxF8j9vofqV*1wwC=ph;`m0T`c5PorL=9+^p?Mz;T1w)qC-9;?(PWru3k_0N#~~k2~&CSH93w< z3*nkXsKNriah{~GlF-P7eYvip9VhX183|%n9TJrd3F<^>^%^*|0Z?~cMRBJ17tvPi z(mjgJ7Rv3K-dNF=E9&>(E>)px*nuhBdv?lQBj?$d=V`YEhg1U=@JU4|f&q{~bMTFl4@pZ0zOaKNO8B0Em zYmqTq44kE^ooMEXV+fUHz&pbr|7A$CA;fyKH!CzcE0#gqWTgUNM6NBwJCSl9;&ICrz9i|M(x6KG-GZFpuz_3+(whjE-ELQ5f_ah+wO%a zhxAL}hN8@RV?wFXC#m(=VSWs#8ABuYQ!^afofitMekWP;vaf^%tG0+0NW)fj54ReP z)bFBi4fYj!5_K3!z6O3EGec4{V4twl77!>OHmZfOBTkaE6uF83h;9ojWLg&E?9x3! z_pUFi5^sD#cADttY1;AZaW7tC@7c#?Qw(3vEVM7*1hx5~TtiW7SDnakl}#h~5RLE? zyRrLI*lb^l%(yX9v6gA0?t?-IvIcZOBhcg3=g(a<9>W_e5=te$0aYVW<8fpolN9+myTL76qDJF@{u&!sK$~OJk`xLf1}Co9{Jt zqoiJnDsIv_zw8jQ7jO@KGT_0&d;MHN_f`Z}T?>oxjm@`AzQe7%ATYM!FdYsX{LwYw z-+BYk*poJ5m=Cz!Cj-Yg_mJlGm|hu5rbQAk80GEi_jW3TUyRO&a>!VBUj}M^i=ByH zm<~e?)gxrhYAAnI-V@ZAv1@(9ix}2@3X*08h0q90=0>0aLmr1=*49izO+8we*+|fs z4dmt!2Z0nq*%b@0W2Kt2QR9D@Q17PA!;>Wf$Z_>lchqi*F6o*Car?YWoC-J5=FVbR z!1&Z@KT-tA(PHmeQ)nB<+igq{5Qh?Ai?mUue!mT9?V(Q|C2=S!4gCx|)4)%}8$Fc* zCA30mD<}h0RTfTxXSliR)v`!2q?st0@wUxE)Z15t;%}ng_I_~}PTniUtcc-7P?xxy^gQkGWpmdc11rgLKpDlD29iqN!dnXi{>9*$yn z$EVB^7@o$vYZ-XgOu$C;Gp~qt1E_QMH1Gwp;mgBlTY(h9~q!iyV^ySjq)ttZ7J73 z-*~3Fls-Lar^fMJV{bu@l&#{n%DR!S9r?3$0Y}!wx9dW@X(PSsx1PL++gcZ)OOa^P z6Xo4d(qFg^XIK_D+4!ZmDD}ji7LGV$@0KpwkgKg{~q^HdP%rpZ}78du*Z{69m#XHJ`X3)lqo@5KvMnOxaIZ8o^cn)Jh6@-R3-}%LWgM-F z*zVr})zQQ_ih`gC_v$mZ>q;E?HMAan;vA6#WhhWRxE;f2uGHv|;{7bvVQzagIqCs| zs-Az%_mhL;{g@4QO4djxWQJ3nSt@1Q&NJQ^^*rn6bh`-ylEG}d;q6$dKqri&v!=^# z6mQ|RW%NUAku(199{zqe?ir}3@nQV;-9(bTB)Yw1-o2FDd#P%BX(oH=j(ZvZH+68P z*08d=u%i3;rVybRmV7vjy!;vYI}h@TBd`#5{{zWECEY<4??E-RXux@=4sp<6=GNfs zRv+M2^Y3-=Ik%$SjQ5?9@9kpS9m!!}QkBJn<2~kvfp7y@LjCS*G0+V?M$*nZhXu&$=y-uhVKV55<4a8}NG087Jy*0#q{`63-| z?C9wG(J{&K3ElB2@A28~V(#R@rYCy$QP{2I{_SJGo*w)gj@>vq-v9Bx z%2<4%dlz5mKHdL(viAv(V^8;%er!(QaqPkN^8V)H+1e7`#~yqh`_F~$e-YXLD0Kft zWLK9rKaOuL5BzsN_TM|*bMvEkCHpTTyD&36FgM#h^S`CK$6Eef$^M<{-s`XUSE_q_ zq-S&xH_+eN-_zFD)!NtD)Y<-5t$VQ|{=bB>O>I@>ow)x!)!pz{s=MOD)fs#|#Am8`CTx|dMmmpdGOa~x5w$PHr0Rr5I1lg!T1%gA*7HJ@e+@$e?fHzDO5)87CdxXUL+ty` ze!6E7oy(yCpaMd*wj65pmB_%GF$gr=f!&tqEyHB|wOE>U1cF3hGl{s4531sVU*Z^i zKx@PtKQvn#W(S&#(hGpR#w{V#t4vcu$o5F{5ud#zb=>IN>EcodjpsIX$D#!$UaHKw z?7Y4=tEMS<@R5ke|RrD$F{d1eMr@N_wtZ(aoC?@MM3l z7!uC_&z0L^&&RUzXws4wCb=es&@)}1Glxs66&7h>UoG*Kw0_?&*KH7%v{!}xp(#*` z0|U2_y@K3M$`4t#T}4yt)g}t3A?F3kqnavw%0@x8haWaGF869c>GTnuSA1XaNNB>uB3(4py{~EgwRqcWzr^59P;l!=E=lnPR3Jn@>vlD_>BltFJ9(|Z zbXItq^rY1!rDA$`6;hAXFi7ir!d1!+QK`qzgG%MCMuaj1^H_`eSWm&zGr$6X$L^^TylQ7*mD`qK#d6KfMQD-`6^+cx`;Z|A`KMR(9r>Gh{y~+Fn zr}sq>$?(DPsgjeHp_%Ql{9j5oRm<&fC3_KlXW`JzlIbrci&(&SXub=9elq=~WGhXh zB?bsY{!+4{C`NA3_MN|!Y^BT;jMRB1uZjARv8s(~+bpCw_n3OVTq2h{#5bjKBPlew_3(r!IxS!AB2%YR#? zox)doF)G8mn*^W3cs=K)5eVXjuO$Oh!-7GA+LbunDWEl|2F&@SNdw^x@zp^;R2?JI ziprhJkh3MI55tB1@ajpEMHeyYI>3xe2D1n?!UerGVE33*GTAIgW#Wn}!esbxE_pNNM)b+IsCHrv_bfOVXicJWV6W(GF((m zU>X#^S<*ZDSo|LQ8}`vJ;(WtlNjOBy&20pOL~VG8S`JO=TZBv`lY4wYA(8Ej@HZ(a ztD+>sx?U;LqTAq&2IdaEtRsW*TD^^m5e9UcXh1?F2dMDoSfv@*gL=b3Pj@_MdrOem zvl(;%G>>0(AQ?uLX}9IWxtEI49Lg3G@r!d~M(?4JCA|_dV@g}4+7^nAj1l!B3^jXv z54hF`V{6p|e$wo>w=R9Ck4)z*F5p#)+=6}TDa#|%*K&Y+Gx)X*zOn;9nQ%LQL3oNHC7;f%WFQFIH(FjJhUQ*mr`Cy#D@zoqoLE|)02ETq&S1y zs1~y_aA7&A#!Y3losZEI)4rq}A5?BGFGRb4XMe2<3h5tsIaH`zy`}eYFIx_F#i_zd zAi**Ka(Y0{vB_G2UO{v+mFJb#bdU_<#9zuP?DI#arEZNO{v5#S^HW1UuQ8GT$)6T} zU!-XMR2Z2?MdJsQb;H5pvD)R67@K;%DNa;SZ8BCFYsAj2DyDu;H0|$PQhX#?ih!=I z^a7OyWGg_Kv}ZHjooUz79XLnY4kT+PRnHg>;FLw)oym1qkXb+=4%@Gl?M3r#kYuoL zsEZ|zwj^xQ!ef9EX>MU;WzO#Vl&Qfn#RcuVCvv3`j$aw(hy>rBDmk)sH5_$infZa09^AkDHQx!XuZ+?@v}3+p7|^M&eldFJD1W&)kx*Y-3_;we zTw0oOT&1lZ{o)aPxx5N(XzbTM@_u=_va8e3JU@E$q~-GCNkT*Gj`nfTvZXk+sPL4E zC^}f3iujjL7npGMu^P0G47Uq7lxWDWSkkcKrV0ewjb)bm=v% zTj-F$jhV?P#RVaPLK*xjw8_Nf3kBAt1tKOoCHqna*1a&JU)oa^Y#~ymI|^@lqa98m zAYj4HZOY+!92AvCx?Qp=@2Bz|Oc^JtLc5cze+T>Ldn2<7&G{;!%n=7v*twJTL{FXT znYe%R<>{6g*TfZfiiwM-8T%U%6cCvk6`=LW_j;E|`n(Eitatp$&ft+O@|ar4o1Oq0*Or`aSa9k zM3@In;1l5_Z*nOMY@V{3MaTq1+`)xgGN|+S2a8piijh)&MF;>1UskX&RpT}-+}OzU@|eNVgU$e6T( zn3f_)3@z8P3GEGa+9ny=76#fj5N)NIbakdXw$es*jgV5Bb^se^P!%_t8D{{GqxCY8 zJS7t%fZ7oI-^hhZIx|jp#wXeY@Zc>jK&l(%UXK!OS*7U!(SEt0IbNVS9iW*)!DslX z8>(DM3H(bcp&zj>>#N{vSi<@)eA780tHhm<7pD5n>{}*{d>(--6^8T_c%BQAboL&X|%5%bAF^CVnofIR?uaRT}(4n5C>)^v*GRYK22Auf6eoLNaT^(p+{yq|h9loGT4 z%GU-a(|Mzqfcdl{)1+G`p*&U3b24BdxdM!4;Yy4YY(JBM9N=Fz&{$6rW)S&vPm&M- zbPGm6SOvNc1-ne>m}tPb0^LIp6!Y6K3#3S}PX?)&v!oIYe3}4XYbF!LPa^m~kxh$w zp@+Pnj3FS{hmm_pOM(J@%{5>K?68hiYn(dF4W241E}vQI$ts2c;<8Be!D|yfK8*gJ z{x4KypBu`+Tu&gb)jnb}%n#r%KRS{qh{EVkClsSzQ7SX18G; zWTB*aL_c#$Y70rXE?yP7WLG*-M$(h~5`_dKNE}3yz;(e~bD2b^nQzS0_~&!7ze|A7 zSs*VLR$Qt{DtgF2@A@Q=tn(F%bHLjZXc9xXrupk?0-J>Bbh7;@Al#=}7PcvCKunOw zmgi3;3!{;R@p_WT1(C#`P{sgAh`nAsaSkZ0gnIciXp#{etY#AuyfhVf`S}ScKkt)} zO42t!@BGOx3*V zq=Z!o+`}px+0`A=)i;;DTiKOCm(@y=H9Xgtcgq?zYBNq5WqegN$t1a-kTS6w-2}J}m{%6h(eU)rBP_U40$AaI zAJ8jre0JWL6zst+-xM=kgFC6u2u7;4H03bUHI%~QFPoeTn+nN2Lds!9E%a{pVCKQi zGm#CXYc-Yklrk-qN@HOd%NAPhCX?hADubq0a`l2(`sebkypq+`!E}+at$`{n0eKDI zy;{eD)qE}6M(3LNgkW~%^t`cc+}AU0hLg?TaKYu|?PfEr{Z&BlTFY+v-3B4rbxW4< z2_jO0im6}iX1@4~=#F14RlS!TTb!&8p%Kuv4r6#n%33?&J5jq|Fp76~XJYYswv&LS zQ@^T}ma2Kl4fkYSrXEY&$N--xhjm%PzYfp{uuyyrrWQKHxuZcoNfi{QT|8@XlzBIp zD5zx)X*BM2>r8fwQqaZGbwQNcIx@cl~~tq>Mgh2A$* zl;x@%<|DmLk)1?vT!>Pior1J;9F5D%zCIHiuCj&HtJfcmBTjDgh*O;krgwbRpHAJU zSJg{O(CqYYcye>Fd9FYEP$*b|HXx2A z%nC-gJjhMd57`_j(voFSpe>7oC9mB5&^pv^FxYQ94ALKR@EWWQ;d>Q#qhn<_x^Nhp zJlN%~Qb2*|3mLJk8yV5!j=O@nxzplC=xVM;25MUx<3@Giqra8=f$$+iT;uG>=4cZ#OSQ z%hfjZx@+7IK0$W9HfpmrB5F-_Tbpk6ih<%c_3o?bomZ8=eWt|GLt<6axYaS_Zw8Sz zQ7*(ZH?A{cWkw=zN)b3<0_hmYo2k5_rnot2c?&M{2ya0q?X6kV9?@#CQYW~N)1c>Y zhzS>MID0&`E-S~r7L~LBvgyjx3V$xB$=B6Mw*gkx5^s&zTL234^H zshUS|Ec&E&NZ5`& z^zn++iq}s+M)%ZYw|rc+o|CPb11EpH$ASOO_feZ_a}-wnly?6S>{t=D{hR6(@@c}F zD#-FPZPzDU=SsK`tl=XJkOL$8^eN!C+*ieU8l}duQ5fOas@~+so9OehRPaxDc?lct?q$+b0 zc#pyJxw?~ZNl(o zHh9lObI}2L_I(b``wa!$O0h#Q!%uJ*5Bkw|SiUfAW&2Q^4?{f|e&BgzYqU?4R~h@P zbKxC}g*kl>+cH8MwyaV6{yyEtSlc#*Kq)Lp%?kcI0j9G;O-czj8itd-*&?ax5;}q% z|7rRPg#*SjgrvHu@+#lUz>y>Egti^xr)@aVMC8Z`^&c4DXBr`0807KEZVR;U8U#Ok z4u`J)W*lleeAWsrI43jG{lpVfEU z@q;pLE{u{L9<=yB2N)Q16wv3hT9{t0nTByK88Cw zIf_sJxCa=N41m8~jk09=+9>5}zrOQZX4|G7V~}@W;paVe$~@CHD&{rgL$iq6gE^`% zO>Pb6;rrC-rA7kNb$(wAj3PvjKSm(&+EzU6*rqGu@gMP5W~Ynw$Yor-fV9BJ-t;#K zHB1!x&|#!B8HVekm}2;CV3*`;i*K$`@w#`^1haClmFDW~vo*|$z7A>0`oqrVkTIS&edli5 zFWfjwXk7xD0+7w@5rHfYXuUr6r1{7i1y7D_M>Cc;! zbwspbMR|_dF3x>oYnxv=?0?OiAhCadwG&y_ohqpJn8vCiCXd#025L6M2-Z zYtu~a!?Tp>AHH~4Z|?NwX$Ff+Il-2h+lTnaz0o0GO10T46-CUQ`+207T*`^1KNf?G z$)#@1M!e7!gJl=o4?gade(>~5JjtBdJQiQ*CTD%J+RTmOg4pm_1gzPBLuJ;nBG}>_ zj7No3p6k0chL;hdeKMxui8C3U{^oLwt&hW9d^SVj5Vgth99-mv8vWGt!`GuVR0>a+ zEnIfAY)u3?9=q2^GQZ;aXy^+Eh61V)b9Pe7Eo%->?tygU9-@wrpkJlh3S^@2fd$ z5>EUm!x=1c=)Y=h1qCeqyyLvl@zo*d;>>%gG~+9ce|ymDn7cXWj!8vUKL!IDJ`H4a zzt}x`Bgc0wESgMN#QZ+%x%|_Ex0Gu8QFJ7;^5?8nl>#M}FK(F6smm=_-SYor3BDjK zVYm#8mc(5w67ujTbI6AXowZHaKuB5aA-JX64)oysoD zpEg-iYGBR65`Fp1x}Q|rn8Z~Gvx7k}u5}Qn+&Tpxhn?adIK^|x$!L%{>C~q+7@x^x z^tGN1<-ysTD*XC%(!H#M@5Q~bAULP0BqtRsE+MG4JO1$u!<6qi`*hmk(Y50y2a@oe30Z<%}}z4ez6q49d72 zy+RiWw0Nhp#?x+y-gA)%Rl1gtN@9WWbA^q3J)g{;BH+FC$Z_~_nOcCf*F)J^GFltD zlg9*RPM|gcPWL{;$DNa*pWh{G1T*!e%A1>CY-`YwF}!~xkjy((7N`gLoty__+*P(0 z7?xuHLQK``tQI)S>UG-{z_b;6TcSskK3e_Obzr2jQVh&S4e{p6YVV}=VIg)OW4SlN zFIt>CkqIR!hL<`~K3|$H0@UQ+mM7Hjc9J@l)GGav_E5b%FSPjk5gJZ2DVsOdQN{+$ z1P8d7M)4U`?Q0b)+$#6F86ne~l&;mH<))AJF-p+pcyDLEctKJ)C2cO4>!0psv`9kG z$y7`lQL%3-0y69&?9IJqTrYdU9&P;L6)xvqr@Kn%9#QS>+xIQvQQDB(QN>KOE>FI_ zGkn63nx~UgsSdk*^x~QAcp|nqyl8Jr`H6h)+}5|7)7CCBi$&lU>8~hrOpUY3wpw=vv~aca{03kaDg*7AK@}Z z4sWz8X{zKA6curi=<73PqF5YIdLK%h!4gVMl_MG<>lK<9_azq7RHce&NoD!`w%^58 zHOxoO)R1$o8m@HR!(x?`BGR)k_`B^$1=G06Lm4@QX%f$%N8a6w45&v5;k;$Tl4xrj zAi7V^kRoUHEtO5e9y;Wd-YZKvAjX1DcTWq|B$$!HLx|`zZ@!tUA^+F(9QnjC6o*%O zaOs-L($Jx-Nrg3~H%|TFJRdLNTiXW&PT4H6-sX=l(rC1Tx(M4*dXSAdx`)}*)XB#( z586@ztqh~IyvOf0Vw`OEgZSW2yd(6rlLy{!H{sYTKfLrMacoeN9O162_N#sXCJI=f z7jt}gUY0c9jGCP?K_N@Yj$Q%*keOUH$v(Hj@|0lb2N`uOPATp&4#86JTlKALz>#Gs z!TDb~Oxo9H@vpRrTJIH%IMqVfQiZ2l6jHA0v3G86iyOV-Sl>2#OYe~kC8~?`9v0gmoE$zAbe-t+CKMc$lr{1fT z*VvmwJX+@R_5=Lp3!5m|L7MPB@o!*Z#-s-u%m3LIrpei~*1*wsFBe}o%&dbVtjq^mE{iXP)vYZmQJyZBF7rxKDq=ysf!`MFEk+&@L>FPrQ9 z`#|c>b6sM>LLP&&~qTg$faxAe?}bV{%)_gT6K zsm*Uc#s2rFpFi5SuhIPE`;Km4u?*(Cnrn=FE}Qqq#`EADwD!z3#`^N>Nk`@3UFhhPX8n8h7_+cqfq+ws=~U z9-cNMA#=QpSP!o{OKtls4}w$V;il`hWOxi)?oa?>j59EX!`42Ab`AMEtnZ{xPCAzK z#a-$vIC6Bg|vhNh%GHQ^HOOQ)haT9{3VZ^Lv^veYtBjS=FC&hVeAp)#!X=xl^s;V z+{$==cBxr4ZEf7ps8tz}RTOOP(e};4XX$i+z2$pdYF1`_u7o4p=kQ-Ba5B9pBo~u`PHa(|7&7u0xJ?i|RNCAV`Fv)>Pib%z2k_dO9D3*b1>ePYe zRn-_H_2Kon*qMPutymg)P$G*2t-V-oD3gT)NXC#nLyP={0(mBIu$5yl0#z+|N!D#1 z79m=I84z#37;FIzH8Tul^}JN98H|7pio1dPI7%@|8r9gLs!YufC7J~@Sz;4IHrOaJ zm`0bL#=D#S+1%ta_*?EnwQ3b|B|z@=cNvZJI*j!Bj`U+j2GT|b3rB`(M}~VwMrKAvH%G?KN5+Ap6Evff z+@n*Hqthy*Ge)Dc4x@9vqw|>2g|yMd!qKJL(dAa{$?i^}3GJ0y@@pX!g_J18+D(de z7K)8`v7gRIw;aZ{eaCh%W4pi?@fVscxjJ2qW4HmlkkQ#YA3Fw)pU{k-a*v-$jz>5r z)uO`PC(>2jQjWlpiZbJsvY4&~BBR}K8&BP;6OedrOv@_K=Y5H;RU)sX64&VgvJ#B|q$IcEu3O2=v7|pK^z#@e zskUMv6>y4M;RKKL@mIx+Per;G-uDDl_V7nBD^mIa^Z~4KL{f2&u*59`1QjzwewF$h zstLd1^xAC*!~@9w-7fANlk@aG2@;0}lKB?Y~VZem&j) z&qQqR$Cvf)TTsIumQ#<7?Vtt6QV1S|Z;!g}rMGEpI3ld%`{zb%|mevIo*ZIG#_ARXT%CCBy`@ub@!sV}=V!3@**@GAOmLkL7 zEyeV-)aG!fgv7*{*tow#ijk3+u)&vgX-c7S zQh`B2zHVIZy_h#DF&@e>9w>ZHG4j>lMC@*OmI69cHZ(>0S-NCMnpjZkt$+A10l!2( zpEw@xcy4?}(JKaDQDlGomkdKcdib{tD^{0tGQa;X8HV|v6~%wyFii`01LONThX2H2 zNOgT#BWp!vZMnOe|K3l;<1jI4WzpM6k-t7l!cs~%B@p<8qJZfC--O}^5DTg@7Z(nq z7PK0u%ZR!U-}T~lDV_NBeIVbf;115=LER%1wg%rX^5tHUyCQyy*^;pR~$yGv`dOJHpRj@~5PdDn-wR^O?A8rCTbg!c&2^wIS$qzqHNpA(Nv zMUgj@9eEuzUxOfK1&AF;8mG#}%9Ax)!sMh?#QpmOMFxAx$&49EYJx6CN@_C${KXTQ zCU3#XvUigJMutC2#&#?Sv;z!GR8@Pi$| zwbBPoq^0Fa1+e5(HVt6!{$cq?2sc|UvDbbvG8P=+ri8DZoOG>CwInfc-ddhEd-sZP zi0zPWQ&{PQiTkk*)f-Gw;;l--vrd`x*z#K0Cd>p5$TNaZD8ASgP}$0;>3?)l>UW4- z7T>&8#qlt17jafHxPzEIqmk4JSpVTQYGnFasCkmp!Pk^XwmhX%#hTm|>0ZqOpND)@ zcoTb{&9y@JYL5HX%PM{cp%Igv3jc>fOV_TFI*|J>Q>RGwc6gDFFq$8xnN^75=d8q>QgW5JT5;-)5kStndrx z+xUc{6XZFuLG|`|4Ps#j*#3=D|G~spjtB+VA3M&u)RD!L6=f==k^m|0fZcn!gmnhO z2?0ReUN;^2+T`Zq5}{|Z=A(#CrMoeW?_>k+4S|AE7JA}jxa!(RM=aOwPo!`4Sa-~I!K z{a(zFJ0$&o#bJCJgPIm+DVZaMywZb%IzeZtxfE~t)is6;vd_{=wB8Du4i1?#pQTsE zy}jwAF>JAPmeDx!R@i@V`2Mf67o8MEqEQ+nc1&M02egXBi3*W#B_Vtm@;ULh-Z2w# z8_^TwL&x4O3Hl0ZPy5zZP&t9r;%p8tg(}x2eUOn)C^p4TlNe2Cl*XOc#hF>Vz_O}T z*NKnhdfptI50cNU>Gawda$B8iAXUv1R;+Dln*_9D=zi(Fh;Vp=Z`$1NLnEKF_Bd3& zB$bh>kJ(Nuuz$MXtWFe^M6{U7ZZ+(rZ?P_f@hyP|Yv@spJ9Z_*3oX6^)C0e-ay}Y) zpRyubmj50g*zEj1#6bw<5|i5|*ie7*VJxF{_ewf9; znoA_Ki3GG)`rxq+bvCl+z>i@8Q3VZxo3}Mng}UBPVEY3g_pjE*Ozt*;?*I;}C~P$% zz7N6PEzRVau8v`28lo-+XB2NX6CTqbP3pxrYwYa$W%T@L6Bu0UfVQa_V?=N1u6u|o z_?9=rm}ofPvK6{Wpc$SA)l7$(-R9`s((zPThEnx>C{lO8Zv8223PjA;;+F^^8<)T{ zRKT*{CYbz)IZS0@trfiHYJYzIRtWJem75`)zuGUNEptPfL+h22T%?5rD?La17PJjX z-Ql1_o=e#DTBhm%b__0*5rSy+cj9J;?sIg_8_*IeN1FsYa@`?R0X^q3$o@iX#;zbJ zssw!pBbI37^l00UFm!~04S`*-NzYef!y7+5yv1gObhv(HSw>ONb13qH-dF1*Fx;l> zt`QHEa${G=%r<+eyaZGPDUwg999pIHk7*Z#wqTD90^Nf|RIaCq$9h4$s@eDP(2Rl5{a*|L_yNWP za~5RZn$GYURPe=pP~`{q!}nx`VvVz7GOc8{w6c5U8=q0Uf65Ohr3Ahq(w9<#C1-nK z7RpJyl2cVC4~1%T3m+|czNa_PMq5!Ay?Rfk^FdE9xu=%nUD#I)FR^*1Sm#@r zMvK z?*9R*P;7>9;N06^_8LK}kVm^=gS^L`SDjwV%Ph)M#Q{UN_9=|`a0AwDZyyf&y% z3#%kzQpsm85=}L4{{_@S$Ir+B{c`&pL4Bi0xZ?tmH2y7R^2ML?W-UcsxhFGV!F-m& z+}{YB=Mk{Yf+16mwmo#>y-sprHt!_AdDx$q=uNG|kq zE`*c{@@s-fS^xQWr+bMF;FX34a5w=7_dIKh>m9qUr6;AHXlOPcEJGTMFA5%tlGNeX zIO8GLcZO9o;pGX4@gkVn>|SXD{g;fVq*W%)Zy~(=x}QD48S0_JnE-hJNiaL)tdba? zYOczK)UCQVbMe+E2;bl{YXcKd(O`6znx&>5pJf}>|im5=xa~nO8sZ1C*X~w2&XMpv<&vH z%+n|=mRQXHbEm&fJ@#-dl7s{3I1%FrBmZGTLV=AUgcEE`MBN^UHf6^W+CniG)R7D^ z@6!TizhkB03X4h5kO_(Bgu%Kp&*DzNPi;t^RzmFOLYoI-ADzYCfyZ?XXol`s-i9kg zb5N#|@{R7s=>-rwBtZ_7@KOyDlo1=+7@NaS^XVeKEDgJxnkW%PVX6oE+LySqk;viX z2oxieAypwE^Zw!p>qWp)0M0;{JCHrE#ZVhsJ7UsF5~DmKOM(;&jubPc6jOct-l=5P zc`cGE&>W78D38pLAcfbQRx*oL`Z|zSHZVngEfz@t7A1hTr<1IlK!4gmi#vIoMaheC z@my#^Q-qFSlh^MeDI#0qo73bs7*njGQ!UUbG;67dQ|9}q2Ut&Vhz&_Rfb!ZvyONz! zM}SICARW=@Z8b;RSLtb!rQnrC-6Te^UFi%Y2#!6WY)}fbGpF`3hZ$;kWrS;6>yr_R zQ8Z-)6mKY}?&z-T--;#^WJ>m;Uh^dM0+Wyihn!H>1SEERqqNV3d=F(zgh9VfKo=*1 ziK;-`HuzK~)|V_sYM$1b9VQ+~9C%_E{XbZ{uc)T_chUC{2!udj1_(_`=p6y+z4tD? zqaa-=q9C9ow9pfZB2B7vq)P9-8j654X;KuFrXr#o-v26lt#$SuV~=sp-MpJOb7Us@ zJ)iHhK$_%2LV9Ab!BY^i1+94@tuAG55&wmn} zKL^d5K`tK%sQ8h7=pEU7t0O{T zga?!z-QAE+;u2yjO48B_6R5}%luN1pz+M6;yjYLa?=MhvCnmxXPO0FQII^I13?2;( zGd8ZYxLinGF6l<1)CJXyS>Dihs(Uj;r?s#!Q4;4K%FH^3OwN)-n-?1NIg3p%Nb8D} z2Mgf>)R51`#WqE@Sp*kH@{Sj`o#lW;Je5fZSS_AWO|RJM%8ylx>EUxEfa-Cc*S03w z@a3S(5PAX@+6S~okVJ%;=ntiLkEoof%M5OnfsP@Uex(j5M#i=R-_O}9?xY~XH2){S zIE0c!8^FJ0V&r%}7ssBQN!^W;xsl2~<0s~E1o?ub3|k<&o?L5`t*-RsvF)Lnjvz_$ zqx2(tWrci|ukxzl$-{F`+dfhnh#W8sqW?7NYSrV$K?t2>Papd3vnfjTUDVfJ%_z+y zuL7!^M@s38%}m5n{;Y)or)3u{dI4h|(Ai9}SaQ$?ZcmPyzZM$mOp>qS)XGsO`j`xa zB5hsbBx28O2i1!|hH#Ioi`E8f@?MXNk-@SNs#hk#n)HQMJ>;*09=*;~Cvyf<-3SaB zb+*h>A@d8gD-EQLa0}rj3W-(XARsdK1IsxFYiUzN>^zd4BNmQm($cPzv_mi>3H4*i zK>nn6+uu^CLfp3rIhja(-%3p=w+ug7(sRBFbOW9!CsY_m0;%QDjJTAM?43==e;A%SviTg~tG=!dP=Tv#jQ%d{t8 zXk15BaYm9paGk)65bTUBhJrRoY@#ZIt`dr^uFAeaDy>^Vi?rhQS^JX)4VNxdh8cJz<4m$z%>#LsE& z6v)S)(Dv`#T8r8;iFd5l__oBsHA9u`9;BjJYO$tDZ?HC&$)>R4_t}8pa*>`x^i* ziCvt3G%pSiLsvd^VD@(rgl+vdW*?aMJDGNq7Ia-vFr04tUf}k-}%N z?A=ATfSmSmy;V&}E*+uaR9Y`F3qN2L_TKhkmpi z=oVs>2?s0vnYV1HfurU;VUy&9rAZ15fCF%=dcmBN^{z8D?R&r?oUWZ>mK3*ug3n{Z zwTQ#%J~FeEeQ9}7trZ=PcpMIn{X<`$2$cLLdeteH(tu;$2R1rrBu4>8JOFioH?Sa- zt4LeJ!3K)7ot;b5b&$~OwV^I6l67e?)tfTHZ##wHW5Nh4g^pI=iFYvCY2lT~>H9US zfa6upgd%E%Ol*-@b)J@eO?A4x(|1h`wYKEIQKX0n{_=sew?i1la3a`63SanUcndbO z7}ficbo#>#YVOABM^)DeC&D&tJMjFFIVEXbPa+4Fhfw>&cI<$s{;NKnFo#A>2f>%9 zIybPyYm@~u8LPmt;pT2+TSXY+p}~iA)pd%EIiW6fq6568OC2nVW45mB!&U7tJv@?SECcizbZN-94Fu^&*de>N}ZbN>6q z2i0rSJ3zUye;+=?mkSsR?b{X%L{c7ln=YVKHzHIAqy6{SjU@N(0|O!~f<}lDmCyT* zl3$YdVH6CBN}F!NK*!Pg=@i{J5!&WXV3U>M`u(i?6;YN=_WR4mRSlh#5+eHmKnpVn zc8x#1j}Q;*kBXRM`*Y-ony}h9reg0p$)mf!3b5oMIKFga556JaAPBFhXxmrWqQ3&~ z1lLVnHo^WUV%>t0FgW}p-OL)$Y4Fh;bpYx;RW`m(CLTZtzq=nVz;W+w#7+&_5ZjIj zZWeg=A>IB8!2bYIX4jS+x?%GMVPJ$X7x_+H_c_;b8erejbNOh6Uw3)+!S42;$MG%FYhW<}_%o|EJDgL)5B{kP+vAxI9s7@3{|xL;pu5KkNd znrFW(>h{gxXMos`WFy+T8ft@Q;C7=6J+ULxjUQyVZ%)TQDV3-ZPBhp1@~m(ERzUrp z415Q`&k-))<@}HO9&il!{3a&+6RHd+F@js(f6rNPIq>mP>FRjPymyO+aL-fq3*e8Z zDOhJs{0#U10xKZRjv(il{G-JFN8$LK=K2$7iq5x&CU1EldHFMezve#)#WyfOS4aU&v`?eC~S0*NGzPaFUrQJ zxIQJ5*iitJxXptKpaXRV?8Y0R9sHD{nJhk=S6Ea#4rU?TgsVw>Wr@qr;@{P9@CR>` zi3_W~<_aWx=!JhhDLCbqF_>-j&9N)|&)?{Zaz4j9pm2gA#sf}KYzQ57C)(Y0Ir)q7t~=#b52khmPlgUn zAAe6edQVeao5=M;utSt7(wM)u20y7tM5Q6B3MK_nidWONp_Ql z46C#FJ-hJdw`hcuMG2-0DO9K_TcYKJbhMeTHZ&wmHK_~?Z*nVE2)E!r10FqtGVu>b zqGPJWxnGh5U?&8H92(7U8w=MMS1(24u-K@CvqHjlE(pJ=;*&X~6=|V`h50kE)M8Cf z{};W~uuB8&Nu|O!DhXlS5VgD4N6Z}ZkV127-{wzrm7?uTM@zUpT3QS1y!QWzW;WSZC{#Pz9wKwmGT)|W|r5!orNNHvIV%)ZFOt$wiDBa>(w$RkL5YW9O zAYwl)cakHP^ik9{cL+fC&ARk;zPLA2)Azv!NAI%tkvH5V5SojEm80RZBC%iMKmeLPX zuAgM~=8MrPsVX{ZVbd>m4M2H~KGPglP!=uZ^VIQQ)2Y5sdey|^B*T-aZql|)vg>aa zwNvniF~KwV#0oi8UvfFWi29Vx!OOH70T(#;;@0CTL#!T9bD`zdv`OaSYC|)blwZ_U zQ{xyW8H5D9nYsVAVW{1OuQ*@Gz;T?4=mH+r*=(^wb=4mPOqQmf;_Bf#tnc?ITmeo* zI+|T{&4c;^S(N=`Os}P@^&Laf7A;s-Q&tP4iW(r|35nO^wYt;u+q8t7wS89?s@k1G z@P;$~j6+!x%4uS+N=vlwp>4`Bli^y+?ZlOG(|_@Wp4N38Y01L?)r1z5sO9G9h)*sH zPJO<~WjN?O11G>GxSfGQ^Y}}(rar)Z$L7j6JfrxS>QZk<6d|)a(1YREFQr*7M z3?E(Wo5Cn1{I-tG8}a6o=jLE&eDa`66*f$t%uxdUXuEGlkGb% zU$NjS$`J(zyNyOJlW;@W)#YpcTK5n1=4z|KQ zdJ3fiqNXRfQb{EgP0ncPA2ohNnik2>N$14=B%KDsYja1i>|Cn`shX0Kkaid4TG`^H zU#Ajv0OznOp0pAbPt7<;epWod_IRj4`R@iLyQ2*fbeMR!lbwo5jZwl$OkssEaH5J- zF4Pmzc)>e&P{hFlM8_&Q859JM&pEl@5d@XJ+MrTO^J67O=y2>1GKr^gWg5G@h_*QC zI}$bJ1mpztlqBEo=tWRI%$LxYP;@sg(wHmYX#&(kqun^}4V(3P=o{GxNO(nA3XBG2 zS&1KTJ-(P7W(_LWUc6IvuYL@k6W=nhLY?jVlgsHV1yT|%o{?_6EW9CAnh;Ly7i)(h zabSIPrP!}l76zRbZKcMj_O0`b{$48>ZEjA2eRUY4s|!b&=Dx)B;CZx=h9aY>u3zFPUE6wZC1Hn(;XFBhUWN z@yNX{ybQBIwN~6y{h8xq+F3yp!V|o%*~9Q=`#C*c_F3%)$LAiu_<ebn-=*%IS&K z8~$K|n?$I|@(E$oi;V-n4E_CYhD(%(#ox#3Bho`%4`1Qhr=0sHTeG<~wQuUq{5DcU z#FM<1**LMNFY!ys?39rSFVQUYP5mUbhJ31`sLlE<$ko^}vGN|xR$YCrN}fKF*b&%O zSG#&Jo8tPN=5gy6J89@9{m1hGDp<5B`ZNP0u*b@t;Mad@g~kdVa?6^13xBrVp`OQ; zy71SXvYXn?T8_&_pfTYzssG0s`*nd5D4* zW4kIbsc?`Wv^fak&GysO(Ql~riaVC zkJ~loK~D^CM~tg=41aN-KviF;bu9G?Ch0EO*%v7E2wwLa^COh{6DQfu?>DlG(N~fy zU8O60^nTf5b!o0xd9GMbd|yTxXQqn!^N7S7TbKh*sxtnMurpryi~W^f-b z1=v)BtX`cg8cLPTnR3;R+2tgAd*>!?T4Q20p@8G7$ZTV0M$lrXq-&+Y+zv2prY?Mt2 zWmBDBoCxSVI*@~fY5U}B`P4$FqejrRJ=w?POmmRWMQ@T@q|&e>=|bYzxpq{r_PrJo zui}`rFr926h|O)i(Gm`wO;gYCPY(!NjlDuvJ@{m8}uOOs2SU-cI`{-2C`HK>cwkaxc zIHY*^4UJN$PkU-@+^umat|9fIM9NG9M#+clRI^ElCFZHDti z&Ei-BcH*R`$dP&SIY23IrackW@wfw>cQBEVKbFpwkSjno6)}0W6)Z0-JBc;9S&(js z7S+Fp8Gdy+F;6~OB-euDQ>gG5k1jLXLJq`VmvMo-qw$DuD-d!&V(r?9?zz#@#NkFC zBNL+b^vnDVDkY&!2J)zQY8FMx;nQyNbdN)ovitJ)>gy+{l zw9eQknz1VigWepi7-oDEg<*TTaLpCnmcnnj?bxfcaG=so6= zi%jWL!XF__mIC&-Nh$hhFfD(aSJKL=I_An7FprRgd^{4xMVNO7PbML65~HTBJJHYa z^kGfffh_Y@O^cPzbM@9Hk)j&Jy-o1|eXs?YTdt)S0s_`C^Ktlar4n~&-Pk3H%x1wj zFj`#FV$|ofYr~+>+OZOe1*FdP+)F&(j`CuC{@4Q>kD02c!7Q~mAD@}x))&;9mJ*KU zw@oZVeW|lO7ScqKX_Ftg`ppdu?Gi*6Qvect?fZDX_e8k1{d2Y)%u<@$d&?3n>&fN# z{N}dF5-5&MZ!K#vNPR%^YRS99Anr4Fj7j z@35>!XC}Y-1j$C~bhe~aS7WX&ZYR47LPlC%mtq&D-hT+JUiu&mNnO5y$3Bqs5c{0PjG#(80wg4^ItH@1_IgA-tpz4V zOmXr)_0We5a8L>C1mWNJpR-^BgvfN8pjDEXuZGxATa9v^)wNqzqm4Vs@Z}fx7p1g-%2EmJgHli5VpDpe39%ZeI(338(E+4u`USeh_C{yg1_mWdwLjK>bot>1qBzS184-g?l* zT9!=pl3a{#fyWYim01m;i6K+2)xG-T^uggyGm45b- zs%4(LD^87$Oy`s$stL2H2(({1r(rP4MzTuz+t?!~ex%FK+w4ItXz6gM0)eEy%$kt+ z7Cu5(k|$->7G|MHrYq&xE<6`Jw+8kBFPKINW(t%M5J(d=nJ?Z+S$CSo&Tla&dN|xw zdAla)_mQk;gDU}KvK8$*h0$Wv8YnZmYgCTOajFz0v6|PCCRr~T5SXDRBNTOKCTO}N zx*J4CfW^nr4M3YKZb#zj_Z7*4wW_0Q-7`(V4;-D)>ozi!lbwCL(HK-D587l46?tzj z+2hvu68RM-FG;x;5`UjQCt?r73Q2gnlAcfej7}3iwM~7=H%$!*po|MrB5)&+WOCkp zw1cS;+N`@}BKxN*0GP3}gPN~N%_C5Z>Z!=}3h@j7Zl5b5WO z-V71tF63Xo4uN`O`u+S!t_SQx|5aS-o!*Wk5Q5cf7$Xrv?SrzGTIy+^sANJ{zj zgI2142+(~FPDhWEL~s!_IYzjFHxiqlQiEUjto`uCTkZtA-rKD?M3vpIQi+caPxA`= zx|?_CXXLvgLiMc5U6|2_@X;1g=K5OK*AqGzUrpjGES!7v^)z?nZ_8F!){Xf`U;Qs3 zb)us9#SKBsGX9aEkK=)>mX#OR=W#7phS3cEWNOQ`wVGsYM!)-V_ny}>Q;9x>voP&U z2W{=u;EDFW@=wB1=aW+-`IS#`>~MLdzaQYF-`1q?z5;I3qV0e-B|PMo`H=TsUWBTW zKQ7p{GxN68G(4dTbi8xmdhgKl;o;g_`?2pBc2;>>CkP`ItQa6Rpn*(34cO~)yjmAI z5d==%`6=a%a162nK->LF7XP1rB4~_H6MD8fMD>P~;1K>A&Ik5PRtGfnwy>q0qZWU9 zSqD@t3nI@!nl}570F8KHHJ|A&g-fI-;S^5R!znO@dCXoK!o8zN>aDj>&)rsfu z&qz`SZ<%u#-^tuIMnEeud5{{_SuIP<%&4xNm|-zv$zXqlW@3qzKscqqk069`IX)rY&;UW%j48+l&nN{J;lL7O!Y97Euz0vD|a|F<^lB~ z3dVT`?) zd+o=oO)=(3DLeh7uX`^0c(_T`HAPBq( z_wYpaMM3GsefEyn2QbvUW>p?_?6nC@(g6p1$DAWr4s9uO{65W?ah_5+`~C^{M5efV z-vNiH)qom^Y`Qq^G`=EFO_}`;B9O{SgN{fXznGdHl2UrdDmFfM!&ztK#XwoYh5el)&jR8wp{`&{# zV%sCB{3H=zm@OZp*$t-bgVsW>D6n#xi0_5O=S(3Zr9X3VU=3)w>9VTFW2vtzZI81Z zJH<=J7AWOUe;B-$IoTe2F$}}+OCPOg)Bm{h*BW!{%TjaTHzhNzv!nZruTSpFWU9FB zEHpfL;AnWhCrp#9w8tvCCAjzP^xLR9sy8YXw{?0hu%!VE>^ z8>DFkbOm8zSe~43n6DdRW`ZGN!8b6Lhya&(;kI)Qohh=+RNhNvmUZk}Y z=NB!tX2xBq#+dP2q$9Ol9#O}@K^&{{X|VlfcjO`7*CMn&7+jS6BUH4{z0-M$6*QTR zCnvITi8jE0j>Xne?EB3R-3t<$A0|sU_|Q)wT(5mKB9cTls50efx~z7i)IMXv?ft>~ zNzN}mi>*-pLX!cIp~CGTh#NtT`YpQ>iAmOPmyOrE69P5y`eNDZzOU3eB^PdHRHZY6 z;9hL84%y*SI!<=cnS&nfe;(bTi-k(B2K8%}<%3{8(jUXE2KU4<8T-;3(Yz&+Br$?r zGKRi8!!p~r*t33>A-$)vJ4_pB-JRUfzp{G;2}*MNCD~8qK9^T^$$hDA|0{P;H?Aaq z*tGmq{%h-(F8ObrzyHb~^^z+q91q@jrf@PU*sX9nDSxGKHm$F$`2D@zGsPbtyt@^D zvY9ep;#bE*hHSR8-JaU)g_bB;d`!4fx;!3NR=)c4efe4UAGlR`#$UJZH|MX;wIwg% zwGku=NDxg~4_LewMH%MoS3V=6z2-d%)%#J=8a>>CNqBXp9mcQuL-Ue$Kg_y(= zRF07kiN?@6y0JoBTr9SOqlIT&lB4xwUl)3eXo}b4lEb*TIQd6)&FWL1cX09CDjzir zs87qgHj`k-K%_FW z4kyWpp-O6gE|<FhV2rt@fc?dfym zJ7)cV;45rGn}LW{=I%Y`)|Ny4@3-#y}CI0`|J4cucJTb$A8X`F3+zo zzWq7>diC@3pCA7-ef;O_-*wBclTSatf4#0B|2#eTj{x%j&@KP(0P=t8mh1ZQKLOK*Fu818BA>HH^sJl0yVToV0%HZC>)XfTgU zSC!|rw5B)rysB+XZtS{dE|}W(=<0u%%d^VnYvWR0R`Q=EA5f+q9Br5$J2_68c}Hi(f#{|2Bhc5TEyN(nUKqSK}Y)^76kkmyBCaaAF~8BEhNG zG30CM!V{Q$EnPSRqOP$EhkxQVcDa@=VZQF}|7swIJKCoz$X-hqCt(SD=j$!-u2yz; zENq-_TRWLqIqKQ^np!wqGZzC>8y!PSbzL(BQ){LF-awXC)RB39k@{aA;`6PGmVd{p?j+^)>uAUYVt4OA~5m7 zvf*>opkKLxwX@6jX}z~qAN~O@;c{>D70`kUMq4D0vaC={qcQx!*DDbGh`x=n7_`)G z^kZmZAG%wo+gcE_Giuzb&fXl)yyd+%ACB+B~ttp3Q(UU2sny2qR0#Qu@8tC-CpS)*3o8$fy-qKpAhw)V>6lM%s-lZ>D0y- zI7xlpD^eh&!!crWHlZm*pZMuBW)thMF#%B5t%uyxve+2#O95=IoZbL?IdSw={C1?a zzZ|Rr`wwv8@NBuK_V)hwyVlgcjJQ;YuD~pRFZG;b0dWQ>FAaHYxve^))HqU`c~UI! zFW{nzwp|9&spD*(KLcgd12}U23xF{hOkSxuyCRQm+ovlQYK4j|0WUe~La}vQJXNAC zCj#62I#+8N^j4LaJ9pGc+ADz$C|n4~2&X@*%tezirRA5YeZlur4yIvy&xM6fCnUUu z1pMfoo(rq5{N*!?ByZZkkw0r9Z&)UFSVi;fQt3>1(nQ;rrA>gG)>f7EE&1&c75}mN zY+{Q)cs46_bJm4N`?Q}sW#i4uVj2nTfEu#}UupLpfjJ*l9kwf3{MxOi5PUX8bvU*M z>IP#|HDoJpc`AJ<{G&CIX6{HLjn@{~eEj%ph%J4)0%vky#zXo*=Ws=uVNdj!o3EGvEBaQRd*lA(I$;e z`<|p++^AYXKi7G({UXI0?SYI-I}=Z$3fKJVM+sj#V2iF*NlSQWbWZY80fyfp&nGAd zfKvoTgc|##XWbBu zUw0*5{#R$k#JUc8}obJ&HaCAVULQ#UBfKqX}4&5yK*;M_`CeD59YM*)!*44Z;gx zbs!BH;W2tdO-gFJlb{VSMuNMpiSo83k&6vp3 z>A|Vu(UPoom3FfH3_UN&F%GZ3GcWNYCKJM^* z18T^qHt(5<5UD^#xvof3rt$A86hZ`fhBx9zZO9^sJ+rYuKz!;5|7)_BMo%vCWdb_f zkgze{o!8UWX!~l_OPVjLj^`r0bdrzk5TkC!uC^$lAIA4S3na<#3!<-p(c66+L*Izi zs$T@_$MwR)+y%c2nvC|`NwZT`mUp@H7viz{zd7rYZ+TiTfYCQ3asg~1E zD9P@tUs{dT$n6K6!tFl3X8#yvz+mw`oE{TZkQ1@iz24V zSf8#`v6KgTSzX8U+yvCjiOHBI?sPP#xD9(Fdvt2!-ZT49#+H>4ToVx+8kXEsBm81AU* z^y*{6MC6^{t06h!9lM8GtLM>WXH(5gqdl;Yy?*Tr%9b8dqa*Z<%XNrxOCSBzQH=cM z29VM+z@GJM-u+(!m#pQ>9hr9_gWUfHT%e~B1ksca@0@h(={y^oPWunw!Wq|* z3us<$eYRfEnrl`99$gktePR$PwN{C#Pa_1bu*3@qYe|t^!*?-viR1O_sOYQ0w=9|7 z>MX4x9BGJI!~L4e-l8HRAFAJYCNr$qhyt;C^s|1#{#@Oi+(3zbCPZw6rgH_D5F?Qk zS0)-8u$iPsm?En9d{W6FLNW=zyR68}uwGLlnO!D~ljW`C~$Vh+@^#M58jVhoZV z--HX9uAYcRvoihNi2au4_yzQ9uvN%8y9GErRmI~F8Gms?8e$ErXoEm%jgEZNNq!^FvLs6Ch7QQGFV@+VOh%X!)Ox^nwf)h^X z0gm#a{1}2m0!C#%;x!CGX-^WQ*YVyuzpe|(-8z$Be9+mE^3KwyU2C70V_7jr)*$LIntBsJABdR-=Mj+iJ;a$>xKEMq7fQdt{uK+`( zl0Ztxs}XyX2Nfb32Z-yYN$Do-tB?q(kp1pSd-TYua*#!TKj6+05iuP0i-b&PR=TlI ziA5H!%+LE=6$|ml5*1(@*on9Ng7#IQS3N{9Q>vA9QswvRe54d4!_Q|$pVROIb@bGd zBlkz7lite!oY!9r*@;b$2-1(7%=v*t{=iHm5Os8atl3>$<4GVo^-=~1@}RCje0>C@l*??bn~24dp6=X`m4Vq6X0kstMZHJQ;!|c-U{9S%B2>sz zwc!I|>TnL`HJ7;62$F=_xS}gkvIu9Ac;HdW2VgFO8~!OH+|jIZzATVuMw$JU&8 zaX=?2b>TYi3AMnp5!lZo$|xBiHRAfbj`B?eNI-|(PCRK98xyEwz$;l`Q%4T${==CH zRpRKLJpR2->Gz|+bvlMi6U?>5k&7*SXO%vCgel}s7K XCxhE%JUrB;&<0R9jSE zO0Faq!Y&INU@SKM8SObos1>jC^;|Oq38=IcM-Gs?&p|=QI5Q@lL8Lx?w ztB@tFcokm}AdwzfSN5I|2JS7d63`ZWqU9z7!`fEfe^}vZT0UF*I;)_9WTT=3s_&}@ zpq*Jl#$FHG>NCi}M)g=c1%Q_qRldc=0qhkEE``K|Rf|xq6#@D@Tb3bPz?rGWiMXgQ zi!KRTlxtc;R8U=CQRB|_##6O&Ry4gmi}B#e^B-ASFWTsib*pksUlXBf370i>mdd!Bwn84)#3tYpP z0Fdq7E-Uf+&=%oggWL)NFwhQ}ffifS7LZHh%>+h+d;n9~A+z0R3vVqZYj|neK~h&g ze^sgeD3s1W6!?_D5OSl7OdZ-p0>AmY-CV2@I^7gs&`I3e_L-cYS`R*|k1&)+zR&I! z56lHN+HR|MFQ7U}>nK1S>M8PweLLXXo55)rXj$$V?SHExkv{DW^d?45ZY( zAhFjCp$s`$eIz(?P;VddfO|$7KA6yCQ}C7)*A|27ffn?Lt#ITq!g-hxaybB{V0Wy4 z@2qH-@(TA^K8F3c=Qg~7%yeM>xXUm{fkXk3uHQ)nYO=AH-qlB3jR9r~4C)Gi9rKV0 zQK!vD2N_|zxBt+`v7u+K{RAt3r_V4nu&#(4p=Zz%ztK;&(HXX)?X3XBUkPe9g^pPE zwwoOfgK;BX$8X6CdM)5BN?%57;3LMk$|QXiR8qlfB53O9%Xd58%nc>4#2*f2Yb3p5#Ft&S1^PB=P zkqyXn(5?9ZXL@uG?cZs;Oc~UTz*Oa;=-7z*Vx?(}^9hZ`8Me%FPdGgD2(;Hl~$PGo;5e-o3MwE|Ugg zO%}fI zTh(;?20-xP0{3*Sxyw9JZ*Pq1oXv4JDQY0zkVf$jjUx=s^rv=V`rQj(>em#sSVeeI zE~8{PEq%_rf?USr+y#*8yG+!ynb>^m@{$4*HM1|>o5Ohu(?yyMe0kC`jo8Xae>0Wo z5)ENxl`y=~aAkq8BGM3;RYW|W1k@a;H-+Hu+n4cI;WIRZE4GA7z=Msh`masjLmpaU(PCYYq{0;Cmb!vsD^5LGpM4FX~VLN!C2e*qx} z20ll`jxW&V3&>s8FZ)tA>Q%y6x4?w!hGHMVz3<%#yD7xBC^iaJjo<-QEp8s$Vn%BU z{u{*b1yBEvRJc``Sg|E5{7E=4CR%L#IaybD8|uF#PgoxD2WYfk;PBr9ZQzeq0iWaz zFIM>Dr!-&7*0zhbVbdRSLV^6xtD#q{h)DSkD#GdH)T#xRWm^AruuFG>?G|nFo-A&H zcH@&KsRwyr* za~*A7-MF{(^)_zHJDCOcw6a5K26X%t`s}j;s`$1cOUN3KoU}jH3DmFFvA#LFRd<|K zurF$QNYwiYwo%9-0`P=aR$O&7VO7XwH(6YdPsSoou2&BH?d+uJU8E^^zY~7Qe*;Vd zVz|SD;AEo#KV#wPreXX`V{H8P^$Baly1PT_f%;UZ?M6A>H{g~-vDT}%m*g}qP7P!y zkK_i9^1hUju$T7L0Oolg;P7wn^r*Z)dSg#^kc1U~m1t295I3`r5iZNxUv38;KaHTE zmFs52>K!9`%O5!b3dR7NBlUq}-Dw1+t}6Lfgoo|%xisz@Mctka>L&!(!1-~Z*Pt=s zu)W~Rbt61ADc~2yMzZHC#s{J0RU&|?F_57Q?@n1R3#F}i0AS@VGyNNsuD+>!15%Ao z?8T3Y4QbBoevtNFDqs1w%&k98d`G+LI8Ss^|N0wXaRqecUZPi8jvHiE4`}xtX5+L?b~}Mg_=pMnpx)jGl7-R8o5|gcyEXZO8EV!`cGyxu`N#| z&aUgn^=^}SnqSP)mCT4V4MRiynN=VAt8%C_J+dunR1^C?nJMJP+Y=3A)5@_Hvr?9n z7cvqGW~yhKeG1u>gjp93@bP}#=F?oa7%4G)rImZZS!{-tc}}}m!E+T?6zp)a8hW-P z;g(@~B}8uf-EVU+Nw8+&ob$l5o?gl9w&@8&kwG#|I5qp|c$gMmkq$~JlV5WtJoH@QrNMFB>)2)lEVS=-K zBPL7eRaIOku{X7m8btNU!~|rTfQ&$q5F@}H{P$pXsu2G&CP(e6l-*p6EoG*zOvW(l zwux@Yz-f^pVZ<(5+U3R>TQCo|z%)ujSZJ(pTRy0arlWGdgeC2abJ7i_b58HN)nHDmAys$gUBK>9nLwJYf0p$dpR>tmJ&M+Q z(Q-fb?mqHOE@O@X+Y*m!TL|JmZbf)wc)~(NsCSbe-h0BabM>0NNFsccGimG?VICg5In$ev8J7R8PM! z^h($7n5ESt)*Ml>&TEG#?Jny8VHK2?bCxOUUNvO>3-d$BndjPCnZ?UcHsi;M!KGa- zOXFdyGOfd73ZchU-H_1Z?t{xPR0o})&G&B3S61;8&)CHMqqF{0(icp6gl_dc#$0{Y zetmvC#<-xeF4;2;T)_MylKMxs64N*_Do31Cfk+!UEcA-A#*aZTnRs(A8vQDYE zKrLGOi0>5LfQ4vL9B(93Lzr4#vh`jL_23p9y=GNfTwPvMvFWJ(y#RJt7`F|SjBRBA!$Er^ zg%Lq5KR_0h*h*|5RQ)MQ|4u(6g%E@IyG>TJJ6BxT5s4fL?_vYTprV)WTp=P&zgTv1 z2hp%4c&n1yq(76^ZjcL^j&Tij;W{ApB$0X?8+}r zIyo(7Gr<|t%GGX3_b4T@00%u;#lqZ1z6Ts1D5!ojs2L>oX%}`BmT|vvnSS!zoS)(l zb2BOOMmVc`2Dr6ce|SOKi<>xap=DcdpG-WL6&%7=&Tr%V8O!acoeq_)(0*hy_a?`j zNyUO+KTgl0Fql?lz1(b7;zyx!fCYb9$L2V*1`+pG%@nm7&Zq4)F80m6BThV<_k zC$|p%tMg7KhugsHW!bk z@nHfHIYUYFYR$|%acx$sl9Pz6T4$No9IAY*mdr1@1J)|IMl`tN(+`+1)GxR2v}vtFz>bIgl#t@E?KKM5@-t1Z0}@E}<3l_s7( zt3c<@b24#JJHn35dygFlhZa?G45-bbETly|mJ{BYxzOI-XX4Vx?Geb#z)^cg&_F{{ zZRrf85=zvHBGGwm;I-%+$N6XsZ_7(7G&_MjOY<%VQ9Kf*k8}v$%*!u9$Iy^lSo}d4 z(wl$ko5?(rEUfdj-Um^k97~>$_t+$h9+1Yp$tFTsJleyKsB$5H5vw7upx2sXY-4bk z#mQWwz4=o;*C0WlkZ_Jj@Q3%s<#s+sW)YFw^SM)zO8H5sO(kolx$C%)%E;r}Cn=sr z><&2<2FQNnQYl{xx+*>O{w7#7zCKlI=bX+-vMl_e#k0bfjr%9aoIPU)jF(`N4 z`=qG<)l%KYHB0?2FL6VKBIqPRt!RtdxRTLs|7DWx^->zMHmS4CX;{(Kz2Yz4YPK&q z3TblCDhvqt-ALQgyXqaJ#~x4U$xJTXFBb)=I?>p`wQ_T7&V^5het|Yg34TtixWF53JuI+;q`(t{@fTiT zzW5p+(8qHx=!EslnVo7SsCPwc&6y#pQSAGxGSbk&)RvkZ;sQ*hHoF*EDd>nq5gR-8 z`f6puS5bOU_$@rUsS&y6kzjK5BhI(@Jda%c?2k77U;^clb2fabd2#Y9`mmproUs<< z_r3+^1u0az`Wxg@9MMlA?~M{i zz~bsuL_24J$#)PC?FQzxGLI{SE(l`5-42YYZV-$5a6eA!4q~i1-t_(Fd~`dM8{#)m z^#&R?S=CwxZFH-RAIAq08AtJK*71@x@+o9gMZV`=WDd)dT~BHzA&}LJYQ!G?Vk#b$ ziS$kUdXJn%fjP{X&h(y|xT_)@fP)z540e`|%u}lq$fd8K1nL3?t~#T@?EuCmjqLF6 z4gfVCiW3&f4Q_zYnL=ydml$w+Ml(;s2E<~PY4d$L)XuRhm+T#!MhF0AUi!Dtd>f>UlNKm4TLd=<850fS8xtFMyx`Z}Q z_l+Jvr%vnMm!8$=R^^zEFah-VtQKasg8aJo<$~IbYsuOJ4bDw1?D$&=`n|4j$F7J_ zv|f{vS)E20;LZdi2N=H@g7P)YDT@(%rR}9ih43Im4&em6Rv*=U^RR~^fT31mA z`sFm5>a+z6Xppr;I1hG%%D-I4k?%KW4fZJ=bl59s!&UUUaB35Tsr%}Bf%vdc7)-0K z--R{qp+s*&^=r=>O(ThM;R&n3kBT-ZW<(E< zaBWcS%nk5PI7Vk6)TA@3k@3ig=Q_c(qv{s{3Z)?>IkQ~A=t|fXIG4o(fVBmR0y;hbp+F6y5pgD+@Y^ z81KEOP$M)_QcA^)|=(fLPHOYB514po#uqs&&Y-EesF|oRYc; z#S!SC5Ju2T#R);ot}dV;-l1R%e9J>K;+p{t$v&5hu`cK2=dqv~{gEQFsb{=qdkPP` z#0WIHC|5g-tjKSFsc9*~Fe8|^hoaX7wt3VB$RYIF%JViTz*-*hy=1lkn zp7+yn6J907H3FLq{BJD6S*)`W0612PF-$6NDqt!}eU(mCyB`iU74JtQ=q45C@NL>d zD?>F9x;hC%hKhc-mxRgW=BdSVzrG}Mucp|k%su`%muvQi-X4xkBoXndw!L@x%d@%A zr6e3}BAYMpxZ;O7{gXvz(~5J1Hg@=N*>h4IhVQM-6#EEl#_;2k%`2rIAAg}$T}{z- zpAE*DtqptJK9?lBn(`1c)7br3dYmRZg($}i@NIAbWu2XpLsUe!*g3^`ylL6>)GDO9 zLFL6Fn(mK}DU1EZDfsn^gWWl?0|rAs7Lk4nBXrinIy$YaOB1b$1PbPpPnURH-Eg<c~$$fF{)#UXYro4s?-=9&c6y;TK>vI!&wzW#F8O?~9HV=G23i9XsXYzmTlHFZdRi=wYN77e{LEPZ9(a` zjQO@qq_-YuZkayZGIQE`DBaA$Nve>~DZ&FZ5lgOvg?fSz97JO{m$$H`}Fu zBn|u~OR5Z|Fw=(AVM07td7h+F`IVDC6D9k6C))1^`E?op%86?G zqN9fK84%*+zq?hlD)PF7%F8g?+lfkI^frn{?DvW4ttjxFPvqepGCbj!qm5@LNCs@x zb}hmQwM+C!EE&W}v>FM;m z$NPCOIOGeMIG%nNE{6XqJ=`CKif||NNe>SX`lb={4L-W{j2>Yw8(%;VP=WD&M}{spTQB&f^nRiq}7_G5m#A6e&UD+?ugip>H z=i%kg?|&uHFMb?d9&g`@(SLE#{o5G&)%WF#?`!AZH-3EI{PBI`==-8K{+bb`#grYyg=&|_*(Ru$NMpeVI{zr@krrf&?qx&KM4x|4E7v=T{{!5HqS3#@=vt55ZpEm9$s-*@a}7OHHBBSA2iCV@R9;2z z?=bo;7yXYg`v0pK75pz^wD!Ly(Z|3tUif`us*?o;z41h!;jD7TDUHIv2oh=bB8mpm z{zHuNLlS^j7s=($yIl`Sdzq~NM~u?(<-NDa7y8)8|6!)mwlj)N@2AU5NOeu9o~5*& z47|1>j`u;8RcalRW3=gL2m=y$G-#dt}AMQiF#S)zo6f@8?uNB($Nwe=4%8c@3h zVeles+6{UB_)9mwnPPI7$F4|7(90aPOVP!R$mfm;g*i_rhmwd#m=)BjJk&Y0iTPA# z$3CIZMpFV#17B{%=gkOId;u&^xcHc++}4QCkw+e5^WoSZ718@|22M=OZtzjm}%1ROCArr?nx& zx1g@z*ABeCe~MASYzVbfdbhAI-KL%D5}FI-A>FD4^^9ODT2QB>;30LVg1iBVM0z=H zKp^a)%we=s)QPGaXcL|Xo4Xd!aM5tV?Q~P#Qfl?*>XFc(PIC1QAIbWv9$);F^lnc; zeHvjpARhusv=ru|A|)$Ub+*BOQNOAxrlejPLr`uB%2KQUT&9woSiV=1Juf++^-R5F zM`g=^&QMK2KchQfnQC+ARRj?0=tOS_Bygt3J7VNkQ=srFe5_wzSdwew^ZcM19VB@t zhoU^{p=$N7(71TAR%v9SJnyy}q`1FqU1eD0ygZ9z&-+l_ciB-S_#NN=Q8R{b(pmo@ zdzYJ0)%7FjN4(f3P!yT3$AcN2S5rqP(-UELk$BQGkx!7eEsWVAbIt# zDgW}&@ioZCX9*$z-|sD=Qu0DYl-3ti-NcsJ$0I70fE_I#Cu1+$ zeJ8kxnpDrGYAA5c{4lQFhN z<|;Apc&Liv)I3#nd4Z3f{_%9p8{)>%MQ-qt+e=zw5UB9>D}H;9%tp&O`|KjV)JJF> z{6Ud<8s6S-la)71`=k4ZB^nfyq*G<_CNAEF$kQ`%UPIx+c!D5nGEQvq_ubN!hx_Cy z`k*tqV|~z-_}pQ_2AG7h36e~ioWEuEp)V3t(-baD&iRuY{VlGfjYz&qXpLJtL`e%| z>2|<-mPB$+!1Xn3)kv4A0#Ltgj`aQ!>nAohVsu?79TB<<-qN;(IBT{N&tt-kGLV|G z_DG|>4YtM6EOl(qC@?HcjIX*~TeoWr5|M{X@4pu=B-#j~o$V9-rA;E|)UFamYs5Fi zgvj$u3FDLKQezU*5(#w%Dc7rU95#lLd1&{_&mV{1Z7F0wNB1hJ^3VpM9@Crb^r|wS zAQ1;du{;s7>hdQE$i+f1_n%30Pq%9K72ZFS=$`~6Hhl|KR(JaTZ<6S@V$@0gG-EWT zM6y(8==r15%-O*b>Cb&bFa1xmR>?|bdv%6AGf%U3^-JYv`i6a)PIE9Zr3yPbBmVQJ zxfg?_O6Pspk)U6vf8dapsSxXq1~cD|TsJ6FO>z+{+&t!nb8o2PG>+=ZMXv>ZrmwMCR#9`07j(SmSue>P*x6Oug{H-nDJhsC zv>s=E6h_gCJMoZcdDKk$4C@*Rm*uNWi+ugIgN7lUJ9 z5ooN^sQ6vWi+t8!0=?#uLY4Og2|(Li2oTIt660=2x|cfh2Z(?QMWW>&SJL7t z-N0KRPa@b{miXD!Op1%?08$4Og)>G36Ok;4%%}Skt!>r& zg#*&tC~?8>*i7oS7GHA0WHEo+6Y}G#K;Ki4hS@=LAJPi3jqn~1&0FiXM zA({8X7I(_O!9h zE=13QEuu?bu0CZs|H7uRVf7`XO!En0#$AZ!W~tzvSnxxlYSp^zFnbsJK@vHg7c&aT z3bW7=>in}A>Jz7si`&gPh1Anp5@&cQzk~%nKqKv*xv|W66#}@d_GrT{wCIu6ui&vl z&Op%0rs>pM?#O5z6NksoaC^-&Fj9BRrl_LiU_?}vh0OL+#2iKU5AHE|bKQHQO?RZ) zyzQ-K1>(SAm~$i>JA#~5vqx%nEm|Te5(b_lyFv>ar@bg%HwP#M+xmiOrNmQO&bCHt z!l?LP4?p8peKaDG=+LMd`uv$=5in|jlXPB$`&YyV;Z=IBEtnt|o+xPGTSy}vRjmZRtTw#C;hDpqPO ztw^5V+DqSu-`vk!6LAy#(f-TuqJ!l(24U2)&M8c(Fd%;wy!4C?p~nCrBF9VuB-S$IKf!@Txj6_ z{%br-##S~O)bF4CDg=)(@XO1{AjPJyH!7$Oob3^8{^B1uLREyUqwmg(g5I3HBf;Q4 z77HLi8xl3r@<4@UK~x9CgwraN=VBDE&FKJTFtS%9Y1D%lC&cT0Dt{lh2mnBTp5Ko1*P0YX-YyuH3f_)clp;6z!`YA#`X!!lXO~>mkNN#7@puh4=-*k6)ry946i->>>*V? zhVn!V=nMnifCUsMDUC6#mhLP9Rg`g~G?8V9qtFmSNvb{fFnn>F%7>t|GT@;(>ApLt z7Da*2$wr-ob13%8;o=>8S=8;v-th^h$+A=%Q0}wSGt|~18+*SlYYqD|Y<}us5FhX(M zW^vq&yg2IokYi0y@(I3k719|aSSf*fJPLg1OIkUrCa}(bo=$j)rYWC|-#dfF=NsQ$ zd%`tF{MI%Ye~l%=SLBx%;{7P)ku*2MUhJws9IH;826i`L*%2n|<75*GqDlwd@e|q2 zv---Hw3ME}@`Z-2JZU>LM0PSc^7EV9Q^i-rDKb1M5i`V<-JnFUe?U=6m=@zR4N#8? zD8b#s!bQzq$9Dnt^s59B(J|3_Ln`HDYGNtC3k>=o2Fik_Nf{^T?*-v`Bwo5x_@2D8 z7bD$ur`&-7Ic>ubQj`&Lz#lSHs*Q@ZRq8Z=`w!ro>fs+!-$GU zDFb1!_ZaeM7*PzEa%nUuP6ZeMBg%(S>Y_mz8B|$&LDyw|s&F!&XK5Uq=`wI4tZkU( zXwZVYjio#37Bb^thU$W=hv#N;}TQt0r4 zRBub|#$;yau+wVBO%PX50a2=^4YMFeiU(X^X9yiF!TZ&{E!G=fGq zpEeUG3PY(54yCHXeO5(5y_XN3r>Myzy3=pvnn!dulIUOu?+1t?00!6tQSSEz9Y*>E zx|88k0WQlyQtSM*Arv-T6#LjU7JcT({2vG^5bkpfWs-dPmlF9g5-x_I?8u zv;=*R&q>+zt2FIghCvL(j^iSW1_YT1$*DD*%v`Bxeu_3eVoX>Nc%U{I-fM zs@O4w@Nv_vKh3F!Qd+I%%aFmU z5E))ksEZEDn>(UfMeW)eo!#N66L|Ymi+{n!|R(KnSm2F5LCNb zQ5FT*!uolit59yN0@yP1+4qC&!4wzn6bRVs!#6~tk0|(E8sE#{_g+yCRM$ELr)6tp z3Y28;O#_=Vp69H8O@BiopZS%8liEF098lrs!i2KZiQ{(ne**?(uO^$qVYsp|RyV`D z$cne2Fco(~Tz7vdFbGZJV#=I?Wq`@R{HZZMVk%l($WD1-JW(XU<2(Xlq<_zVtB$SK z7;&H}1`jgm{{s9He60cob(@gkv5Dad9{5MP>hgj*W*t-BOA=dU8^|&DIA(*yvvftQ zdL|{iN=z%CU-!5N7`P4Uq^sO|$lfupp0wm1%hhh*L4Aj8U6$+KkrhR$@;7ZL7D+3fx)2TBs_-!4Pp zQxR7T>U+891iFAOmEDp`&m{EkDS)txBR7udGdHH0Y{IFS(e}yFaVz?%?EWRP zv6h~COK`uP$7t4A#~lSwa3*0%%vk+qclaO!cPvx38|d0?ys2pHo$+`uma}hE0YpkZ zQN=Ta$41XO#1#_ID<5dYoHP6@n~BC6RDM07CZfllLzi(qnmLA+5CI7;O*WeY2-^o2 zVy1q2-F8HKTCxe5vI*e_Q)^sM;;QD}> ztQ=iwMfz6;pyC%yk8%j(0zo>8^SPn3Px8m~m&Vf)`pt6)KanjQn9gyDfFutY$PfES zAhRupIv$F2eb#JgZlGW=s5Ef#_-yW-$AB!~()-B?n}m6ywZS0l5K~+1l9wqv zTrLK$t&`wx@Wkl=$JVAGYiY+TO);zYg2bz<9BA!YICJP^UxEbK7*7wE71y`|OGYj&MVMY^>dkV6pL%LBUC$dy2B92542*7OEMG0d=hxb}2x zCGwM!#V|-gl-`St5n;3UhG!DLW|x3!*JQ2#^l;AscPDUcb}IH;R?+r5$P%o&8z|nM zV?$?q_-#*ZzsGaS#(38fXRWD?p+J=0^OIJF(t#uAeyaMn2e{w*e>2o6(pA`iZH5`b z-DbvY=p$~o25fW-0sC2=2MbElR*H1wLkB?416%RKtsw2uTg}=AvTI{_C(4NWePq{u z(EnIwc>f6$FG^=wL6UHUad`cm zwEepS)iJThp-KM8#^A9-(#qzb;BO^5?_9#;xRWPXPK=!R`dt1InfR83ku>oL?Qkv= z{|e|W1^s2)DWlq{CG5;Ne=}Ho-1p^~E!C+S)q1YvbO6NipQtG>f@(WKk;y9E#RvwHb0HW&>x3rr$njJl;}0SGMp{$dflZvB%_nY zg5FfjO^c5cDAPV4nt

1HYnu&cUbn9ps3;@F_Zbktxouh9LVi1 zRn?~@u=sa6j$aPJXS&~MUt>X+OH-iseSFA?DCgWKO1i*5esWV?nyejB9FHQDso=tE z>E|t7;n&s#r0p!QH@+jW%61m5w zBjkqt_=dK6kI;DM_2T7DCDZ&XP%)P7Bjqh1UBF5BM-rW!`Py?7i3%fTQwn7?URRI$ zZ%K5gF&@mYPIR|ygB{ZYCx{|m2-W7<*ld>`f%z~2v+2LYsMjtJ9G*t}?0up9q}7@fD9HMAG`(2$NPz)lNW@N1@M zvuv=!`D1RS_m3yaW+UZahF3;77hevbrN04dhDvZ49IGJ25N4#%QBBh~ zNH7HtNo#~qyG!1fFoC!_6^kUUG&%lTBW^Md-Dt1C zn8|nU0~;2S_z1&6aUI??$8mJLg24B$@f|`@x_p&g5(C|J1SI`24;2I?MSE|>=t-9X zuu-_>3@})Ga8FPbA&Wm!Kz+a9#PHtvX6;CD#noupSLtuZBI#Hs&wD(>dXqo!Pjsu=^o_X;?LvrTHJPuyodQ;weyzfD9t}i2>Riu8A6sd`;j+;Jy#g;Ul zAxx)ZSi5=#FbmH6@Pm`z2rtRpD(z`1H#K8^F$)}|<0?0$WJWq0Th(30sipCJDBn1X z_w!=pC=)tH*uK1Y&SGR;*D|h!M%ySVE{B{)aZl>=lh>b__(`d2pbS)A9-9pdW>Y}( zB9B_sn*z(5;>Pu&U)nOHQsX8M3??dsD>*6H{G|#)*;L&e<3P2ITTbHi+SV#Bc}$9+ zBTaJLt|apryayJCh$m?gsa`B_LLqKam)9|s+){cfr1vGUMkam*BcVxe*eYw%aEHEN5{0Z&f~Ze(SeNwn+L+t;ex<(JA|fF zMqw3ocC$yX8udc~q!u1hScX8}ve5ou2rd7acm2v^tj~KbZ``AmRYd9zgPv{-CJyjz z?AbHV)L=KG=nst{nc0O*Bfk`imibEnKB=htSw33~ZoTor*UtPO|4@zB`F;|7zWaKE zT=#KVO&YN>N)gD+!Q(Lu6Y)b*b9}q!(D7pa6%yxqx#;K~P-Go*K2phQ2K>dL1+x2G zMOEs;ZMOpbCW9oD7UHSN(%z=+Q3etT(EeiVRuN?cV&h`C>G55NiS-iirIrbiHj^4n zncn04VYbPC^4^xL`?OscgbZhfK+Zwc=Sg-ntqsBqBy1 zK~`0bza5+yLUPkCnKAl^nQ*Su2Ls`eTg=~!)28KmPsDW6Nli^G*M}m2@@&8eA?m)& z2Ly4vB%#qNHp!W2IY-UMgNRpTS~?Hgp3)wIBZO4N2P}bNq|xZxfc=T+BrK7anr!gr zEIs-m{cFfC#$FZ;`;5fmk}xj#rY$pomfsjVl0HNBgh{7BRoURdvsr@DB3+kE%~VGr zVjfC)Wr;#D`dU1YACBha*|57|5h31MxXMvEy`4{2ny}zxth{tW6{;$i%a1@^+9yH5 zu!t3d)RAin7xi?^FChLf4b_~}Pbf>`L5Ms1Y5GBvc+NOUMYPq}3dRwr4UXSs{F;PZ z4~UPuv!Y}A0;*)#yQ)NaZjw0_*{Db0&b45p5P-rpXRNZub(fh%eCsihcEz%Na*#=!LJLrsZ!<)k( z#piAJX-*AIGIUtTyng>mh~+EJF+UO2G?jZ2aovvMD8CE;L&7>y?1JaP+JR=(y}6TX z8AZIg@?c1!EqU!uD;LQp&EGni7kGsCaSt)!X_@P_jVU}FagoO2iIynslQN!2k!ZyZ zJGRn3g@=dCv2XRM*jXHzCm6AwI#yPRhJ1w1w4aPT@%E9t(L5*}!*5Z%669{SYAo|8 zBFk#wbmKS+IXpoR^-y6(Clj6_#snd05AKZ!3~KmI&+FW;nLGDCIIs_;10+!gPu*k- zxyD#d)u#gzG$Pau2Exn=cr~;N(>uqv8++(^ZW3_gdu3j40m`B$mJRU3##0)+O7xZz zE<+o|t6b_mFx#u~qnSl6i~u&TR#%(z`I)ao4VC3%PhU7fCO&AABBKkJ#z)gVxa8c- zyICHFlu2>DR?@zYvD=LlHUO{6O4hKATgBC)L;M)+g5L=w2(Wr3F&FD%_e7@rr0&*O2B)Y8~2`)Cm`6SVhqiFz}Db7bWeA!QgS$sl|aQI zYk0zhOGH)Rf&E8W^`hh0%4gimuVfHfa=}cQ(HhdyqKJjakjBW}CGN1!`@<{bKbtq$ z1gI&W6!I1vRcu%t*lIOy5UctfD+GdbIR+z>ObqB9P-nE|C~kI6)8N$r=5C_5<5GA1 zS<54bi#<$SrQTs_vv*hz?yt0}6d17X=lL4q?Y((EO?0yQr0ARp8+Z!0p;z`Kz=R!d zPxXkJeqG9Kv1}CX?q;QO(Z>HZXVG+4>wXidQrc(~dC>AlAgfOJyD1yR+b|gQkI1}y zF3~W-NK6E-RfI53vs+cf>f>ZPu4vX-vS{s$V;n_i8bC!S-wh4mcM#es2PT!3MjW(9F;SExY+#; z+0M_P7WhSHERLw!AfA+C2!tSbb)XfQ2kGUkkMLDabZ1jBRTE=W7Xv7DP9WAEM7hH| zg)tx7XS;-DRgo$hJo>7Pj9q+gZF0#7Edt=aJ0xmXeRH)%pCC#=SWYSi207?h+NVTX zsAs5<(Rl%AGCL+2<2+Q!rtl)eYrAwMRIQ#&a$Dp<9zL0Stdu)q_mwhC1?_T68yVg5;HIv>2y2>;1yPVE4gr z53iPT1%S31`4b*;n`{!&=6>HnJXnQRmVRuQFrY+|vf6PV7NrXt3C%lLxX*~zLm+xQ+sP{Qlu~h+DNL0sc)IZ=yO&4@g^_x7jKu(M&HBQq zsxtfzbv^KCUzc#KVgMphKh8D)@Jg7Z7N}IQh~q@2gujPqd)!w#YCsB!!P+SRdyxj= z>H`&<9jm0Q=?bij#-xn_h;A~n9op!%NrehYLw_=*S9^d(Ns8B!l*4HKXj{^6Jc9VI z`!lKxVUyuFV8QEtJQ@OEmv+}W=*t&Qqn293&cSeyN`({}Z_%?L&vqzkv~3+Qf`Sdl z!(y%in%4*MZZ;uvQG~DXV{r3fsIrkS5F#SQ0iIi1O3*xTP<4kZ5;Zvbx$KWeU33&f z^2FU5e90n`qY-1F2s!4+)QtSb=FL+#P2j`6HPLPi=a4 z_3Tgu7v)Q)PXz)dg|A2V7yCn)8R5PWrUEfg1u{5HV#E%)hGU53XfnwiFsWCscvHm_ zb&1}P&1+LPh;yERn8HGu3LgtZ$)x~DS=qkr-A`ux|>%P5n5(Z>35(fVw`GVC z_Xj|4D453C%!)TAl0bLUfpYHvXnAI)Fk~X4U^w(vGsbxum8W@R7r*DPVKrqYVy)K_ zG8BoKG=(EHHR9~&^j(L>>jpcQlBS|?W@-U!4lVKcB69bT=4Of}!Bqn!Dh3d<=v|5Y zD@3gWU8L)jQP-rxQNTqfW+8gnGK30RX~ z)KFD*SvY>2fv4l}{?NYJ<@6OHBWIn95iu9p>i?WHK=6X8ba6UO3X$IZFvlP|95Z{2 zc=$&vAlGaJ7p?c%G@8L5lxHkc%QLSdY#BT{LW5K)_6B4Xr=#uWS~e|j4z!0HlqwaX z^2lhe0exj3C(Ca}ZM+pYd8Q|Jhpx(|t51WQi_O^-5OnSf@Vbd{q{Yu&rkWpSxn{7U zMUx@d_Gk;M*$cg!(MO(77vQ7)8Ep4&c}uMnIpPH<$Wp654B^TKkeN~_5T?kzZn+WA z9$m7`m72l#!kMNcEn`i1l(ICPV+9`_(Iaca(u5&;3I2fQw=ReP##$#K*8~x~%U{-d z%cPctQIkeEgx0LhBNuFuzSC6%33)#(3khH$P#h!1E>|2v=<3pzNEA&*%{7cdWyeaTC@ zS)T5VAT2~f>M-dRxx~;@OLN|{W^D0^JZ84&vly(#tgC~YYiJX;r1pW z{aW=0$H_d3+o#%T35RL3P2Ag@^0wpF)|Vd|OmOXq_KO)D&MgOT`}f|Cnm-9z0-6UU z?3fDDKGo}h`4DuoPmL(rB%9YJQ51ns*Kx$R!P}cxOA|5r_ERp)C$|STh;0{k1TJh{ zlZen54O=>03K7`+ggfrc2fzygfNk-maq#6{wz#9b2CeL*s9St$kdz;BJ6d0q z>LT_5K;k$Pym#)$u7-#2VsAKi5hc4@e!EdUyS*gaw`Xlm;sZ{(MbM+&)z?*#^lWO3 z^9i5S-rlE9@!9hfSF$6YPAhTI5x18Aw3i)3OE$fi%TAT_b1#n~!7DsrknUUIaDryP zLy^-r9=pAWvW1e==LK2c-cKi%HGHdR0EJC|`$Pe{~1pN19Ip6U+<$N`!Z3dcVB{KwVZ)3P_=|czPxB#K_sU zBm4lN5>|~N?}HvVwypHW9SrdS`ig)Ds8AeP+lLKLuD1>*d~m%4{)n)c%)`MO-`+e` ze1ZNHrvDzmLI^a5y}&-reStn24@P|qc7Bl|pe(k0Xmqi;JnSlA`x4FkG9L#=SKuXl z_Hgsz(f-4!`vS@n^DlzCkG_|fvj}{3lwB3J-MXT4!#w<+q^*jt9e&aod?Ni_Yx>|v z!*^DF)rSJgip~VuqV~OQ-*I|hv9X4pybgCrCvpdc`Gv#J=rP1vrfg?0JAtn!4&kIQ zJHQOa%B+(~EFAbflzbUO_2jYC0sK5Q{65Ho`k6k@n7%KJ?A0-IDZsbkn6(n{ zed?I~{FsCI1k7;4$$!EnbHc54!ef5I`|O18%?W?Ri9p(kVCjj_=aW0VC&Du)B0DFd z=O=fGPsJEc#raRM5;CXvv>NW9q-rfrYn)%#_`a@2yp}9ImH&KtzxPyO=G5#?&W>i3 z(p^#&eo_bnsp`t9n%0@R`I*MEGtD<=S~Ah6`9P`J@LkJ^bVkB9E>g|1GGP$0nox9a zu-8vUFdUUrx*B5Yo~!pqq=Z@!wo+Wx>Ni5d-W;2i8 zirTx_9WH^oi#^wmqC7Ez!@P^N39&r*V%CQt&*&XZO2)=`oA<(FcPI7M7bvq6G5|vBi~4KgfBdQr!T|^@6HpRse>fXLxvs)A#Ti2N zCei|51xfgk;i~8^pp@9V*8UuhxO({xQ2O;PnCA+P&W8g=h35IGZLe2S-QX7&?JKPv z%7_dmK%w~gLIR>QEudrMDxxX?E|&RLm(Wk@CK~5~#_n|=HXs6U(?gADoB@P932Z40 z2=NV6ezBvnL-I0GEK{irzl!s6{#Db$UBsdh!wcnz_iqr;)ej!Kf$KAt&F=ucX+f~5 z%YFVwei}c6ZE+_)2eFU<{#oJe_&+z*KmXHIU;p?s#CvP1FHR3Gj<^11)n~`Mx2*c& z`{pgH{vT6)xc={^`gnhJ|7iD5Q@uC;cZm1r*4VA7KKRpA&z`K!|ASQz|5f4r|76t* zn@b~G3w{3p)x-ZgsQyb+Pt6RkOn0tKwl7b1EKj!2O%2XY4%{Yqm&d;To#0&1$ovw)cE5!RBrus{3RmIo;4ytRa zD*gqkQU4WGm;Mc^|Hw(p{vS{cd*2XP-r)ZysIKuUs`1FL`b$&a#&`ds)Qj+cQtFgj zN)5CAyS$5tjEcBj;lXf3wAG*4-4ct0A{aa*APD~Nx@~#@a=a{1R{DyLWEmyI!%p|A_DM-1c`pZdVMq=RY;| z+kf8L0W*s;{Q_e=*h6WaYJ` zBZ&9(aaTHZWn+cfNkacL)ie~by7lj;K3LQ~U&?gPykoc4XhZw+xsbWtW@x>T^UsQf z&+Z%jIj(ft?ExLyATQjRi8&3TsfuE~zbd?1R%T*bkT!fyS3Nzkvd&7Sr%cy{ezq1- z&#jE<0YdANk$jw)oVzmXpdNfG&P`cnjImVdvC#5R^XFG3sVTYavOcTM@hVX)UW?E# zovR(;WIP(kLDV#!x!U!_n4i%DB5y2~-Kb6ByA)x4wD65r<5V6}t0~^EMacj3;&gwf zzip$=JcN$+iR!295_bJ@DuOHFe0TRbWw4@PIZh1L+MU*P*#hA(iH=Ox9{zg=7m3k zCW(YOk0!~~+w((SHIPuf2Ml4qK$&u_ej#&RV|}>Ps^WB!c^&$fNM`O7u5Z<7z6BQ_ z@>t_3ix27RGw%uOg<>*+KbRTyodPemLyF!{@-!$j-OggzEy-FbK}ZlB=uS>+Ly;a% z%rpgA^OLS^13l$OUvYLAo)o#yHF0N>Bt$1wb<7GtA195MCv{c{gz`fOh%1hJUQx+| zY$WF|kMyWMJHCPdxkGzY0}lO1A2r)Y(5pN6mzwmozxP^9B%`Ed?U3;lJ{x^)a8E*& z$$WBJ)*o+ZyokbZ)5^j%mfJ=xIMeH_oTRTJNtUl^vL7+8WCb2`F8!EZPcTQ8kYMF^ zJvPlkul~lcDzz2bOtXjm_;UruzjXrXVm|AyvG@UeqozW(Y!Xb$BriBD9-CgL6%@g8 zv7IfGGNu_$GgGUsQnCILBu@x&U((=FlXxKA3t;sT=*ejU&A=|nTFR@P zE{0bMy$$S@*C&HAuaNwUber|3ljg5lk8#+OPkt=E`F?Z08gcjc1){z~`f|6l^0ytV ze(UEiOz&On_1VlT?9IhaCHD9A`FAW9hb#|=SQ~}MjDZ34^Y9qZC?a_b92ApBz^~m7 ze1r*R9LytY=C--HPhi^(T@rrpVWYpVaO@V-HJ zvj0`#1z{t!ySVPL`v(sG+IV$aPDuOMLqwz)(kC)u;NcyZ_<4lO&h+=7u@>|yvg-J9A8eeN2YmpQqI49(0~NbBsUSj)mex(HA}3d zh@3LNt8Rpl2xEGIj^cC;1O(6q>)ByWphU;-RZ&7@)xe1gLMrEc%|!ErA~WzSUTp_G zG{a}yo)QulmrQkn0XWJOOri)ds4PT^&Xp@iXdI}hUxJbi3Ce^#K8i&#cg|ut)n880 zB9w`#=ks;dt6#hpfSic4qRytkbe-wX1=sN~j$Ys{)nYYK-Gm(=PZLm%>Iv*lM_olh zPWcaE9eMfb8fr)KCQE{bY#}lS3NOy{j9eY>`%srSGw_=AC!Zz~t&nu}H*>)Nhk$t` zR>IME9YZQikV20_`-D{H<%lKT2cgn|<&=?b{#=p@ih-V-@3tx&>BfUs-8{d<3>2uK z?SNmXF2IyZ$^73J5*W@UQU{IkBaCAt*{@^+?|je>dZ)j+zIB$MVOVoI&&b4c=duqP zSCd?-za{kevfpC3CiU~+mgw8d0b7dN^j`gKiLA>(XTy8ZK^O<=4;fhh2NxdMEBZU~ z3zx&b!?n5RgF8xBmm@HWx;$coT~(G}qX@&g0*0YoO^#^1XZkEaSrE>xlNWl3YR46| zR&Nu7FmlQ+6B%OgMZk6w*%Vxap=;aQUsOoNw10rOp{=~KxHvV#^~UyxIM!EHQ^WV+ zVh;~p+3~LUc@U;8x-Rl>vpWMwR->xqpl%KvguKqj<@OBXahiE+pj|L=b-l#l^Y55h z#p<}XTIO2xJmC2baHsMG_=O#GVNs6YXWaTlq6f5*^LzMbqTlT@cJ8-PTd@eml7wJ3 z=R)>PfTwYP>?_uSx8PknMuJCNP)qmEcKpDL<|z#2IYlVTJ{Hi+P9aX|f^eXEz8bEe zs_607d~uzqddz{h<~ZamfQ4gzPgVUBJhG!1yjXU-e<}dLRn|D(iUGS{*{FHBfp@FSA`G+bezFD#z;EI-N}mfARquCK-4?yLF+dX%TkEH5>*v>mjfH|OI;r*h#bJZ zS}+>H+!l8RU{n30)KIr@B5zP8!)v;dJ@vHEbw^TQ>3Tu5YeY@`D9>-IOU2Kh}8Efku2!NC=uTO!`yvEH5KUlzK0MXKms!) z0i=f_ML??b5_<2wCNZ|sl_s*&gm0@nJ04r8$I3a-590AhmxtGCp> zhpz?Hkt}Q!h4ENe!z&^}(9d>q`o8&!Q zb=i&`!cH;tk$OWF@ahf%tp$OONUues5jXT!4(Wsf71{%`%1U+84uf(+eQYT;s7cHu z0L4N_2|P6x|Aj8YpV_EKon(#NMNqa9L(-ij!txIA{7QWTLUpl9S-$!heDrwUo$^&- zXlEs5?zLMbA`j0baRn&OVp**#sU|B)BHSr|3kF0c2j8C|?GXh0fe>;+zU%ujH$~pt zPF5(pr^5k)_clRgm84FqWG8}@a%V5EY3R8id0B%ndyU7oAUOyP`#Scl8XXB5$63sf zCfEY)wx&D30(x^{Xn1%wCzK@?@uG@;M#7UUlN9gIPF4xQv%Vm$3I!j5C&wu9mC+y% z$~%f6JV8t+YmE5|5?Mju8m4l#8}+@Q|A^M^vg3Mj9I#Is4i|bnl?)J?QI&4MHt-6e z<#Z%OLZDqi$~Tqt8|{d*F^&$ppl+wvd|)>d34oUexJrK3NdO|vdh^&k33BxOjs_qN z_((Mh%e=DbtRyD#pp?PJ5oN_Oev7j)C5uab+o|tPvc~+Gj*~hY!9q<@dHftQ=RY(> zC4HFG3A_#AhU&2b$GwRCo#@WWw;Dx>yq<3A$6=kBY{`XTI13<&6d@!5NMv&r>y!J& zhMlrr|5=YWR$)?&32_*z#Y_@hCgol`qIovrlUJg7gO5w^8`yKVPkq3<`%ftm=!<-6 zQ+6mT}%v~EQMPX3r91U ze&ce}$Y6HJfD$si#@bm`XIO8)J>#av5c8gXbBwjsFtOw~*X*iuo5)r}BBq}A>MvVGWdoKsLlRnpWDBhM*%;%Me2jM#kaZSo1#dHrW3lq)@ zL5Y!_`Z3l*1>xgRKbImM&%zeFT#!dWrlx{kD$2WwLFF*GpBqT^E+z=dGsEO{`WJ-| z=2u%Ph|K3bu`3D5%4upUQSmIS^`^VjC?(=3wj?ZQHYjM20Px(9G(aEi2O>gykuE;NMB)+SZ-QX{JnrK-4b}@ zQgKF9zBEZez@V^AkNOo>GLTBQE>%ukB0ouv3U>isyU?ATSE`&+v|)?#!>h!mDu}8o zJUz%L2uqnG_gOHIlWJ zAqEwsYlVsnifn(2I~B@3$7_fQt2H9zPG&*|eIw|EEk2o?*ANlX}sM}hA-7VUx z^SZ;pT8K2Wt}Afe(_OBqeP~zf&Y;|Pj^yzHtpC#Jh3AtAeSB^uJL4@YKIni=lQW}0 z8B&yhs%ktu0?EcJL!}i1eSoXq3`x?Bqe`{LM>T*t9o*_VwcFSSA}>OJp!8_`Qd5uC zYWgNj;}H9S3RCUwQS$`dSgs{!@)wD3Vv9&?9_eaQ!_zmOvyc8|{>%t_-#8mJm z^*BOUT-{T`GP1bhK_3CvxC{`6)MH$=8?Ob-QqVT1wK6J+kGQs3n5F}StwRa*kdDUP zJ+6B~31R3@0-%Ny3dM$IhK%MI$2=!>&m8%W+8Q|CI9(VLV_UL+uuGcK>*NiJuw`-xm^o3&k)Z(D`vcJ~s+HyAlUc8Vm3x8Uj2!ALMWja}W)`^4_K?>r&Q##x$8jwnp@G>J&T(yEZ5U~B0gP%R z4_yXV(h;rc2$#QriFFAQ{#oT{ps;0BIIdj{Q?!Ndhh}wYqKD2H1?x&tN%H_kdaQq< zSGJ=UX)tOM*X?09(5cW*KJrm+n5+2$@j@H$_Z=5q`#j)FQ|U(c8#=*9Sf@fb2Fn_K z>M<&d9RO90bK_+ZIv29Uvheitaj_Ah3qClXAKj2Iz~4d0=QeI_=HApk*DmipWm`CtT)e~&Wq0|adV z-jQ0{18UeprN`3j6ZljJdWJl1k_tVU-3o|50(?7khE0z!3L3Xun=T09TeA(j9a9@&R%|n=Q6bg7f%f`Ex8je`Uo#V z@OJaWcI9R=1&irRaO{#GW|%r_#5``s`#nJGz8ED1PqJCu=7+}}AbfQeEjkvH`Qee* z=DU>|8dY@Vw?ed5vJ91bH?r7T29z%~L73r1Hi*Tg*R6z$$2P@?wMB$3!g++6Gy|a4 zL5;!S`y)We(g4d9@Gug=MY(Eju#UnGT`{dQ!8iC{18J8CiVV7v13-#-1;8#Z@c|6q z*U*1Aq(|54cM-w#Yaq0NkZYsIVY+aYl)>UNuzIw(+UCkMU~QVHDui}{Mk z+SbDCI7b8TY!ILH=a&5%Oee^Fdd2f zB}<*s_BHAe=dZLoN#%&LWw=6VK~_d5vSSPZ-+n&CSh9?4)kV+>%z@BbVuT0awH-0^ zR~trZC@4UUu;-btZmsWG)xOI3ca+^;;uYd-xq5sf#U$$obJa09-tJf&bAlAwwTSx`&PVwY zHNaoBCtwiNuK+b;I3kJJWU)KpB|PD8R^dK@HxV8qJicoap0Z=NOva}u3BNh*(_XHT z{qeV;KvM>={X(J-PIYNH$F2Aq4QrEbi5O1236U{EZ?>;$M&VfXsoj3C zP3s}0Vpdy!!0%qcZ-t)-bo?|YyaJ;y$;SJ^oKSnsk zt*b^e$-WlFY1wkbQY0iPrxn{OwveHIyRs~+*Y8tALh z9S|EhCwh$X2!cOEfw-!vitNDQ6}jVW4E&10g0H^4BNpG>|8z{U87ur0qR7!5R&FHl ziL9h6Hp}R);<)mS$>Ykpjj>cAK@kXVPVGfNwl4RQarKi=jHJTH>YN=VLhTIix?TIQ z-a&?ytg_)p&1hN|{XEhVa1EzeHFcpzB3M~qxHcDw8yw~Jb*{b6?7HXON@CAP-?MB| z(UG?iuHg{%xDesJgAYdMj0Kpwg^R0Dxa4QuX30ZVDq!eq4RxqAk2(Lg;9Lw7mxsp3 zllT@zO+o}Nxs6QhsX0w89!AyGNLdY17mZ(Ki|U24`Gw`0h3dFft-FcF%#rA-C3#M3Aj%dlNj>ZxR@_s!xlI$1gHT~ul^9zC?T7ZIt>(GTK8YauO9ho-$fIDKz_ zatRP3v)8bXo@;#gaPlSdEWK-`k@d-L513v7bo5#o_~*eDco6 z&hX7ATY{c9@s}suSN&g_4&M|e|4oky|Fhr6VPE8mUOK#cy!|lt2sU=-bS^S-M+r_y zPAcv){(O8zhPl7u8-(%QbD7vBCv1C}5JDcxfNvbPFZfKLa z?A{j-afopxsI_y}RRVsK5n=m8*dP>!U95&TgSi_sjJ$SYcVwfSbxL*N?}Y@hwn|}O zJ2o1kgz&e@Lby{+NQL#Wj1YMNuCt$nI@myvex@SImd*YTFKLVPukEOnSbOoi60w56 zj`)3*2Ra2C;Ecx)-IOW9e?ZCT#<03{PkdRZTg}zry79s>;IPTvc(rJ2TMe_I0fg)g zI&GRKtUHz&OlFcdGy*nVjl=X%42H5H{ElyPJ2+TL4Pm+gJMa38Cr@pkYB}h3$CIoj zD*;A;b{qZ)YZ^35C~ZKFRUjxzD|J=VxKSr)NB?1m;u=Vy!Iy#K z%)Z@J8uQ9fWy^bevWSzEeVUN2uFM2>=2G;^*6~;ENfas0RQyhs;m)?1g-LNzqCFlC zP_E%2%lUb63ntrq;z@;(=Jk|pBFKHTKbv?D&o>c zI#14CXY|-E!3K_=<3ExsrF5D4iIY-!2{=sXilujrb->fbks@k$VVe4N^9(8E%Fo4^ zN-Tff$o3WB$peQuS$2R4V7Nqj!q~ll;p?|{P32-W?>$Z9#4i)4-NnU!3GF^77}RA_ zv*A5ZqjyPv6v{am_^47#rlMS*FqqhJ;mtZyY>)IE5e%GJZZK;qTIc zFfZAmmS>bI(|^HhRd>cw)SCc$@;-YwX7%))PhFY2<5a>b{paGrI#?wydHRqdZIkQ` z0_15&x^zX%Id2dz(*cGQ5a+mT{J2dS*57)cjZs96J z`zigExox*=tkhPb!kJZx7VF=Y%ygCJUUr^9qxktSZXL%8cSwvDWw$A;MpL4pI5vy!W&c3vlduOD`Snq zKaKH=Cpit57%(V8On~hjI0nRdC0;+(7*!-ZT^1Xno?B8AbwfqS78ihdD)j{~9AnPT z5IZWMG(8S>*k64O^|vB!zUjntUnPx`Jlv9pagILZo6t=Y#q5&xjhV-0gs&g>`?EZK zFc@U26WMBRv_s&WbavL)yTDg~0GZRjS^j1V=VuE)WJe>*)TLprFI0q-}NL(9*j70P3Y6Cu86B-L;L zarMS(mf{A(JxJ?b)bb_o3m9}xRMQvG$AYB<-J?IbW5-DBWY4%9+>?pwv=qlA8}`B#+VF^}w<@2PAX0>6zN$B{p{2fk{8eAkHBPl#~u>8amcyy|Vq zLOr~$BFVuLj7$;VG{kb6_>=hc&1eaD;Xf9qHhHe54@ybkL2e@yBbf9?NuA}-T{zE5mTU04yc znzlP8e>g^aOr&s*P_P@jepG#21jQ`Hf7-+e2k3u<1chxNLR5XqZl499=<3U&%D2fIOR)}QzmB7UEv){+ZHtYT4r zJ1$b&_k}ZDD?8Y<155%tLo%rh&MA4DV^$P$w<9_efsPiV_qR5K@H(ralW7o6jwslE zO!ZNR@O~{>5P|MaH5;EI@>FCa72e|9!dO+=N}wd|Ne0&r&}|6eZRyknWDPbtfR1(` zPDyzm0(S^xP`)iD)5&3kv8xoB@b4nN;MGpYeBS`;I(2_pSGsdrqbUlpXvyIag?v)# z0rqosxD~5vLT&~1$S_1*-NF&zuzI)T z;9}nM+*&O0Rq#E9<8`B&?C^w}Z71_P)Rez&V z8FwlchQzVV_DAja%Mg7E%Ir_ryq+_Rq)SoOL~2ka^nd7Adbh8nYb1F`LOp6Th;A=R zA4y4pfMk~rylU3iJRC@{?&@^acps$EvRWD1LS=-6Xlf1mS!>#vV?XQ%r3Q+YAVVUj z2H3O*1{F}93&mx=VR?+Pw;MXV_JfKpgzrNM0zC(U_@cn+aUY*)*#r$?&p?kaKo6|N ztT}Km7u8?wN8Ppon6 zsXYtn+iH2c%_zIrK^c(QbHbW5nW!6(shgam(z6dMON=Aq8Tl@X`>`mI)55>j|M7@A zWL;S=h(WvAzT-zF)sam6&b6p2)NA(XxZ1BQPwd!Z=Q1wVA#5G!WWWACD@C}aIlM1L zBcmrYs0*o6`qe!K<1F6y9eoflOt~~@y`f7pF9|QxCgO)&%H&I}=^#1#@JhJFG>$(( z;|vGvs2+nG7y83ZV@zdo^AiTFoD*zf6YP$-&0>8HN5iLf<2QpRR^tq?vlLg66SsOM z_*8mGWIy^&P2A3VTW_c<$T{ipYC>3L5^p@7$D=cO$0SMQ`J{vnN`eu`nKUUK9RIg_ zQg#avkkynUo>D*=)8vd}#EdD!GN@&zRIbgn!;~5^C6bT;VGDg=?mrzgrJV<%21p;N zQ!wt5vD-%8v*p$iGg&(%leCRAiY+jDKK*%*3}Xw`fOMMGnPB~;g8ik6BEs$g{`XJ> zTDFlg1T*(qr|mg$=1#%5{>Ef45S_oNwQZ!7|BQ=@se`O^Aa`8AtVz627}`1TUaP-@ zZ6pJ?DdBZiXv?%@heB~DOxzY~3-Px!`QlAnmQe`q^$!xM{qp(|lE~cuzHKD;s@WSc z^JMo#1_@BFAPGt4m%w22xBBdOC0nSL*DS7QHp!L*8yq6;G#yDi7tc+&z|a>fW|0IL zOE9qzteH%DKKCwoE;(r~C2uaZZZ557E`56L{nlK@&$$o8^O>mmEYA6CvH2X8`COCv zJjeO`=ko=@^My(CMS1hZb@L@X^QF`CWn1$FtsrP!K*fP&2Vg~57r;ZeP;0VK=eY3k z`9eL@t*`ylwXq9Lg;q@sR(1VW4O; zt|BPjS4LsRZOu7AiuDSvXAPFmr1-`f*yD%FX;{1g4|QaM=$VVLaxV#Dt>q_4rXSfL z>}>8B1iP!F#^2i<7cb$l4NE!}rZagIBCE|yOj%#}ky9w>me}1nNt=M!B{jR{c7Nh_ z!QgFJ+(@34Fst~}8uB4dM4e!8X~W%poe#beizf4n!(uDHp0E54UO7uz`IEPDUbphM zXXRpg<#KD~s!n?8=RLaj%kK`C39dSJ#BAAAZ0*Kuge77<)R99rkTn|!^=k9*bV#Gl z>admV_z3AU5pm*_WnXiu!AH0hFJkg#+s}Kpq51%}eF-;4vT3t6?P?daDo*!+B8nBu zEGKQ?1?eucqZEJ;=tA_E0s;%~;t1B!57yXTK=kS$hJt~-dcRFjD&7 z`}}WP7_O%&e=Q0>a)i{I2h!4Pbh2**12!Un4cT3Yp8KMQ!p5Dux+qng+w?ywyg=i6 zaOHjZnM8kre=)+Ye`AD1piunz@ztNBt3QWVXNQ+(N0(=Z7ytP2L=yzZt^+)MY(8So<%A@Y}T^Jo%4?aP!{{;qSGcYeTrdGV)JDxW2Qwvc2&? z*I5@f7eD{s4dKlHXb9W>PeVA``d`;!e{>f z%(0f6NV_??Jam41|ADKmy|az&gUma^|73(wqIa%~tR@zAMrQX6&F&hS-qkg`uWxLv zZSapMtLk->Rl^XYq9QC2s-MfxqT3nCk1?4#H2h%lb@<-Anp6xCUTr=C&042!6N;|?m}dP4 zBP2^&p9-w|SDLl?XQn82#W;H8PAvNzb~8JRsqkmnQnS~|?$VIiT2u3f^ZXn6Wff~( zIK-{HjBzHIWU8Vld+}lB<|pbb88u%f7ZsB;PU`-edK@++9yDplFu?QLJ;9B_P`%_u(@D|st73cYmWHDZBLkt$i-bCbk6=BPDLVK$rXN-&KkTOer(KB1*$Ce~ zI`*u?tvbqEZM3cR?{DR~qDu>}RsB>tjX}?6rI&!3fN&2y_>WNG zMzjp|^oLLw>;Vu0imSg~rJ;6M$6Rjh#JWn9seMT#Wjc%Vq^RNs;#AL*_20?I^Fp&>Dy?f+V>=6XbABua4)z~#tas3U&N;P>Nu&8$ke&P1rC8VePVhR$P&hYB=Yu+aqc90#L;gi! zUNX@okQ#f#L8FWYxmMIoqve*4GAKrPmS(cu#gx1t9WQ~BX~dSajLY-sEDF{I@98%&!@POZ`(e|Fj+Xb0a|4JJ#u`gNCn z*TKLXWuX12!@KviL%eFp@5#0dn;iO&>X#B0AAEWA(#VR-fnR6$9Pdyk=gO7%OMy=> zmruDw)pfF=OS`5<+w)fU_oYO$??!&~viz}9*^V0}8k^kZ2qzvfIxi*0Z;1Fi1-C?_ zJb9g$$JQ`8;S41xjlein;@7YB-Mbvz{v3AG-rN7w%XQ5Nd*4iK)ntp@zC4{WYq{sw zeqwg{Yw_hhzDUwP`^N>Iy2JDYxCYXjuP*6P3Y36EIURsiD?9;xub7vJM;ld+$!(E z1Ed?Od3c78GDg9xndafgDY2Pw9`@e`8`|CC(2w9^Ta7_dS1=Foj^~v184`EXX8vZszyNPBJ*wY%6vKd}Q7-1hd{C|HnhMab&8k-B zRo-z1kUFF6E8KfI@lM&98WUX4s9p6$j5ToSVhqkEu1bS9;Ll!glnV>-QH8yl3EELD zn4s3gc+Klz3y&T#Gwe=-n-gT19f~+Sc#V@ZO@bBP27gnamApQW^5gJCuRGCAAUns# z@d9oN7F+vjGi%&GDv7iLk9d_eE#p=wIU359AWAA;^lV`QYS{M{U+#Q~CGs0e83XS< zqrb1?W~uB>M40;+L0x9IB;wUXUaUyo74BP^g#PNdEjR^4yqF)YgF#kR4Q=qJl4b|RcWBAjru3H`d zZg}(N*G&k=^`3l!I5D-^tN)P^)}($J-oDfP2S4H-eWG)d^?xzK&|`ul8Cwv~h6T>^ z*U1M`7*Y!H4@T&D4_qdLfOd_A_hwOL3&+5u*%*)La@a`X{lS~8G~X*pB`*$X)YL3P z6MEC6&N4$iWTKGQFWdCm<5cq;nZ(}|^yram7NyDOQ}OwqG3_<=pPx$+){NNqxl22tT-NqI*P!+evo7xDUm3de$x77#FK zANZ~-+IB?u!k3PowNKW;8j*kiZ;@)WgWKIh^k#X;P2+25R{NJAVbM|_YV4&b5NPr_Y zDG*Dg3X2j09_Zg^RhMLwxNGfTNfJlqk`%z?VT?gj{#KxTl}Ml`2>T9DEx41U&p1mf zc=4^i5w8kJ54NN3pb$z%h;pO&+;4bil1#Z%1&BW;17Q1yR4T~`b@Th48^S&9{<;mw zDchU2M2L`3&tCvJ*n{LpJH)ylu>AtRCvkUgOiDn63`7V`pZ2g9gzec@#6;cv=LaT_D8)(&Y~#f>S-_1`rCA;R<1VnZQ#aWa7Gtcc!P<^H8yEyDopS zH)nL~LXvbx>Q!s%_)||1A@joy((OuXQus?zENGvAg1;S<4^X+{a2o`KA%dZGPsx4Q zIezN{N@!hTY`Ex0QbumTYb?B01=x#YU-f@PR}E{~fzKzsqKG36PMv|54 zVJyMWSs1Y9Rv}FB)&B{TeU!*Y(s*0ob%TMLn$V0QjGd5h-wcR02vx>B9dzCJlwXY{&!T)jP7Q)bfwLsoUfH)EV!?!o+(vZdML;y6F9se4!@%llo^(}4 z@_k9duRfzd>wFcALVt5eY)?dB<3aFfGA!DK7CGfEVY@-TrynZDL(A_@;{A#w|B%Z2 z5DYzHSrtN#SH|3V4ro~T(@uGmXOXT7-oJ0eQXNN9cOBLCq8fL%l*|ezIwC$-fW68j znHZx=rVV1815Pqw&hC)w16X0}`DV2D6MAq>;;pzzm% zl^OZRu1hx@I%6|0B{Qg-kSP7Ee8qUWa9^UvEZXkyeWfgBO-y5^T(N#8yCtTkQI0+} zTi`tVvL;*5+l8}OjzlU40B1`y<-8P$)f&hN{6#?=2UQqUU~`e{V+FvLxn#(!4JA@g zRifBnZs1#T<0b`?rrgc0P$D>)nWcifrrd!f;LZxv9p-^Ov$yQ?NY-+lb{`m>=Nn9A zN37+8>3B@uCXHO0BTQp$tHbZv*Fe*;VH;Q161&;@5Y zt@DDZRQZ6W68pF!TvqW)v3!p=s^7Z^ge?w57k2QLehrr&*F=SD0uNK^W~3@q9Eu}5 z%0mY$L^sPoabOVur$RKJLevMjEXovJbzuTt@$6(i3h z>!`JDmiav>bHDlHG<&(pS}nG|d+So@umS zrGb;Qwx+Gt5tmQT6Y7lNtwd{W;w7JWIO<+@)a+vlK)xa!dq|UJIzReq((y(zH-Rfx zvFG$U zNn6z&;)CK$>#@8*_zd>wqU$N_x_4dZBFVe#Wl$SKNRmasgO3K=L~AYG{bZ57qy)hD zmI0V%t*WyA)gB*4l0fn+bN1{^>Y z)LFeI=zg;cWZ__WEcu{)^`K28t?XjIR>vn|%s^>6B6%NSJ=k_%vFp-jNE<%jm@^of z)z@Ci+9(4I@S)mTfREb9IY@h-H8P!#=03C!=`kX^RxvL#B0^YgnAPcp8AR-%ruRp3 zj|c3tI=Lc7!=Bcubd(=LyIYY+ESJD77~I4S2=gtfS7^U|03V7(9LvBZqv+5FfWi`dWWUvqacYJF z_1BkCNfyxKhnro(FRZ5ZVG0o!0LS5USNk-$s@U_q5&6e#Es)w3}sGD_8dn^>$P_qlH)t4b|jslf7T`Y0S*9NgWYJzwVpwb2UfsH)=s;f(c13y3_fU1+t zC9hf*uPO^z{Kzk`riESattv=|!C6Lu>$+O)!dj@`mi+iId~FLu*ddy=bO*kiaBE9T zPG&+DZYu}C%MnRZ8$(0)$rZOB(bGJkgqJa_OA+&O4RF76w%N1eRXCYiy+i3~iO zqCPzgRXmD-EyGnt5zV@Q!E40(QQ%%l{bVNJY8K4(Ww)x(E_7`NbF|JE)k(QFpIJ#mB$G2@ibWmHp@6IN*CrBirUf z$QouuIpe4(8hXG7SGx-wj;@_W7a0pxUoOKLWip70Mq;Gk`^)=D3z`Fukpv~QTHbp) zaa*#OEzDY5S9I;ZEr;(|i?+cb)7p3B+L7$qF;eIVfP^zr{-@@{SM7LC{yR){fIMn8|0nasE8+Y z4_V+EpDPLvf9ZjK`FhMTk6#oluGBqKpM ziv4bPvcbmxVuWCx!$m=lxo#N4jejsg7Q(ts9CTYdRg8(b<_5L7ZicMi6_{RVL@5v+ zL0YU-eS z$K8q6=cjK!ihcd1Z6n?9+|@Lx%5YjWw|%{`wO!=xqprEP^hw;+Ph@2D_1enI2Htc@ z_mab|VPb))kg)Fj{zISg_DEqu-WELbe%brx$6cdxka~vDOr=7f1Fp>nJH<+A^9&xAo01|F-&y!2q+(c-&ay3ZI-Yc)X141zYbmqU z`QaxP5yO}Q!nE#*Vy~Mm0vZ%G;K>3o);n6chSANr&o09^hA!&$5l_G1*Y3!nKM#tZ zh)Y>9*z4gaBTMMgkgms?@^~tkj$8}x6v99aQz9&&` zRvS2ecppC2FlOv*?j#@oYhEWM3U}iP{qbp*%=2keqk9Fyi1Jxp$8QsV}rA6uEou#1Gjm(?hOsa z`QE_o-e`1)hf|5DeV9#(*pJo@y}cW9x7^uzETZ;z)?>bUlC;-k^x{)r-uaHWGl-ac zGZbS%S~X_$F8cM)vUG<0der2`{n9_-HucXWNI?eIW(}3stI(D#n|nK?@fm;FZiHye z42*qM_q(tR8S*~)a>-@)MT@>HVFI#@x7di(;+{8@zr?@1_mH~lu&(;nLmn$r5vl9B@nT**0o1z{bbyEl zn1tI?GPz@Vi~LDhKypI&18=-EoWaCFE*y1t6cenZ zz(JrYo7?Ou+8dGhVD;O+>Ob5ZMk2stH`8;sRSdafRiO^)EE?oSsmF1?qEA?74?`6) zgh$*zs_MK68ek?eN?v=u8IJELFwwQpOHDLl{dx*fr0I-}EmV33GU!vddCVCg2Tvy& z|LWI5mKHwhkdjE)ql6Lik2WMt;Un{>P&k4*4WkJX?3PsTr{*QRMOv~Jl3-?RjlP{$ zu?wsQamkF6Wj*aA{@%g-+C?hX$FQeB=KZMdwT1)~>NFHMi}i!&$#TjczWwp1SRun@ zS`D^(158M45rHJobucNh+UnNgd^XMiJ3%k*YbZ=NG0_3t^aiu8u2*E#v@O$>in6=5 zmcb)BWkQwsW{|&es9n@UiPb6r%Pu?EEsKMoqz4?9YmNm(*c$R~`g9ck>zUP=t{0#> z|8WjA#)uF3Dh?5S2%M#12@`>X9qUYCFU1S#6utnCn$+oC*R7`uk=@jaH*A*N(G>o* zx-;~du_d0w_GZyYnns)r^p=?6!dEuciup${0_|9%J#WI+rv?elik+r2E=eVG2b)MH zP|I(ra5lpcGcnPzl>^)9N^2dy=bmXTxzuOqD1Ucb?ri@W%kn15kL32v3{zP&VjT&R zw?kB*)ZvUBwSR<Z+AfSpUnd)4z=Es$oH3T8O&CYR2!gf=d(H2Es7w=?7t1a z5JKO?_nUW+$90?sl`FrdP`RnU=F3An7+jhZ@}tJMLGbrrU=hxT-wcNEmE;;T(MTZ8 zx#uYPWmu(Hoj}oLP5dP2lVVeilJzTg0a{wV=lR+ymin;yKQv>6C&J3+7az!H&c?*U z2kD)DM?z%0-32W?orIS-zEf@th{RRotx=;$WddKA(uk=gGQtIJhxBDz{?x8bcga-d zBwyRRRfd_^#UIW~f(B0hY*Lfh#7OZz8~q}pZs|ri@?g^Z{)xif8%R-m39>K0Jd9-& zoQASe=U|wpYK;7J@}G<5JyN>rN7iXIV&;f;d;1I6g(n9JQ&_`7>YXmx9?siHtWXN2 zr{U$FKF;k))7Xrna8*6|QRGEJvN%d>dt(_0dgCCY5ESz;RMa(%&v(7^BuQ0%w6@p>#j1vbnC9Wo&>cIWIQHjc~s_+&DMZ)>Bmfar_{SD6yp`{Ps-<*>q z?AB|xD!1Jv7d!f+a!g6bE}y$NV5G9JB$u#XE8R{+iKQ@J{TaWl#Qv>3jLO&$*^)|P zO7{k`{X1x&TwC!l@QKC?N?R9-3e&>O!c(6gl!$xy(A6%lRx=^tv0`85(_2Tw_o4y3 z+|1MUr8|#Ed7G$DLl~VpYMraStQ=ay@eU*(KecKmcK>vtn^^%r3VlPs0-s;Noxq&! zPU~}WdGzKhS@NI%4n5sxE4p`qA81vmR%mu@n6CR_=Az7tm&Q6V;}7d&30PYRd~WIX z*Kc>>E;nGz5mJI0$#^R&PP-D)F1wi-AQxIo;Y^4|2Tq@d#2DDade^*@a%~u!~K4J)yLG7`fq6 zwrBrw_F0TSwe&$IO|+}>z#)`JhL6wTBW)zEEg>p*xAQkEGHAYg^DwejN>G4r)zLD(p$` zOScBEsrPSk>LVfY%b7HF{X%ROH@v6R>^J(tYWf~ROKsh8pS0AwSNrgD!_iO}CDD2xQZmepoX;Qvyf%_WDWihH{2elVg`nP!b=lRCm&7~Ae94xZ# z51UlP;mGORBkmVM2yHc&3weTCVnZ$l{h(SQ?74-4pq8EBT5GL&{q{GW@EN@6E&Hy>@9>2U^h3#?dP@65kSn%R zD2{0_(<$=_$&IC}dY?;#O{s@hf?FB_YjdLs!+JUGVre{e@ZlV^?_5>G^@&^D16Oll z4)Z#?e@C`2$OsOJTev~*_F?iTT4)c=uT!H~bJeI>g~Ia>{)?kWjF9q0N*bY?S~qZ` z9G`#f;}{cLvHFU?b3gN86pEk4cw)8A3KM-xKZixi&TYb2t*I4m4BT3zO*?3K)h?kCK;hKPK0vLTP?T)1y`yzZXA-J=3k8|BUog zBMu(FQO6Sys7K#3ey>RndpKwq-@>@0dovOOloeF$=(0u)70i!E3+r(_pCF^2;CkP` zwO>J-GyyP*v$am}2WKI+CT{z^FFZ{;1y2euG4YE{;zj-5%XR9DJ)aa0HiGp)A|ofI z@>1yS^`xhbvau-8(xm)SqOGf;0_PO^6-<pvs%*BodF#D{gl?D zILe+WomM!oIi)ueFCAg5&uOv@N$+HxG&C_eb3)l#Pn*HW+zFc7$4W?pr>!30ni8Tu zbWh)%j_y63wpAgEF>kE_X6!G?`uD^yL|+S!kxAr=wYh!qki4FD>C;UcD!$rZe{L`4W*y_-y3M>uH?x z$rt}tW-RAyfY@xH%50FyY_Q{O$n)9I;8|SKEIur6HoR^&qGvX8dNyinHu~pm4Dnnn zYA%j*E?#UdL1iw{WG=~Z?(M%Ap+)va>Oi5zK*L;5|6IqcMSF5U%KwEC_CVYfB1JPv zUL-?T=}4SoBcV4)+{cKD{6u6Gf+x(Ol?+5K5LjOt)We*#3PoMagnNDl&W_-2ctm}D zY35RB)nXHGaz@Yo8}~|54~3;sPRJuCDVq_T z36A?k<=t<=m|Z54y%9k6(9+Z&_hU6CTHog6r{ZbdawiI6^N93!YgRia>Y>-q=c2map>zn_1k*Z-rw{)5tB z|GIPZ^)tm3_s$W>{rZ~zR$u?a6xh|)@K=3({B`R8MERBc zxAb~l&FgYEGSNCg9E}r&| zZux48f3bczjdK?-xn8hyrhtCd7cDI>IGbN^GO@5TFtzyu^fR!;=$W6_F;lW}{_mil z>>r@tU#y>|l*0K_a_7WlHU47#D4^dTl;6KI1t$Jm#IGVp+>hoPefkB8DKL7HVhY3? zWod+iv{U|@DR4`wh*_W|8xzInP~)FP{+lT<-zfVrxoGgLHN_Oz{|DlC5#C?&^`)&! z`eiw`M0ZpvCUC4jmV0{gKM=ob-+JES#EpS4((TueFU~VaIt|uWEceLLGo^>U;vxAL z@wNBgNpXG^Rim~Y%KnK}SE*bo^{eP9*BabC&IE1z;R0u>md(u<>!w7lfvb;R=Gwrd zSC)J4OWuC`PGS!?#XxhW{_Q~r|H%25G1Cr|)cPd*n-(@x$u`aSw!&Sb64V*v*hRbdH7#aNk2y*9CW@5UGaVhpGoI^fmRL0Pp& z(^yo!(>WUh9q^IN7D~Jh`F=4;l7?Q7d>4`d9g$L8yNHr{CqX-KjR7LDLNLCmLgbRS zOwWx|d_@Ej>297uCde0yVK3SA)d5jVrWdh3hFTNZ4|E=Qtv!(*&zwQSS&Y;S=BgGpc4J!>ysH%>v5NN;eYugx$obvU4(r=X_F$r&PD_N^d65J2 zsMeo62F1L?`dpMhSkuA|>quyY%WrL!c-%NK+|rVjS7g+3+FD_F!C=_8s!6NHDz3c@ z-ynlKL>5s&WWn+Xu1WvNtn*s^=xak%5+L;n<;N# zQ$qz0wv8M{z3yw!yQmXt=f7^hE^(N#n|{fx`D2vvtB4L$V)zSh7Lp4*y~Kl|<_D#| z-m%V~2N6)WtXAN>L@0u(COpNWS*+Rngu>OyxA?LhlJa>(+{86`JW9U|2Y=VaI!B>& zd^NqQJ1dP5EN-8*bR~5%lj$>PYc#hXdjo@dQ!CF0pwdHMrkp>B1j=3M>mtP1T3KI| zQ+;#bqB+jNgPg3=wdK))Yzvt=jP0JN6MDd=rQ~M$_%HqAd|mFQ&0W^X+Xr7U{>-V+!oAVP_raolI^5E*|&Kq@Aih)u&%2 zT&^V6F-$H6Ka%m)q%SP{xsP#7AE7L*soJly{whz{d+D8+rt(l>rC()#r!RTx#miW> zB9`P!u*1{Th3A4uSzk9P5M=M`)l;jCP!0Lu z1Qj8Y&&rDzL2XpA#3tiUooQXR*;*m&D33eLr>+L;%k6w)xC1SfNWi;~9zbgbQL$-V zN2GH!!Trwxy^N?$r_=5?QebNm%8y*I`;f}m3k%!UVB(67vQ^HFq-6Az^MKZ*vxJ3S zvC8Jr#MS;>ra*_l%+bfs`@#DpSEzvSzQ45=8p5-v+j;6E%w6-U_DO2GU4ObASiEF% zozMxmV;<4>UEQ4^Zf0HKFH^@$bXB|whbF-k6P`=cM@0=2A(L4O^UzQl-GAWyh-N*Ot$r3z@=An<;Q^42?NApg9ZPKYa1CUP$Te# zAr31>Qz1-$y2h=PGqIjp;#!chKySFgy}2KRoh^^|xmf*fucG09Yi!-lsPT zIa&%tU$O~3JGcO~U^S|p=j&844iwipJqRSSX&3ByJ-~QA8LwfDQsFr+zqe|oaIyYI zc6&NPmL*ausdT9h&@9%*3Nto50@)SXaU&H--FR|5w_#S-I5qU? zR@3qPZc1JAy6NYTDJ)Hah9i{0`SV?UTE=t15pRwSGR0Uy;1duvLqtxD7&L6*PC7=e z(hP0RGs*}Zkfdo?fIm6yYog7_E3 zwQ1(^Zaf$pS=H=I;S-#5jf&9XPi?z=HnJ^H^t(d}=9%FcOKyv}XgxGfj=sb#8S0zX zwCUJJ!+#H;fdE(;h!cws+rgN_cy%ouj)!n6bJQPRnc_1cK)!w7^e z&O#3^_}f!lIn5YxiQ{XTmPOgDc=7#!?*m^J`Q=X=Nc}+4;;`@4B&K_W((-;xyq4Qq z>(w{KxF1JCZ!W*uoBniLhVX&z8M?xm?&RAm)X1%@Y0;tEce(Oq2m^h01(#(rr3fHc->!J;0XYwVq(Wese2X?$M7M)Bun;k~ zeh)+)K_d=;JtHLJBAi!lFt5Xz(Fo!hB$F+0;TsT5yvZj-P3ewvssOj^aFjeREuM8# zEYf}D#tQ)nI20)f<=x6q6_I71yut7TBb`HFGSr6~d)z*G7{yl~r9TpNPDM}rjFj_> z$Y?8?^732Vqg;=Ks4K{v`)EYM?%ggbh8+Ua5*9LI6~k)_e(E)V99slbj3SSf(!r%e}%h5Nl;(vnT3$8l<#?fBEcxU!%JXZ0Z zz6sP289=%8$*6=oM5gr|vo0#y$q1$|vWzma!2B*#;}KKWE>mP3^9q$mKGgLRn=1%M zOSi~aa>TJryka7V2;HUILL(~KY2E#k-JL_~ph@je{2OIw5H&TrJHamiK4Qt34`Mh% zbGq&_iH(JBE?6UxNwjiFMGxG&oay5rLC+>!H{7EcaL5BJW8EY(von7P!5E@>k5im! zV=Q!ekB*M08c)Tz@5~wE5C4p1S|ZEPxImT(OsnOP0|Vfzr_amacqkE)N6;v^2+-3r zn#nuZhyY!zNWYT}<_R*q@lG8`Gf=!vqby(UE8*s&X7HaKryBV52@72OsgZI$X!GY zHVQ;kwaO2k!blWindB`M?dW|oB7FVy0cAFeNq`r*8$%Xhd9?h1Micx4&8Uh7&y_Qg zZrtfAhn(clg*3QzVeWt`K$T>~FEk+D4!@p8g|JI~pXqaj3_sj_pQri}w^8$))-(d!5;5!4DiZf0?mYm?=pGp=1$td zrX>KjX_@m29x5W4=q)!<)hA&bdNOf>p@0_)*Zs+*Gc1`*V_0rpQI=(DA%n@wg8mE? zxHT_=DGwVp5rI3Q&pD+AFt;IAa_GYS5t~#zs{TyYUKtg3`S!&=>3B1l!bfb60Tv@* z-dTFx4SqfVahZ;VzL@E?c$n>N_&$MYg#cA5qWR&^ApST{@)Y1I%e{U=fSwTtJY*58 z1#}{+fS8xhk~pB4^Fn%&JFQpzp|?*%c@l+z3?(c6+BlVK?*s3@uyW*jJ5a8~$R`>N zq{*6C@4hUG@)!2c_i*!vD&7$3@okYck&T2T3Pa|xmd=9L;v5))Xe3j@3&4PoM}GV>qgtc;(*s*?Ewixt+kNX zKWAQBrN7`Ehc#@z245;S0GC6alta^tL2|DdLUq3XC>OMS-L+7T>coRxo-#L8@LbY9 z?$@MI2cFDSh+d>*k&}c=bjIy9@1lX1gi0gDN>*zqO>QdaBo{Bss3YE_`O3aTb>K#k z3Q+sKYB=tR&VV+@c9nAg&466BR%rG4piI^Rs$r@cbN0%vh$^FNHTSBk2o#7q!dJaA+O$WTJbeo6KWWpqJ3N!T2Tq1 zhCL0{&KN+650qy&u~#%Ts#Vwd5o?oib=8U5ktL{CA+=r3b*zaz;Z03)Ixw#BMwBF= zc&&LQwqi&f@JOs0mh^j64&1oZA{^b|lv_U&YT$R$gc>q#p%ZNQaI9A!+8P;M)yBy7 zZh#$*1$;_cMOLafw%KkmHiWt~IvT#YZQUG}+ek0h^qayChXKi#+HeI;w_IA2iLDGK znqU*uN=b3jNV6+9Nv5;hBDWcgYm9NJ8Zid=N=e?G4T&R_5Ms5ciQe2LSW6R!=rv$$ zw*7J^X-D&sax2K`!T4@$Lon0D@1{Lz0QN^c_ zl$5qU59*6rGZfhxy4YrwC3jXZ6$oe%jPAISB!{o-{w&&UB+!*Q(){fSaC)b^EK(&K zpM=0QTewsYxKwE+^{891HB2GjAG7YC2=vhAwudhE(o^?E4~nbS_QX(=?kDLEt028z zHuzCD#su_`B!M4K`mXLX94rupNNwh%PEE^>7bZU5J^+?yfM_*fK!Sb{*?Oq&jIHvZ>;48=&0L!76DfH8g{_-{b<%r zV0_IG(7EqGP7@-l;mGlWz-}|g($26s^)L+1_AQD1Zq^8&BXINQh$Zo@en2f%IFIKX z@LP&?Q)<*&vqGqpRi%jxKUpMOX!bCTj9`%!EFVXWsRvAmZ3s=WgC?bpKJsg4>~aOY zS;Y{XG|m-0V#KSe;LF~e1&n5~c4Q-z*{o-WChVmFyA~8Soc(7Q z`(yuM&$FsJuTa;1)mppM#rW59YD^j7#tlhROfF+~0h4Dahcla1@8gtlz?7;$Z-Q%G zQj7G(q4SZvWIEi)FZFlsd1I>K?D`J-IdKlNEQ{}VZA-q zG4kxan|b8Rg+Z2)dC=bEMmA6N5c|+} z7mRw61xE%GM-_74AO1pqNMc`^C-Dl5vyf((0!B-JX3(8mU|oDC;#kE(z0fc4LA_#* zKKBFjZ{`oCEMvULx*^p1S(YasnO}u2@egYq%rpNs1*Bwsb zib-QHA=076N&0d+`=&#cZ*Prxp0f%lfn#c!OE(!YrEpMruAq z(R^aV`~v#bsRh*6XsO?_WTi#@Tn$D}G9j0YD(2|}R-n|qbjU^29wnN~9LC3@R>t8y z%*=6V_4wpfm#yhcSKIPE8PvH?z=d$p7HQy?8F0}I=-Jswb=r`jrjFo6KK$5dlDp1? zTc;iAApYK9AuegkEkkfymU0_r643wm-Bv3ftc3k1O)kQe0UESm9Z2J zeC%J|Z2pAYd-{oXZ%5Ulkw2hQ?kox?!(v$mti1wGWOfdo0`r6CUEU)z?y{6S?LvsV zQX|dy6uB$}k|6adD=ApNUNjGy zo7XU6MN}!UfOGN{-}v`_P@-pyp8)~MZz^)HUtRC`(I!G@0Aj6JE}us(bN41#%u`wX zTT|fQ>g$rN%thvCgOmx4r#g>r2qojXLs+*3ifk1wr&+%b3eH#9OISg`Sr4F_guS^zs)Hc%D!wXX1T+BIKi<59)i%*>$n}<@EHB0 zzV3^>u#&vw@cf*3)%1zTG)Qbh)SxLBjtdPqf$%w~_!q2Vv!i3ue8{UE*^*(KBmTMT z6R$4!I9WfdZ{lr%+!)>$Ti>Bo2pzO``W5o^Efm-Hr-s&L@oOA#~9?Rdy2wlhqA$d$4vsfpXLg7V$V%dHwt`RP(=NHrdm_%!M# z4XJRzVBj=U~(#OFKFZlaXDHmvcaG(+64^HFIgduN{5|gK#F%${C4_B~OCeB5HeKW)nZu8UvE;t(E7Mk6ROGEocaV*@#*)=00-bVf zkYc<6HkyRw8-4D}lKgkT#<^<;?!h@Bn}f<9V$Dy*p>x14LbQdN&9ar1@7KcH(%vB|u4Q^pwn8twK>AXUg$nB%R;G$I z4zYpVAH7k#`JX9AJpzH(!BND%@8?#huv%1Stz#r z9*v#;2abMjk$0HREb-dk-S`_xQrFcFV+U?A4kzS6{HkMQcr)@%-ROo76P-_3j}Ak= zZG4*Hsc*DcwqkjT_Rkc6E=A+--F4z~M=*5usIsaa7q53J<$BciU47yKZf6tN>54nQ z(Hs8*lQX*fCjQ(kr~LC1*90nOD(ZT~9odcuIvr=4x{5a6Fd-b1#)879krWzha^z8H z$`@>8(@9VI%(vwJ_}T2 zeyJ06-kML_I+sW8RsoGS7W9Ne@Kkj5GT%_!6~4pzo~s%{-1mOw|2V4ep{Imjd`puN za)M7jb3Ts;?mYGnE0Rs028e<2?=fWRUd)5n=+8~U-jjIV*F4ESG?pv6wQNQWZa2^i z3vSA7i+#9=w2bF>R&;WH~&)!u#4tlvn{UfJn4 z&lEGyE44yD2@=zIXQOeKZ|xB`C$oQq9X6J&;~5Q3M9ib1I9T~Wnz++DVkyBYuGcB) zRw;g-{}jQMrjmmt##UGR2hV)cN9nIRSfNC%$_yI!0-A<3{zT$XI->f;dEI2yWO?44 z_bV^DJjKu-48=0ol*Au24{P!YPJGBR6F8bPILi6~z=D(n^yekS5-XC`lx~)stMJxm zTOBy#2ru!-fZCd$n!GMMQRwfRXp_C15v>$`D;WOVVg2RUeZ7v-h_i5$S$U2`@!GQ| z_jGqmr#tIir&DgyAa`s{?O{PY%9RoUK6pL5Y%;TsBX_jqbG9^c9J#~5KrKyoUtrR8 zW4Y|vulV31BVxWLN`~N$H;IWd%ilPxD!mC+cK|bSboC1EOz$XP6_%U(0X94C9KOWp z%JJ~GUKahk%SIuIvwduxm2?3t`nBcnunuL7g}F$Xjd4h1Ygc`GHNyQvqM)+R19-*k zYpf_Ik&83R>dllvi$_E zR8T$a6@D5Sqm7IZIR8%2t=ZuIKBmxE_MJG~b{lra+x^+Ww;r1Brys443LBE+0jKVT zOj<3gj9t%oZ-f!mDH8y;%qe3!3eMi4T7Q(+TL)=){p=bGj)e)#Emc&RClGlhR?)C^ zB1ukTi*;%yWm6Y0rZJ+AbVw>(S1DM?- zP3)#vIpuUb-Kadsec;D3L)ml%3VOfn#ea$P4rRevsd^*K22`lgm{`*<3+vPM9O$hL!^dCeZ#-L}9z{cyhc8@b444%F4W|%KtnwW1UINoj z_tt?KQa0`vxXx5^er!LR299(SVg(WEeN`%*-QVgCL;95bHlPn>J;H>j2)C3AT6SYx z!9Y?&jiwE+qI0H(i1=$24xhWs-KRvC&bihF-%eo$N4uimk-rT`$sj`#DyqT!YOYjR znrKGwCJ#ZS?b(;1<6^^Yi;FO-2<)M&?N2J_I_v=B8A$atFqK+eV?TR}BP;!c8b2LF z(fI*zYaPdWKwKzIn{05>iG2^V;j#!EG>Qvq`M4_`GFL$z-GMyC%5|hP&Y8AR2W>{5 zuS0}o4mI_3uv76A{ot>_mA<}7^Q9PaR(Bz)qhpZI`y(lIQ(gNcpQC_pbJf1#S>S7e zLD!{kJ*T0`3kUs$N|#?mAQQo0OmBpon(&lYHg0jF*0muJEpUj@+Dc@tF;y5pQ<<-=vFUegs0f zT&SZ#!oQ9m(=8NUT!_sfYeW--I#t?S4cZP3G$7-!)h}S*w(|wX55kQLy)fsC2n;W$ z@d#@uC#z<4Xp`0m#LWAg7Ou(92t))Jc#H4?xz!E9s?jQ1ag2ng+zFW_nl8p%P~r1@ zD`EvIc<16IdupPY5Ok&^#c-)vtRS)AJ6NI{6bBxSdw!{+%g*8RFW(^h^Sfa=p<9Q?}4>Bq2>k=1}ypZ91PyY zGA#)&^v07kB_6sOpl%8&>F zZZsfO`|}hN2;(*1jiEhbNqdb1Az^&lmHzWh296y@vD01d^01bH{`z2jrLnHBIel9Z z-IVA$F2X1Zs@a{XYU;)$0!yszG>)}ZThCFC#P`t}4m9iZWD7&}G?K-BFd=4)Np41; z5}-XhFE*ynbr+c6{Il>m1Eb>Sz;=E82ZQSbxR@K0ie3NP!GSi`=d_#su4u!tX2WMv z;(p7>(?LTs=>&OtAnCEvEUO9aUdhRpt;r5x{Jx;KI?JFvQ$G?t_yL-Wvo%|a9`4Gi zlKT#P!wkAYhc{r|(&_jbpTyQ5;@|M+KDrG~vf}sB#Z;wC_ubw)3nmWxygd?5Y8^EF z9yAmxoV;HB_Lm9#sFS}eimGGfZF7?T=E7oMXvq>5nW;6o$#nKc5 zWHfyYcK+D7b4wgDkG+3wICgiqE~1y)?k%9JfBlL$aABk$rbSrPdQ>cWFj~bDR@o>1ij+ErmD^{O zIvhPsJ9a2OLNNs%+8VLdh@V`Q98-GrK-hikMu|mRTI-qB4)pUebzWdZ7=Nm3?A$Aa z*x?w)F}03$T#Gk_RcTzO2Ep58qI+|E(YA3nY~1kqxDi~GvKVI)j?kGHH~R=XcQ}qc zjCasBwNRRPqSDNFcH+XT)M)X1Rrd*7=>)lq3HuB2WJSDX&4gnY^cLuX)1l=Z&%_s; z6%$|^eQ9b}(kC&Tz7=k5vCDE@gh6q{BD7{aD28#~-|C*bRYZ8=RS^o} z2mN6^9UBf+x;c&a#h+Zo*v7k0vD8c_9hM|a*xnKuPsy-7Ua%(od&KYmk16oENxm!0JK4Tr!@iC%^Aa^%Au?O3G+U)ROB>G+elxKqo3So~u|9^e!F0B< zX11wows~T z5x^^MKyaC{qwaWS6$G&yQmgA+o#+@|lzFx&(~F9OfXU-eg5AU6PogNYz=hE-A0)j= zizw*zX-6E#LS#8)*>|zW$~hXKJB7qE1FpBjp>6Yvx!W$$91b6(@mptI{Y;jk@bgx( zy{A&}GfxbSa09`^kfEM#s0h%l;!b z++9T>2nT!HdU`v0I$OF)l!!zFMG`n!68#rGSUX6r8W^nT8-CsUrzfy`prNIzxV`KD z=m~uJptk1k1YtadAS`Q){LlDc&L674f8m4oUe<;c)!g|bH(YhIpduizA|UtmU&Uds z>{nNxl>8MPp1p_q3nF|-fe2&FQ~rbq|B?j8#KyX(}zf^%y|DGds7WY|; zTxH=X$?HjlY(LM3R0`|*f7*p-UHvb`VTvkn3_TFN8^XY=Cdc#l;;_iqcq64^i^q3f z{s%|seCMk4hTlwy^9SqLAyLYxq@1=-HxN}i+g9TLhbpk{^@leg9GJJL60FHV8vppK z;3AQv5JYYK)TE(ubwCx#6eK|4QtkRm)(Uf%Q5;SJdGKasAo-iFKNo*`M@c4g+b>t} zH%vKGKqdML{DDAku&Y<_EmR8Quc3-jh0*avYWu_6H*a8q=QtUwca(4I);HQJgw-N5!R`S9;Q0Xnxk#|LpsBpI%fI| z%;O0Z=3W~c2^kV6O6imp5L8}sJQ|mzg|G<5THAQ7I(cx|AQS9ul%8u|1r9Em9??fn zT@Ys|5Y*&4$NE&W)9G4Epjq4BNs1jvMdYl`#$FaIn8BzDre_(;;!osHX}NQOUBsnp zb;&Pahga7$U+Kk?{ZSm|HhI!2b0DN$i9Wb$UX~QRrRB?)E~$NAUa?y&=0!ar zA$v4q`wn0#`B>BU!H*HnEs6A(l?Rj8JnH0H?5#pb>FpdIw2md%TDAAqv8@c84HjD9 zC*!+jpMYNp%>V87gX_9P?R?Ff|Y@TdQznl%Y*qGc;aFY5mcuQuw z7-Q9?=xMshR=t@Ee|N@Wm|sAHd5XvZo(Rj#9t&HTT8>UYY z9_fV1x+JeTYZK+`wRk@D#u>2D5xvGC{N6ZzodaFcBZ81(+?S_XDhkO-KG8fQA$ZQb zD5jfjQuqES4!ciPasF8xUetcC%@YYViNnD1fRoSq1)U9oYTADkhYgy98xsC34yUf_ zL{VM;lOsIL$Ab;UI5vR=w*ME7aGyv>Di9Vk>@%|8Ps_4a)BC!Gx8>DK+Ki7Zo;96uJiQKqGl=mP<9fImxO;H=&+bFoiQdl z&KUby{0kp?B|jD_u&#ccGT0Bw`64Sg=V97gQ5C6Zto>C1uf8Q9b#uBy6FqW2x|>?* zb6dMx8MCDZCk-ah%{cD}t*=YlFB5wpz>`~?hp}a@i1jx?N{{APW4T}%5Fw+5B03F* z$2>k5zqAkEH!&MQLUN}HJcMz&YWDWTU5eZAd;L>Q8M+j^X&L@CbRo;S;WOu;Xb~Ik zo}xh)Oxmdx?j>Qog=>{)SdtK10(455Hd6kEkF}79og_!Y)f7*0LHz|Nb~SP@yYR-S zErg_B&#Xr166k)~M9pf@ZG-*1a}#~1oY%@1BoNM~Q@JSxy)tBk?9h0P<~XFEQsW@v zAJs-e_b!{tdBu92q-XdwdA;?o#7*Zkbh=$+?Y)ETNTF!gu=(0}6D2q6QNDsoR|Nx= zv~Q)es?naiA!|WjIAL#4(NFG6kvOy#OP&~tm%xZy7(P*C*-Pu9=#PH4`!w0}Vu~+R z>}7kzsFyf%ytuJzoExYqpZGE9!ClDrZZ84L1xL7BxsTd&ALDAv&!dOvowIgYYzI!! zS#dlFhWp{_dW4^lD{rDde!j6=s{>@wXp65! zg6=GWmEEU-zt6A=?_O>@4-0RD^;bY!AkLO>HkxR61) zni#INBd+M%^HBJq*2p&NVn_b;l^QLmXR6nO$PzIW-V|vW`<@N_qRj5_=4<)u<1?TU z&kl&jj!TN2!R$j-Cw%L~kiWpK83D%Y^_^ETpMV`72_T=e{gWcjcooth6{&VSQyJLq0=Vks zeOeGT4z4a6$#08e@V%`rEe0gzZkK~>cAMUN^nF8bp&1bz%}a5Dw^35(9z;$Fd|3Q_ zbn!PvLS!RdQC0+ihPiTo3f5O1JxCpWc$YT>hmjS({N2XsoWyvJ8DG5^O>mJQhbJNS z9QJGKg`~xAmklsZ)^C4IzTQ7n6R-{Cdw-|r_EVnohHdA01PEZ;dq*W_TDN%}#Ba41 zxac?qpD30IhHYKEd;}TkR{VjP^eW1s8_(=fLA0_gU3-?%`$ksV`Z6+7SIDx;`8vrt z9O;jc5Dr6vnMTN3r9ve5L*DHo1PQEPZ{K^Feh-9Xor!fplJ1eH zEV9KM#_wxPKBRh0qic5;|mtv4O|g8vQ+z; z!idClc_h>&+=IZB8*vxT0kh9xdPax><-%X@M`@w~mR%-_Tu9e5`bBg!Xz{G5IC2rI z`h^v)&JsbtN4p0wN~=U%P(h63#L(p41-U>;XpONR+&hoh!syr|jFrk7lAaxbJz)cH zW8f_Qaks^RkYM1hI1nL@U%Sof?upL_M}|$oS*Q>+y?97P7>pXUMup%uh=Jn&+}2#C~1y#z1??}lC}r=?khmX*_8&4F$^BP1f? zYdP@s28r4giOolb-@jRvfY5ZrJDNzDhDCLZbI6O^2pSyShh48_ozQF8c2(T)kJ^n#R^HCSd%srUQ;y~zHD$~rP_XOsa>PCW!>ML2QQ<**V1z3o7W)ts z@KAb+mIg5}UJsp5?gVzWQEe#`%i6?TD*4s`p@p{7OjYpC zO+eMg^CPwDOqE^#eZlAYaBfeaT}-Y0;ZqtS^jH>5g9IM~PhY7%rFdx|dyK=YL}`@h zlr~(LntECMisGXBH#=bFK9fWz+iV`~l?W*1g0K7Cqq;M|sd9$(9H#L}wqzFAVq1K+M`In3HRrTq4H=R{a+O74}fX@w1P)d>PDzoSJQ8yS}%}ruhT5tfjowm#E07VzrB=d z0)znA)KQ>U0;4eP?Xi=`+8PnG@g6~43l65Iw1pyQC1xwLg=y8wX_OUdPDg-k7r^Sq zLCag90;Os>Yg&!nY8`GP!~*r1pej4#)39BNm&_mv4ImqI?{d;zIX0+lsMUG$qOM%G z2n}>D)FvyI*;T_p0=2h}ll{nbw-fce8S7(N>qvwbmIqX4)d4!g`k3+Blz~)_OSM)( zwRbriayA%gb77g+@FAB7+3E(C+^}Fq-9R*8WLQPYf#hBb3qu2i;$4p-rN?h%^F}oN#rD`12yQj*66xl*Eq!n+Cr=wo#g5(uJP7AAu^ljzdc5Igc6M6 zIoZR2l_t`SAkz8(s=evq1hQSUR6l`>%_5Zd<~2a+XM2E7L-H|d5cA+Lv_s{mncN`C zOYIF)1Z)!7N-A$F;qLSUHw!hhOC<49?{xaEv|p0z1O-%%GIC%Y08XE->pG+hBc#<( zPJ15$jb?*unDJwE&ijeLr`hf@)>cI{V4%TC9|nY)^tcB#k@20B3&?dh7mP$I+K zlR-WFB~|AB?6%H;Y2jm(O9%S3)6FK zMrAj5Wm0$2xI8UMGRn^Cp+k00Y|$3{r4c{lAKXt!1cL-3b(#{xMuo_zTPC= zN(U4n3}|jbD?vb2N9;EjG=R>eiQ{5_n(}>c9w$Vv- z>&PXGe!AR|aLsNS(i^sLrCfj1f-Z6lMtRL)n#I9;0dGnE0|KTB>vE9WCl`?6KT-K5 ztzp#7Z6*K}@0cA+DV#*UL~6vqO=MbFw;g~xKl>+rYUwrmaAD)@fftP$0lr_To*nka zFd%kd)cTbaQ4gTd*TWbTh!BT&pyxdk=4+V z7iS7Q`1MYnwLct3_LrLh$-OBG*FH7Rn&rru$=eLKn5mFHyEMmoc-+>+YizZ{iVB^X zmYW5UTEmP{k9g)nk#DRQhi*s%n>=g`uYks1tkECm?#MN!pX{*Sf5kuK`_>uPI|paa zhBaEqy{E;^-Km&*WIAuZ*rXQz9tWCb8kukwc>DF2!B#e}Nb?+i9#uO3!AZ04u$k5M zS})vU#3i>MhJ0^YF{kId@R=9&A$#^NagnXeKx2r1EgaBkc@JKE&x=5f&a?h-VyuL;MX_;knmt_NF7htjILR?}XEtuoFPT(sSso)^b@PaXM4FV_~Q0ix~$J}D=4DR!3+%B~_OTNQ4zbW!s>nea;XQlqYH?jgIeP+7O!e@@E z3FrJEgDjNY=Rd8If4m8H*>=iZW**sDIvHM!`vg##1E^>FO1X1}BOl)he1?&>;V$o# z&Lg+{fOn-|6iNH40S94O?2tDshWxNlYO$1-T`mB$)Wg5ueM_nTmb%-ghkN6Vzg#fpkbC z_mLU7&(wF2!;i$=V?kXzy3PC@Ix&kJjN4ZKY4df8lGR`#2Z_=O7j9~`0LQ3R(}EL=n>n!{pAC#qST&03TYtK-Ig z7NRb)3-2KCn^HK!e-wu~t^QC2`o4#CQ;BKw)5Jdy5-MLAe(=cbM;?db^yyfWsGE;e z>GLe|F1&K;dVFEqrp&R$a*$)N)8=_`E3>q)Ke;c>h}%*`G0?WN1~kUD6KwO@sWtr9 zZ(5$r9N89vEgy@I>~Nm}>lY)RpU8mnWN`{no@Mvt>Tq_;r+uTFt6CMA#LBQ~tVDTR z>e)B3yqCV7?7S-iSH7Dmd2ThxK%1ge93-w~LUZ~IIJ{~fGfzqxi{*3t5wxY8_>4AX z)JL{1KJk^t5V^)=VVTqHT(DH=O$tZ&=H7MNYY`k?Ihu)VnCCwmKTF2xdKNrKhd4if z#&HUZc0j1TI)B6$EvrQ@7m6t4P}%FeZzjJY97`{0*ryT8qk}JZ4rzqyPI5g?%6cELMl1Bdyn8Hp$M@Dey^`_W%tqRH_hkbc&b3$o_q1dx%c}ywIf=&#Ltt@KT#n&!&V;Gw?W{3j)=RLY_vte*^BiS!`2)er zZ)sJW#S1qfleSgy5ZOZ6`FJCT+dCG<8Q9frwTBNFW9AEoZwWi!iB{b>bSxvh}U36Xfb8*$w-@e6Vy(SPf&(?90SZ1^w%a<37cUENA?n}k) zmOVR>KyDQfg=VHjoMYA+uj#flpGtAap%zKz5Y`(yJr_wmCE^mnnCKqA@&)SsQ1MXh zddro_MKn8A2_U`fWPkj6%<>xjS^lii??RoY<&{JhGDp0w51hVi$YskAxw_GISJeAz zruS;%K~;2 zDV#5am6L|PJs(fm4A1LN`5#j z_RT{DoGUJCYgj-3*?gD23-kM1e0oF&3S>b??e2Oy>&Qf{j@w}JD6$UEQ*@8Lb3q@$ z0Xy0AC5wzvp=jO32rfqv5M5}u^n(hm2v`|)4x8wPAc0QN+ z236a$lex9hasf#ahn4cR4yQ*ms>Z>SI!_^_4$Q`0>Rs#cJlXGb>c8o+?nYN^Kyq=4 zG##?`wVltJgS!EpF*>Fcg70#uUy9MKgZzBxPD>hm@IK}de zR@J-7d+9BMiqLb>-F34(Ll*D;?i`4hfN?~;72be~DVSVrI6X483P3k)$_ydCtIl^KG}L=4glKffGYsDXFPh1G*3LOo^e~Z)7}n zbml@UQ&)ZDU-BZ%th{b*&8RirCUpzodeCL^c)d#0pcG;lKt;4^%s2m0L_JB9LxtL| z?s%;~=x(OvaBWg+@<_kMeYu6&GOjmu;2Q=^T8Xs2-OnIgOgcI|cfsXq?IEtwR>J*# zl!5jig$=f^8frxY3QzcWCt|rFBkUPGhxH;%_+t0{PxG9kCKfL%-E?N0qEi;yurkAZ z83^J;gFc=mT>vO9xL(U2Tw4yi*LUCS8~D(zHL=auXvqo z-U8GjG;=tl>AA+KWN*4$6E{!#30D zU;PCQKt$i@tK5$x<7U1}_Cu}R%Cq!Y25+jmjP?mdwyh*j*CYhgfp`eSI%Iv}AoIs@ zOB`g-N4(uj%-0CkyRy%w1|hP3qMfvGXcfLZ|8^*hz2NrK_r}@Z{6ivJYIeZt-t*rr z$pR<+2aiD1dVG~>D@C*VHRf+ki5z5AO&aAf9`D0A`>}xw$1T40JYU!*2%2hs4EhEX z-QSk#O!Unn=UyODFn2kv!dt?vIoM z@pjjd%n=SM%7 zE0>5xldMv>Sx@g9RBy6WB$6bZj2Lm3%u>!skavH{MP2jSz|i_{Kt?Jg zREnfJ@2QqhC9Dhe(V>SNU4Xe@bF zq71FN{S$KSEU5-zl>3U{>`#=FHr4^5cISFS>r$T8UiGLm-JxwXY_+5=4223sMOPKY z$dfCMiL zQNct~4p}H7mxPGX_R}Tx;-Z+xI$eeO#Iv7$^dL4vQqV(#+yP`|nf2c<3!l(1|2{C=Aha5?qK*pA{CK z0;rc)z)#crkYaTi^?ilcQK+M)=wF&;RG^FKXwH5#8MGBu)O%{uR%#TTMz0+y+nZwE zYagrqqC%tGqb(BG_ccU2)I5e($Y#*5~X+4nIP}Rl&Gq>cDEnmnK*0 z7(Tr@YI<&@(;iNPa6z?Z#WyvP=N{>xQgCm1bP5XSkyhe^MKMh_3G^k{(dua85YR`X zfyO4y1ZW)I|A?ZF{Uhr#Vzz+1V^#BY^{1o~t#EK}vzRX012JtPuVip5<5CD2>&JfS zUwejYb{Y8Ur#UDq9!j8_Nuc-ns1Hl5y=$k@e_0uR{nYH3ILQt!)XzKhYbkmbeN##g ziPfFo>W}i)NfwL1hJ0S1qq+oja8i1!REqj6A@eSpBL!fk4~^7i!pFVuJMVJq+u zwipED3`LO`hRMeLqL1ZN|HvndnGDj;$`n5NoKTgli(NyK0^GHw!kS!W1cg zr<50If(?!-MNLNUs*m>vj;B@(l~-usOQ?ra?zL==Dm_9<3A|*H9Tz8=h{5TXd*Ct( zsFOSLi*bWA5o0Mwp+aB7U5`TvhDP=d>8FptFKv=%oWSRrcQ*aFbZTN>(Mw9qQW}?(|y?u#wB#R8ieiBNbr=^G5U58OJL9x!Ye}h9mTzfc%(EqH7@S)IAtv3xU;lj0BJlWQ~+=`_*`Ib9680|rrN44KVyO9EF>R@^U8qsavM z0|Mj>>frKQLu}E?`Qz^kTv6nk;nUwqkeKA8hynt6)T>+SagK<=sc{QkrAZ#@60pvP zTd13I{aCZvLf!}3+1J9vKNwb^B@0l?zhV>=K7ZZodUR}7ycbGEZtk3J-2QY{%7&~Y z)fBA7?=F8v*(D*EVTBZ)*5sfC+ey!jA{4 zp$58dkVw4{f|W<|F&4FhR_3g|na_h3bp6w*$U%Bmi~T>RPNw2lQ!%2A)K^LuCxTw= z@W`-lJ=}3EdZRi;R7(!_$arCm{2sAX^&~!*5nK=l%r{%5dsy75T;5OFYgU-Pf(nB5a4QK&0l8ObZih_Z@uYg7)qddL&g>#t#4gYqOv))GC4IP z8EK0K&x<9+FFeDr^MV!Pzfj)Ki%)HvEYb)^+@0E+(VzaJDr1)ra^+jd$mZFLW>YIQ z`}ytTG^;(^elS)pGTz?FR?}xVo#*BW;>#v@Hk}>?KUp>6TWV%83f)_o7KllEYQ(Jf zDA{Tp1-2~PG!b^A$us|A8u`UIt$S)JzNIwrwhWjWv`+MJ#bANbif)EnJo3@o^=M`5 zW`b}g$vU#kJcK%O>w=QI zZ*3ZEEMI#khI)dkX3()TF)G9%(PwNV6{ARK$}i`bsy74IvzQV~uyK3@rcDt`d;Iy? z;3+{`x*Lth&SU0MSrlrubI9&%I=kxE&Ai~gvutXH{gIRUU^F@GbULoOdc_5ApS5ytZ8uD(O|6 zo#8smuzf2Nt^>Z+weT|Y6@)80F~WW;ZO#EKyhinE>lVjmSkCubD&PCNdmFoND1xkp zn6yR9wh#f7M zwK=li{fhl|66roQHFoya{agBtcV)Z3n5fd??_Hd@&w$-mfA13R#>nj7BhuI_S9a*t z+XHQ&8v$do7anCfi{y14<(M~J2xqBMLhKX)n1 zD6ZGSVMR^?8$0?4W}!OtSW!%kpx5;tH{MAKyi-Hs8q?t%-;*-Lwv_La6ztcVFP^Mc z#>mwjrkO+%3vMfHJP8#;itQdM^K-%Yz0u&WDjG+~&F^XsM{wUGji@8UizCg#Bdxk4 z?Vcl@$s^s3BfZn3J7mZD%*O`&$A&kL?`j+y86V$sIKJoL=wi}d>7AftOC>=yk9ABI~E<$c21X*wt;AO1l1n`8trvCl$8XjJG+7c4wy^BUzpMCQ{&Ba8~ zgkPmM7C39gMaC`01e5wt?VVbI3)DR$g77iEz8wCR{+l^JN({MK8|Z6`sGZJ1_1zFPS_q-8lb%I?FgKDpS&xg#Ls- zji_pkR^0m$CPtjc9GGQ(R=2xej}Oo!jIz&Q$PxX4bQ}v1V}oMACYn)sxgfh2KhXt0 zk=Q7$zA!EMOyYLW_fNT34p6r*m*JJ3mFfIKT6ul`;fL_|L+1E}<$w}D|0x z$g+3-!MpxE+5T~|dvW~7g8Pr-?SCh{e*X``>*7C`*$3Yjx3*TTy==0_mlpml?>ag^J2*GnKQq%i zHN7&~^>54U?(y-3;nsg-*|S4`+OGd@#C@~pr4-v3@^cl7*^GQ0Bcwrj&5wrfpQ@_)8n|7FMh<$uN5|DU$&YzXsTS$1+t zN@;|7eEh%Iu9s!DRqC6N&ygtj^}$4&+8S({kIYKzh&8VW-wn1O9w|cTYDEvTPKT$j|vne z|AJkUB_vHB+8LYwOPsB5Y<1`FJMQY*Mk;W9X*0XqYI^^Ovv1x)NGrf4rK|2K%fuzq8%QS=mJiE&jp_f7 z1@|zvSi$O|f6lV=`Hs13-rq|JDEoVs{ls2Gz&#V|A<|~!!r*Lf61rB<9H3oS_UD2- z$63CWHa&?_ZSl|O8{A=z>pK>I@~#;7V0PIDW({p|a}jr0kJ;Ny$(;QsPH&j2OI^8= z=*A$FH;w)dj+b_fv|5gSMarkLnP<@OA?ih5;)LGSM%*RuYDrzyr8}r+NjY{O!>$qs zJlAJ#xWAMZImDQRXZ16)V$EtGcY8T6C31MW_oYWEp-NiCcPEZ6l_E2zuNPc7iSd># z-MeDc(_6R{N+n@`6*1a*fOaG$L;-O7@%#Fr3K^J(+$ZUeveo!#r6AYeYBFTOHgHL( z2%-P)?Suq3vb=vYP{IUNj6mG^9`*%B{=en) zDdl7&Ua2hmPa^`@B^YK^tk|mW6i^8Y8RQdpeKokdtuLtWS1~5|t*9Wcnol)?vtSBl zbK_V*<$@evop(nxHpxltcBI#mn=kbdkM0MG08E-fm+2o__N;!U^g!s)JEeweUzAg1 z=r})sIHoXfZG$BSO4Hdot&8IN-)v)O9tTdq9)Ap_yF4`&-fg<+scq~V#~>pD8-Lh{ z`AFHOkoaaCBDGpTTpH~f^qZWQruot*DlY`y{NOSvkAx4EP?egFQvMKBbK!Q7k&tNP zA8^{z8LuMSbD-S$mgUVaOCvq)Ma}{zR2Qbk&~Q?T4u-EPaL2aERn- zxPBpo#_q7+#39JolH`KXgj?=oAkfEP&^(GG_3RyD)wyyMdR19S%2+zs$n2FnWcgR& zsALA-!&%p4<|W{*vQxaYwls(LR^&{C`6O+)WR zdTS0okk5+@waafKXc<7g_aHt*%`W4Sm$(SOyJbCSXwO&2JM3_nooUqXB0Y_IYxN6s)^o=g9N zUlrlfD6j8GUYJX`cGW))-nU#5m5!7>ckKCkuF=6ZBj&8wm`m-8>)>Q75L3UKO@og@ zbY467tTBfHJV)$1`Q-Pb#Sarz7Rb7UO!v`x#5|pG6v17L-XdzKyP5WP`u5`C zvN5#f7>!?9NvME4-50aY;rl0s_*YlAxT9(f91I>}<9&if_x^V~Z0Op+b5P%m4KQ^FFph&UcyNesDmc^timT-03 zTn=U$DCI)J-x85K#IehBe6mQAhjZX^b)IyGPdh?|#L2Hud5)slH|aN~qOeppgYdCX zzn`)i)*+MNtK&~z6SW~U`n{yRR#8aNN2td|MK2*wOWCWe!o44Qq(2^$)LMf+=01T@ zf0Q9{jT`Bab81695O==G()LZj>>h@3Q#Iy%$ez32fGcRnRw-XL`UOfpTY`ebCt#C9 z?*04BNskZETt);XnZ$5C{)XKXLoW?EDYJ?Q0C6=7(%WI0W41uIs<8YEH5S~bDXC9f z=8-t)H~6GGuzT#yH5ezX{|7a_tUh$azf?KkJm>Aq3ADhKq-|X=G4Nx4F_@LjX(9&G z4laW(9@tUhu-9K&9N#6kz5>(lkPl-qe%&u}Sz5ue57TqmpRk&`7ELnmOVsPD6TegV z9B77ODXyhzyDvMXkeHhIf!6$bg}|G)Z+7&*v=DKnqq7|_c%F19<$|7@6ZbM)U)GXh z7!*l4a+jLhu8byQSxrsHCR!lF6qHfPuS8^dmG}V{$t=Xj*&O3Rr`8CfN4U7Z#q0_3 z7>NbwC&sa_rOPDX)%iW$Q-z-bCo_{!qvLfMe&PONC00YDtoe;q@x7 zz~sh9R6+ww-|{OYhEJ4j%vc`yZQUH}DB!f&ht)EyihUv#$e~Z-o`{cQV@_EvFRd+d z7cH0qPd^msY!*y8F`j|^fJyU5SxHcm6p<&cD|>6PLGIYS1%_GKB8@1c@rHd4@OoS+ zPMz?s-2gZKjz5jr6K;bj^EI)nHmvn+Nnfs4a|tB;EzAD3p-l5}DC$3C*-ue~Tx-VV z^0b8*uQKP0%YpF5sUE$Ps+SjAj&~YoCI?Sy8!xs!5*p_=^iDs{UhMeQEtBZ=w=$q| z2>kiik*B_-S7o7lSQ34(8w(K=0T<;RS;ZB9IV9Y!If@4tO2fDNsgH&hY|KKip|P8? z;1_b#(9}f3{MmQxli{(3IIQR!7lebIhX`ZRYu_wIc(=NPa|TLeVX}K}*1jMxE*sB@ zLz)fF;a1CYG_DN|L42x%g*!!qMG{)+UE&<3K+yzv*fo9Xye+G%F#wKYEAeNAo#oFD zMz^dASUzWl%&mZ;?_E2GJ$OvwD-i5KeG1U8-=*f9q~9fbUP%(jR|o(EbW|i zTi)jg=%(jJgqC&&wZc3khJ|PLLMf1-^BnuH24PSiAoYbC?2>e?*W#-OL8Ixl|{)u&9A8hG!ncbM)SjiI#&$E&!s{-9G_~h zPwx4oSw8{e$ypB7RalC?e0K0+OqbnifEDO<2#p*+Em#wv$nX-I0(XmfotQ8R{e2!BPWO8F2t1UMxAbms#Empece}SW_JD@i^?!l(EJdXpnd7{Dq9K(W>p4otCF8JT>6@_kxW)l`PzETT3das&Sg;$SjQWMdoYf#8)m z00bIl-W31;l@OYZ5b%}^U@u1fL!a7T`9<7briKP_gFJnsctKBSS(vG&aIX-%A1H#$J)fvt z<@C*>Kb<(Os(6068Z&t2wt{ckWfH<7N)?ru-2MGs(0}O#G=ksCEfuyy-Ve_ zMfvwWq*cepS%IxqvsGd=kJ77k6aWPZ`1_?wU2V;JG#nydWAd^l!KlV`w)&2<`c+{- zZMFtoU2XUC1H3ra#3(KV?Vx`3zV!qhar6J%#DVJW7O% z8M6R}J@;orY2e4O&TQ*pV(U-r>6DGV3?KJs8|r^*SW+^jTwyJ92C8No13NGKY({%w z;KSpl)Y^}6%5^@KP4TeiI4jD*D>|>g*Y$p9Au$8m@GqNvSL>`R8xr^H$=YgGoHYu5 zGP*Rz(*I<6S(-gPY{CJjy zucTE_M`JaRaoZWF`^3ViQypj4(a6(=Xk>Qz*-<43G*NbbIBFxxZ3{$_Q(8A`mB4d_ zv1Z8TUfOnYWY=9P4Q_TurL4{zVc>o&GeWoxRM~FvOxu!*^=4DIBSXUt7e=o@z>tb{ zNVwT!4*u>6)8cm)Y8`;`V^8U7CkWQzPuK>+?^m+x;GC*EjB{~h)~%OW9Em~C>+iV7 z;qBJB-F~^`6vN$_RO*~_j5c%NHzmwU=1uuq@USLE##r_Q=S~vZPo=TykuHqpSuK9W z>_N{ySr~O0?|*#!i-pP=7zpgc{!)`OSIece{WPb}cb)N_PE-FU7M&bmlzrf3b^d@0 zuvE{|lL@@)A5cH)G4t#p&K-28#YqUKtY=BngqA~wo0hLLs$J7$i>ow9hU+ z3j^_0MnMR>ypc^Yl>>xvw=gpR<~rlAxuNFHUftzE62hUU`yH)10K%-BfkQkrBA0Bx zTX(;Y!l1{0zy66iP!QP0B_dvPA5g#-F&-g@V`+y$*1h5!;^oR7JoD=G^P>_M$@JFP zr@2@^SU(wZP)%2q$aaXrdRTXP43X4-XIr(=g|R0VaEAg^7c5&@<3B%CTU;>weg+sp zm}GAOX1Wv7JUzz4I5L9)-^vMMdY+%3BuyB!jpn*C`yPOIFA-*s~vqXU~8zW>idT zmt7YZTeAsXxgHOIgBkS}z_z6fi`w9UPkokpLQZ1qHf11+w)qS8)k(!!qTCrR&JB&k zb;Vqe;qCQotBogkn{j>Qe8>$(cnkd#y^UM(oALYWPmyy}Gn>YhYcSgNB)xUYf*S!yP7X*M_zr=6vmjit z6kj3EU7BfuUe^^u3^0s81PT{+KNj{S3=Z2$2S{>1 z_lAtXp3^6^(C^-$)q-H{6lvLXX)O}y@Wm~3O2@QqN4Km`G*;$lJc*nZ!SzCWbg++> zS;uyGdc|G(!yB}kc!uA<0kA0Ty+uIJja=nfzoX?TZQFNku4C%lp;KX6c2VGY>xPCq z{kn6DWx|<&=Yb0C!M^nlMeaU*0#I`Suvh{~RPn0iKe#*(9YpEgFR%#WffpP<0fRyI zUv1iyMraUI56aO7u^5Ivj2&9y%kK-Af}3oz6D|$O-J+e>M$a8FE5qb z=L;|dNtdJmL)bLoKNj5oUA;4V?o zfHy}T_H&K#x1NJIOpi9B-jA3L%6>rD_A!4D+In2OjMv3HXEc@3F+Fu#Xb!s4)mdAk zUKAhqNG(n*Y%xOWx{T{s#`02lZw|iumBmk=9kSyC4hjP01c%RPLae}J==2WB3z@lJ z!~WbAkf&VL{WTZCzb`Jn4Co5%6NKa|-s?R4oD@@Fi%^PKcj_!a@r3K=o-?6$l^{1) zD^xKIRPM?ueaUv%u@m8V>WGD8k6bgcBrPu7Ia`rBjeDoK21hoVzM^hlaehxMTz;z_ z?$QBPi?GqrO6IuCvin|N{x6>9N_W^^#7PK#tH={x0#@N!t{OnZI5`!lggtzM5+>so zqVCXT%QVnZ*zJ4*6`&BxPc*iVcCLX-9KGwIz-I~GAr=!gtZe;3@lmhxJLkX$L+x87 z_E37ZuXn}2g?<}G9Yju#Tr0aK=c1SUO>L`7+cM&~`}VM3RgZk%Y=Kei)Uz1*E5a*6 z{9%s7?pzeYboaSOZ64K5@0=ffsklSR?vZo=8cw}NE*cv%i>`9vX@Fx%`-G3h=srDo zIyoMf2{&ay#lmY7L89YDjG`|NW^gBY^Z;diK}ph6975}g*WJr#`ceJzXB$>W%Im7; z(2N5|lj>`H%jhThKdH_cuifX8uQRbCqv*FzHFhiJ2%3ARZX-a5%~iA|5~JnrJ(0XF z2HZQ2wu<+A)Zm!EZB$hxOV#h6-@j-0B;OjJ6G)?rGK>_kN&w&b=v;m)fH1e>3k61? zqiUyo-1(2ETou$zty)#aWcrVs~(Hpgu~3g#J( z5hqz={iGg_V9lV}m8tL0E`{=NvE#tZd1UC2M^ufEjmGX*5uYLLLlwhq7#K&WuX%Nb zkix8BI*zm(w4`qNZRU>HI?OpO9PJR!C{#5?YYc>Q?0iR%B9o*NloNP1W*{7lNo9O_ z!wD9Y>Iyg{`VK=C<_c0B;dGX)9@!bsXZ^`5xLA88Aasfo19OlYGzT(;sloC^BB}V@3YcAG7kVpWA->o1`L>D2Y z!A6_>O6rZUE1TZ7oeriScTXsARKrQgDB+0V4X1&i>T`cy`bga?DF3gH1n)m9!dDfz ztaC@JbS0T^>c{8>(`H6U?EINLGZM~XK!5e zpHFM*Nw1e(<;uDgcZ{PMYHxa72fOLcruCj5mt@$veq*pr*LLDBrkgHt|CkQU`h*8I zjw9R^=*Ig#O4P?a*wSh`Fnz6j|61kofHkX4Mrj}8N8(B(MCh7DyuNWwIYU{KAFkh? z_PEIj7NMm7efHaeuZTZs?5~rP9|$G*-3s_S$ZsnH&X$@l-nlJk}L8 zow&-`CEUBEe>JX3cl0DDpUQJDxbUa(k=T^d(o?jA{ewhSNUiuM*Q6N!BpYz~S)Ke& zrtejW=GnJh-O9J|;DpzGz!NE3sJ0#|kT7O-$7ND*L%u?djy?00)MdDwC!wmt9#5vq z%C&^+md+anGjgl-iBLZ=oXOURH)< z)ti4gLigw$BbT^)y%})tRS~UZR*kx0v(x=nwh8*grxnP9;gh2ot~)#h|EpROUW!r8L_bTVMfO0#1{7(LsJof`m^oP3{**#9YJazVG%2O{f?j(v!i%Z2B zSN7LqnMoH4hP6FwE|)mmaLbInZoOA3J;S9szD(lak}3T@Or0ezG60B~JdOj6D)r=3{0TBjbyKeh5Gq-RXe@4|P zNqR4A-WPa~@FB^60pmFL>x#?6fG-@awCwKTw?vt>s+p5aQWNE;GNTYHo`Y0P2~Au1 zr?{%yM|dWW)D~6X`RN_Fnb(wR!6D}^XjAn@z+8{|Y2)SGPXMv6G3mo=X(|5uSFina zISSn9cW+S_YoX<0CcVB^qaWxs;GB!Q(#tkPAm7*IAH}Y;)N35(=?s)0cp|(7fVlF!p_gUgA2TqnQZ})V3W~Ux)kuDbxOT#9vs^gCfhJX zpb~}>PC#J&l0uM~s32K^@Jw(BrK}GND$KCx>LDy@i95k6VP6}~krSU5241=XY2~KC zpB7j9h!uLv7e2Kq46}*?J&Qs@`ThI~e}8L_f-3I-Vkn?vUSA>XtRn&3AzR$0%7bDv z2kY0%NkdU08CADSP^@DR8AY(J3yn^-S^^6B@*XA$dSmVSo~voh z*J}zSDwgTXy_W5z3y(x7qRI+1i2K2_0H_NL4?9!;EYO@pNMR_{dACz5VYIKtt~X5a z)4Xg6y)a6SyE~jkBi^z7wvM(rNk6urC+QjLu54`4byPV!=|*FtQJ)#H3yw?4z?R_OETab5=n^B9kJ7m zX6b)NAP)H+?|2>cu>e)&qA}UjFcqugaRl4!Oh7JG*PGx%vHin{w(dEU#58V+eQ-r; z@NP+c?2=CY)FTmke;)w? zHLa*;%L;~Mp?5orE=+WD(xDTXgOg2>7wo!QtF8B3z}r%C0`Gds7%7hI^e=Y>*17K_ z=)`&+>C6{tF<3+sF6q-;4E^3}XMF@74X1>1pd$O@DQkuk^bH~$yP0_9xz)ke2F+cV zp^N%E$<}l>4}_y89GYn@E~4|ty6=tO(S3UF zt;E$z!e~4dgi9LiwHBAdgM#Pk#5snMUEE6`CUtu{8ZwiDtXF+*$`zA?=#~|0a*>Iw z7>yYkcs_Q2%4OW&^_{N(XCC--9Wg|~)Ofh!KAz}!G}Ui1BxX`(djj*GbZH4N{Bmy? zb5pw1B*}xoxxRsC$RvDCY2_OA&{DSjahxJII7#He>-s5YoXPJo+>PqH8F4WxE@Kz^ zH^Xus6ibB_NTZW=A27|2+%`92VMigmUO$_s%_X0DS%b6v4_yl7D@D4_$?FKrGM=)#YSG!==U*jy>k9`x@l3CxgENH6KP515y+ zPtaXo2t()&6D$nnh*ne>tsaB*Hp6Ej^>ZTTsZ>4m^KrKWhT~QS`^Oe?P_t{PvwDD~ ztNG;S7l_#!MAU3C2OM&Gyx>f**fEd5@}dL>EFaBUHaxW?aO*kYnL)BBc{0X1iddbj zErxuEtdFpqdBe6~HTXL{$Lz~2c`aB^z}&fhsr@+oY`ptS4XpWy>R!^^@KF8`<8rh< z@w~cq!?=Ninz02%+!imYVui+uqlOJW!VX{7Gl6q+LJp20P6~^6wn7E)|-lLTqOK8ja}o@?)mut|P<8Gsf<4 zyGKkV;5Td3;_KDC4yz(-aKAYd9`NB7CZ2HJ=kjA+lzFW7^L`G`CQR=-qgciugumku z%QhhsrlRXK2zQZMd5q>JV%e>kxrBoA_XTei?^a zsO>On-J6;+d2sPgAj(;fa=I(=dE{5JY~k<+H1lWaDIkbs%4$~dkO6g^0PnW~zBs?% zRA0vczON2%Cg8N=j!JnGyNOPxOBQf8pzoCnIrPn!Z!g_P=Lxmugooej zA{pQEfpbn?X8?}%wOX@)L}p~3X{R#-uXe5kRl{%RfReTO^Kb2Ln(ZLIJR_Id(r-O! zE`n|MQLnZ>Mbdrj-Wu2enwg}%*SCi3(>0j3M+T|i9omlGch%0=9QWDgAKscw+y3mw z75Qp=b|+z~dmBIRM)mnN>cjf>(t1KR)6PnnC5!aV>H_t&hs&CeTi4R}jWoAA6Ke<}bu?U1r%)Qw*+WZiTX~+w8l?Zs7rPyY)k^C$F~j0^AF5{4S}x z^9y)!!(}Ma@YNMH_wkPmDq#g zwJY&WG`yDr&~%|TcBOeuk7f$Yk#hOV ziUyBDsCS+0Q7z)A#>5-;uUR%~b1+{y%qb_U=4=A)QS{C#{F4(2Nvk)G6}p~5ao0Ge z*oi~}$H44IY5R!MYxC&tWITaW_(>%LBrfSHR>gcVUicbH-~G002)FfQydK@X* zf=Qx^+}y*R_)(4;0iHeQK4Sr)&=WPtDIDxa?-59E5@isA(h&`GPz(%5F@<9M!*YDX zp*{`efgdyiB5*&ExRgrP`A(W=rOiLX1b)H&PCTGLyG}>DZ=!mhp8(%plDUK56+UYd zMKz0p`}t84em+m#!Ln>*gZN((E$0!AdlN4%rtwrG7AQu#L|I6r; z?f+Ir|2q2LfYpDL(Wkqsf11^Q1FKK}16Y0dZQ&na^<@@)ygIVIG4~f(eY)KBCs_S2 zee}}m;=lIM!+-VB|IMr(o1gtWH#aal(>Fc6Joz`XdSY^LaiZfNX7yzmz4+h3>Xv^7 zt8v4FEhA%JaW(&vMfbK{X3;&Jjos}{IBY$(x$d%zo-9fF%dD>HAFAx@t?2y&tbW(k zSJ=_p)L2*A+L(v!e%0Ldva$0;LwiH*A6ax&MM+sj@r#P=)XNB`78_sP68E7wrm88b zyx|Y6`hDU1qBliv^WPTa{fUdaw_!rwB~`5# zo1=w(jkxTf{|us4qnycuL3EM2ti6f(WexpOR1|eX%-qW153Snlk09E}#M03CA>x6H{ymF3 zcg=JR9w2n@t7;m`-!;3ep%q}-a!Q(iY1NlOw2Y#L)Zd$EaTyiSKVC4AznWD&s}m)-1G|cL`RLY`^;es#@(d zT3mX>)6i4!>4li>zm(DZuq5)eAM9F3R_`O0&_Wh{)$c|N_4Bo|g%WATi*=GG`on69 zC(Erm&>XYL&ahOX=EO^OGe@}8nKVAI`pPhgWYVIFvmq6X_(R6fM!s;qqu zcfx&+G(ME;&EaDbar$i!NK`odj?>mM#;(?9jR1^EJMgf(u@JMTlRNo=A*u*Lkn~{?rLdBe^ z9>Yqqwr+qSAHGYGExGa(hy)?eFutVopmmrHUDqR6gwwmtyx752Ek}C6Ykj#EYb*wV z6rSY#Dk7mrkXPm_g8V9WhGUOa_$8z_Ma^%|Y!+8^H~1W85k= zZ6sj=g-j$1Fal};j7wL8(9nCxd|Dx_^>#I%UNdz;u5y0gx9z$miq*nu-nLL6M{&4A z>pjUD+ESHi8c!uJa-e8+-vUPwQWy6yf*BWRm#r=7~7K}0S6KEsx- zVA_f%=N8lI4Yhq4yFE2~f>^*@bL4@rUdl@N1Pshv;L#!0Gq>k%K;pWg=@r!^%?S`4C8!!zes_K4yjUe8z!QXVRl}|HyBn*b&v6t(T?HY;cX7p;@ z)soqnD;m}`oom7rr8DoxyeD-ZSp7&91Z+eo@H)USU#`e#4V-rMtx5yV4KR z?2M}$BV;hYp&2pQ&sFRVgWEux+lRU@8$K`GK0cJj=NVc&vfQCqXBcLQFMjC2`6Yy3 zGQ7c*Cp7=HD$#S*Ny$d}+n9~kv*^)v;x)cUn%@BQckmF z4A&0Mcfu@25#PX^i{0}p(~#2+|J5-y>8@n-nVx66=jO<+;h7|C;gs&$s|d%>-1NdY z!Vjb(fnaJriVyJFU<2tWmQZt&ujwi&zOB>&`a;g5h*gRe3aU!tD>=ysz)(E?8j^

YVi+Qb3&vxY(PMHv$cp4%PrGC+a!8*mOU_)@Dp4gY zeVO&MLC^4Q++`VE8Ak9ckL3@r+HEhSS2CaNk8{8@@D=WMo6s3VkNnKAn~pr<`wp(> z_IaX#|8=l%{b`R1+X3dML8oL>KD7%A&HrPt`p+`D-(LPOV<`5mRH5d8lj&jRRR3F< zy50e|fWwzdRE4rVnuA`Mhgq9Ch4PcVgFYV*v-e^P6*n|L2OMl5bg!d_(%SL21J4T> zmN5phuj-q#J;bs+grWp^Qd=YHmylPd3w6%BFk$CU__xj?8W`Fr{F=4|qrig8eLtG^ z#ntn!CJr?PTN_519Od0a!sI0aSVDutF>-BRB~NjeO5!Kd*1%YyC2N{TtZFJ$uy-(X z12APo2a33%+YBrrADUx*MZ&4b(=ajqnLs~dAXww}D~i!5G5dm|VJ#?W!N(NVReLl> zmz2MqtcH_EGx99**6MQH!77)@WD$p01NW3=HOXD42WB+Sb5rx#zY6epM#$ff1m5^) zm=i5q!pfGbO~PrESNFpAyY=%hwcb!yJ9`PSw85A26scG=~! z=kC|rFaIhxE7v3$y^;e$Jz<*Mx0 z*d|j0o@)5rca0WnF}`8%x^PxoKp6L0wjy9sUaJ<{zUS8PgJAgu9h|-DyrDo+As{2b zetGuKYE>Qy

>azlj!J_09MOVlJWjgtsLcwD}`0w_m4GK2+h(6##w> zcGl=@i(1jIOa<)cG93Y(eQ@0?Gdp3n6>(acQOWUd91M?`J0Gh19x(4f$_0kYq_x;h zh{}6hii(Crty^V-cV3WH)w@Xrq^)Q#nQ%V$B2TRRG7iq4^A_Lmu)0kquEG*wSnbuZ zH}l=WH_@v#_n}w{{ z&D61LtXG7Rj$b*fM}Nkv_E+WuQ2PKi%@h}&5KQz$X`Z*ie2j+S6%h6QrjYpp4taZ2I zmJYwHIO!G_WtF{AyqTPK^TT|ee7b?tWsoNSSil?&QN2ftpPZ08zPE*YgT)O-#4>y|?| z;et88tD%TYmI`nBvdvrHQ`OVdwZBY3R3<|Vg-v8avWp}O2?phFAoEEy43qTlWs&1{Zg*&Dt1-ch3kFOrZ2cre z0EubRLk>cND+Z7#aeQ?N?IeH*2nKziAYr@gXIk*QEe8C#Y^$|bBNJ%O3_41Q0}kuR zmvpqV9=>Ltp~?$*274~;U&cx(=!Tu*RSRHNh9J3#yyc;C<}Tda*sOYjUKoXV`ju6G zkZ_rJ+erH|2t_!*0sF+xoZzfFok4;O-V3%}nt-o~AiLJ#QNf_FX4ZST;X|K7 z-G$h0QXN@5a^Z2TgaOK3P<$AqCImu5Kempf+9CaFLdpe!b6fT<<@l&_gBWq(JeL>R zQ;9L_W-=I+ssx-R!^cTXijGLpX4Ai%S5@PQdAo>Qp8V^LHd- z3rSq}`Gdy^Z!BQdGGMFuSO?*x_<@^nS_nNBd^RHKPEHb$li|D%P=f)U1MVjKT4vn7 z{p%)iyUY*B_iYxnY$3k;4Zu4YW;#!ZvlVNJ4x1mD{f8)kwSzAOBbU};n&e1X2x5;0 z*PqMX6(QX%0N?^-w=IDwFeU=Qaq+qLY-cWE6d6m52`MG zwSwjHqp)XwDaz-F!2c_WhddXP@g)R8o^}|%4Kwu<=H_T#Q0g-Um$IPc4=KuLiY4cgyV(r zQpq%wbwr^a_Af=4%?X}$z??ng_q`^W0h{@4?je(L!ACt?M$b$>*-S?JObBhpAPrk_ ziCpc0N`q_kQ4M&%tdLDpXkxvvyUp(>cUo71%d5+eLA5!FqCi9s{DB3_CuP}^U=bPNzb1@sk}etgy1K+9yp%_n2DzROK0-6lb-&v_^ZvaB(C#I%cV63@HsM* z_;tj31?`eYw(>!#QmX$oG*F8xyKv3kWKPx#RH7q@l&gcrxw1$}nO6s!=O;7$ra|su z5XBS|$OK)9-IsnEMyAqYdI5&9NJJbBbp3$&aPdaO`s+8)va7%KOSn<@r;5f+K4e%h z)766HcFJM#&^$ACQrom9?+2Wk2yZ|)@1U~AF{zp+nb@1*Nv^6EF000n!yi{|UeW&&tn(fX zVA89rdOs&5Rnb`2Jj4K9Ry7sEH4$c2^r&iR#`VK!9qO$lRK|4%y=oEx!WnaY?Ppcc zOjXA|bI(xi7eX~+Mf-a6y&`>`8KGaH#B;s*md;AR z2Ranws`Pb{jGDm5ABqBMs)M20JlBt}zX)=K(g~EkJz$pOX)Kzl+54$o^|SHwOjXfY zPEp*8U-(L^!lpYTdg=$vkI!&6f3H83Z8RKdD$*>wU)p$R-%t&JeOL4@Nppy(@LH+V zRj)UBQh8bm2rc&Z)pV0ghqSdk?Jc>QHGcNr{swSwGq=)BzIZWWc&nfhveJ@h-1Om) z8Dia%Wvv$o;{f!Ve|dg*czW`7q%B9j#eSo<8fbbU@UwhG?{Q$Wt!yKm=Z9cx?kW}F z{h9W6k3Xm#v47RCu94<7;T(eaQ`77Fi&3n?BbP0R+51ai;mRG`p)uuXzW=6+_0Ta(CzhsfGQi zW=){gey7-8*Y%2474ENv1DTrDJ3Q=W#{(9}O`0Q|r@BGP09bV!d_ib}@Uqj|^*TN6 zp+$Ew9k((GbY{E#PR!}DknOqgv`2ikF9BceZw;6{7)oL2#G!sEKKLbW0DR%)bUGTO z&uZS&AMVnGj7-2@pKfmLx>G$rjH&<&M~w||-OH=&T(M1z-NSxa%@2-~=%})TJ;zmc zvUOJ0fNdowtA0IbgNbf3X%enm5y>fwcpW(ms86RXBSlxO>`8pmV03b60W#R6AjDUg4OdIH7xzA**$%lG9Xr zj*+(Q!ResafStT=XG8S zg3TM1&Om8rZ6{}#YL`D6UNbAc2I>S#PnNBd7EL@`VEE9-z^5t6>$ay0j4pdX82C)u|Mxj>sE__xJpj`+rVG<8JI11`xqM)f%;p? zF)}tmx3Ovzw2@TWH@nKl-vvymaledXmoVC7Fk;W9^8A67uG`3N!SK@-Sq;_bQ5k;D zQeO6}o%}~?OVzj~TzA*%;Z^{?vwMUMWy^c{18_cWiov*5pP!SS$`&NO2`ycyvY{aD zxAbURi!%S(Y&6NNvhj|OV3#-xkLp~iIg*apXlQ7DP+%Rw3^WuVS$fIAzBx!>_QKWO z+s50Pp1ZVmFn=R@pDti+^)DggPXmIZv83tg&pT0U#6ekOEu(_`pFzJG@s?1T zFW+9I69Cg!w$$>UFQYQ~Ux2i}2HJ`_?^3S<@%-#>UP8z`Od3~@ZyT?u2plGocY{dB zzq)t8lM|+%3`!4AZf6~2QujZScOOigfMt(pHm*I{VJWvIUY-GI}sxLxtr2n zlm@Lh-qU3?x59kWU3PsrpL zyiyB0b7RRY|3;BwrLas~UplvkVnGROjruJME$3sA_tWP-(yxM76pYcsU!JUvHNLbs z4Oa6AK^h(<&ml8v8q|AxeeBPX)Rqw}V7~&4K3$*WzXhugp;2xen6nwV-sXXO1@?Ds zc`r@9-McPG#j4X`1Daml`qwg=a}1@FSHz!@=;}?#IaFA)0^_MHYqw5=)qO?UuQKu; zZ1-_~w7rzO?Yiye@EObOERu>y^{AkebRp|P8;j*NOV&}~Cf>wNc!Dh-iEL1WJ5b-a1OqqqAcO}QSAKaCdMyu)(4g3gcG z#J|Piwp+&Jo-OVQq99O@l;MO&E8T%&@5-Cz=Q3Q?oNlZX8u|nrZM?aBXnn6HG<+lV zr;n8LHz)4AN@&aTGqLI)t*_<-HeqtfmSpCE*@f?6c7-prQl4MCd=F1K;JRKUzqKu- zN|nm@XbJIU8x-Py)_PebEXnM$TdAKZ$t5ob4rwX6%kbGGWbWd=U>}I2qT<)@b>H`Y*v$XXYckHO)9uUoD|gnx#C*e+r8J}(*df*8 zJC9e7Q8iRAS8`j?2;V*yt^HMm4eS|8Nq^d#tXiR%W&2FRY|9pQtKE1`~Kdc1V*3S&aHE15BdEz z9WEFYc)a_^1((nD!&WEUOsTQ3OHlhJ_-4&r(jjC`m_fQ_ckdDws-9!G_%e$2v)L7D zht8T{U8oIKPUJ_}HeB#SE5AB1o^;2hB;>-#>zWq!&S5UFlwB6*kE~J&HF=2t2r)%Qi$&!8NG9fs&gXl1$kb1ScaIADKjD_;8rXZVqZ-<-eso&|}o`=Fx?(vY;cQgb6yoZz{nnjCU;^&h{TQas}aI z@18z+@(pMUyZwa4(cJ0&l4dJm$4Xrn?kOBADW?4-iqk7+it__m)K+PqO(lHh&6BhQ z!K(=c+FqJ3m?6E}>T(h*tG)TTmq*NWAPGsO5!!Ogtg5V=Dsh_gdLpRh8+{d`CI(?- zA=(U^K{W8tn}O?G7_la&f^-?qDqOcUdy{dQjf*Fz#D5Z{Xq>y{Zb z!4~r%kVHpL^`duP3?D)ni>_yGM1_>U$?>-`xbbYWKSBP}`CIk#x|xgd!Z!(@`G32* zJQ-$DV{=3<4gPe}+f5va68_@6(R*80u&-0p(KT9M7x1}alhU4r_EXZuS$PfD<~ge0 zeHtZ`iiO#^s0%&_?lPVnl1O0dL&pkE>QJ<84)Ps&-im{Rv`mPB;0AW7dxNHP7tIn> znlqQV38LzY>CvfP!ilbKPeouXMn`Yz=r%Of&chNOmfS%v4SMKFE+q`-Dqhl7TEjTI zrqD`Ci=@cT5uDmlNa~yF>fDVO!ncH)Hcgdxl6CxTWz4a2Vc+*ysV#Sv<(j!K{T7Vc zV@$ek5{}QQJIko-rkmt;TBWfR#>jbI50-}|dA+kV_xzC9Ck=3x5ZdTU%hXGjQOKom z#N!8g$c9IEM;gMT?t?zr%#9>TN8}i<1++S;nvQgVh3lZY8}oFki=hjgBD^OaL<6sx zB)12RqWkAf7|eA#iSa^0Ac&Pj<&tf#5KrE^W})gN@fa~vEv0(JrDEDRTSwN5{pPxEM`;QBIab15o_o%7 zMI@HDjyfB!+#49>koUJo_@(zFuBagl5|IQR%Ea{x@pX^Jo&m4t=D_-qz3J?|$3s+hT9 zS&H_MaxV=RvV!N6WyuV+Qs-34oEb}RmDCh{J4hmRw?3sdj^AMME$v}BJKiD(tMY_D zP;`nkP!2&J`?I7tyesk>9o2Pq@L0NYdrM+65Sukgh2}WS<;X$4US|-E`SOV2bh+xL zb^Aj?)4;%vE%NY+=?2^@u>So^m9J(ztaBu#?n`+h{XMv{qMtsz2O(V!N?yV@Wpe>a(F@fbht;}J zOs7uOYvPqO@tT#aIGRu*gLI@VeGyYbB{(SuG6GwF1W}HMg0fUdEtt-AQP75*wUrc4 z4Q(8NO=_w1VUg%ah2ic+s+C@OUmnx^oyg391XjQ|5@o%07)@ouhI_CqZkPnSn#A>* zcj)KdztSf#fY3Jh^F2AA^@tBj)tx;;#<+T_f}@7QN_3fDFD>QcB8zP>~mYD8V< zk;Y~;MB~D7)~eJomvz+0lJq9awUOG z%)q89jn7H7FNm=M8Bh^@qVzWGZUNZ2kT}I!_&8YI6bB-%Yu%f;=G1bHXvyT+^4(Kd zTTSX(ft_ZKZ*5pP480xuPy?)_qD`cP`4@t1fQUdgCYu^YYw^g7sm-M<)yX7{6!MF2 zTVO&v+*7JqfJ=QS>jR(E3b>! z(Os%&vTX@XA+)9j>T2eK+>=0e7eX_7TVI`ypl5VrM|47iwUd0MjZ`@Qme=g-6ntFB z{QfdjdGLFfP6S>lJc=BCucpmaC%i}>6jsjkL_C-dtQTjelZ0z5AT#e@2Umd6rf9g=edN!NgYoDk zPqfzx8ie9NJ+P+UhIVSTqd_S7+BjDyo~zZT0L;e?O(9)-)n*V{^RsZ~XVp=MI?OP1 zP%GKRkRArf%8J`G2BSAxN&`DXQuPZ*el8Xo%Kzw;c7>?jYJHE^e@&S3bO#-N zvTd||#3;5(q4FG4&N)3-Opi~$PIS=!B>L%R6a@s=GUfSf$ZH_>LR=>eNLBj;CYix% zg^4%KBCpQoZb}nj9oHWynIhPU;(f+fCp#;GyW%D=>pHCsnh>og?{gi^LUcf5F=o1N zdv}tulh!-G<1`5}ykN;~@Ij*enK zXnuu&lUUxyO<6}e!;5kY!GXt&3Ni*40B|X8;0b#cU8#9AQ42wPBRVzaZH~NzjDfn8zj8~m{Hj{aoy7VkfDcx_N6L3Ud;g$@+t)Ir+$tkBIZ?)Bhn5$u_nbEH z1Ue^MPB@<+1fM@Xi~z)-)nl^uHE1wiVqNnqI$2 zeL)_0mpYVSjqDDrNS>&3a2P)QN4IBoG&QVW_!IHttQjHo$7`-!NuJ=eM!ke{#2R)> zWnPGL7Wt_BZXq?LP+n1x3U+Gt2-%=dVo4g3?&%{kDku(R-=1p&sLU zmE?py7Sjply{BV~#5YxS;*}3D7hHySR)->A{feWARRQXkCJV>Hi0pf}AZnveDl-#^ zu|f}+hYS+_isxSrg!njorlE}8o45_Qk39*~Oh{#M>tha2Zoc<9df4u_``OWZI2sy+ z9ij@%smM(F4Bl&mlSPQrResg)%1`pZ<*3v3x&RcGmEDk|Tf-uF)gdQD;@b z!SF%7)v1sLe3eV(!Kb)X=Ful|n!ui&G{T!pPRv-U-p- zh~z5%Ew47U{9`aq$11Ppa+vtc5;6aKOW)(Ocb=Yp_BbqGYY`8ZqbqI^kG{vvO5YYP zCY~735rEkzH=LeZc0#M7ZizDQg2f37(=Y6z#{4J1;WN@F6t&v=ILvI7OJ8X2bi0dl zh|UDxF{6D@IlRR|wRjSFLnJA7>%j=0vN^Vp(6%#2Kdd zE;jL8LqEiaY+oQEG{O1N)viI-JtM)VcV3sG#C8(p(sV|!m2tW+5T@xjsJWQCPnK;* z&&{c3o;R<_d0ozL(g}YqV*6L8RPTJGed@yF>vVUj79PC&&{J3T!eb#!XSCq-EA$xP zSB*4PT69kgcDuc(fH-$?FU(Mlh`ktj2?SC5K7U%c$vX_2?X~(laWO+NQfF|{-C^E4 z&JiLd-!Bvy))Dh9EPn^5V#-lcF!x2^8a`~$^%Y&7tsT>KjVKO!NI`v!4CE4%6VfVS z^fl(bV}Z*T_vKe!>bV|MpN z)xh~%%`X>_hlg9_g>Z4;WEl(}ds;JHbtOTxU-)k=mVXO>|kk({MlA zpQDpPP7BiR;Uf-<;x5{)C2&n~uCI<4H-x>D=p-*A7iaM;j-%&^HF53=*ZNIii`%Iz z2J&F_RhZ1}bhg>GQ1Z&Xl9ivJhh#PF?Gwhs@F@MD^Si;>58eOZTWVxpq7u zOn*v0S;P^Seqa=ykHrG%b5y=5LGR6w%;pP!iTR(IlT5v+i{&JnzIhH#u;rT9h4IrC zc&gfc3jq7v(fm=EujiioqthEkKlZ1`Xv7G_n_~;CtW}RfYNka~{)o-ndA@^kNfG(n zpJOECj+}=IIo!Ah+NX}TzLP|h{=iM7<`a3Rz=Mz4)fx>ifsvP(OK2bMro!o~UTR!^ zOjxj$PtQzl5=z^^w#y8OR@c}~T7Nae-Yr==VbuC1UC=eHJShCxyH3j|p zIA6&F(TY-hyN4&z8p?D;{~;KbEX2Q$J0}XzKec(m4^~(paAk%k%@g{XenZ8;nIEDR zGZE&svscC$3`_hBb@mM?zVH72-sprG=|%rl1aJbrZ!d2%VEhxiuICu-b1c{_!rL3e z_d)T@Gg8c~< z-f>5Mf3Y7zIZXPx|K-w7V$nI`p!@Bmb1 zTvu$W$HC3{z?j$JE<_OFPr!?asZOv$-X#+CIL>#CFWA84aQtBa!p^VvLzGN6!(NI1 z-(VJJ{vD$U|A{{Y1I*O2C_tW%h36eMy!TsZ-fMpT+uf&hv>YXpIX0NN%fXMIX9^1Y zW8+v%>>G#?J9Ds1jJs-gy~Fm=LYJRK+$Mn-I6_0bR1IR0{?A}FP9PJX9IjgEvLVBuQRcR|Dbk(_pM^EdtaoDc}TbL z5Y!USKRA$g&9vq<(O*3<#%2`X?J0h6<#UIv{KKsit@n0QV|5X%7tV9+e83UmqX-3EJ7RUFK}dJj^V5hkyQO z>(3wlN9HldyL~RzNte(e5J@omBiIc&oDH+y6Fx7No2Qxs{kM-|U+d)Ci$(@12}X*D z3cqoKsCpA3&sFRR#>ipIaQ9`0e1+naAn{*? zlZ^EsHlYx$?VnFfUB8J?Q{F$w#R=0-_KBo9rRxq_OPqN;=y$hbUo^uhERqtq(dZ|Z z>9_fq@45fMz8LvJqfd^y0?1$dO{8eAqk4hFfp|`k`90F@YE2G_cWI!T}-(IRHRgu(sb;V6Q!B>>uSog$+v=( z=hE(1DbK$OShHYv&NA*_a7;emzi4W_p}bu5{p9jW=})yQtIqZJOU=JNfBW6?$NX*2 z)mrAODjSVwpQ&uNN>%@u9Crx|S8&8@bXi6bE>bQX%RPG}un(JwGWScWi?AGk$zR(( zAETvbHJSUd^7Z(_6%zGwCSm@Z5B3N0DwUaA?uEk2z*W^`JUVZ^$>)tWho8$s$zd+? zYp4>5-s^6VqePhHAT74O^v*M<+Hl583$pvDoS>dX@~zugjwg0F!d*!QY|SNht{8jR zd{2~$;d`~bq&JVbGD4Y6Up#-P<8ggri%;q3scoE*k13iqf!){YZsuf<|Ni$AZHY{MeR>IJvk}B>GskW75 z2xp)b#hSUqJ4!xEC~cQsh?%%bY?bY3_m7T4X?XA_VjivuUDu4e>ul-rtU7P-| z;r@-~iRHD$({TUxe+l>R&2+6TjIPWL|I_YY8Snb1-9I@$Gx?t|<=4V^$K2$={|Zw& zM~6B_2fKPlhyDYmObs;rhfV4GKiHJ2|ETu=?)*O3Rr$Z$l=;@L|6x-)+v-}HYyW{M ztuFFuzf{of?}-@SR8 zops7nUcY{on(?2>{-mU&XZc?Ob3gmN|K$Dl6!WT%Vl&p>-!-mY+UhJxuTgf z{~(prM^!2dQ^gogpYR7~n+?%dJl^qDw6*k%)TI^R|%w*{Ty2a8Sxgts+nS)1;n%v!v`qPY_x49Uj0XYi-*0S9n0$SklPtPpee zN^CPlo-xgY=?(;5&Z9Bgn)CuAofHb(*RhHqg~Iw>reg`l;@v(IxGg=Y9tI^?B*b%C zFG{f0j3289nGwYHmQM|6oPn~5*wXb);~s;O>*KWpk?TL(#! zAkep3lH!oD(=Q1iD;FGDtD`v&lRLM#R8TTS-G*W<)!4!vCOh)jUsNCnA$j#POquF! zerHUSQV^f!W$avU0y*sQu7wZn3A#WyhW1MPo8pFlA(hNeD@m|>_i?wtB4^{X(P=&P zn%0|y)H@J%o&3;Q{3g$%k9A4+up2x6xHnh37u?FhVudp5WOYqvt)~ZONU1vfP&Q@D&R(IqD3LHKYa19$_ynyY2jjAg0_pZoeKJIHZ4d~3>~{+FJ!ycj(5Xq&jBiK-x^8r zxkfVsN}{&sS$pbB6fSE}su^dF>RH+1Ze!(y%Y#7nFAeLup_5^n7w(0OV`t1ry7)hM zK$v-k=NH`~)=1DHV8r0E7<H2mR^c03!Cb z{VQ)b4QE~aIO-nVOFZSBU?HGA*jo!XoxtI2v#z~v*ofjV6n=WqvlA0nc7^{ugRG7h ziVLa!s=m&AzFnfn!Iw{E^DZ+{yL$ijbtHF+_;Z)GBM+wYv&N^SZ7hg62PGWXiw ztL?T@yMhk3UemyHF-&@tkTct4utBamXB#E_@^%&wo2x0N*By0p`wdq|?zKy8-Escg z*=Ts4j<(*fg!Jv4@r-NNaxB=igBWgozuzKie86g|a*yYouZ5PIU!uNiudJL|%ZA;Q zNh-q@T8$S3wbt!<8Ek)v4y!3OWvrOTHkB{?*#-C7q&I3W$%|3f)pYhPBKLgfbFs-q z!`?F#FC9blPrcY*;d+2vPKZdwojh#Ckdk`23y-%v(gtjTbb;iA4^5EOZ`whZQ?u=h zYc$;3P=lp%Zd_I(M7|33pY}9(;dM(6b(Q)vnls_N#ij{@i!cSD7bhraO8POB>%kYv@oCu6T#s($UlDu)zj*vmfWw%WZ^1W%VPt zU^yECnzf9XzjuCjMK{|crw;MBl1+i5U7FCKEulHIbX#cC9G}r_`Gk_CG-XWMBtAh8 zn!1&=Fr)a=-|;+SExNXT_iaxYp;4PO$wYy{P8MadNl zHjcP_H3jW@jp!M;!%`mR_SzPACYGmp#J)G%2eO|?6LuMx_2!70$K#ZTcEp7Xbf z;TwgBIk*+t#r(IACJgDF+$^icsxxr2S-`LBtbj5u;)`_&pLdLq)ibL4W9<1x=g
|UyyGP3R@$i`AYVEr^_y}6&$Fj{@MDfOi zS*r*Ol|`P6ILT2aI-Xg{9C@$Eh~`lBsgZAWAAZ7>uo><^mCN+~*D{Bgnw_pHMYV;7wH!AgHGGGO&B&->}6T_J!`b|L-!+$XLGNG7%vhq*FxNcLh zPA5gQYSRb;awiR5_Kqg5rx+bC-J%{0c2(_s?K)lypdL;jtEqd>8VRV9KVp57E7XqG<})qv;!6}yy3-y?(EaPY9VC+MUS z2EU$?2c{=7h%E=`G{wK3hIZNx;cLe<<$(|q=P=I=wOj}o@wmUgVO>N=yCw^>AnWdt z!4BQwa(m${PY@DvH^xL!o-M#*2GrXc1Vjdyq>|J=$RHeL5W5t(Y7Jcv2I&lD3n~u@ z7B}WIiD366GRnfk68*vP(0LL~VJgi8>B119v6-75K z4QGQw;5## z9<~0Q5fy2lmcXiueWfV5Pe3rOGc&jbDC} zczK~0yy$_PKuZ_3MAc8w7oib{>pZosQQqsw#rO@FHZ?exseY^RisbU_-s?kpS{qpLTqCrI1Q< zRtA}k23S21h3JeezZlG^qgE$PYytl6T@(Zjq6Rb4+d~WXG7#zHQ{c7Z!3dYks;4=oH9A5ln}*TmcRUvd3N9NvI>mTFeC4$HJck zGtC7%gY8ooBf(UfEINDeaS5%WD_Q9>tS}eOIF#KAfgac)h-i@C9@HNV^1-;GYN9-- zH&0)}()dh)Z?fqGFZsEfFE!~3q;(!wkVv9tg27@7Fda4~$ktLI{9#D5V z2zz=bp(L;d#Y@(Pd*QiQ30#KqrlHC}2Q(Yf3Ww0V_il@N?E1bS>iyGS*5^vh%5VsA z8CsTf8nPXdp_}m__?_)KBeez$u`9EqM2Sj)So}ZCH!}~+$D0dsc2J@DbhLB=p7({w zS(x=VR8j<&X*TO&(bG-nO8Tb=N-0JU$fiLKUWTnlm96Ws73zFAfB!?@e)PsA$j@dG z)w=*qfy74b+hitlm@)B08TkfHW^g6@A7uCqG2Fp@y%UVOvmRsH8f9=LJ7$ph+M^6Y zL%U2VDBLSJ|NX1X{U9$ikTwx8>4EUEV~T$XI54}`qu)6$=^V?#HL+j}h_!GK93T$r z^~fv~2OVO-g?qH7t?)&e@evd4>XXvUSnX)pifER2sHZgO@}o&J!dR&|HQ+OT7$>{aznrm0FJmH_m`G0}VaVfO-1$MRWWZisZSsiE{>WT&)A2n;FGSOv0>Vbv;s(#DRO!Hk7jg%cI;RhWpi8~k#@VB*$ z%C~rw(!HcWUe!RzKOj=U+-WN{w+dT_2rcy`)lQSGZ(wcYc1TVjcabv8;0Jwvp@E%B zgCmOOCGfLM<>yOW>j0kipyFqra5Lhlt^TN;Y~7Yj3!}^W$q@gcO~oMEn!}lY*!_86IbVsER64vwLCg85meZvMo!~4Nn z_^&i@iU-I!jhm^xm(IQ+rLdn-3(ri3xu2syv@A>(X!cPB9AXFj4DbpQ{Y~VM0aQbk zGyr`tNauvVKhgim4i7^AKDdhyp6GvW_v!`hV0wrC?MikIBE+4SiL5%re`ChQ&Xa=uaydO3Lb`JvUabIa;yGl-colU6sp+ zca*`ib9{9y&uqj&7UFKewDpoZO=XY)-=o(temK*{WIXQS*%|Hzv=>esJ?(RJkhN@(o>;K)w7M>1{7~|*Poj% zqlZqCMQB%mr!pMZtov2sj8-=ohddB9Oei#hBd(J7?$epFhKbiXy>|MuUp2=}OQ#1s z2fjT3-W1I`3u$C1Kg;1p9p@mmBLb1I`_LEH5={F~m4~#Vo5GZSR_7XK9znE8?Z+Z4p6IUEyn#mi#x=eI@ zTYH}CD}pn`eI>DX*=%w`^n~-L8ql}4G8Q_VDZc{kUKw0d)iW3{om_&+uG-5sSe>li zTq(D(pB>6t4W9&Q6t5xW2auC%!L+M*R4<{|wo0f;MIxHwJ}2u%Erk zo)>aT=#EuVUZ4zjkS7W!#C!0Wq>_S~Y{}HF1JJ%({ZHKHs zM)rL}SzF<<8#pBUouh61#&&BEhj8ZK-K1?N{9n4sRorBY_=TNujh$foHD@HdebX-^b6zMouI@!#RR!_VBO8h!275AJFdOY>Xp4?lOCk<7_@u z)`wN-3s<@C+wNaQ?Ov_jeNno{fL}A~-piyKesc$sY^U=6uo=BxH=G=YY;JQ=IW=H| z0QK}A#DiO<`%w)`whs<}JZJOi_@g6m0G~WWvaQn#3^v-bv5z07j_B|39bcuTn8fb` zRDq_N*W7a_Y(>wH72X`BbnjmhIGlN{H+hx&Q8oK&^@%KsiXx1#)E+^we>ba*d>+ie zHuh*_^-qxs!&CM`v(tQk*nI}qJK`SK{#(BPe?=g?0ukymQW3Y7c)vg2@Be(hanAq3?|1ce@paDY?3|tZ^Y*A+k7ntS$4NAl$i)I# z$tt34xQ$gP#JUjbX<8wV^C6tJJFUquC1kFu+ExfRjkI&6CX;wO)Cr%T39}{0PYUhqYYP?^j1_R-zGbLdugkhdn})mPn~P8s zGUY6@WW|b#m0cgH$g=twH_=5@`pTh~oZSW$z=xj5DCkivrwXWP&p`c(TC?W;e%@aM z&mCFac-}tXQdN#TUAL5(ft8Kl7}HG=&@fJDuEyNVs0GA;_VItDzfe`~R-+~;L|3Y3 z(k*SZQSpxc3*cjc0P=nWFQb`p+%tm$RU#f=UdKD%s;%9N@0T~-YoSF>;v14i-e)_T zmG+cC&Ad54_X}n22h8FIOI-}qf<)S%K}zdNJS^Ns15Q^@MSwc@Ar*F-#EkV@?Yy9_ zsEWgh0%=XnYWqk7O(3H;kSnx1_{T&7*MQ|=;R7^%cEgH(2fT=(KJd+MHDuSTtk_%q znI(5$f9=MP1P_@;S9mShl_Lo(Pd@23-6Yr_haB1x5cR!8y1%_Desw^V8^NirE=qJm z$9Z;N!7ryFmZ7w`;&xuDNA2?(o1EPH6S4))vl*YNklIU6y;?{o!a0%}(|g|2-u1>! z&T)k`6=V+e2>iq-GYX0poffgF_?a@VCFk7tpQ}S_V&qCcsVX!*8NYbonl^Ft4&grv zO!!vk8KE=0O{6_VcvquYb>aVm-%#vCozlwFKPouvG-$Qb&oOsxHbZhRW$g_+&r<&E z8CMn4JAB`2+t2t6E66k6{kl3UVdJ`yAjnjS0{NZG{+W(^4yCEDra7aA(yw@aH>cVI zPAwuZFg(v9h{SEdl`aFRNmtlt=eoZdKPsh4qE)Q}AYU>JTw~eeUps$ZNMJ{3bY}A6OO3npfa0@-)>So|>|A*BQ;Q$OuiIfwNN; zM6#=PAinXzJQ|`+1qJh}$(+(SG;pCzf0k&w(-<{S#57!+MC2VN_;tz{7Y~^sQ!ZWvY{oVuSWnuN+*KkM`p=>^KvLc@@JQgTb+4TMDCkMT zQAj7E3t^j^aGT4;;IpD5=9&2$21}l(8{jcqtzg0`|YMpF@|x}f53|7E^Pyv4ksN0^O7>t zkwyu%XyMQ7z({hfg1L+*jE@~jjL(9NtKw1UzdX)cI z=%DwGH%`@qK89mWfbX6)*(4s2$m8pqtMg}CC`KcZM=!x0Nm^x`tkQY&UN;AbJkJWw z$Dq}uR|uTnCu_6`B|=o*vJ(S+aa_o~aV6oRw=K#I+k9D2#dZ6U9_`=HUZMFhqM%+G zVxIK0o)tePNVeAH)A(Z56pnP4zK7y7q-eKJhN^$URYvR$Flp|E}JzqFS7ATrTtaZzIUJ$TE<|J+f8tl%Cf4%uFUnZ*?or>u-2&X?Kwnp!_9yZoBK6ePf*hY0H(XM(YMW8{6iHV9~g}WkT^s8?uIN zsXI^K!j4S{Rd$Lxzl^ut!LZfy^@<`T!mWaU-JfX0QNn+czBkECRo5Zk`x?Y1>^Duj zkqo)t$=j&g*!e1qmJ-~l@bV7&G&|N_Q$!=~{UmjEZe6Cn`eRnSOJfGl14F1@{<3mX zjbAh)2MMz^7Yj)rnbuXBFZKER=RCW*ItBC1^waUK;v|r>w^-6p>^yWK~b1U;kcp zmzQwGv}Rgf%~h~O_DBZ~9pW11HnuN!$GM;Qg-I>5=-$+lO*5n^*2@wsnTMoM5a(v7 z7ZXg2pQ&Pf1JExXY}0HuO*2XO2 zywUh(L4V(K&4jshd&z>sNG8z2Ew12lrq)&FUM2M!(#O$fnx75sp0BEt%wVxDyt46o z%F;&h-q39L2%=dHcJu1l%2UZL6QbX$t~cYqRktuVTs04?f23FA4%?%7sw`R0m3|Q^ z1z0z}R4e!W<>|o9LU^pOk!p|c`>FK}*)&M#eH&jx=ls`dm~5|uI_Tiz6>h_YCYk1e z*I%oG3&r);v&6RjFRhm$k=>r)Pk%u`CCZDV%2%FJNfau-zud;mv>ZH839m@4dVmw& z2gQDhfdVDLc%ks%5R5f2h7b-oj$nLIg(bWruDL@_pHxT4=ayhKE6oW}P{kls(bid5 z6!{~NN)SSgyBwP>(SCiD#u<_|F4r>W_Bj#M>Wxu}0+muOw0iCX0sCrVwrcRN9nlr_ z2Aqm!erOS?kSj4@Ct?n_;R$K>sXwO!$-NLVyG49`xdQM}FBM3uLFOszCyC5_7P-E| zD`*TM=A$|OBtG+*e@0zdqbthc_CijFPBTn$Mh%YD(67M;-U6?Wu}(g~9m{?CJEpNm zfi^tWz!|qCV%1)ye>A3%NE!JQau_ON4zPTr89pMAAfR5mkri%TdWdaE;kZ5B-(6M~ zKA_lTSHQ4??RKPV>hBKQ5s4 zKaX~x!`A46ndw9WR@4H|)q;*`Op~aZOVkok+FKBm$T9HcBlTCuad)JsX`3{;C8R}G zT0=CDS32f|L}X8=01Y22by~h-v6@sn#BW?zKBXo zN^yzTp4ROy3n9YD^<@f!EAm;i{5wB1hrrP3{=AfporV@Q*8$JHV7s^)8ZXV+STzjuq^Op{PZABpEuRPFaZ0w;Y?nY>3k2$u2 zXCP)F!Qw%bt~02AA|_OgqNhphMFF8Vbih-}AP(ET(*Qd*rkLbGhV1CqHTPrzBd;3e zpbh8Li%Jx8^rDf?O;hyxQU2P5-=Kzsn?5U`Dukh9f5>(LHomzjVa}kGr&=tHEC5dS zRsk{#1XmxYud#mIO47NO(1%0CEeRQF@Nh{S7wa9;4{sR%_3cBUPhS}f+j=iENm#*6 zctRpz)bd;`o5uw##XCX_XXUeuUb?{*s)Ks$3Mn>h^6qgoIXL!JwU>ZDUT6Kzh(Mf}b*eOuk> zb3<0$Uxo)_TuQU`FQAUUJ^@<7i7qC+0rxqWoc%zl-bETCn@n|!V%9Qx zhA&E^c6GMLVQ#bC!svWv$l&{ASZ>S9#^lv+6O=aJ0-#s*Z>X5>ri_6*iO%k3W_|Zu zDZy=6&l}KF&4h}ShXe5Uzu&))_QH+O$4PIF{ms-ModFu6>}p7DzQ@cdA8Uu>C!=}W zH2kzBH$tzU8(O0adF>|yI=>1}j=;Wua1xeTx)KRA7{33xz+=f>hlInfl}KP&g_C0IgTIvO!mA5isC%2JX0+P_32w(*bt|W} zjwE(Vh%UP*g8f<+{ItbcZw<9+v62Zyj=O!IO9-(%Nr?4UampsE7+06r#-H+2W48ySz<%3Bm;TR zF0&yA>#wuB%o#a6WHy?cU4B1Z32W`Ua%9X=X}7@!s>fAtM91C?p4y15!&{te;CqsH z1n6i{sn${!G_*EmT1K8)#rhW~(8_JHoRaxHiFy|Hht+d)n6K{eKwzW9Kp{(!aj zfNlDKef{93YR-EO5-((yd>Ggm6wwPQD^Uscg<*Z%cx$bTZ-`O1&~lbm{Ig-i^%y+L z5-v6p?kB)g+7QBTG=4S97J*58azMyMFXYyYJh?*h*BD2LA&(A%c`?Ytl3>5Xg|hcE zWGwIe4pa)z#yqn2QDq7g3QQmp$gw}OKU&~;!aT}SEK4L{w{0{K;IdQE&@$5Z$G=1W=e&T(4@|gV8hw0Rp|MZD$ zP_ou>lE6E^Q?1_ENCl3QFae(Xu0enOemxs@voZ=ofLMG1B#hSlruHC;T96scC~zd4 zp*QHc7}nqQNs}TxB2OnwLGG7z6N#F!Xmqf!#7Ky}eK5&H5GMFZS*5YzO{^vhmcJO} zML3Eh{~gYc6<`7VWefKy$xHeJqW1gE3w;_sLW0>~<*)|XxMBqk-({^oO*?&>bCWDV zi1b<5pBUu$u-2c0?cZT%ztIgsK5kD-KmPgk>DuD|^X>D|pWHvVjZ8%Wl7Z5bkEfq1 z#ITh&$u!7A$|T6+;;=?DY`z>nmD=zrwQ?f%Xsa=7axx&ipU9zx;2`ym_{}_`l}NKmO00`5N3mUi}x`Uzyrmp4nTR{BLmoe~p?) z*A}PNevJJmYF_<5v@kpNzldO_PZCSyZ*PFx%(e#|G#qP;pUm) zw*NC{-Xc_v40Mh3eY$R$`w5>3-EBRc*T{a|e_H0Rm5Kk=GWS>Z4Sgj1eClj!sA;IJ_z$(8`%ljNE~U2WzjNluil*=nP5(b_zqq*Y zKid9v&YYf^otBoGl9C*gUKEp@_uo15|6g!FF)^_L;~X0ohl`5-kG3BXhQWk{y?l-S zkF$S2vA`<6Ao$tKfS~7o0Z)DZt75jm=bOg<1MV9{<>*9a|3}-`i1gOFmiNQosD)*! zhNLN>(-cst*EzH7t5~TQ$=B>YA~;?+C|)QKFW?{dA9kPTNequ~^fkVJ9Wrx13B6|b zAOFklXX~pxaDC+9>~Y`zVYUR~x@C?=NZ8mpTiO1@?weWt!|q#KX`5Qw8Cf|QncM1{ z*ytEqY3iD(Y8lH|+AFCUD5&WEN8Z0?_y4z?`M=G50Wqb2%zaTMUSWBjTXNjDVb zKKlQfGsknJ8hst2WSjOdj>2)M(>52!e&b^2GSd=fpvrFdUoIl*%&#gM%#`!nn(M2+ z&Y4w0AndwHIr?EixHYK)sp5vBf6V>soO!a$x_W+M+$VnOuIQ7AI?#ay3{#Zh$84z#?u8q7A=h^8>;;guLZtI`kyeWK8d_ddqkO?MipyDax* z)#hQF+``{sk2Oxn7Wqe*_9=l{8n*IDtg2syr|D57o1IBd=`GzB!@%q__-Bxp#57)t zzB0zXvhEYv>Lc_Ty6nZgD+|}ZG3q1E#C<_#?7-TJZ>k#_zu3c7$OH?5hjj|FWydS> zAW{^N2`9C$<)82Sk-nE)Hsq0d8Yk6ipkbgoR*{#byH=w{&?dbN9uOps-_KSNWI5*5 z^o>Qr1V|&Raj(o`sv(i>X>uz$p^VQ`UQ(+T!CsS_fT7@x-D8?O;zf`?CpcLRp97YM z=*x8y`C&Cgj!WWjPs?o}FFf?%0W8-5x**4uRV9f6k zbWVlqgS!tz_3jl=yDQ*}+lAd+)NOf+jpa&Nj%i|gX{2&hCcKd&wZxRu?-GHL*DOH0 z3bMT7c*^sqL6U?9BCjD@!NTM^HUf!M-RA=TO`ff0U1Q`yIvoHXIEoWG2r zrK-$V^m{EF5yFS6m1+U!pT71(zYUmpa1&Qld>(;pcH(X^PsEsOPFd202D#d7;? zVBk3AH2u7aDCdN~s*&FN(|J|3D+-#KwF&Vzg&qtq%*NzO8%KH=&1Ahy*sXvSAx?LW z#ebx^-f*7VS<^Je5DUIZs8kZk6mO=Lm!sK${vLGu3Zw~tX0Y8V1e>Bw7s79m*5<*Q z4?RTB_vyFtLCpy!;Zka=;Zn~HS#JV4iwEcmhUQ3Ga(bomjwqng&j4&?GsM(M4nyq= zujsb�+R=i6?hjRRD+Yqz=y3+u%Rs)0V>>(RnXF^ItQq?7WsHh%G zgfa)F!RI_ohjcSrg+&0LKt%FLZqz}}Qk*~YyfBow^o{CylH}Ir&oG1r#Wt-I6G~iw zhggUJ?F(rL#jE?aZ{+4&^-nfuYzRCuF>x$(B6RU(kcN>jvZ>Nq({!ePEBwA{{J^Qvw%UVu2uh7O4D&6BBoT| zRd+n&+i{WHV5wnH|9JMF<6;%ccg7LA6L~DZN{|NcOjG+OiWGj8lCKg=>1*~BwTtua z(Sih-#@;xpB?}a^58dt=9f)}0$L}}i?l*+y*G&+L;cWCk+VH_1jYxCeutiI^HPQWb z(PG#qWLnUhU_Wb7ml)UJY*jxq!*Z!P-B-7b?DpArh?YrR4EpZAuDY9)5#k^CH%G;0 zUpKUU`3A~qP)0Zk-_01x5Mn(j7px6?bhY8ak@(fa!6wl=Y;mSj{pQGiWe%#$rq9m*{r88Kr+28v~y$bIH_p6AAzojjn5tHty&Vn7hpdOkvx?jpvWT;RNR#I z;ltLv_*4|OLE@?Jexx?0jIVt@%~4FG9VM$PWjVLpj}}5wXT8Dy`9rf$dO&qS_1XTa zf0l!o&qtLilv2IHvI81;Lf^ZGC;6T~gc_tY>&gYqr+trj$EQJKp`Y)&^O7@P>^8#i zb+OT61H%P|Mt+|MBIP+jRbIiP&~6B;@Qc`xv?AP=BZ+$`>%oE@)_e3zoXVdhWJ2+n z>@me*B-Ogx2|7>uYMq^S>UlJS+VDlK`e(pKg@N%7mChZ+o-IsWB}g-v-te&_7DJ24{W`Q+T zCGNUXqaHz_VHKcR0QEr*<$Eq*5sH0%!N7fy*m41YgPTXg876Z6Nv4-aR5)SOx75hS zDyYpdpk+MBQ3bT2LggFGm?MD8KQk*lqx)9jd9Zd1h9|zJ_F*bi+M~o^Jb>hoddiid zJ85BTVje>Vyqw8w74r~(n7LlyjX3FQHd zSR+2}PlH*<1`JRF0|>%qITUy!DUDZx+wp*`3TnTj=n(>u>lB_em-5#YitnSiP`eN5 zHP3$r$KC8Rb#9b%pd}1K6IMLQj zyqbKH0z(3ci6yT*%`+$1h>8N4Aj}#;y>u3xlSBQ$Czfn9mPD1k^pN^VG2IQF6j_&) zKR&NP;t7P`RGc}6n02J7pQ6&}b2CU(DL1dH z_X-?|uauNLb-)7YSS0DnVc?ixmJ%xSd1)qbN4olAW}Bc{;T8N*vmi~+SH3t9W$qKH zJNwk6jzVwusSoAf0!mVebJM@y&6Xv~UId#xbk{z=i+N&_-2;H45vZ%X+C&PNpncXq zf-nr?6tMR&pP!5C* z41MoIHN8oCPk_dzzwp6VjIa(}R}RY4hQ{j~o#~YVj1EN=LJn2Sp?3C3H&dXp_zH{p z21DDx?l+-V6Yt*R1Cu%e5lqqc9CQyf{bSXrHvn84KGc5}l{m;;Y#bD!b10{?H#O&ay%9}sCN;RY8;}K8I+5hCE1Ob*L?!={ZBivOKpb@Y71HY z6&30=A9Cjf%EJ+^NEFD?fqaG|rt6&&*%c8Hn+kP)0$`DYTW_u64ne?>1Js0=RsH?z+a^62l@t{)|8Ea=QCQ>L~th8Hw0bTr1$_Lvc{@Bj(k$99= z4+5RVb6Nb3j@qY={#1B{7g9n{fAt}^ZztWsm%q-ueQ&EYL?QGOs(u3mHT+cX@R`|w z)s5Iuh^^0`s}J_+TUq%6?Ro>Hgm@!(fg$x?dFd0-MNVNmjOY)({P8ETC!S4{LZJl; zfrVIw$?kfts>;E;O~%iW$Lp|?E5SmDBvBSz^E$B~o*_O))LGoEOY?wrDgLwK@U)+y zufJOPi_4rM?5#~m+WzAXIMs#^c_55R{kZ8<=i?+t*17^kdldDE1Gyst^xh|~Ih49i z&fwxYPxquM1ySw$uqfqFMj*(7@RS!S_YPR=&+%MX6x9K~+^nvGlA=XN019{ntIwdq z`AE&^!H_~+-lIkDJg&zxXtVyUuTRF=ViN%(3y?#OG6O)2AcC?(llmJhzAK{uEbssCDTZV zdPEvl3q($Q(1yMm$U_H*s#8E~QSJ`~(kqhyW(a~zaLLuf2LB|0_gQgNv#ErGHW!RU z9{`o-z#`LfAM{296aYnX`g3i~?2y`Q97G04aCP$+3L+5fo#Bo4FDwk?azX<=w%0nl zVJQcU=J^0)SmzMi;I27vjLl?3$*{?GkUn`}xuB2OH|N`q@mJk}g<}GVFL-gsm<9rE zg&J-v!AdiSsFMf3CXqB7!}>Ue(Y85%&W+387`Su5ngD$l=jl(cJ9q%}*meZGIv7R- zfU%DP5G=b&EzlNY5=v-MKO^n;(LBddVC4Xlmoe8M6Z^}tTr`9jO&~cK=DuxA@t%?Y z_IS<}O`q7H@y}*P_WQ(cIYc)um_;d}<#QymG3K=2NxBxG>HFi^l~7WXG0pqNxHpV6 z1|%H|Q0v`s8urQM-a$8_QI;GE>zGMHj?uTOK-&v*m>2j#%;XD)sWtSFJG=33;cuwwHMguJF{@sdms&kpNMfs`E}(q+2H`RzM!~gaAN`rJy4oCr=RdZPo|@Yf_I^O zh|wIPF;d^bg!e`=UPEp)xkE4z08e3kn+1Fy7PdQ)+hX*7kWuJ1ESr+$0R&p`vc7WA zs6K`CpM7z)23e9j_%-rvqUiSk6v)2tON~o;v_wy^M zId_`zyvot9S%mp4qqsM-ZjRr{=~NHFyaQr zLezfTY&AVCA0>@{&$Gwe{1O)Ma%q2MehBzo!rN%+KD_NEoHc8S)Nw&}$dEppftCF$ z8PR++=OU13L3PM5&THi%dWHQ43#T%ydSqqac{z+|CBkHs++@`{)>KiMWju3{IQNHR ztSMzI%qAO-doe<$y6hfnI&>e_Xz(r4chQf^DBp`w>=g_-&urT}25MdZO26T7)v>Bd z{3HC8fxO)h#wDnt4=nD{j~FUbNcKYa4s*`SO@m{w(_%0E#TQ8Kdbs#%wxRYh&5a2Z zmG2ZR)Q&N%6~^}p9-X}v=-fdqzGCUP1zaR**oTf9lSy!Vi9Fb7H-GRIY1Uql998wJ+zkrxK4HVO-yFVUlvhPt*b5W zpLxUI;ghmRpiA?xX39n7j(sXl60rT@xN<)==b=i+;Ck%No!mnvYDVoVC~X!MY>T&L#)Zssn;)t!W|F|fc)*zuJ?||=nlB!#Ob5ntSAG=YuKjU;co0MwqyJ4#mT48 zH4Bq6Gxs^JIrb&Cvccq)H8)n~rc?o=nFf)FW z!0`;;5bdURpEO3~f13Mt76P!X4`{6$9$_ICoI;f@ga0FE2D;RS>EUl7K2nAyORwG9 zvuk~Maan8Qyf9bN2N2_7tQ7oS)@aHe&UW|Ext}3Il>u7L)K$@5WBN+C&eUbB(BSRf z_9LOMA&~AdMJk>A62M)8&|g7X3RNqCCqw2N#ZG1^I*>n`^_V!V4(On$`gew`3G`eN3>fKxRoWYJPLaG@lf@WTiI1P|QM}t;3h!YD8HcQ}20A4g z$q+2E0D;)yY8EZ9jJv!Vp3}*Jl))t{U?@n$aZo6AJW}@tVKDlcmYZV;)qJCSu}Oa; zSJBn`CxLkbNv{OHV1&rP&KTQQ3Ok;)^X?yF+$XkXLNF&AUmgoGDDHVI&PVo+k=a6R z^NRRNbUvS@DEf489@=oVr)~**gsF#PcQA}fv$>5}QKWVO!%ZbW@iz9KTsB{Dm0Vbc zKSsNlhuLoSq0Y_|c7ygzL8o7ZjTA=jSb-~L9CJa=X?W#Rjg%UA?tl7aro1g zr<~Q3o59g+B4xo*T4Eb_=E3i7{mf*XpMQG59Xi-vo70Bd!+v;02nfAC%nib<+-$py zw5Uh+lttHJ{lZGDkUhdjusTX-$3NBf#HV!1nK@!yzHsbe5vD1Q2aG0<&(bU)slLJh zjL|nAQImQ->A+2NUk_k9Xe>Nv#hg9nJo5PA05?^EP5G!rNa`e53o!q>uMtXGYN6KT zQid+^ zM=er1ydZ+VYsZm4=4y|&c8w57f{?T4X+(_B#JnB=Nq;7S@;CXyJPI3Pu&iib>Yx5S@h}>0;|*;Z7<=Dynm&hqIa*!4Itk8T0uQ3dI@zR( z^tDFm7m-^}K5sXSrBbDb%f6Y>a&RVLv4~$bc!$l<(emIBQpYkfSJBeyUacgxbrq=% zh~q7xV?tk|qrR5VvVc5*Z+K^2PIMW;}&|@Y>4i%>_w?O&Pu_T8)r( zSj|Fc9*R}EjMPq;WHK5~eMJf8*Zp^Z$AU*u)LuW*E^A}bA|plUbU7l?1E zjJ0I#4|7{eM^bpvVxQ}}m^=({;YV@Kp#9ZuhQ3G2Eg)fC&ool6IPb38;3`aCUapjZ z1Z_1Hj!fEL`BXlBxvXgkfa=p~u-q_-GuQzoIDZBjjBOGjCISXajcfTxAWp7CzrnGg zXpRCvgen&#T2OzHt8^7fg#gj7z6ynFv?Kij4n;$dR`t_aNDAa%njcia28ehld--43 zw9mD*!~WO+6K{vf3F21tF}RUO0X_L#pvvI)QEf{x{=#WGJaB{Hrl*J>XLN4pE+nkz zoBoJhD`>M|!5ZB>bV&1g-{v@(fI5G!WlEpMjpHRKuzaGK%`T{#p6$CcoaYp(#Hho1 z$^E!j6=yinKo`|OprDhh6!aGQ?B849)-K<4eytn7|CR zUws2Uphd2wJB#{t<$1`9YuQL>2otUL-`A4Vw$_&@)k^XWXG% zs$cC@X!UrcFwhP$=!LIcF&i>kZo=MVTmWkD+%h)b>m78FYUAv#{X%4 zsr7V7$pEjmfzqMFJiQzI4X^yzdWD_y=}^##vr`7|hQnl^liVdNrJgs3cZiT1=XDgm zZ2L%mnr8!9b(jrT-=-sKu-N#92Qmk!?`mH5J^>9v3xeuUn z8z2|w|5=fe{$s?;9eaDmmd@@ON}XB}&atb^YF9syIv%-YAr?G!y>Ck4Tc3l@n~szU z7JIO(votJlKKZ5PSMN{oijnE_aKuef>-xz1qsW&_k_F7G!GyWWE9K0E?_I3oFYmq@ zz^@elK2_&X`9)3Z?dspjGJQrC-Prnz8??8~SYj>a$CZ|t*3A1Sh7(C1>=q6#Xou9a zd$+4VYuYIb+5-e4WC0y89+fnBO9qPWQzmu@-`cVu*R~A$c`r|~A&mJ2=w5}Ytw02u zFu83zNW8uEizfv~GbLkL6zv-ju8fnpKsBO4m3=_?#q~Rx6-TJ<=-cjQw541GXlAZXB*O(Rq8K(-T1E z3FvyV(5X77{@gl3Fq$#R=T2h#XDr|bAxA!4uexEj?I9eba;#1yrL3`&i6`6+sKTC^ zMF}af8y0AUY_#dsgaanJ5|+C%a-l{}Oq^_Q%`}+wn!EHLX%?z?^+&~)?rUP&8)hT1 zr6C9hgc@m8H`*uMiv#58kgv?5VmLu<-AwtQ8SCJm?E)lo9nth`@4jE4^-v0IFxF!~ z4zhU^{Q=$^zMy5vhV@2)e&uU1eFFU^4j1W)G#a2RU)GLBDz0<3h2ga^C~aT1-nR$X zWNW3rOR)@6AnXb@OsD>eg@q96M&`+Z^{kKy&CxcDmW*^mW&&iwjkPP~DrY}|25suI={tK;BCmZ71U`A9pqfvcoK zI}F?3hlB}^gTl(*LPz=mBW>t2GL>lUhnd<%k91>D9oe85%xsLgUq@U8tyPs~eso_! zG&W8{LuZWIG@2qMsoqSOTx9|oYu;Zt*X28>!*zW+(5{`c0%uN$9--3|Rn)v9`SKX{ zrBZl6knJ6WSf~^oJ-8C-Pt5792qMEqSW9A`0|u@#YY!h_r^;)qfZ>iwpxn7gb`a9R zTBAlzI|i?Dwaz*CR51b>BGup3rM=u8)*ux`kotOzeLWZHOiw=xEP!Ik+RMq{4JZl_ zVEs|t4<(So3)9TYA+pWT7{F> zq;&lCQL>gyP|4y(fF<4yfBTH0Sm%81|6H7+!FlG0B3XMk^vw&VS0QY%bs=`(FN!ZEK>mH)pw+i&Ky5a#sRc>Qn z#6*phS)s~#j)3|`2<&Up82~SqJuQu1$V``*$MYoye}6oX*P;zH7A9a`XDsd`4K6C< z6c-rTi=HuLzk5=kP~LFc{X50{I9OJW+jG|{mDC2sU=RgYC<94y-;T=Aj3g?{rSBdB z%Yh;TEXzov>uymdN8XJk#QBlrzN{s~2Yf5`vdS-yFTUWxqbrPW8FyJxvn{a^<5*5%@yn%!TmMaZ#e+;f= z@*X*d@=%p8xT z*gQsHTUxXP4*4B`*h_|-yfclHv;WaI$!&~1AuV^55Ho29kA_7x{)#G*2IXgAq2cT| zt*59Azi&%?toaO9)dZE3LdX@Se0~{vvWJC%Y+b`*-n_xyq=cO4U@g3&1Y9D2Nm}hZ z0&>JIdQoN}h@qjHlx$?eb(-peDf97@22t%!b=doLD3dEgC6sM#$m#uQL9!WH;pOa{ znOOiW!y11asYZR6qwI;rav`+5^KP3;9z~C6iVKMP##cEqGR+|{1Bt;Ho}to(|2wHZ z$?X*mvIk|p166X%Ash}h!Opxgw~D+#8uOO27FeU9$Wl!Z_dEra;5(@hl*kM*v)r`D z0!nOT_4egbV9W@Ke$=h)752&x-6hEHPDBO^z-uv_WNj5Vl-+)lZZAq+<`(lz zsDbsGUo9E456CRg(vz=hb|ZIZmmfF+^nUoz_0>bKLFa1=CToP3z9^cMdFG)`wTSha zx82~lh>LQdW%C=XwKBySkjy_e>ekU*xXrqY_rt3l;D+9w3!=`^0XdiHv)Wfd^|VkD zR{~%>hm58T%hI>#x>;kLQ5~!65xu*A~^NLCF1ehZReq zkXNy8D&=GkEm0`OjjU`a`E8I%I0dACLz2bgHJN_kym_Lsdr=)|H4Jj5BR8kQLK|2p zv9OjmH1X;oQQ-%-53$&%^I#(B7zXBfO3CdEyFvVrhnV-am&?+cy9T_>C&Ja}0H(K{+bv#94INHDiA5RnKNuxa)_&Hg*{b6VBP$62V@rd~nX@*nDWhtM%?Z zx=57AyR@xZjt!pY8)J5Bk%nF$0=FXEzFgJF!5jG~pVSp}h~W~CMeY-?)|OvUJvyNXiyjwUUdOKi4OAX2+dVQD1s&F$} z&;uZwUDaT;dPFUY6_=sF_C0QO*ux)iuOIHTfWa78+LsWBi|kjT@A{vOf<4R69%_o4!;yDsp$TChv=o+ehDp@z($H zEojuJr{5kqvWpP^ae36>4o32yP-a%g*qyi*(-6!~JitKLh(M`jZG*NGuU8u_IEw~o@TV*eHttqLz;T}j9ei+E%5pD=^Xsz-dFhAWPKtq>43eKuaP9&;Mp=d&5d^wa?r z5ik3@lLPJ39-eRoJ{O!xjQAZP$Cq*%NiTGmb`|vFP(Fhk;@SH<{x#aqO(yx^3xwV zo-ZV}AB16_r3L>@!v0N6dtSv)Pj=(O+mV}o^?&2|pJi`Ej{r_uuTI-e!OFfdgS_Y6 zz2MYR3KQ3JLj4ljEwUr^{7W3xviE#&`ue}^^WmRZ=fML-EWeNPMP~a*@?kao#a^LmpB>QK4%w}mf!S$G4~00F6{(i_d}lkB%%Ll z?n}6imAfDD4ZTqaI^5Yj;vdOT`;WOlR-l_I;kEUzxz8j-3#S^;_aOc`aL!}6P?ND- z{;jbQVm(>vFvn=_#jc)N2*16pCUcz_zKtb)b)`~J&sAzdqDDy z5GKoGtA&|tJvUW=q?LSSCOEfPh8#OL}JnSLHo(c`u!$6M3u zp-Mhk+vyAT8Plcjll9q2i>rVByn3x00!U=OFVV8!&E&=lAHNGEWu$xEPh>`JI7xJE z?lW5!AQk?ECcX*h8D&V7p|^x{;RN3`a7F!V?u+-!amPsiYwm9~aL4^)?&DP<@;vdH zEKmP2_ZxW<4HSO=WA4lICR^A%TM;ig4*K!<>6Dpjw!g z5CoPCYYltL7YK3wJ$KoX#{WDiNBGgQxMF49J)H2o1mrO~diT1B(07e#iWg%Z6*1lG(MGV@&DoNK7*S28@1n4LkJ;R0TPOo zP(->kX;Kn;?;=eE1Vj+2qS7SP&_RlH=~ZbqkS@I%I?@EBHvth4(H#DF+xy<-nP<+K zIq&j%&6>5=Os?i!%XdXp2TN3QM2OD8YZg=LlpK9b||CluBs>kY5mCgmP>L1qPr zGy3x6HHi<$uow z{-K{AZq4m)F6?j4?{ChXtP;L$&hM_zZLiK;{h|64ckf5y-kMw7_S zX?izP9sT!!;O!uxwtuLm@2`5GysN*oqpzv){j1gw1#R8A&0SfIozELS*1xO0kkIRD zUcRcSOs{=$(G4WNZH;@~98=d6S>5ngG*DjhpNoO?>=zjs=@+@c^XF;*mJ1ZsUFheY z`LFK3sB+19bvNs!LuRFYdikxivVZC4HF%e2$;pX{NpW%U|B418A|fuLfuN@$0YU#$ zH{g5G4S4@cKQ~Dzyod($WAk*PU;L{ZP>FK8=mu0SqJgkX#gL5ae~SiWp2q$y8b}s> z9DflF2>yFCa8V3!d&Y8k`(Jbe7tuhR%gqb={Gu4ReaG3__U;9DUaTZ@5e;Nt6$zKe z+_d^D8Zb4#{U6=H4LiddxAcrGHTBF?wTv;U`jTe0|0)Kq$!m!JJAnSrVnBgU^l!O< z@O2&`*}qx=0ckYfHI6IS*m)({1m)N+OI#>{{|kMd$M>LPgIegy0O9YgK+kX{H~U2^ zpsMyDT@kldQJ$^!`oFXS*Z3qj6%bzvpU078v3QilkV2-$tMr&Uf6AJG_&4~w$HR%vxbo~LRLHK$v6e? zKiPlPE$2{9Hl0LdH)v`4nJdi4MR~9HN84w`Y9uti=A;9C zsJ5(k@3w8m2}K5C#0^$_2ap~XoA`q9$yr|v1=R6|Y?Rc~1V2c4fng|F`;>`MM`C`q zeuNAU6SmB-%rN9KWQ7)+#Vl#BM*Yq(%WPSXZz*2>m?<+NK;g}T%y^slprkZ!4XxTvodWp;*Qmu4*7ndw>2# zpTAoj#~jHPbvq!h$?8&Xt{#Q31VV}ml>HUMK-d+g=gIuxbWWS1DA*AX7NhJC@5$sO z3FO&c%eY7AWX}j()6A2VYMExj6Nspo5{ztDPA!u%VN3W ztnOeo0W0t5o!P1wH*?+9t>f)CbYxia-d1_`fHGc>qc)8Yk}o0`%Xj1`y_<*NzsaQh zP?_2&MYh~(=k59N_EqJa=$Yhq#tl=6d^8pfgmT)9rF={uUD$r|H(vgAm6=gF!#0WE z-N`s&giu}Umi-LjDLQU;ET|;7PUAH>^C0jM!vE6nE<=94XTAR|T|#O0a;GOYU)fXtXS78yF(Xc^&CVEj|xKs^5|`^d;YAVQ7)Otm&bAX6bhP`4LKiKvU8@JApBb zDXKMijlB--r|z?Ss~W^gY)%}j;xbL2mk{3G4&uBa>?%a9kVR;8))0B(oPa1waG+>z z!#mPExrJ~Dqq;1l!me_kKoiu|mw3%xqsJAy1RFoY$%cz0&LByJfsT5Pu#=TGD)`I- zMf2Id=v-UKW3}*%v8`{{Zpa#^(FuQ=lU%j^ov641meLy~>(cv;9o2%G>bQ>bn4cL* zNLKIf_q>?iq5e$ijUCW=gT@|Btvu4ig8OCnres4O5A#YX(7SmU_ zq2+d}HGH3S&+aDIQae1QY5$}w;|$cWsXBr7H7B zt(Lxsi?L5rA(!uohWHdleX3X6^6=R+*D-82sf@1QVRGJ^G+q_0e&ftT%Q5pIooUZb zlMjE<=fy&IwFWF_{@w~a>Km{*JAB>-E&2bQKL0RC|MqLF@n)eZd#YwM%rWY8A8iif zCy-ZEaSD5I`a5w+;H(RasW~@AEeTo)3p^%9A)IEq=7ta$cd+S*v!;y?bDo@Pi4nM66!N!h5LH@}4?SA5xCBPAi<3`r;hZjaVB#N4uab!4S=v0|e&%1} z!B{oKSi2Z^h6;zVj(}=J+DET?r<4vp$Yq*Q%voDOA#f0SJHaPWnmL5kt$2dn)R%T6 z&_pqf4cu=TA|p(8mnqgGn)g*Zm@DWZ=MkxzoA%vA*AzEj2JJ|nG-FUZak{IFyj@es z{-|mKzbvRbE~wJI^r}>*KsswQQkLoNRq=~@eI31f)7gp9dt8!J{`#KiGaALPByI-w zT(#3TKAi6bibwWC4noAR!y&mDlA8gAZ(ImA5b+kKTZO zN0xq6z-wM9tZ7gC8hFW)J%st=Vo0w`3%Ts3hJzT8Lh>%lxvV<_eW#d+iM;e{W(M;h zRC*nqhCaRA`wI}{Fl7SUUC#SrODP0!Yi(W4QD#*T&9)8Kyn#;0)RSGFPE>O&byn2D zb8cZ)hj}czJqMv3pk)iMv^;150UuqGI%9h|>}|(J?5Xo(pzz%$Q80roB7njt;?mo_ z;EoMFk|!7U-NzWTgpjz3s%1e1^Tl+Hc}6C^DN&hG)ky#ezCEGE38QyVng9&HMc~#S zVvEK;`hA}Vp1tsH+Aw+~h0l#_Uw1wI`~ZjYQSLRG3zf-4i{{`9m;=AqG0AaZ3hHVa zp~DH*_ay=c2V<@a1L80%&WYf`Sgk;SjXUhqh41&$F)&e!yFtWUzb~1FZdD*8OVmQj z0{b9v_!;ho-8#TuI?HMvTgz>IN+?=4-Z2h&x!&55$S}EVE!oZHHaizFZ+x4O)n|TE zF=8C0$fJvhWUP<~eK>~QXxH-Lg`gVZ!LM_aEyo0kU`xb|3aqi!rEIpMxf-@^Sq!eG z1+1wU(e?`CGhl_eGRH~wk;;2kgK1X;$=Plf#+e=``aqNm+28y?rQgmcB9WXSmdP(_ z7$<6isn7BcR&%ov_X#ogLyP@+r>y)ZyWsQ*+Fl{jOImo{s7S#YS zQ5H*Po|BmQu`C+d8wn2q1(B~^#<^=QGjA(y$99BFi*C4c|z;?`d{?9l0#CiH8rmX@lUlHv1>RDa=SnSRWfA>NTz>QeH#@ zl-ELxjL6iD;W3Yx=g@rA`*2Ck(7im=<%^6!#!#S_VG_;mZwtH4C>*maCV_`ICWhH0 zlH5xQy{>7f&`a-n%pvj|c<%*M6ASfCBC(zh<2?> z#)H4N=65|m(*M*z0S{q0@Lf|u*r+{V=yc^l(gXy9q6x5V^h2((Z;*keWtUgj<>ls0on2x&=1< zrd|3?&*!fB;0XXuY@<@T2bg%!o-D#jL`h?(X(`1hC6_3_s{>Dd`nza7GBSE@W|w&b zmuZrpX`G+#f=j5~PxmkfgbA>PJWwPCUXhsbH8IJNK$`P2gB+3B+T*Ox<6ISmx-h1x z0g5{2402M)u_0en4ZM4V_PCfX_X(zx*9J|p{0;F^||IL3fh65+S)AZxbp9Z?#J zda*rQ__(bj-Yl+{*hI9SNc7Cao5>w#P5g|GY2d3l9v`;aAX@LdAcN*+8TT$I8dkl%;r zkdp3r__CT6%cTdtR-q(AKsmItQjYkFiFasS3*ffgrf3pN6e;2?z2p;h-Wj1}j)T+mOa?(U{vyK#_+|*9 zXfLFyh3t{!6?njv_%B3_B*(>w!Zd#3NX6H6nmS8mkEv_aq~+UY04K&BzLYqkS@`J* zKqeX8Ssfmr2@mkqECm_W+Tt^K1-f9J}4Lk_W<{BX@tD(9l zno?O;-~Yb4V=>=6i%z^YnLD(hPZ~`9sQx24#ZO3(k72!SErqdY+0xyzI`!c7bPf78 z%8r%jfZy8j6-fLA{OZI&=Q5 zW0EcTJdNiudcU@{Ct2D)nYI)ck+-3NY}Yo}d0R_oQ?UaT*$7QXVk;03mEA~9G1A5y z8#3pg`}?eY(6p_{l$s3t!4vcG(|B4jPhEBY$Dyz`@utY4EGCfvb}@P2x^>6LH^tHI zO{}`?!@+>yPKUqDM@?N_ra=_1Jd{L;Md4+!jmuj!!l!FM$22HQ?6NUu$ikcb^?&Jz_Y-o5+$ND9z_dalQjtQSR)Sl9HuXb=**U0@oD*Gic6fg{# z7>efXeUaa{C#16$z=WCW&aWN*5uhX6ggTc8%AhQx0YLZMr`n@_+ob*?YzL@z2>e?+ z@jeO%a7xF1r1l&@#OY^d4X=!Jr^!Pzw+WZr^o!3wkz+r_E{#xfe!5Jn{e=}p&;?!- zvzdPCv|m-w`Dry~Zqy5IC*;;Tc6fY}4b)PZ>n{l#Rio8beT5R)WhRhNP_>Wg1Zo)s zBK3rUT~?M%*0CFIQU#)@A7pgFi73uM0QfyIm%`zQuAonvu*8nrykgRPHTh)xE%cz? zIcXAhC#U z4#S3=YA48+7TouzUKuVH{AnPRHHayu z8Tj*i2|@AcCU%}m>@#wIY6L@?9LJ>n3Sb{z-v8cbW%q?#>~rt_l$7XnRQm$e(wO|7 z3i&If$Q%SBHrSL|?f z{wmmJ?cnPg#B-zu_Ur@B78P(;@05Hn_#023*1VkqWD9-erW!>1$Mo-1%=N>;`Y!5Ha)Le zn0!T$84Ez@1Jrw)ZN<(}v-XXzBO}oK9;c+`mW4H21OYHwa?2m-YtitGXKL8%1ZuyU zk#3Cyp#~o?P1vwMZ9$f{>{{V=l|2d2rJXgznuXZ*N)S?8A4&LwUK0WK{?L!lZ-3KA zPP}Al3_?Ax0vwyy$&C8FMfZNiBY*s%KNI5o81%*JA`;Kvr8Yn=DKcE4MI0=2DLnw_ zZXetf+cguLTFGCd$lroo1)^bxmhD@Si2b|ydz3`d?^;GJ4Dc=?__o=>H>!jEyX~9z zjrtTZ>*6oIV>~+?L>LTOxaFUsR9}5l|3sfXyMF`w1A4F)k=+j% z>2Xo*K31$tZ|{c*=ONQo;Nmc78Dj zNQsU3`+Sqg-%x}j{M}E>MvovPCsw3CD8=@XoF_=cX=1g2$oWaZ!4}=fDTs6xgx!K7 zwkemsd|&u^A4(V9di+2Mk?;Z_Y5K^dK=1PBxXPWrR}pDX1XAZv7TP~u+PAoc)0(ex zGG9fMxeJH81Gie54P*gATUT1^Ila-*T_T(=kI2072f&>7e|iB3?0$`$87!&(JGyTJb6D*`6O4fb>-f)BVBcIhqy;4QKePh>pwBG_B@##b zqTNB0Gx*rmLA%G!C~H~cMYSyHi&lWebi=SfEskBy#WbMzKK17Lt=0%Ot7D=g2l=jx zLwjFxseYqut*C$LSKDY$=6*Kc=>nICWT(IA^E01X51Zw+asQJ&{nlCWHD^n%$6={5 z3lXP@XBVx&d}~jc&7I(#+1*D}ZfUzComax?iwg7JFLKvl$l*mhtuanD)$Q|6=op#I zmnt>NG*>$bLOpmEQEn;L`-!x5;xyGoC1G2lD#)7-2iGWx_A1wb>xctcYNgRiHMU0= z^m#s78(&6j3KHs_+xfQ|2X0!pO=LXZ8!*gKyb*Q*0SBMeI zhHZS^kn}|>P;mDPZg?VTI4=19K;Kd{Sy2(3m$zXBS3#;VVb{+Tk#(G@(aZdEZ zp9fy2JhzqP4sIns?UrUUHM>0Z(wyI4=VtA47r5U}H(8dun0N*9x$q&bTW;R>=yRpy z)XuG|S8)7?vIU_gkb65Xr<|^rWw*h0oNDJtT(+WCN}LxGGTj=#N#DkR_g_oGV)yEt z*fvodr|-b_vFfXM)z&NS-kIjmkX6V2tKX%#d&B!Zy+p+@!J|>b%4G%kwWo~oiG0c*8;Q8QKxq5nq8ajpbowjiBPJqhhx0WFqGb)$*I}crlGbi%IqZ*n&_FSO=cf zXxVVEu!;v3il@ddtJle>h$yf7ax&YJa?^c`bui$u(uJ@T`*s&hyED1)^f}v4sma-I zgzhB1&2&DlS!nEIK+>1SebV&`BM}q!&F-6yYSP$8s-v!XJ1gvr}xYsV|D@Kh{i$ zU#(Y{J^!d}yAYNY3zI8sTQjy7JsgM)09OF>|>!riRQ`?=Vh!*m8<6SrcE7%FDV zO-GQ7OBP<*-O$+N>warw$dg|fJJl@#SU44xF}%{$BlR$O<}+T1&f%0Ew*Y+1_;Pul zpm>FkqzbK(<@81ZCK}78IbLG;jxvx?1!?DNc^_UX*G&V|$HGEbXyxUD&6|QQCUH{N zN)1=J1p1R;UQk*yrFKWhQy$F|v=@%(SImFgvwx({hQNB44Gcf$GM(0a!yQx;$DU>@zOB!n=Zt_YeqAK2+if%^zJ4kvO?|p;j))%@k$3RaZtrDE2(n*)yV%+Y0?T;mlwjgHRHP8GP3(xD+zQx9J!j%h_ zgNpK@EhP>wX04#~lx3OM-wax|LDv{xekz!k##CZ8s5L-pzzk9oI|ag!y&ki0vC4pF0F zthcG~W@e%~=m&?kQS@7w%Fq(Ni^Hec)#l{GRP^zY=3zFXqc8pH((A!!w$Pn~xs3RS zHCNOjqPxCx9n4eRzVC8$6Yo3RxikZkuK(uw!S*@NDAbL~T-%D%O1x+U{X{b1o_wP7 z{m|KklHQa7wr3_;MdMh+DvlTny(+dl%k!N*qPgLf2V3>zB9~TGOu?Z?>(KRnn)mn? z{$T`9r0PdR#HSiDx&zpl4C`k;aL4!E{kZj*m6XlL*yZ`deUS|G!iE&KB@hueCeM8Z zsg=`Aw;a~wFGoCs{PrvKhCHt<)E*i7OdKIc=_(47D6 z^)3p^&f{wF#`{O^cekVYZ$?+#7p0efM0+%g>-)>*QvIM$diwBv@;Ber>zRl*u74iz z$d(yZ3@3ipP~XEY$$J~c5dBiD{v4*S*K7;c$sNmF%BBA-(mB93`6xDUr-c~UO?vel z&%}Wxf1%r2&OujP(eZO$J<>#a^lbM^=Xds6w0Tt(qLT`=z1q{OR=NNCe%S4E7EYye zgcMyD73FKj5yfd|r8KYtbF@@gI)9i4efGk`#Xkrm<~z|JkNQ z%J|Oq-5eyG#Ya(uaJ9IioE-{5$tBc*>!->AnsX+0!H?f65tpr%d5fs;c*k+@;L}54 zV$dkawy2@#$Jzm9qA&%C2nAGJKAKD(Eb%7xZ780!6D)A??9uFaAVDYPqmucU|Jh@u zckLf?rt6aUI;+WWih~hK6rC6cYGw!U8#|%C;En;NTD28?cJOukOp<$T$_i1cTJqG4 zD`4%HbupOE^q3 zTMU?jL)yBm<*DVfp-gkpA<1#Gmm-MuozHqZosCHxUv`m;;_rraKT8)(@=z|Vxp37J z_=;k^1@Q(u;JmR)cWZS@CJis49>h}29ahj2A6gelYSY1DQj(t9Utwx8;J~>a!Od>F zC>SX@{6-O&s3@!C0tpV?d1sIw9PZE?afELy=!6#7k#qamv`Q9}L zcW8MhgmP;B`6(cU>4Wu(UcRrDw$bGR6_u)0>`a%59@Sd!00A3X#b;V+ZR*h^a4k_9 zgO_xlW~5QJK6Up@#;{)J^^k(qI$Fx=(x-W1x_^dwR zo0Tr!Hn=H3H^y0dYoo5SF#ZO2ypPa(&IY)fp*HwHR~R}}o6d{gZ|F~9tC!cEg6eQ4 z;)$Pp20v3!`wikFRiodj;@e;LVS>Mss`uqKOoOh%Tdw?sj$kOIEy z6a7#SzE%_;QBadFgJBjJocB?5D zI1wy$U*+dHcz6_yJBNVOsx~l}-gE1xB~mMu6*4WwZ4H9lHfS4S!30%8R4+BS5_~=m zhc4;7s4(@-Mr^trHt zHuPY)4c#%Yf)~lj|FIG;x*B$IEydl!B;0z<_)#=(I*v(@1$idSAtc(haBeNU!nLsr zYj?;FEPhy@P(wp21knxef-=zP{f<&e8NMN@mCJR z`OYAgm%+;tV5(iP)sJYw!+|`K8_+rvdFC-!@f#p#Em{_CgcpP}ps;qDOL}x7e&00j z6vtF&kn}jzwi!(cOzfg3j8{z@uBoLmgH6EE)1hUpi224|JbKzG||~&s%0o{ctJS>&EO()wV2*7XPr&}v2Ve61&Ep7=T?shre|Y;R#un8XX6uRqUx>k z^El|k;VYuUk=s_Szh~n_tz$`gTLW0gpO|#rn(O|JZ=a8;m>uaw!}3jL2fF6s!P1OamHlFzXDCUx50{=6(+_?Ol+Ku^n z#7U;^3MJ&Lg3Ve^ROj#LmBX7|nz3$SO6%bZaULN;- zIWCKVn&_=!nO(KpvEVO19T|SU{Sxi`#cuj`HDN|5RrTx8muTJhv1MQKM6Jgj!qL69p@pf5MLa{NFDmUW#e>i0tO_-gXnfw3XzxJ0bWx zeTGZZHQ~6j6)llg#9OdJ&?|^6lgP0H@8D}GskaxyNE4X+_Q100mhDa7W>rb>)m*4m z$?7fMsL%d)`pa0<%x>AhhV&I_ls9fq^*Y$YW8saT^sRIF$tIM zB%n5%_mxf9HingeqhaZdYTk9VPkG=d;aYvXShSZ`jAzWuhK4Mbz32l=Q7=~#0$ z6`P6<-cA->{}3_R3!`b)-;v@B9Y9g~*-jT4!h7(W{Z(7z78V5F-KHAa4!+%S5%CG9 zU0NRSj@$0rwbWVk#IuZ!;oagtq|Js~3yPZpsK4m*uj+d%W_znnduzUX z>k)e!X?vR`dt2}Jw!8OsCiiyN_V$kVzJb2&|Bv+fu$xo(f>5ISsbZoelI9#n^ZO6v zk9zclg#JI%=aKv1_tkUEAX9C~wVH^rgHHuOczFS+MwDvabGs(bgZc$@iy6P|8Lc21 zKKj|CfUuQX8&SPT9wQb`atKirjr8U7q)&*2M|0FXJ}461Mp2Xbf(zJBJlnv9bxdAR zX8zK8&`+bo%T!R-QBD@d7-nMh>w-vx21Ff`hAZ3dr>gwdHjhMm;V0F z`S1^v#+Q!#^=_#zl=q6h#t88ej2X~^u-ESlJfQNK|K3{0gEWX{4EwGP z@!S7aBpNPxncT;5qA2*gnlz0`-Tqnwd({$1^r^Su%^x@J{xEy=<7VU!^XES-N`F|s z|6$eh!&=%!Wa>vnjzuP0#O=~3g*=}yXHrSSBO8P3N;iF{9er(XGkdi~dhvyl7Et-( zM{yW(_j)S7^ayl1o(@ClyU60~e%$8o8$yT#zJvlC5vHdFTsJ3N7Rgo6FQaWKuI-bX zlbm=@HThh@U!7sB;RSnWdYdYNy-yxZkzc%5&_Q9RXbnDG)a@PoDdUFqX|?NV=!S9l z6|iz7KJwG!rP;@!8>e<8tR^0_sT@D8g?@&}{DinaNep-rf`9TlH)6CL|8_Z4PBYwY z<0#|H`^?trki~}*H6Xt>s*p^uAz!4sK%@$A2JAkA~;Q{qw(meEWU6M?Bg3ee&&JljO6LZ|6TY ze;$APi!VQ1Kl!nDe6)M=edqZ5&e8YX?+4ra``hQ=zWnDs^6}o+i#_sRtKEJUzb+?F-cxu9NYLZ zyt+7fA(*dzA^dHXJoo=)mE1Kk`G2!Y-s{f%_f>LRPiJHI$EMD5x%z`}xH@8TI)QC^;qh1I{!dG4bEF$&q+mWYn$HQp@Dx zr@^6rXU+csn)^QS@Ot>KVe*ZnqQ5}%*uOw?-ROUS<{E#~%vHiOltMEuG;`VDXVQVG z5&L`-@ew z!^JAO4Eq;l{yt>~$bT2i|Id7R-2cdzkD#UR98tt)J?vHMNTx!!1&8G7= zzTBw0k{8I<*+m2-6) z>Q)ERAGV-RKbDDkk$rnhKE<%y+bunGO;W?)%Z4e#M1a)V*`@Mi_-BaZoakIn58bVd zM(J;txWd@`;wT=avg{5L3UywvOHitPqSm=0FX@GL$r`2)A*zEfm90e1(46Gd^s!ud7$?KEw-(AoF}_4;aCl^rp77$^ zFA=Q18=MBDup+cdZeU@SSVh#Stumv^VdnB`NrMos5g4dvYWp4Ng z^j3lp$ItoLFwR8b;c}#*I)Cwv%{a!Chtf|vS1`w%DY>dki%zk|h_`Kq0#0;1!x&eV zu`kM;%Brvj!~@>Mq+9n+)=~nFH%ko$)y8k%Gw?%}iHS(1k>$byEfQnJ!;?!en@<>~ z;>nXNMxIhGy}P2IoGYDL_%zLBt9%3Trdaulg3qTSAc|O?Y9m3d#g5J9k|R9s!8w#- z+yqRWm7CSW`73&PV_dSk&!dx5HK?_U#4xZTh$@TJo6>g$h8=v$bs{Odsst8qKI~vO z&n4|CUW)R%{qA4u@1#a5k{!zBohrq~%mfV^VR13Z&18Ka1l~HtbGv>J6Z_>@b*(EI zXrpQt{MNB0Nh>zLWeoLl1oCq&wLOR~@YKh!)8Ot}Z7uzv73`l#ql z87`F~cnPXHJ8=g4GlEAii-u?aSvPe1WTOaLTr?w=9HO-|4goRH6C44x&s zuz62*9|y!{#*8wyLoD}0n0R{c1Uo@5Ksh&NXg*j&^Fu>D-k3)>A9B?jV!4&|Y(EkMEdYp-nw?xM2Y5~00=nlHe7W2~lwoWEL#bw$faO87 z`CtL+eQ%eD-$9Hmw2-Msvs*m#Al6y8kY%d3Tk69>oJVXS>-q&>K64QN*ChF*w@2~s zlVmiNRVr&u56|KI%Cdui8MZD5|efob*lA*deGANKSRM~Qo>TET$pci% zED}`~yB0eodq}Ji^A8Sb#MrJe(%`Ns~K0xJ6b(E0jG#O^aE=@<7y7{4Czt zl`U`Lmz>o&OuJJbe$eFjngWeAqc9As@j=^5tSjTGT06q1o>PoiDNpl{hc9|NuLdKh zyK9vwM(-9ujqY8i(@8uMqAdU&XpTXoG_IK!Ugs9j$Y1E7eU1prEPb=lhq4zR=2ew> z|q^3PhdnYRbELv zAc+hTyB2|kiLbs0V3{1#VzYpN3X6(5yQCpdY>)D`#^q{r9l z@=8o*=fh{ZPUZDg=rMy(63K{n!~JLb@^PMX(QQoTLk~^7?hR^WDsI(4$}6$CT$Q%b zLvO$b(A!@*c>^83qqAp(Vz|AYr1HN z{w40DwZQUghP$W_*jgTqZI&2-=aR#uyDzv_B78)G##eg2uj;ba`L+v9?eo!h@7_hG z&${`~;_oi1>riktx@Y~G+t7diVQOg4xAE8fe*F8Ub-izXv%eNjhu^oH41Ejw_3H}> zyuOV}e?R2X`6Ae${v+e?e#G_jB_N@`^NRjKwAJ}C)2I4w>EVNTfB6NvMVnrwy*?zy zBb$f#!l6Oy{b7oR*9!7HctDJq6g(L~CGn|Y_|ZZ>dcSFb571O7GkOiy{CJ6uJ{53j zkM|2JoV?Ng^V52>tQW&8$zcmds(vGw(n~wkZ*y{sBE^S3Dkx5bVLOHka|4&&&U6px zB`0vk)IR_HOvJuU7cCfXe5FXwS+twc_r{}`HV2tWL;r^f%Eyg5#!}_%z2pLQa?hDB z?XJ{-5XOraB!z;aL=M$8UmxF0$%TWY`;-rrjK5PO91h8nN^;!>GCa<|a-1xxkojs0 zGia|Kl|?$p?%P4TE``lNlj?RD3ld~J+b%6FhO*dtCe&MX+MI{|GzjJh&~#xrrl)>O zY=C$@!KHloKJhWarU94t_0+XZYANW1xg72(pUxFucC+%(r8QbbL=^bfcPXpM$ zNq;E)6wgEYb)S|FfOSU%9N>V@B~0D6mIWj?FW~Otw z7|gjrFIOLGj0cRS-3LU&?To^=C#f(I;g0#?XJ$~F4Ww=Q1O7=bQv|tXeuPDP#LcCM zTc#1~AY)JxIQM|M9u4G(K2%wf2r{JI_JCiIJrW`OWsYnicyGZ2{3^_N1khPOK?LQehbdYGrZ%O%+;h<$yL5g3= zs15P8qVSqWF=R;~;{N>u4fmyjdsJBHLN_Wz)8+>W<9D@Sa64@$Rzh}3qKOZP--q+m z;Ob@Ita-p4I^};ce3kGtwuk+d0Y<$Im%t#+W8U(|}g*!vv z8iviJlh6V1GYyW^F{;IVks4B|4Ndo+MH0$d>NQ`HJ$l%)C40~kZL1^w*#`SL33d46 z80t1EVh!lm27o~GUc2H*-jH}=MoGpAohTuDbM3Ch9a?ER(ix(+wm20XYQnGn8PL>A zzTHL(H+O0)2CJlmspFR%u zl#PgF2=htV^b@#MRU=%=I4a8cDi*A$BnRnXWhB73Kb7-?hb# zVf7@P($kE=2Nb;_MIJ?$n{W1m2ao_$m#0V1KaLT}gO`wG!bajNMwqCz!r_mg6QH=k zjr4+#E;M$u-#y@LD)d2**qfihE<`mVnj-s2oGB5L{_^8h1M~QAMcMG1^@z^orA0_RC+8^tRTHs zm*ooW-q6T&Ufg2YGA!zfE-J(Og(gf?ssid*7nMwpBH2upy56GOriD@tdE{bwhAaW% z+Rtx(P!oozhyhT_cBoaf+7%b5w1A3A1(fU{?@qKDT295MypVUM#N<7sn^5dysb8ot-AEg z^n4PKU0IfZT5cvPR*p?YuELC`)cK&a8&jN`R9@ktR_cQC*936E%#MB~WOl```&I3? z7%%%(W^fie%9XVWXt`TfjxSa8xv09&FycROj-0(z3(KpCMu9C$QpH|Po~bUlpb7-o zrq5m_uM|cL0L9wOiv6YCgsQbO&FIXc5mM;E2Tjmf=}l+oju!L%vm)}ONN>MtHHIpO zk>blPMbDRBwrJNVJLG}=Pz~B_U$<(sOkdd{%0al7D1T3J0XF*C+6amoirVUA&SEgG zj>}&qQw{|gs3maLP?NqEbX930ZZQr*m^oqqgw<=Q@tQlNZ^%7gkKt++V>E32E`UE~ zK^LIi?+ukkb@zTjw_&;Ab(O~gC|(*ikV`e_py;>XTM5%zyQQ~Ob~VBIHR3vemf$<- zm6vw4Rg@#I6FJ{FZM~D|EHU;+5nY&ZE`V3edjW^HA(b9hmr#;cz`iyU&Z=G}<@K$R zI&VSXGlc1-AHca?FThip>W_-M#1sp8{-~mXKdcNgiwvv;G6dNibUrX1l{sSHk1ml@ zk=9lTYUotHNwIrFLE7*>MyQCud&-Xp5oK1TVXCtNB7Zd=dT}?KA_QWP7Fj?`778-^ zVQ@g&j2aQ;kNkiJ=7@4^HCfH#6z^}=zVDCW5YMbyp}9&D9szD|l**5SVC%sn?~vG5 zBLw(ppaGlTx=X{n7X`=>kiT&)WS$Knc4d`1fa|3;G4fVp(l&@^6PZ{G1GZi1pqUKY z%5+Z80&O3yt+zR7Pv>mlIu~m_Y@)Mkd207DZKREVP+{I5>FWwi#c+&V?`TYJv@oiI zE`1EdwNV&#$TwXV4?x=a1LfD5lyw1vfX<1u4k)(MSXZrX3($cwi3W6`jv8**b&}h? zE8FUV6}8>t>`vosH6Lkkx{r$f@H$YeImojEl+Y1a>+#6#xkRjMr9LO59G%BfKMUFw)jI4oXA>{85&?4O-i;=+_BYh*arL?s}HcOfi@}Q-FY>zZI9tIe2r+6=+Y7ZDHcsl- z4re7!^Qsd}j+fZ>q z-}JB9m}(V(&o2St==K4RQ99DeivwKSecEJwiRku*ysubD*E)k1bfb1 z;+h0y4(YrCB88`f-4@ftzEE(E*(6Q>U_+E=SD+RE_ghP~_|j{Zb96y~IvWaqAN6n- z_@!6gw>twRo!<^zzMKn)2GNtY0FpMyz_}&b+64$=N)}rUw;a7@gTU<3+hp}}d|eP6 z2F~VQ8~iF#4_bkaRHw}`;z(!-w$vp1tM*CN4Egh594Vzfa56LvU3%rz_|;4#m3(PV zgY;sde1T}LR_?FbDx&lPTj>x};{7YsVsp(G=T^+FyA$;Rhd=aJbr82(D6C;nzn1m1 zkuQF|K!Wx%daEiVX9E~nw9j9cY+D@wNRnYBx0cqxb|ZJ$>3W3_^}Czzb_O`|*J&1^ z)(^-^7m!+efbpvuWksMu1d%hlRrdgzmP@ZCxB(X1{MfdtRkNLe7$Ox}!;EbA=mWBQ z$mAdzYZ0o^1*ApQ!VlLS#Xmsz18B8P-RA{>CztNo?uMT}wY5HYDF}JNjK}B$?SBxz zXXd}e?e0E6_Spc*@l@7()F=APul5$mNVg!h&sh`N6_5#2Z4}e$}z_nu{SL3~(L{L7%0NGRe=WKM@e;OyzlEsf08qevUJgt*4I_)NTr-R+F zcZG?H(_94lYDD^96~{pB%B_)8DqOcfD}bFR@a?kP5j*7<+ap}M>~nSJM$$Rz6a9xT zj4|JUQkIv4@pQ8=gvQf1*SOmai6&?ANk8dEdJg#uA92uiz5u*z>c6Y$p1Qg{S zukTfR@9SRAz1DvIgjw^;d7Q`le0|!{qE8?bGX$z#Csdjo!zfeq+*8cG2WKths z>k$7T%~GMzAJ8V3A(gDQt&qTJ(B@C6zN3`FZ(oe} zv0$ex70Vuw2Z+^FLG*_`X0Nk>aKSqru#|zM8?s4h2*chK%|oqngI4c&opQ}itsM=z zN!csyIeq@1cNViV@JbbSp%2VhTBm7t*oM0q%eN&0?(O3BNTc15hFA7S8GY-V^GV=44W8b`C7bHrO2Jk9+svh#SlAE9j4n;a9yLPULcU=Ss9*k zF&W8^7|lIW6usH1R*AckuVM`^ADU7Yd?1dSVx>F91?G~PRSl`gKgzFBE8pz4 zSW}>!(OsQeXTI30rmiB*KNA}9{z<{3=lIeJ$$QgpRfAXF?JH1gUK63kcy8CKkYjAf zWSNLoUlyyF;dDr|iD#D;Y!oj&)v(bDFIvb$^nxxNXg& zC(lxXUkG+L7wPTVweBq^;)vEy+A&q`(x=>?@6vz#;T1;ZH=?Rj1q;q8W_2UR$d9(Y z6#2rg52hp1f%9+6k5I#Gu`V;s4FWWoARAv!dcxDj#u>FY&^-`+0jQd)8tOcC{E$rGoypL$K zMbLi~s5K77uzF>ByvPxFvr+E^0pB#enW$t8f=Ianj%`xeQn=ek&qGrg^237t3hGo= zBb}R-cfHutm0I6f)><}+NdHPPw-(&?JDvO3dm3n1vaVXD&%T*U#Ph?arj_aiOiXs?gphWg%K$xT?_YQmLGoU|-q_H;pJk2x>SdwLd9Ir{gdL0e z`&8`SBlv*^LF(=p==fZB;2)q|fB6PtKpo zG7k)ffx{i7m>A`2OgE)&X+UB@2;+5QisydP@U*bd#qqx9ZE~Xg?t{U+kFyLzRI}st zPbADZ2Jj9Gsg&+OjKxr9@u&(pmyTS@NPlx?CQ1T@Kr`x?9&_e(rwDQPqL8Pk8``cU z(73cp#V7vqBrkwTVpm=9kJba&$9NU>zUMI6=&(dnQN%76eRa%s4qkmXn5flO#Z;AN z@l+@ntWPkN`~;OXUtc>4cl068hRV}Y8&niRD2f3pP6~MbL}=7D4-K>{WhFf0Hfm`} zY@4Y+%6Ef42HzT`sP{{KakIf2N!pQlR1qZJgxc@hQAthi6!`3@lfX-WkCDAcp2S=|}1G8ctS525_87 zP*Zgf3|4zCT8NweB+@9?Vx_m1G+4J@oMPmys=FS+H6hCGuOVZsW{GjMP*YoL%R{vv z2z01*ikRAPVR5%FH!@`-9u?btw|N+2Q9Yd8C{tg)z!UVcICSyw_lK4b&UhA-j7AJ# zGPP4>plSX$EFg1P6WE#C8`TV)k~hP>e2ie=ywWq9)?&3KJ(HGUUslaRd2`@m_kc!Y z(lJfI+KLx`dNiAdB2wgsR#3N zGtr>(BH%zgw}*1K&J=tufRs5?_t}-X$Y#3~2dghBi$anI1N%pdoP~59HW{a=3x$vG z(C)PB&=LfbKqJN)SR?VJDGc;yZ29pyr^+IDOWLZXkUWUJL4NiCpRDO?-e*`1UHs+m zI`6n4sl$pCrQ|;g6gnd;gVEBi)1~$yqp7L^5^dZuTUTJiHSyStbMTq9emVnaI2rbJ`RZd;wt1dqHxAaI zRz-la9hXHUOCkZ@J6yGmpHbf^c6RC{K#puS-F(zG6exAot;f#9gR^Y%AG9#l_PNfJ zAO;zOX%G0{tlk_7P}?Iq#3|0W?a{MVOfJt2chDEPg;W^&&&`w>+qCt`J$u<;02DH@ zw?QvOYTOpdwPx`ksaTe&L?*;O)+*Q(vQ;DNo?W$@Y9JS z7(Z#qWuFa0S76gvW1fE85hagoN6Txl{Xqp*QUN9hj*RCJonrW z+IqN)H5cKzBeRUsb0GHqrZMFh(h_=J{*ysBoh9WVWCQ=*-LD$^X5G#oTG;eBFcBX} zqm}oqABIbD(I<{>)AVqBPS^SB_F}A{p zH71;c>LP-$CPL;Ia2$YsEe!13z6&a@FDczI?QD534hiNY&?-r#%v4#3Q27 zK#;gWTU|pD2OP{bBusH#kh`Y|YfUI505+Oz2VeFlr4sny4zb2Ao@rtpzU~=`@&`yu zDTD@afbm=9{f;aVzr zi6NCD=kL*hllvMN7n5!J8c`DqT=0-03zI5kBg<)!jL~WBmy_~a>(S#yY+83E%|kyg zcEavMs-lB6S^&A@;8ttGRWrno_rV7DI5g{`$tZoAdlj9mk|&~iTLtnzqcoWUmW5PJ$#B?=9lBZ10Uauz__?z zjIiZo83uW|FbsM8eYwGbZg_{3{M|s5#^9I2?f{gh<5~Ujaf4-gz4r(qFPfOzqJiWs z`7cOMD=AXPIjoLa9=8(Ov^SX76P2S+5PqNGTOpVqH}s_fPo)R&`3Tp~za5POAtTfi zCE{0+rtpPFD&A+{s~q_4VeI$9!Aj@hBxg|^Wk z(tDz8gd*oKUQK%{g~>tNZp9TRD)H=Ijg3eI$PKn329G@>V2q=OBx8O{625yQ_kxj_ z!hPrFV?of-@!N8)&cQvqv39(X<*l$)=ZKkaBR}p(mOKGFTVXADF^gAYhha*1;BjUS zz^TYMHYO>&a2W56BA{%fxCPMmnxM$IE2J9sz&wH|9DkyYIBEegx{ndo4(~A!>_A{D z#Zc1t2}q@^SmRg9-id4yz>kp$y6rHsctqJ2p0GTOL6ql&MZeVI2IW&Rc6I{5Pz1HMIseXJIiHvXVV4PZuIV?3RDrYRFXJ-#zQ z!#)$$wXPrPd zD8U%E!>G#Q&RV7`(=<}6sz`oKdvmCnRj8*9O{oRQ%4s5aEM{~_X{F<5^f+^b;yHjd znqym22G^SE=fdI!Wg>TzMh1g?wA`~$Ei((P?9MSu>8^PafHG~-2Y;k zt+YhW)vO~wjR5J~yO~&f{yFD(5_csP7Z+_?x7m;Jb31}FZnfHsgR{PC(;nM%m>vM< z<2j$@NDI<=Url@;{&{}`f=55(16=0uDo2Cj=O0=TN^0rzp%%DdGxJ+Z^AVciFR$mL zmT^3a8R;0bqd9e)P($ymsnMkuyyFStF+(-%rW0$mlYfOQxT~gWYU`WQrrBq|*_3*Vo|n$J)g&(D{b=xyBjX;ai2~?Qe;NV7B9L9m>G<1FcSeeLu%Q zchRL@(N14M>AnE{%z+rq@TCsXx}jeE;DLbOBTJ*#OJkVJ?ucfx$u4zz8 z_w$63w?$&i8n+gjXsie7uHnuy0DjG^?>bTfPC}~~dfK3T58Jp*0vk-_bWo?_ng)|6 zvm2Z{8(iNvxUn{Q$ToRdH=hb@ZatIPLHi- zaGk(P2H@Wd^eD^kAvNTXk(0@SHyxrW~?@WSR zAn>i+8a*ArHfdccuwR)BF)4^}ge94rn}uab8Sq;`r7Zj$lT{4?4Bi0E42!_hZQlk9 z_;{*`d_V=?PK2>Z>9K_#7eIs+VJv|49Y08o6-Z{dBX_@T#R~Y|n;)oZ891Igh1jyS z+_5(VSQD&2YY22}2%-rDsDiNHQexw=?z-3QdJyPVnj^>rcZ~lTK1Ti(KJNd&gpWu6 z3?F}fKSoxM_gDWP7VF*V-oLkxHz(`J_VN3FX&+Y)PxkkZb}tW*5bNJL*3*NPtL;f7 z$9l9ii{w~O*JqIVMtbmzj%2(o%yooM-n9Kh`$?wQ>Gy!_36s)L8$( z#Aw^(^ua*M_(<=63m^NsTlzcdJKGwN7VC1k&tDd6-N<;&@L1*G=$C;%9BXmka8qk_ zQFnh{=Rj6_UwUhAN^^HpLv?L+d38l;c0)sXS#d&LEs|r6u5FK~X$z}r4XJ1f{LdI?&E7Lefqo3`uF_N1(`p7K<1BjZ=JQG^E9GzVSilK zOofn4sSpRLUtmP5f3%P8|K2_Z*qZ#E zWBn68TIm{?7fJH|#j(DXS43K@e?hF$`nE6)eWb$rSNkX>uMU+_5s^^hGcXc*DK97{ z|6EM&?-uJn+DA_QKj9;T0QA4LkAE!I$N#}%rT>rNV{}%M+WaKA^m^}4_=s;9JI$0g zi1^ae%Vd45niqfG)VW`L)vd^uFf5Xprn_8ru82|YxGo~5i<<- zzVj_A{Kc*94-Y5=H8LOZ;)ya|CE`y{DoGX!Og-^HBt&^*xJkmy(W0?q_0U?4Q*_a> z*ftQ%IF@TtT>dYt)^HuVCxC3N|J+V0~Yw(`7l-iKa+m$Ty?s+3ofzQV* zF*Hch{TLJ=l=U|MNT;Nfhqfd;9JA~VsO}LdJ48Hx=gCRK7F~~(iauJrxp+H~`-#Ex zaK<9>vJ^E~8GYL>tVx{c%0WC(Oe0y|pNh|}5%9>9Ed>;hs#Yb``dq=^jcn^g;ssZa zqm=d4Pq_-@v&BSF*>8`@Moetan9pcs{;*C=+S0QTK6KZ|QoAYD*l%eFc8;0)pVpR3 zEON!!)P50{i8jIbRczFRoZ@zD;McalMwE!5nU!4w%}?d&B4t6g(@&=@X9-=tj(;@? z^nxt_GNepWX;_%q%d~gP>aCO_A2@CCqObMFCm@}o>JwPtAFLASggqCbpF|eM`9IwY zuQE~k-OG8!98kxub9HWg&RUIbyV)!VfjFtVom-Vmp{+H$n9J>)lAuE)@fJ;i@lJpB*>S>Sr2XNG_r(io zv1)KJHp@~BLc+QNhghHbYnzXJ(oR-3d?LY=sB1}jtuBY#VH)l{A>oBSxWZIH+JQ6M z!&Gn=nEpx=+@aYm?z*t%_)y3jl_`IQ3?EG~cJu!VAL9ntemhpnVyL`V{S!VG_Bc!j zAjmdz{)CULfw>_Tf5Jy={)5Ut;iH*PAP*(ixyt`0e3bp0#Tr+rl>bC~a7gQaZ?URf zIHC3^VY*q@M7mW!medJ&Glcrg=$hGenE93PD_+V$p)E|Tnju<3w1+XWtn)Nsc#ru8 zL-l8J~ zRuMe-oE1p|`BXg_`8cv3-=j*sQr>0Sv#X?-Vg%>;IB7*TU@;$S+6dd+z0JE(!4?esKA zuh#U7Lr*?UC_iA>b!vXDu@4+unJB2xnZj=(N#y8df#^HO5qr2-V5bwZ4FaK+}u*d8)@N>0FAq#AIYDC$9}pkF{{-W`CZM5#^GK1G4=l*NETMaeS! zXefiW5>jFujCF<6Lvz`MHACb}8dNs;LgN>JY}YqUc77OR!gk6zMUnjd58DDvrzb9i zYWf=$mNfY00|$89Gn*$Sgz-*1;*hYYowhtHB54cLS0s!w>nyZ=6MIZs!dci=B|HGP zbm*)f)|7L&;LbBVcsO<89j6ZCEUnyFm`?Pk0H!XY2)#&b2~qO?cTkrpvQjc;sV*Tm zM{IHY8?9W>Wm309Pb2R*Ud|>LxxXIny^|?Dcu^Mb?!g>O=t6d7MBR^~5KKN=t)%@p zmA z6kRq6$Wo4f%pun|0^X7Z5j3E~%Ox%jZG1^?M6=`_N<7WPd?|_@&>Q&*_DNF?O;6lwC4<*G=14JXo~Ay4@8-@t~o{KPRlFzQr>SmRa#F3aeG|39*`fJ`GmX;%6p$4x%Z8}VHm_W-U3nO zI)xp8jOkz;YY?@7-$0v5U zW6)h~n(u%0y(;zBk+n+m;@s%>y5?WUj*-nvyRUAVzWq9J9cx~>8U4scWODH7^e06< z@;e6V-)9JwmJRZ;+rAgS&!Zw+wjQb64gK)}##(lskKK(Tw*9+;79?)be2|WF~@hsq|xq|nL@tPVfKe#u(J1xCRJ2gSLI{XBil7SO zbExfuRmdEf_4*uY3y$`|H*vx~$0?3}QsSsn3nQ@cp&Z0d@d>jiVyjy>lpmR|obHh+rOuV*|zi z5oIsf02gjh61fHFNtkyLgQ097vZo+>1pWXLi$5d$V2wjyEq#X)0364DKzUj_PN)t+ z@~t>%*=Rq{?9AkRERvM09uPuzJhosbodZp}_pTsX9xQ7Z&g~h0ZbcAmFUV(rK)l`* z*>WCdnF>Vvh3_GVCj$3*C8W*$3Fm#HDhP8X{59A>Y7L>(aJn8|Ec9rCiZkNU`H=oA z1SXNcyp``~K!DX5;a(8d!#E~-r7!k`FFH7^TPIA+DQrMTNkq_dl?Qdx@jW926V9G3 zc4v^*G+_=e+~_@=QYWC}7SP28>ah+pr-(pmoATIT2_4Y+^H1286s%`7HWgUKS%lYu z-ghWKYp5Tpb>ufhu|L&D?XP zH+bsU@rO+DZ$9Gp@fz^NU}B$RsdS=ii6>~9B&fp^)Zp=Bx$#!mKoELN*cxpUh}66& z0p^sbk)5d4nP}@q9A`}&0kzoL!9U9)+^@hwg+=iYT%8fj`d}2q5ZsRAcg?4wpQpZg z6jzdioz&;|>5L*3IemMs{w|-)7WBINmdRrrdl#k;Kn=yqPQyh-rG;Q^K^`L?QqO`- zt$n;pvH;c<*s~x)_9(GyvTQ2Utcs86PO@2p9VlpEz;dIdXkjEe13|?*E`kkwil#6w za$%fKf)B3vjN_t_@;O>pezeAfA7W58&H{h)C(kxUdwsNd`61AL<7v-?;OrU`^wzHU zJa3683N6}*YA73L0@Jbsus@DZ6%u=Lml0_kj&6cAZ!A%Wiu&t0XjU#a5|ZVXh>GM- zK=$i^o=&zRHT*;dDuY<&;^=go=+B~TFW#kqVDp#{AXZ>SB=ZkK*9-LPaeOaFEVDI& zUh5)s1}a2xp&L2g?T0`C#-f++DBpyDY~4Yo)?9?=MaO`E$SlG{^WB{5SQBl<$z^BFh6;nCZ&S$3o#`jAV=HmIpiC)h z_&3{Ca41`p8H6Ocg%;dB;OL>55lkmBhd3{ zx!`L`n@T}kU-Fkc#AJz(l&3gbFhV5FTVRal2FQ#w4*FnSRj2?8UZYy)!79*ubZAUT zaQVe>D7IZA4Zo7L+nud0cco^$g+_VTElvOgcR08Fhn;``w*BRSFn|={M{;RACH8NskHj$W3gh$MEDs@jRA9 zdj`Rb>_87Ybk!2Fs|%8XouL&Sy1Lu}(u*ujeu~gSP!k_jxaQ?%G%HBm0fH)IozI$! zoUuLPu+ey%`%)Eb*=5TiAc1c!g?z2k96hvn8^<&8;~PS1s?%TRU;va{XI& zJX*Vd0=AoFUde+RQra?mnjQTU+}Yc+G@3`KWruy*b8DJx{Tm|Bl3O4ki$4Jk#+@l7t&u3$c2__&WGIQ+0ZEg;N|lLF zY>xCnMei(Rx064mZulhLHJ9BL+0o6fBu{We4z{ChQv@+Cb-o-?7Q3exOzVkfZnJ`S z{_0Fe1NXdAl2;5P6IrDE@dC8!(YuV%n-1?nS8Z-Y>089;&={dqwga7q_C?0^nx41f zEzxT&wK}%QVcLaxhyLrmHg!Py+bYV{PB|k9q`i04B(U8q5_NBr5BcX%g zVRD_{+PqB$(;4s*kK~39$-}~EC0kms?gvArJAFmSv_zT%ODW&#gN(w4g0H%)Dtj?1 z+mf?~0OtcWN^le(9b(l)`vS^bhekeotBKC!-t1Ql=Ah_=O?-%A%hc2a<)oj zw4QwnmF?IjBMTyOrW|CW`k+ob+FX%QU%p{8hQYNK%4tu~{>Z2Y#@A2qum0yK-&^Da z@7pYR$FQ;o{NZ?5sy$Da#y**UHDMUXS|9dbAH-4}!a0_;4;?ULn80Ab#%&oc(4Pn; z8U9o`>H{7EsE$IGWz#rFNlQWO_T)pQoxskC#}BQtKrb@TGUcuvh}B@KaqFx7YY;a+ z1&$r)`O%bz#+WL2q%MqdjJ*RBJ|-6~>!BpmSvsbUFB_mlMq&?ATc#vWpYiA!*HWFq zoR~~qN5`3%Hl>xt5GB(-fb@Fqt!(=%g^1mp7*%It1CXk7}K_V5iZFhJ$`7F1%x&SLK~X7oYde9zo$; zl&ewKi%mA(2SwQvxekK((uiw+k-($AMH_Hiib#G^q#0*zBWu7vK)?r=lYV5WD8h+;rWJT<^GUYHphoJh4DQ#w14 zrF-ofW>A`+klVf@eRZ;{#k7F(ptg+xp4I0aF0tS9LEVC?ZsBl&tyW0n3HCo#w!Ppa z_3)-G{sn@2lc<&NTZr!~R}SIxHhcXhk1-?*W?ZR(PgGIQh#4-DqK`<{ub!SCX}x4*Up+F5KEq=;hD_`{ zWwm6|_ps&Q0uM1bWX+sz(oYKLw?nc0S_0VpQt#$vjWZBsTqY zN{qT{WpWBbc9}+C#V;*R4?iFbce3kWg=xUqnQX1xAnKQ(8g9_o;aQssF}D%%qt)K} zoO+^HcX*YPC!8G}4-fbJ=XZSTKc1|TM|}a=(1S(se-nsr&>sI1fp`0ik)(ej8(jq* zJj^qkPj-&?U7r5NTfap)m-}1zNGAf2HRkfi2XeiqP~DIUA-L3_p#W^kL|}Z9)(|)| z?TcVh{-5Dv0!YO{4$qc$o&9oK0JZjsesQNxM*h#jzQI;nd|FSYvrYMMz(+d$RPA%q zzHr)?wxm^*2sYiz(N$DJ#05K|$vubEFX5%ZFbiHev+4s+J&5ilX9^~^PWyV^& ztLsK4Y1!+s==5(LH@a+}DLqzlT9Ezp!h3~tqOp6G)anI?)EUg_WV!Vd_S=ys3}=AW zlu|>Yw}TbQ_!|sK9$6Q%Bg22f$Copm+Uut`;W>LK%zrFayirm(nk1}p(c!)Ii(szQ zK~di$TOLXL=hG@;(~d$mm4~M8WjPg=!qI=TSevghsKEJ0J2sM#T!ku7_P9+*B||1v zO1U&c5c37+#X+nM2d3&p6qjfk4iUroD@N8FI-u|uInMemqT;En6sPt_$`Ydl@m215 zeG%@G))h?6{?A?s*)B#Gv#LJ?ya`#?FIK&~34G-^9kQOWLv(9L}3f(Z+ zbb*GQN^CKSGDM2$9oJ9@G!7uaf%&>dLw#FeH~Q_X<$;lgK6AzK@B{N&t=Fo}mT9s| z5H`(5HUAK`I1#VIYHlHkXNvIOhun<(6Qz5ju~9F+YuSGBDvI=-)=^!IPw>Z`k42E~ zRglvXePGm4ry|y{TMhWgVoy#?UM!~BR8{6l{hHhG(?j}D%3D|3!c@|?=4Z{`uip{s zhjFAAs>c(klNpC{bM2*R(-ldlH8N}B!y2I1b-DET+X#sWGOl3#Frz>>-nh5Eg84Q9 z-4zhk$Hh9!2_GVatg{!I8d*PTE?#kBO=$+diPgy{+{%9VT%ealLC{3SwR2J%+?b|n z3er36imA~J8O=v%#hI2g9ZMG#qP@FW7fB-{)qzt;aMK zbTs=>?#TC%zI?JkBDhGx{^?+X{#;Q_0&hY5(h8KToaT{fHH$9q z=T_&@U?|ImHt+$}8HR#gw5CWV8x49Tt;fPVfQ~hp zoS@|B!#y&FJAD&_fnyHGH|e2+$wi;%=lQ;f8^p6T4!WiE!#$fm;am^AFK$W5${(a+P{*b3xtx@e1W(0G&4RacghpM9)OaiG zB=0j!{ABtt)Nyo`p8~ren`P$yTX6^s!5kIOf-TGpKN4nhHu8bNJZDb01&TNLr9w@0 zCgHZ00KUbi9z zF?CpqfPW@hQGqy@Bi!|tiS_(42-ZB5kd#p!{T>CIO^P7|HbP3mWeiLq3Z#mmV}8SB zPy%JH2;}!9Wx4VQ(lznbs%>-hdU&=p&S9|O3!8Q+e~;g5pgpP8KOF-ZU8hozpw>x% zXjO8XaF8=>ca*^SxY9HSpIH&1z;wP>C1Li`;+wyUsWC6e6Mc+A7v7;6KyKM!kg z>%+q2axYnZzvB$AT?MDJWamnJOCnc$tulgwbv1FEy!N|SHut0V25}u^ zEc=?L7C_G!`s=s+!F+&sA|q>cg7Yjzv|0Yt-D$6fdRjP~90GHjb1ccE(zv2If}fji zBxLFMJh2Re)9#WiV%=6H&pdF-aFiy|%x(2x09MW*>BupPHH5N?4Jk**P$2;Ccjl3)s3F~+Yy(xja_X-Idu@xVB>`GOO)yMDm z1097~GAvze254Gp@wZ%JQJpj_X>GO1nY|-X`k%3)9qP23PtyRM4JD2#wB^kgXnEgP z(ofjJdsL{_)&d0@c#qf>U-Kt8gn%`x4k7Byiz|i_JKUqTnC`(%9il~lzyvemVZ)7|iJO~I}M?SA*!m#;1pM)uY@!7G;|xGD-?FgkrS z{FEPEXm;b|pzxQHcHKKftwYh+prVwG2O(6CxQjw1C`m znE674ax#y+5L|r#&&;(k?ydj|GSTk+0GYh@E`sUWnZEecTUTuRt*5&2@25G&7-rIe z=bIepYJ5Gb=_hqp%Q?T2^V}H`L3r2rF?VqdQEN+cSQ2eUduO5aOns{Z#Gg*czEk^u zcOIk_y!@F9=#B-qs0Np);YUlp#1;WCK%sZ<1AqMB!Yf6v zER@72<;YT$H3 zSm&*~cRjG>0dO>eU&rFa@CK{B4o3~c;lyADbnvL6VD1YeQ09G^IS?#MJ_$Jjw+rF| ze1HY^C@V9(2O_`)yTD>oS<^)~oWh5Tx!cbe9bo+!F4z-;5R;}spojo3LvenwO9Vru zXLNdH8zkP~qN7fg$`1JO3}8Lwkc1}%$~m^nQn2%TRuD4xBCLD0l0#XVTQ&q`QaZZ1 z)O;4H5Z?~ObOw5rIRH9^Z2pC8?t71uZi}*>^aUfNk9=_H1?zsR<}Yh1A+GAz2ZuK z4|o(M{>+HF%l<;2?g&s*gQKj!aSvy3=OrqN8Xy4fBNv<}3x@>o0DR;ZW}GKRCkeu?kV7D9urUw!i&-%5gnvCOI|icIJCJv@5!~cS_amC!Z3(Npha*U1 zq!A!528?LKh_GR3PPuI#&ZbA{=J@80q3Y8=o`&mM{5g(7K9#N657M%h)b$X<0mQl! zhuVCdZz+3&A-Sj#W|@YFj0^Q+M!=oJ9@8KudU&mK=&3-6VMYL~@X0m_I3Z~yrDKFr zo^Ga)d4xmY2PMiI4uC3(@>yw0I|twzgFxz>H4#d@Pm?Bt9Gbxh07i|q3@G~D%GW`} z)->>jMF6`xa*5XDM;x!>@d6%b#*5(!j4gx!ePvqPJQNfjI0_~eU>Mgcbe%7_A~f`z zIf7<$ESw^2iG)Vy9h?W?2V_$v4#%Y|8*RxNgR{YU1!3^DiI9%aWg3W1j3RA1?m-V= zm#wq0Vhjx~g;1ZQu~4hqgZZIgG&-vJJ4&rLD5pfF>FZ5$1mHekiUMF0?TygMpHZds z$HIITYC^4%LWcyG9x_P)b>VCEb=XuNG&Z9&1oCTYkyuwpf z(g$@#fqUk-hNOTgyokrOjjww(3rJ>t9jBw7)n6dE#oTc~46~-3GQmQ@WqNqVGm&z& z(;@Q_*1c8yw(7+E*zye{@lZvtg{b$fz`Qf9H~B^UuKv=l{^(V~797FK`M5BbFkLn6 zL~HGj2JCZ9Ky7{mUOMjj;oP93mOsTz94zn?rVbW+?gOAo-qX#WITnYcOUpe6Qa`|` z9tPC*nMbgE#_-h+8ej!t(JZ>wM1K3? zh+r2W^&XCI$3mJYg7{u7L2fZ6i-g3q;j<5V<}Y0+V^Wq&n0YG@se;Txg*23bC9Qf; z9K9tcoEOpnrTEZAim6)^LKvlZIp=Gw<^VW_?`Jl(!x7vJ+K3nOZB3;5WY2(&78+(t zkq1#ABT{`8(b<<^0xuW5J`q5ZrU+lhQeS>}77x%foyu|Z_1E}me`WkFM{(b?r9Nmi zl+=J&d3icMB9@PG0;GuO+gKun)(n#E)>qT*C+q!{!8~YOY~B;OS@@ z0agsrKH$WKYHUE`*k}Q`1;%(aL*b5wEpbJ^l2!=mV7sM&*>oHQuhlg{0>3CD60+gy zYW=bXlO{p_+I*8rPZQr;lQI-iSBWT79z^}I$>RM>U_!`h$LgK(#>Q9UCLb!o(NHzB z4Yr6bO0DqcGm)1wrUE@LCDT)!2iG5XWHu3U(-$zxOQlWJR{7ugA#I?wpU{Z{uT7_| z4cYOPlBhI}jIbiiEfGV}tLnKvpQta_5nXHY5_ID?n42ZH?9v1THnpa*1wz+(v;6~4 z$X4`}EY<3_0qEr+kE1vHZ&zh~3}6}ZU_1hgtmy_8gqWp;)HYxzE_7@hU8H>5@I#1Z z9gdE8thjgBv+vtxqmgvHmgcj3-Pi!d6qu#ZpB*IvVkg9h;pdawOPX&4MCl!@UO`#qDyOxv6k#Z1W}cw!QE`+>s^A2&^{^K9AJzccKLL zPkr`cwf0+Ft*lK6)(qafsou42T25jW{N;l96j;!%W0v||KvB{&4d2-VX+iF8;pwL+Jj&0D|)8>=IBEvjU0=vd?d_Shmu2JMV?orp>6zH#Io0e4=b8K(o}#N%*zEEZVXXSmv@ zB912_h^GY*ab6*vP~!*orujObg_7IjVt~VX^_hOA>&aS}MR+`+QWzR;1>?Zm&K*@|i%V^VOEZT< z`#FT-^Eo~C1%&*9;n4--+u)MHlM?7fozA;D>vv_Y@0b!V9)G@gQh&kTf5EZ4XMjdq z0`s#40jjox4=pnvzBu~dyJI+kE(_;bIJLu9CPKKMr194S<$!uT^o7N1=)yrbVgp|U zK3?|oFvI6FO4iysiYr+*XT{a) zhDw~@Kdz@CEb7HL*o<>u1Q%onE{hT0W!YTnvaZb|Lk$k{FM0DF8a~*~eRq0v^X~c0 zd)XUj?Hd=Xn-3pvJ_g;mCf<0{T_=Hx+-_t?zAnj*-!P0XCILSBxuQz<-z-vp_a$F8 z`EoNxi4ghpVF0PS8h*S&@St9}``gOB^RIsy@Cb2#@gDAqIa-vBQ5DE79K@9fkkj#d znH3N`=Zd{`3vZZ-4rqb{^r~6|^*_1cg}K3fT;N%Ad~fL~V=#z$+zo{S(y_-fo+G*_ z5dqu)vyX_(PyTt@?n&H$!bgD5(OrZ!x!P5(1YZUE+ zg2Hfzfr^Flch&X(C2szH{NLi{U)TSLo6ooYBkX#6x{ZvRuTM8mP7iL5*N|oN|0G>6 z4wn9zHQ#KFAxYQ6zmcxj>m&c(G_UV&t^X@%{vV#}+W*RPou3{?#?4C;ZU2g!N1Nxz zTK{LP>tN?V|KC;DzK({!RM+KlufO`{|C{QX+c}Wk)|1iNo7&uy z*x1!jS6Nf_Cvh&TD2=ach^gy9#?9f?t)W#dL0=kuk!5pH0Wxd;oR^iGoAt+Y{gX8( zA+zSh#DxFqxmG&mR61pS{tsF6AJ6qq)*O!{U47M}qN4vIUH?@!2L}FAb@le~{dd*% zo%6@H|HzvEPP&Hwi*!Y1&5|Jwf2pn#0V)5UHS>AIJadowm+Jbjve}K$BHp|0G=n zL}Z@{OY;i;gLD;;;QWhpefo!VW#@YFi0cI_=L=>Iq5oDk)3H3IWf!Jpc?Nhu`Om6r zCFHT$E?`t*Iwz+;663h28%rL0AQt>Oz)$v!YAEr)$IU8!T*O0{m+uR5a)@7Zk_7!* z+&q)yLnYBP#Q#V=)vM_rs%vf_=YSfd0seaI12G%>vG_Y=+wMFEW z@e8wDrB@u< zDZzM;qg35VYE6Tzfys|RjOcEXA79Vt6c!5nG`HnD;URWnbjii;6Rb;V#STPwv9e?=paG=5jh5N=&i zw4-@TxtSqp%ci9o)fWXdROZyz0)^q!x>-uR0g*&Fl2jt~*FYTMC@1Vj>s6?L7+-`V zBbB6nx}o08PD4V@~*rE1K-pX%k7^=rGbk;nVZuCv7PX+dJJyYqs7EztUd}H+9 zwk?Re&A{&wi8k)1%sl5~i@|njJMrqGyoFdYQAIw#8LU63`4wwBtIQ~&xllmO? z240VC9g?M;OK{@%k;Cb&mz0>WA2NW8Mh;!#cl@w4`+A%7S;bR{GMiDhG7jbbPOR~ zLzl?V&Cn%COA87}%aB74iUJbSDN0F6cbBM0ryv4SBB65gxxf4D^S#gB`#R@3*R_6G z|G`?X_v7_^Ur&Z#KFjzfFv5tMX%-}hrCu)%Lyc;CLy{a5A-=_WuRl*HITwo&d4j-- zLtPmSo(Q(;JQO-&D0+TVy52|Cc@@@EVF%>Riw_XxilI}-ZUu-tgVgj!sOic#Vjo47 zYj9Ok7dq54Pl~Gx2>aJW7gQrWe25kHe3N;h(Ja42VJhxcI12=U$VMOs%Bee}n*LNw zXQW)&YAWF%UBz{{2Q1q+VjKT?Q1#s|$fO|nRa`D9w^KcUGrRjRfx)rZ1Tn%iD5r@Z z|LFR#<_!dY@V2%#;H#u8UBNUcSRnY&5*|ldTJd@m<6xBpd_TmBN3h5|XC`Ly% z$cyCxG^1%>ijr#x{Eld>R`}>_%siB)%E|VQyRV*z%*KdRjO*&uK0n6>s@fBX%UD0V zM|Q*{Tlv$xL$uE``Q)v#1&190^`_>}792{Bs-=fjoZ@ryK3$oGNMz_Z{gz5f%$G78 zl&%q8&#oq~DLSQe;P+YyY^99&y%IAfjjp}9CV`=c=bH(CJ_#zCB{r0S`B&o;5pOgq zB2>2@w=OD54!51?e$|2XRd($+{S@$--PO*Jkno+*(h$$E`9~v^=FkcwVe@sp zn*hjx^P#!VUZ#qf#~0F9!R9wB<(;QD_sw(#078Vj2<`Zl3*JtYp+d(R|-|i3S&{yg-0AG!0!81Ze4S-8Z_>eauVtK8J5Nglhy3Tn)u0Nh2i>p zG%XnZ_I#$NiaWpkb^S0he~nR4mf}~^nrV$uwhHm|e#U9cFs8;|etXDz)MmnqWx2PY zBGb;+_v|#1=uC<$XK0zF5Y#S5JNlwkL%mMe;2Hfq`=he=o5UBh0>)g&&nDYgHKre6 z?QBo-?>kCc%&@41D4v!ZwC|cvUVeK2_h(IN``&$ntNDe$XU&uC2ahMOmaqQ)>Z0s8 zq+=i&r+ac9`C6G)>>lx^{Po3DYR74r!Jl30>&u%BzO$yuKL;V#SF4nr*XM%MToW+>x>pGWe@B4x>>%`0Y_AR;hq{`CvK&4+m%#U=!MDZ{ zlFUVz))JZF;X!2#2r||0;E1VYFo!0@@HrYToZyKaq_hcsY)83KBb4Mrad1c(j>B_F zBcw0KFwJ2!F%(PFr1RVWUlC6&HFQlBESQNWtVt`Hi4mLAXP%>8vU4r!cfE1N01i(H zh*puIy&2sdq(?J30f(XvKy5T>f$%yINHR^na~Q2G6C-31<0uLBK(j345yd|hlJ||V z7}B?r0m>fv58&a$@ncC0MZ!KKjw3jfd1Fk5V*RFR!}FmJu94)y>(0{lagWROgJb|5 z|3_p;fuI{+tqg?o0`nh?$k?OBo@4dJR0s?iE~kUUQSmo#8N2{X1f3Tt66PCA3ga)r z0-#KiB0EYl#{~C4tp2fRMmO?1!UTz*SnH}^&+A48OQ7x+rcOsjX>xJ6LgFlvN}F9C zDBo$FqnMN%b*{Ax`M_quDS<2ad)ud2Orx4+D%kVlLqX<6xG7yWAgm;0iapd8EM_mN& z=6gpDlS*-+w^N>sM5Qs&fRBO5=!dXlB!1mB8hVCDxrPJfY0_N-=_oC=TPp(|Jhlp6%aM=ZKVY+(+B#|JApL%d`GD};1MM5ccbJnq{| z zU9yCIE+j2?WsYL80t+&xbjE|8*T5@8p+9S&?{K$@x}ZPpDAc&~)UhGCWvCFGTm3od zSOH0zy*#ZNIjDiw-2ec)w+VB~i+=2+HNDM;B;l5{|^?&?5pz z5{?JmI(+uJnWSQhWmq<*Ju(_>ln{N$~RpFTXwIj%GFfei>Y3Q=~y{VyS}PHil37kE%`8b6yTa%DC>{j zQlgZzj$D)Y)0G)`RU#;E76p!dD4g-~HzI2YVdT4ZlwZ(9N&*0dJ0(C~OTb>+sX?fD zRm{d7pXbo@J_Af}L=pt15}YCr%O~kL;|pI1p}V{{T>+pB{YLAWTg*Yhl}!SEn8*BK z{)o3W1w@85Ewi6rUT;15ja7$r5!W(=Ng;sAEVuerWuS&=z%C~*Bt_PTK+ul>ITb2| zXl?qg*ASwv6G6}=5Y~(cYGhJkTE$x}Bkg8thp;~%=z5;5N;;FM8`z~asg9xaj?duE9BBL!u!q{kM_&=nxEu> ziQUeQ*>;>$MzTj&&uROv4iGrnMG-_wa0DK(>!fOXia`KXN&q;gyZN*g_F8i`I}fp^ zLkrQ$KmacUND1u0JUKd>9*~DEnk=4>1^G(kq7EoWlim|j!VjR@dK;YDUtG~iGPBAl z06MyTb+g47Oy}|ugc#W?yw_*Z+(C>2S$OK)38m$Ouxi)==*50A(}Dc8t~rl^KSa$d z)19RFy`G*C8leEO!r)26fb?$`?xX<%!xw>j+Qr$lc%G1`-wYw1fXOxUP_GPXGW1*GMw}CTsxLmaz-;*}+b?@;N%VXV<%Gq8w*Z?7N zBpTLjL8X0wl-E>4$o&4f))KEWR)UhCo=zd3H0zJF~$n(f;skOQPLe|X9@ z?P5QbYu{6L7Z4u*@R4g!OBX0yWMCQ_BUqbKuh!ca1OzGQ&vd#;YR3%QwdNpNp!Scc ze!V?oaH(oQ=?~pq?Op=>8M{B4a3NY#3Py!|z<23WG|@-1qmSQyGko&=ETl^QMFwVd zn|5||iX?3^+VFEYg_7RW2SCB+yGNgv*~dKF=LDUkZY=R{`|=r$0ROkI@?DB9fMX6mrER-1O}mZkZX0#MlD0^t!vCZ9T1 z7FHhCO@R4$gPRSJy-dv6EqjX{OPO7I^i9}T1Np?Y*VUQS_#en%^AxB>g|x{|y=5u; z# z&cgsU)^#`7hDe8oycb;Z^%`8Co<9$;x=ZUfwI;GYav{d zQ2R|&`w2fq`UlH2ffInWFn#dyHi604h->6RK5W|@vk|K(CYXn?4F}kSXz{$}QoZRu z?9q4~tWqI&)Y!MO^oN#1;W2r@lVvz+0!Ubf=PT|S<8NtBk3x{!PuRa73DSB%zq`P` z8riRb+1K3c``d&ypB>PZ>C<+31JyU|*mf_VcF!qo&!u}BQv2Ox4J@wkX-bh+oQ1vz z%Bsiu#d2xi`(%vD{=4hiI&t@ofgxzt`@j^ob5|HvVN3g#^@nEKs2}j{co{x^Koj=+ z$2!;k9n35!@;jmLmZ9$tq9<_0Wg7gq0QD2vz+B+3H(bMdgYph-hb>LhKJaz|exMI< zKA|oMJ7&42CQqe?b~5bd(Ux9&LhNmi1y-mv1a}puH)y7h&5n+3*uOZ2pBPU!)BmBd z3Oijz{Rs2j8>soFdQHQ&LPJOiGyXA5aI`083vjXgG+jF-6#-oT0{m?IyuLrh49{#k z1v$OxU=M%=C>8RWYNg{0ZTQQx?~rosgvfro;Q&VR;Fkx%sgf{|nFm}hQ#1T%wG=rw zKyISDPrk9zqu&BgCIPa89nkbQV)hxm1hD+UxwPTY?X*+Yf?qaiqmC;8CKZtXbH?WT z^`kYwE^;Z3*}rYy6Mqj7Po*tRr8TE)-}Al_!@p9%98wirc&K0y{FG&QDtFs+q(y9Gm;6>dLB`c~f1Co;$u;&QMLJgTp_xIY=MVn; zC1$obwCl0Q_%>L}l(R>3C#$_1(qMOrl1tt<&9OZBr|Qbo>t^|_J}I75{!h?H{{G5= zO;*p_hc(xz##de|1G(0}G(OrNSuHXyh~yQ#MNQaR@D*$>jpyEpW4-N}^Nca=s>CA+ zsb*%y?tO3QZlRK+6b&tZrp;yW+5S@JD=cdVvWZsDyzK|l0JTnZzv`8U5C(Y6v7eFqW}bfZ5J)$7au;L;o_E*}G_*WYc>oQPTs zepWzq%`>vae*4I&!LUKo&gq3WiSp)KRTgK^RH}lXtGpn)RT}#mUp5Lo>RXhSWcZ8YtMboA+YtEE?R;%LnubD_ zYyOAz0k?L4+D1`w?=U)mU!ICs#I(|=?2t%3&JSd%d%YT~@DU{G3M0u{cxZKFV(rV6 zzR#3Mbd;m(%mgzEIW3uY*5XQIu*MzG6(_uNLXQGZ*=pRV4CGbO7Vk>%GfAeDWm%^YfYRCB_%E@vh0(op>pT`~wkZ zB=$i=D+%BC#l8DKxPR`%i@ zT>iAP)c4BRjKli*ytmg{6QwAPqdGe%^oLMzSib+jwdQF4RQQ3zWO#O1;b=?QwFylU z{^O>%WJTR|j%UXhgx^}y*Y;Zh8W%QyXy#beagi`46d}qA|0ZiUPH#07X=&#JT>oTu zj$%U%z(kKxC3h2}$&Q|>x!lZvC*p|DuQZ8B#ZWQ4g_Jy@nq5kDC}t?p1C|y-R4}iq zBP5MO;am?8=}{@Z>wvIuC{*^TN#kprO4zp_+?9FQ`TJI1Bz>_afwV*43|T*xZa7DE zVy76Bzwk>420P-CtZSq+h~X%@1S+F{;_HCU3E%55e#n2us)v`E=A0Dv8gP zOPUZ}dc-wp3`;K07VPh-)wP-=)BG$)Xu0crr-Oo9S5pW_;Ap{wXxH)vs8N_>M1m}k z%!CxYekZ|B$f`O)r9ZI{MveZ z57B($PIiU^4~ySnDvHZVj`Qa_oEz<`g?{N)WDOe?H?g(w;fEK@BoO2`(=+UQooV8Z zq|5~;|7co#leXzmmEyhKf1tOWZ{!@<^}fn~$e+x(YdDimbmu2FxTGp;!@c+oyoC>s z76ExqyWT-R{lEpJm40|!PlDgRXa0f7<{C=e$j;|u{vd($Ifn|N@e(Lh@}##ow7GWx zPc;cnu$lro?^mr5)MRD4m#DbfFjMZW9I8CGqwt86H2fNwEbFkrw8Guf@s5|xWMnL1 z^O-ocIw%qLVYAKQMdQn@hv>@7G#+qFG0BXcDrS9MR77={$^K!sbdf{ho{93-tr3we z1xFEiRmQ2q0SQ*B?c0x?#uz9@B|6v>q#D+U@s&2bpJwA!=q`C5NMW@*yOX^nUb9Cx zp4urhQ%MFA(Bz-@Rop%zNHjSYFZzVjG=1a}UEcGF9H}g~iBDlG-TS$dBtU!&26cGU z%iOKr__kmT5@I4e%R2o?BjEQlx^c2zaC&izaEda6Cqwmkdh1U}|H6Ty$bD56i) z6{l!hp9cxAUVePkJMNvF=9uEsHttmOj{o-*>C=qGO>PaI*W7il!ozWTHQJRB^3fc;LjzICNX;a9xV5RdHG81k_DEhbN6trBQTl%RZyY~ z>%kOGVXFzY6Tg#ts@pAQxO+PwG(>p?Hq9RLaN>G=?A~m-&#TtmCZvBt^WUFPSr_k0 zy%3WJAspGAdI6xLXLCPfyF1M*q@$laPNcs+C#Vc)G-bJrdwpB{59^;_u%~v3f5RD< z<`kFTrw09$FTSKRyg4$ailD zI19{}x=0;9op*lcn<3Z-5=P0?$|IXpw4!@EX-e@{R_0mNmE-2{U(Ye7~Y zl0-}rgg5hubU|m1c*sy9lIC&@7T*g{T(3eRid7=%d+^iJmZq9F7P_IjUCJ~ns$3vp zJJpd55{=M4{v_3CUgh|}?t-Dt1Pir(i=LeP_|G~u;2Je+W)QfUm#kUMdJGRKh=t&k zKW-@Qi1iywV9hee5z0|dAp{}6)5dYOp{_DJ;GqB#1F4OGV*XOUdY~Bm97pCL#+W16v zhblb?@lCWR%ZH2XG;jVlqa)Pg=d@%UMq<#BWwWvTnIpyL6{%RY5?=8$-Y(8PY(qm~ zo(V`2Q1n7$>U0y9dO?iLV1*=rPDd@NS*bm3GzyI;?KceS8ZAZ-#bGr$lTy6ctiip7E>wNq`^1E`JeR?=GQ>%D&^dyjD8&urg zR!d}!F*uLL&?^wr59BXKY`0MeiG!OZK>K@1HX{|79lg;u-db^zge#))*YBn1@lM(@ zDiy}Nr|!HaPY6o8m1u>3*e6{Zt@l?VGj2?8VQ3_>d@R;t^s<(>zPG7037^C{q00%| z=&Mr$nivHE{_zG9;;~c3Y_;#3$`(lsc@3b%V7MNZnuYu)7hS<&{B&DkaBri5&$JZ1 zHp9DQKYYlUQ|ioXxaG?THh)7y#7tQxItmm$S>A_NAojF*d=-ZAr0%XuG%7uxjIu~8 z2nMs};;u>ev4bZ0!fNkQW=VcsCATNug#$_W_e{SRykT?GPKf?EfeOSvOqj%lAV@Xo$^Bxm z*PyV(H#wBXmL{qB&`3CU#qW=jN?9R+`T3c;iq+^&ki}xY#Zx=7ly~N7#}Wm0n#DBW zM4Jo(j4AN&ONQ4Qkr6~n%@<~V4hnuOz=EChB->_AU_VAD+r{K=S=wt8I!=9zs=2x5 z3#45Fxrw2Vw->?S5VqfG5N}ibaPdk`5c$ zKTm;cmG+e^-d?~jqBn~=AMZvlOsrBnvn)-2T*TtpEX>V}i&B3Ju^C|*n^#M?4!;HJ zO@y}ZmCx%&t&iJO_zcA3Enf!FaYQX{?2kPkPlngl2W%$(^g%w3S+0O2C+sZuG&3#> zLH<;I+7Giix<$U$j+=E#mA14wku*3*jW@6){Rvv`LBGn0S>b(dtCCg!-iz~>Pb~HB z${z~ju;f&{fqT(tbHV_-C0DzoD+tjGXc2qrv#`~=zJQlZXZQi%&_Cpu1s-HhfSSPxiD)tzMO(>~Ih;nI5>I{Gc{zCpfrDPs(iuz5_GyHa^FInO&N$IbXT>1ckVxlzJ`p8@ba^f~amWJ{Raa=lH<260DP! z0Eo}qMeAMn0=>hN=UpByrl-#2;53T|+}p(#w*5e=XPWZ_g2G;S`{CKf#1zfr@NKDV z8}eJu^AtEwt?ppxurD{r49e;ci&j0`zVGv$%ETzE=g?t|F zK6~r69FIOE!sJl{d&37K{>yultXS94 zlm?Rh88d9~vFC@_J?3f8kKTKv@lvS)`zGoPfp!VYV(VYt+`p!xr(JL%FZ#5fakl?X z39AM@c$hc8$mm@nv$tX9NGC%oWOWdEXbCm}wG)%?2`|)5d2ctu%-ONu)Uj2P30a0~ z7*XpQ%^zhJKT2F5{OF+W@xt!@CHosZbihsad&2r4_JKEhOlU2l6qlNR@BmBupcwbO zRroMi(dWVVHt~-iDuf=O6;JRQ;mcB=j{&hOh(ida_sgF?Bc+&h3g4kKOo!$^)wPGM z*$r+!qKiAC&p2WzJ7R1)Vj4VR{(Qu;eZ>0f-*B_^F{j2cm-+Fn`^Vgmk9p#bdH)kP zckaIOUlp8sD9DqbE0icH3Pw_%T#HdA3L9~_(`fNPXL|GoNJR4Yn z5_~)LMDf?j9nw=Jx>FR-X(ww*y-|W>bL=a(PbCOq)hFcY%|b>qg?0I*$}5nqEUwa> zD3i<_byBdWXe?bY`JJIxy>Rdy`Z)h)Ki$bB`J10Uk;Iu?D{B16hn3vsD-dC2Fq#LJ zN$!6*>~FIIF)n1ckSIAO0-q z@~_8Q*148@vq3C0*lIw(ihUaEcVhL-6BaqJ{!0FSln}j@N0AY8H8@f+Hvbw;Vlk1t zN@B40;NwmiKjWAjt=-sb7dCLT!Fhbyc|y~9;^2AG=kw(4^ORrbsiYS;x}YAj035a~ z?N0x?q^%?RV#bRMdj~|T85N=t^wav+OX-ztksu?+jEIal|D9hL%_#4hI1C;^90Fs; z%M;K{A~$$JIC~M#o$P*VA zBJ((wKE?-EL8odL_K4*wX7y@`^20OIzx%g-#>oEPR=WTHdkFgMzYjs*DCzT~t+Uhp zvy;8kll_yU?}vxq|Gocw{y!+`liij7RMI!`=fkgaH%j{3=9e2Hy|*&?@7d>nQ_?d# zE8}0+KL2O-d24BWZSlkZ)O=q5+_(05;J+ZX2zMuWt>1CBeW`*sG@`Wexe_82g z&z`km{u?Wejfsqkj(u{Yq{IKC|7`cH(Bf%vU`TjCV8|o?Am4|6Hx+2F2aj$-(El!` zwd3<{LeMu{T0JgDIVKwwouPoql#9raeUc#^o+1(YTrBw6|K`%EHx=kxk5Xn8-f5=XBrA+rinx=AO$diGM24>0%N$V%p5|A1G~Mu3=;?hzkw*Qq&i%Kbr{PUpxgG(d-;nKV!3O8K(*1xPYzcf3a6oOZh zjYpD|TjD>hbmD&-f<_i7VjB3}7hMl+Yd!jXe3%)0O`9DqNFrxd>PklcA6EKVzGTcv z@Q5y#-+E=C<}-eq{|G@JY;wM<{Fo8=#(inzUDfBec0n$Zu6kxjAHH61Y8ipOZg-dN zmRy~tH%spWPq_DBes)%of(NnuLqp#=qV7BRei&`8-5A7i_BsWL9x9C@h=YmBb_*<1 zZ+kJ!ax#|4`;_zMrKwGvHsOFLlC*1N(B0Vq}j3rfxeMrZYUL zpQAPOC7q_qK@rlb+92tuBpg)V^_@>E*Nv6W#!{W_Y@}MTNCE-S+-`I*7^PtxMRdzT zHxxvsWhlczrfQ-pAX+>UNfa-R%aBMjc1AS>HKnH);a7Zp>A5`nN$H`MUnY)O8-5?@ zPhPyK;<`?w|AJ5}2!`UelKqfL{I2<)v1`YduSGa@cN#sHupwtv?7GQIC0>rxc^x5+ zh9%UmFBZB!Df%WZNITkDw>%QmwcCeM0;HvG!PBpm-`|i_j~EJlX1}?~ROIPr8m<~> zx*O`jKo2a9U?~e%PsDzKOXF-A{NA{@>+YfdYM#axSsBe?r$O$fGt&gq0xzIAZT+_1 z%T*+%w=aFIdYc;J?x*ow|Erou8N`&48hmj}f-=3Dyum>)cg9NBo)cdV2$`bgs;zE5 z_)ifoZLuDb;@$yeo)o_!F^E&Xmsoj4dft+G`@emtSD-A{)iqod}37dY&W zeg(;@1;C*@GW!~#7J@i$kdQTGn0Gr}L&t%;!C(2@YT;zg>B&2>JYQtrxS;qm)szY8 zB|tOT%k)e=@jBF3lXUQn#KF2Rf(u(GzT3^5|rb}t6r!yor zd9x)Vu-`^qDRIJbCi>JS+>K*(Iy0L{d|{m8Ijc#F@@r!nZ`897mkzbEmc6Wt6c;0~ zQ8#i4f!?)3wUw_gu* zky{-`7G6!x3;Ibwf)Aq*ds!iqpLaL0Re}$lv3TetT`}wVo5-k1+K@ar{2OlNcL5ltf zL5uxwD}57!{+E^ZNh)IA)*O_ZKl=X@f@ZbZ2?%z}o@P|;*8f^8{;Qc(c5j=eTlQF# zR1maX-1B}}rtf*bCWcH;_SyEwNLZ3+rYRIPX2?I|RzEuGFu{pq-Qj%Eym?EX;6$OT z#^|L)yd}~Cm3{m=BCubH@aL|{XuM1U^Lb3gNN!a5 z`ZcU`n8b~=!1T(+P&@9BTK$k;Qzn!!<;Nm^y1%Z$;3o}SKl7GyE)B$vFEf`nV!(~UA4PrY`vcfG>u?ync2oBSylXUAz`w7L)fH)MRuQl}o z2+0J0z4^)?SzIcgp@!}D`)W2pqQjnFPwd|%3!9YUYT1$)_4*a~Y73>M5+*caNK$Ma ztNX^dGdW*1*5huRphQJ~#2ek5QQ#-5YAZ;K$ZcC^S~9k>Day_BbwZl{W%=^Jn z{QFX*NdO|lYc!0sZu*#2^%cl1Q(c*fnv4|6ZqmZT=pn!ykA)i(rDZEab>yRx_}J?B z_*MRn(2|PxxeM}AW+c%pV03>W9{X6M`lGd0Mzn?dSh%B4iU_9`jLv(oU- z2v^Nf4!rqkhfoO)E=f0KY~hSU&1^}9drhLv?2Ou7VMW{4uS%6!1zra<*X>}Gc*~eP zy%p%0ad}M*!_i@BdQG51|M_=!>W8U+7PAD+Nb*sad#wZ?PILLPw=)@L2u&)D;PoDs zkKgycO}NSeRP~ z9III!qPOS3bTv1m-&mJ1zULx;^<^rhv7tW(S4)Q}O>NtHKY|yomd_`eI)07+2*0{o!J};MYLdikz(ZF-+X>`U z-oyC*H;1YgGQ9$phrX0JQtG!(MC2fh!yIA*K^gQ8nbO6CT}(5+MqC)p8>PC_(0tt7 zF(FVcNC}Bnf!H7~h8eORmcAyUOwOBUsZo1}-YkL*7Q|6D7oOza+;VuS1=75d#_74) zv6g8n5pd(6w=_z=>1%M!l09S}Y9)HxkJHHb8wzA+t+8261rwO0rO>2pKzi5IDfJK8 zDkq8d?4>v7h{ZfG*y;_MZVyRvXD}7zCbYq_?~VlGm+GksA&Dic^SU2%nBN!f2ucNZ zQW2c#soFS+gk<~>jq)3Nzy>dn zla=K)$Yo={@~5NV{3@noJ8LKE${Dshym)a2(~AQv=+_OB=Uun2}s zjX4by;gBWOs} zs)M17oH5pOKMsglwX^1xv$61el>rPMx;xU#Ics`;&NmYxATc`fHAKas?c?+@ak{m! zDIa3nNenL}Xy1wgFYWGz&cVgaA4$gnWD%rm*J#RpG=&ZiK;{Gb8bP_?L#ksz9Ukc6 z8E^-D1lB2t(?ccb+9zmZ5;T3WckTT&Nu!=w0M1>M^*$uQcF?atXz&ze37VufpHgNp z{(Gb3u&CSXa=3Yhzx8K-QW$urE7bXr(g^{4t>Ig>3+-xx<$^r2>TX**k`bUF4$YV^ zraJfSz(3KDF&YQ=4W>pPN2a3y-!lKdO|BbVp|*#V&S;3@A!Tzn=prJN#Ga!(f~C<; z@}r#xqGS!CGn}?A4lAaz?UW-Csbdz3p5j^}wd@V{+?hgP6D)kxPC(obU`Q`~FBi?WY zvWdg^@u`4(N`4n$*BnOt(bwopsEH-uh@h-QlLU!E*CT@Nx-pR9y>R#ftO7y(Q!LHC zQXXGC?P>_!HB%HzBq&@c5@Ga0^>$|Bo&?CJ#I^Ld;=_4@o(vWE%T7_M!k(c-0m*Mf zY(~H(nu75K@SM-93vC+}7ex3R$g_m_2W3$B#=>i#{4sybf+Qa^ha5~X{5em>{{~>C z<(~#2NvE@?Nm626)AOz$0sTP&dJICXW|9yXhS~x{Y6!hk;D39Hvfm!+{Ty#4B3UuO zzJ$S*u;9g!Iw?UnnU7j<;~JLSFpn{aq`M^B{Mi%c?nq%!;*BT1t|4#KgziTW)D4pU zQ6ldEB>@Gvm;&;!$g4MmyBR6Q|)NibBtT zc=6%T7tO{$V}NaTV??3cvX&RJrck{Fc2tn#K2vNEs6L1VcxuQ4?MR}Kt}us^$pA6} z_O$c#63`K~Y`K8Lt|!Lst`SgTKF|3`H2+a>8D#B6e-}9C7A}yVT?_&A4_TJ-$ziw4 zp1jmB@gZcsmXqUMB``!osOTOH;L2ZUdtygqvdAA~A^?Kmij0>r{YoHdt`r} zNJxypoS)r)zOW=8dQ*6;YL#L^%O_Wlw?{P*KTO zTt-++HvCepI3Y%aCbl1u(tnse9jx~1vWnM8ZZ9L)8$hy-q>a&M~IRFsY%w!vR@9`5SXLd9})@>ZUuL#&`Nk#&>$wT5#)z zWZ!y{f@;$cRq^le?w55VD6(}cpnd+GD$QHP_wY|IV-&y)4jzC&VxxL`o$x3eY7KF+ zhFFc#6TNTrOH^HTtFtaB%&e&Ny`ul44J0x(D{)m0?ZO|)*Pe90OOaQ-3BNea!-Gfa zM-hO*JpDKK*BObbWZBK;_NB{mz~cq_7uFCY)9aEemE7;}?Cb_2WOb5nD>1UUUS9QH z2%O0S2+F2&VXPVC2d*#QpSe_zCN_+PXco%@uNLT4Eg=j7fH70MVsv$S2)z1Q9(Xj` z{`0Jj81pU|2`SL*P@s8#7gj&U$lg8LArt-H{HQg$y#3^;;WSZ&&7(SCy6MlA=F%?w zqYmKG+7x6+L;!=3BFhWpyJSq-et7`i=(q2yfHnSZ`RGnFOe^703zZ1W>z zYf^0+i3flT>E_ne=on=V@#r9|ZOLNl<@f6f#Ps;V>QCJP)~a5S=nm7hcG9D!VASga zci>E?kFU7VAHOHSzK^h=@-w)f$EnG@pojdZZxq#Sm4u=nh4(Hn8&;OxR~SHWbs5yQ zlj08s`!S**fCc$}(dM0Vi ztY8dYP^dUY^WrstOQh3m1H6;QaU9^2F0METj8zc6B?x4_ZyCiO`1)JzunO=*0O^bL z@pmW58eW?g^g*U4yitRHnUzn+Xn@y%Z4zCMCqNlCRdmuxn?6at0FVex7g0|d;Wt2P zr~D1O7%7z7tm%j-Xlbee$@g%du0hUmdbuka7yikK>$EAtv=MZ7*X-p?0J3)1n(pK8 zUIO;_AlNi|ZAL*z?%+M3GRA!MnBapFuT^D$7XdI6PaY zStqSwsERpg98hnkNgHj5S%QCX@71@zfg%&$_#>2tpS57`Qg44Tu>YWq{FH|5rI`L? z2%9eyg6n|cJYj(D_mB6w`vcd8tJ_7Imw?Pa@LI1%D_HA@&*zpUc&8AJZ#&S=Li>9j zcs)+jIaSxc)NejL0x76`+OG8KWq6mF+kB@s>6IB7d|q z<4*wew$zh0TT*FTQU&Wf{N>~9O9rq{jt5)X_*;X!HcTOOd({UDy!^rUSebD7E}oVr#4w)Pu-u>_Ro0iD6au8J_-_ggQ)ll{Q=ie+wZ zVFsD-4YAq*qN82nwbjlyFy=fOPIG}iy!r#Y$(O`&3^V6DUXhgDXPHT^@#+U6s}kGA%EQ2gF4)*r_DFg?X7 zqO_K+i6a~QH1H3A@4D)Hw+#$G{2M81j%sb23|3B^_(^zjM7yB+-Q7=~JqSXQ#zN7E>m`;og*rL7R51C=#mVvcw zK&=z#Om4fC(_j*EX5C5i;K7N_bR&)ZLP}m6$oD;U_c)n-$IpYGfvEuD3e^P^*5nP> zv4MT{I##$t^@XW(zVamT$D$5?S_liw>>k|90QNh#W?B(o6`?lM0}@s)zIM>e&tFpG z?^q!(p=oEt_-Q}&0lD^Fq1uZYO4xceU5E%=Y4Qxb_Or(Z_Vz(cuL#WI4i)wH?|}W6 zo;QG~=atYk`w_%`?_1vK^b>$@iCUC-?sM*Dg#bWF3FBs~U%v+=zq;g~KTsLp-3! z9Zx2cESai>aoLa)uL$k?O&~=zC6j0dpR8nq8{@^iyvXpc5VURo%jdT^tri->KWak+ zhw^Scr=`xul@6i^7JBYx`?%I7IPNd^XPf`9?O^JpNWYnG^g8rjM&8Y?f6IbF>&Q{l zZ*a{xWGRgZemyVV?9ILXgoMS)uhwH-eL?cYarO2)f0Kz@nk~ZDV>vI3TNQ7twD)qm zL0-#t_L=UBn&`)&I>W0Xm~f@izeCNLCC_G(*#`4$t^#UKj%hY~+qWj4MW==-zBRJ= zbcf#=8^?C<@9(Fd{!(q4?bob1M1PC&dRzDMP0>VAos7zaPfb5uTnEg$muhXjnt2l66&I)rj`6)Z&gnUw(c< zd=+Oo^J2NuHzRVff2?$!78~*Wbme!BXzvn!x=Wv8xa`e$3{NMK_}E(uP3%}luwZOk z#gytv=g(q?L(XmGNb>shJeat_?Ozh*j8^0?)jB)A_8qjNu8ECe-%>q$T`8z?5iK#p z{gW3v0}#*j@iSX$r@z&2(v6>T$f-5vqI{<9CZ%QW{IOr2JXo>>42Em=K7S)GCg3P{ zbgY*tCp2u9qOZsI!GYI9($aa&xFp|2?`3VKrF+5$>F+f?$CW60Vlpw@jM2Ahsf=4q zcbApp%@BSnd|EjcAcxN-r=?VV{RAx=HN`m+;!XFS+*%xm z*CCFnkH2PBQU`Ec6sWAz3%$(P1coxRJ)Qh-fmo ztm0&wx>owcYJThDdZ}u;s#gPW-u)K}x=4@rKcuvtzcqbGXS+twcBA(mChra|`G_lU zsF*9dX|}P&g>pSKBP%&ZBV_qtZubg<_#KO!zRj0c?s-k8*m+kh51HRzstnbw(lW`V zPuZQWniP%~Td>-0|Mg*+)<8CQN}^JFw$te2A_USG>9 z@d`Q#Jz2vdOyy5`kBlEa&ha4v<5VVcv>RuRy0o)spG|v@|p-(i6xc~0tQ%LvRi2`aLf1qAhistF%D%`|> z+#Cfp>``IsA;PkH7OHfp06Lh8V7cxk?MM&C^#_hT(uHI;rg62oLN*x;}Q-g|Dt zSd4r{mNr#+HXBBmgH%GxYk7`A%4#|}N?}e=c`l3YKs9gyv*JA!tsZv@OQYi7)Oiy) z99h#Nv7SGb!6Dn4p~>Uhj=!mrq{gK`!t+e{3m3;Q3a7GaCn2#IAA9_cnyGeEqhd@? zKM9^D*6Ng6Jv$;`O{L@Xb>OLFZLTSOL(kKs>$nazn?-xEyc>ZY+{~r#+L@negkMqo#+mkb>vNt^&`%lg>@@#Tp9iI z99I$D!1*CX)Ai=aRwqijFszcX@>D{{&`V>jL^d_$Njh1-JeGF}>V`dr>AU^rBGb-h zUmFy0G!F{i+cT>oMtWY@s+I8AyBYj&m`UF>7Wl%iB^&Z#vXa@P+~}f0EArB0sCJD@ zvxHx)NDlW%NrlmLbI7DV_&KsQy7=A&|1B%T|03-^qv7fo{{N3Q_AnT|1W|+Ny)$|j zy+xu#v`Ca_5fZ~-lwq_)gdj=?q6E>6K6;5Bgy_9QkHp_~uKS$(oOS=o`mO(3^I#s& zgT40b{r?bdjF^%LcrnIs^t?6|V{#d6ed zZ9`akW|lUZbL1(+!r(crT}Jzt=3@Di|6yDf_Z5h>|SQcqW`h_x9FC;4fo=Zl|r zp%*9gw4e4pT+}K6eEKOY80;Bb@m}s*O~=Qc$NbRd+hkO{^!3a+8{w=Oi%A`l#k4Z* zj9#^r5NKWp#34#itih2^S?$J|n|GYJ{LJX>+S}J}`4_4j7wv+p$>^Lt)fvo?J6I#3 zw92akhZ$K1x6lV{(}4$Cf6|vz(+0W224W(34$M_R=bZ6jcb+}q#F&2UXflgONxcz3 z^SW@}Fno2$K2nnW+32-2oo1PY+~SIPCL?!1hPZl4o%0i*W5786DTaWIy89j12g{0m z7)hUt&iDzpAGm~*t1!v(({yL2*HbAtX%e3>6Swwqybm7?T^0|oyV)ucu$hk0*~}X$ zkkY<2DM03l3@YQ`ll=6{XKSp6mceeNEkag|9)7A>1ZFHN|IpTTPmh49c@QiSD(K=? zwmib;&2)bzCc11!W#px;$pL2kamn=|1Rf`TIbTAa`18=-`pEy;V)Y1~ShX($Jmgln zKIfHsc0xW^u|!HHxRh+bpKA)dhC8;xua?+}D1ym;@{c2=B+qpc#FMUV2q>L2YJWBl zv(z~_bft+Vl>+(&ab4F`u7%Up|J(zf}+LAFtA#3Hn)9 zKQ)=l3K@F-4wI9s{>8s;u-8GI@x_hhAAGWXpAAZ9-;(A{=A1;D)hQlh0IIs~#eUo8 z1mC0jnF=Jnl;ene9@{;7zV^uFmz6}pYp+;AO=8t-v^TFtlo|FQA>b6Qz3cq!Dsvuj ziknnx^VqhMRZ9O3iK)B*NpLxRr3=P!nzdX!bMj)_wUSXXY-{a%z{;Vi(bNBv;~GMj zSC>0pCa=hKEb)7Las;Dn+e~dC2hp`(V|u|-{fSg~Gpxd$)O=PkyO`%e`lp@uF4Y+9 zL%Uzw#klPsOOV_DE@P%v>bOEhIV`_O>Cay}2q7d0E!n2BZ=W=_Zz{Bk_r3pMVw5@R4v!%a!@Ej7#jN2G}LXsnl)JU<3jzxdhAu$7QjK1;39@1 z`vy_|T>SfUc@(_G=q;E?roGrzHVMrsVn)d8(b$e=XcxN%F^x(bs3G{vSR^mT(J8uqSniH`_sk8H zaet(uhgQ)#RZ4c8rA!G;uVw6oi_d6J<$b5L5G%A#n9QYl3~ zIK6%rlilI0s+EB4H2S8IJ`4F^65ZAwOEA^*uBtaHLnrD?^I%;)h!QpZu`q8NaP9}Y z`1TG@={9=d6+7uA>FY4m)iMM_>ePB)FQa%xTFGVlGTETiOpuFTF%qtNH4=S@&|dCD ztrY4$l$93iY+n(mKVbpUq)qUSx&IDt|7s}4c}w>-DEw7rA8Nnb%`3E90qxa6(#qWb zuD{>$`n1Ed#2?f^{dV1OFbXoPEg&+GDFWZN>bn~E?L&sDUF=KSrI5T=DSEJsO6%{P z3x{jP>@Y+08c8!t29pSTk%4vRXNry5 zDT2C#cV>Y~0gVGBBtk42pIxgMrjw=6bKOP_9+3_9k)CG^dBg#YPQ6svq4dC5ODM!v zPMcmk+$}rO3Og9)ssk0J!PkHksSFc#szlZDiuv}(k0mT*$M98s5pXN`tka+F6+=m6 zkf0rLwA3DIi*)2|QmZ9C8i`g7E_M{@{X>Y znIgXxLE-y8#wl=g>wP52tWi2MdpRQdifad`b6^acYJP79k?JIo%_Ok`zRulNv3slk zwLfY!9F^k`tw;;W;{!`=L&F8Y8NPsqh8Y7yTBbBwx7PG)nJV_A|7fb z%tdcAMq|j(i%0d`>_Z#^lkdiGZmtHYE3q$$NXHp95us*h3)7?}`YHFuv&N=Pkr)$6 zltc=~^XDiH4N>wXA^H+|XMHNqFPfbi@+%x|P_QW71kUQ__kucCZ^2n(chj;hk0DH1?N)Ppkori z(ovj03yKJtaMRfADh!yS(YM-)yZ8ER4pl2RG(}(POEm+9KR38zv>vv2FZ#zEFf$NK ze@TU5Mtvn~^eG+8NS!y6NW2nB5gnZ+=EEV_;;MpG-35Cj7((}nNC_0c-v%ll zD#HK^yi~hnpaU&4)v%AnyY=Bp!#=#+j%XK6{3wq8&0pFa;mMTjv%L5Pi;;yp(gWrY z%C`P&`;C0<96ex{HsL4PVs+>J1d!z%gTpzzI>um;@fI*gi_Tf;4HL0vT3sAo*Q2js zu-ta&;kM z9hK)TnI~df83A=)N~vH6_1&(e5TIj;Yy(BgUqGSo=7G+MQ)YQ8MFGXm#_}EiUXDM| zQRC$uD-~0J-QOOLi&N_Kl<$-mY%Ki;iG(5rmB=p9i6J+vY^4UEvw)Zo?+LB**D7&$ zh4^}y(>dxEwc#pSO5VwKbcmU!a98xI}UFt^;eb=H$K-5^EZ{=fi5!;ROG8);Id zpOZGy<0-{!HZqjRtX|n;$2YRTo7one@^qW;=@P6TSm#=7ZcjDm`)@X(eq2M)!{vgI z%+2Bnl6S1Az-tH^jCm1hTt@e(xNtoTwo;+F^$N!rl|5e-zmbF&o2};j<WH_E=q}iin@uvPb$=uzIQRl}PT=Z7j%EYV3i43`gnLFR&0sFeqE7h)@ zc_FZ^O7hgn&f==k52+{dRy#`;PdGE_o9;is&Lb)@YiqkZ=z`s?uHEg4-JR9l-ILut z@ZLV%-odTCL#e%=ntMkUd&kauC;oeOhI z@8j`!iJtd2?VC1f?>AcQH@JG0r-kAF8w9<>Mm+|OC7UFr7$SwWkWvoq|2qV|7r9j? z6aHw5bjmuf%nE6JJJM^4sfjI(ZY|#R4P674z zHBcAJ>gBV$&JeKWz?}%6iW2`W?wWt)#)ExreK>4aS8G>$ zV>kB8->vazdHUb2@t1+&s=lG}o`Fx@{l#5~_ zS6g=-8fTRiC;Zc5MwK^2l>WsrzbyXpu`vIy*7)zxI4kqb+y54sQ&Li%7gh%qRQlyt zUUSTz*&p5CmAYhz`%9yw%Q2__qs1ONqBz;onsi6ts9eN z8jt?FFTUoOH6kpwA#N~W1+uk=6|%t|8SY*{>x>)E&V@3lzFe>>#dT%P-X*kGLKiLNYZno-VB}31p{woo^HYsF43}D6@ICXqo$*oH)gGXx#o6%IslOMzmu5lv_W;8bSY^gw(Wrw#uTdt!J+9 zOWF69Py*5$KEs5q3~e(9zs<@=rZkA}`cdoGRj%}|FcFtYQN`9rh9I&-@nisTZQ~yJuO=ovNG6R~A;PB2LJtr{EXwSE~ltA#blSSDLxU zOuNkwHZ=s~Xwnv3Sp=dajTRt&H~WD^FV#Wl63OhSS7WOQVGk6kUaqfxMmnMilkVb+ z_#W^Nl$rQ^(kPIGF90L2WgrDJe)_v3O6@C+Q!g`$n=nV@2FVeb>iUS;0_moCK1;Yr z7cZwhl_t%78Emx}Iy76b1I>?Rw;Ya@5#^49D9nGR(_kPWoPA7b?J_KT!_UkJgv%rO}|fQ5rtFVmLd3gp(~1O8I(NCT_HjA~%UVuMpm(qzx-?K90#3p}Rd! z{tln4ezRuQzac}bmIFDda;C5edoK=o4)Y+;i8d-0?_|@hCH1?lAG4`q39F&u*26T^ zD0K>{{t0@t-#YJnfq4b(2{VdStrjbNhOhW>M-?V~Z9Y4}!!lKd!#rU38MRVG8wnAr z!?gsNn_m&Y0cyWr!n2`5wLS>xV|bW~ufzJ4M7=_UPR*>+zO;^A@)4E!JTwzN+*Ht zDzFOvjNZ&^3Q2#>DYpgs8%0a*#F=6V-oS(=fDu0E4~m_G>6e5%(9LFPT9Oix!;rC} zl?pCjK^6KNyBAw2b;K8N)Z(U;%0O7(ULj@9frra;S883gK)3epTuJA~DmXXTR?Z+P zR~EKP^;m9r;B{<3h>B4A?(b8FH-d3CfwE61HzcRu@EdAJRxPU!HRR{2KS_8x84vv} z2z{xXuQM$3=t7$Y>O=pyT#N036ZIC`jRp5cc#}PAT_ZVEi1tFW!Ag2o;T-aqSs`by zUkmW`RQWgM>kh0AH&l6DV84la5hB-A>Xez}yKM9``SWi|LbVuj);yNEaMbygwiyQT z#@_XGD$}5`fNWDT?+Gy?&Qw(XElB-A1vtZ!F z$>zO}F$zrVR#I<6PY806?3Ccl12wv2{Gt8fk{C;H$V<2Wy^ z-GXKm1krl#;b%(>4jh#^&ff!$6^?bni%f&`~ZM zS&_Du?r2i_Q68^Bk*;O$=&Smpd=Ye!KK)U?Kh&7lh)}1RD=fow@Q9~ChEu86p*sph z&11e@h*8JmXA)W_(pAtgR1~X1m`Sqh{C2y8gR@&pI8v5kq9&_IXr#`K_)JT2(Pz?W zA@KMZCt6+TlxS-QI~BLqiq3u7pm=thCq~a{yZDxK^6oA!sY7)hsgUQq_1X7kkGy>F zy2@B5q7h3oBilV@GcncOHO^*jkSk)fq$i3V@&O>>GjusONY0PgZ*c6Wr2C@0uY7fw zGkORb%TI^+NH}lh`{-?qVlX`-+!{sfB=S|SV4dXZiWr%0yd}+8=e|(;6pjIk{DNGz0Vvl>d?4X^Kjl|HCiBK>)eM%;zvdOida!93( z^z3^M`^~g$y2AVF=!KdJ=9*#@V+AtT+Y93J4B2k+2`Ud{lO0m!G4qYm`qYZnBE|%7 zS&0um%4~$aTzuHuKaGZnxz^D{(BTMjVv+BnZ0K$*7u2bVw9_1_)<5*TV)HWxZmz;z z8Vn%paXDsv$dT3OBU@RwtSUqbIAMQi#{+23O>G`p+RU$NF*x%Q-)D$orlnf#TNHyL zD1L~D^K^8^(rO}H5%;4#P7(mal0rLi36F|STRW-s1X6wb$7jS(xslqtCgJ&-#Ovy~ zoTC}2&qjok4a46Kel!#k!43@ z;ChK2wO9iR1c}WlLbdoE!;Q3&oF%h*%%5isdDP`&8HPYvcU?DhJL;zl^j{Jtq0|B` zmlp-=)GxymPQuJfws*@4czsc}xe0vP?@(SH?=TV&tL3Gz_$O>%mqUW`H9pe;PR?Y^ zhTwaCXK8T?Ng>RSao$OKJUDh+Q*z{u%l?uP@Csa1F065ZCUsJdF+3(A=as5|9JQEg zztQQ->JzRU7i|+OPV(m!k#x>H8!3`^p1Y@$j#LjRN-2+^$UALMv7WaWYg?&ykn(4^ zJI#l$hb~wD&nRzX(HE|;itHQ9URKBhZj2eVI|GV!C9<`~MLZGJCPK!nNy=;i3t_<97)e#RlFYMA(O!Fj_JF&Iz^FI4Y?>ghOjn@k*&d0boejW@*3Jfe>t{D^~uf`5TXW_h7m z`xGbaq+22hHEHqD#%402@yjUVRbE)Y3MEJaw(Ag6mKa0WN^}e(9g^|r@&>N5)l<&` z4Dm2{ZpH-9qNP+~`eew_GBEW8@);34%4lZlbBa};ME_Tbp|y$l)-WD`oLYq3?qs1$zvlRq&#%cBB2GLt7_H`*9jxQWPxx5Vn{Isb+(v z?$cD)y){nEFmKH;UCe0YW5AS?pRtkO{6IX0CD%g%7rfBhUL-phiuEg4{LLKvCz`O9 z=wQ461_E!QlQz;Sx3`DW85SdN9a=3s$LXrdiKlQBIU)(1aPlQ=R?I#i?(j}F_1%Eh zV@(HWl}nbBcbKp=OgKB?6PyCZ274b$t}2@{2cZINU?d-(E5g9Hn7}(mm}zkcg$>Lp zl;s|WM;n~)|; zAsZiYjpjlge1w$_-^R5{5=xODwlbI=lkF!3iYM}Edg~5pgD=aaFAgxS*}xH;6iLG3 zVGd(8qKFYm`4MUrE>%QZo4@#hSilB`9WEkrkhS^BKLe-v1&f#UL)`R6m25uwI2EOw ztq;SZFA@cGye)=BrQ5Re`cs);BBcZ>H*M-8*Xaof67jOEVb}_wX_S9Vgb~#$gGx00 zaFq5*43_Nh0T_w8ZA89okN-jjexkzgLoM;;A;B@0EC>#ESRgl;DXUT|X)`MNwnmD- zm@i-vw>+IfSW(8HQc8^H8LmRD98}H zpI$6~;&3n7)`H;U0nVBck?h?4`DJvf9|;fzF0Zo4a+2E?l&OMXl=guHzIkKWb}{=D z>h>^2ei#}{!BWp|kPd2;@B*J#p5b}i$_SyRW{9Rd8-%T5Sp2gx2eSWB;dozy; z)vsZ4>R!Q}w;|V&cj39UsaJFPgK!y!mp*K;G;EW}L71ra%l&g}n)SxlDIiM_b}p(2 zn5BVW5s<)EG7SPtb$oFUQ5%+kw7-?II?Q63P}r#LmVhyoSB;eo@2tD1&7N2=xILK< z`ffwt+pGNq`K1k1(C*Z(6nuv(mb9aa1mB@mW46OkAlY-jgZZ)<-xzChX{ap#4h{`ewA1w-^gRbp?7>t9qW4>%EQp za@gCme$=dIiFYM|M=y5MbDeyzJ;;& zwuQd-jyG*EppDs3>yj>|k)r~MmH;YYc9rOYXEp-gGGSh9(w)cGOf8{WAAz--o9OuMd z2KVSs$-(K_4$r2v#|hBqZV$f^?S_>asOxt=IOw0v!Tq@GW>hqI(?94y+2W-DtMp)G z6@)tJ_j86A5dNlRz8Yx3&*?%Kj}mzgi)I=h3c$`wdQubnBo#->XTP#lm!x=i0hB%3 zXk&d_f;5$ON83)ji?Ios0UP$dAB`;c?!i`mja%*L&kBs%;Pv4eS#+;)V8w}!qfrNy zE^`BzGZ}-)&cxL6*j_&^!(*63+~jSdJ{dB)07cku{^1lAC`mR^bn0T?^?z*nxT!(3 zk&Phq(;U6^RY^A_@!Pb4p0Xf)GxJzjjtjxT)KaP5HuK!w#OYK6Mgy2s znv+%%Hzayn5&f1@r3~sYLzR-0shry||uB(wAZrG?lU>9C`*=uCF>Y5AUr63eh}gU9%e@d0D`C zqZCGch3iamI3_MJogr#mb=g1V;O3{T0`Qg-Vx29E@+Cg?o47 z4Od6*eOjUyu#|X42lQs<@;4iYC5nn~4-=P&bG9ml)Rg0O^XIp!QZ~$6*TD{3FAloe z4E5gh&zQ81>yb0G{Gs>W$MwzA|G7u2J^=e++x&cSFePVp(r^U7V!{m3Kk*L6Gf3}c zu;6%r%U0TT@}3N^rEP|Og&g#TP%c3hdn5$+L_4;KRi;B7wj%^!m-lFIkncZ7Y+D%b zK`F-uUoifDyK9Nqf>O|_{Gm5}!dR%ge$EezicN<3L)+G`W-9vy%|#R=n?{JPiqfBUiRlMr}x|ua|*ON&Lp+XL^gEp4TYTx_j!x55i6dXwx?LTZL&q3ek43P_hWqy(FW|zM@ty8QZ)2yYGrR=t__l z>j@L~q~r3W(^lT}Y5Hx~*F0t9}Pp?!jsBGS#bEI!?9dO`Fp$$bhX+9PCp;WZ9_ON%CHSfPBQ`q|~5p)tYM z36XyJAY6~q*ik_f#?xJaU{Q`_wmw|`EWxMDEKzQxu1vsfo?=rj(p3{n_NOVs=Gc9r zR9O02xH`UqBieS=kx!EyXY>en>^sEw%T??Ey_(ES+jF1Q0TuEDnV|Cd{Bmxo0@u$q z9x;(%eAU`lMIx$TQ5mhQ`@b(Tnrc+DtnOQ_P7CwLvl@8qb|$rzu$Jt637>Z?gA-7w z8|CEBgnpEZA?z1ci8Lw(ULybjl+pz_Mvp;-i%?XZGIeX9rBt98B|lLf&MV^(!-?W{ zASBem&LHttm1(t>E3|GNUz8O8yrpVfHj5M`d*6w9>MFpbAr7fAkJmrc;xFqMEvD${ zOUf1Gd;>I>@N(_;2@R=>8@zi$y{egG|Lq{B^E#{M41fQ{i3Nd%e zd(Nwe%p?j9`x&^VCIK37dz9{T-tY)HC$aZeFmqRdT*BolBV#RE^U)mLDsc`*^ZG|E zu~ue>$D2@-?h$fSsJ7YsUEz0JeAB)`Gh@Hb%oak8Q&=DmVZn&yn=sc;Y{N&QjqKq&pwLb+|n6elAE{cY7Svm_huA>}VP&7Ae0 zPjUyFHitTCh{ddP8YtY)*b$U%x}M1U#EJoP4_HvH?=F@YbE}%DnBNQXOB=5$IDA6w zAul)^PWSvjyilj6i;j4UAct%Tu7$|mtNS5t1D%doUy^x$eKS+g8}_HKF6ewR)-l@) z$*z`W;e^*$xqo__(b|@)E>B!|ZGB@TcdET_s#!ctLzF`}&3v40)6!*U6)s0H7@ILgacF*G z)=O>!OYp1TT%%mC zgSBr`95%(l-4piId5u@?F$!Kz%+6=pRTI&#JJSw%MBl{T0xw1817jRfDqSj!KfXlv z3vtTpx$1s4Ava~{pt%+TPJNTwGq91_j1H!}PdP?O-ymTk9i$=gMJDer2&vl62vw4T z%wpqmX$jr5OxQnb_oh)lvzdOVdIU+lf|VEA&Gnd)a!kbLVc5n{adAG;i6!ZILMnwS zuuJ=#`}&ju)N|1~t@V~~1XLMbj05V#jwId;Txo5!ZM4m81X;5&iC4r90$O2CP*o|e zO1MgqiqKn(@4@(I|7Qr1{u#I(`4@ZJm$=@_hdAdq*7E$~uf@G;RC!!zJ zk78^OZ8~U%{CKUW*~jA-sySooZ=dVdCEx9w6nams3+ik59uxeYMIb^wlz`dPf$Kdt zw|l0((L*Y!rX(#$FzQOqM6Ul}vJGw>CBjOQ4boceA; ze6*(|oSQ=#Un382QRZ&W(YPA6zcPNB9SY1P0ju|`pO?dWn5X(P{1StZIFAxa2C`Jn zC{a86#&wKakdq@M!bdej0YgWx&iW@*vm^(P>ZO9*AT)(f#V3SLd1(bLrgO{gXdR|8 zEy)>W%p%1NCzdOj;n)wYE^&MONJhN8t_|~Hp!~=E=&GNh6CS8w)U!lE#=G6auZ~NU zO&)0rV{Ru05~zHsx|%fD(e4w55{yJXCHC>EjI+6w zUGUaU>F^b^ymK1)$f;Is$ZTkL(9DkW0$-PRy!WuTr(&v3=gZN>SfgFBODP~sjl=cO z-*%4G;k2~Kl01?kk2nY~z#XGD8Z-4;_|zBYc<9mf@gA5XZ7c`1(u{c$=;0XGWAK##KF>Ez3pwpyK=EcX{(% z`Om%8Ebh>~DSrIh?}L(Bb0XTqD)+_+OeVsp<=1l{{WE~$B*AYLip;L^$ZN)O_v+2KsQq4=TjXfLHzwYr?C1hHCR<82)6 zqa@lm)T3emwybh*U*%>nN*t>awVq&SivA-ajpD88TNjPw6&+?k_1?bCk_WI7w%!~g zLc!YDodBm~$nvjfih4je4=P}ax~_QrIK;0M)54{E+oglsmA#6*&)}YCt#_=D3S;ex z%k6^8Z4u?Is2{K%45fEW+`b+#wV)V>D|r-FY4!+Z{af<*;(_J&(xyG}tYIE@WCmUto?(bXP1x`i9<@ zh{7%e4h#xL+0AN7vV+Hg3PGK$g!L{>A41i3l$(0@Be<4Fe^=!rElF>U@xoL%fI|&; zyW+s^CCx`)yTVf-jN2pzxu`2|eKZf0>H!jm9M*E-MLluVwhP9gp%68_b_@d<8j12E zjEnw=uBLiZ{#DD97v+fp{GqtoZ@`6DivU4Ybb0<5wlRWNHF;QZIbGAWya!Pm=~&y7 z2*nkg1CA2frGcdDoVpXn=$SLca3i^7D=24Ud0rJbtQPz;9LVtKE7CqlR{~|lujf!384;`-s-SIi2@sg2FX*8VRlv)Jg6ApMnsxsme|K}7 zWGhrZ+Nkew-1~_K^`%~Y%Ec%MGHwG^mfHbzEf+7wN=6X&KRWBHLiYOm>Q4exLuM%F zV5m4(Pw;Zz6#^sqA$TA^#h`5#m+ShaeOnCnx(C^z0?2B~MFOdC;+grs9!0Nf8+%nxWRN1v&E(h(dr=rGn#1^5r9j3EMzN@1ZTL?9WIqyfWdgq78JZC?&8SZQgxK@t_z z1ZFb2i=4U}$v_&t98)Vf!-cB01I^ZFkd-)nMQ2->%iWDR9wg(Pb$@ts(%u#%gRpu8 zCIF0>oX8r~frRnsbiWV%CjI??l4oaQxgU#g0 zBt?jQdnO2o9~%np+z%_XrCrngro}OfE2zV?MWmyY+_f#v3M6Yx|GE+G zW=|Z<8}$ym5bO1|ywcS+51&pSuEy%+s0?n!_S5T8Xi}(Z?AmAK<#J5 z{11}*bl?MfL!=Q+b}wKzA9L-e4Ie>ttXA&3KU91Iv>G7h&oYgvatg$9=mGPLYLJ|1bq%0@69w`IbjlhQI5@lo7?=o4J zg)*6S#j=+6KD$(tBMSBN2MVi~nVp#_Do{kNu`>~-J@$2BQ0-Sw+;F}q-Ffx%RJV`< zRHNYA)!~V-^7U9}Hv-=9LVuw39{w9TF0KkdZZ-P0ADTrB_4A%e*8GF;z_mvUw#Bzl z>L<;Jh31WWViZZx@%I4l5Q!L|6EVe}|zhzg4OL4qdvqb#A&LJQl7Y&_*bhiVJdOckj*7plWQ zen9o{2WPkN7eG!k*t*93O7h*+oA@~Gdla7v?Yb$ze&e`cjeSP&^BPEVb{NfScz$ca+ z;YMWV6eG?RY+WPf$CPwQu3{q5G~f#y@xlvkEf3TGC2#q_{4f0OAZFdpoEOsfey z*o^&+pWFmSc0T3Goo|?WI_bJOZw9)vPN>rT^r#Te^ZJdn5djkb60wM9PU=RQha0XF zdej;(-QRzhv7h0EFaY@(f{qQe!;cr@j~-gk+xr>9{LB^S&pv&hnvXGa@iVgXGxXBE z%tYtVfJM8 zJ#Gh}1O`c&a3}u6exB?-Lkx5J+73{yLmXz6FO ztb1TBz^{y>+EdHs!UQBfFt65lS{YU{#gt(DCtoP#5+~{4qW94?I z@Yj<^TP_y9Sr{3n$Gety`@5MAq_1kd&ssKq-j2EW`F*s6nvbK`L zXk5x|%StY7lnMHkn9FF1+s|8r8FB%K{n~B|nGr2PRM(I-?`WRxYq7_hM;mZB0jHn> z`1tljiOmz0^W%6-mO#N1#B4c z)d$Hg*bp`gNiY6n`%H8>o{L_WX`M%GwLe|@>0q(U^^I-YysyyX3yIA!t$dQ)nElet zsY;ixpYA1AiB#4E{M_C7C9T?yjiMHQqEPl4Q5!GrxqJD{#F1nR+DQ0Y?qqw$jgCpi zRsL-MNB2#$xGA;*#8}T~&%Jq>tzPi6rZUefrJW`qadB_&s>S#&z)2BG#1xoqe=APh z-c*hKj15U?C_xr3|41RF-4O2=M>0iXyyb2e9aqq8=;VK_-wb>~5{_3~ z(OW+k@p&eQ-&+M<&-$t9!u^{d&mTE~icY5I0+l_t8w5TN$o&$i8qt*(tRA;{E?6_| z-XQp8F6ftF?P83)P~A%UbD{c;j}1Z%JN3VW8V`Eqg`19No(nghZ#D?G{J!`ljKw2W z5NRd45iHUM;SZ*aha}gD)VgqSi<;2fcqn>@Os!G0o8|eXD2_c=L9BLue(XWLus z+AGGrtQt2ZBc<9Jhm%<~`SXco)$fFC$>@@g4f1G4qs@l3xJ|}j+i~9hWu81cHE!lN z@(sQPE-`)K`>`KlHmNbE2pdz6;0!E7-ngGKuUHg9!&tzuLcaWrK2Ksrv$}22WY+e@ zm~3WQx|GT`p`qD|T(x73$y~>%DTPn(v?1TeGMnRBjZQe2k$`q6d5kDzz;v$-Ir5yT zxvwE!1g?cMSQ>rQqIf#@{7Ug`F;-dWeC6#+rHhT?7NuW14OdE+Bs{FjSHBhCc(q(Krfexv`sUt))+zX#!+(@rFDilU<=XDApH!ce2i>!{Q&D?2J5t_ zGA&~W`P3%&z2lcfm#M{%-g2qENn{b~AdG==-!?7kecLYzB?X@0v9xx)2?hP1$02*a z&klZ{?O&el|316^zI%1L`TJz&*XjPR)4gA(yT49$&QJC(kJf(uTsuGd-;P86w&+jy z7XG;m`SG92kcGdOAqSh+n~?urhU~4)?W|6pEDimI(l1S)E_VL=IAn2cd13kcx8=p@ z9}DXXe=kEuu9qR>3-kY+g$&Kj49rapjm^yr&CU*do9UgN{+C5RF**2sqJ4g>ZGNnE zdc6Oi7XANe9D*AeY#tq3$CdqS9P%%V{(2mO!`5P(YnvNuri)|#9*5NQ4_Ef}{D(!~ zR8`d8{ht>7=bEars>;%TSoC$DN{e3A)FgkwUhhNVDw|@;>m$qR!%OQBCAGzWLG-yF z^0NO@=>KyZ^77-CkiyT;K2-VVfA-D&zxea7l9QW5E#u=8Vq)X|9*0CmAg{+Ej>);! z$@vzEx&K;;1O>nR*FMDC=jp%jdDDd4zsDhZF8=WFOc% zUhhNFg+=}zhnU(rm|NSMS^d2Xx%cnO5Lwf^O6rF4DtfZYIx685Yc~I zh6qS&2ui>O#FcN0DqchMe~m+g)v_6JNTCkW7GfN^C z`g{LNp(pytZ53u8SD$tGo^nF4Y_T0h&3_-7w9?ApLDV+&p!}XKYRxyDQ>KqC%bGEw z?w3qpw!Bvk$E$IE;}v)|lt7Dy!$VxrD+<>3|1o#pPfhiWzW1p~2q`Nhp-D+7(vjYz zCG_4A5fKoPE~qF9Dxrp+(4$>i<&pzkg&ole^ z>6||xnapHn&8)S)ug@D$+PpFsQ4`abjIuTIWws{2MV9`Mh!MnN^@xobX z69W)Q)Kr2YJpf6dWeJ%igLgda;uq~am#K!cQTi94cglcN`3_5Nf*bzh$X%?MfE6o@ z+WCpN1s9sX&Uju0723IB$8ZO%8f%-$(44iLdwtR?^$Idbq(tWU^poWc>@A0n#2T^v zPXs>UNM}7yggB79KkfOz%5v80%frmcAWw_Wxelv@JdMaQBiW6g`Gm^z(;u|cl}cQ6 z?(osvKbaMJc&}GCskyIIvMlyeBrRtgEQ=snwo|F=hk203A0$EQ$T50bjx##m`5P)_NA#7N4e{6;X%5NtH&tXpNe z#Z4=hm6q#t?;f#^-YkA{*0NHnLv^(TH)LulX_4f+Kl-KB(d&icr`Oj^v8N&*wlJwe zyKGD4mcg%|5YprlRy!xw@`ZDR{Aa-3l7kI~jho-?;jBz=yd{ygoFg)iHm&0XnrVZU z)9TUt?262nTP>$9jkyOKaUhvWbamULel9yb+yG!|@!+u_(Q)@{XI5nHj7+GjI!t^< zcANcNtGe=ST-$Toajc8s?0fWQshK}06%n?Qkm~C9d;2ELtU?O9F}=h);Oq2NkCyMGj>*Cv!3mQfL%|w-o7t z@1Sogtb3!Z1$5xmXQ=A9e^%&&Rh02bBp{)H33b5#OWi-5bFcvP?nX!WgkJ;>RtTX^ z5W>m+$1C)O&~e6+Am59D5($N{%Z6Rtv;SAD&_7YpI4m$nK-gLq*Hg~zI068#F4R*4_$Icgx7wu9 zgG(+u5^-W5JP{dUhMGJQy)FwK0+Bpqe5X(^o^PTpDwGYr&=jLjM;3LZEc3j*ZLXR= zqwacSEuJKA7{u_5Mv)CO<;(BT=L_w5i-NzwSU86V2wu9aSy(aI@Qv6x^ z9PEh$A~(+JYq;BRI<29un8r57vP7ga)~)LH2qmbmn)5NAHIri|W@*sJ--7yi=}x*Q z6+@XS%Eb-M@!@t)vKw%T@`W-1S#RWTpVC_KG{5nju_=7Ntnm8==dMc%msL|S(}Mhp z_Osjku1=!9{b-*n0&J&92gZ0}Qq<<3c^xT&W+U=_w`)pE}jv%@LE(&f9 zWsKBq+eO*=2wg+LKrBQ*3bh;=_J)VwY+QRjmF!T&%pQ7sM|WOFp;^PzYASY;ppQ1s z&1Rwv;oBaiMOk?yXecH+>;Rc?;?xtvbbOTRE-^_xUNm_;SV5kA#g`qb7_ywl!Y)r# zXBr~)zskbZ)vKOme9+;!%(H#Ty+qh-jmzU{|3mX2xXoThTgBm9c}X4RTH_S2&cn&3 z;f9)N`VP3;X7W}NQAhnVXmZI2PsXTOC-;Da_;pDt3uc5wm1zswZr z>PLTaVF_oU4Xzp4Nyu>$!PCI1@cMXy#=GQv$+aaB0;trd?&Y1FVt2 z$SW`sH}UBGwaWPB6L0&?pUo=-kqQ_$0uNuaGj&FUDiAkiFTa?hpW(o<%nAi4lNY}y zP+r_~!aZ~WPekDn2c%{Nuy@C~-uI~uXYOp1j@Ah{OX{omCR`zV^ip9B^m-%@&xQ&_ z($e~S&?{k#XF;^48vk*K@=vliVXGWWyiE$eXwj{eL9{7&M>%ZI8z}a1W@Kkq0_7d zha6i5?MOx|=xrBJA`bbuoy2PxaoROP+0&p@?~YVQgsL1M$QB9SN51Js9J(M91MV$| zM2U)o+cia_%Ai6N@9o!$=;^>!o?_am`c2?Xk6|8^NjBd{=&m`e0Pm+Az;y4M-3Oa)MO zH)43-6_`JD@j(YBeJM}kDL~%)97_u$VKS5Wrx<9pJey&stwvJvGU;gBEYvf|P8uC` zBj9*^AA$!nzo#HS2SDg=#S4;s(-xUCMS);#?@-){N5{c$g;Q=Mkj*n5n^fMn6maN* zD+nLYOrMf^pH4Ol#3-BWk(I(gPmczeo)#d4w*&VB@Oy?(`Jc#*+Voo#I*Tlj2LL@> zNM&iKUw1+18Y0$l6f8Nu?-{sT1_;9e_kma@S(y@fF{>94Gcn+qjtVku zUS}GrvViDejrvyH%=8XqYJ~`Z3joxDff%~5`I$V6o7s<=v)5>b@dN-AvJGEbVC0X1 z&_*CqmY_A6geIfZQsAn10rX2Pk`9982eU3|1507KOpko^w1E+d_v=@Qo!cB4dmIik zY)>-jqyP}60z%U+#Hi7`|3un^XDo50;J^&)bT5%a* zAXhrp@7sa1fYL0kpr6Ih_=^v{7;MZ7K#Ifg0hh5>Qeq+*7?l*^vvwj}SAYKqo-2S$ zJ20H1FvzqQN*yBSb^>|Yk%`;EO0y4WssO!r+EfpvWKullzFlf~)(s`a6GXJ>Vd3mH z{6t+&(@Z#vCBxPTbnd|RGadc;!-w|{k@4GsLdRxFIh!uN9r@NZSN(R{kjGzV=N~=; zYZGik-T3WPZLdAQ)Ts^EUIYhuu(@Sj?VN^o2Pfbfk+s`_g)Yz#7f=iiu@B^2+=h5k zz>k55xr0Dw?yDauh+J;O=k4-Hugs9J%=8MsWHAq7Emhp=96=2bAB9KY*>Q%*9}DTI zz$E_cq#DsUesS2-Y`R+`@NHaL?e=y4*UXES$Zxgq8QF4a?yGNaBiFVeh1=!sU*LZs zBg?e+)5Rk<7+?3eWH7{z9A~V1gdI?vEOA1>fNy$xTKBUMwG1(?7rw`=A!^!Mg+trA z@mj{L?{&(fq+pD-GJ|6n!`w>zK23oUDim~@!VC@bQ^f&GqGw(D)MRs*MSeYbsmx&f zqF!);!HB|aF>-bOJ7Y>veWiQ=!)4~vxCX<@F#L9d%LxWP8G8B=zl`H+$81BiXiTRi zL|zE&9j_Nun1X~Gq40HNAsjcF3S{)~~nk$gh$ zwggN|jYv2VlYBxiOB8lZLMJPr*>d?=XZtgO`j~tZJ+FZ#fqhmU3D|(;bLHOJnismZ zIYfUP(8k%Edg6u16quoorL(=s?9mHjOug0#VgwHG6$esqEyfe941rC!SEYjInmXGX z2jg`oCF*e3kAF|&(~wpp+N&lnR$?<xy}0A}wtT};a$3%iy~Qdz5kz6EMWI+F9)apQ)Z%Fbxn>h8Hl2KpCzxjMcQ&oAt>ooeB1!vO{|-D>WQ zowaq&f$dEA?qK>C>2n`^V{rvZ&nju?}kKkH3?xjH(&ST~+5Aqk)$ zhhxI0l`-&DNR@#cO&w76?F~k?xTyoaAuX}$h7~@XB_@3+Nf@0|->tNsc-gE@nYMQ( zjrqPh2p;UjddI7deozO9feI}P)$!%Qrp@;;Q~R$k=7Iy8?x+ull|1S!cx{It%<%yl zV1qGC?P0#yb55Pi)aKW@9N;*BqiRq*t*yj|U09<17PWg?U8n3cM@LS}4Lmc$&LA_Y z-h*ctFI1PrgN>;iW~2wVn)G`60{1tD#oRmXs9gcDq0a4rYxF(yIY8gwo8z>>0u0;4 z)2*Guk>)$hh#&l3HR2Q5+tpE;Z3?)-dN}j+pGd;iPXp!&9G!zNK%_Q&BJnv4%VG*J znQ>5Qb5B6@y~uZC==xqet04%fE5_9^TOv!Xm7wl~?Pl#~lzlmrz%d1WqgPG%cn-^4 z1qg+5jEpcsWyh_mwcj~mPb2`YzlR_@W9NTMaa^r~)A!yo#QL7@Wu}f?T^wMg!Y*sb zh3(oS>za#rutlc*OsaU}CiPz1ra1G!_B1c-w(2y7q{%#ul zl-w2AcixG^cXoogV?5hWroy(wI1*UL zZs4bE{N`A$k6G4DL#?`Rp~jha-ge%R*q0H$Ert5if*DK%TzL8tNaI6^+Ja`-PMYsH zgfRW8V`|P!JB#(bdB@x65Kbz5pmXHiCti&~U+kt6;OWGXoCw_H`M^*zgc5qsIy!r_ zsWb&2XS4d?EISOVn`0bSy8^?qv3`K;3_g(J_;ZKj)%=2o)mwA=KA7y7@NcZ?9gbC= z=iJg9$MG=pz_+ZZ`K$OruJ`e8USMlNKl(8)!8*oXwgNNjua(SI!A>8cR>L=`GYO}M zwDR@n&hto`V~z8cojL~k{n$(3>{Ek)nK?EV{>hOKEAG#8L3&cx42y?NJ2?+BP`ga& z7kaFgAc50Xgu#qED|YxEsTNF_>1aIRJuCHtrE53F^s_zvbKYu<>L!pyJC9Aj!@*Vc zK0N7j|2jq+jymUzC;`m<^-+hM*lIDQAfB)oT~zRb?o_Rq(p{svlRimk898mTHnB2$4SGSI6kab2#cWk zhE>OcVaE!q)t7UD8$}7rrdCfP=z8}|HnRk_kkr+4)Gt(NSWzD4L?ug=BzW3<%P4T; zG-|e|ZW*9{GP7EIV*b^5XI;IcA72AZzQ?Y-2cT`3Rm8S2e$i}n`-as!R@tv+g-wvH zZH?pl#TM3X7(2#;TB|{O4Gbil-sMh4?^R>iE&!=*i`T5WwP*#eF&mp=Z_sJJ-3F*d zl(AD+^&=)WS%xa)q-%nv(cUtZqY;^4PxPAr-zoJIp0UL8@(*EI4cUZwA z4!@r>i7n`zDQDU5NY?|b>l-)N4yxlT!{|~#-dZ`0O-W)~#q}GCG;f$Nqteloz{`f2 z-{F^n#pV2XfkX*zzBky}V52{XC#@p`J4SrILTRKIVEj?%!ub26BVp7ojD`xj!kG_8 z-E-3=LmnBekSw8}Nh(~RQ& z*9!d*`7%zps#5@3X}7CCl>}wEt1D{CX7Ds!GKsfu9q)9}gVpWO$o_bR{?6||%sjzD zdal{uYv5vMGBF+SK=}SHYPj8uKT9bTZ9S~r#d(LIDN%Lx;@Cs82l{zxLGG==IuSgr zXBBDlNd{UzxstF<9UaE>q@&H+)y_IaJAQ-wzi@~kvz)&MqPdmEDT zPYVEpO|cc ziY&#a$~U%~Wt6><#T=&uU^?m34rJK~NW_@Q>94O+yVzTwuPLeOr2y>=Kk9oG`Dpwp zPfwTE4nDOq;J-91DRE!IDpS#j^^_3*gQpN<{?E_jWDE_28z$Pb>y6t}?vB^#pm_VG zMq>OKSZe5HZ&ww5c2{UPbK#z!ahYUUf1)L|>bks4b>#8kdo`)Ggfj^}bL83hX!&^j zj63tQb5~yeHhk$(=AB-~0{-~@@o)zGk+qs+${WX+PKGZw37GLdfmVI`XVgr#a|( z30BGp(#EYgd#3mjJ%`uXwk402!1&dykb?Z*o|w8&BWuOlVt;I`qB$W%yt-Deb2M<= z;vR%2G3r=v_?M$#ot+O3`@0(KX3;wda@E|$X=c_{z7sK5T6|nxxJ2W|h)K}?_j+zB zwZ<%bVpANKUvdat%j5CV6N?3FZQY2pa;_bfPOMl?+4v~az3Mr5LQweh6Uw^|QC6*c zzkd{s`jvn8hz&Wiev#EuA^2gOTw?lBuyFGY>3tkY#|4*(Ilm<)#%*r|Ik->z46zi} z3Ik?kQcfmaFV#fq7XB$GsYka<%XkrR=HkNQscBoM=1pSD$)FTMP~;`?Th7oZ2XRfA z5^{LmSag0-8)9)pNJSlQVD6soBzuK?M#zqjvq&#(f5VLNXQ9o)ZdK|=-(71lP_+`N zKxt(Cni#48t3~Wdoc0mA*y+Y+a0wB!Z6(B?(`Us5PKTH32HNg~)1MG9NCO1!T68!Y z*ryRR?8i(V0Q#b^a3j;Al2nOBCmTns&hqpq{`sB>qm*1O?k>~WjL3&m0?HI`!^;X2 zr(?y>UyU%u7N69kdv!5bR_#moSf<#7yHO;C3gNrVDNlfjoek%_h@s(CYdVB&eFIGW z*&i`eO#0+hQy|i}-Bm8)-i#KFMJ(7uerHiPLhZ^=G_D$q}cE0-;kN=33d4|EN+cF5FFQ4w@4fVHsy~k5lemGFmL=ZZCIdHY2=X?kZXNCGHbj+9=4`+DWI>NS z#DnqL+l=<{Sczk2kpdEsFjKs*aky^4-~;&i>YVr!=I8sHlya}7_({5yr=o&H!ZjR5 z#x4qa`3%u0Ex1FCU$J6nxE|L-OSJui1XcF9=t z$#v)CiK(`Ow_7(p&&b~0O*L^(;WkOquJoOKbdQ^0XFSp4lA<#GT%^N4lHSttI=Aiv zsieH%YzDhr+{t1GUb20b4I%M(%#rb=tf6V>1!mX4 zBsS>>i;iBRoRVAi)K=--i(N)+1NJ5jBmZ|E9l z)AC#>yL8XG>l`=ksqR|`S1&_tDWMDZgUzNo;oYw@KkViMX5BI*Qej@g%+VZPJl)z$`t0mTyECf@bYQvX6T!r zz0gMP$l(DLNf|t1Bc}3f=UqU&VKEnI^rjBwcL4dp<=Hc`XUb1o`z<%==h+t4cXnAJ zT(l$R5Q{yEPpFALVMk*EpBp1h5b4({U%hkaQ_+8NJKqP%D>FpVpLn=M@o_5VIdfBg zvY{=g=5;ZTKV8Ul*Vgrf7m*7ggnfggXrJ9x-FyzQ+eYHfS3_>NbDVj3C=DuNZQJ7& zx{M342^)GaJa|rs)jsKr)YXX$obqjx0p?8KWXFkwU>|1$-(FVhw+(WtHUG>6Z zX4On1VbMR`gq{z0>hC|KQG8vx4rhSq{jv{~klJFp4`AAlo5|?zM%_=ARjS+$qT%AJX$QIh!iXr^;9cj zJNl>#z$gqt@xO;5oiP+$XMttDu z+|~9%34$vndhKbO&w*-;3!(5@$0DI(rJaxOL}x}X!F7S~d+DWrS9`&^Iw9NG9pl*g z_4pEb$V_kTC(DFFV#087Cz}l+y8Y$RwP-LSktW8|l|~_?1c=lwurlnE0fprFi;&>( zOeLY%M2W7b1rYQIq`3dmY^f{dpflYQ3$kq_$w(yyw|}B!N}MAbU1tG}s%sq)VkpPI zm>}vzP*T@j;f5?QvT)-SD@TaYoGrVar{bs4HkjDyUft+lUB_<37xzl^=%p2gC3vlt znu*_SB7D*Aj48Npw@l8i=nh?%i&xR{?QNs5c02FuZ3ePDSc_L~VW%s6sq4$~5ZZE$ z40b<$sRhwpM}t^Hdlc(?e5!OlIK(FZivLoFmb;}Jt=*6%O1yWD=&C{pI?|1Ybc#h9 zP&j2X3W{qE5)FkAG||=?2Sc6~JzB&x!ONZKtw0V}H%w{o+9T_{l^3U}w8k51-_JBu z@o9@XFmP>uNt%9nL-LjTdT$b)OsYz@bQP3y4??e-oKq5acSH137g-f&I1?_FpbbvI zfNp12$COv!tm;ds#iomLyj-P^kZFik;i>8n^p)?Aaf!L*AldEstowG%Lj}myFv)m| zq)x7JRalv)VEpAd$TcIq_-13@b4IJT$q*M~OR`D!&;CShO#!36R7zszM;#v-hz}&J zBT`5ilYrgPsN_zm$c;67WJG7l7|{;mpqQ3f>MNaqJS&dHlR8F)Sm+KIMncUd-D8J2 z+b9lZRe&*){&nR-k1SIdjh)V{BW)->xH}E#tC{Y{tC~lP_M|$PYvxM6#(;b&!;7Y| z?{#8Due}uFf*2nkLQshP*wWL-X1<<7x1P&pkgHV!NuYiquec-BFG3z%XJHF}-FG;6 zl*6!p)EcJ}+qKWScr0mjk%#E$1E09ZbQT;XRYIBO>%UC@Y={7Lxrw4$e;jI=edFfl zwfn8Zz}=w5G|QBc!L)^u@)7eyPi(quGOHr_QlMc0H|*VhN!FOh$&r#NmVyI&`NRv9(C(`4Sz_Ir8qQLpir z+OFRPL#<@{p^zpq%G;n;vfOX-)rPn^x_*+1{+|M>#;Z6ZxZFu?hol1e_CYQ8?laM= zW`pX9Gz}}Q2+Et^G7gV$3AGC2>=@9+hr_+0)2C!(l?35C^+*m`wy_iL;?A7+(@!Y-!9om@)Nx*; zGjYb^Q&&=8obC?bzj1C{7BuwmOv(weP}7vob$oQKOnT?>~(NO=9%{{7UQdhF^0A@vR-uXRB^SltM+)b8S#2Hb4BpNjgZXoVEdRb=RG=0 z*Yb`kMKbiyw5Fb`tEB?9JWbgw@t$IGX?z*8zbjVBX+hWZ=r`n^RC4b(rW8;N%-M6fZrnn>3{t3MTeo6k{XUOpD3I+AhsIF05i%~iyKYS{#>-E zJxqV`TY36ZvTB1E(dj1n|k9*PGZjnSj8#FX~ zfIn_;=bOX*{i$gI0@kwMygA5E*=xPJJU`c7ci4&lgU#Pe*q{p|V zXopYHI2YfAk5n_m-rN0#D4|%4ysQQi4 zI>E+m<$Uw*<>XdKm!8v|EpoF?Q917vQkJ6&4f4r*>tyc^-FFI`yiZ#J@YgdCFNPeW z*+Ej$3lb|M7xac>racfS+X$H?XS++m9uQ`_voTSt(ZRFN7;}(#RD|d|#m(@X9W1P=yZ$irK6OGTN9>*1L+uPAvJo9dleYTh^ zEEyr3GpQF@)%6gi=gIz>$?xf{p_6OT3v|$Wki~HW1(*qXYnM!R?;wvNS-i5%yj>~u z&{v@5?@XmD_MXS;$3Njk4_ci4^RxFCDc#XETTJGhblG|5y&f*9qj;bF@qw&HnisU! zWcYA-e%ULixr7VDj)!{%_;Ho{AW*r*4pwi>*G_FSjka0QI)_)z1}!Iwj!w|gF&w}8 zs-WjuU}`?;XD+jeU=iFoZ-Ye><1HDRqkTSY`C001sIo^7D8l=9nb*`9%>huSz5mJ< z5UZMvSh4?-?;k@KRgF)H&1~N!Lv41wwlL9hdjXWN!pI?cb-a@)4k&F4vekk?c z%~=1L;j`OwrhGW=xm{v^N~Grqb2KEt!gGr@?U=%M_Ly+Q8*a_F`CEi-2L<`YA8e18 zORAHjy+*d_-fZpHUYN_+N+4fBfAGWHb2u7?sGdyh-wo%aeI-qAo0kXfi(YUAE^1+S zP&XlpI6uvX=#jhIG4RC%vddy=71R>Mb%6}OuuI#MnP7YLB`9$>p?nMedTZRD9PulD zju-{w-=q5)KvRK|TsB_c_?keWR~GT@0@;ynKt!bz=Q<<){P`-xzm3aUNd0pyfisNl z<{paktXM`;{~^f}7p<@Swf`-Ij|g)OTe zz&TO9ik>s54`lfESGuoEPWPrwhR6y(uF{o9{u*Ppv}9BaJ6=?pwfw$rG(|quzB~VY zt@!*(Jl*cH1Dfef(xo~k-78morXb6A1Be#(5-9r^!_gdTUrW1yxi@mW#5zz`ti{6V`HN$Hq)#IikXh_%r_|dbdfw_I!A#mM~d&sKiO`_s$*ii*!=F6WakAqPgCanOd9J3(%~y6#+dzy-qIw z>RC$)2Xtt+v?d=0e=Q%){81cpP4s*P1{GX(#Wl+Qa;`YAT6#Nd>uRn*Wa#{Dtx}yB zx{tNWzZ~Lp!?k`jXz|jy{c0>L1ARQxRQ9WB^o(K6ua-9tlrcW7KSD5a-(GTrR>^*k zE|~5xIO>VTn^_$7&@!&vJn9AW^H_QIHHKcuvby{7Xo!{(oZ~(Wz7xNQVu$}8yP4Lh z42kWt8NdAd^w0cF|KHQdl(@IXGmXDnE%|7-4p!$r-|2ARefKpkVRrYu$e-iR`@-wE z;q3>Sr~a(OK$l;})zkfIz42%52bog^EFJ#mPEnjT;m$hvUg`l?#Pr=5z&W>;ID(G8 zfuMay#{M`@?)h~5C3k)_(h@l%j*!f^IU}YYLVwVa37wG*ToB*?ZyX|EkRs`|E7YIH z`RP%b;bmL}DIG-g{vSAG%MFmjj$84+5!$eh=I_ka*K6^w`Mjg>fFm}H_iLcD%V03L67`0o`@ye zRH$NL?!ID!mD;1%gzgj4uP$?zf#Sp;D?Lg*ul(Zse*=fGj;Vf#JLkk#CpYn_=?lZk zqvxAjJzK=Olu==g4Dsb5jeSdbE0)e_iQ*UZOU$QqTo6LOB_TX)HM&Kx$Y_2BlTeNh z7E;!78>6b)NCA}Vh*E-%hn?wWQ)KD7p)FkQ6t0G_c(vLq``AuS2PIMBNi4Eoeln;m7|QMcDYc`|00073=@KPQ|}8!tVdtso45Fzr8&14@LOf zAq@Q!srdin5a#~fA-w%>IfVBA9I5!nA*{cy{Fg)Mc{<$R+55WvZ-mg$-uf3pn69P% z2STVD==ldBRJ|T-Y-=v>>iypYLQ_Ls{gdNDMP*^ru|TNEc-C+nsh~EzO!^xk#MZqa z*EIeMAykz89jPcT{l_8X=VWJRrsh9N%qqQqKjYXT+$(>4yR80ZN$s&i2rR7iFL?ZS zr=s$>Q*q&b`83ULU>09s8lUz*5JE2TFNBbxLCRG78zCs)O;ij`m%E*MDwry9lPVUJEb^ZP z!qq5&fcXCq2+5Zn{>oE$`nh@dT)61vt|AOtzhV}u}j>Mw^NEUhjqsVXR;A|S4e z7gPH8P6g?|?o<>!ySBGae*#=-c}x*l-!tkr@;ky!*TM zjxR>KdREey`~SI9kr`6so!&pOl2`ptr=sd?`32U_)RQvvGo)G24PKQ~l9}Pl1uRS= zKdS%kRPdQL6}EIjPh*{I?WqKLvY<)+U!98ln_#wTee;FhfC^mxiAUp3I@f|o%?}~B z=C#{UGf?&UfQF8GR;-EBrLBDRfM~XGfgdx0w(_IW5*LPBZrK(=O{64svoG(G-a?;i zmdm<*rvwT{(=zaSiEez6FWi=W(J*X=({$qTEanC5?jtU z0Lz{n32Hy!NM+4?_ZLO5KS+&WC4iHBN2)}CXmEFT0TJ3+->=QbaLwZCoSrS)`Mwzt zH4v1=XcE9$CubSd4s#fZNBIs?GGgB= zzdemMO{r2HJ^Q7)>Emcd_;{7iA4z(HZ7v-C7Z zpE5hJ^no3F1emRj0jr7b^Vm5LET|L6lqEPcrKdgv{ROKwkl+2#GuukFd$e0?5#CNRbSh{!{DGPUfgQc(#{ z)-2I`42X`aI2`3hy8 zA&Rx?4;`$4j#)&=hD*qr(X@bpBeRl$o9PDZm?DTA2!XA)k0}B!3PVx~_gwPhKBfo; zhMjEL+kaDpGrgVc&$pvw{?AYZ|4{=#658QT)YOT4h8wVxTBItF)vGr5~uI_i$7p8YTECpi%1(w``U5IdazK|uGYvQPl(KA zPoEs(J0_2ay+nYHW(6)FPPcp72@cUEg$zb;Z^d)V*f%$}YS`QtK)*JWTxAQ!QE&-1 zuMYX1fCIm;;&kP7RYLcKr)|4#nhqi~UvJZ@zJBvV6}nn_mKWkegmtr8)*qB0-7a<>og{mRZWLwP$3L|@*VNy8HHHE8yE$+(r>+cix zW7-5ARFY9f&&M$qf1(vnMf-6O;S~-zxva}L`ugr_G!QAEd$HXmuM?w;h>$M72gO5e zp5Ds0kFGE7pT(qSC?%z0mp#GpWI`X_J{%W>dyO$1fP{~pG>=d~2!K=TAHvI}t zC)*VNq->OTDsam4rgL5&h>(%Kv=_X7<^dEHxNT;DWHB!;i364tZKXqfHqO=s=f8u4 zIX{mKsRo@iC1bp65&OJP1>DsJX!ON(xp}^NW9$ReXd#|;%myKpHNhn*uqJ?1shw?) zR_)wu zsM76hs^?_ksYj2cPFL2RnzX=$%e^+WYMh8VSmO(_Gb3g)^LEE}Re+eHFCN?iiVmtS z&E!7TUFfnWX|LomvYk+!9a3{PK}9O`wD%qh59&@bHgp&P_kBXcYb?nWd!1#Gkyog*S3-u)(n? zL9)+d=c9QJ^H>RyD(7ocR0bBCSP%8XwCk` z;oI7zhN{bE>yC5(EsF50zRYaX``o`%ggad<)2Eo1Czo!H5BWcMrHwlUAswlVY^nKc zhwauh@(jVXc~^gZ(Cbrf2iK%R=ompvmldCr2uNX_(jK&Ex7wCfA|A5B%yQvd{FY2o z8R4oKvyryMav((hx(+WZjmFv|FTJ)Gs)Sz^HAH@=LP%8wd`XbO{kGi3roNN2)Rf+sWGIi9`tF1WaQ{-2t zAJAD<6>tAyF)#c>2(GNWo47T>0^u0?5zcvsIam3uQh*ll4jK95D(yFyhzugYRGa73 zz1RVM>z`QzmznohHE4v4_eUQ!FC3X0weI&B&S$1Yit<`O_{hY>pGfy*;Zq^~uOEc$ zu`(T672aJJ(T^`sRwDWDjs$?y0n}>*<_DAe)V&umcg^r&jKL&ES5o;6x8s44b{vG$ zkez$lD|msMM+Kk);U2Q#d6RZ9JWSkyU6RxDZNUi<2+S3TkUQ{>2gF6lkP#{iV<1b1 z{Vk(KZq0N$3vGBCij`#?tB+;#WQNI4dnr4JKevpup-S$$F|6YdH*3MG0OB|caMukK zAAqa^qih_a@}Aw)m4)?qL~2^W=ZOk=0m!dC{J-_st_4P*N24EuK#{>5X|J5PPlBZJ zMl@!weOefR5dl=jZn_n~+v?CO_5yGAZ-;}Ck1a2k2=OMDlf~r_jyDm}IP%jQQA~u$ zJa%a&MjSky-DAY2T_)E08gGjNcB~d&fBD8!dQ=~ky*5*I@3V@3lh+y17>3cmCjZM$ z3T}@IFH#hm4!D(eu6l5~wc}1dq(kzx-_jUCq684yML{g-fb2*K9OfS1Xxf1r6Z8TPauYkz&J5EV4PzE;_IsY*R+3L z4||z1aLY|?$^reM`$~I3;(!p6wv8N>fe&03eP`v&BjySszz27Yw>^AcxJ1Ee9YQ}H zfGN(Krs?RcRRB%Le7aV-L>u^JkmAK`Ulk5)8v3N+fO`e5tEIsz(SWISqPiGx0gN#A zK;OtzRV_xcUj_;aybM`j_Fk6u&47iM53$_Up9H=MAhLUe>OJEj*0)Bsu~A`8s-sZ8 zZUwL`!!fw=*k<`L!a@SWq(29PWbX&Ds4NF0uPWn6%nmy&LWdWS#ED*q>=86NSiBln^co0M_b}F&7=6g$ zT)~s<_((J@_cE!RfxeWCDr6*7;4XUi`W9_e~l+@~)uGbZN8mF^LW>ne!%9odcg zd1|3Bj_gN`*@T=5Y@b-!5Vf+yn^^E1dl?FAcjS5sg;i7(_GRni9l0iE6Br1kZx8jJ zRq*gT0S=WlcEmIGaJHT3(H7p=-HqUtLdU$KIBs+r>T{-^=Hx4EXC*TN=h?G_&vsR29OoZr=e23#FVsMeNLylD*J z);YLmOBn;}_~Nz9#o0&Kc$6H0Q!k!4+CI5QD}16*spn%1aQ))=lT`%5mkH)P-6^iQ zg1Vog#=mG>zq?oKQdrBlQ+(84f62YpRkljSkzd24L07kCNt|n-zu|BU+s%c#TU))p z2I#YLYOIso&WU}%gM?-CfVz4+*G35G@s$B@pGqG4(}3lR#;;Es%u&yn7N12?t06lz z;qej*KT*-FSg9NUb%M*r1h_NTG&N?(8d!7A>Pc2*^V9E*VW{UN63@fY&9;Hh$HW0y z6VB7|&zl91qr^ryq3&MC^NjdsPk!le^cPr%H@2RTuYt7K5tet z07^dWk?}1<@!o?WtqA$2mZ%p{RBITm@Wt$$s)`AFf4tU}fM-h~?1k%?c@r+{7r^Zo z*ox1U| z9h86$+(4(l0NfIU})0V`NaAl$|dNn(`H6(%bT)^~*y?3t17L`tn z>&`erM;xIwow&H?fy0oO4|6d$TU66{P#@>ec}M-$SNj(eMhh1#}ZkeJ^<&MG^>k+(T zCoylp)OtQzE6~q_{xb{y1{+6r3@8P@IX)Fnr5^)X4FIG4FjrX5;5aI9M2>y}GCK5N z7QN?H%O-{L@CBZ(jhp`Nn!Gv+8EsTLd@eQrmW42AVKv4sFapq5o`$1l)*rP|x;&&% z<2+cC-+(t9t5A*hl`12iM>#u=2l19RS`XvvrogUG!?MGj&QCMq$6a^EY*EKIoZSf7 z2PqmT4HMYnTAU?(hKc&dXml8}IH5s55}7x}KtGBO?1hfjev+7V3>-%U4!Q4iV+u!n z6T>moF^JWZG_yH|(K&U(1T+2de^dB)?lp!q%`97`aC_j@d7#S-{q+cVYTByOF$ym)pHDC94@_yGIJX{Zn9twL!z6Fc zwQDcfF3u{Bemu3)yLP+UIR9h#&ZJ%43|MxVqhgr_G4&=Ga9&&fk@!hg_7e*A(c1MB zihfZuu&vx|{?mE1w>f7sWPfI-PkwvL)B z@tYQf>kA0<2R=^s?A*tH9x`;SE6YyXB4F+a^sxd^dERG3*tm6qt^XbHI|+!pyDfXI z8exHAI?9<6?-qOy9R2}Ly|3np_-aI&(W=|l_QzhG-2ysx6KU@;35f9vb7;kvfD8@o zZ}OENHOm4=?c@U)($AnNTUYA#F5zRkaWG`a4tl59I2kaeZ877Q-Wnsut)UOOaH>}O zh>qn$If&quF;fZUxWyEfQE~56s5gA5?@63(Tm2~N5)1vDTGh!*=h!bHQMu;m!SXEK z1@KFj?~nWIlj^7#DqG~vcb3B90co_FF>C_fjkWqbw9c>>M#gm=!-mn;2k# z8JM9pi~x++-~-1hN8$NOM$jeai^fpjK8mn(nxLpde?J&N|8N_Y z!pSf85H^`BA1G+G!bta}MB5+VN{E9#v=P^F3Lct%?MEb)zzU3vFT(ilw0g zqwqWBdV(3y3eCrlZg(o$sdkiJ-dyLZY3rU0hkW+?2xffr851_0MkYa<;GxQf*Zy$r zLbA?K6Yux2;MEU1+thcE+noyk{Cgpj0v6U%BF|wV9_!!Jn9P0D{Ub>jDr8q|Oy*gn zn@!dlH*fAPHMvi{!XcW(k4zJ`Ul4fz%^Ce6A!+crrT=iWc8p+j=Ex??{(Lp*#qU7z zx|6%nlti9Z*N@ycNn$IVvM(N0+HA#lX^q$wmnl*94hhTt+BsRfAIvTE05=3rCEqnv z7Ltkg@)KqUIq^0yj^v3bP+P%6l^)O!cI8 zU}0rTh?)f5>M<@>Y(j)FVl&f}18KM+IC_=d^Zf#wKkfm%unMfzdQq;kGpbl@cXpH} zWc>V9MM2?(=e@~i?Ozw7 z^vJR{S+fr~ox(>)b{P_gVi#GGeBD}|<5`>}CCpX4O*C>ygPRte+TBan)y3bx5@ooA=VQraTf@h9 z+jA@dy_}vsntb@r-c|<)!YWyCiIrLS9rqt6Ge~r(c7jJso;BRi1f3?6)XF;ymfHCX zjj-FrFXO%ibzUHPyBU)1IlZ+?uI&tVN>-ISvn+@6a>}k*Ow+=2gTq(s zgnz9*3CXNWa<6m#-VQl3FICF#P>|qcfVHYPvMM_oqYdfl%E=;BXlaLZdiyx+A?MwKz2ed8MoO#=yE>UyB##=7M*x((6N@>X|5_~tPtkT1~nmSi> ziYCR`_;@?{9d_eS{;0-~`kRQ(xk4RPpR+imZHtV>l=(~;a18T6=U{W1Ht6@t-#~G9 zSige9;zjddcx6Syt`yIdqPz}Akpu+iy{!@w1UMr{6=*k zL%Ug0S`#Zm@Ysf^J*IC(vxE!5?rhOO$%~w(Of?q#H29NFN1X%b4Y1lpqcWz>dcTn{ zt6H;}-lG2$0IoR^^h!UMPf~p$Q7JbJ^0~Lx!}eWS$w;W?lQ#ypkhNVafI>_oZ0$-C z0G`XOc`5AEpPyJ()fQmqqy-aN?u+D+~-a zV`Y`n^n87tDuNr{zL|QOQSi-L&{nptNKzpE?w+P-Dvu6s{ui7+^sb8FgdFaE#H0J7 z;Vh5$CDC_~=?5TsP9Z3}RYoX6Haq0b+_w!BPc?qYu;8gw z`b2z_L-q&!+%UJSy1~_EynA+PDYRmMYNJy%faSIKBh)ZyM#1P$whIOrjb$Lt<7lS> z4%|jR<`auZrd8epbFcaby>7yBqT@5c@%h3JEohUt1}3zmnqRB9%UD=okgOcA=HBQP z#r+YYY*BA4`nT||yf5XU3*BzYl(zxH)i>j%gwNy;Sk08@RK7k(?B5G=Iql^lu`rcD zUmvj6`>MITViI`9lM_dx{q6Yl0tx?(W6~A1Fgx}Fx=B(eL0J6oPw9>jxiJrW&RE zz!ZibxQ_Ru^`JwaDecN`&W^bS^eH=f-ph-I6K?(@`DTdRjRO~ceb9%m*xO6Ez7>Jj zFQtkC$v}YCGKm7V(vg>nxyo!XKSdzsKE9JqWr`p49if z?J7u^a#*Iyj*TKqPh-)QN*o#t<{&<_S2^_VQ>6l)g?~7N^!gI3YHq)m=Rp2mX(Kt8 z(>40&#M*VeFK+{*H;5-aq(m0plQU-OLh+~#^Rz4V%bMnpn)Iu6x1{>k4_JXntN?=q zjj7^H$oI1lp_MM%r>c4mgTwU14pa&HF)EyzQDNO(&Q(C$Id$p=N&<&e?PK-)jX^I! zjK>(cmPA%Kj>hvwX-S`<5}@!tUFFj%GDC(=zjLIw#E_^Z(h&sSvDJ`H2CL5vm2V7% zS0SgKfJ2^ALXC!PB8HFx$eZ+bU}|`R8-S1w!;QF9jHQZ=0E~cT2P`U6quG#VOe2ZU z2h*u21N+H=h`UifBTp48f}AaFviV5&AWePMGwSi}Z5TSjG1SDW z0F)6B)u%Id*01?-oP4Ysm%R>TXM^(tly>PeK8YFcpA#J`3x80iTN06YH(3eTId&DK zhieQT8wQxyfn?F>ong?s2soaVCjK3Wvk0M69f;8reyPZ-dJZ2>MX!M-R*}hLOOcFL zxtgm6;eI-=$NLvm6%cjt8mCi&XZT!JBl~HS8y#hge>djyP_!%&bh0ZTh(t3mfjtav|M8+KzJ2vPH< z3C!(XPpJ7Cx&E5gNT2gIm*>l!)7Iq>u;LXPm^|>YHDJ~>uj>85v}4}tq%d@A{;^}J{=AkA=YpN23Glbhp!|ZPJN=$K zQr~XDH!0b8Y4qNJCBk=qk{=dMTw)`E+6%0RvUnqA_xdK`IkCjQe8$%$lu7D zs1i~^PT(&} z5nu!=-)eMDV$X|}x^$$ui+R1|YJ=Kpqw#8!<7%_->W9eHmh{!ulGV1R)%Jnaj``Kj zoz;&Qt6c<`ZfZ;qC#F{t(|5aCYm6Ci#0>gkh9WV;>6noc%a+`RX`Vdvu;s{-L*3zfol3A9I$kpO$3q z8iR3}H^54d@h63zo7%9PStCN%hfN=w-j3_3Z2&((cBsLkOY6U1f&BLs5M|c=JdvOA z!@)FQf?XS2*-ym5Dzw2^hGs0|AeLzXduJER{2hCjaFc~*la*_eO|R@49NR8pXVQre zRX|c&+qqY5@Tkx85)yI{Mu`HW1L>kgfs!qJ$iPe@Ks=JS!>)$!g$DniU2#kJR(O;# z9O>E}t}H_I%N+?vJ{DiXm(be^>)!mMOD4tz^sKW->_3jmk2>GkQs4p#2mwzktvcaA z`6y(d>9(KIR^-wa!qWkjzpd>wsAGcEr2%p{VdHRmQwSVwsCL3xcEp*j)&3w2tsM=X zI)?i>3S?}@W)i|-WHL27wjDcR!#nC3(Se~G$bEoU8L^kkx=qxsivksA#_qk`<*?Ar zNMhhW31i&fgz?}%2;=`*Q$GIn?=|J$7yGw01&W`>IFCMJ?E2aEnXX5kz+VSq{;r7!1l#84D z+v~eq*zHgMeHjV$ucAAar#hEzuZh;B ziI(~4k=d!CzwzS9P~kuE;%L{uBFaPk?Ss7?Bi+qC|L7<$)%8o>Bf7RV z?4K#+!s4QW+m!O#zf#J%Sy`E{GtzGr<39*v{Vid9QS#oW`2D{Kqf^eizX{`NFy+4p zV@rfd5(<@&ka(L?{%^tAQA=t`MA`kxVH zaXB?n85I#JW#PXrB|!B0tGvJy=~A8k@LYlNWk?Q>xhXAi|^XUZpZI@>Oecn#p^IU>!z$CCt7lD;J1*+g<=lu;t?C~TX#)&PwjM^o}`FG$2)m!hIr zTVJB%;xK(!*cp6l)B}Hd3-z2ZVG9Z)7;u4W5=A;0@(>Knr==5|xol=wzK~sbO1;d3 zdLhx|sjhr2dA_0S08uSgR8#BkRX$G><5oKcM{KHM1lg7p9|rL5=SO%ivsqK{vT2!? zxWnMKJOGBfs_qoUj#{5Eu4n}ovkR^qKuo!v>X{5Z{lgRnAD4ov=0iTc_~M(N5QR5C zB@)RgSz~U?i>)kLawI*A?-V73@U)Oa)pE(v#0PGWM1m4CNTbZFpNCCLAKSPa(&=5@ z{P09&Awl^9RGT^paP~^&9g5=PR?41sSP{X=0YxU;!E49n>+eU;lyi*xk8}_HohuYK zgxEd@0-CZ>9VEG$Q2KM`2u`J(L043#ke3d+j+_94HUl0!Iq2ef$HbBal@-AFPBQHD zB8Yp~PuTp0?67Rc<0-I!H|0n)uS+O_dCN;UZn!Y_^kpD2PA)IGAN~t{(uBi zUa-Db7GP9uN~0w$v4L6Ao@*%|krh|Xcn+<-j{XTh!efuAC+5hPUAw75zahZ}qDYMl zuHbi-SLY#fL{^5W#Zkh&jXJ4}R8h&^&NZ@+T~p=11QEG!jV@EAzbac0Kl9VCr$orOCpe{Qw=Gj`$`+^&;DH5;!2|EF&}@=oZrj+ks^0`SM@{*vk!y+#^(f;=)Pun z)6QXsd~ipVX{++Jl0)=ILOC>dJ_>Z2VT9spEaRNgj*=x+^AC0zF)+-;kljw6st2_Q{td}ir2&a z#b)l#y77fn?_dMed>ppMks@h&<=3=K_nl5J-Ro)KA! zAP&@%eW66Z@gn9Q!$S%`&yqqx#Vkac!^#X_QAnL)HrkP4b-Ay}sQ6+IZp{%b^RFqH z<%aJkb zpI={hgGxoBHOK83zGV*Ul#0C`8F!NVmW7Tlm3XH);b#8r&C+DQ5o9^&85UI*&NMC$g)wuis$ZL{q%dMs84XXFq2PgKD1#k@y znOR^&ln1mHjb5F>ja5%$FVVOUlRiD0LKK%nOS&ky zj7cetsGKUVN%?U@corfbsJpxBn9K_Ok*#2TR!JHwHY|8d18Bu_rEH4IG#;@%VWkO+ z52Kb&Y0eb`<)5Mp((qLgbKgY?WK)O83VA;$Jb6e;uY#moe=d1f1zdJWala z8F=R?n3+8bj~e#+dZgu5Q<^I*&aE8L4m_9~ov3|+bk01I71%E_P4s%N7)H_BL@+)T zl4qaVVQ-BXr)J%|6CZFX{wb<409wlo3n1Ra^UH*0u$ou%pW+&usRlr!cbApt+JMbM zaF)cZxG!PSsFqzh))zaq*5EK?P#b66jsZ=Dq2QZQvPOl{NSHJD%*kFYN>q^5U1g>d zrFIepJ)U27RxCi$hKrHcc(U4%Ze|9}4p*P#u`6IUkHfA9BMP#FB#oL@O{ zwbey1k3ZiE?>=J`5FJM+OrDqC`+WdUYMXnfcTr*S`_Oc%ZQ;Y@MNQ!EBOCJer6IlV z@3V7-)w}&yrmP3JH!vqpliD$RdOzA$e}DFyYX9_O^2f(tzrTc%cWe;pU-mNoIYsJs zY}Se+cnWRsaZNiUjNt>k8yh$&FLxu-PQxIoX8`qT$61W-nm9gcI3bQ z^bF^+pGv{-v>O_Mw7px!qH@FY6H8CqzX@>|#+TkLcu;40_gBxC5vix#ck>qOC5T~) z0?KJO03Zk8Cz{y*EcldGXGI#~GVjSM8bSyq@saW*5XJQk4;uMF-ZB${4<&E;MuN2= z#MV7j=*F9YkZ;uyX)A>iTxt`QJ>??ArS1tOv=!8t1>AUYUC{z0VF(BWR|rLNisK46 zBl!#=3q%p^qrr=(#7->WpLO_Jh%nwIZGIj|7_I=&;5jiA7rzIbycGuY;GJ+U4$_|Eb^ot@! z;ai6i&Eb$+c|vM$LdlN8pWr3q9Be$3N{$Z5)D9XJ0b(PCS;GmH!lg2CWMpFTadFq- z;6yqyjLIuK1G0+Kh&azzS;N{vOBB{oks#b~fPwy%6og`!?kbvy28Qrx0an8$n3iro z8226)*Hos>zvPEG4HW5#!#4;4d4cItLh8ChuDBsk2-!ki?D%DDeI`{VT|!f1Sp6A3 zuqciakwAc@H+|2&P8*!B80Lq=4E zubwO2B$J7nK_XF(lC7%JSI-v)AiW!256V@Q%zS=qaTqD06b@4OuYBS~L|*yJIXMaXXQNrqe?zcs)&-83pyp)u-fKTu^T_h|kq?0!g=}vO)+68;J?iTOdlJ#M!R0aVWAMIAk<4 zTsC6NHOn`9BoTz(?pv;5d7H24b+`RWae zn7=3OrwxKSS;+gC=c3Epw_V&9p;p;2!ngV4&>5~R9FnlUS8<+Pm9{y{m##v}kBPA{ z!08<9WllsE&OJE!SA$&iGI$M@8y8AeVngWul^AJ5=zL0YwZUvwM?UXK80*RKoIc%f zG4Bm8B=|IqbehLKj5%}*eCWl9!w11A3RC=me7$s=l+7fS10NFsM7;%Pru^LNiUN&ZCO-Nv>ZQbO*9k}ZnhW>!2Umc`pY1;1h;WGaY_Ly-rDksFVu zv`9qCye}if(md7@l>Uhu2iJ$NCIR{0D7r!1{Hlg3aItJ;8;W>tS`haX)NL|c){v~m zoGh3R5-L~O=%!5s!!wkEzoIu2{tyQP?LHcEjrx9ggm02-BQzXz?10S!xFh;Um_Z;t$XHX2kcBgZyFbePp zjgQCj@^*Qsj8;u&1FxL_rPnX#dq;|laNG>Wwzk!m;;q2@t?k|Iz~?NGFEJVoj2&%p zBw2ACg>wz#zdF#X)su{!bNuRW+JT)Gov)2L`YJoguG*Jx;?%p2It30$Pc=X0_;h$U zfbbBl`%g40DNbtVIn*)5Z7tg2dosY%hWQ?K=k@K$?G6sm+7>GojtLOPKBg zuujI0{6Ry}&VBgF&1u+=0`ciVPhn2+)XxMUN;gmGgDr=Va|70Ax8M6Q-FA>5XE+g~ zVaP;{(t!wF-)cfgC+R>|yw0vRJ$@5`{gv0++E4F9Jv|d39U05+v}sbJ`ohql z39s`Jf3M+SgE2tz_=ddBM-ZL4E2J%F(uHF=m+-GCI zGh-fshI{p^-M(~xg6oyShcjEYGqmN+bUXTZGOZph>@IIk`GibqI#6lc9(U&6D|v=r z5LI3EV~aWaxnX^!iTSf}ojYneW(4G{b1(!h7%}u>zl79sDg^ z^a`?ke0MF7di>6sb^V+H0#kjXylOB#x+18?sY}0c|I=XVnl0|yE3dVEUCl`=`hnlm zkG*EUtWke>MfIR+Vjla6j1{AOw)*3Qdh|YKiFH*qhB_I%f&ZE6O(zv?F68hx_0=7k z;PExEwH7oFt0l4S@Ac_*!HUlGGSeSL7G|0k9gx}IR4tHo&OEBm{F@p*^HwRV2KB4L zpM@C{A(V;Ko7IrSHLCE_z8^VTHOjMU9(O>W(GNw}g*>+Jvu-J4=iwecQi=4c);nZA zJL)~3XpU)vJ0bV-sQ6b_%qOXmJE?wxpgR-PV@y!@Nh+`4UG=jK4eZXV=`BLUo^;P5 z5p>&Uk`g3vTQuHbm?*TpG1@=`Qw5H#!|K=lwy|+=Y@8mO(Ig-5B(=Tufh_BRg6%$O z{q`fJE!l|!Eu}-{o<02BtN`3Y@G(VzHT13fp}gpkTf`P+&sw(LQC87m#YZaOB!s($ zYWsMi<0EH{HKd-IIxP{>ZVmYW8e=n915X!@1s_wM9f{)}EMX7ilaDE}z37hJr9Tw> zpD155LxcZNKm0tilSsJ{OnF8o{eWzbr2aF&VCjnj#Q^EPT)_zddyyX!PA)kIj6z^Q6yoD47Q-(de^Xe_c`R3}+*|wy?&+zwK14mc*$=^l2M(dJ( zhJ2!pOrrAbnkNzc5h4IF5~l2V_KVu6ASe0#2gd#-2j9n3oYuH&-5s~gYYmvq5T zAa>o<_Vm?F-i9RNdbVqlDQ)bRiv*@qh*2)mH`uNoE z-8Lvwl4zze%WzLG@BUweQKFDFO_`H{luv+zwTOy7s!H+d&hX@zeRG=3)u^DNbDEZ#60Xb`bfMo}@1%|+?l(I-xv@xkZm>R>YazYl zh4ZecQ;dyx~XHLM-;;I=<*yZ`or;n@yff{eE ze+PUA+@z%WeE&RrbvN7Mj%Mp$HRXgh7*MgU+oHcd7s!Dso^6>CR!F9c)9Tt0sdxe< z`rRj@0xrnjO%Jn_t?bQ9WG8M=quV_^dwd#TVn7f-YKQfP5kH40$M+b@g& z#IVWIih3A(l1~g25&C3g;EkQYLG9N7d4o*DnNc_BZ>=`8ICC;Ud>k~uTay1UU~3ri z3V>J7x$0*wQvC7Lx6iVZpS0jQ_kUpY-s%I*4U3t~QUtj1Z(cs(FI@0E5|T=q*%W`M z`Hpmsor*@ON(QD~RM4($9QaLuoBOt={E!+~EjcO3)BzNh$pq_GD=V|B`|0z|pg~x= zdN>TlBq?cnoA$=mC7b&CvY3M99N6suc=*yX021|g&a_y3$$QZ|&8vUrM(m5V#lfB| z=A_voA1o!sMf77SE~KpewfV&x3~VV+}gZ%aRkR zR2-6}w0l)qtgR|8OJuFgl_>ROmbdM7O&~8;BlOi(%B4DejSIY?Gq0yP+r+9ACaP`J&vH~|g(bN0@6(Sr8i?hCHh zOcyz&yl(kkrJAd2Nyi`CccOneGaT4kO-)n5%Chg=RHbIDz5gO75yrevPi?+goCn2o4fh!PQqtLlx*oV zzeA8U^|Z@SLY1hvL~$acTJOM21PPlDdko}i7%I;U;UGT7vWagF_4?IwWHiPEyR{@s zk!d88ByT@*gNLh0h($Ot+49J;y(pyI+W=Bb8cQ@< zXfqjW0Ldi=6C|CKW69h6nb00iKK83|B=V;B&0>G4BoY2V24sedTG?7-dzU`kIO+{U z%r5(sY5Q}%p+I)g>3e};h@}0hTs!SOjo{Xyz!bL(Ic#bC;ZkbI_f(cECZu>qGDL&H z;q9?RnaB3BP7RMC`}lS|CBN7-G5`|sjsqrKmYnd^#h#JWN|pXj+vKpXkuwWxSSu|ld%DbZ14zFgmmP?ggN%^Tx_eOB6sYER5Zl1ZD%syH24o~*Dyt7--%d7O-&SWh1=q<7EP z=z5`a9`#P=6c6OldBJtd4RxxnjoEJ;MF{u{lZ{4Aq{=&rhVM$Wn@zr0s7-W_SKO3I zsa~mR#3$y4y--^q$*;w`4|apIzmIo!2`}al9Cm+JnZT`@kJI&A(8V=vyman@E!sUv zJu#;HXIxKAb==F)u z*|u}Jrg8v^er<)IsqZF$h(A0xMBR1*>p*=|mOS+OP}Gq91jy{!a3s>E9Fxq(=>G}@ zP@peqvgd_Svm~<`nU4?JFiFuZ2R*@ho)+vw8@K+*MAPB`-l_oM2cfXo)x!rfxmg) z4g~b@dq zOANMKa|eCV>L*sdxo0DjL{!lQUU09aZqj$a%frbkn-&ShPDu#df84)Kg9h#S;#`)w zp6iROT({9aX2adUV?YhRibd6O@Dh>eUCN_Ivbz08fZZ3`D&E=oZ?EgPLo~Inp=VA` z-twNzHaJ`t`43Qa4cBoBUsM$9PTTV@KYWg3;`U^=pzA(gYE3GGY?&zntGdD0NW(4U z{Lfg@oE$07Je_^TFL0sPJc_G*56CgGL*lVU;lPn{{JjFe)i)aK^B&hQB|Qq{$!x+O zapW*PV2?FoOeG2bS}E7BhYLjcD^5YvGw&X{{X3l?!ALWep=gSqG7qNg`-ajN#pavx zn6Iuq*k8&wB56pXIiwpg2%`<8??^aiN5Zy{-|YG%9r~hReYgLxrN=}^EeAn8efxAOsNoc0KeY+%9@n7qSdr%6nf>Yc#XHJj&wZ5pwg&D}b;e%~jN zU2Nf62%w-_?Axu#9zPN@38djUxoqE9MrcH5{9qAP%>!Oq1WNm%Yd1JXJ~vcH7m1@hp0m2TUy5lX-r+Jm;DhNUbkRUH2^2&#z>6(gyDajUr5C z75F9&wn-e%yWe9H5LyF&mUPayW5UlBON&}q8cUYarhfP9OvfTuiWB#?r*KP<$J;>M z3u2KK)N2kjVKwl(QPPP6InWnPl8ZcJ0uob?MVLyGUZ6G4H2NukTyr3hU;<4FsQemD zEr}c#Nc1qASOfB)91O@iC)Rj)+WHL;my-+^({X5hgbn z92O?PFNqX)H+-fu8#_GP-TiPsROLs@EOj+xHXbOm7Ms9_Hu%3W0 z;zk;}dQ#PDb0P+t)1=zJ;RR{^t1O25E!1=8bB3I(Dq<)OHRAvYbV=XT9jhb-_xVRg zMu>cP&(aXMe9pWYtxHWpBWf&r$Kdg~G3nZDM2p@8oe4%}L=81(AKCkr)hNtwVS;7) zf=<`9367IM22W3nwKeicpRzeOnZQ}x^h~zoTzpX-^NJoAtdnHm`{<8={v=P5z`;Bg zJrNM89B_y1*-B!at4YZ39-2n|DWnMo_%Iwi;OO|snDTc2uiGd(Qkhl~Xrs&gD8M*w zUQNboK?2V-$!hS)z{DS9RwU>0?(8&%XX&JFHhr!C`5lmnT9P#j@-l5%?WtJ~#c*z< za$EbNP09?4V5Mk2l}*juO2_0|?0iY2IS27FGGV2{o&4Fn={I__N_XX=rlRVd6#|K6 zXEw+iu*IVGVuP^-h*+dSmp$8R_4?aNOUWwO7KEr??MO(hn*Rr3Y~nX3!1V0Io-i8q zs$o|BI$rBy26sr#ye)?QK^P-qFrx#OJ+P(m9n5&k{3L;uG6Fd}y^NMz%jMz0L#)m^ zTD{)ydgZ>hv<7spFkNn1OY(fv-f1;7fOiw%NmS6ix|VCXacNa>DOE>pT_*U6TGP6h z6Te@SWYFEZ$rph!`xJ&8GcS(`9bGsmSv_(G_F!Vl;pSg{TbxlNk0XgyQdGW8Scrr^ zhKCY~gtEN#gv9%7=56p>fG0dN8>O>7(_ERzvpAv9Ph7nVW_OR0{fGQm3j*Etb?^2+qY_qz>u6o$6Xle6pW*9eWQ-o$qlxs^&YU@Tk z1Bz3=eq$OTc{`ZwhwHqS}%w&?X1*OB`0lW^`Hk>prB=;5LAL5MbT1WW!IlvOhqNZcD7h?7`tu>b#+Uc8c?^^ zZ^!O4$c!+~+Jn62nuH}~*T3E=L&ULmiICitO*IE#?c z;&eb=so014<3-HAp9)Px0xl)S`IFl08l?-}l1R_ajX9Bc1l6UhGFl?XMs+_G3!- zW1IKm$Vl7=T~s;36HOeGqGIHcdl5FcVoQ4o>IZ3r@gk>$K{(MOXa_%2Kr}s2Z0UA% zjVrDtQOe}N8k8mviB|I)dqacl>ZeknBU1E0!t;sLWx^FQGxLH6)P=M>aJFqS+=$$r z5O9ZQ`B7@2jBl8M2Km5-;lqPt{BU4c1Y{4nbg0I1)Q~sWC^<4jV>p8o*{W z4K)pQRV7W084acBE#3cFudHo}sBW#Qcvt?e_@CX%{JiX(ztCq!X4WnGyd|L_l^>$Y z-vyO71-xr|S<>KJ{NB5;?pc2Ale`+&oGPd6O8cw|o6Mrs5bD46=j-&el+@JLV2z|C z)W7S`D38QU%k+2Vsl_4xQLlXA@9FJ(t3RJU^Z6(JO!$j_>c^-2O+Qs)+%^7NeszP^l(< z>pmZu+xROh8k#=7rJtH+PvJ(EItFGiT@w}9Lq#=xc_nRW!-p~on$ilee?=?*3weS+Dh%UXTE&_%HG`duFtY4A1@8YWR=!mv zZqwmO(ucqKMs+85-;K4k1YV?-tJPF7UuoJf88K2LjaD0fzY+RRYu1+`$Y!7T{ z*qh2%i6a}Gw;>%8X-c=}uFGvHC7&Wr3o`t!XhHaEX_RNYi7)oeSQCv2pPeNlmN8Mq zC5?3lsTeV0k^{tQV0-&*OW*7=98GWZ#ogSUdQLE~OB}+l+UU3Eg;*i6drFqsol8_|T<(7> zqC#B!TJu1lpV_cCCj%AEPx1|{{3TarmL$lkY%5XzyNq!(m%?0*%ojnPad{ywpT$5~ zViz<}mW=APDb!H~E$?+jJ^g|(OGTUQE_E7*QUdFFu82vV(Wa6<9_XT3J*i^^BjYw5nzT((?zu%lXQG{305ES{uo{e{J z{3%u`gph!x6ffOvucE4XB{hRQ>jpvp)GN4zGc~2!b2o&9o_~G2L)i6C%vLxv3uJ0sv}Ut zfaIXBGdf?EPE>LhuFXF7qDZO7fg|Dj-fu{rf6?83C`j2$MxldRA~;z+UwQf^vr5sF zl(I;K`fXZ+ZcB=Pjk4dz8*uUvp>O5-U=agDwayry|4fwMObVnC0ABmPofiIjDK(Lp zGE0wJxn_1TnX<7=*;!yt`R)_3v;+-;``oBGqH0tALGgq->1pnRE0K*9a)94XH&Jbd z1)%eJP6jK9&+7&%dbbz4a2kmn)y5}T?y7@7&83y5NVnyN?hC$lQnR9!_;Up6k$r!9 z{DFK4L+n4$TSho71fB6Nn(x!!?HBy{P(~Se%xu>b146$7>adtUe1s|lae$>}h_Bsd zIwO>}6-aD{zOdlcAi9MgN0X-O!J@!j_W@8m_F-INJPCr^Vx>9n08*w`F3hL;&dO5$ zD@%h0;ssS{QVOC!H%!W8Mea^WAe2h#+@~|rl#q42a>SR36GRMlVSCp)xPMvLhcFG7 zJXT}`4Z#M*_)wY(5=9J)!-G;%4pguFR(@b^|L3ioCFWe&DFwXz2lo`B8k)uVi+iTH z1MmICJz>nYPLlZbkJLKF8>q z=Ks`<_TvLhR7D`FvY;xae9|A&!u^P1^qXh3 z!eP!Y8}>?N3qUNIoC7IRskjh<+!*UyPwXo-J)$+C5kFd8%6?cd0(ir zW@pa}yEkWU$nwmRbyn%n6|$6T(Q|-?=G`PqA(61YSX8Tv5z9PlG!M#z%v^#^D8m-v zSflii`o_GRgL+F}R&NzGSM#0ay(_?pPbx9em|G#Dv>4QO}|8?$)D+Nt(dT7PHje*n5hZsnP= zF=nyrjU7g<05^p)tE%L<;&Tm|DegWR9;7;JEN zsHqx`HZ0P}Gt4dri0;R=J7!RQ8m(QNSkU@d^^Ay-=#cGFaVD(=*T22i(CrV<&cT*N z_GVbyLky;qy~O|4Vbr+h+yBGbeSbCe^^3lT1VRENSph;Xq4z4iNiWhBq$?mum7++I z-a`*Xih_WGfYcx&ASLuFO+*Aix*&*vAXRhu?q~1k?7PpoW887a{Rc9#*8F9yHDB}n zvB6VHI4XNQDaUh!NMt$3VHml9Zk@J8TOj50-EOi<2~FxI7X@MGYUF9XzLp_CQ>67l zsy$nMHp{`q7$DFYq=>ePljue>3x0KCN!~DHac+3&Fp!8S zg==HF2Zpz+C7fD4v9R7ZdBF+yvY*=&41d%7Gx|d<+6Wa+ys3~qDHAg4NU2j1J=wuy zknJxDjBF~3eU|xfH`ec7oC9~8qezh&usls>a6dYnsP10&S_oG&^OQ?vsU+nx2Gnfq zOn|tP-F{?*da9&_GHLO2pDKp;6>tylRUeMzE)Hoe=53jB@W#I|erTFg!oqfZ`{V!Q zo_}`SOy13X8vEV!?#~b3|Ky$zrYOt?-Yxu}xhKQ;Nx#zHeO!9m8o$Zuuq}HLjY9*K z(OwkD?(Z-677&t^hMV2~pwiB*mWR zZHdvqzw#xWwDw`#@I>5zaI9naPPzt1+UA&YxI?&3eayvCLf9t1#&-teom^U&1mzJ% zAh{kXkBL0YC1J)OD=+{J4uL0$5+Ok*s)dvLg-2$DlS7S%KQT`70&Iaaus!%sKhPf> z6s88id?7>vdE8?JAV4)U0cJmmg6$!n`%>;=key}%M-y;GAkv&OntRiTf|0vyDugbB zWLFKdT}&w{55NdeVlgRd3dsz_-0?-K5Mu1iB8c^fH#kVy9`cnbB8)(>T?{A9i!pNUf_^qlb5J25+F(-UgAjZ3IH4Y)I1B_8OIFnvrjVOY&p`3AuNjPyY#Z@h?vN+5#2x~hVce{cVvxi9b1@YID6CZ5;3g2dfYrJKpYC6w}mG2U^9&dmQF_uHkvqQF@Ek(lR?rt1>a*p{z?d2@I`#i#isf~ zX6hr3T;m@?vkG~$q$}f4!F06wSyQE-0NB3>X11J%RvD_Nf$3%CX$oP!RG1Cef&Bn+lD@Ze|0L;N2etZk)_`yJC)Zzo-vjpZf zlB-pfsG%4R?Dc{`PGnQ@LmBmF;1bAdy_CtyXMrtO6EReK7}k(t_%86&Lk)1=qgyYA z{160wDg+>|Kj|)}$bp1~Eur&d0o#X8NFJM8+&~`_Lzpjutto{wsu*NO`Lmv4qaL{d zaI?)KE+ni+^?>spM8i^n#RsT64pKXTl$!zl!dzl#=+@rlv+|?xt$@%-YA`7jR088~ z1?sPJytsn6z(0TS3vR=8A70`wW&tmOj;dO)72Xrq;kv_kMuS;;U>nt6E{z_Y+`Q zr($-Q(NjH49>bDHPuLEdXdljjPIALm_TZAxaM)|41Z^#t6!&!wd=|-;JXdj$Q%FN( z2@J#lg}&A9zi2`w5HEP^BZo4pS7oS?T0e@HMvyQy0#jPOi-uCw(-J0cvw|eP zOMC`aGJ7QxQc+fqIKwo>xgd^l$n^;*^3mm+0b~SKx+xFbRYRQZS#S)OdC%7l9~N@n zePsx)bStOoVWP>qM*lpL*Hg3AH5UfTpz!mg(VTSpyV81B7YgFcUu?K}i8ugXya87`9G1PiQUy?|Q{O)@2 z{on20(&S>8j>uf9&sAtv4C$0`kh2hVkf}b;UPq5P6yyiZ)}ro~pg3bOR1l`-8P;nM zrruQ|P%8s97{GU)&`H;od`R6V)WulP)vnc*O!f}UNnjo&L^5?ZYdt3q)f-j>aWf2i!uYP zsdqRV4tRgL#wSFb#muNa+Ph2&CtvOh{BrHSL|c?(?>%K^dg3LHO6iM9F%e{CcJ?X) zWekK|3|7$fX1CE7m;z2h>`K(#!YM=LJOgo#t=$ttFF5-lhQlY)y-!)0tw-P0ez~UE zMvvJUSmEpoHUwDhM#|`hJeE7VnbeXs(0 zU(b%}FQY~KBi$rpGZ*?2JKdfoqs}5@tDz>a&^|Y__uFlri+1$Ep*>2M5i08L{T=;b z+fg^azRS;=ZJuK#%kO8~#-IC-L`IF;QZondjQtS?BvK~Qtx_1$8K`Y zwwmh60<9r+5yoMWsgu}Ycha6jeSqg4=iij6yzFr|BEGv?88{YUW(@-g(#c^1*Mt`cBUP*KUlrddcGUgRJooh~zqoy~w2Ly}s6_&JhVLq1f48}^1-}(_a zs677Xf=PzDpFHEk9eaJ#RJ5oHyF~S+0Uf@lqMv9-Z~0~9oe02f2Ur&L2eupeurUf( z_rjK^W9;?B?dh`(`^nYcmzecJP!rw2r{wo~d)4#O3{NKfGD`?-kTcS-lq)z!lg(y6vT)6kNkCb)7LhMt286@6JLE<~@l z0YdhSu3>7@UCHsYV^_h92pVSt76YsWwh{kdLqEQhdmS+R$Ck~p9M=U zL_1DWnN961$bKrzf4T)M+oOY3*srrr!_4N7!lWoHfFV9cCeX)hN9SZyB$;TPmPbY8WsT5*0xA1tfy>ZE#ow#F~&j~TZZ>8f}GdVkk;Zu9{6 z&{?B^u{WcX_j;1~++DhLa{OSw2mJ%w7YBqU(ulLX1~@N74;xH)8Z#aiqUD|e3-*lC zHGmF+-s9G{Li`8S0(96S;7m-TAFly!JVUdyev1}U2HhG0seg)^oP8t)EEb~a*|(x6 z*R9Pq;bt>&C8MWRKpV^EGlVA29$g+jMJc&eQnC^3jdtz$9*^IQBi$-e|LDOv+uT7f zoHA-Xx#{n;bE9OuOO=r#3|-{4wQNRE+x_O^I2q8sa@1Q52*&z_H6w2te58lcz%S8t|7*yFT0gLYu_W(pKFDo+iamZg_8_*=wHT{p+>-2 zq$d)!fE5JD#nJUdrQx$Ld%PTIpp({;dWnj2&qMt?fSQ*xxv{+nkc+I`K<$F|e`*rN z*FwIf!{&|HP)y=zU#jm$>F8J0J7$w#0nTk3$!P@XZ*|fg_KR=Ux6wYT=p~~gkot}% ze&077&C>xs6Z!4#gMM$s=-El1*8%8+p+mxf)n~^B86PbiKTqreZ@lS;M-K}pH{wmu z&+X7eHq_&Bdeu5Wp^i4f1hBYz%C~y(xBEy|{p`69zlo2i>`&mnIBj9knGEXOdils< zc^f%-jGA085kHT2JlCE4O@lx4#2+I{Hd0wp<;K8=Td4M*=jx6darmb69JyfC89<>?F5eA z{pIxAB;hnHt~UhjLp5dpDOSSSRR5p2C$G`7iy+fHzHCu@N}fpxM*~ferxefO_5b3Y z=9?3RPswIDg+}uTZ2Dm|A1cco`J;m6$NVcAmefj(FS#en%^j--7x9}kjGI+)DMpW< zxCrQCgi~tdUl|HdxQ*PrA2%7t@(=fngCoZTcL1}u21p-6L)eSU=?*Wn{6j6A*50P8 zL_pYV4maa&#yQf|>_`|m1_{4H>*RA0J*TOP9=0jZ7uUDf>k}dDb|-sT;gyPy-%HB* z#YgfsgymJOvPKOEzw#fmI}g}hNHE}N{dA;Fn5Ga13oE?9M16OW^{<*c4?R2j@wK!0 za)gEB4tdWKR4qB}ojcEGlHko;Y&@Y(oq{8FPtHv_T2!I=kZP|bshHd3`3@b(s|~8l zgYTtKU>z2%mOrZ(Q6gJe6Q~pd)Ja7|c6}Ooz z;iS-z(i1E%rD+_EUGeHz9erBekan^9lj|@RRbQe+_XvMY=9BXS5%ReF41TupH8%}M z#m!ocq~b?|@@b~AdRIH=cp6PLiDnHWRr2|-X-(+4=Y)sj>18TMHO2d+Z>0Uc_CP>a z1`Rb$Tzd`GOYS#!Grghi^5&z#$6xRH(JI$}>UR-F2B%7&Ob_0)j3Cb$?#;ZG&8=7? zY#upk^8{Z85ij>v8x9etA#m};1J65xQR0w0A^Lkh%OsqHA2kr}B zFJD#sqc^=wGoMuA#p{$hmLy=WH;{k}d+QK$g}DS}(~5#-1XdP`%VD3s-sIEQPqNGl zLvA$RNhsEHEtXnx+LI%UvKd%MUuk_`Vj=ka*Ie?=j!lez8pIc^N1L3NiDj z)=X}m9#JZZ5Aqid*dW` z5#sOfSWN@kRF*RS!a`%eNqdz6w4>W+rlc6sfbUxwqc1m&W*9W)I@6v}Kk#3WbkWTV zh&5AjU+S$AADtsSyH=danKb`B^+F>&aI5@ng)GYcAlW-pWKA%VVTOblNAiq!i1DfG zZ9SEF{*~-U#|qvhB`3=u<;IG@>zC7?G)P^DCgyI?V?`-Gd#!CF`mPKTPL0>8=3~Y` zV;s_})swpke1R%V*?MQcGl>^RJ`v~OK4P16CUrQ^BLPkeG7C4ZfVF#=uuV4W)@TI{ z@+DgK3k>wCWJgprk_Yc$Z8GszgNx6b^={tv=LMfK8P+Be&sSp%=z>u8q%PvM!cO#C zcMujLTIh`>Y){^U&U67!FEQ&L+Cr<;T-KFXz}Gvzw9b9%^^ z!7)fTLM=1a_ZjUVxyow@t161F6wpi6doY;l9~TweTbg|nL(M?B%KUZs(?1PGAK5#S%Z}-zeu9imppB7pVylf7C{%B$(M6KLL5j*(^5c% zv`ppm*mNl?Dva1H5~nzmCZN2xH4HK*O71BwlL|7Qb^(iO61IX9S3U*{253q0Jl$F2 zM`w=M({DtUBz8-xNsa*^Q;DNwY^3Z7>SpbSVn?$$Wlb)zdao!W^~fw}Ey4`1b8G0}XWn>oeAHLJN~87Ww=_u~^cBm}S$>p;b9sRF zj*k@vxCeE{6QhG)=w@rnWH_OK%}D72O)ann!0 zB)CXX@+L}~II>jMIZT2?^i3|_u$Qlbp&tA*-}Ac_V~tOr-_!lFkBpH1)Iv9;DF5C)&CN+{OGxkHRZ8&;Nw@ABXyza#QEMq z%~)0ki7r(AlU5x+)~v2py6Xxt#}v!nAuUu%IpPCVWlX@T<>GzPG_QYU3zX+h@ppov zinaSCYbBOs^lbv4vpb(mag*$6m!4h9b3sb?n&++S6x zC5ZX=GVe3YjUt%TC`(CHuY28DL?#5a9}l=exhAh{v|L6nuP+z+4_7ng+xfCXQBe`G zrADI7TBUf(90M?yv#fLgaw0meu4EY)2p;?Pr%T59K6^k6qp^5{kEQUc8#ixOndwWF+WwQYz?`BtkJ(kqZ_tRyi-4LrLi+?_d(HK3`N9A z-_^fecX}AwH~Yk9?)LB zcn~QBtC6{vlNlsXUeT3|D_nxAC(J5kO{m4RDyLwSJR%h?9!aJyy;g7*&vNT1T|#=t z08FgdRjI_#E0yYBuqTSW?8!~q1yF}OTB#>$$@SeuC(N2%8P|Sc$GzB_AB=L@`_v~H;K zK+;KH${rX$(V8+rdofEXLJ51gW%SDfnH{pS9Oe7Tbrlimy+B zhKxchvSlmnu=U)DIr+-PdfDQo(BM#N1G=OygPNAiLn#=8G(G)BFRb*b)QYJFz6yGc z2VSor`FPYIW!6BDMYnSe_ChN$BGypTdNjF0oU&QmMA<+)baXfr7Qn;8l?W)Yzyj&C zHtyGM(7?V&*Tk%jjFY{OBMc{!q3R)JBRn?Z_vUr8QqvMHap zBvR~ho(9jr2_3|XI&p3XmMqzKDsOU8YEqmxPUL~@YiYAoLeE(d-i<1xamluH6RU*o zRJRm-y}`o13FNVfQI9EQ6>=d380wt>$dd%AVIL;+>LUBGR;DZ1p`r>nBi$rpAy#oz zEtdxlz*F+SXyh{LF&#~|LKA;8Q4uZ+dyytx#n;xOGB{kOe(0GzH$|4N5q6l;*^v`$-HISt**Avn?$k>(c3J{9O*(@e-rE4nw&DQY9iIfXa&;pv)@pIfDJZvGc`lC(xbN*Yc zs<+nI8h++sWY_h`*Q!W&7!QpIlHbcm=r9R1|)Ml8E1HTO;Ew>Rl@ z$#;~+OorY-HQC|Nn)FPRc{i^!XtKs83$1Z1nRu+uju>8dITLZ{ zAt9XOR2KKTozfn*P~2FHqcNP)LmD^HLY-#nWGe{6(q+2f~O_X@55c{!dpqR zAI49vgYVt`!T8Bk;Tz*a=cql)$;iChswvLwP^)L(IBLFeDQ-kOQ)8ef2YS+fV3v;f(sNHrE6iXpBE_h28`5$Gwa2br%YW zgN~Lh4y51WlzsWV+8ZZK4>|q#-OTQ8FU?Bb;$4tL)YHS{x>=Xf9_c| zzw}&b-nywV)0#8<>=u8^jOU=p_lFu=o$T^ux3Dj7m1qu<#qjM!C4cRY_nItT4^P_} zrl*SEH6EGSk)wsGFYJs%eoUkR8QrK4=pP?yyRkU9pU#gN`b1r4Xm7xe&x^>prXSC6 zKjvrd5mWY77k>Zv3h{0zE|o^?uEb;iaJ#PF+~sMx8=sfE9`7Buha`2{+Pvv4HFtA6 z-1(!m=<7(Q9~aWKW}GPSG2 zS7gk$1ec!AxQR^gye{ZRTeq#n$sl3jw-65b6~6yw%-zv2jUdJBp7~4 z^8X@A$^E*b`%BvLmyGK#*}z|N;xLH#?f$r5S@j?RGAd;vrOGj-stM&)B&9;#FLnMy z4Y@;2-9wr5B3NLOHj+x0f=ch0Qs3n8+S@~efkVSjheqEHSyj2p^}t@6Z0{EmuMdiv zoKfmH$T%`mT>p6}1FNrF0$WTlTSmb6Xyd(r_yI0TRbT!Iaw=7Ug!Ry)?nogG$^h96 z!Me>Tr(^1%>(HOqC~XsPR)LiF1bAHeQ{K`;Y_I*U_kCTDOHi2zFkBAs$vwg^{Vtg; zl_Ci!KPkK~NA1P|b^m!JvuuMuu@07_s-TJYDhjB_1mHIzl$2BfL4o1?R0-C<^*N}B z!JEtj_bDx~C$W}6n)`w1;p60QCuzqg=@h3phSLoG(@eS3EZx&=%hSi-TR|I1wI^drHz6NuwU%iUZo3MU;vfarV*PFf3&yS(^x zsMiv>cqj;~2To8wE4Lh~;D83+{~W{s^`s0*9E5}%pVi&QK4XYCV#dBiWBpD_`)J}& zgmZ8?G}-pNnCv_r`_TUO@rMj(^UsjRi;#Heg*^krLVjtW6Dvlu*E4Y16oKtyfcTl7 z50+nq8D7K@LZj*-HTu4Z4y+zOFV@dPEmBJ{|e;( z+W!}tUi%L;z4D)d+#g^6yO{ouI_~EG5Ys=uFCMLbxD?Yn>$6*{|DfsZuVde~H!jii z^0&36wf`ZeC;ug;*S?JXW2Ha;+e-iUI&S~}%}P&qFHU!T{y6$S>bU<9>4~oYok)Kh zs`*bM-T!)QxMy&H@Gl?TPiQ8zUjpc+g_`hx`{;jnasTnr{X?zo&6jE1(yqaOb#b4( z>-jg1E@^JAt*Odstp8UIH>IIH5&sTb`!=SgC91kPrlzW@@@2)#=VfKZmr>l}|M1ay z`A;r!bZ+kB%P4MGMMLmEQQX)5FYvx4^UpYN_?vPt)|G50$Y22)= zth%_nX=&*xDXED`$^R{ln-CQp8x|228WtH67I7=9)H<{DW=3hyqp*j8ArBt@FCTq9 z{kchMiE&EtwWK0*T-aq7S2M|5H{q#P{L`y3Pn05a6(Vxw!ZWXgWJ^BEl6e%O_|Qiz zC{s8vL-1kxztgz?9Y_B=jT_;0=U+bhmZO`^E$3HS|3q=EZJnZ3RV-{AZ&?20qjl^& z|ErFBQ%nDbnvRLGhT-M*#lL;@KV4k8|JB76lhYEF{zpmwe@NrrgR<(?7k9-#X@%?t z>q~kP0PbrAdiW)Nuk{renQM$`UpfYP{SIA2sn(6J(D)a38~(R6?gz|B?B1jP6j!~? z-Wya3%=W{Ll^@Fg!%BZFdlt`A=AD~C(` z?%|lzY#_2>%N!p@sX-nwKq2P@2~?e;xxKIQha<9Nov-7aoe|M{`LXkw6+=9q)vkVC ziu0DWXF$0>Q}ADqB@?_4#E7++eu`iX*j!FfIECbDxwUfvVZPdVxG-vK==DcroGzL$ z7H>JTXj!*IN*}(D>q}}vG|r3~TbNmzv=X{rvmoPk86XLxBe+u@u z-e9t#G1t@hX4JcCSk_#;rgn|o%`_OCcw(9dhReRN{MMqs{w(yjdsbqAKG|&nm*~fK z>dAQ1HMJjt=5FeyP5v+8H(TW@!=<;FOmGy;abr2M*|3VD(j1TPnvbU{O`Xt{?$h!T z;Y4yxflG%3H>YZFV%xj#hVCYtzPSC_^4gs#DXkwGpTtVVv^Q!` zt<}%s5^D`MRj;AiF?a*h(mfp!zld8pvEH4uO4;HXd%y^)fKA3_=QSPY)BPcV2hG;D zWJCNDZ~4eWKREIFdxCo?ESNLd3nb0)>QeK2^c7-520*gdR>4F$S>ls}52i}L!SQiy zFR@OtTRDhHDO3oqn=%6rP(LySKhT_RX609BmHTc5#_V&!TSom$6gg3Iz5w9w$iCIWeW|M6Bu z#F4B*Jh%>a*loG|MeaK~ZDUjrz$&WutVR!6$gwg@6Os6PFtA_hZU z0@V#tRk;|2Y;u=SS`KQ!A;y?DG*}W_y&mSdJ@-ZVWq9CV5Bu3(f*SR6fEYrPX5$!h zU(@jUKWSV(#r;Inf2DDSZ1$6^{z>Bw_K7{(Pj>hxjeBXOpX~of8uuS7{ZAS<PTkcov8}`%w@*nrNygI`2OyUSv%>u1Bkf;^8;yMK#{ojF-+=(qnR# zhR0yzHK@1l+Ct5U4EUWf-R>yL`g6Df!AVFn5 zVJ~QtnP_Dh{cfm5g9U55jqPr~#2It;U1>6y*r3t4QOxUXSDehIF0VKiwPT@9;XZy; z;K3cs`11DSIo8XNC15k>fQJWrsSCN39Z zqyp1s(Qk>?ba9l{i*~R2o(Fx&!GmB=LS(y5VQgCYp=^Vl^x(8fnGJ6UKA+uyB;G^< zY6_>r`j838Myv5XqsnkGgFUzs>&CCfGJM<1%W~GE7w0BLUaQXd=~I&P7)zhF-tE*a zQ(c-7)#*sFS`85A%;V!`5Q;*T{3-5e<#*jr^4w6C%*=|JT(0ByKh?$BfIZ06mDPrc zhm=o&neSDYX?b=RDw=0J`D0B`!Ro|Pi<%Q-#s{(z`@V56m-o1uxkew>!q@s7Rl@7V z@H7cmU$}zX#hiyI6l&nO5r;P100yMvH0~98CzgPbO@D}XzRQR@rz3w&4f}ORBMum6 zCL==j201ZxWoB5mvLVSZoDL|2_s7a%o%a>2iFyWNfl$sIkLeA%=WCt=j~$VdWe!Wy z_~_qY#Fn(lXK8D5qh2a@>W;l$=9q^_I(F5z%nHwXd-Bfo%~HJ_qd^m`o^N5lA8?xA zTClI^l0Z^v>8$FxT0#a}=Z$_onm=DW8GGAtdE>&*&%cr&n+X)g zd(kWxOHh;MZicbFcqQd4x+ej>9LD=ewihdm3DLFUtoH36bY z%dq9xLC(92b-x0Vh&cXe2;pMm7Csuu75U4!!vTZY#8BugfrZqfzNw6_k$Fk%qoN}z zjZ75za%(l1?7B#=k1O7Yt_9WDN`2?HI~#8|*5`m~D{Tpoe}qRvJ?d9Eg7iq#{UuU^ z+j`Jf`KFD3cljB1ti(fF zm(}lY&k2iE1BDZU2DVE$G%jZm|5d-<{>%PX1jCdOy)q6d8-7^E02Lwlos%_#+jz_< zl$|soX{GN3^Af^%6vP4ir2kK}*+9+g!;q@{Ix z#whWjse?Z5-W4t5SKS>)KAoL62iy0jF~rqgr@z1Cr2fcGkg^;EV@SjPSSV0%MwIaf zt~x}>Mnb#%71(j)St$w1pB#u%iK3GWyeTWO?o* zSpB1o*U^rsSPeJ5Ee00+N;nN?(41+|Knz@9g*+${N_3zMl7N6ngEJE-HXMR)LSx19 z;xwU{nJcubB>`Y{gXCjm0r0vzD#k(Sz zSix5kR3J0hflG1-DO12*z#$U;3qUGok_3<-&U_KY6H&a9@SM2h9!PXUGtdg8193@>CA_kwgP4bz5BGO7x_|hj{(FDcv~Rz8Q=q&Bn2kZ$oA9Z zHpt1g$TuC_GcZ60NfJ3JOM(M);=VQ|l9Q&$no0Oj92=`$!9> zgQBuz)nE#z=48tfUmZA7_tocdtZz1ed3tXQXBvw-{H-pOI6-M)eFNqOuJL8S5|A2^ z>=%(a`GLMT3BUvcv;({4z#B;} zxc5N)G*Y&ho{fM^+;dxX2iMg<-ObCP&c%I^2ZAjDitD-GxSm8kM?d2fc@+#4OCYWd z6(T&qSPa0kgdm^GlK_!rU`J0Kiwie(9z=Qp4df`F91ugsG9;U;iL zs%VI&g2a*vPCP>uxPzSu(6JSa-zbp(ODx}q|P!mK4)o8@|EY{U9Wt(u+~V2i1qGen1(L@O8rbzUK(q>b&y+ zw-8%3$w!I{XXy*3CcC6rj2spZUg+N{42I z;phodCkD`e_eK`iXmPIXZJqxJUnSnkq0Q3d?B8^E`HgIS!{lV5hk=fO61}P?n97z( z-vBQs2skUfz1{ovj$;7`ns{&8(&^9B+_BB|&Ws3Mz zyJs8iU5Ov>YJsz~E(>edQoeI^Y>yWPiiX=BOSW~s>##U%xn=fN-ImGQy&bIHd2+5l zsl;Sy3+xNO1>5N_dV;S+GWoiLO@x8JLM>FIT6x0sOY^KOp@2q6m&sbQO9_E8m?^&! z*rn<=%Llmvjl_c~mR~hekBB;t+;;4u3$4vk?K(Is53s?MNR&hpXTCuOCgHBUJZEfFq*3X zj;SBN$Bc89PLn%+bQV=su}6oD0QT=0^xI}s&4*3QrYY1XLL6rx_#X3ph^^75$Cny( z1PH2OaQ5thkWQE{zZw^r4KEqLj{iWRJ{8i{Eg%AXXhZLh^xN=$(%Z>aVwqg2p7)$<{K-I*73;e|je zHQTiF%} z@)t_fhE7+Gu-Lcj`_rUGD40Dxp&A$=vZ3c6bzca5j1)u5D5Hanfv-mNQ#HWq4xQLN zu%6M^bYt{!JDq=ff|+`!@dY7{-kO zt3@F97LAU&<>YZ^z;wEY@g zNnb?xPXoVgMal1v@r$(TKfz{$u~bvECEHH-fY7CFs0r=4H*JF|YRQg%`5Exr7^wDa zryd8!!rp;ICRjLVUA<`uM0V6uL>sNy4pmp(4^|plZy?GGZ2R{>JmY|hi2B*VAD+4k z;77v09D>buHGF8I7wOp20q(2lA=L@APeZmCK*xc)xiFKrRj0*qgyvi~UOqr(Y&ntc z%S!B$U4HFh>m>V0KB#zAM(k1 z@ze=A)CoC}b4liWW7Guob&CL6Ex*}*?fUL~nFF;mPJ8X=S-df7 z%m?f|Mg&QokT_~yrg3Eh&{}TXH0lQ6Q)qRz>Hjf}dugS$@~28+k6El!*FMr*Zj0qh z=`^C;p7TT@6(F=h;1|aE+Ntc?Pt3QjzceaTwSZ9zb?e^9ccNh&xMRVhs(H5d-LJn_ zf%eW^vAe|&o2GjU9dRrSWnxh}#VaC8nPqm-u2;`uV<$gpS98cXgmzo*JN2isU5zjB zdp!3#QT=z4i0@C`r*wWakKIm-C-GtAFW(o~9C^&t*mIXo2fQW@>$zg70$b(R7CRcAN9CZuXSj2)_=T1*^z1A&llmt=f4sYDQe9aX4d7e)=UO$%}94kNGcPf=2J2#5-K%_m=T z!Ij3HmNl>3UcM3}Xl_JVEl8pYVIoP~RD$I#ZT7h-q(0*nR8PJg-y+CJ^Tb;0SI)KV zjgJ}-1rnw)62-*VimLjG+iM@O>d#@ef_KY{n!cm^hy*8()y$xyJXaE%iC9`=*?pTV zNBXBhTvghw^d4_M$qKTm00)+}6n@t|mS%zw7?Rqq-*ekWvXW$FAs;^uYGkDk(k=pRHyOrz{LA4T?@JV3?=`FpE8>Q}-?J&LM$yU49fp}~J{ zT{vv{COugK!tC~3a52bu3_G%(-1wsH1;t2qNBFsl)AGA@-TPk!NIWp{r_p|p@i2t{ zQwI(^o&?lgKP~Cw7|g1wBn_t5+m5U<|5i5FD`K`UZ>T7Wz&&c2!pSocS$w6$cC#M^ zB*sEev7FO(6GB<$ILymt2My3C)DQm>K~+6{b~25I7dx29i9t>3W?zj}QIwcq18KRF zytYs{4;%l`ZEdNOj4y)Z?lr;PP(e&2*xxv;L@Cm#I2Uk#>@1y7<-}@9{w~YQ2eZgM z1aeu)@+c|2lAARYRm=&){dgbrbV7@2?YaPsMXY5Ljeg#m{Lrm15ZkhZHox>|n9hVZ z=B*~oxYwDkzo&L|_f%Ut{H7-erZl{59A0KOAM^O(~mN2tr@Mku85 z%AkY4%G@A>cEd|s*$??F)-Mcg1hQ0L5qU&S{oji}&TMw&b0t|ILvm+0F=5L3gFy#{ zdOiuY%;=QrYGeITA0vs%CMeJ(Qj< z*&c+#MW@oV&FK&v=TL@G#wL`2G-nt{S7uKdF|cFIYszYOcaR4Y==j=&y?s#e?=teq z%rpmkiHmL8zY?G38d~!~!In#0w2={dc zAe?W^ZqayTn+?P6Fl@Q#f6+GWxb?g43Hpc5%p)C^Mwz$chtX;k`$_Ilp5`Ql9J5!6 zbhW^XS}b>(IqG08TbdpZ#*13{ZQo4ufA90OK3+!EGvmfw^bWS_sBeM z)k!DAdt+0jRz`Dz`ay|A655+zRv6??nV;G2WjwWB?bl=A4YW5(yYb8X5)`I!Ef?eN zsjdBp9)-|Ef?3n{$mx|nzZYxj`s5ty#H_i|A-eqH#_%ah^flio&F9y8kL+ygoSH_# zcOS?uwr%bq-uOJ&*v+;-$~#4qt42CslSJI05lK$K3OJ_s)EeAPlkcG^4}hrmCxOI7 zf+xLyYgL~H=rFm7R_GK~IYrxig0jnA9r^wW`RD%rH`w8G5n^)jU` zMW#P&s()e{SyRYF=^Z#f|0Te%*l5aCnX0#kE{f}=HCVs=giO&%^|wxDyVu>$R?LJd zn2yiE6Bs><#HBUn5!a=>GRba;emKNRCHDMZtleicTyMYle`PQjV-KT~j25DW1VNA) zM(@1@K?D&JJqU?WM;|3335nh#L$nAoqmJH1i>OgTqDMk9Ki~5`=f3aX@0@$B^Iz-# zY(Lw3t^HtMYhSPH{aGzC=bn#l_0o(QVe%ZG9boC{;%Y=t-MG6AiGE#IPg9j=c>eYW z9?D&hN7)jX?rZ%0#`T>!Dyi0wo#@zFklkJbm?YJvWx?}}CK12kD9Mk4AS;7Mmm>UA zMKddak5Xz;)t(|Zgm_*aM?h+RS2Hfyt#JxtANat)|@}AN{sSf=ANbqU7)#sd_Smwr`?@SaS|WYb?Fh%5FWZBeEz43>?0;` zY@G9I2U9PCH;<3ER=<9dFa-^&^PK+*qU%j`pg zc1u2gvY%d38V{JJnLhXZ`3BN- zR9uc#x8YA0RaI-R6cD7RD7eBr{wkdX`|TFP&r$I4PiS#p!Y{G7YdmtL`){~ptHa-- zR`7|d;>mmIZ~=XKQFGC!jP%@Rs!c!H=n8${-S@biHVQ>Ts(V{(0`W5SHA!?bd5s|s zvA`&=kG+hBmWYGJ1?ijiMa4n%60%q1?AS=e_F~7z1O>R59aFH5YTNz+x{y!8Avm;*nC`epD%q2wp5U{PC`Za-M%6s+1IDjOLYETA#T*@0Vt^G7kz z`jjQ&t}Rit#*sQRjIaHPKy&fZn>W{4h9>!6rnhlPu*$&N%OY~{J*r`Kv3DJ#HP%Ory6N0oplGx%)acDHX>*e~J zX!X>xk`UeQe(#1%?RWb?98+jgb7^P9dM6H_$Wo~mR@)_U+C7mgNnQ!MdM*RJb=*3c ztEQAqijeM3Ms}whRHp|a8VG2gLhx-*CZ7XT+LkyLt@ifv+u8`72}hlzAVA%dL9 z*HK5|6da5~{ds=zMgGO~g|c|=NY&;Z5&^o6j0^CL=i>zX@_^y(AP8X?G2CELY*(7LnUK>8Re|8P^0-dhBx64(`LO>(!elVU(e7 zIK*cJERnBciBRQOa_=%A~~ZynIse!?b$yl%aL*1S8pvD7u5f8p)F3- zV90y`ve=Wd&|BiJE#A|U4Wciz8<_QnxXIE#L31dY=#UjN=;u2I7X2A}SHQoNlE>|s zTxGAX_M(=e3>%RoA3MmPG76K`H{K`{XRV(^k+=>TYLMR9rk;*WSg>`J4r zNyIgp4>Ke&wuL5~)>3{sO+MfmPFG-KWHWKlk0WQt57z=xZ=V(@u+s94aJa1>f667?xClibaj3dBdgM#|>2I zS;OL^GloBgr82Qr_a2#4 z;Bk0oj{MoJjI`36FvkF~hH4Bept!3ckl9LDtf!V&*wAI~2=J}=3kE#P))q^->N67b zl^s^w;_L<3ffRTC$CXbK5mOVKBr^LQhTAIEJahTqVR7M4^md!8h7^zR?QzG$~QTIPeIpFLf_jkcET{m zv8LAX51(KwJs>Uy*au_M%Z(NhqQ-^NQw2;i0l9)j!)9^o77gAO!Wzjm`Q`=IR8n ziD)#PsQV;uz*P2Y_9H2W{Hf*B?Fne4Us}KD&;|r2eT5gv6uJ7_J_To$EIm(JuWb{C zy23tvc|GB%kubi~=2nO6@0_nMcd5}-zXZc#$TDI(XT!P}lE>ovv2Q4BH@`e-p# z<|U zo8(fw*yNIg1(N*Pi&4Pe=_5h!lGH5;1E<7=#d?LCD+^0k4J|_Iz_8>5MX6-z7h1~f zEA@@iC?-IvU>-#~x-fwK@+EK>_f^f zI2=cp<76B&k{kW8Q5;O-W6nR0q_SK!Z@Cqx?a~@hxj8&>~{I&lS8g8E+5?sbpn%27bAbJu1RQEc( z4~5sQi^Wfmh2KHs^u@@F0gnb>JTftHXrn#au;>Cipj@+>#`4%lZXCg7s0E6;Mm;Uo z!5(g<=LU<@*1w7+KCAawA78(x%P9M8vrBn10_j-Gx?cTAx6frGkReK^(Y5YK-w-7G zuKq5BsGZaLwWSpmN8#E^>$!6*42EvCwF1@hTOEN3HQzR1=3CwO64TP%NX4FF+jpYe zzxGag*5lrk&u0Q! zjkk{Oa3aOxNmKdwM9_%W_di={_VElbkAwQnLP_wW&RoxnV0gg&qN9k@KcJwUh+WtC zQ7-UM>-UXEz(IIQ?YW%|cG$LPFX(}H1cIf{af`0RyHAJFrEmu#f~EhsLwA+(Y4vyL zgYP`KPrkDIOeTL}{qfCq>K@yJU5?mY&ZoOvCA-`WyFA^yydQV@)^^YR*ga3Thv3-b z7x`aU>4vn6#}SQqcq4effpec+FX|`tPb=-0^^A-BGG5^^qtXM$Yi^9nkM~v9_EmrE zU#B}javX3C72Vg~EEc8q!1B}|N7;KMcmo`*$0aC{F$WMCMT+`aB?ko-6?XR~R;TM~5N9#uyNm%QHurbSzM#7I!j$@3-am3Z*NUbv% zeH`s}9P{9KKQ{Il`^xvG5q(kGF~_4HQQnk1_#X)$jqd+AKIs&UXO8rtjFp}W3c^!9 z;KO?1F_ty~38Iurx^y16ecXegR1vUt1LaG%OHrayYMimW`B-E3!^^{wR@mTdE90C7 z>>1n6?*_-ag}?$rF!;a-M2My+rm7oO(2Z4p^DFxjxLgEmz#+wBeUyj~#GgO;-5e5y ze8{tNXlgzG{xi7P;(G)0P~#=+JF_6d%{wcAbbY4i75JF;ck00DXvy4az>O$x%zKgFiuBmuGzxG!DM+g1CEJyEe&i?yybpPK7`rnkJNB_e? z&;NfeNB@_GKFda*f#~^>mf6t{vm>puXBWeNXQNyHyNO_zxD{ zNq9$SX*^@mGjFl~okdr6_q`<$OWV5tor!*ZW}@pG|F2*)zA2`v=`0ETpCGz0?+ir0 zdX@9+Mb4Rqe)cT$>C?>c^7^o{`jEdsbd7&ujZYr_UhW%@m#srzAUq=KEE4?>4IL8t_`#Wj4h-@2e{kP7@T?Pk$M4=* zD*DVvo8t;hlXK5Nw0^=Xow%18@qwDLIqK0bP*Km%BGG?qXr;#qN+FMBL;nKNlK<6- zzTlTE?3?trgXZ^6M0h8hzn>6%_l}##{j)-}lZ%I)lbemhZOa=@ueGJm9CWCfikY?J znSi!8vDCM*GcdK)F|^XuGyf|Rt!Z=}ZFuIO6|d`D^|1VR6#C*-jekp_C6$CE6a~c< z1TJ1hh{~N8kvn%mmQP%XPxuO$OcD7%H=_}y9xJquA}y*5w4%n&h4Eh8H7DL5(=NB` z`F|WVcSf<9TmDO_7D_(d+R~8%?Q}8w-i)GGF#<1ib1wS-M>E>vQ*T{`?wzWLfU~9A zT{+B~)&SvKfNh2246Ws%ZbQ|l_d)xc_Q&lD1uUSOSc$KPW+=@Y99-sOVzcwzI6=La z`oZgr^;9>(g|x}J^660f+Yn98b+d?1x+dn!<@?BXAb38C$%NEyTvc~bwY<3I`)5Mr zkmoMTLHnp|8JmBY@nQS<-s>;thuqIy_Q{ycSsq2eE_AAF|#N91wrKU^V=R-h$OqogAEzgA&Hx z!ijt6WSF8@b!%Usmc0FeC?Z|}a0Dq@567|)m-3O)w5+{4RcN>It5qbog%l+1GmBVg z8F5KV7z9q|MyvYggt0#BHod6JAp6k{Z1Lkcx?kAe#q1;f#V=Vdn+Nf3tdcCcSyo8_ zfRhF7SdN+}cXT$=bSBFAF)}RJ9($WsY(4j!T+eV0O-rYN3Go1@7_NhLySG#^HcmNVIzqf}wC7sib<~VMjZm zG+ciEP@bje%t3F}Fb@Pj2`b{eAg*3p?joT<5J0=UA!fOi;w3RW`Z=s4Yp|OB;)-u6 ziSj~KF+^1FaFwJ%AI{izM(94OpzUC@iGr?q>oyf7gM;)^NXE87)SXQUgGX5v#_y>l z^^Mb?PYOBczdpAjf(mDl*dqlUS`6RB{N`Y*rYRztb}6Xz;QAO^7P@8Aqz)!!=@>J_ z)Kyq(cl&5on@2wwLJy>S^sh=z-K}kIRyuRgrZnW=7t|fpqwYyRsu1$gx{!jtuePM$=PMoD zz{}cse*59@VyIhHuzi4tza&YT?UBD)q#)>%T0ZOeCADOzP)L{b(7_#&pp(P!(2KRI z_a+?nb20&0w5-SIIM$3NUDVS-K>RHAeow6p|`Oj(|CW+L^X0`Xkj?D`CNH7MuuyTG$ z>?iZaBAj`hBPQOTUV^h4OD}ahz_;?o?!i)4O{Fh?D&)5Q)*;nSkLiUaJg1s|ME%+8 zOrw$!(oiducW7~z66i6Lu99Oqd`UssIsM9Np`HdR_d~@)7*i}4vRDkU*^z|4aRMH z?mvh^J9F3D0B(1Nf_y{hGxdAKBgV@?-Ls}@YF+Fzp%!JdBdbU|P0ss-K19k3k}Ah2 zPgC-CRfFIy`d+{QB z94=-eu)KDh04;wP5(28E3af#Up<6A2)9Ykx!SzgGuxn)AbcA;x;s~;x@2h4z*4pv1 z&h!hL+*pP2#o{7Cde*tFa@_iyyX+mlO;nqJ_zcLZ5foQ=bJf}I$yR`C;m^Asv!!{A zakriqkF6v9%Tpt>ysCdGYa7!GTAG{4QQ#6%mkaqy&|$uOE}AsueEm*EVZQVV4mtccK+1+#eJO z*5Dx4yh4s=f;JMPU>BMhFtq}z=Qh-Y4(YWB&OW);=!?0%=&!++GQw5h&{iJE`5sA5 zrx763p4W=|8DqU?yH7IP9<^qs0NG~=u5HPrwi=PR-oD7Yrp99OqC+kfe3ZhBrOO!C%!lx7T&=-@A1b0WOjp*f4zfYb+O9SE^;OY5L;Vc&TAs zxz)g?<@;X~_~g1uH-oRXvq}m`q<_`@oDX7%nUBrTdVH+GmNU=E6v?o@=IOwe>$Q{V z;pF<-5`%4z8z(bUgZ1_4Y?S4Dk~I9Hg!=9zHi=^b<;qLJDCB}FkV^r!4Weoq``twk zy7h5S9m5`q{H`!_?J<(jM)AwQyC4_A$tSA7v#WAF@ZpWco0U}U_gQjGPiH#_p`F*| z2YuFEI~M_?f(}2mY)?EV{}(c=8keO*jM-@e&Ar@Z~3{m5bbdM&d9ETp7OnVh6AozOBMbr2(!w64QEAou+RLx znT`1phuxiLi23=4(p{-(6A$Sm-&|){ygk&}ZiJL%-Oal7$rErtzLzCS=LB|sf4|EcS^&9uVpG_%>3Eqhfmw*>XxHMlR$fd!22Ab5P=6*v0b9{^7-KZ6 z$OGUy!H0(fV({xB27%b|l55q#Z8^|Q;6~WhJ z*gu(q;bA!Kt8nHQUjS2Wz})@Lss+%AcfCFZvvX&4d>X4kqNCe=knhc$R072P0PZUQ zK3TV1@K{eumkhFFEUOi54N>l+ugDzL*>ufw&uCdgIU$cYga70)8;b&AKH#byXigs8 zI3Bt;%ybtCxFX;Sc-mM|Aa2T?LmPNXz_51H38d0qr)E%JXYerQKH9wrNhUUIK$5@kw#0#C&Q0D(!Jed8<71OEJ?8{v@+arA1{5jf>mV1k~ttDJIt?0e$I}x z$!CvdcA|&s)*fd8@eWG_7 zm{R!OzHYr0%;92yqYg0MP5sh6GvOkD-eC@rKD#Nmh7O>m7=2#x?i25)jUUqsM4ovF z14nsGeivAyF9KKMGC@Q-vbTbpA|U-E{%R3(l?em)MSxf5X0*g9yUOazP=u!=G~yz`Mt5^*Um=)t_McP9P_FMVg%IeLkkG0;>LbVGb#iHP*0T(n zb#$xH@A<4-KZO z#_-9~`SzmkKQ9T@1sWYurG&yTrBcvhMpQ^CwznV?2`G}Emm&{J*vAX0C^5;u)E~~E zuGyBUx|H~DA_J9xz_K!=e;LgRW4>;wUP!r;P%)9Bm|BV`1^U4KXK;(q8Nf-D|Zmf`csFtH!=1+Y6U6i*4_x2L#t*uNY zloP_q%~d8=MpYfDHmi0efo+(Zm*qv-`mb8i@fz#Y{6E|f;Ku7zlPap}8tVi#wrgyB z;(*l+F0@`*j%~ejArr8H--kcj#?&Bu0k;&5Rnq}Q0>=qHbx#^L!L%S7rgCA z*@O3$8+mouuPDnGY~Z^HH=cKFpi29@Y^aC8lM^0L!aE^Qy**`h{#PxthiqC80hjk2 zIeM{FskJ3vQO*z9-rNODUU0pecq;|z7ObaIWOC2Y4QeyY7V9>!+QXMcUze= z>H}nIHbxru`mWcBvklz^J~zF4NQtAa{_wN!df7v^gB!qEHTPOBKyOF*b*m{O0eJin z--c-gc%^fV*{Wz@7zDs5!Iq=jM1yG#A+~}RTevEvMoehWc887=;4-|$R6g$lQ3Ua9 zMQSdt-RI}%lz}c>J5yBKjl8xXnKlT9sMasBS{ujc)NVWSK4h_iVyi??;`04nZ5m7@ zGZ7M0{XQ7e4x;R`>X*=7>uB9=4;*O+=XKro6g!-TDa^v}orb3~aBbcISWdfoSlHF4 zV1)PZhs{6$glo62dzZS^l$=_Y)C4$ZM$CH=eHl#A^VVYdk*$iCt;#kq= z(3u_ANn%5NVr!XezG3nf0-MmSX4J5s(2(iYxee}b+dr2Q@)jHQ;L(DRym=+0#Ppo=;ydg}m>O@xE z#POsSc&ZnCngJ%Q!bbHQh)!btzTW$+1+MPJK~^TRR?leqR49kdDCG5M<-G#D{gHTwLF6M)X%AC%~h!SxG4x6#VOxwXmsPo1Ky;#@9 z<`l`8DIjm^1AnVtYJWk?Cuz(l#p>y^X7B@_309MlD~t2%e5^aKS#y|RujbgcBuB*Z zX5mg9Wegt=U$dTkQuUPtx+P)XL+8OhpJ}9o>iJ+lTiB$w0UH(A@9aS_6v5zEFKnK5 zk_rA>g=;1Z5PDH{E_H#~X^_AOp66SVAkND2e>(e1qHD4QpEo%0!yC1cjs zC|4M&7oeyKSqFgbTs5^*MC!eD7M~?K%qqRpjP2PcQxvdG0`@uk5mGSb?AlIz$-Z@G z);w&<0A4T;XgR>EJ^>mAD-`p-j5UWK>16K^cJ@1Kd|U|7@=w@Ujo>D z^v#Y~?w|^TLgC)Yz{e`ql$M&)%{RaAeP_y>6H;aAO@>-+;iEK=jK+g^_pIs$H^U}P!a`^(z#mvg2!Ve9b_@T&s` zlfBH>ER5MLR@GmvQ)_=d0_Y_goQDn})q9sm_Cb{Unt2;wll5m!N3^M5n4G@Rj5Kr& z9x=ftIculZkzqOKA=!^QACo17I){MBc{n9N?YRRP zLO_~d0U0w*c}lyqdFzs@KM9Mwtf_w#iBvC!>2nD5zdq1QIBrwG^v@hL4bwSvmNbr_ zP0z<(x%)pmXx<_kaell$-eXudZEJULQS#XZ7Y~=}I5Ux#%8FjjCM-{oy6g$`g-)qB zLeaSg^x1x9o95*fuN^v{TYR;QcmvX0RDxMqyJ)K)F}#otAAITcn07&--myQ?NJbt~ zKYYtf=g#jxG`xQ`qlJm==Sq9NkKmp%bi4CBbAu$ufR5O#b#k2(vI{IFxcByrJBkcm zY37_c=)~s@j~*%NNRxSbQl~?C1M>x4Ti|?e|7u2iFO}ZpRd$%!n_TTnxCWvK9~hj; zQTX&HDB+&;dv;3t4Exk8+AoF%UTM8Lry%>r-ahlsImlbfsq=!g$xqOYP>LC;@jiM>pqgJ>E`n4_Ar7iaL%_&80;)j{bE265n;d1RNoUaWY&1!^}kH#$CqMUv>YO#B$7+otg3WTTE{~I5Sc3ES6gsxWG6NE6U8oJ}|_j*@~hDhld02C-dyD z`pQ*&8@;7(gGo{Ga;W^(a@8sNU7pOQq~pXv~pnKGATzFm+L+olyhG`HGM0~e?>hasw_Q4^Z7hmh{E5C)@r5H7wy;UCSbWJixvFUzW z<4`(9LG!hl<8L2$F~vni7L2xHH97(^oXv&t?43j2M<>nRQ+dt4f#+&O{06Rwxcd!s z#|_44YTkFr^;O&p-X=8&h-BR_{Yk4(d%I16vy|(@yMY<2t0_5;PbpP{9;-c%dG5|Y zf%G3e8xIgL5&WS%V4**gVR3Wy$;IaR;R4mX9ku5?A!Sp$B}Nh`XIBI*h4cc|k4v2H z-yK7WNI%y)yFcVJmr@PSPm72>*KW)FP=*@{wNiWa>(>|9$)}WXX8iCRs7WX!OKs4iAgUZUCONw*!Dodz+ zj5Mb}GeFN%s-6}u&N=GcsT1MUG45{^Zp(i*5G>>68{xtj!Dk4VdRx2dPXK%U)&fwc zomMRO+Qahad5fS65~*8*%DYa2YG}kD`15z(QL-dLbajG zDR=K#@uFAph-i?`GDTeKH38`q23~&6)2tqy@{M@m)EOe4BTbh5VnPmDUpQw`Lsiu! zeNesVdFEI~S;pQ4U+KcU@mnpCLRCV_e$Eo-^K~tK(-16Y5nZ7jT^WYA+TIzup{j~( zjd5h5jLpSqb)-4V4JE&<)sqF`AMX99c8>lWj>W&5-=#jm$0SP&#qqQ|H*DcAz7T@h zkS8|)=PxkU5`}2WQ};p5+$%X{vn8pX{A@S#MO3MkSyVK9+oKE%Um`w+8ptYdP++m#z#sMg$8kzb~0aW z=+n&NdGSUzlKiKpIEX zUg81}Cw+OI)YWadLgm|HR@1#!U3(b~9dQ>|tW{{fU>&I5vz0g(_RkfNmK|6eze`yP zZcuB85-4a*gWCqD27F&ucqY9JC-$9t)T2KZ!DZ_lC8Mum6a%CBl7xIaV6mOA@R-yM zuA~4vYPVl`>EyAtd6SRW>k}+U`V$A9lrc4AGj z3bLCu&%SEo<+y@TrXDp-+=BQ&OXnr2FipBKtPBfsKGuh6K5VWtT>OC{5f?pEDc(=v zx(c*#pL*l*ozvm*fpyI-Y^BA)R~VH1P)k|&k~vQVmNV z|9FwMP%oq@r+W{BFnb2x_3%=Vp^BsvnSa=m=(uF&9lN86`fUIv={Y-$&F~0%GdXLz z3v!XoL*--+!3FK3_hPZ9$XoK@e$>)4t@jo}qI80q7ZBt1o>Wv)bjhix{Gmk`9+f$E z(ua?pwbRc}1&~(qnh5-!A)azZ+l}c3(Gd4ssbfQZGgtw&1od5z`^@Hqf<#;noXk+s zs4eB_Zcu!ZkUqW%CqC%isJc)@#!3^LNN?d`2umZ4H0|FfXsYuEM8BjjcTz(%q#nQQ zXN{7<_OAvDUV^zad=K+|^7&Nke*VDCsN|%EUc{CB{ry^pc!7-*gD??t^FnGAr3T{D zI>@(a;_15TCY6p^$G4|^XXyhdQBnT4X;7Nspl^mBcI~oN%Ai*=;sf)ejR@4~(xt@Z zM~c_fG9TyOEz$V7dcSdg;bwmKCG0O+jN6M%a;nA9XY#17#33oyFC}!!o9tS2YSzpCu5okLIuNM_@xd{xX33KW!03>GeD|n@kz^b3RzK<+tw7WCs6^U)5F}V^eN>D|k9sJtk@b6eC+Z{OxYI+?ycIiTu%B5`y zP(ga?JJ)p&&{aVl$<}IB6c-XiBjCI8Y!Yz?CmoiB@#3{$Gle9iCtN3@Gi8`j#J|)2 z6ifLPOUc_oM7CSSAsuA94mcZ=N^`CoC#mp)JJnNvRkWp2z>2SR-8}{G>cS8&x*YKx z)VqXA_ju=yF5lCH`)G*21lTrIEEXW9aZ31QXeCY&u| zQgWkKf_v+jsP^nT2>fStB)B^*D_4e-6gL-7eypF+as@4T5#Kq6h(93V6_9ONT}tQ_ zikX+S6qi+wNl)~#4+_D)5Qv37#KyVjIhx5n6ns;bDMtuwiN-l~NWXyhVkmT@z)S|b ziDCZQf)_jT{B;SONab;GHu`$}u{zC9;zSYiggQ|grR5`* zaG>j84ze_kY{x&TSl5hFkZoZgyamzIc=q+)jrJfgJXK~PN~Gd4;)AyOmKgOSrk)n= z_BfXIy^rhfD7?z+hrP!Y7ukOn2kyfom|W4|;S3Ee;`>T(&0gMX#z<^eqEO0N2X&z* z5<5V{#jVt&F|OZ{!HG2mLq#FUL}{&X@Vf-o#x%YAtNyc6-NP>TtSN4!;!f5#31$#G(_Ih2#!IOdk#Zh zV;SUh4t4In(n?_;>;e3#Gm-LIoAyEsHFLu3)!-Kjb zrlKkua={-WwY3keyU5ZOX7NEr6UYp(c{hk2QJp?4r!gR}0Y1-{cty~dwJh&-t=XFc z6LHC;6YJ(nVaX#9+9vE6lF0;Qz$|Q!>-RI&D$>r<$8JbKp|{d?>&BmFj7Nek792<6 zTxO1>cSah6u}xs~VM4){j=Z8FqTSr$wGP6sO;v-b1z<4?6j`w^G9BKE=e8xrF_9E zET7TV<6D|!4vQou6 zK9wYWoh)S|1-u4_(Ybcs-l3F+FtUY@)a^OVd&`#Kr4cJP*P-&v__s}GfSq*@sx+Y3I|3xEd|CasQllcmTfsHzcG3@-;35O5v zbK8dw9SR@6v)!yD&F;#5PPT@YDSti;i@T#_a}@nKX~7~AH+Nij6Wnt1vkK%xP^S05 z=Me*X4z;Ag-!}>N{k5d)Pb3#c>iR!SHAa@s)6mXw;Le5ZCVYJ2SP)HvEd%%W$L|a{ zR!$hiIU1CCi;X)x|Eh|qht9)5jJzBm_yMkn2L0wo;lV4Gv zTolKV+N`NN++8$dT!^Jq=;9UK`W3yd75zz<358@1XoBGdi19gy2^3;Fzhb7jYHqn| z;ks%Wc$@xQHo-XZ4gz8A&k@VEQFh*hIix(}l*J98E^@V^pBw$y)+1DlzZV%tF z_8KJIy|_knTnjWzy4T8~gG%&RSR=Z#gq}-|jr(%v=UN*n#?df=&0*2e*cEdjnS2Ic z2|<|4)^S?yA|JB20z`ZJpr(L zqidWfCgvHfk)?;Oi$}!Nsw3xJOd~79*d@DStTD+|Zim{6wE5;sCtedv{RR6f^XuKh zyO{Ma?_{xBq8Nf9ef{9w7jt(b5w4ir+rd!UXsJyMVyi8%vt0_?0gds4-bq{-@W|XU zD)fxNdp3W=_J7+#pKf8mUgc0)cf4mDE`}tv-6I7a(e#Qq-taTL6MGEez7n4^H8|90 zh-EPbeZKH*Nz*Ns^b}V7^dH$=oBur*J^G)y=<(sVpL?rk&D_6(xd*%JJ3C)bzR&+R zE4p~r%so1*ux&3Me4X3dTKH!+cVp&Xxai2Y^-o)0W;a)+{%Ynf4E-w?{cqXae{#{q zxv|yRp8tsF4t|;$_%t;%{^?)ixt)t2J0?C3ex7XqJWibdzq#nA|BH(@PY<=6jb8p& zF4{3V(mFD}*7N4SxM=Ht^Kvn`5!u8wsyW~ZhzL){`6g2V|{h)+p6j}75UXgXJQmr_aW(ROF~U^?3;K0$wfz`*vNN{1c7FL`VN?Jl8g(*bbNT&vitVRS3S;4D>ermldT^8{CeawWlWZ0c-qylCs)qIXfW>o5u<{> zQU5@rXJRzc!|m^8?#)|w>>Sms5C!EuR`kdl97bL+|{o=I~(Z|=1aG0P5Xia*QdR!+ZlFNl#7JzE;w zr*3%OnI$~=5yL%_oN%@|BYv@+j?73pD^2-Zg*Lw}=u>UU0#V(subZ?k&tjf8b~7 zQG2K$5GAFV#Cp8#JK>-A_U`AwFgJ#H4Ynq7jOatRx`-Co=A+|f<+c&Xh8piB?{@?< zaG!eA2V5Y^tNUW~E0j)v+X4oBLBTADLD&uFL9?Ni?n=!hZ0umBVFri=WMl%7G(PIa zf^<%zrs0zMZfAS7_3KLsv`X$vYKvil1`==3%b%mqT_|Moq$|6UuYJU2-j+jo)Ig0FQH`xU1xWbk+eD*RzRMrp5~RMmn|^M3@US(SP!e zo8yMc!ELouVe_^JSHm(&kOANWUbO=Q^K4|i_IR7xLH3>~>H(!DkU*ojZu}C#VonuB zd&p&;PZJliR#sZvYbF6gag7KR;>b#w6)=_zs#2yN-Qi@le9&MaU0CfzJ{6la4BH|m zG?WP!s~dc2Bh*`7K5lt;+aS^-THKYMk|#qErH{UCbO~2896}YKixU-7z54noj7e() zwcMo$#L@BD0<9{rhua@0=(2HTeMluZ<3xYi^@#pc$p2jAicWI#ADcA;JvY9 zy~tRGe=SYfiCG_Ai}L=s`3JB&S})ztF8pOupK-6;cJ^@IpUs5yk0<#nUhI@~q6&x_ehbpM_G2~6 z?T0$C8g)VycLQS&a0@tTzcX~b&uPN_H0`Kc*5gqQja+QycJ3^gZ)w@!F*E!jJ5H}w z8buTlTSZ2=Rh{m+`6SictmZE?kVv)yWhn&B`WK>fbPdL1b@>8rQwQV$8sW2nN3x6vNAX_sTTs(} zkPhcZKW0X~Kuc#utNs2SiGVZyfl}pjO{`vE=;--X6HbV()#CpOc4R*;!U>f18)=Tl zjTckqZ^cDLw$kST1bm^O3ahq+bs-a%JX+?S9>1aItwwg$6}AUDvGV>!IQX~| zd<n6b6{+bju^c-nD~>GQn|dRw$? z2PMB`7xNQ*Vv&TKPM__}US?x|k<^2pK8Ig>PYIA>=~$h9XYTzhl78{!r#=0yO8d`- z6N_a_bOtZdA6%viziWWWGH0 zq+^+>^wgSwC+lf>wLVU`rN z?}#;iuk(eXtr!WmAe)8z>?|?3=OaKPz0G1t*NDaE-$ew5viZovS}4PH7yP*%FO=F( z16gYlnsc0XjyC^N*7%lUNDkOhC~IcY6=fjoxJ`gZOsyykMgfB^YT6vnymOBn8Ai7J zkhRIZ0)2k#KLYxqsfo+?-y&*!4x-6* z%cDuoP&+0&Ia=-MTi!UqW*nzgNB?K!Yjx*lkp}-m!e+)?-XkGg9%#r#z{enEyb}0< zQ?IlMzk*r`CF#y8G6v1>t4CD;*Udn~5%;iVG|uan-B2*&WVy@%8}8KIua~i!;KWzF zUwheH@K>s8k?`z0vAkIp%z98~je(C6#}mmmqQ2$lYg{5^p9z@#(R&i-Yc!LQp(w78 zeMG0W6^UIg%R0DZNh46R1572({mEIOt?_i_LG#UqP(He_C8+~lG0~pq)4I9^JUW@F zC=BikB$nlCNIOsav9KobvCIfd1@TYWfW-9OXYN>8c2`AjCzhvX%sN{(=#quBTeic1 zFH+7WyodMLwJUHNz+Br5;c1|F8vNNIuM@FmMC$BsfId zT%G@qjC>!B6Ps5DtT}}Tq$>#TG^5*t@jol5l6dT_O(T$O2DhlD;`dRr)aPP*J;(1o z6fsAihJ6!CjTYGdu08-seP8l>Ct^$N*+u7|j%$BX^4z0hAe^aP*Z=GV7cvHRSO)b! z{Ij3S+_J7^^lS9RpMz4PmQAanUz6|u9O6@2w%m+PW@i5!HGV%2@P0U%JNfg2z}&hM zYjnEALp~-MweCF~I{k8u{Bt;^^`OM)_vQ`quc@IwDk2nP%DxDS8RqL`n<`u+HI|%P zbVrR{b)lR24CLO>j`%rreVE=Q??*%^k=+qVj+nWbs=ouG7=8=_vz@L{(14APpK6QZ zXvj~)f7gbq`kedf&A`0Qc}D8?anM?0a}R*&izD;$4ww~3kv$U5OM&?#gt?YSWrGkH z>XNT|Li?DYYs11c<_&fS7>)qO3yoZ&r4cYNJl({po`uo|M?p`ZKE<=Curiz)TVT$D zxs67QQ=D#>efTkVnDV0N@z9zyin}|^cDVD@nDciC@C*?)bL;4zLYM>*AOHkgzw8%a z4d`lv$itR8+6>1CDsU>4UR|aX0ew77x3S=2JQ8y+$Vh@b1w_%o8g2!E@}kCbq5O^j z8p&KH{a{5M;O>aA!9^rtjZzf&HWnh}Wa8*kDGG4RKI_6u2plp$$TtGhHUqpl|0Pf+;Z*rsZqnOh+}6${3_84)@FXD>U+E5d#Z>Gb1Q2ij5;3SGd+j}QLPa&pV8Dxm zbBZ&p_wlXQN2HRRWGZMq7q9jo_?x^8amV9BFYF-vvj$nVC*s~sw1JbJo=90o_!x@; z207fVYsm|cXKzw4PPGW9Pl&lYVoco(wHF=bzm6h zmH0QTB%f4(v}-1lzJ zbtcl|BEs=_3Af-G<9)IY2=TlekV7R-bpY|73G5qQLMJzh%e53WAKzI+f`{}ehCAMJ zF;Icv(88ozgFj~LCEVWvaM*w
#*097b*kS3L1&cy>X4=ua(tcRQlwYig{Uxaw`( zBy*s1JO?W`l0fDmK&yzC5J8-rOK;&pNS8)?lN)tHtc}QXmIJilg!}P{zAV7jc!b#* zF_+O>J1s0s3-nPqz+7oZLQWmsA>f!+9$bqaH5sU(w4Mh%u|ftIfRY@pq+Rkx%F%`_MGRGe%cO2*mPK4 zryz<&&RLmq5Fd0iCsc|~3@;$X$A=#ez(!Sqj@aW)!~rKQJ*P@SvPs;{0OB<*oJlrd z+97G%DqqTv5MJJd@88H38FD>bwE0x3z>2%-5uTBpn_)045>%2i^{> zOBS@Q%Zj{Yte|r&p0zsjxAmY-bl6&Lw;div0&dmxXYVBqDK<3$RovhqjiEGb7avvW z^oAAPqJ{v~uV{^HSoM{R4asloJt`YlLK;7B)?)@XWI1UhrDKQUtA!djO;0yOfz`B! zn&xVnJ`3g>@)lJ~XauBV=k2R>tbJ>wYUx^1&oNecNFBGuV;813b%Ql*mQ><~@LIqv zBl}^Y;PlcoY-PjNkq<4OKa?n;mKv9D)yv?3+nP!m0x(F!t`=(>Vr*(2QYqvB$l^aA zEvYL>kTbhI+|{=2@3&v3tK+9(^BIwkM8ZF&V{cG(^a3cb9I9 zjZD+z5KXao2Ucgd_^{e<4st1<+J)0@B9oqh^KP&S*{^hLqKp#g0fnkMV7%AU^`Rur ziA?hDAx55KLaiRE*6dK#W_>{Mz*@yj`r6JLo}`meEYtH2x431fZE*BiS7lBa19xD` zR~gtN1Tf$q~USCn|!Aa$H%*ef*6#-si;YQZKjh7p=YKcK^J{?l(gD~^W`2yEic8O=a+ z!oV?P=QzlHDxOBf|I`JP0QzQ29;E?ra889!;A3ddg4P!ePkM7Tgen4}k}|PBt^hh3 z8E>WoYOqEdmnOQ64!mE=ZQdNhnVL*aH|eeS(<-nB&RRa2%>0K z-ffPWK$@SX1AZ~^SA;*_O*i~8ek`N~rrpkoym? z`|{nr^s+yU${8LyvV?u4^wtk1R}P$JlKssD=KNq@0po>xsdmk0mm9JO4l*ABWYac0RruHTgWnquNPtl^DLVac}Iq32D|kK zww=l4H31&(c?BsI4Zn_X_jT-q8cNzT`n@3m@Rwvj!&GhJB}YXmOo#x0e)sMao6o&zWy2-m>S9z?(r88_zSIh zI~=09{=BNyunjQLB$tc@Txp@)%R32XFigKy&8jKDeT%d_Gd*E5Ta%2*1V;J}*wi4` zxf{R~nzcf6e*kFtlby63Kb1K^pm#510ju2PhY!z39cHQt)VZEKgY0Nc9N$a9 zxY_`Wcd%csr#cf24wl9O;tuzMk6T>*i@v=|wvQ92DJ1__X zPppqg-%4MK(H&}3od!)@2BI$CAL9j&0VA3arxntd6<3{5v`pYSQTjSF9uu5!PP#q@ z=Ubl}z4ppGwTEElKE8cVi~~kr>i-HbpUiu5LvBWIOsg&=tG1UrajGBRI#&Yd#3T$R z+aw7)*i~cNYWr<3Nn_(kttx;wrew}&H`S^+dVv;vzr#YEp+le`yCIFNR~ zC+J+ZmbvTYx$b{Snpe6^2l>xutgEK1!StvrQS zmi&|+^P@&8Z*X=t2Y)I)&GdNq1Ko41;{~<|;dF4)yljLaJA~kM|L(tMbM=o*nq-(} zp4g*rKWl**%3m0K3{}v>{1q~s_PMN6P42O+g^->3dfP{?7kwFqzimhH9gJwBrVO`( z-WR(b2+nUX=J-YYy`g4PL)lN(x~%qP8rT1-G-RFdU-qgWQTve-XxUBQG1&ZwDqV;* z*RCRRjESBm%k=j3(MqG*=-I2IoWK#Mo5@W6A=QNNZ*EOR`nkiLM^7gySpVjn2S(^8 zhmJ|0<1$tvFe5B0xDUuAR3z_+uu ze0399xo!~>`m%>liRKNKYTwd0hpJRm2mu@7mIyzdBdEtJUWp|;g#UXe zvTUdzeOYZ%_&_t!tt*gS9i*PFYO*5|q$g;v#x`gDZG=W8a;P=Ti+-vuMKkYUAf&SS zcg{E0yb%ErT&9|FDwJu`zQAvU*Z3EOSF)!QStnXWnsPk7f>WdRAHWi-Z-Tyk<90ve z%kA%x2T9()^Wb}~@edbm+H$@q*M2E`QKz+(PCzfjfl*ysf(6b~;Ud*)&+l4V}%EkHL2xEQZH7FTaS*OsX`bb3Oqn z`qD5rZmL&BtG&oB5IXsWB-N{?kF35rXY?SIom#lVp&zr(e*dQ!OVN5FOz@AZ>(E9z zK2CzefOp-_=KvJP=wuGA7`C`mxx23o*@*M7>~6vMFBQpHp&ywBQ{1b4qOUx!8g$T+#g?68oExys9#FE8oyqs-)zH^{LYPu z7JwV?vz3}@#{VtHT;WC{_lIh`L+QYaeu=C>0T);6%(mWAPqcVYCOHP$Kt!uHsUUlN zAXfMjpIWq9s>$PLZzH`VT5uk!Un?UY720Gi6OE zN#CKoGYb}du311l-Rr*B&5dS9;w8sEpP`TV_uXYoXeAtN1$7xe0f!;$hhx*-LDlvjTuIgG%w4eo}GcWU2_h0$H9| zyuBuBih0djL8k1QbQz|gO@~jz6uFS{m|5ObT6;-g1~1QjxY7w-*msRAz57vvB5t1M|D7KO}nLTd-AG(Y9==dc)RVb-IT4+|Bc_GO= z?;H-vwAUa>g|a*Ldo+sW87JfGmh3SnOLsEMOjnJp=OF#0a-;X7=^Ijh;aJjl7HLQt zJg?hhPTN2zux?UDD(%Qa3@dH45Jn%c2|tUpQR8bmk%}ZN3or)#b})u<SSjDNt|l+4Yf!xC4_KCs0%w&#_*X*y zN3T*RL{Up+Z5zPZuLJiJnp z#^PMdzRRcm#Z=)t@fNuFTF+dwOfb)^#`2NTrbIFU5?Lp(&e?DjDK?nIu{1$!5q89K zZ?A;S?uH)4IfO~1rz{E3Te0O1uc>=w(i>!T3|NKwnk$%{8K$eN_b_swMl9u8Gat)Sts!^79omF!zoNL@Id$>5 zNEXr?4u=%U1X72FlN@^Td}>p(w1=k!3O{Z4(OZl;Hh0?u4T!Po*I6ZWM{n|Bnh(DH zfhRg}I)C-Nfi==h&3=b7G5X^xiTpmz8^11#3l*bJK6Qd$oakeN;PfJf+~aiamU~AB zGjQ~#<1AAbOVxeDS$dC}K(|3stwPXb^}`kM+r&+S$5cwuM}ypBMa4D@1q+h79(ehL z`)XF3=#E;LFUy}~Xya0Fn|J+5nly@^-wR17r+!ma+ImF%M7f=ndLSOvoPYR*5L=_< zk7Zk-sRJfj*ZN&wgrxKD0|nn3Es>gSJ}kOn+<+zYnC8STJ#gs(2qZ}IM$c9`z%=>DRPt*!mjh{~%FMJ_0-REVcb^`>piN?3;Ig4%^@VeJ_0{od5~^9sk8BCV&CxG6Ma{5&g1L zcJ;FbcQ{O|C>XDx1HY_88qum}fEE6;gXp|N=~F8Z(yDaQL2`gNxs}d_x23x!ls4A} z4)7hViR)0%<(|~S^IC?wTS6atKMi4zvASHyK{PEbzFOfJtY~Y!Cm3r-ss5-jcrzyN5mH;OAk%@p4fO-IB|4o%`Jd zS9O@389##JS0Bo{8fhhWKJe*p6Ox8K{!|APOMss|)%&_E z!qHjYb4RSGv>%CuZ-gEx?bFv2MUikafR3IUniFmQI|5Bc6i%-k?XBd5g^g`6khZ4y z@jM~`D^f2&=6FB>eVu=uygwbtFjmjX>H!5~$!d8Ac5*Z)394oS)P$vO+4zVeANi_^-eVl4*wktd@hTy!Q(nys|ZCK+}#mR z7>>wxmbc$gTQTRxXauy*0W5WpfiqXBBwpEFr!%r>U^yYrGwSJr5)wYLqSc|cIh=HY z>rtubgccF3RUhchH^G>Y&8l>K)s0D~fwC#Xt223wM#YQq`yn-s?Nq5aAP5rd&=@M} z%{Zw(a?7ks5^FO5EZ+3>z!5j$g!>qS=ZKO=DWG2j8XDv_x?K>})f16ADB9E@5{>A_ zY~=fM5V32*)9S}g5D+%Mj1g3%aWR~B&;k+&Nx>~He4?i5WQ~apXtj*1M~SM{!Fxh> z_*f!Fb9g1!FtBsv193k`fmiTud%)`wNYDr&yPWofADS?7WC2UN0f-}Sp&126fz*Lu z;miV(EdsUpfc3@{*5i8VN76c+kqa(yGsR3Ou#KX#C zQst41GkA31c67H1#Sa?6yo9Ky=9r+$$>B6))+f~wW%ZZ)@zM*7;YBiqSCz$1L62X_ z35x~2Aaa_SwzX%4ZkckN$gv`=!*SVQH<}?R z9^O?SYJWJy=SU`4{ERkelnejo zLy6fuSQ8EVjg47wS^TP=p63DOCV7_{B7JT2k zV6Pm`Ngm$hfzQ<&LA?@9AOt$#ivO}Wo*^22=klV?DC9Xg$k@23AYPX(VcAv}gvpE# zie2mV4b8KNY7zp`A->3`lxp!CnL*HxgDCeI<|VuY6H%fepm2 zm#98PdKb4LgFhV*bTY!7X+SZ*5`F-~bx15aTFVmgr}QNjkzG+MWig@}pxq0gaQ%}a zHa<$Ua)U#!u#FC>qfD7uNxxL28QKufOxqCx(yLRp5)v*dwFEboBlAMR3eS;oPk?ey z6DjWHZD1fCp}Kr!LcCDA{(MsvXC-6DV1;$&2+8?CM}e%LL6ounPvVPIH{0Zcb^lst z46G4d=cWq9Yq{10dXGJC+aRNjFYqV1&=4~IV`GgO6*|9p6i}0XZzB};D~f!pag9F% znqVWfWzURM-(m=11xKG71$$dK{4h1qLw2{s%(iYq2kBmJZFRl+5e00v?R;5%m53v? z9m(|~0fazTv7_!>_a@W7BfuNzjj7>ZKMJt(w>6QILSFYqmkw>O=fssgHxHUMK_Qrt zCLh6<(Ij1TNb9hj5*j%OUIy!R(yJf#Qp~@G#w(P!h&s`S6JpmBzt}hC&_`?$LD@<} zZ5;pwZTC^4dT7Gazzt3`st;|uf1bZM1grq}I5uWv0GS4l+g`2|NI(y%^G+mWeu~(F zn9{+x=$)SG$EQVuvA1V-5Ok`!O0KWA%h6S%!Mye(pSC#>JH(B8HD*iYu!zTfG5JiO z^dB+fj!sRqGfl9)@0Cs>Rc0OBCNxsu2%Q6qKnHYYGKb>vt%`t11%VT>~oO5%?_*K{H{l}{!3!+TY8Ip<84QQp<6@a zj8F;}%)!X6zend=cysGmsm#D(uH!{t7tXA`Qsm2P=Dx$Qcm&={OIoA|xzk2xlm#3TqbI{H)>CNurIBi-S?(}9I z29&B`pain$C66z)qwSgN`5t@!nJ~psDDMdzKPY_k%ys%@aJ(BThjNFPxZPvJEs-Qn zK*`h6Z&f74GoZkx#3K$X+mo~4l&Y{qwqr~3O>e592NTY@>~?Hc<4ZYxuaWT#GUIcl z$3#_ZPRfPn%WKPg73b>VqwJK(+S&7`;Zcu%xM;Cld=FR%@m_hR|Eh6(KiKW}^YB-= zM;{FeFNVA?jQU??xrKeFJT5pv%QtySMUCN*I zj&p}GPu6dLockk43FSuZbo<0%hTbeuq8oYU;xm-Uvfel7c2>caLX@;1ssORFvT^&qsEJ{7q4P- zqoq4Nqlhoz+gEY8J}$(ihD1JZSOhtW|0MFfCLMtJKKHRKB>d`somzNp(jF>Zah)-D zow83#c=Cj?+mp329~-f;h>o%_A|zl$Az zImiEgUwfA~@a1+tSj^3V&zIYU=Z}4|`Jj}nI0ECI;#K0xtv_FA&h2THp zciuUn>p_yRJS($5rSFTT6!AFNIc1P@tH3D%V^`;8Cy^?Z3^!=#4Mi4OPL?_RW**HD ze{*)QOPZI*S@n*{kM9Jc9ay;maZd31(vkWqky;vdjJ-uH^=g?a6YdOYR>nzL#f*`I-7(?hf3WfMUys$N+YZn zS7+PXwcJ26!rkyLnrhyTkrD%2R6}($x_6xQ+~7iqb7$fb9s=>Tc|mq%<8Gol0YBG} zVdJvS4WWw^wR{RS`h+19Mc|bKHk5pZ5zS;RgC8NZ=$-$Rnb`{@(+Y71)WNx;K#VA* z4`U+1E)s~FvzegRg^qksPJC_@v6+Y~R#V|L(Q2w_P8B$bm zgq7BoZ|2jhMHSOj>`VtbA@zixnThMXu-NoBl)kKaMC`gjkx20y*2H!hakkHK4DXBRo@B26|8MO7=Opv>>DK=>$$WRb`hQ6KwFhbcpUnPjfA!#SYxiLL_uk6?X7-!^ zF#G*~nEk>7vp@JT@-Jq;zP-7=xw^EuzOb>jvo^7{KD)I#^{*uJ=E~TwrGb9~_GAAE z>_?WCzAr3n%suG(e}Mh$+{gp4|8Kf}_5Y*m{}p3y|37v8-eCQI==%SNG52-!_cZr) zwe)w?|GTcQO8=j9ePc`Y|5evF{)etFuPjTc%>1vwKI}h$ec^us`+w^(r>1^-NHRb4 znExBFch9SOnN#7M{natE+%CP$CauIWEzdlq*z{xJQoy5s8T+K9q_#l42V)-{9TO25 z^Ym#|lP1p;|ZqQfzA;}zcWo_zt zUd5>3gE?p_@ZXcnd&>@PHnP5w!TA3r$z0>`EKxIG)wIFxKa$L^Y-fVbO7I9o0CqiB zQ%Ew^6<7IEz1z?4nQHoEKn@m7DjXDCVE8o$pZ|Lah;Fe7Ny=e1+`y+!?uYGa%)!BE zh}@C=`_bpC#dcMZc%l^td!9j{H^)0ua#2gbaQkH9_BCidN_&&@(d*&n`iCU5T^MJx zr*Y>5NKP8d^6uw)WCb?6$W;n~UGTCVIFq)e`SN(JJRQY(@8&tYU9H*PL+(jr9T(h6 zRzT3!c7JVN*vYMd2a8yglpzQo_boj>qd} zJ2#iFIhP06aD~D@_+nJ0tVVLy+3N-q9X?Nt=6A=+=kx^W8q2ZM_nOLXR54G)V18Eo zsVmb|w3(>B2wj)6W|hrDuqs|yo6YU^B>0Fju|}@x+?~8OveNAG3$av+AJSw!^bE~q{73|MQjyFhtQxn2XLc%dv>$9WDeEHW6wdiJ zKYwvz7mUopOuZV9(Kq_YB7@IevRA_Cicgv;^aK@-&-&J$HU2Y=jW}r;IKp?gAR_le zhHP=Q<3W{e*0;3R$U(6W<Sj4g>W?^r(ZnsUgRly`RHwvJ z%uu`}#ogB&$1O1{&*RPf2xlGC_uAySWS`Jm_sPbalDf)0CYmn#3VzNORm2_RW2eSj zt#;f?F40%UX@Q5epJv~yuMs8O1+$&Z}-{nGEi1eJ*vV$ZB@MNO#9T#yE?x9n@ zuhVs&C2@H&K84lmcd_h66-p~ciOp4`qL_l3veiU|{;ZW_4P`u&b%=gOm_WrM$XXFz z@0Gq`f3J56EB^lPB=g<*+)LE`)jvt*yUSw~3XLEK4fi3*OnDLjQqRG7^iPucBoK(s z!D9I*$$Sz-KAeLiGVnhonVFg1xTj`hRb-x%c?pXD=(sAC!1Vq zi0C9UEHrxLz=}{s+Fn(B1|pf>_okJ$ilu5I))vW};*1fh9|r5qc^l$(PMGZ&*TnR; ziXsOv9}^h^YO}JjeW811p7<&Nu}3kh_=v-60xKB|tKK9UMvx^$Po50DK7v{sE|fHq z^asI$Tp3FQ(M1(a1^^yza?bJ5arA6K)LK`kv03QYXIL8`cHb(~>QA9t1pH~*qVxhm z*2DB#09DZS87Pz#!O z3`26h>TJYvyCbP`nqZ+oHsuDKNj58dgp}Ud`j;QOtdQXyI0=**tXvhM&iFmZltv>C zWxZLaU4~6#4jt&QK2uGk?-AW_NXwA566BRt&pT<^aW8rXnE5hN$1s-AVbf2{umNTg zzN12%wn+tt`?&%1pr@H>@!9yV=$m!-5YdZ}g4ZF2)*49VxwL10WfXO>+11q{UE}dz zXXIR+ls%PeYNq*m^kDana;iGY+^**gj}HfI)5yq6_$vi)#c>4*pN$5tC1v5zIf+ws zjRsQ?`zZUSX3`u`vHmH8p^_>Az1ez*H@b;=3PE>_dQr{p+zv^Mttcuhh-XLqf>gA2C zinde#Nx5{@Cz|!0n6l+3_3c$Zf~Yz^Tz!+C>Uuy~vpO+lc#~P;dQdC2`a_}mFLvYW z?*^mQyUgRdSrIvCMnnQSWowwYNWyv3@5Oyy)>g)!Mb;iaPc)FVjRn`_uh+BQ$!;t z%0CAg`8gSC!!iRN-F4U7reeQ|l0A(i=AElYRSyDl{y^-TyPqJu>w$=89!a=blcex| z5$^j$Q=X8Y)o$LE#Pq*Qrz@D|-JM{{ zZRQ(6V*d|vP*RY@t3IjUPU-gtWJ)U&Jkcvb zfMpHq%ipUCl4)JiqNh1je!;Cf-c~2`uM&@sg^d{M&ezIg}N6CL0QVfT$Id&g=$ z-_J438~Ls>W8HS3pJO~8N4w|=b=^)dibAuKSbL|Hv71Nvl*Uih@QUt&-=|HhPA1u6 z3BwM8z-14RidSPoBRfY!=Sp~oRrT)vx#F=1&u4|2^@w7KI5fys3bgcdz&E$Sn(3|CgEU-0yy&~p$|&m z#xbzd1+z-96k>wG7g((YbFwCVdP1Bb=q%R}fHy`{{#;FO0u?f~QTw~fQx4sKveGzBc zIb57m{3~AKNOPRZ6XJKQ&eo_7;v8K=5gYKNHZeax@5?KD#=hVYCg0z$2#M*Rmd>HK zC6g-3;RLXPgRY1}41lNx5cMUYu{5+p2@1sy#7CWAQH$W`7hr56i0&-~=Wx+~1`vhw z^3DZN|3U)~=thg+5WKK)EGjg?q>IFGe<>hf&K(#?Iqyqj4}^`!tj^QXoDlBiVE$zS z&xv3u&2tZQ5_Ty^@8O0ED&k$tvyfIhUm3W7P9Kma>C!k^w<1^+6O&@VeVsQ7qD6SN z7DMRcZv+SP4Pf4&0;r43BluxzkBTD#?4()sVRx^{<%-~Ag|9j1%=jSwQ~LgR3HX;C z562MT`%1T{0Z=uwljMW@76nKviC#_P{t6%($i=+O33Ikjz(ytr=wV^-g*P%f$aD~< zRRLoOppOr2S61}zyKHISp;!WY!ruu8oEJps}Y|4+Q3fFecQ=>YKSr2bmp9Gc6S~Hk- z{4>q7+m`vtDm7lsF-$x>*J9C1c8 zOeHw@;WPnFT94obEUSP4n-7sSy^!^o7ky$OtJDMI3{N^-Kl>^*`=&8lhApM*Tl5`8 z4#xK-Hkb0`8geOaYW*|P;r~jhPmrjSuNlE$Q`8?7IN!f=hkB8 z!YQSwjq)OA@rUwrS<{~2mPmY$h~{6+qYuGo?aadn%ol9RmsFJ&U(7dno!3?sfLMGY z{au34s9?e>Uv;s7NCr!+B;W^KuI7!T(xL>m(PyZaw`|F0%`bWF6Q9k*pHL3M4ELy} z!~hSrJgYRxOO-rR_b(o&xetj04D=M2MM;|ynC15`p6i7^ls3BTfC^>NFloMiRbfXb zUKmRCNiwbkdH`tBoG=%TdCCTMTPz|DDMU_SWS-z;T1TR z49OLIB}L1OFDYp%$#g6JN-3kCM#isI+J;}k&kIIvOl{)eQ&8lVG zUvO$}O0#ls)bYzjzLX7>l#Gby&$C;#HkEg%0s%MW_f~~5bfr@zC1sJNT8>}q1&Unx z%1i@G+P;^3#;<7B`D)Tx@p8SmRJ`Q6q@pP)+90M*~C4J*A4SzF?x%8V*a<#0ngxFgsuW`+Fw{TX9AJJ)%hD9Y&XR+$ORE-`$_z|{| zP!j>E0l9;pbMR=~Qppcd*-+JaGNd?A!t5k~m+X%!BkKm}U&81r+$QQg_RR;3s(o%P zxSE02`(!3d^~Vg=^yy?u9AzQt()hPzW>G+JbHi`?Dpg25*u5cf-(p9#wiP`mRYK~6 z(_`sUsK{;O#kYFg)A}zGmT~(~T=AyTx6qhoXhbP_B~>%2Vs=BRR8zBLR&(<}SL4%L zvSa*~zNos~=Gz(N!(dXc;x^|p1Nv;hy& zsDNJ7#nC1oSh!>?{)q!z8wG6}Z`ym?=3Wfl-3M0Q!oC@||M=b7VbS(CU2QTQ=B?I_ z*+Pm@Can|5?ge(p?7E`d_Gp|Y^STWeb%AmotYe?e5Ktgs7}fi&4EP3MQp=23*VfAEPX~B{BOyoOFBh4tPDh zT#en4)DUuKAvZs;^Z`zyWbfm^dal4exZfacV6R?PmkxS=|4H|glR<-oR<`E8FJ%(i zW$4n>giy30F6{wF-$MS}@3qV1{>w1!gPsYr-j*`p0kA_%AX~*lvCrIgP zd!qo{dlJ&}2{7NJtjy3gWI{lD65C>sxf~FF^a~O0pAi7~L$b=tZIr#*cdXE&+9|)kF)pjqZ&McIwdbH7L zz7|-xbx_A$y}-;xtMLfxl{Rh~*!N1iiI!`+_KxLo6rX1~X?H7mp-a)+38B*D{E}>8 z8#Q&4e`s?{|sbbLB=lH6U4z}@}d z7{M0Q(ea8>I;*7ao67D>0OaR{4$<++9<4iZwbXt!H}ER}CuST3vcSCRrXA^A9PQpy z4chbkO@vw_9v~t`oe(vA-N)_Rza-^_{h)F93z=~hcQ=zbUL$TKApLtnMB;}22oA(@ zgEP3n^4wCca`kHoGsks@D}PB=+s0_W>2cE^ z5X&62o^BodJf1*1!5~IhR&C`Z9YuAW+>aijxR24tdK^Q<17iWtcg$R)5=6wOv}4k| z&kU~JcjN+3^Ix4&qaL54g4dMMe?!;LAXPh@%)hz$j@cd~gpVb~UqB^aK*219bb|-k4YD}U3zC_+z%r(Ay)5& zLQs&f$Chzp`AIKS^>bn=_c4J~9$*BGXfd8}6*$H}y?(5B#;pBEIPfBp zV44+aCLb{pYugoW{by=-yYN?PbU|Kd3e@wpTllIRCWB=qG7R9qozbhgyfglwvtx77=k+!p+7e}2)~8AV>s!w`E~UEQB)1w{QE|CMCc zEcbd|%K3u*y$d##-hn|izn#$(R4cBQ zyvKX2=yz6T61Vcs7W0w*nOxIrbjE)fdqFlYvTKTS`$_Ugr5E!DRld#Tm zi?sq|Nj~Z?A>j?$dv!D>qPtTQ2&1>oUu&Hjs(6UQXlcOMsLA5i)mm|4wyeuTU5 zd%He-IA82C%k18bzx6kUaom%?ex++N)fc;UEl%g>_b7clQ8ZkWL0$~v&4ISKHXj0N z{k^g&DO5fIOOjWDeV4Iutxr zc=TYa!2VXyCSI{;CZc|P<{dlzXK zx|Ms*8diC^o~^VwRr$j25u!oJ#8vC5=>Vc_JBIA9BoZC0)Q9fs%H)(VE( zI2-T|9&Hc&rBV?iwWHR|eox=v)_v$o-Txx|e5tF|g1^ZlNj!d$#feDN!K3F%d;I># zd1mL|(eipco|QZDPnatGNvN2nOuy0?TfW78C(N^>>F}m3SV^j2RKz14F`vZ3d6HeJ zBE$4^EbN_BlExx!RVt5e(?s~qNLzltf8_Gb%8;FO{x4%|Qx2)6ZPw87Z&kKv$+Ly+ z?@`~{O@%!Q+Xn9|RL3Nu4`gMVcg7hbm(t@lL&LafnO=$vGaj&6Pas1~T&P>H2&A`QCC?gc}VKNiuCO#GP0r zsHroyamQaHhByu7<6PNY7Nw#+nqVM4|EX?tLhb}g2xtLY)4Sv&s;_dR&?US6#uh4% z@+L~Dc#Xa1ZG6v&K`LUXI-e7u6-xf@&Fp0x$W=-kz+uqIw2p-*IW?G|_aP~ahv1i_z_;)eWj-eHgDC29#_^K* zZy^wG8?5t)Pp`h`WrCRoA9Y%eli&bxz{f~Dcu-_{$Z62BABg+2iZ-#4XAn6Tos2eR zmFL&#_q4BeTOZyNSw}%%1n(!Y%p#`dGYf(ZF-9PK)#_P)*a9M19TSkg-O*@?2zre@ z<*nC~MY47oXhtQz!iF=6%Ev5(zZ@N^_Y$i9*hEVc?&sO2=}n4$WVBbHMJyO47HO0_ zdS+@E@)W7IBr*mdcR1|7s>%WOjB+A`Wt?Bwn|g#bvrsX$iTdBj@r9hxs#8AWxt%Z0 zKQihj&D!Zfe3eteT|JLKCNp>6g4D&FnZbD02EX`RO%+ zFOk*OcnwcW(zfAit+RJUwZM(DUK{OM5Q}v}wX^qJ!==Ws9>*JS^rts9*MtgatG6%E ztoEDs`A*zh5hk-zDV>CUoP4}_&(<{OYe!!lhVoGx++yhC^ju&GSFW!-tugO`s8x8i z&6$I|Q+iitR-+0@)+Kj8y~}KHcg^4bxqOvSarqpD>HhIxF^Z(IVnUtUO$FGT>zf-C zYLrn{^|R??@)^vw=T9;0`Wa0?#^=@=A5aAj)Z`R{zJUp-PiG`h^-}oaYhk)R$ql1k zqTtcGpk@=e-T>7ga^G=B&I=PM?*@WD=kH#9qL|8-iZBt= zvC~R1vP@Q7^44f|jFr5q|8D)NOd@ozZJA)Cy6++s&1HV^z!#A<`l^yacJB{G*lgGA zX@<@Eeh-vvVeD^WUNGkFjbg~;cw4n3Q;dsi`zH)-obmEze}~1$x69jKR;wmjkNnw| z=qhaAv|N92ZObJqI{PE=E$~q6{RY)S&!0CPD6v20w&3M8mZU$Ou&i1ap5=979y~fq zqKA8{8M=%w-hFBcFJs;;E1=DRTAoOq(bN4|WK{C`{+!5g@$2$0o^Ua1Q>DXCb0#X} z^**Eda-Nx&cL=G?hOtm7ss!Sdon43PiH}lnH=dQapq^t0GY#q^0>A^LqN}`l=?eVZigVlsWKPZ*@bE)!*GT7PZMI(!P@^ZQ|@J z&AZRDNhT_OTrjx{%hRKL7xN2n$}9YjUOjyOt<1>0Y{z|f5-RPt@o4p`U+LZ1$9BIh zk=5(5@P9M*d-|(4bN%oB{F|{~yX7%}o2>XA-oFK6cVCO3W47 zObY(`SGAj+Jte#BUqzvCJJ6sV=!_kUh7|vcw)cu^s$cZA1B8%3fEl{ffOHT;Q#ynu zAiWBTfE4LP0TC=fASBe#i>P$zy*CMjUIYX|u+W>Rph!`alXt&+t+T$p_CDh~7iWw) zGIBXDaxpXizvp>I&&N@{qobaogOKQGBzvG~J%4TN8++(TJ@7F)-4JLPbDWn#yyp;| z4l*VN=PNIC2}1wA`B~hhKRfe=xr!v zJd{QVPwdKzVdkdO4QH}N_6kHLo{z@~S~5wD(J^YH#ZQS#Q^LIpG#7J|xOaJcv!c7R z&}TC5GO_hSoq3&IS?ELqOm~*%C3vE8C6BLvFFmPG9Zb?-A)y6HnsOv9ZIZSnNymkx z8%VkmpCuFz3k=te_|zAFt5)+DPucBqX)i1DsWS|LRX|a;p<}43T8Pdx3f#;WbY0phdAbb^`Sk zRD|bD>CFS2*_x(Xnhp-yp8!H%h{DOSz`WOVKinBe0--&$sb&1H+~dX@stnE;TuH(a z{jUwA5(e)_Rfg{3{L-TPf8jhisBxv|9~BMSg7HFv7_U5<2lF~f?l=V&JMidIeCM%q1%|j#E?O2?Ua8iDgQ4D=7+ogwP1emcftJg$+v%>%j}TFl>gYutbX~r zeMB}<{>xD2pFYa(JMaEwC^Pfl4rTr=Up~F{aeQNW?jKv3iGMXw&c0uG_3qu+!ou+U z{K_0@d2ZnExy;`_%KtK#`9Q9g|D#?0cA{f`qU(QeWhMrDre``QUw;~`o*X0n!$CNe3yby@#x!Om8K&G}SiNSJhONKdUb&FE2}J?oMp%CYva6wH?t_tz;SHLmAuDV)9VNhL9FQj+oyIyBmDp z{~ta|v%~`9_`JW{y}8TJ2hEAzLN^8YiGky82Zw=(}wQvUY^^W;2s zv&9K|7WPq-{v;%$8(qoyB7K})WJFj?fZ+2~)W0byshZ*~TWLg%v~@kOS4aLuNja8j z-Joe7YLWD&#+7ETWUVO3};P&N}^_N z>Ohy7$a9&x)j@(fo6j}N>-HT)a~Z=jX>sc@zQMQjR^OHva7#deyaIMf1doP3l1(#B z+j9H}Tv5GXdUuUnFsIv8Y%3Ui-ih%zU%K8rybe{DwY(vH*n0)sr=2Dhu((qegN-}m zGwJRO9)Z)F6!Us-jZMIkOtc&JIv)5!Q~OSNcki5>fgqww#yk3QZ!iBugXiq3mR+8r zF|3Ul3e0UHlXhkLMT_XV$qmyeI$LP6Bm{qL(tJ`?C;!nNJy}VKGSK1IM(VyW#SmxQ zU&m8Tu^WcaH_ZbI#nhNI<2wOCA2g}ea9>Zs|cg|-ru#}d;PR=q5QmMt1 zfKuw=?d|H$L(gL4<^|G+^QZb?uS(^&oT5n$oMHrph?UTkMyhR3bF$oM?Njr+;Kj*0 z%55{dI@fcaK!Fp5zDLQW{EFB2Ch|8vcOKB*_R*Yf zStO3WXU$TpQ3tjDN@7XMM47NZ2McOxUW&Sq{&uUv^paJ#t_?bZA<8O}zVF~`7ZY09 z^eIY0&c9z_v(l>WYpxrrkJu<_cC+Y>+Y&Q+bB0{285b^ySxA2ay)VJrcX$={`}#TxMkGuenUH#2fLy<}#}N z>JI-hmtns3*jKCR`2Xo#=KrE#u3g9>9;SBx-IXtv9oV8uyjoklJ5-1*b>H+nu8mWR zMFb&6`Gx-`sla4HOMuivB^iTTul2+@FXC@}iKxDciip&z!PB@THDRm-qzak|S znJYNF$i&GHA746a>PL5HsXf;&{R7b(ucB=gz|~%5RmbtK)@{Oadj(?ITJ|} zJ2ZJYwlJmxTpiiMf(tb7<85cv=AM~K3NyVAT!E}!3NzGeFqf@0&ApgN6LFQqq|I+p zHlA8+3N%#r(v8FOllZr}1K20yvbG-CHbOtFV0qFABRp{$m@&^_gW!&)q)bo~0 zVX&CRn}y|>$Ms1F?y(b>dxL%}P^r}rzRgdeUn zR9Co2jxUORbo5-V1PkN}xL7|e+t#RTC&&@4YN@5;rC|k@sn8~*HqU}NCSN@140RaU z#|347u9N)OI86|3mMR02Ik%lAW%?q5D-k&x_r zv}<|bwi0cu{+p;C`fPaHdXHNE#n0|k2=la!tY=)w-ybkbmw4TN2aX)P>$`UTXAn*W zvwS0opv8hKa|d^=@NLq9r6=sK`kt?+zYxyO?>saR9cPyr&|}yIX^X=dD--TIrgzg! z6^OFtT4GC?gbN=)1zKgUMrvH?RFfRWn~kmVlIJqEQ(}Y|$!?UlbD#GAG?&R}8C#bM zI~jFkXvi8IOFf@AKjw1jChPRr#-)yvvvL2#hTKiVO{K+?iI9ngXGde3YQIiig)=nf z(HL!MCf%oWIbeeclTWb}eolc!+jFBAf z%{LfpCn*eXx6hOu@_?(uscc?yzG>|qMie=I(%V$RmVL2jD4+b~Fjz~Yt3OqyIx2V3 z9m8{?M!x|e%ktUeSMn!xTlO%<`|{4g@}W>FLND% zuCV1z`jT^Y8b!k|X^C1t zSCJRfG=nP%E(4>_>CVWiNCX3WkrB`6vjO$7rO%Guotq@z%ac|d-%`a$OWXg9xvma zN1r;L)P4#$_wx!s29C0(B>auS6>mr%_wwCDMwzP^bA0t0RPRPI16M8!0}Q^As{9`C zSDzT`F%JlrI5v@;8t|l$sgF?yCF=ZZn0-vI#bu7&_Ses2`QSG3nvBkRQHnFf$ce9i zz7wIpEyDRunHU^IX3XxL=^lFlNxYQY`>iyJrptk!WZ8c$4E}8DQ1AV^nDFa{nl1_) zVfSl}{>*^Qmw^H%y7AbFD%|!G9Bc-4bq#mKglm=13$nqjkq`(GViG}RogZOEjIdaa zFkcRLpo-9FwpWj2%hsSH`}>UdDTzyw7R!++QC1la%tbv`foli_UFIYL!?_keqNAUt z-h*l+!%yI%Ad+?o$+%0P=Mst1x`wb@@~1{ess@|DoTyWY)Sl$THz9(H18YeUX_ky( zsl&+ZLr;33t|UY6_Emhj)kCcR#`!R zGF%#3ZloZA9weZ%WJrH_M zPV?_^Op%a_=xen3_h^zqv3raqq5!UkkvlxrtTmnzfrEup9-(Nd5eX-b46!H(7Y*Hd zGtH7C1H#eo%$?TNpLS=-e{Cq1_l0Yi1{{)~IPVe;q2gQ8;MvE8Q4#5zW$vZSCA~kx zF>1BaoaIqL%Hqd3Vrono4=w?kqO@m79!)5P(jKEL00(Lr>X1=&$dsZi(7LE=7+Lha zPxrYLAjtu5QB0?Lk7UllpJv%G5)BZO82|y4pO>mRl&a>DrjbpEbcdc1#7uE%{2GA! z9{so4z_UCktd{C5kLHeO3OG64Oc6^!;f1AGi$w_-xN0E*+K^o8eX5xNJt_2%Cw`r6T){DHhb&_RMa{yB z-nIl1HL_MYa-vQc3(w)qb5wTx85aPsZ4RiQhvDc9NVNC#a|m^n)hLmk^0~oOc5nqf zlnvaB;Gs}LW{JC|)h4FVGIa-)^?BU$7zht%p(eU1=5xA|orhV3GE*n85$ds{TW*VE zg)xF6zof!Jmx?kO_kkINB0xrHsVI7cMq!r#e{f|vT8`ARtDCas$|2i(3?m8Pfq%g>s9%2X)D9 zUaDjNRdfDoJxs1-?scsgU7ch{&~Ms$(Ag-AQn`V8t$wkg`cg&Jet82Vu%76c3y-T> z7^(Uo-Uum5;T~0;T%w;sH5C&Y48t^77F8QUnqZB!;`db*mgtH&;Uhgwkj9#mP*s~2 zI5F=rQKQn$OJloS_4ZOUak7HgLmlwRm+ZBC0>INz&0$;`1GFt~WTBLZxF6@>V1-r+ z5?y1d>UTxJXQ>t3NJ|+JF_#LXB-W`QfxBL9f0$c|wY6_Bbd>om9LVf~IBlW4HiC4^ zb1r!OVmpYGem5B>OnYw36v*O&r+an$qM~UmXV0hO_Lcw=I$C?5s0%Bz6X>{|IN{gH z`p3o2pB7y%#7J;5O;SWN)tPh!(X?VdPCZ?}`4O=zVZYI#qo&fd`*fAURl2L!G;Zb> zS0yK08}#zm-A)(&?#I8l=B@)Oqc6W>T0$dQ9kN;y5j|l3m&C~q$PIN0?oQ|Z4$^4) zSO*843h}pW+pZp)%CE+bQ4Z0QW^h0+_7ibWs}ASI#-!3ABFXz}w0GZvhElrimQ(H& z7kmf_q_%VTdsR{;*MxfY?J;*UaI^6nwi8Y1D4mEAPA?(oZc-fS+iRkeblV3B;AE7; z;0Az<@Bg;?(jlVd3j7>-CG%i` zB3sEC_i30)niMPv_2GscsQ?{xui)=h=Oo!u<7kNdFdr4@x*<@=30HVG_5Ss^Gew7( zBp~sQeeG7$yL%X(e8gF0g5F}m@NKkzuOQ*m4sI>rv7=eXX1+6|jov>-a5 zr#?sm_J$lL{=g^r?1EN%i5F{UED-mrKYaPI{`lX^fRBe@vAviRn)Sr4S{wfkp@ zf*#iA?SRgBt3z@Vv~Kbd|0M15bkO*P(PZHl3xG)#D{TkRrov7forqS|)P6FMTsOU_ z@-`R~4Uj$J`;$=g{LAI^998LVS8A^fAjzKDWe7+e27=zbVwzeoB&OfjSR`sRhF3AS z+Aln)yABP2x}z}gsYMwx3}XOqUIL({iWvIM@^Z0-qzVw;y;I$P*Gj*Wga+t z2rNATiaMs5_us3Ty>0zGtKszFtr4%Y(rfdGx3v4ckGj~eb7e#G-+X?rQm@MDk^p?8 z=MK9t^~+x6mmTYxL^l-imRL7W&7ktGV#$(XhGuypoPUmyK{X+4);3~-20i;=`7Nsy zpqjf(JM*4MT!Kd|3;SM{csgw<-4XZ@;8kN^c(?L~x$`OyE9x`w`!~mMShoWOO<2O} z*y$uFwS043D9|y1(I_fT?5Vwnk~gpNH=@Y=htRu0o_cy z!0jsb(Mo{o59?#!x6x|swOS?ww}2N~G>p0Wl!0ubHo=D*paes9iIvy$bN1zkXb#8znCXE2-%{QzE6^=h@6 zRb7oWX#z;DW{+M3{GYK7w9&nk=>P7^%Am?Be`An7`SajvQ?u$`7t;Vk0I9Z5rF#PW9rX>j!;CecTq@)=oPe;PGiKBT5taaryL5PPfv+eoL+ zqVYc(KC)1sDc__+WS=2MjS-a&r=gL*sQ7=IqmSv6zaq>ib9mvgXNHJ8bzl?zTOYAz zf;eED+I6G&3{0IO_M6t|nFJjAv8g$$j{wSb-U(P@Nd=V(*WdorluAwebkqhPu zwR)OZdd6;;_3*MbHX1^CtJTwyh^9$)%H#MS<}%J-%-tJ`iX!ft2E&E*ZjU=jBtLDG zGhHD%OG?wn_YtOhl!&ps?_?}LSy$V4J^Fht<9eMZHzJD3R=g@7WOeK=7Gg`hLKj*EJdFq^} zr+3RsJSyWH?qw&Zc`e6TY=w^+Or)q*lMX|XAQ>Nd4keVk5o%Q9cq|SRSl1oNYdd86 zNnbo56Ihzr6-B3;O7|a1O2*X+wgz6q;Q_~`kg76A7D+MHb2>8nnfPX9u^z`f!=Y-- z*rN2+3oUErBBPOUzRF@9+EBTd068$4+Wt!_pOGd-BI_1pCBjhoD~b6PWc*f%&`Nt) zLT1_u9ERCAle{ZRm6jo!oWIV*^zEgJNO7Y%%#UkqB+c$YV3Q)GU9fm*`bnvd2$xd2 zcAB;JmKsJzP|EV^?c%04n``0`m29@Rel*D%+4)@zSB*B1LawcS|>+bOHESB`gFFSLf} z{7fxilfH`^;%tdMvc1QstKgIxs&%ze=tyYWQd_Kn{bQ;^@lY#%E7YO{&unMzlzc__ z9Dno7h0$9XQT9F)Y134x{92cvK!;QJ~oQC|89!##B$wBO^>^m3-S8Bvzg%%8_3F9rx#00{8``Mqr(&q1@q<76k8I7$cSukk7Yu(8eit~BY{kyFJCc?o~ z$~cg;CAQcmF*<1s6YXTao>*kQQphg^wjaL>Wfyd23VQlgFcp#aOE9ZRm7^%M!F+D@ z=5*6p-B_?G{j-?5N#5G_ z$1WEE7bXkSTKv!-mHdRpWxNL*}DQ+OhCIF%%eFz0EjSIz`&>zdw4|E5Wq zBOP0$EE$LwI8)F!NFiw;W(>|d)$?Cq8;BA$%R%i4WnRK+8wx3AU!88~GH9MozbugF z6!}`;n`h1P-aCE$sF~9ArO}%;;F6~$2)cP-5L-t~p&1ttavdRsoF~rfKYN?vN`3Y^ z$8Lp6v%V~A;D(tyCkII)i7bWa}C1ua7j=%dZj6+Q6^@)lAM?MN_>{Fg{%(KRjY)M}92yu#}+gi!js@)`7b@b|7AZ)Z+ zmizUm3TWr!GLDfP&I&kAu3ORKmEa0FB3iS$-aNzmb}11mX{clg?@bh}J9A2&wdPv{ zblSAhzoNX{9JH)5=UHnYQxaMX5m@$IK~Fg`9}oHzYRr6)@Er~uN;r-%(+#Gvj{I!k z$(2zI__feyR~bZB*scteJd;_jv^rX_N!O?pYA}+JdMR@wBV1N!<^o+X#%X3HxJ7d$ zTHl2J+v}XlbYXMN9m9-OlPBJ{#a@*?(W`CjOAmLu`=Q^@$zLhaQKk3gANyfAB7Z7- zXs25~nN`?<$-H`PptH&&8KToWlD=eAa?-yS)w^$-4X=`TaYxFq+&1;V|DJq37i{p> zt!{XWLRNYejKV{o*>3>b3*R;~G~K<$Ya-EYk1jQw=2UwM+AW-vK9fd61g6s+huc+k zabRNsSJBiWe5L+JYtw71!QZBYGxWcOfg!UQr%fp!P`HlmEyhbN+2d3JF)Htp0e(Zl z7OQ7^2c&%Z0PyOg*td1oiN&mqj?F@%g0kMd-0+~T%nG@?LOJjElX4CU`Oa#uXnq+Z z7_BPuzgCFRb)vaRa``%NNm0zZ-NJY?H-}#|H^6}7hk^c4q428^UG)tWfWstegotW* zVIKo%wYp771$Y^Pb=R^(-m~vV-l0tZ1$A(<2Yvq9h&&e|Zz!XUp{Rz6E4Ki{d@T zBjrh7IcaK2x79##U;yg1~PrqQ(56sRj-p3H4m8M8(s;{KPI&snsx_O^MRj-m~$!<@5Hyv znLn6WF4a@|lVW1mv8G|trZ4D^l|AJgv45%Tg?r8a1Q6-E2_w^vk$!JjJ|M4pdK=s{ z{`UN$%2uF={+iSGg8X;fk~^U?qN|u$2V>IrAJGOyjDBZ7(|!?;N;6IDt{5{Tntn@w zs1(C@Q;X+2*3zot!wfeVPH7){h+bu<3lO}YQe1mk>A(lq^>ZR6V7vRkR$cW6LO8fV zv~bSp)ae25&-8(z*aP9rjyJPOwT*ZCXNASYj<(b-=}NYqKyRGKZ!f;Yplj-To_LVSccuQy4J1D^upuABrZp3DHdsM*7hkEHFKG<-?#>YK1h_jnnzuLA4aL= z^irAvy`DV~wMmS*T)%~Ozr`9xVi#i_*l!cne`P4zwy58(sQ*fM|BVOzSE95Bl2J#1 z76w<6tygT&i{?2cy6h4?QBW__f!mESK`5NV-A?W0rkj%Se5rVdcO0WfJ0YC?7$qO8 zp_S9a6^H3~PX}}3#(9Ncff;r0qC}@O{1@i<&#kCr|7=7DB5*i2D@$d|;!11}1k-~h zcgPWGgS#m03}l`$OC0=8W^N(uEaIeJO{NDcIuxOx7h?D_x+rn+Dr}D{?za>E^+=-5 z`DfYgLls;@_#TMYk{(#4Cj_j&)x+-A03;~q9@lEbXbffp!>|!OY%3%ij`hqNhBppB z$xWl<9I1ioVr%tIpjTq{w45XiqQW6wdm}|8`6zE_bfCc|ayVnCYFUDAP68jEMxeP) zi>DQN-lrbp4yj4gFTP=bMP5xIfD{QBPsyvbts_~W*vBmJX1U@B$ENMt8vIaS4oCVg zW_-u#h#zz`=X8h|Pmj&U7ehzbNL`M5EnEJqUuALY3Nl&O7>s&{GQFXGJy*S!u(d3s zQCn9h0uydk>S1$}&m>`5PfS|^Ng6Q(qs{}!qRYtmjM1FJU^b|(m!mROVRTzmJqAby zMq8Tl#s~_=HHH&o+@m35;orQC-?UC-Iri0G>!=dIAB{2unvF$(R4L(*ZGpln6{v64 z_#TVNJMWS2F7%i}yy`(LLz!ZfyZBL$HuiX!^0RU5G4`!DWU+G`Gh{?zl*6rmHFeT> zdx@?|1u8WSqe@5qmcx1GnbLJlMwn_G8$t)U)aiL*Pr_htwBnr$2ajsaVwQ%}dtS+; z$QjV#vq)DT*ER}PjYibU8G7NAuHt0#rs{i`(jMTK$E40L58@rsSK|{)8}YaTK{<;C zf&Ni1DCF#(sm0~HvKRtQn4StI+&qdfEyhE~5ri++>#jp;sfhEOEa|H}#dqA7Alp4X zIiPYK;W}L)Y^g5#sjjjR9kUQVMkW5f7=CDn$v_ofo+j?8Fr%&0V3uyV9Wt3-I#GXZ zI3;{2tq3PxH5D7Tu!)8Lk#@Wm0G2`G|Gfr%%Crc}kQMN$Mu zkAYIeTSE*6WCH@`q|p2%ZunC{m~%qnkRh(oPWdT^c5Ea?Xp@cqxXnDlB&)}~H*4%H z#eeSTxD`8Zmb1m4BSRVe+ZyXL|3)LRp96Zt68|QuBqHR^Ziq2f^vctrq|%+px4V>4 zt#bsQ1V(w7v0?mYs1X(*!6>w`A@h(paha@f(b~69`fW$TXEQ+Mz7ZQJQGYvW7h;~adTlsN`lP!((zu|@{RS1d^UZGeR?_FaGn zcOg(Z+O*R7aqnpn(zcG%H?-H^P5ih)TpIrj#~S9r5wqvG^>gQEVPbF9&SvRnvHtJp z6jW4C0O<3DU) zc(>DZv!Q1yb4w0H3zN?!^kUvs@5MbVECTIW$3Q=Pr;p?I!Y`G+CWU7cfNrk3DK8${ z_t~Y;y=zP34!?iI26)4aS?Rb02Vax}&x~+O;RRK#*U#tJbXLyc-5qKE(86?aFLxql z=e1fauP@TY4TCTt2G@WR975RXt>caQYbm_%5md>ebv<0txEG>%Z#jeQg)~;U-o#q+ z;H`DyKO7I>K+3ek=dr-cS`;QE$F{T5_WUIWp~F~@3$UO%^?szyS!|vXt<&{}<7S)4 z>oszbgjSme)Xp_}&gmR>BSWiL_u(Ure9VQoOTopLo3Spm!!tQjp4X^KW>}q%A4pKGv=o+;UBsUu##5a?Go!8oHJ`f92Tm))CNhFtlEUN^+cd z_wnKSMd4)$uGpK#utEC-d$yzq!1;K~F-H{Q^{i;i^?kCa8)~B>E5t3fmhQ7a-0+SC zmc#aG?d`g(%8+8bmFcEB=f{+g+d{k-W<&8T#(3plRm9_}vk&fLjs&KKCVULm9n*@5 z5S^#uaaR|2zooYI;76n*5KX{sKK8|U} z8}_r2d2Bm*Hw7qv)skFY=8m0XLb_>*ukxtl&P{sAtb|hs-_}-pm-5Idq$`;X<^XkS z$$Uc+t@ByGlXxKeAx+xO1zyWfV@qXjj7CO zd5HP3_C2%qFgc0vDK@`M)Kapj-JD)UZ2y;&z2afc{B<^^V{2HqZxmI{*Nm(t?)(~^ zjg&JgwctcQkYhNN9~d$@3*JmLh)+^(1~U0kt`Q`H6#0dDq#<{mo2(EgT;anzo?koGxHv+KkUs5#Ii6}uS zL`p*UFyrK>RMT&JY+rYWoiMGp=8=|Ih1+Lu{Z%VNZ|*#Cs(~-3&wu0b`-au~j^_}1 zJMVMU1$4f(gB5io7B3$^x+|RYo$4HP%m{b!V!X0>PGU2GKA=lK7JSBzk?76eytH2c=n0F?<)6{jk z{clmno-@v_y~T%~j5fFK;dG6^&J@RE#y9EA0B2DyJ?@R0mycMk+>5$q+ZLR70Eg&3 zXE;7RI2zcXe0g;D)xFEoFqU`*{qi^DTBZKA!lTH`A$LuVvB2hWUL0XL#dH6NT5$gk z-(lP!Gjt*uaVxz;w~J77>?v}BLHebH*lnV+DBds?PX+H_K$^l1$t}UR9^Z>?^%)-T zaui+V%I|5`Ri$2vGR`vc%nN)zcrWGgSek0`riN|oz)kM_;%hc-a(mzx>XydgpiGXF zOh#<(J=~iN`sY9D@y~#~J-YC(b8{HTvFtXqVfH>OUHJ^%YF6MCRbUlJ^X^ph*Wy z-|41;b~?f)Td=R@eobGFAG`hW%&`_julSQIKQ8O-5f%elNc!;B=JZm_!|ZD&qsD|S z4Su66c<^(8%f)GjnWFzFYURblHIqkK*FJN@7$-6b?>#(su2bw@eANFH{N?MPEQPNU zZKoHzQimO>*d2O4*_L)+t`Aw_ht^QI{28lBa zK$?*n4f=KqpMUw}v_Dl4JN7vZ@xH}|NBa4qQonDRBO03*x0?=j7nVOT9pB@B?I_!P zK1rJ(d2%4k54IVGVSgTfOOB<71V0K@1pBRibwKE{+iNfJMNnhcQhjOVOL8MhqtTN9 zy@3LMG^;_>Gh0{?%a|_Ptqn{JSxH$Car&Eu1yA@bK#&n@KNg7Z(BT-1rFG(1y_wS( zeLhL`=TIgM6Fr-ullosuO8pV`51P-ZnR8OEv#wjDS=rqe(z_yL`Q!|LO-&w`dNWpW zBg?p;1-R={-X{FSCnF6hh)CEJej2oJUj(hW+$Qq;VY8xh0?j@WKt1|PNvRi{En1kM z6w8N!yB>=cr`v^cU#H1thkIm({uC?C%Ep`e=tPH#mzM=oi)hMEl!{l@jl^1*H3_k- zRkrQ4SLn#Hd73&Kep8aH>z6sOzc(P>QCXSHDHo&BC9Qm+>G`yPX$cLh?S+>2!UlMa z+YC{7jmgk3srHcIb}=+h$uFr+Z?+&G^dMC3cIU~?CoYv6<9N8{=&mw~_#zpUcx^^;MMs7g|4^FR3)!`qG0u6~$U8Hm_NaEMo1B^x24*R!|}@B|e_OY6WL? zM=e1xS2PvYitpY~dAZ&&f_4_BLto?zgmRKeF_K0rwCE$+K;n1CjK5XYn^{e--x+N7 zVejQ(H0KIT$CQJzJRqQp;6^*|=j*{X{(h=QHw$v3ryfyG8D9SQ(8i_F@@UpgHvJLT zqY%yTd+U-b3Ci7b*j_a?#dWh;Y=ef7O}FBvqEIUw6Bn$ew0%Ck_A;cnqFYH%4#gdx zSUIW|rn52qNcjs``o;Y(UBCV)?-A+LRrdS29;>F?BHcu$c~Ezw>?ioeNH z2*IYFpP-tn!?Fwv$;}kt0-#{-3lhs4r%2#JX|d}AD1@%7Ai*(&pF><_lsB@quVoj_ ztuQuA2m1ySPJtp!Ds!1I2(2cUWODVCi}6)Kg6R!2Ya}NXx(BV($}KH*S!ML{i2HzJ zUI5Z_?bc0=12z_Hvc$u*!pizq9l=C*uJFJcEHpAYDzWZdb$hf!4Cf?x1Xhyr?D7P; z*b|jPJ-PhG1Vy#PM$A&`(@Io?#4XB3tm^C2t0x}_Nji&-+D@lL`ZNwJvfLWB^Q`q! zI1#+4)jC98h9*YYDz2*X)6 z5Rq{g=@hc1rFsV%Wo()cb=pD@DNJJ3rV40?qUe(SKD@3VSAnU3u;PwJ5+}Hb5=N!L z$`mV#b@motFIMwY8o43tlBtyLqRmb@m1``D{7)xr??0TdRFpAiKfnDs+5dC0_xpJN z_wnB8G5O2a-^X9hj&^?k8{u;LpM=YopZn|oCWQTqaQXFh?O!05oukhy{{!Um@t=^( z@!A9#a`{gc?8k|}Rj~hsaM@gXz4dWoed!IEa9RI2IlJ^>{r&jLyVw74!cP3{g#8!P zg{+1BA5oWq+1dX;oXh4A*$Ml9;#|7g8{bzxYMq$+A0U^(e}`OJ$wJur>W13NnrbrV zl3!U-miqsOb6I@M`cKZK|B-oeQbJ;4Vr*ReKb^2xZ1n#LbqOM)E_Z$W1HJtM|3+O5 zVxRvXIhVNq;9OEsAxZz>ToV6{bBX+$bIG?;_w@F6b@y>{@x0-9+s@vlKv9N_y5KG; z{nG|(VR_4hOt_fY=^NYVT(uiU1HVC7Y=$SCPZD`=xGYhJuWzR(xs z&}0v+gp8UPN|mgF6_HXFCgUv^lmsOe1tk>DODG74T}Fz^^NGmw3d`|GDDnIQa*6(L zov?LFqF(DOWQFS|lek!<7E@(Rbxtj}fQ7;7hOeVS>I2J>T>XZU@h1v*cis&*ym<9o z1H)8Q0({`jmzNi?|5wOmHu7P$=lgPV#<~B5T)d5IsNW-4H^wVbK9sJ}5~YEaauGi7 z{{gu??D5L-y(rp4wJh+TkPCXiJ7gxOw)b#m{o%EVXRiY28WLZ(PArNM?nYOwUZP#^ zYwF#RI>iE?#{&*m0#FIB(4I+RMMO8YJ8cHV2Kop9FArR^BC629Db zrga(@kY;bs#&&=}v`=$ptj$Ds*RLaFwgh*&DUbQrUdO=uKi(BKSowem9-+sqA|0Iz5e(Uv0`MmL+@;%S=1rg37i zmghAkfxuF74eX~7ntnyZ(h2t7cC$Fk&A==jZYDl;mr0d&I#uSgwT0L-yDO#6;Ojr>{=NG`X2QcAeEZ__m7qM>p?PF7r+3ZqMeVdKCV5@I;sXRUc^0{__>$+3(N)!wEZ3jXd&bgt1OYQp!{_%y}n|gyv3;T&7V}-m&LxXBR_mjfmMMxU`Ax+M21e{@! z0Q>NeuF|(;LVS@RU0YsY&)18eFgQw)b7`UT&b|!i_(jm>iK+=n(tS)gd2>aBipujB z&OBXBbVXEq1aZh5x_rsP$V3}9?MGtd5MdN-Fu;3{oH|`ZzcWixEAHcMf#W3^SQrk< zQtnYN>#D9uD@6;IE3CR_O13(W+cSYfXoh2N<47V-yKw?LgnnVZf(d|!*xnm|M9 zyhZ#>t3AfEI00X5!Eu8X>$3q%F*2r+D++N1#q9t9e&?FOiY+;c%lwK}j|U__#5b++ zHk-6&J)Q5VdbWh|AQO&L@G8Gw*DS_DTXf(zW z{PR}L4n?I7I-t#h;L;yYRJ-0 z%=V7vA;}`~W}@>5Pa*HE^yX$=kv2NB7}X`2Rg7t&P;}eAMoAmu_cQA=%rohCqOq3< zN#Pc`I&Qdw-FH}{gA=571~rI}LWrgEF{9qW#tv$cs$mA8#P*)9GgpM^A4-y8pQ^ViS0 z9){-H^WQNB>|ygm#?AGamOpYkN)r?;oM8VK7v|)bj8eJ!kO@N_siOhI!4ytQx^9;H6kW%QOOe_NCes0<-*29BeLTye?ngKVI34Hl z&TOU<+y$!hFa<1VcLb(^$mri^Su<*PC4G^C#g>E_g}x+ z64A-!prsX~;u7KOH`7+xII-{P$!|`<~yMyPVf9k@k{`H%aN`m9qCg3Ek({ z_Q(Nd4erOWZ0`KrKeyc6d8FVYXQXeLErk=&{OYeVOOZytVVZJ-;(9Zye7_v26{ZK; zy!QWy)h4O(+`jl;Pj+pa0UbU=Pf2;95k$FXNA4yw{M1hy0Mj6S z49?Hzg=DoEiZR!VwnAW;rLii~^eS4AUr0K)9-37Y1NRvcex8FdP6Lvc#|RE)4lea% z_z_(%h+{(I)MWuC6t;GfPjWMa?iloAPaKM((@1B^*7Hb8Vdx2rpbh}XMf=YX7=8c@ z6lsrW%oxor)E8=v)Rx`vP~f4p)Mtd)lSwF5K5gQm_y>Q+GI{nbBs~dCdzgQ8pVw`jb4(bHz z39MmD^d|MZfrkn8%{2XaQNlWaQ-Q+AC7$jAg~i%)nAK3qVIa>jfo0%6B@^S>9^(?y zkP)C0I$4GSnXD->O5I8+dK3S1- z0x_0pK-8fONqS-1;ZT>Quq1!rFa`2q5}D)71;wPwLUpNL@XgE7e+ba%MaeDC0vc^* zj1&x0#5;;TjCds6ZjUh(d5=$#l2YGX$I2K+k>Rwh!+kBoe=37gS`LYXKcaH^E{!9) zC&sogtPuZVZDKPaXL)YJF2EN;aMMis>mVRfG3y2?LiMe9tXVRZQzBKq!Us?gtS+N& zO1kj)et_7+(^_aqbY`pw?I|ivN)M?10oryUjX_Nts z(@U(6{heeeQm{B6VUMx=tQNPN$AJF^`bhrN!2bZ~u8ARC3tUDub7nH4grfcXuZ7S^ zKLty>&17d$qv=JVoQ;ZzEq_Kw8hk9k@SVW$8br+&1G)gv-BF-5^FYu z#N2Vb&a*8bQBeeG=N0B|eBO==F7Sl?P65B2j)W)Rg$@a#ERmnhG-k9f4CKgt?GlhF%_NAv+5bgIyLRgm`oRM2 zV^26mcnRh#NBdB}#6E{&Z12V7Qi`O#7geccwU_r!2s~EYD6m z+D?=ce0$Z<6!p8GK9dGO&(A8^H40y1DaD!SdxDjsbswQNJdnvF7w=4XDF=i<7K>tl4S7;a+ffUbK<$rktSVL0 zOL$W$*Et2&uyJ{_Dgzu(>iTwSco)66xaytc>ILJxg~RIo(`v*Q>!rf0kF!Vjw0PT-!^l}|@@mU`Aw zQq(rG74W>5L;Nq+?)ojthTr!-%?x=C%+N7NBMnL;Lw5<%2m(q9NGOU(GjykPNlS-x zcXy{WNC^n)Y`m_u?sebyUTYuwc%FS6=YKHgPv^Y9uaDv&;{F&o;{=?}TbovnVHhev zVh5`On9Yr9EyQZmooa3D__XiClyB+K$G}e1b*~n|21a!!<27dE#hT{z8qNXt*XqK= zYOM!Jk@xGLwnt+-V;V!Mj#KR7e(%9fk-B|UGCIluMTHF}1*a)`xLRei_MqTGZUEdWd``V7ocQ)q><}!xDe``(s<+MGJwrGQKMC^R|t~vK5+| zzlu+W?%7Vp-%fKVOJqz&=2=GQ+^Ad8PTzE&F_nfcwWH6xgBIGsU80cG2tYWYl;WLI z(VZ$49c~+)qK9<6hjQXHU8y=<^2Vh6VRD;>ol2^#I5cEJs({>W*UZE2C#l_rst}c? zZn>>4Qv&8s>NcXrM7^T2sGR zSFe>%n+@l{kxze8c7MUrz^Z&-s86>!WT4Em_t#`!jVDd+Pl}>Lpt%HS3Mnt`y&Y=cBpn#KKio7#%r|6SJ=jh#{Jw-H)U$!;w10-Po7{hJnUidEiEe%gD4`iq zXBZ~*@7or`4?%yf**>DkHxmAM1nfM5hmZYhJYY9femd&@2ec4Ptzka@QGu+HN1=QZ zx(uLUa;)W1LI|-V#;Drqm?ioMqP>LTJ*<@zqDW9ah4yG6(@eo~0H7t=MliY;!p>+! z2~B{d5>nc<+5l7*(Zm=pYjgQ!Dj*gPup9wAX_FS?lh4h^-NhNd$xS@9n0ka>qiO20~v=!z;#JFlOJO4{8|0)v3Rzt%8v}RJ;+xcZ`Vo?#u3$=!u8;Wc$5;3W{Nb?4E^hMHQA}cOPU^wYT z(}Gmi;-mIO3B(s)uBsrDc`WoV3=H#l>(jK=^E_gBduV3Fh*`d{*_Y26in_(5|yQJ8@Y}~a@r(Os*m3Msg2u!dkc)HH>T<-Ujje6F`i@3F4 zewzYWn=dXHI-4KGs*kAec~{tV<}5+lIKJY>>*#pdDv6muE|-2~vj*9C4*Z>?#Zp(WY-_++-5|Vs0)y9fC!ipjyO$Ub82-c1XR-*{FS_s#@j(3TUkDZ8w)^W>l zRuNje9r^edW%yf8->$i*hVZ`W>3nPS{&v-Z-?y;a`2@%71hkcYQjm#DuzEs-I(b{p z=f!&peR@iU0?0B>VZO35nTRSAsI%C!#X6N4>NH{b`tuIGZ zA1-^Ju|GW==iU_KUf~zq6XhXb|8U+ja$f3w^z`(!{NWyJQws%IN&M*-dgcZ96s^@rg`#CRxd2d3@Xu`1*!2YSt zlg~1=8Gt@Y#Bt@&l?NDcx*~EuBxcy%-n#T+I4_smei3=uF-G_y5rffKT7j2LVYemr@#6}UIu*oVMly3(Q{4IzVxmY)@oc`hC*o3{a}wIjMFGgp#NSI zVH@%J4ozKm(f~eYoTZK4X3$?2Km6&Zy!9#Lyk_Bc4F0`v=E_s+_QBJi9VjWHhDR4Q zw%5g@Kk@l?KmT_8pz%|FV69_~xcA%PZ?tvbH*kg`PFA-mTP7Ea`d##V731_bnvX*o zuRAtAo(x;qigX}8X^)*EkBM{$jLWp^zc*n+>-GQBgmqYvMPe{3DY$x426V__@C6oIThsTz5lVt(adbug3 zv+7J()K890Ti$DA=QN;uIpKq>TZ4W#5 zxYI3*V3mr?=+SVQ+`8xbHGIG&p1mBgqv3o`eD`uc|9-UmntSB>-p$o_59+Fnryq>L z)2~e*IoAEcVR9;($CKr))T|AW#|+z5;q7SFkG(r`u?mS~-NMj0mL`4_79|0QOtw8L z6C`nxg_Vky=aT7hhLig@`Dx{1dxXeiK*dTbdh@JvkGezI?1}o4(N3dt3EnNRbu(r7 z^DDE<-K?dQPObIzv)74(mAJo>oT=o!Tw+hbt=!U5eK2b&(9T>DjWH~^m|LaZAX`0| z&++*X)FF<-(h|Vft1+ zw0FZ)dG_(`IMQcs26mrG+#7g5y?v-`Quh{-Yx~(jjmq_K&skvSq^Zb=0&@)QiMh_M z>nDxEwAiK9OaRA(PbqxD1lGK}6{|57)u!ulN~rvFr@B4ZWC5*5abqSWUfB$oKItO$ zd$gBZ=A@uJv%Zp>%)%a`q&$dSX{^p>^vSFx7LeVQxkHJ%dNJ2Ivqt=Haiv&@G{AIU7lg+d2v%2-eF7E5Z&t|LclzN- zY-YvCjq~WE$TRc|f!U^SbqECsH?YvP{;7tt<4@P=7oV0T33*osEasG6HCK^}4ktSu&%UwYgjw@6 zX*804e)i4t=Pz#|uJ?O=?)v_P-&dC2{y??%4WP{>H&u+1uHmnK$Ek0-0G$|8?RNbp z3M855({v-6BI@a@@kRN%9h&KFrd@MV&<;4uJ`ZkR1KnbvKk%0(oW{=r>Gq`_4Li9v zS26f#V^b1dJ`dvPGA9ZUmL0*0MrIbTLo_U8nI+5o)$9pLvkE@bm)Rk;Q?qT-ljLH} zqeGuURY)p!zShY|_#5>sMj*OIExJ8-pSn{D~b?P}b-@s0E!% z^5~%=NAIkv^#m$EVOj_Bpkki#+4B&a<)$pYI*}2Ukl574Lk!5UhkAYHxZttnCmnA} zjr!bjfr;Fm$J@yoUPMvxzc@oB&<%66iQ+g<1lbV%Nt%J~d|rg#2OltqYEAjXW|MbY z%Rl&{6|sFDL5pppC?~2NlQ5ObDrcjt`$apUb}El2z(&&Mj@XTI3Bx~P(py@RY znjmP@-|@*UN2z)oYTx@9*Uz7zmg5~{^*Y+Z?+Z%(4knZd}IR{(a#gF4< zGc}(Bj%;SAj21d_i)y+ZUb;0Jtz6F3wPL??3J^2iAe*i4m3#RrzR`I5;cUZbz)ROW zF_Zl#vtMSrU%J;cnjE{&Hm+hjzUdY-JxiEv+L3d7Yp0DyxEarLTI}h~%xue5 zx1-nh#;3n8XIoL&PTtt!W*7=P)K3a~WRC-(WeomQdSKkUW2#vUmpx)|w4CmRcZej& zqFtdvUb@IUUII9PTFlD`vuK+y&E?XII5MD~&p z232SNcg|Q%c*X$RpmdW~e z3Q@Owb}A`m{;47x(#S*CmiL6prE5epe?! z&SR8}xr&PPmWX|wPLfGzkM01_Vfk{*qkX!~`LkQFZI~yc6=%I7yXXdw)nd#%7$G2C zmbM+G*m&o(*78oh2jo$-HA_j4;A*}1ZZ`Jd|6eOG^%sjdytwe!gzW#=3d~In-sJ*I6Rk^kGUlJB zd2XWjkBm9oFgIL3J>Eb07mL|EKDpUf{ht%EE&qgL{+W>NzI)ml+M4THnriQS%;Cz! zhS5JbX7%7`*nBi5;cRps&e-6nOU9Ro$f%)&;Z+Ke~-tSm|Ncom_@RD zccFlRp}B|jqsNBN{$7sN)zjAeGaLJ-6}X#?m6F#GmsWjfV))OkfWTcVASA>4ClvV8 z3a|^w{jFjCBNt%f5ohHQ`x6cPRSf($xd5{O2!%%b-?jqLa0=}?kZ(?WL3VE>_BWAi zoJyu{$0M9TMw`mK!Nh+9G2w&$UT=GhnW_uMa};Aa{-YJZ#|Tlb`Op2>n&R2llUQ%h z_t|oC4A%OHpsZ>o3xDs&)^T^ZIw}-8SZandI=Exv)2Y^%uO}gjgF6otm*)yL$<)IS zt<&mspp(LQtWIf+%|NI8PqJ|W#25*?*nUz}6{DkPd{J`G93-i;-sND$L7+fkMobRB z(kGBYPmCy=H+iy{T!B z6Wj@ry+?RqYO${?m@Ne(i%WQ=l;@Vg2>#8w874^efI-H~V+yWryHrpAnk5SX*kD4w zYfCIBZ7oTmKeSwWvpvoBHBRT|#hMg_q$N%e*|UK4Q0z2?=qRl2zA*=U$b3`^1||Dg z1Ti8QNX5z1({aExG5DJ9c?lj5Cs;3xPbPFOjLpQhVSSMp5p`y!@OGq&ISGW`Kk0>0 zvA2_-`ec4f&3il7TrQXMB2zV5m61g*I(=Y6M(8<8M6;0B=81L;He}&15EJH7=t%`B z1*e7NC{z{+j}=EycraG*AneAnS+dwQl|k!<`JeAVOxEfivgf}DIqC(TVRVJHbXn#KJQo~5qiZ^<8CX0&? z9qHnyq+Wkc%Jnlz5TS9QW(49Fbcvmqku~fG((Z34Vwc)Sg$f68)jnYpf>udAlF2P) zv_kE;$x`)RTrN`k$_h1E?37+<=@X*_O(U*HrY=>?hML@^hXO_FRYK{Z&(!#|Cr=DW zrf1z`I*v~Ue6YkqnfA(W7T7$xUdR_kP#~OKVAjA{@ z?8n}|_PRak@7xf$ea?K?y=%h%Pu^6h=5~G zAp6Vpgiw0iI8(5SBF(%t=_tsb=i6AkHWbk($XyYk(7-5{D+7F>w2bu3?H85ZMy|Pb91|TBz^r}cr^!v7t)!sO0ekQm%thslqHj_4i`pkq2sn&W4yD*i z{{ih2wjT!(y=RnK>IVsvrgZ#@+BU_wyF#8%1`H;G7^qZMixd3$otkps**;t1CTH?) zYp>vHRgoQ1uO@n$szn9_`#M1}L!{Y0RE0)^p{jm_9$Zz4)+NR&aWa&nf)QF7TF7I~ z*w%P;0R}tQF11xR9kxQ56l|p~s-FGCk`}^uC))7@HZ}AT5{f+3v`Asvb#is?+&Bpd zQ0UMJ{5?2WWvt!wL65a+@jc7uc^8V)O%=L+Ok^%%VWa9kT{H=1g2nD!rZQ)u>OSI% zie7G5W{(4fJE&$DQam~3$QI|y6LNJzDT?h&_d2>zZvH&ZLmWKV{6?|5OpzKeqDvNc z>M7`D^{0wY&&70NBHqACY{mNw8uyU>&46P9exmS7k}kA;AHIXnz5&|!7=tq@l5L*2 zidQ-5Lqpzx6-@ccSQKbW_7`b%1HFG*2<(`Zrn7l!$`I;2_L;+wM`08?))@$;7Rkcb zau41RK2vv%aDj~3y-2+G-SnEoGQ-mb*XkGyaek8@H^g2bt=PoUTwTZb!^WRkNjUUz z%~fQCwWB_C-oz&rmlr#o^nrQ^d1*39JcaI8#KL6~p4CIWnu~H7Iw;W*ob;YNS0C^F zN%KHs4~CZmF;u40o9vRw3?>PcDK$c~$Xt&*5OX`#bU}MMph;xp4ITAE-=EQ9JO2e@ zQs0ar)vL3~hj-=0ZpNb`s&iS@_LPloCXz;~^MwdI*h}UoQ;BK{6x8;$Ki>QwS^*bE z^x^MsXWPo~3j9jth`0q#||InalUgQwyv#?=3OFw*+z9vWb<5!Om9ZnuRYJJ60v-?qP`AhY>cdTE{Wu>#Z05*oT zHH>k2VPNc=8tUUGto14-QypbLfhCB@S}z;7Y19YV4(I_=fdh!bahk)V7DZWKXVG&5 z!><0d5pZF-ndsa#17mpfH7+2m9`!*uo6Hv8{YVEA@#q4bc6zO00CV_ElVxj&fL#OO zcnorSgSn3L<8Et~D8fq$y_Z#AH0$H>yl1uSb}o!chBE?5El)xN58-_oMbHwYl}8kYb-~R&;UyLI~p`f&vb!7`Adq9-eVHgu%}enBs-Bs z_~!nQs26hh4N*(TJ8!AeP;!aAci-NLKVD&(yLPX~ebqyal7oZZNTEb?(SPmkc->5| zzPmx?5Gc@Kw9Gz58T|w_0yU+FPZLq*AqYSz^&#q}7dDNiq<;rrp5g>zd!tiOgsf4g zI^8*KV6Z;<*38{n7;c6TfQyT_+Cxf^7vtAMBQO?3Zw$h1bWG!Li!O z=j#qAJ@F1~^dWx%5BJ7l+O_Qxfb~iNBWu2|AYPy~O#UPvTwLtSHjprd%as&oHC(Yg zfv8;omH-F3;DCaeuBF1Aa7y%jo&0m}8z7s;D(=0&x`!gtM;VDWor(A2#Q(#U>oarr z_$?}2cd8ve!b>Y#Hb$R_a$Hku-~#}*i^9p9psSvG{uu=YM{CJX^3rdjnPF=MrMz}> zuznY?gS*2QWZvc+w~oZn;@B+r!{Ebzyp9|80Pu{)`|!rr+l&Aw8XQm$7-Vy;w$Z#r zm!R07;e8Eg204Ay_o8+p3h_qE6b6#&l`wmsj?b8`=-GN}f^irK>I#4*EdD7enk0RC z_-+^r#Gxz6KjSr?(WfvCeWkrN+Gs$h>KR}c#k`+q`&^L( zupf}lf~c3)fD7{F?sJ`L-3LcbQPl|nvcfMhQ4G$Q3{lA)G@-(35tbzON&Yy_7%!aS zUYvkXZFekXSOgG(rS+i3hiZd0ygU#WV;sz21CYab@Y-XsvT&l1+&Iz1-=aa2`XuI2 zo-#YQk*{^Y9!{BkPQ-T;w{0LBUc3|ikdyIOIcA)nDMCNXhn~y2+s?7wbpu#ho-NG2 z{188G5Baurk3kBO4KqDmM%t?=;oM9j$h{=|J{dd^FudqMaZ6}~g<9!YS(qdYC<%Ig-zNH8LWyB3Ui4fvdqevI%=+p$5w_ds9ZkILad z?~inH*`$+6f@^m7S5knr$Frg=IB2jYAWblNX@wdV!qK=>x5-<*Ghh$1$? zkLGqkbRJp67ike@nFpi<813nUYgxp(X~*-DKa&aAL=n^TlCAIz`XAZt^2mraFoR+C z!vQJcBFPP#SPbV65=Bx1`yg~fN$GtM${?3u3l9Sw_n;Gufygr4%>`R#!VM+yzxYx_ zMe1|NY1>j5DFSz2pUp$0W)#T~1@Vnq8LBDy*n+qQN@P|k)IUXXF|NqNFG|-e$IV6kxk%8}s>NRTTIjvOH;N&s9`Z^s#q-rrnwJt{gUs= zLD69V-0l{mEMgCnVOYvp%~TYRIDqPbk{iZ!$_1G9+tPsXEP3zJ+s^dFF__PSSKw(* z+Ct_A)gv|0QazuXd;94YhUDl}1=0H;&_dZwY>A#$S;SZYhIx_Ccy6aCFf#D@wzKF- zMdqP0g)m3)Vo~`yX0dHWmajPoo1t7*xk6N@G{U>g%{(;1J05HN?x!uJE0)YPgjp;U z28|aMhyVhOm7=Jr3Ox=A3L^l0|MNo?NwP1WbuCoA_|ooW$Haj+}BIZ-qzf$wcUFQyJrUka*%6#7vZ8;nifkGfIsO%G7Ck4Z-(S* zcvV>I)plZ%PVZo@DLFXfRc`3nIw^HGIklSY)mY~Brdbsc@M1TrPyWRcPg7tIgL8r^ z@=1*VBdUfefm(g7&sgm>j_dge?*PNWhRMlFP3L^v^{Q7DnQl&iU*@L*6^S}Sn9e)k zM3lV9C=UZsS#w{a8SjfuR;?XJxm)z>2;O{L>ZW0fOqRuRd_?)H=*H56ris`Z-K;{8 zPbCL6c{b`})!YGVUN%G751{G*6srkKHUbp!$-P5?ySQWk4ee5_#Z#K5Ze5EIk=2F| zW1?;bjW-&%H{qhA5%IQ;Nugijqg@ZOTWtdm-od`z_jf_hHop%Lh7p`oV-g;=5tj&E z8N$}@1LRuSM6W0PTOO6TLZ>A9K;zj4Is2Bx$1~!5PCLRXa^xm z9CWS%_WIfTtg2YuJWKl>fTK!5Z;yNa5gbX-PsWIhUxJps1Kx>|uPn4V^0tI@9De$(ojbAHo~^N-Fa41kCJuB`4QnCVE)Q813`YndBPI-EnC6*sVq;UrRVXXxLtO zCtW`L1-+%2)I={I-G@e~P;fN^r_``T+bpSNC=w2Y4MJrN$MGsAlvH3zq62EBP-G~y zaS%`_CW{v%zs4IkDusdurd0U)h!Fi6oIra@*RyvsT3M57&K>xC)3)t11dv|kEP^L$ zvvSd$&Vx|;W?*k|+Q4}n%Q^S#C$xpP#F=YOaeY=Ky7SE-z*am{e>$vUUYT6p8CME@ z>IucU1y0#}OxI_b7RUC73NU=ea*pWt?l0m)<_xl?ak6HAEET#sEmS!`6G}-Rf(PqQ zrzh=TB8Q-Q+NFo>v&sxrfYyQ`LwT(OU{(whK3WoG=vPEVPq6(WTUZ2IOQ0(fcUmT? z@Aagdc_(Ci+z@>LlC>y}p1swO6Ct&_XF?j12E{W01WL)6-UFyoQun6MFPm3I+v|_+ zL($%kVVE!JYpvlp&nb?N;6kSHyhtI9&>1zz!Jv5B{xWULx^VQ2iq;auClg(rVmF+$ z=yr(ZCF!ZbsQh>#@d$8Z0vk2~#?&B(CJ^DYDFH9iV5>om_SU+m+5?F zXAHMQDz=1Tmx&n`=zW$*v<9AVGb*J67V0pnh?eU6kiDO+Q1m5ipReY}5RW3L$O>TI z43n0CnEnPr@g|{KQ=Sf3zUAP0-g#$Jh!v`g6vJqW0Mcgcvk9PYlb&WQA42YN0jNWe zh6FIMwi2WciAaMQ6G7aYU_9!8P8ooca`(2(U_iE3_CTM0?-8!g%W3U^D~9UL*NG5? zN}>nY=y&MmeuUI=H84ha}G@qN&DsZN{-w<3!H zb^I8(=rNfiP#6yNEjS@WWsMq|&p;rV3h97a$RYzbWN+~t2mO#M5)c_B4H!PcKun{| zvyMVj#3F!eb>O#cjg#aBrq*}O({&@C&p`VDh~Z4=*AXFl2^jrz;eI~9<9Cxrs5J4} zVsSbt`VoG`Ie2_?VkiJyk*ms8zFK?EZ%Iy3@1#wO?j*$W2Wuf6^qrhC=Kw`!msrflBLtDJ(h1Z8>jr&mF z-LAm(YNpRXrp8S+&rPP;4Gv#^{c;_}Q<4XEV+C}#VDwM55v1y&KS|B6oFQl#ZMV(e zZZpQNH3xyOsG;v8pMTj*!mKEj8^<(ftd=d^>zT9nIhuqeGX) zF~g`4>k!!Tz}Cs2&j@EZOz;_?uke&Mz7U&6|35%Xo5{y|wW3DPr0h@T`pF!FYK4WT z$4w)X2sWboXINx&qt!Cx(+t1w%U73Es#Y5wprjS7bswrpBwKoGAXa^Eplg};qp4{r zi9N1zAm*XWw#WC4Zd~`LOJl?M(=KO%xKtJq!wHt5D>6P7lDn!*)&-0X3G(y5Zai~Gmn?-#BDT-1pNBpH-5HO6j-GIzzbi4vpR?0E9N(D0o|5(;gV%cT6Y zRwN{L;Ri`3AZ3Og#ba0_;;geN<%9#h_!Og}(SEYYsOT(M$kKnn;#Z8i7E_fgV~gHn z@3enR!puW3fXreorOGWym?GuB12Ib?sF3B+I2A`tZ#R`Ei%K+^IjN)Z-c8QQ8bVD?)mGy)yzd7Cm4e>Vc&t6D({thA#V2I z3*H_1NxYHx>{m=BoUCqJBz~#*h1Ft@UJ1w~=r>nCF>?Ghu2Zs|SxC}3;EJUX7uV@f z7Q+&7!Klry%Fd(E)Ahj6=2Kn*iy1Q~r}9%H{xbtyjRmsY38~UrW0%ozMJhw86y~8$ zdsi&on=ga}YSI=l8Y0p5(#}lp$FYUYY^Tw&vQ>$5G-EZbz9jNW$6B$^Kkvite<)L@ ztz#B0ROT3-+`@;+V%BJTE$e4FJP>Y?u9Q!q;p)5D!DhbjB$-`^`j6YX1s1{F{kze%+pL8OT$Tyog}y5+7HDON9^}- z#`BV&GPR3V_KFN7=Y`_pO1NfFG2}rKq$T@4hLrQNpB9H?*=T#bPr0DDS8$%}90hkN zbQ%AEOPAMSBE1ZsX4cM)jJatU_@1!OyL*tFj$tS|8i6nQ?&#BF*8Fu^5#xI^DjP$! zMfvt|l3D>x)On+IL65wGI~;?L{8qed&XdQ6s9B(Sm;K&4y0j+Y{vNE(@js#UZCbgE zG|#E!uo!(}<~TbbDxpfpWgAr}j20#togAgd7oSqD!Ym!xD92LC>ZQrbuq^qKp-n~7 z)aS!p9;yP0xAK-BFY>x{a&66l05-Ojek`N)v;ObfF47TZq0Em5=72om?h@A%4uRPI zxGyuY`BDz1aC9<|L8T-|g0sa08mTSR0#=Cb%rZ`?so^Pf&r}4%>3%~Nr5FYp8jTv$ zC7LB1y&pi}RBFI{(&;cUBW%4pAwkts-z|knc}AR>DZenfxw1ie*`k@N*OTvwbSSw0 zlwtXOcd1Z-Xhkw<$C;StA$lMx%?4lJ3pRXJsm12o=heEWEwiDlDO;iU&_C{X6j<;~ zU$q?oKP;TzQrUVOFZvS2$1+DXpRmyvW5zFVuUB=Ozu6|~t^R<)M5vN0w_vHpd)WZq z`E6lhjFBX^$LRqcgtA5B8O7zSu>yS3uU%)w2o3n|@p%SYEWOcC7$ar5w6r!a;KMhZ znc!G1Q9d%mkmDvC%k1Ru6J^{VOOz7K_N>gvgFfg;Zi{%yN4e&?_CPH7`cOAqtPr8N zPZGNwcb`}sdCziEUF20j(tXM`rqbB*Na5a4-U>^;*9$S}H?H@)88daWMMyt2Smu2< zw~^(J6A?G8$-1N9`48CDt1hvM>+ueBYei!Ult0D2^A+1XaSy`5`5?g6A5EU2*rJ_i~grZgQIQ{keqVUp&>r z2!GKe4J)X(ugPbcNMZ{q(X$y)Q0QpA)xU&iS%E8G6&c1$b=LnjQ?MWYu3r#>ZTgI} z|2vvu2Ig~YwOEQ{%UF-4Ee<_o==Xm9kT)@O6Q4Xy=k47mznECVXB#NsJj(ELh#GJr9fvsxsm}LF{e!<8g$?hSAj;Hm;n;8o(C3*sZJh%3vUf%5q z4B)hU4xR5)kVKu`kE6k55t{GUAnM}I6}RHh5CJrLDr1%Gsq9Z*GmoEE8ta|aN$@2y zUp}y-UV!6i>2Ffa!WB}#ith-2Vj(n=9I|<#JzHFk-N+HVysk3*}zM26lF0$O`m( zQo_z~_AOMmrzTE8%g%K2%S6Hq$@`tE8ZM9MIZhwmU1?s6=R&unH1lXA&|zyGy~PFU zp1_A#G%?RJ=NX%*dCG-y7m<|y?Z&|)T8~I**)MDn!*7*z4htTGIVVkNef5#iWP5H;m}0TCJ!9rV-O}dku6fx?#|mzj<7NYY%>9B= z>K`x0H1&gLvoaAI4HY`L=xiE8MKyfFM!uLL-_W!%LT<*sTdL6qq%wYNQ6DGPMy9t3 zJGCT>_LP>nkXqB;d;DEgP?^NN!qFy$-?>rm6_{kWDOGa3kU`dZKy%gGchv>ui+k9j zaP(Vzjb;7aYE`al98*l~(^DoTeXpkx#^2Vt&2M_19bd~&((F8x>{maJ@Hh_4B`TZp ze7_%ux{l`+=gq~9lXyGvrQ9rWC>gr}3R+299U!>CI`@zSXc$e2r5#>ol;F=I8USAA4m=u88 zCJn&Q3AX6y;9Tn9awg+p3hua1a-|u%5Cyrc9 z?u2Ja#nelER&4f*N^xn7Y#YSO5RoX{XLLvF))Xv9vN1_WOh8lNDgJNtL&?XE4Vi=v^yeVd9D^mya9kfZtO<<5lqC z6HgfHYP;?XL@LbBNu-?yJJMu(lqmSjC+sPMzk+1i3%ckVqUy7|4ejOM7EjA|V46J(C9a636%?G0r1e@xFviV3wAQcZN;9=q*i*xXsJwc9peKA-R zJigqqC&{vC_-!90e2`~ym9;)#5g!Q5hDN)6o+6oPOYsY|$EN?$L# zt@0FN9I|0t{w7MUP)pk8EdMi>imi@fl&~Vap|_-s%pgu7CT!5frtfA~ zIq*c0kX;6;sFEb5DB(NUQbIyohQHL85CFrC*DE-csoiObpfmAKnjZ zvj;7hbwi@lPl`i!-yj$aRYz0Fw9%Dgd130vFnq{x;Pv4CNt#tw3`)XsV8nmeR;z!5 zS7=Ic$eJ>-WUQ|_u4i4AT+l`(TB^UW393@rvg8jIGtQj#AF)>YoUq%~;VmC_9bM*{ zU7YmMO$Yw%r@C=+%!N3(mxka)mWCgjDzOL;QmQF{QgPjL^c6%Q(z<67GzvLwomj$y zCHta0N6_RFF-nnMLm`Yb%|s0<3h?2idVtSK4J|;^W?nU4m~g8K*4z|=-d}RVfbgNZ~;Hb^0Zi7JYX-_acml0 zncdrmQR53^iB6&qt;Tt3LKZulg?@ovpXL-rDaGy<-Le{FL0R4(o8 zF+z^u0TLsNKdp#OITje)_a5H|$X+N-6(>!Nt&ih&>+JWjW>^a;piP8C4Rx%E4-&*I zrv_UnPPZFOKeeCUFUNjuKwEDRtkq2sd2;Vyko4#RthYPe_G4O^aAr>mQ(~2_|YGT2_M2WYb zE8$1Cqj7g#LSFqKojyFp@5qldVJaoaN1J&>^Ma_yd@9`7>2A#WuT6qV(bVAU{UImA zoLQgon>oXV=jH^F^90~Y6~bHpD7b;V!kpx%bMCvty+h}jj-;G4FbTOIk_nshWAnVV zvwrN_{8ahm>O@RK*1X@z{2a+bR&%@tZLlU6K>&74b^r)!RZtMWVA!r3T^c7?Q+Rc@ z@VN$7{1sF~NWd2WD!__quta_pT(pr}Z1XXiN}>*ix5E340)-oXS1vY|!fL~jsSgNx zkwSsO{apQ%F|@`VHF2WB)6q%o)1azmSe&SmWS@y{e<_SDpbH7tMzkCDzj{1Y1LZfF zBZQdHgSjlf7EkFe8;;NB@FKHxrb3c*QG_B4CV71-rOTXJ1u^y7U2`<^X~atwI$xhn zujfGB@dVcG$Fcr%f}Qx+ZIg&?%u@h58DL3r7!D6WCTGPHHFN0_Q_9=syGk zd6&-fo<=D?%`1qwh&JUiFYhf~MIC`6E}}MuNiN~DR9I_R^56l2U_rHT>Y@qGieR@_ zI@q;lR;u&SaDyq~EC;Y2e2?Kr(;B2q?#^e6D3?2cw@!?iz@256K#U{_>yc*q$f)5x z;kwPEsK)*=%Jg-SugEqS!JZ`u)f`E|Bu)Qh1G#I$mPKrsHTJ{0ozrB4<00s4JmF%! z27?bDe)R@V8T4CPc@_rKS`eckSVS;SBdFgkMQeZy`AM%_uhAMyS z=I&EV`S^P`tYvE@`u3@jLlZ~ zrmHo1#D%B+_*(N^^J``gpYoLvTOl`Yyh#I?ozD=ptC5vGM{_sgE7|;U z!YPdNNcwr5doE$>;gxsY9Th%fT5GMQQcTwc z+lw`^j6B(mbGLD=*pjAx@zr)E@%MsV1k(Kp_X5T9kMc&Oc3X2CgfA}lgsh4`aPQ}m zQ5Bb(eyaq#JlPi_EDpLXlPMS}V3|7*ner1hEV4&z^rwswD|Z0AU}n$o{|Wik}8}+^-f_gPRU-Mk_VkqB%V@!I;E;RrS3hYnLVZ5 zIi>(^0;0rTr!~>3|FWYzQ#mr@+xmH# zl&i5bOIrcX&(jN{_96&om=+38UgJB|_`B+hg7EO~^yqGeJc)W-VbaZRH)yUpC_KF# zJY^vQ2YvDmMO;Oc+igK6el{6|GE67R-G6xIIdQtk6^rzaoBh?LBkq+G`IR&4)hnSZ z7lkWVy(_mDSMIN0U;BJd^3HvYG88Po`r7hZ;f>yBDa_}euFPPUA6l(`2ESGqBUUIv z+BM@Uz-OW~gHnCTuWgy%1is0Xd;>Q!19{@oKT`B}M!N`MV|{>zB^`O~p7sWb26Gn8-rGCeIp1IY2X1z?HTHM2d^bpb*DN2d4*#=nwzjpp zxV1jNv9|kv=bQasHp_Rx^6Gf=;zaA;!SbJ4d9>w!50-a(3jX1n_4c&)b~W6k%6)A$ zZO!$6b;|8yRSExxPC2`+=bt0xhCA7;>W^&pSEQU8_diF<`FYv7e|5@nMKOP+%4z>Y zs$B6urOJz5r2oLp>V0(nEmaN(ME`_|;!N96Swmkz?a6eM4{8z9n#>^?g$SLygzS&>Fa?t+}EGL=I;S5l-7T*QSINt~x{{+iU*h(qJ z{r?^;t2StkjwA+owa~EsYp|T-#l#^HIaRD*WxG63Q>wzgJ2c?F5 zMU>+VZsl1MWypA*QLsvM8o(1f$}I-d)h2fodPR&ZJQXQ74E&Plf78`=TYL+!c&5yP zB&;6W#PXX+S8x7uxJBr2e=4keS)&zGR~lti%y+vT(*DTk>F6D9mim@;0jIZN;Z=}V zcZm91jn}fL7{OnYr7pdv?vmuv2T`vv&_Uyz(`z%C(z1jvpjtDE!b9)Bx$Uk885zh& zi{H*OWven139RuV>n(|0F@go6!aB`fXgXtdD@42F@V$u-hvTqsMLj6I1fn{xapP^3 zNw#ui*!~NZNA3DA-vS$hlX=aEpQ;la~=UJI2 zD3&&m#1pjZ138iTMYc(q249Ml_%~1#DJEs=OgqK(+c${?kDT#HQ!xnfAfH8P2iA=E zJ}%XFx#6{8&Ghwm&ll(qxYVN;nM$hDVwr(S&g#dvyvQusO5 z7I_tnq4Dttn8B{WgG*^9BBM(WtTJ^r4}2{s)j(%LJCuczrx8%#)N9z3w&duVRxUa1 zp`q_8ms+r)nzaL)lxTLhQw8ktf=B$fAB?OBI`s<9hE2*neTKt@(Bj?E9u(mskLV}T zVkT(@f?-SYol_i;3I42}4c<(WVNJWFuRk;?x8@JO&zgP4v!Am}bZ{RQSp9J_Z(nzG zS-j;l`+d=M)}b!Pg?{T`+4Bl@bmi)S;<{e*$K-ywj$|#n-Ut&qzTS*d;Qp}{r}y&5 z*Q6I^Kekg}AOG0N4C21o%}soHvsdt`>}J2D?)c`QyqEj-uzL38?NR+s+3j)D)$#4O zwmaPHq>J3~=V>47=euB8=-bcpu|L7`l%C_S?{j~G<)zo(eqF5v{Rx&69e@AW{q!eT z=IO>ZvYV9SDZsZ{@>0JlNu3^=PRv?=aQaxKsT|TazU0W--ybxCGAF( zElfeFKD^H;LiqX#Q7(#6v}8;)_xMPxHCe=1NU)gIjT3xpyGe$;G5GJvtdl~X5jBgm zI|Uu|&FMds31|ytkQI^p0=kDUzq=ijsub;)*#pE-GKJe&W+FQHs=|! zXcXfrg;kNMXK+d-^_p7OR4S@ic-&zguSKCu(wi}c1ddDu(_W*t*B({BbHXn??P2pF zmk`1V&A9qxl!|=FIpaE;ndo3wjLSpIObo3ZDML%~xPFyxhYDUiqT^tq_jt_2=>e|vYswQ&{b4RWqcae}FRS0| zp`8ug&+{4k7K=s6fshRb{5Fn*h>aoyYH|Uz02hX{T}ng=QtpF%Pbil2S1m0z`3z|$ z9|szwrSCn)$B>!=X7gek!ZTh;qMT0{B64zeFW8%;?ZPf~6va-~m25B+i#a5cW!lWC z66v-Qo~wZ*X)tpbwz<4F*fQ1ip3T2{winpRJ3-0s`|+LpWpx49N1MlkhK+jxT;vX= z_QMYYJ5VE+we`cLFJBKXuH0PKwGoy%1*t4;P+iscsg=D-99-HKy=oW>FLV90Siq4q z{bg#n%)M@K`S|Ts;~L@TH@zw=XDL@ryK0}`&JM0zez|Hs33q(W+QxS?aMhyfgW)xZ zixK|)b?aIck2fwS6#X>;2A2AXdO_ye0bhMPkN|dn?Hm5CdJ~GX-Oqb@w@c52Mz~hr zD_)=F2NHYTA=bYk)d7i!aC!p=v-wLZYXyp@N`qKla)(&S1A%l{?HC>vQu34` z-$T*fQs7dRiIWI&O4FB91Tu_CMZC)N7%JhaQk(m+64RxliJpW+U?=#}UovClanV`_07s()6-Oyxl087D;eU~K z*KJWg`o72M9N->0B!*4}kq#Mh=$0-)MG&Q1I))w^DH)_gy1P?g=v2BCBo$GdgX_1} zI_K=Q*FO6?`ytF9_goXN@B8xszsL3I^kpbXUF#eH=24ZnCZPMPZ~jplu7qo4v;|qg zg3j+t50b~92;sI>9GFTnvC9Cr+r|u%Nu(}E0I*kQXm}E#Rm9dyqUo|FD<9!1vRd;D zBie_hl^V|Nee~H)<5IKLMu4o<1FiflKs!k^6c)8uhe*K4Aas4-4D#>(b_ zx!UPj2mh^59=rjlCCv+fp4bkZAv*GG<`g?%m5(>d6M6>3`&PfBhtk6FMcK*a+h~aM z50&VwCa9>}#34`CRrn{WBV99Wv2l4qC%61SA#%3+UeLO6{4*jqgBB1PAi)XZBpy!k z3dKT($%UcRp)os5-!{h@$y~{}Ty0Z@mRjW=L*sb^&A#BZJdryu)A(wvFu=#0n|G;K z`JNny|5@{9R>kA^H>^1GAXJ;orOh^rx$PbMG|*-tWueUQ0p+{&_d?2@0GkE>9jn?r z2U-$}4_qu{7gs|M2T>ux*0QW}yTl>L@P)5ro|&G&GB{wS(9>82j8nqeh)b%mOMYTR zIzj8-R|2{ zr2INTn^UB47LT=JAkheT80LGx;Y!19@8uFjP9mL3^Ed}`#UOX~nycnF+Eeh9iO2Cvce z5Vi|C?1jV8#!`<2LA-fFya;T+67&8OcxH1{b_VaxLKMIWGQy9}IS(nYf83%Y9_<~S z%@!Uo1HwLyst}K<-xqmr9CMW#9a0zF+$>SF7}E{od?5zHppE^43&QOI4enc3!(GOV zCEj?8J!b*ri(@9e;}(s%+84#BGvW~XvHml0A892j1jXIt0F-$A#*?_i44GPS+5>Lj zbTJ-P7k9yJc@Cqk_D)FXi#NlJuMvvLziTi1WUoYPv#%*d+8-`wA>c zi=ycmx}1}Tu;WK{XdjFuPkSWFABgdnQsMJ3aKA}X8WCgRp<*LsNS#Uv?MrkBj;%>d zG58_%;74-sX^h!(F)F&WJn=LS7k?s`6uakA_eYrMThglQl8=!H=jY}UCh0G+(@Zx~ z@lTW7AnCZ^6mPop?l;kZqdw z#+%tI8eIv%bmR@AaHgGbY~plU(THS%Nu~!1ho~l{vPH<3kgCLl(ZM7uzb~`)GzAwk zv%Q6BQ-?)sP`phQcq5U0oCu~tMG|jh>A7U#o~AiNv&K!h%0(C+@z4$ z@N2TegVWXtS*33gC1$p{O@_NoaJ4GX@+Q|>KDZBqL>z-^5t@q+!FS&v!V-Fm=Ys!D zg6oS<-q=pAHCr~(HN=Sk95o__bDdWjnnUdi-Shz{OsPSc$S-Z&M&=l56N|f<^%=j%S&=jT#4P| zrGjP_Fy-eH*t{`@zQeUC&{1O-J)~5ZWRxbN;mj&4Tlsmmr{)g7N_}A#FtSz5HZ+f=9{935!a;;Hr~Q8--fznv6hw9C6)#E zlo3L5G{NPynW1hXAOJ^Vz z$~MVnl9kpWMSMRfdsq^?M=QNg3%=UC-&PZ!xPAkMrfZ>!53b4KrWC3YRbINKr*u_e zE)|N8%au0DuX)+GmMKSk0c14gv}85r3V{EUV!sS1l%!c41*X-&F>1i?)@llH%?wr* zQO$dTno2%YHN845nOTmV9v1FT@V(I*jy6E*Q0ks)%5CCo9-T>fc?f25q+uVUL`0X0 zelAw;sjAVf+-V`FVW3cEsE-vcBh$swGE3&zsML_6;rdB~AqBjr2anT()!S+f{r)&z zBLRMXgpQSa&qB={t%kJW!8qGFYzbuR~g5|DG#rvwu> zSs<%n&<2jvMsZXfd`wi80gP}2tcfXpUpFQ40nf82EQp1o)dAMgB!|OVsAH>^OEc`W zWrP46F9lFJl2^2~z!Gb`gUiWKEkubG=~+PLVR{)uHE~pxxo(R`579IW$tw(uaWnGZ zwkEvORt>)A+8Hkb-p7XHjg80Uaxp2WG(PPrQ*aqEo&u3f)eo#4e4PHW8udn;4p+u?`hPd$(XW zh7Rye3dk%6Zu>IxSs;>MwLR(;w!Ixfi1u+g3~Ybkry01B572Gt{7y`>$3U~Hjxma8 z7e(|^Ks&HE@6=6MbTlE_UF5opXovdB7)M<2u4f>+=HO>PDd1m#aVdfk zbwVl)V4%5icBN_k`7jJMVu{%yxiLy`I%s-2L^~p|Iu)#p*>BX-U4zQueqN zp9GttX5?;S5BMF%F?xLZ?fP`;14E|T38KVl$&DFOmr2o_Ne4mj%qn>-g8-k*END&r zGztH6MCeA|s5$rpDdx;QU5^nK*NPugBuJFT5uuU*7$x0Cru(7%3>Q0xgy@J6S#4gW ztIc9FZxlSoiR>4G%xcKYlY#3EObzdY~%n_JM#KZC@FWh{R zsAg6pZiWmwCa@|Nax)QbvH0SKFe=Vm+BKUTI%XU^#esx3We|T59LEQv7(Sq=H7P84 zhDo3cWz$PxH%oa(gd?e}!l`-10zmT(xZ0oU{tY=F3yRnR#fL%j=!UobXr;3fk8W2^ zfCk)K30$G0YUG2LrD7>WP4Feb6L%OVN#ZDenvfq^2wUGwbU3Xo<>4{Ch8~@)k?JlJ zLRZcCD62at#~3N_F|d~_@C2PPBrs=*kt@${R?m-CkU`@#cFUxvi=NOW5}SpDq}8W& zSfY#@0dJ5pCDJg;iX?+B__e?!+1=bkPFE|5Xr~WgNAqPyVe^@s6(=ib&B9Gvo>Ei z5_j*oVK_|fAmug;_WoJgCETxx2S01H!OATI^)$rqKLs zv-^>s0{f$`;K}}l)2GAV3GtG_g}xn zOJzXG)smORAjixupicosErl4UyL&4qAmHu&RyNYzAg3?7JDiwX?PZkXmcm@tU+2+l zBx~d3KRYe(0;veTLL{_B)mY9uZ%9O}$i=j!c;x5iASYDFF9gW5$FBQMeLF1o&J>wX zm6;#8zq`OiUh4EzXng|stwbqwjy0IhSadJEbMc;6ALYAUnAe;$XL&w^?2`3dY6_L8 z+yGWzMKQWbS6KFz<<6Ocztx6b*!0aXl7CB2KK^||5@_}9Tmw8cMN}C?B-vr^_lo@F zZlmifn)=u)5axH$zNKW(O_>zaOitVjkl6b4}li4D|u#cr?%_8hoFJUoT|EC*g_<+UMrC1;L{e>l(X}OeJD*q}f0mprRac06$oHqyJA{FEPZCrQ9HH*TSEL!V=Cp&G-pPB#kJeKEKYZw>u_X>GE@|K23?#B1q zAz@=AbJvYj;O(CmU0=cUJ)ZkFX#A;WTdb595XtNi?(Vj2+v?jxm9eUl8@xkpDDgdh zH5Oc+KEYBPDaA=BSj8Zrvw-tXkvw2zSA&c~@G95PNZiMhDLI+0Rw{#SyU2uM2!eSi z4QFd$)c5F%-Vk#sy1qMYq~NTgjdL#>!lT2QeoOJ=U9I}P@FcbTcK;t|d0b=clWNR- zqps>is4$8So-OHp1zs|ZLuJV*dY1yx)TF_;UUz)0^W@Rr6)&oUDW1%}E2qDN^M?w{f%g!;0r^5yq%`A=R4#N*;9ur3NAC^jYp911lwmS(v)ap@H!$naTF9-EsH= zHI0CSp*fAKbIHR*dAv8?cc0u|xn(nonhw+^rSaNOT`Tcfzw2<-6A0g~HFXKED{sRx zi>)nl9eS-TEBlP;Q8|Y!r(t`JwTX z91r))F}PO|#j*`)5!^mc=37%=3PkhTzW8mtu*EyHRzzlgA{CKOnM(O?t7DZ!KkN|w z)DHHgQ0GF@sR6~tP#r}gztYu&?|W5Ju`nq0s!|Q_)B)xzSC@S5C!VD zfT?~rb+eKPvbpHTVu$W=>^dodK>aKg{(Cg&OPf)D3y1=qQc2#*&7Lcpq76|FR>!fp zwzIE}4JZb`1)~MH%ba3E8e^xhX`rJrKVt)+RTM&ks)AT}kwEHIx&sKCxd-*u_IQ`W z8rM0>$Y7iT70onqo}^V1mVsEPD^n=?+dx$8wt(veKfhEc)?Rq+&ztGXE*WQ*{9-9@ULO8MsY4vREg#<|@bBw0%hqE}tpUcBb!3f!> zNOWmGRGeNvm%g9~{li)YjXjq3ZMH-pgeB*tan z@z^5|KZ@7R++G*grmp;1A&cppDW^EKh`4G8phkQ)*PvXVKrHn6)$kIll}W?-naHG+- z=z@6VfZ0gi=T-mFH20Rmm!8S4ij1g7Z8PkjeID3ZP#;~i&Ghg4g!x*2YfWl7`mk#O zKC`@f)TM+RVPTaw2ta#ZeZ_93GQ6zdbx_0v(^W|FnjZr}xrm z83YNn+mL!0BQ7qT;iV}?;B;C!Vo{gqdz2e*%N7UjMVxMKJ0d0q7YD@#g+A(J+cKd! zdu8y>tmGXxSZE~fWz3?h6I1zVe%)Of(NFy9`}P(r8@cVXq@_d&1D z%Z^t8-&bOP5DW#OH(VneK{yfK;K=a`WQH@r@+ZQr0_o!yrFB-@!32qDzHQ=3^<1XCnOntA5&^y!Nh&Lz;TeZ@18gT3UbwNVD%kNT4%oqw|+ zyAW~2pV-cv{lC>TzYc%V4*F5uaVBs#0G9L+@{n1f=M?N68N_<{=2_tH%PQLIuWyUz ztl&iDyVke=WqdwAUB)4*dst@z`rG0jVZFZL3n=-5Pl9eFpzq5;!o3A2r62tx8>eLU@-`c%u44kze59miAg`h;tDq^OWBR}M9hduSSx)M9R_-1?e|?(MAH9;3XZ?wq`<#yho~f286HN1koXS4kNOg_*jgE*biC zmsyN8R<1NTmluh^HS?OAu{++#D0}8DH0@R_T`tp9ZS=t@_$P^VQyrJ<&!{j%o9D+au0-DuNcs zSg2dVjflO;W|`Z!Xg1LE2}^00j7m#et{;m7Q|o;(XlAR+68U1{=hz*}It);OUGlSl z{l1$X??MI#rmF&oZ|J#@$`md5s3u$P9hIFK^dtL_K@j#v9i`8oS-EgRuze=1hp^!j z6hAtJR4s&rGJ)5X-|nNrmj+7ID*_2`4S(8s`>i-}Rw^PWgwuUidK2{QL&)8`1tu|m zVE0EM!W^(|q08#;)3EbuuXM#FI`;_`2+!=O94Cpvrcg?v-3J*m=o4l`9h=ZyIqhBU z+gZ6sm!E|6qxYVLn7DoAO@q1Sl7LAs+HDtV^Y|2)s+NsdzBTdpvpwhM%2; zeL6B5i0C!gD=A2$pG^hgg5U5yC268A6VO8Ap>j;sE^_4IMDEYhv37jN!>DYcbxQC9 z;0AB7QMbQ&j*FV1a)L#}UML=F)^8_~5B$iLH^CAS2*M%s)2K+hZQ$zSQi z2kKZITBn02X*_R-xe;CML=Rl#v9~U&p|6E1dc%I5DV8^LueDB%U>U}qPDr2oYq_%a z;WEgtiC)}o6zAY(R8P7#aMva+`hsYeF>-3~j-IXnn8hk%^(*jStJ^oTx#Uc>44wGw z*fW;-B@g1z@g-Gj1hDf#M=dMAf6S9XQ!lMa-f(#8gfBZFmH>#XjvJQh>t?wlqJC%1 z(Beui=0$P~y&;%VMRjYO}6c`C|c6uLpjiFd@$NMr=S zXQ8sU^1_NF4xuakJLR>eB}>9N^pdB4;unEaSA+a-qGT=J+vmi-jAc8E@+bAMT%)<7 zFhi7zM6&^+s6l}tHyKX$$c7Y?DKt=|C(fwfrK^UZpZ(*onL_mj!-)GfEi@T+_(GoX zGYH3ch#M(ijReQ{bA{qBk;gN3Qg!?>{dvZ)M$!HBk@2UJx2K`8MGuNqKRB44XD*Hxi8hUVcXS!cdQ{SQnyK+GKE!zb6KaJb+=hX;xV^GC*^iF z*M${BPDn!ZQO}(#L40*KUxXh=7}<6;DP7dwM99^1Fi&AFEQohDr2V7gvDzR?He8#LUlTTOJiR$UgX;FH@u%RVWnGqo6Bcb6 zR?^o+<@tC*D*V)7J}T>o0-l*zV_z>svM5nCQSBgW?E})cr2R5aWt5>N5~PNd0JGZo zzL0DROUuV?NkSXrz_UE@rUrui9AAQ=Z-)ROnzw)vTOT5^`Uv52j)MGx>FMMxP4zQ zO#sXaYL0MNa${$rR)yo9*@n-4A3jOlF{G)PitYzSEZN~jwSGVZ-C-LJ;XTDWSzB4_ z>BDS^uZ-Bvc5H#k`_65Y_ufzzyV=pAAw^EG`g&_J8aMV1kg&ER;Tg^pQNKSn_)%0F zf1)R)yKHZqYa)JrRoJg@5p1gNwRrNJR@2fT`Q%yrK#%gUOo$9LT=JAAxo6)T*ni<={c?x; zC(Bm#c-~eWfxgaC%5$M1Y4&8t5NqWY(l`RCFB@?m4!_c-O_*ru#}56tG%OlYnvC?y z0hmi>n7%v+HxKqr@CH#C4gMC^N|XTy{9Gx;lTg$t9_4Zx?qk|`*VNCYbsBB9Dkw!h zo^fyDR6IVoo{_9&SVikBDeKoZH(I-8)M(-?t?k#2U_#6IGp+N?m0!E!lPwco6X&^n z!bDW~t&@>j7x@e~`!Ma+>GX+a9^C3{>*50I za*cj6Hb}8;sfO-bL)#j!lNc+`M=h^1f{tTv^a#n>@pv1)62ql+B+usYksL(<2o3Y! ztW3n{BwPFX5Sk`E?nvX}kE0L27e*_J4jq*0+(UdN3@5z*{n+L=v(;5QN}@ zya_^HMe>f;L`qlOzHib5phrx;>I$r9uy(OApGQ6>dXNI8{64IFMR=Cr;vI13#<}-x zf-cr+R`wMS2gQ&IaIi;P!vzo`f&#yh%_{}w3j+1kq`6*r`@4Z##eleQ(6ugbjB(f5 zGiV4Alv|92ww6Vo5MW~xr|IDh$@x)pyY@$tK`%uvFhf|m0e1TkZf<~=+fU#sgpJ0R z{DhobkaUKF{Ot*ipds)%GKk0<6cgl&?-Ih(9P*GL3_{}z^xClXkp2Xd5pI%b=i_JC z5b?1RBN6z|tcmhO0udyq5K`htCEC+AehYlFNVhELi)Djr4Y=nRv+cSNVFwdh zL`1PAlBRf3@L4;ZSCiHQ{`jZZm2#v%tx2_MLn53>c~kLUij(htb2XK7Ca}TXMdCTI z03FrQk{i*oiTE!J@%(g1j}W>ay-0StW3-#`Z%%?L^T-|xQVbZoVGoE5pTJR9(W1Io zZs|edQ)F@0{&B@2Vi_2Fa>Qn-B)iRSAx(g}0^t`J%@-ZAC6Bw`@<@)^;(Q>6l8}%i zgcuP#foLBajkpsNL>AU;`06oH2L(|I_@(lYh&c;T2D3*t;cqsuXe8aKh%h3=GWDs( zXP^SpqniOjS{!tB7^{6^TqGWP9f#E$Paz7}n-UO0;zJt)+mQ+~L->Q%Ksv%U<4O>- zS9C5U{}l2b z@#v8yCa<$m&!kh(XJF*#kx_aB4-ewvn$n!!1ihk52SG@ugXwzkA86p?$va26V}^r* zNtm(ZEhWf?;%BdKb%s%@Uf7D=A&?(^;n7d#3yP@pEGQGN^b`W ziZ=1xpFDGyVkwSYjPEOgxGsK`o)lE(+xCXoCyWRSRTSD<5{q6giC=b2J1I%C zD;cWJdR0)8#H$)Is$!Q}ntNSpI9r_O;OR@Ga=Zn9HwyEjSNT(XbOxn3l$N%7l+c#e zwZbxpRB$AKH1G1ri!x{T!p>zFoJgg_8|3Z`%95yn+m*lSC&tn(8*lX(lLY1@D?^O?5PN^fz9?O0>KL8BuWM39(-q2AQlTIcyPs+S zE42Apt@iGX);;g-m+4ZL%kWO|v3gqGugH;P(N?a|I#V(F>$-f58&F?9>IkIp*5R!RFC9?R zvv%Y3RJoMj3Y%`SJCX$Bv{qxlj~LqTegLGsN5VBASGN}lY2zH{#}wt|9j9yd18uJK z`k(ihqDuYBfs3DXM~;0H@0zS!I_28cJIZ>DYP!faTAVSv2{!tb+8t%?41mH~^?P~= zko{TUK7$I`uAkK5D+BKzbXeI8MGs3YTP3S>2&$iv{$v zsh&y?O<)ZW3pGdTc4KV}n(B52v{RX)E2unv0bcEj8rj3TiH*j0XgY|M-S|dy6Nij@ z1}Qg3h;4>5SNRh(sQgyx#D4+B(xXMwLk5uH4ajKHPip7!Q4hU7BHa;KeW~k_hn2^cTBgZ89?^IA>*SJVj3|t-Q$X*7^5?HsB9`|7k*JCN&`Xu zRBcPd4^4y4c=*Up#Kidp++iJO`nx+z5Sg@(ffTj*+46ZrenPP zi9e{)Z{jyU6OlipFqU??eJZ|x65KN&Cp1MaKw0{NDomQ|{0=3<>)M!Xlr*v-!ezt- z(hulP!4exAN2l2ZC_eq7U_|EtWF*wtv9uP%AA~gTom9+3LB?c`D607>mCR;|g=P-> z>IbD~*-;a6s3{7UnHZNz14tM1(JYnjWCZ4nS#T5C#yC#poFwMFk?sruc*3{_MT(pv zf_6Sg9LKSlv(qGZsFao01RlzOO|$37P#-*;Aod@C&^1~$O&~9OfpnwUi*Zp*?*qOC zI3Ne$6d;Fb0s$Cv@gy`VGT`Vny2ln^YEAN&9ZO_F6Y`L`kTr_e^v$k};G-9V=1$97 zr%Ueg3#8z3vf$x*5-_g?Rk$XASmVzWpy=fVU9YZ?y7WhbS51YMKJZZ}Ij&G*zMraG zHQiX1s9i8X&PSr-)^Jd>4nosT&@~*PKH;_EO#yI6EXXJ;2?qKo>O}QPV8R=@Lg}(b z(6d5?T(TA@H&|P#JEBNE8umV22HVV&BG>VBKjA<+Z^JsC7+FeQ`hG}3RT%;Fka?&NfD zCbVwg1h1RwZjsytgk#As<93(SfuK00Jh|Iu9O3gI52knu9ZO!pcyfna7zALP$bG|ptjC=so)d)F&K|EbS3%pGl0q9UIe>G3qIK?OPBqD@ z^?{_;uHn!s47o;VvkOHQ|9VXkdzS)ATJCIcSUf?}`Tj7s8!J9~pGbH0QO!pHjKPn< z%hMs*zyMDit>*iGR!+g=i9hW8{h8%;I8m^anMH7Vk0l=;W(4YnA2poehj!$xrx_)EQG!oRD zKz{R4IlorCzLny40ZhT2@QE!<9f}u~0CUIQ&hthOTeu&NCN{Pa5?<+Q~3z zF^D8{@d%tjc?oC6fNlzkbiTX&5#-x_mmgOzATxp_N!35ZI=@L<{=fzAyPzL}HLAoq zCV!4jU{z@SLVhij**kIqPra?do3R41VqgdYq+wb+7*&SaU_zj3aC z?pt|*DITkbSZ`#4=E#QA8#;_QR@0ki`J%MtRZRkU&v{R^<*RuxyPr#Fnwp9zh~!Q; zbK2EbdmP<;komo&k57%HwVB~hDh|AKWYZjJVH4p-{x~zb;+e_d5O)mwHP_LDXRqK6 zIG$jd5p%*817#V#DqXn6ua}OArr*#nmRY`z*ktVG9=X^$d{TPi6=zpny#I@x-da!n ziFx#IO9Hy4h zFSMG1*%N&oIR0_ilvZJh1!wZpwvZS6+Xorsszj%>A_YnOkl$hAMfH~fUvviIwxerQ z=cEhl)BPQTv%$c)MHvDBgTt|6(e9JIM#KVVz|SwR>pyXI!P)c ze{KvOVl3PcNp!4BF8%AX`}xx72lPVxOd6RKWr}qU5It3nxqWiEdpY|PWQ;@@lwEQz z82Y+5wtG5Bc$)izk-fi2Ml7vCu4Q6NDQbPXWV7xw5qKx=YPc_PsU-~!s8oBydHJJ8 zN_bBR-&gS0AeO4NK=bA1Rc`x1mOrHPOke5S?zL$TGA_JZtCyQ(mp~>>lzz|CoA18E zwfQxJsq5&g=?%S}wONQ99fnnKRsYap((vkGsh?H7N88nM-Tqt>KchJJ>+crBn1L;r zxW&;A@qTENzRh3k@}-Hl?@Zj}6WB&qNGXp*uq=v`q`$&5F$E>|FCin?e7y>c{RTDe zwddKvLNcSCO0rYM*C;bopmTpaStf-hU6sB)C}@1X6#EqRG+dk(R{D~&jLWHE<`FEn zVJ?1%(e0@-fmqc&%{^MzddObJ=~KTe9{U7U+P?QBtCIOWO7cIB6RJH3o`=J@+wwfs zMvIue_FoRa96D&{WOS#P-pqDeP?5TXz_cQ`9gX+pAtK~pqw>7<^!)i6{Q!*FIAtoKj-etqa2P8+GlcnimI5d zPSLZ2>tTbah{i2V$vb7r59i;ohWYXOynbuo9{I30xD#PK8R!u`B&{csa4}V+;&82c zo*z>R#xcAZ^M|?$zWSF8wUgz6$ zeA2)Vg}!;KI+6k0#S*dI)ywFSAdkd4SkvgxCwu2Q?*`G=$xFKb4Vuhg&@gtZ^~TY})=La93zN3^bEbuWQStX^X76 zbL&Quc3{J^9{Pq9iegMxLA#?^f{d3401fB_;%M&QBbi8#(IyfwLa%37!2Cl z^C8BYBIAIc{VHfvWf}G*d9{v1R=8FxkRK;&Ht3l&jp}6dqJAD3E}_8ZUe#=*5N~iO zw+g{1A~aVMd0r1!5T;jpeO>V8&G@LW1o;Q-${1D-Dnf`#Sz?^1o$&05y)={;Y;$pu zC5-E!G=7j8__ROd-m;ZWlRk#$Y#(GQ$iZL$MN+0`ct>}@;gN97oJU?LYhtsK@qpx` z8s1A=r5pIeuX<^Qj|&trMatzqbORRqk7+jKR4mV1iI>Mk-fM<9#+FbKrX%Yi9~nll z(XHUF>C5+M-yKIQ8isdEH#kL>Jm7nhdP}rXRkxqe*6l>57sD^0;JJNekqZR=eB*qB z&wAe@VN_%^cSuDONjWROyeUdlGXeI3T$xK=E3vu0iNvN%UjU2bm30AAjKuLJh=DxS z7q^DK*+YxCB-l^3Ej-yCTk zYxg&s*?BY$90`E7%EPrb-&GBD9LwjLX}p?)wH&a&y504IZ%hz$V29e9SUC)P>Na(t zaRYd4+;C>YF-3D4a{zqw_BwW?_ssiW46hlqSc#il`$gh;9E{30?q!NsC?p9^yj;GJixQ znLQsCAN z)lP6Z!=#yOy4u)A=l5eBNfGfOqqQHh-Z&!X`_zzDYtk-+I+|w(N=UN7@s+AaeS4rD z^|QPAZqlgs$8*}Hb|tx0#)_HJPcoR-dxn#VM-dh0H&Dmro@U==b=N^HU!OXs~%QVN7^P6UD^^< zmB$4Ur+t>B`(54@>=XV#s~>zeraW3fu6Vx-KdgB-n&_|&z;%a{DvH6c zDvRYJ$Z(*3b$AtUf=4_c3OkTvGQsZ8&o4|dYS zJl=SoM?lXG;sEh3)pb_b%X2*t7Fh4SyDcAn65=U{TUsI9V2+ykC1$TNZsm_&u%Zc->=AiKb~8j64fmURXpYk zRW(q|>z0e~RvhH+v-T+xt?1V_AfRlg+H_00j*`$(9Doli!i|-B_M5G)l5g^R4GIS0 zgOr5%I!q1vAN3<>q?Gm?lc=^kg;N1=j=K6trFX1eWYD+g~zEa{SO(u(ml&;KeZ7)>!$lx!&LZVfe{V z6wZL3-F-2(p%J!0)Hy7IMKNlsZ(fyvy+7${s^W>{$eaES-Gkwf>XiNFM+SH$=47bS@ zcjBZ(gET(AQv=au=PM?@&=|)bSB(H*gVs54Jnis^Hvl;0v*eR*zn%gU*J`@?oZ;F;Q2Idvxn%k++bF&|Mgu7AMaXtQtyTPOD z6%RW!;-=il)z>w5{G~!G2)4$#>r*C1qrPR5ppLow zviwnWg(!N)(r+5@+ee+Tl9ufj@?g(%}}pRe3HXMZ~1DHD^)Lf zae}8oPvx|cZ%(fiHY#wbhY;ky`86$c8Fitibzeyz9fvXe;AVo*Zbs~g@G5vlf{~C8 z6x;2fD|s{hl%AJmPJc%uk|mpf2Zu<381=AF2O1uo@k>=PRqNh`d>qScE-l*^_t`W4 z+&24G_6`F{fyD3dDXkm5lOA2&xtXzOJ^h^N6e$D4%V|B2IfwPoB&_^_YJaK5w5o|GaSCp<&)}VE)D2ywlG7 z%ggy!xC_oy3oaZBt|AL=N(=6W3m#95RMt91*DHJAMm-q|Z6yoU@DR_rh1WX^0hbGb zxQjtli@_X=AtH;RN{eBJ#x-q`A6a4t7CYPav(UCIY2C&+ZnQ-%I`YJSt!8ZZ_$$U+QU& zL^cpR$x-JjCEk8-D@u%vGh8Nlyxc>u98HIvMzuT^WePeq$#S9xE0Wl+m>xR6wS_IW zm6%q+O=eH<%B?}3w0$*4@ouW=h!KNc_)2Q(O1yv>ikIwF&~gXWY7fV1ugGej(rUlq z>cErLL66m;@YP`@^BO0Dcd6!+=U8JTQQc4A?H%TwQY({{LsJ%Tm+HtUnTR$ExNio& zX9u#E6lh;UvxIqE#MAYk^V*XJI2+zuC# z#<{??h_RPsqXWQr+CqzdW${Xz255YB%=a{K?wXgFM(C2|95 zf%Cq9v%%UnY(0Ex6@&-9ii0PyXa3Xc_52UK-mlC3e^2(dZ`I!A*RA8Phgbh**Y))9 z(_f9G(}U%&habQ0F5h~+?;8XE#jflA`t<&%54#%++n?s<)<5m6eb`)``JZ^bbyVB` z?e+eTQP+QXy`91C+eXsV$ln)TZ!<}MVZD*=`u``^Yi@5S`nPkg@BiWTvi^%wQegq| z-MhU152?2rLjRZ4OHE0x3b&1qkH6h=g-1n4Mn&J&kwQZP|0(qXgF^gY2YCdA{!{9? zxOx3Iq+aen7G3`nrYGo~_!raT@krou`+Fvd%_Z)3*OkpJkkvWnR_Z}s#rzZN#DiO`mwoRpTujo)?6JP7?O(|x9RmvuU6b3HS0(kod%Xw7 zHj;8`|0H{VW?serN%o+Bkv;BzkiEZUk|h63yYh;$aEmZ=i7;_KVC0iz{97q0^xt_s z?T^za3S+JH=x7!N`hIFq7Rpw0F1}yLMSxvP67@-tZ<@oRVa zBZrmm9`YJc=H3W!_^B%z=Y?0N6$%jFZsNoBxr4t-{pWg>G^Wd$W$Wvg`v=r=I?F zONAbR2cw}lHN|o?@so{G1ER@(d2%=txnzp zbQ;1BU!bH2N-KY1Bp<|Cz#H|TLk&@Yq;{;RX_CKqs$d|gWFd&a+p?@>u~y7T3W z@$l+M*A)xTJEv2s$AV@?vvw-o-|9CNora7xB~%_3Op5yjqbpv? zKO&~A)@)W4n6`|#_rMNXnR|4#WwzrmMWoRrpxYv?N~()85ILqOdu~GbW4}Nyec^^m0>2XUz75gH8kQ2qarcKw6bE1(%r>K91= zgV!s#wJ_L!ujLP3uYi6>X+UiGB<9sWc)i{NYAR4`x2+01(O&5{&Jy`_rh+F?+NL_r zkA62lS$KmE_{$sFRx`_j1aO`uA=RK#M%Weup1&z)2D9+Ex`JtV_$HF0c{saG&V7@7 zC@P?Kov1kWjA8*2wyokyqqYdS&er@m}hL3===oPY{#qP9sPW*9wL3*Y!)%psYO z#OFPjMAy3=Yxzm^DKm=x2iz*H&9Z~ppfy0ul-H>%%M%#oqZd*pAac-aHJL0V}RI?6S zT!Qu-F)pDbTv|6KG^WN@fER@oSpJ7bli^@?q+MN@cwNop{%6`XCo3RFFM3bE^=hs<=3S+Y`o7W1 z)qK;6JG9dk%Kc8`%i zDSvv-e<*1gvo4=Qcg2t6foVX8;5HhJ zeI=`pj#Vi27R)IfSUAU`Y*A#4N>~WZY^9AyCSmatDR+tLpIrI}`JNR?x6{7#rS@S# z9o3DFXi+tP2-xmA!Z&RGDt{Nx)00T<8 zEAsi{J(`IU&$FTlw9jHMU7pJXB8eV~p|PMpeO0)GC+oYEx^dau=xZV5(elKzC`r{U85*upy)B6KtDFhfZV)49y=#VE+Ej%Oh0BuB&7Bc98d64>40NmU_u$%7F zCh_%x%NVl@Et>eyj2MzjF3}XAQy8QnOChT1frEVA4R^`KB7Wm{!*{)e*8~UmvwcOY zzHWHFFiEpmN1EtHa$3k3c#r&0=H3~*i?kVuAv)wXf#GvDfZvt{>lYU$hRpN$cC_uel_-_d?8VV4L zC-7uUg%ifv%n60y#bJ5CNxEGkD)c-|PQwYdBH|WN4;2B;WENIz?86=I?rLlTZ0nt~ z@R?HJ%pf?NFXUlZMA$=sQ!Wsc7nOPsAIy)V(C3n-3(Wg@fTt+CLV-aMAe15kANe}# z1_m_4VS^KWHp8*MAA?&%QoC*1?H7~PPxLX#*^wgxLK@o*j~1F11F)@Y0=AV!Q8$ zQxu59n`=K4lD^p=Uu&4r06`qQ%4liMfC~|{U1sd!Ms}6CG>c~Tdt?r#WezuIx^88R zUS@vzfSy!#lr4qMq&W^aXAQDtEiYxQUuJD8Q?6oYv$qYI#tpOEsnWk(D)cpHA6{l3 z)8-(AvQLK`d^K~PCuYoh$n1pYbSdQgrp?7^q1+SA#rMojn$Jl_Wa4$_f?MQ?Tj<-5 za}7Yb6w5cJq&(f5nA36|qo*DHRbEbUBIqVW%VlrR)7Oay-LERYI(V8-ALeLTIB{; z9z|UFwOrLl71|ej^u6U&`{{3l{3~=2RnMp29DCA6L{NRcl8V|Z|8Yz9(i6BzL;Sva z8>&@}FRlpAs1~$*8&g*unNIa(xY~)LnnIOnl91*)qKKN?fo`Q{9J^+Q3pf*_>>#WS zM%1S8*Kkxwb2%_kt<+kxz7-g;JHn^{{Kj>-adkG&Yhfp~6399+2NaKZy{1;ZCMZ|N zp0LM)E)Bw7??@6GoLU zWSZhz8)72KXs_#FLRhxWjTwIUq5Ihp`xGhMp&FE39XPMuZ+BF&T^vGOn55}e+x09*2GH&3*Ll-Z1UXC_SvV1FmA&)Z|%rvm8@xP z!^L9gg5dHuPxfcj8`I!oxXJv*n}!{l*hyQ)h(xilu(ULR_?3>%h8!g?DlH-ePc>wF zq`}J=*i|JpB$D25ZN~NQ3?gdVzwAt{scy<`aNKX0B_gZ3uE#}|pA&Trv_f!dAgk4| z%nC^7ZXLki8BIt!qe*1z+{1I+tmEIcSJyF+(M{I|TXk+^Jg8!BBcC^xFneW`gZI?M|ht>z4SqY zZqEHJ)k8uj!wf-#wHb|_*CW~oI2A!`{lbV4Z<;}GGG2PDHs^ld%~7TLA+4^ibN~-) z6KB2>mZhRdNK3hqIl4cBXHyAfH5=cF8iWIQT9eqk^rQZ2Fw!zbBe^8mnVYU-PqA}< zeD%<)HcC+mAu^w-Qo6xxtO4IbiZ|8Ilw5nswYqhu#$YuaV$S{3nz&@`C~5|1M&^{0 z#Go&xp6M`mQWu1k;M`v{Ic;~)1M(ll)*McDtiST;*X)|Ohdm~C&_lQhDXko)pzEHl zCW?m6T6a$#1`d+Tz)I;yUs=K|!)DYSXwRc4=((mnf(F@+#}~a7?-Z0-SG+OGo2M}E z!$D4qB8FQIdJgFakE0aFZj*oHn{Y5+u*Z(J)cj?>m%x(^PNERTPMlzwe|#5#u4y&@X} zh(ASbnGBD^)~wG+=Qd$pq``&n7x=dpUw`f)=-PJjCKfs&Hhl^N{*nV}6E97Y_R}Lo z8HJP?p;3}@y!6;>n%h!P5_W&st3wjZanzG_x%o}esG&Df{96T|dk*<_#xc>vh%G4Y z7WDUKpy&K&rKt4%YvOaiFH)GP*9{Lz zY=BQ0PfYfseb%P#^RuUISjWV_;jj%pAT4H(Ja4aZ9d*V>v4CE0k%KN)0s4ow1-||1 z@w+p82hqR3Xao_e)o6Rwf0m^9I?V^0>42Rs0=+R`H7pax{6E=leO1E#_-k~(+qr+n zZ&&K)KB>!LZZ;|ehN$!Hcz}bXBh$Qdm!R*oQx1(4e+Ul!={Eq$Ke1Of( z)%)=tao({;@3Gd_Ap!R3gRSErwqvThFq&t38677J9Y=E8CwsU@Z!y-V>~Bxf-s}+} z4!W^mU$RkW$KRl*-((&j$evL#$FeFu*g7=@Y@&|48A+!nzbSwSbswMWKR8$HITVUJ zOIP^Dei!y}9X9tH&^kITRX7zOT_%(LBD#J4So-i&Hef}PW&haj>Fd*T;)89C@7f#o zCelIzcTq22pW?m!0qz8*CVz~4*&I3f0hu}g>0;qc5?{ywc;O=zMo=M{LK-aQ!T&oX8feBXZls!S0H2%N#KU}pBkoQpl}3Wd~iE4u6o=%-uTnAYU}<2?2s`}^Lt*}@9VH<@Q&Btp{7-LWpX8! zNAWK}ZM)*2NQ)tQ^cUJe1`m2Va2MX)UT64%Tftp95@`@WDwM*lRCI2ToL`>O!19ET zf|9vfp4O%?u6Dw{mtT?L<#rt661X}kpz&g@Rbn9(J65`#Vp*%qo)aXX!YLi(pmM|O z?J4jyZr7^53pmq$!#BVxSb`Wq391Wg?K`XA-w3M9WBpiIry+hML8#_m-dmJ_B8v&yN}?iaMbG6dV&z|G>nB)IX+H6?zqia% z0r{NWq*Aq~X4mK=kmO(aX`b2f{q2{m&-7>S<++d;H<-M1Deq4YF0Z!Wighd{d<;vP zHYoSqz@uUJc@=QZtUed7C-MN-nug_Wz-17^Q`r72|8+r2>f`d?umWvznGM}mx#c7l}lJvO$a@d{8LDVLPL|lYdFL;0H34hFQQM;m)7<-%I zoRIX|Tuec+(Qw(2TZ?@aw@PDeTBG&XFIwIBocjUxpW{1TkFm8nHEx86KW*MoaGrg! zn|$ri_TzKwv(D#lE}nIlk*m-)K4p|}nGex#a~U9*_7bdTDrq~t-Ph2TH%QK9R6WkQ za{Kv|B74^OSbJNm+nkeWyZgdp>KX@S>CpBU3`-4bPnKwxC0}lkdVfc(CbZl-nbp8Z zdVET;>G0Ue30)st=N6Rm+(**?zIs`=(BU-*kgTa#3dOJ- zek|$qy3ogh&sxQRUX}cSp&!oBDPhB!Wbp4*D_>UVU@>sq0llzuBzIf* znYoRNfxbBA-~46G)rOS_6IEIPHJuPukK}(Xa z7vx~J=@*eGLShC{WflGD__T!W+x$(^>My1f7Q8;N%ZsXLCr>Aqpscv`npN~0rjyjQIimv&^9r@{pon7Jfg+3IPVp}hpS=_tlH z3^WnMdo)6Y_P6X(?s0|qaRtk=s}Cy>O;7P<5fzVwf024?nCABKbjGc| z{Cy|xN1OgWypTS+d?W31*~RXT$OHNL=04i zi@hhSO&7H=KCf5e6oxd|)UQFnm|4WjpV_IRR~UN>Kfv$Eua}!>V5cBn&K=0v?p2v; z-PfI`bP9$Nz6o*5&+cBVc==et@SF=)_4Pc>h1?Zq)Q%ngubR)q|6!xPKHs}>%G}J< z7pGtT*2B|Eomi?OzfZ>&&8mH^{X4sl}qv(a|yC zvEDc9ba;5g-vhN-LcY|I?&+{gUk~f$H!0XZbs>wf=>zZ-e04%ucXx9 z5*fKi&u$_Hj)P-~Z2o5AS`{9icyLGJi*WIPOZY-xdEO z<-;q%c1P?lv&{dvQRn>68?_m=#_V7p-JptQUo4zxoi3H7a44*}t%il;YvD)=-+$Yv zyOSYXmx;8olat{kFNTFQ=cEFT6E-AHks7P}XXT)0#w?>a@=lNcYy0 zlZM!6`Q59V#MMaS+l?Tppx^STWpL)25W;wlZ#*lT185f2Y&B7fg^=e&8bqOov>k41 zYDm`5XJ0CU=;q3b25B;7+$Zj>`Gx75tp>7!Jsnc7&CJ7>k4!cehtBMiNSE<}&+P0O(Vrk)PRfu&9gY0W8( z2Qw;geo9ms5+Qwp-$y{143fNnq6vzAKmz~|!3>#TpwP;N=pi|k9jp+ORFw0MZS%irn zWzL7(*m9Zizv$S&$oBRss(mqMcBrswuDBOupEmO&$>NqK?QqYVX4v6#{mLPaLs*$* zd*;DUkbws+b9L<4k&~r0))h_-Zc=rQvOd0_*pN*DM(ET`o}hya(%?8{p+rWvVwqjG z`omX1l~)RKt)=%<0~P^~vzi~9Wto9f&7vvtQwSH(vL|)+78OP)^wt{mPIIsCSIg|3 zVoHW6bTLkq(D4vQ$*N{M=+V!Vo8&%N^3uM2MXxN-){wV=E`8dG_1=LqNeBigM3$f!MgTv8M(UH&eET%nd^ z=xX#G5q@IV$+IYJ9}wx(u^t|IK;g$vM}KV8!%Yb?lz(j0L3szDT0U<$Z-~ff9C$Bi0V z2q#b;l)ZI|4pS>+rXCtp5Ic=SM-{UE-<&el2RMPN{fSiiC_P5U!7;xfavd6gX%ozh z%72(Z+YnEmqcnP*XfYa|s0yFGu$HYHQp*a$z9*|1CH^KL4B3?MtX|Djr$ssLJ1dC; zKEg)ynE-~)9rQHqdRv(+$0cGVtk`sxUWrztJI2eAoS_IpFZ+cPKt?&kXZaFk0A#GC zz-LA}esftPG~>0^mwfEoO0PHV(9_#*ZXbvQgCHO9QfZmxFwN%jCZ51;NDm#HfkXJq zOQj>gUAlEDA6e@kR+#xkj9kD__NHLJp%w)%`PR>E^f1+}7Y_<`Es=nHpwagO5WCC+ z*gEOxr(p?j@w!Zzo^C?9Tr1h|@DTAb_WC7$N_!TTaG4LDXagE%{@v4lwrqKNdw4#d zt5f0q7Ja~W@}n#y>w&g)LK`+IHL5Tb??&m9?(mdXF-lzCP`z!KUr^V~ML>~E*c`5Uia`(`Aqivt?pYcqZw*gj}o zUbrbmwf_3*oHGonPYHnawx`_wu}0zS?AN-l4VeHVzYF-`l+xuL`IdZIEy|Yu*abgn zNW>x}M}yd8exGXicT>XsE*}c~4&rF)Srx|&PaFl^`f(AvO=1z|B=sJzWKms`4DHtz zw0>ClvS|0Eb_lYI#bo`szZow+*iET`uC7GV^l6UQ+7HW+k!^|hIo+2Fw>!T(nEQS+ zZ1!Sp{y0ooriDqS&IUA0FmTLZFZ(Pui56=vbhA|PUbQ&I*JqEDTJKlMmOmg3zi)Yk z6NmL#(QDBFz#K!XH1RWzN%H*(UN{raYWk^|zy1-b()yCnR3AVPkY1UI5MujH!2O0o z0n8?B@dxaercrntjylqx(pIIl1e+Sq7r(|6cgo)zj|Pkg0EPKx^8s(2i5CZGBnABq z{JieIQn?%eel7szA6`ST1LhY3@lQx1x=8m0@Ili7im5?VsQ`C_e;X2ktA!)=9MHD) zMR54zng>4=0gS%bN^Av~a;OwHdXfR&U}PXs9OPTIok4QQjzO>i2T+L)HXfvKdl;Hq zAB2PPC$UgsZ2#faXAOiS*dWdXFR@@3x#4F!At7O5u1(~TH;UFX54=F|6(4zNiD%zu z?)L_akYkeihmkyZ5fjc~&Z%LlS`n%?xcEC^iytG!2Of(7?p&xSF#?;xRN3K&&xdf0 zp(jLRVX_lS&u5P5+T`){{Bd=+qIIxiv=A|xh^VgT(RY6EwCQmb@Bs;M%g5MKerudv7=SR~bfF+4l3S6%^4lN8%vO3F(L zYUMZ`(pV<`Sg|;)?g7HfQg3{0{GVvQFlUn8Jn&T)#LAEGml?s`8Z>MvxL8Dm9%D$# zm_`nP`>-^}PVm7tszb`Z;7q`=Ps|8G9I&ep;MOr9WC#%3x!&Kz(-(~pwDB~XBx50! ziaH4mRsw$TG0M~?B*nwvR^(F02?TM(dDS5gk4YG(Kp0JYkS!SF_vpzni8U7NWRfgk z5_W_|vIG}+0T5qq!c4o++I9)D15r2#2o90}(csm&WsQp@=3Qd9I;OK)qTJu2FR}*I zn*fKhSQ%Q9U0E;WG0C$uJPaTHyA-S-%@q8alpQ#sRc>&GCfLdhzYrA~ zg<1(pG;TjBp}1NEvDPuTpSaigm{RSM!(5*clZNBFq_Y|V8(pmR74>ZKJSKYIP9 zPj^fbmWyL(qJTQqU04d%w%Kj#rW_+1>?uRQmj5X) zq1dc2n_+jTS}A}XFYyu$0A_?&$0Q7;#1%_8voetfe&8C93=CYD)tPt$4mRJ!+ngkW zph?`~vCxaDBjN7NUDi1-b8)dP_&pPG3Gd)+#WDGX0Hm&DiC87gz->P~&P|*KWxxA= zc(?ort|rC3IEAf_Nn9=Rbv^T~F2sz6-O-yxAoGwB3=-$`UUBJ@EUCH#RtrHG((73Z zP`?AYXbu5!+4ZmzkdE&RaxrVB19tb96+(!Kc6 z2_uvl{N9EPvWfT7FQwR-z$ok)rugPr2+DIwY7Mo5`0zb)VV|qj3b_DYK9Z$Lug}iJ zGI4l)9+^WPrKSYXukXBUMa9AX70{U~Uvj2tEE0!LWYp=#&hp;td?erabXo1RF1v^; zWnNF9t8mQm2eFB*(J)*Kf)8kt4J`bq-SU_vcOkg3=q1pL2-ZC<|4FM%TLB2fL+zzt3J`R6es@LnuOXy3w7EibO;uY`Q5fo=e%S+uB zwb_^npu)7Z`3;eWv^c=S1+;p#x(vK~N7UA_qEL`QoleIvqzP1ux4r9a9wqXq@M7w_ zZnJl5vqC~Rv>=eU zwnJluGh?b0Krm~1P6OT#nBcXPEL^DB6yGq-8Z@O-RsaCBvlwuo|+D{sd zD1gqpPc^Ye7tsTX>zw9)Z)PHI*+zwGqdrRQH+5^qkD`7I9jLVIGmWb?j$-0-97r$h z0{^7;IvCJ(>(EE^;!gE@W44-uR^2g4ebJe67W9<y`K|tiNiYnqoA#cCpE)3 zV@iD{1Grn0p5~MI?UT&+hX~cDE@lSQx45!YhE@I~U$$PZ_vW+nkShj%h<^hi z`W?zC?pX&IAL0(Jq0fSB@&aDos4n)D_ajPQAL)RsLF%@Jz;^P|l@2ZcF=Nnt1ynCNZTapy}7{}&#^)7(LH#OY%Rk6y6?5-Ik z)en+Vy_SqQ#^J45o~t5<|CG&CCtq4yTWMcQIbIXQ?lF;E_XiD~--5RL<6#Xi8v+UGdLC+OA( zOH9pzkkbw*m&ikk;Kew3wJM>K`WIjSFX~Trur@&+rcj#PU0jzLn19RjD1ez~PY$&A z^!}H}E-PC3yYc89bnY&e3?RZdY#IeTGey-i?#h^aQrudhh#PwG6uS?-BQLWrLAs?g zyKl+Z(#p$#^4TZoKEOBMaYFC30$9T_f^X#yr4kuz>%=(h=++pZ4-N7X#gP|Ku=rS?i<qIE{*a?U4oZlAKWq_azb{hj#PJ`Ungp!>TD>-P}jR&!qY6uJ`Z+r-dbz_WP^3?U~plEeX8rS%8opu zh+8fUDB4&j>^knW1XpS@9walRz7^2J zkhOMwBsjU`?ZsPp1g!X6HFT<~Z*oU|r^uTSN@pSs@VNk;T-}X3>MDS&VWNMgYjjJ{5><8I0SDv9zyC`PwQj97@edqh*o=hF!nBARul}!fUY^M`Bz!QtHVjMetngP2~k|hNhtU zL;Ky%Ss{PFE~ui(U50H|(TW=^jfGUO-qy~g{?ir9gKB#tfM0>52DlXl8}+8VryzZ7QZTE#E?~tT}BE>b?dIx6PHJEm2a@%zd` z0F5OjwJr5$bCCX;utzm`U-6KTH>Zp(#ChIO5#gnw_{%NegEE7Az^Z6_R>1nF)%&ja z`PR8B4ilozA*I_sjkP+sk1}8XJRxA;{&hK!y%bn-Cw+~GxtYHyLxsi*{ZXqHQ6k7}u3S?Go)Tl~MWD=U2te zy_dZqAKI%04uZ>K*}?+M0_i}7;n-``NX+#1AwKBR>`>u(XBJj$ApTZ{q1r3i^s`NA zyk@g2>wF|tOg|B>R-{q3%lk!V5(&j+NR&}x&n;ejEY=HMWW7rVZT^v;{OstHdNz5G zz!=+47Sidk53C%%AU47-g*C3GD7M;XfsYD_L|$D)A-(zZ6J?1>t5~Xn0fOkL@FB5j zgaUSaP{>Q&(FZ}SbfTZP1*lsIaj~0~qPM4*RyRM&H1Wqv3&isV956FG;VABL#KUE0 zhhCi834jE+WMeI3}K`)Bt`gUd@@nHjIt_> zhtGH6(@IYdo0-Zhy_2A%atO-_bHwcUkJS(Jw2 z;;kZ6aB&@3qL~#lstnVR`|#egCoyvjy(5F4pc{D5Q>G})qMv3#gxj6bwCd9HHs3;w;?7X7E0NtFeD6^1M3#P??BZg%X!N9QdDW#5&byZg_= zZSY4s7;i@6GWk1>=8-N!^EH@gQAhLJ6^z+r+i$aW9W2S?Z$|GI^bLLomda1&(yEn8 zwZq@b@QRa7N9fz6%ZD*qu0Y-yjl-Q8`V7tXjn;2*LanF@1m6hWzjHEW2-3a+NYZRnpx`Wh$9Q|;u;O>rjG zXRHS$ro`_Qy^Wbo%bERb@cKLDkovER?8u9Fwg?S58zBD<`8{GOKCxd~KhLROW_ zqfBWVj-Ji(@AdAkYr#QAE4K9C6?(6oTtD7wV?tJ|+@1M+CwXPfeE7RX*ckfx1I0wh z(sAp#&pVvh;yLi?VL8Sw{*B_%%BHuLtNRNN=aBnt!%IVr%hd_ap$0$g1G8tm8y#I@ zuIJgdo{sk8-aCv*p_jlRNl01{e3o&xvVB*2*vju!f@h9ZZecu2pLxeOQg>lVu^o>| z!$sTUrnWE{YR_r%+RwOs;%bJJ7hH%ee`+UZU5o7!`C(wFF_Tw9kF4vngre-LR(mJ z1_<{JmTErS?u>g;HG7mWAn~Nulsc-!8(}r!{e|V!nqbUFBf4`KEl={impf=X$?om$ zg8uQ`OOx*`EiYbN<6y3qkBmQ&B0a4R8Q9i;tX~K9vUk0xx~A*v<; zOfpNVRv?q0Lyj~D-a>}#}KYPr1Qk9A8ZYNDBH2wMH7c)NtD$tYvrt$J+F>s^bX-VgI%`v^!pVVU-v}A zdz1}JGPuEa=-*=+KT02miSvc`2#-qKH35t95c4L!mk??T?~#)PNx+Syar5Fu9OKMX z+xTQq(yN_uwmtGW8UrSg=ND4SKgAeEQGL0n<5v+f+r8SlQEu-$ zXh_=vIHYtaS`<*guMq&|CNE0g5p>mSwB4*O1fHGgdtBJkgWGSO2s5>eQUZ}A@uMuf z#h;A6^9R#E93|#Dk!c1Ltb6-6k^Me10Z%~+g%EMfUW+5^z$T(xlV{-N2+Hmt(nMFp zR&C%FD$+O;_?a+J@9>Vj5a!l4;5!Qjt%m8FKz-;*JMBag`!*g|MVb;$)Pv)5n1ism)yc z>G!>r6IccV!jxNb+Zmb%GrSw69HY9Y1|dVrxj)6k9icpg12iY{g>Fp_y*YuJ!{2Si zOIMr23S+EERVq<~``5~~97Es1s&9E3vrurJa+SLJrkWt;GRu)b)X3UH>7B?CJBLo1 zt-;oy;pQkf8w;vq_MRas?2QR4K%rJ{Jko19+DYEszby(*Q%2vC7<6k)PJ3HB%LJ_- z&Hbhd3K$tbll90$VNMocu0YOT&-gt}_eGFAZ35WUI3(eG-b{PGn>l$>F!Dov7Ffp6Ru= z$Pa4TQ>@c$?HXP|(`%LfzcQykuKHi_O>lpj<~^Uji#NkZIm3T@MnHH*P<{p@q&FjM zHFM8>=6>*uNYadG(Tv!;8S%auiMbicPcu^IGtzjoGL*B(+q1I5vvO6ET!Zg9HFZ&Q z5Uz`WNsFkp4@4?OM5>aJoX)fApJp}AXCL6rX;RK<-Ja7Hp3{+^)76{PV+gB+#J6w+ z+NAP!02FxT+0A?)XDqU@QYrm8s1U!f!B7_O!xS4^Y@c1d$4*gI$TVx_TOG&P?j9kQ zdiv8%daBIWms^o`92E9d^TQk|hFtn?`9v$H^UtiJoMFX$Ku=3GGC;(@?NOA&?V_s$ z13&Y5_u&w{yhu8<7H#{&V}|rTtUz~UkVR4CtFSqL5&eg2c~fBvev(9A4XoI`oT9># z7Nh1CqdzUioG-@WEukrw;%+a+3oj+e8y=)*Ck8j0twDmU3?m)pQ++zp?u79j<9nM$ z+W3VAHHE(N3$aZC3-ZU&6)m~e83s(w*@!e4Qv3eF`!J$#raX;e5DhL6B@ zm%$6*qe`&?dyW~osu~4}NLTSEg$Rc|K!dZYMr-F9>LkHVkHEfj;Kn55x;b!byCF)g zH+FNfy-&DB7~H96+@mh`{tmd8Aq<~XD||A~<`r~KXI1ja>ZNj6ZWuvU6;FQ){aaP-{7?Mt$I)MkmjA%t{ufKjKf$-} zpC%8#to<2QTl}Y`Z+|OVwpT{}z~7etSNv^$VeG%*Z;P`d zHw4^2dusn8;Qpti+TLL8-vr#hCDq>j3xcaj{2PLMH#+%txc_emuCBec=pPVVT1!t# z^Pe1C-5-jU%IeDG>h#3M&iIC|nEHUmTo~sb#sm;0*_Nqh)cEm(}@?n3|e_-37$gjrR5)pBUSI| z>-}YBxi6_CEUxgEoQ3b6>|aSWK4B!U@QtEHhD$)|4@Jwr6L6gWgQdm)e#7$v+4!nv z_DRET75_oNIS#*?!EX`Da57u)zttYVDRQ`JT=y>m?s2gAHmQj!T7KifO~PDHmoKQx z>GdB3Tyw2eMj3r=Dz~$|mcxg62!#(Jb90V6t+j~*S7FmD2e~ZoRQ+7DpcsMxx-eez zr-5PY^OR~}#9-=)AAd3zEVUy(JPW2$9xvtB%_(k}U-+5va{k{80p1Sr?kqm+Va6089+Z^1_|EK#SD*yjrmZm2v82;ZWLt zE=skINTG?+y0UthLuT2NgfmqF6oG3vwq@HnK^nOP{+L2zB)0xp9=gtOm<377C0{O6 zYR`30-Mb#dCKvPb7HK80%Ng&B^KN-EK}t`V5y?advgG&}tTa`CvnC9@%OSIy%*0Py z(MjlQ*gtF~;3VW#F=TXe)SM?{-IqD#FGa@@8s5lVV$=$F_?pOA346+jdq3sFF1?ao z;~|NT`e-`2`DBZI`%Jlt;SFzH@XlL-E=ker`S;wQK@KF@427UKuGKYQL)@JJ^nnaB zPbOpr7OheI3!iulrv*?>Iy@2&(S@hEBNX}Y)B5@_PJV~UcH$bkvjwyFwskTY4E3Qs zR>3NhZyDIX7|VHXwoOh#$~=mi?i;3$hyM)62z{5S5qb!WnNvS)a`T5-=XC6SMs0Q9 z&-2o(ekoPY#m8+)Ns2Jyw%?w@ai_N55Jqauj3mjTp09*99(uYRmqu$E7wWhf#8=K( zT0S=sM2WR-iTpxKJ-ckHeg(O4(~OFHJR+ULDN>@AGu7w$yuWBeGQUJpW#;*n^u$D1 z!!@!VSMy_3l;$U7)uOY!f$GIGSr_|fm|vcx^5|&6+mh(Ud%FyLy`kuD9F`2}#!4UI zJ(6V?YVg-yV8my6v`gY$Q+!g!-}eTQr6!i}6ChM^b|>4d3FJ*7niKc`Fn8boY=;g1 z_k|!q;uFMH393dZrS?edz1yl)QHmP1+ETQ(*oj@EwTia1R&8noQG3^DjoPC{wJ5FI zd7j_vysq!K*W-KtaQ_YYA&=v8Jdf9#B9nKGf{GjLt|R9cRpDN<`WVVF<93kGn5dy4 zS^c#)`z*P$#0uucCu&cU{>GBzJ-&q=xYb9ksMB@6s`liz!{WaLTqPQx&n1yc+j!+4 zm6kcazz_|B{mXw;TJ9jbg#KA+u{YA*|od+REgtoQtXF5v#3ud4mXUSKGZ z>(L$b$@-DAZcw72>#9)bLgZ^vAjZPGjJ80_2dW{XS2rMR<99Ec~r2B zqdzWzuDclLpmbQ{ObnDR$RV{@mI{);79WIotCX@^@aQ&`g#TFLO@AN>nOtZO@Rr`kOfe;^|q98J;j~aZfqp9w_Pa|ug)u}?7AO9 zG!5Sl73LDd4|?ek8j4&Hk_ba(UZ05s=?I`HKd;m0X5Vhbdke~G7#hl#=mEqe>~feY z_{0*DTJOf2!bGqSsW3jMyFA_-pEMQq2(=`&7;CET4k3|=hKr6y2CfN&19YP0Wj?Xk zTcHlc-XnByT@?Ln_Y$dnII^FnT6=EWm9;%H@+|Z#Gv7-QiK<1svB|G=gI+3ZC~jDV zpCe1Po0r8P1*DoVesz{u-bQp2DwG)@$i<%C82>Pz|9{><-BkD=Gt1gghUzWYnakr2Ly_aVe=Wo^9WSTZ7_SK-n!!V z6Q+vLfFxa~j1NL+kSRxqL}=Kuqwo)tI z6Ezk*59CQ14x&a8P}k;PwvAVo2=z~w+|@BOyV_R~MT$Utx3QGbB29ZrIWAT@kv%vN z^&5%mEU^+@0Uo#5GW>#2v1b7ezMJkq51!^Kx44dv235;&LU=W?b#=WCl4v=D#Va~8)F*)M`*MdOh3t!xm>sOxqHWZFf61YwVy6rTGi5Xv9&Cjr%!AJAh=7$lSSY~eB#fX^?8cwzy{u84o6iubbHSH)To#4}CKZIL@qYV`{yLjk|L~FB5c_N#+Z+fKYC;&1d>F9RwDrpJn#a8*2RYG zqv#+)pyjp@Dg@10n-8cCpU?it=o6=k1dwcrAml$u4nxEwGsa3%FAt>zt9yw~$DABpV0v zsFV){I6KE^6pRxK z;gq4Ef^%FK0vAOh_JR1PYlONRKpi2OB>*Yfn=An(2ur4@g5V2)9HJ)p$1c>7K>KzV zwBiE$ih(#{AcYuaZD>H~0~ylpgY$9Q8yn10{wfGC__vAbNG3%TijgNQgkdoSUYQ=@ zOl9wt>04>+ECu!22;yOeUv|XR%Bc9t^Ln7!8ReNCHb`Br%2?Q?qe3J=&`-yZjQbU^ z6>~P%$kZp!1Q?j%B9!4F;Cz>zJ3o&R-C@y&Nr^FI`z)D(8+LQO;YPO?4XbXY@hiL^t7evXhAtPSWo)vtymIV<89-)AAOtu9FFBM2^ zp^X>6m)#6y2q3$zf*26e@E;QJ056*Pg$$=(j6X22yBNsEE^N9NkSgULzItgX#y=1R zrCFrkYyg5Hf!`DwXZ*m822csL)WAMK4sdEC#6a^Xe^f}w>@semKoA$2HVh3M4J)D) zU_8jybIio3gvSLqOCV|hgU<17j% zqk1k)5d6c%Qt+a6>MKDHb;u=c=72W#VuILb5UAiat$!O6PZ-s{JF^^Y{ZH?BcJVv-|wO_{$bA?(ys||IQt$f`E7=I>Gh@$BCy%;Ak*PsOI z*$~D(3VPOPB}oMS0RoQ0WXjVSdUGIj^NaU5S>F$rY;6D)Rk2i$-rdGRe=9KcP*?QI zzB^Eu72f6A4#I4+)Gz*(__yr!&=v9DF&{@R0axE zYX|BnS?geCYhLK-lE65@>TTs*F`^)8}7mUTm_-}5$9zCV$QbM_V0QuXsUy2Wm+N&2WK*^QYR4R;Xr z)Rc_{^i4#+T7T^Owqe>abS*5dX)g6$MF0nbbu)EnV@I4}xf`mcsW~CF_LmE*uOd$n zU1LBXVVGXGDvpgQkYnPksU?G@)e%=uC0U<#?kcQx*F{-Z0;+oSTa!UGkM(P|tPQi= zK8&{0A99`F`mzp*^7tzPZL=TZ1U}dy>TL9zJ-s-F+}_j7>1=XUP%bu|uQIK1wZ}zN z4s0PmbMbheeBkUiylu_HdfLeEZosbCHcEU>>)qU(-SMQT$!?^rEw6dhwC!rM4#}ET z$N-SuW@C8`FgJHT0=MIE?|T#hWg8xDcT(_j-KQ<&MR%aGfn?I$qMqHADA3>pYTVgk zyKVqn?(cdSQ7?CjJdFb&+iVI--FM@)LCr{y%Yf!KTdW&k$lddZ<-Pr0CwQ@ki0FRP z*V95O@pfyWJ41Iwo$6=k1G-!s#o6QpcO7gqGFKmX)X!$zR7-@Z2jDvElm?o>0~7gul&0NF+nT;gNTQ9P zdQkrcgYQh~vvFK{K?bx*wHChW6&zeAR}*p~J#^$&8_>-}(S) ztCy*L*d(;EwJEt&znAKBGPN!1Jx8QSLa2X6}Cy#(Wwo#C;8S3ek0kt+f)7;}ceqC1R0owerJEr|Q30hA?`>ux$ z(xJ(Li{n)J6Q+hKbWe{LcWJLce_`QVf#sTpuRCk{Yz)rmq(|<083@HbGT_!PB4!q-$c`1gJ$>|>V z{sagEt+}&U^+_}0G&pQFGM7a9BZc`4l-Y6^HzO_j#s_v-@=oRqM6V6 zVesdh*iR;iDY)c#0Ag_2P_vDPbw;@fK#y5V&hB_1*IU^3{vh)|k2`qNZwJqtASTT# zhoIigtA8}pfj-K=;-FUGOA8YG91xH1vck33%`Rjujd8RBBRl7Z@p(gZMV3h$n2BJ6#9ZLDb>gSy+SC7#91xDA%5dGhOsp^Lxtz^<=rMg0Ma_;t&}Go_sl9E*lb8 zS(n@UqH6k;1-tSZhB*EMc!`6(BtYJY%$edF(zpe!y{{~x%XX4;Q12yr$yMuNh9MJr zq{OO>G%x5=WGZqxkFqoC;+tW_!{T zN&~F&BNkq_Zl~w3!beta;^r6;8>1H}$}ro#UeHM++8HAR*%rwDLYs-%`0{O=GIU0b zxW=46=P**W@D}*^7B~lbljnE?10@a8eYayK1bCA2)zPN0(x6Ok4?x2M5ZlVXFR*4Q!}VMESaz1;diT{M%;H87XGWyXIljSvATAxIBc~2Q(x+O{e*`bSIS0fYkC5pptRj8*3)vR|Wxa>j1 zc{B^mbZVY}&GfI>_EBX5A*OqMu?tIk0kylt63q+{;y|)bErkaw;T`3Try?Y+iTFxah_cJPFde zS({^U@6)N7NSc_gp~6Fjd)M?*_$|zTr%$J)UX%TNqa@JiQth?@)Q*_AQ(DiV8)j;o zY8QF^_EVe#r~vsF88cP&+UHQ9{a){4mBY1<;y5p8dfaV&;ciO-R|okr$;a0_VIx(i zD0jn`76YFI;!X@3oD%bt8N}Zvb_~y?)kY>crUng=?UO?uJS$4O1#euB9kh%gMzjf6 zUr))X>dUl0lOf)rk*TWL6^Kb%YAAY^K;!CC&`uM`ZO(qxDTfFd(a!g`cbF(O4IY%r zFWD2F5|Zt;)7!2*_B>_|Rx#D_>d@r#$?r7n*cmBQX)PBf@^Z?S2TA$ZG)1_Bl?r*& zPMUoyX2pBK_8k^3oKp(TQzE74!2Yh`CA;*8Bg(vzXz}}ukBKI%x1dNbb~?*^k@44y z`Tgc*EIv`m+PbEx>S1=mZ@-m4f7Gcq_2o8l729%gQA`A!xh?yfAwK>5lLI6&$X+-x zB24}%`j>GdE`adu=B6tC=$+1=(y5l<7<|azFb+KfHWm9)Pjr_)c~8YbF&zT1Gg`+C z{H;qq+kgRLtOn#|tXQ3-(;HPVH-@yVo%0z7eUhAUr~5RF$vG*xCf-dXOsfx-nr_su6t}Kf3vw+ehbT=3^zBayh zg3r6KPr5YInf}Wq`qU~0DG=GosquOuB6dktx?`EBfxGC+7l2TGu8|-3uS9vg60SL$)jy!u#8q_nIadt7DG_<2D$*Xb?{p9H-R;Rj5x^06eCl~3| zH0m!^jw!tmAs7iwHTSkeNssJ;fzTox$lUqcm+?pk*K=+cprkX*hiRMdJw?Ii2L_oLifJH!k5W9f6c>)W9&f>Nl&k73_9Bc zrS@Wci%(Mpg=*(k#NEQVzF5*c8<@jMpXq)iQguIczPgrFntbhZc@m>J>Xvc;H8i^p zCFgLSv&!N0&=-J4O1zIK#by;K8r6H}2mW5+#>KZZ$IhApCSXI~#<4XgatWw~XqK&@ z6Rpyl(o5--V7V`EIu5B&=lep{_)w~91p@Xri8B1&&I$r;ma%z1&d2`57mp=C0`ZLV7sImAaBv?lU`@T zc31eAJVoiVW>YelvALrrt&&_BrML=U8^o;!_p48BR$aU^Vx}?yCuVAK#U7o}sT57T z{i(nW*#{g)6%XD%YT1fmj}##l!d!$L8DWQyXFep-*VcXB@i2~ zA?DXr#^e=#;l7x#>u@1mh>U;uL(#PpTOD%P@y(u2&&3tz&H$zGCKn zw5{VY2Cr03*FUh6@Knv^C!JVd(`zqHJ}lb5y0F)p?Dd+pOqD1Rb@5c@#};<2UY-go zBK8a$Np4FKQcD@drUf7V|J16Vg zC*3-^=h~LG+7u1okNBX6*0B{?tX@0Ve=wm%R!Js#5?o9xg=84z}; zCA`Rq$z}NX(lI8qrinU0eazwGD`$(xeNy0@RE0-aGx-kZL z`Xcw9pAvnAr8-p+`dRpnnoRghQtER9=)L&9mVQWXes4U4Tyxat24#9v1od7%=Wme0 zeu!6xVxpJcsEZ`tMJvVLpi7|dqYeJ`x?HV}R?+1InuG2XA@%;EkAt15eFpJdWppOO zvG1h^K7nJnEUTZTG9G3d6jB&YFAv1K=$=*K4UX5#M;SiyOALN7p!2y59gvQdv4&)V zxr(qxUEBkB9emtndOs4r&W~fxK5rvl|Jx}NIR02LoTN-KM2Z-UUGM3jXmGV4Ai@n( zFhd75L*sh!VGPNJ2C=_M*i)Z=(p;(^MU=M*Uy_4W<;GAMV zsb62SzuF9*beh25;fY6G2W*`t1vEvq-auS<;^oWn24WIqdkFhy9Z6uyl^W_A4DmFi z_X?0z6jYe72*VO(u~77;#sc42Hhc{ zKP@CqA%B$OK%Y>XlRx$C&s`s<6#z*4qr(wrT3FTF-*KBGqhBU5IojiT_{y?t3RPRokt12Dr z3Z{ELGD*G2U7c&w+T5>oJ;995;`Gzhn;n~0fm?TQ_;ylKnbK!c+4WOQS%i!A+WOd3 zn&I$g{J0_g8TmS)A7(S>M0NyYr`m`MPMAd=b7!ZxrsIjDHv0POUn({1%1ZMM$xM|N zgwkBQ;+%=)w&^2`D5ptk$Btb+X)<>Ab0>jqH8}AyE__D$c9e~A-$nW_ns5u?8&2S!5F27LPKpPd&B9ODx!4{S3WJUJ{dT_P2xm z?THD794fzhL5+KTnM|QoG@^{lt4TW6?>X?mRgn^Y4u}=!;sx%8io<)^ zzy1A%x44J5c|l180Lv^1K6C&*w252zbg9^3f-DY)*9pH}vRb~u^kwPFdDPkhCn0#J zihb$qs@9ze6aIIGUuBFEQ4hb$iGM;z;49O?jy-g?cYsDhP2 zzWXdvW;M$c!jqRKLN8?d9fas4f|nCC`j z`o^>3jjY;@?Cy=6$&K9Ajpx5MUeIjjv2NxIZWhRF7HVx4-PnA2ceD86W=Yg$Y5L}? z;?38!n{T=|%O*F=S2y3bS~iN(R|wKqcGFcoq^q`zy|lae{_a-o!>zigt$NSckYnev zJhz(qt!naC)hD-xUt1q&w%b^@+Xc5fSRG%2Xo@B2U5*EfA(5n8=rR+qw0w!)LscbuT1Q6ltiayg$@cP7|*t21|$p`xZiv6EWgmc&{q4`}V{_11&o=k?v0()5nD0tG@{*&iV83t(OPLxV45)y9c z4Ib&H(-H6}Bb!Uq->+HsJWZsRbm;K|07fs17UEMBy&o0B%E^KWVez?m>y9coC zA*Nh?`1V4OUU<|FSk*f!euwqa6x(gQ1p9L@2-RqM^!^jb#o5pVOr)QGx>J;QcIsZl zFzrXXoj8|lCAs9qX~;|L&;{Q8)XP3m_IZ-J)RA63k?h}hpYP|D`PfVFM3xRecxjqz zY6ZEz4B`Ik!?p%lYQ-P5;wA6<@;&_#&CYIaIpe*9ua=BZm?uj(L*!(Alkv2yw0^!U z2azbhNV$@sP5dr#P~)&i^HFK6$+?^JjysC*0#dzP{PaEy@vt+;3;CLU7&6rUsfe7? z3x*&qXPo{maXbIFCGOGQ%D+RDKlZlHLzE}qm;R$g`H#KC!*9#~3{fuqt3tW|Un-Ob zo3sC}P#!J!onzeX)!Fk9%Nr|8>&x@2U;m58{ok2P{D;c@uSLo)BQ5{^ zUSiAtoTFUtY5Wh2+w?Dt`|rubuD1GrO(u?3r~RK}+~#wPoByFZr-hW&)c)TjZq@(o zSmMi);=-4O{}@aB?+tF+d6Dw}rNKQv5uNWPCjAdZ%Ja!YKYZeUGTeXGDX$aK{>^ZG zd>@>zCjMLE8ph}8#{6R=(I6)0Ul>;%@2(k@qaK;98lLqZ7?&U&lqwaF_`jC8K9T=J zlrrAU<{aZX{uATc;atv(lrL4T{i{eBtcv+}ky6{r&BVe+-^5be@Vcg+xw?)SR?9?L z-B9B8-TyI4DfgdI%Kt1kfWKQpnrkbiBBL+zdv_rLcNC*D}Pesd)Yy}9|^=)*r+ zl>gdGjF8=(ZF}on2V+o_;J5PeSbP1?7UhQ!D#cW73EsI-vBnEGW_2stq&k-s{@Y$+ zU@hv?Qt7p34}GlCB`?WAA6Vb?AFWuvW$!&mL5@oXx;}J6K;}7Kfgc^g+vDn||Fgda zcRcQ7H`v_pqg4AG;2ve?ZDjY*T8RpAFCIkCGIpOm5xQlc9#z2j!c+4xXc!W7_gQ}{e5&Hd1F z+LKy^g~yvR{{~w)wD%$o%en7ZfceFJX;1@fSS5wuD zA}=9r!RYnH6ceqDiFiir4PvBHr58;a&GZx@1s*CjE1^GPF%;A}CrHTp11nk#pb9-2 zmaCT6v9$8gd$smF=xSu4dcbqdrC8AG1BW<Hx`m}i_uDJP(N7iBNKv2;a}q*$)-SLzqcn=j*Lub}~4-`c=zHcJx6&z)Z1TE8HWlu_4yZ14NI+;O*y z{r;zS7}$L$=GsrUE{$~q0o+XFPKg-v=cD%&Ua7SfWbE}zOF8G^RMTsj-zknX0-2C! zSVB!_O$9BH{`wuCoH5qaT?u_Qi*l<%`_ZT+#%@~}8zTe^kJsk2z4F)C9gssVHNzAwN$eJwcRrn~-ej*%?1cG~{#NaWAa+WB50{U4S7&&FS0P|)hME$DXNqBh8*WD`z|Nm$&@w`R(^U()_%SUGzbO9Bt7P|_&!@Xt=q4r(+Agi$9 zt0uf`Am>le6R*1TCx%05{cf6CCKJ)Cj3)hcL9ggDno!8z@}&o(lm+im$;fAp#(oW5 zK5`W@KSJlRs2}h^6Domn0SJ1xLnh2UT0Fiqy6A!wLtsBu3hgmoVITVuN8sme$$p9D z4A%?WZWn&Ttz*#I4P3_Q5aIGAT7Vh9T1aP>(AOfSpSov2-L5%mNhm2oL!IS8#Sc_3 z3&j0zG^hWyL{y!wjr>D(v{vRm%Ey%#TS~(F${FX-d*@-cnc-T5f(xUZ(L@1@vN(7I zx1@Z(%))4YWPenVpr$MKBRU~0q>wqTGU*!oNQ}=qKDKUy&1PRRp^#1^BTEe-14}ju zCv}F-jsWv{S_H3(NYpg(C03fwjC$h02MU`b}&#V)`3;ztf3bcgwq7@q5w(d;mQ z$;BDca=u2icYYsrO*CU@T$ zxoIb2d~GhgDZ2R~8kVvn!Q^JNA+b~0k`|-$Mvr;XETW0=*bnFnxD7Xo z1Ilf4ZFK@JG!w)g9rvkt81z4(;xwbEJ?kcOM5Xp95Wa@oMEf*IDlaN5w>|OY9Cv)pYb&XR4-ySxdeBMp0YhFuGg@W&ce-+oY4lIFL!S?e(bMeekAj*Z% zJZb~>DEhxJFQu8lnfA;XN6H|s%NvUW%T9S{ZgJATqybht=}(z4I_BT4d8 z2N;^jH=o-NOJu_MLIkdXf`pHIP2t*UQY#FR{`av82wABz{3;X!R{Tq(&H1jmrj%4T z6v|hkE?0}!&yJi7o}8&niZDBux1fqp z33F%de}7f0pZI)xV$sU@SJKChQYx83?u)@mzVq)*F!2Eu2m~nrIeCRR<ekDf%ehAl+ZZfT(mg`nD~-A_5_P{m>bhhU3Up5n z%TiATE(hQz5^x<^Ksx$d@kUGKQ=dl?sZFC=A4a;6S#W1M$Rs%=ksXt3(a1j>wthE-eDhPJDAdup4N@wZ5J}`| zjYxoo`pwD4&Sg?e4AVgg1lm35ZxcA)gl27z?y(6?z%FdX-n%mda)zOE#?Wn|lFD`B z$7^Xxs5rV%{`p0L1(OR2XhHxQ2!6;seTI)K!23c&X!qJE8K1>c??F5BXdy(ZGYSp> z6=38nP$mbwWp^hF8R?RZX3Suj8Yyj-h?~VB)CPXfSV5ALb-14FdrI|P3!rMPS z3!$X~Wf%(srcn1=asVsJL5Tbif@aIcUCqX({9!|gr=;xF5g58C$7Si4y(lFvCH^u= zzn#Z87DDTQqB$EzW=;!c%4c+%WOPl^AOC!0-3xeXrl{dE8A}s(rm{TbQ-7MI7wp0> z2tTq#Kk^a=eB_fb>`zSnANtn{W`$+VW1Qe4X|%6Wo*scAmNXMya3_MqSIhL0Hn`Cg zyX`;VGrgfa!*ggBNsG4dtieZ@TIOM?@VRXc4+kO^?w}DoMHM0w`Jey-?JNQQbAw;! zFb%~gm^1sD%0;?R=L z;t*@k=`6tp!l^4T=E}2a&p3$!gGGQBZSZcEBs#sMML{a~?`%}NLm=gI(hd6Q2Qe@l z4Rd25J*VdbuR>u2F1VwxWkbU(q_C}%N^_>@wzSugFW3lExNw)=>19-suo4hL?aA&b zg?V`$1k#aUxP7k}7eOURp(MCVY3k)-wdrA;dE1p!RmY3+!N+3zn&L=)5WK>3X`>|S zaVh>W5IKX@KFccATP|cPqDy?O0aJLD{`i%k<*Uq@B0}RU_r}uaoUf?_vI-j2^Ek1x z3-pvDr7vfSoMv7t`jr3zw3O}iooz2GUI!ey0A*QkzUk!oEI*0TA#=i3+z3a<=O&O>5o9-A+l@v3nBjgjTp8q8F%ViQknP!*Rdso`ipS@zcwhzd z8(vg#8YRWjMtwAhNl*VV|HDrn7H+V%<+Yb>WIt6CFU&bkJfT0=>yqykkNG-2RP zY}Xavd$5!{OIDduzPF6iq_E~doV@=`^Qz_^Af#VQ&r(G%ZFNsk^JZLaS|ymyyXL+k z1`~*MpXFA{0|EonPFnuDH4wE=_zKhn->rqeZ1< zdv&Iw<_q7*sa1d=%AAG=tg-=pMa0WKmSBmPv_9rHvkjq@EO$Nvm2a55j(|Vy4U{8g zonEy}#3nOb*`Z|*38>p*&TVW=jAI^aYVJeS-a@p@WNZ95 z3vom))&wrLq!MfA6*ZHyTRXK{gW8+6`&8HCkQ#x2_bgjh9B|C_;eBl@81&(^>Dp=> z>(3^(DXup2)J8~|=DQOXo4!khO>Js^ZA=UiFeTt`HWFdeUSIX$v0A%{cRROI$IMBc zz_tco5G&U<8_FFi7SxfO+|I+-DPbT%)hvI-rn9ZKLxEdeii@4`lv_%<_(|%>dn{Dq43dN7PaYP(5u;ll*{d7IraE zyOYzcI6_jX?DjO!)W59c6A#EM^&rMcUZ-px+$^WRNsqVDB`1JjGk0`6OTd{D*<`dQ zkl0~FCd>Qvv{#dp%b3Zc$kbEpv!Gs+s$QOsmgjTU50pMWUh2YvdMs=>p5_1q8-%s{ zM@;3%+&jILppTf)k5${~pv#!QqU5GIVJDkb6Yoyu#hQBVewIb@HDW&e*SMJmo0%t0 zfejnha`%cBt05Gzyj*F>g*Y^{I0PN(sZnCk)gS(GdB_pe?|>en832GCK=73G=kl;= z*uX99pp^Fzr78U|1?)ZrgF3@?(BJzg~*#d0!0~BWx5dIyAVDP9^`#WgM zD5K<<0(!vq&ZvjPXf0t(0fu1S8ABq*Tq?&++ei4khvaQ3`9CwThKvV`Fd3bUa>7P+ z76(iz$LT`HKS+$4@nnh7;JitgcZu?!N#XY4gX(de9a{cB z5dU1J0R73J9pqvTEB^DOZ|<0v#Av3;rx*_;$dEaq{8C23xQWDQGiF+zIGrYTK6X2) zBSyt<%K!=)FWfb9l5v4A`_q{{38ews>L5O>T{cz0+z) z)MkMaL5guh9f_%)+A=%r04ui0K->Aea97~r09tX7`y-f$x48kcWMeq}_@AL+q=VClF&0ud;K z%!dOypw%8xz_N8Eb%Y(I=GUDDRGF7$MYly+dBl963D7;uV1O$TQXf* zU}DRtB6;Bb1|oC=0oqm#-B!upuGnJk9;~VdBM1d>{2-ciBKH0Cbu7HTV+8sIZb8-% zM9OerTPvS@VV;GrI}qW=d5?uhR?IJm2iYOK-hM-&H&Mi89ZzNl@!^%Xi-HGhl-{di zTl|ad`X}f``H}D2QRBT1i~#Q*aGQ;Zcke5R5y`msV*!2^sa}MDPcE?hR!08#3+#Ry z*HBuDp-iSmV{Rqm|F;{IQI zW_}p#uh$QCX~si!2vJk*_g^yB;y~-{li&_q_cpWs{DFaEy+ZuYTl4$!13&dtNA2I$ zFNE-kQNZ7HbBo-U>kiuYy)EH*`xi3wz;)=rNL8Z}!Q7L&c9FE3xcB`u`Jd8zKMC{dugxLh0lY=xtU2>q&sEQV zm7~J5BW;USyU-&l?5;3w0|-41IQU&L4^*i#7u`O|aX2=w{Oy3AX#D_WeHU&^`iYP{ zy=r>;fxa2zcyeRpcjDO}7I!#``-onivz066sFFf{@J3u{E2o^EeiG@dx@PaH~uAY*+D`7Xi=U^T+PNG zQwX$l`ro-%5gg{L|7=l4tkXMVITX32nOrzZdg$Wm9*~2z2Cgm_+aNt`7QeIcCAuBe^DDq?x@xB ze{R)OO3RbI53IB@aNpWrE@KnE-JNr*y1kfr`hpSn43~`i>IIcAIaUuWb2Yz5ARnr) zoXt;w#T1pStYv#BTY}HN9C1Z)Ev-z7sXw=A*!P^takIXw_uFT4>mzKrQ}5*Ax7p}# zG`x0Y<<)mcmpp>)ly68;`L;y!-hT4dc6EDRwod=) z8%EWWgW04Os!K%`9pr^wK~CdQ6Ep?A>On7qik3j72D55_xTeN0!XOLtZD|A_yYn(X z7Pt>ilHndQ!!jGmO)qO3T70V1Nqb`5b0JELzg%}6WhST>ILSd%CXzs^dIzcoSM;Es zo_aGIHZD~4$V6bCIl|`SbOhi`7Kg4N1Pc z@1?JHNhiD!FnsXN74SbhX6y3D?=2f2@~-`dqVxm;_K=W--0Z zF#$1>-~JbKTtZCSTd2^w#|Os+V`*?D+A%%})G;>NHK26rTc- z^^N<`#g8*Ljmc>8g=y!E+`IsnI_KwMOYOG50_MDFe@(>j%odCB54=BG95P$*lo?~k z@ULW)w4(G5%~~Gsz^Z1aeCueR7QPf7BdQI@DJY(X!fzgArB2*$4oWMYdJ=T>{&jOO z>$f#t{u3@|b`1g9l;NMoZn66sw7=IH#$H8xHDt|DI*%$%85)GK*^u`n>ak}9er*AU zzc0|vr?>npy26JTPoOCeyR!4X&BxH^1%#{aD#v7n`0<^wYj*bPt*~7!ksJW}XkWDu zhk|A8l1^xRFftbj(Y~TQArvPn~a$lkq=*6NF%_0J3n0a;iwajZrMIZTH%%E8)lz7F& z<+^KfxjkKnTX|SbT7&nq0U&w(ZYOgi3%cV5GkNB6IU#v`>Jl;y=8QgL_8c15ach3h zcGrj;T^TPZbi!UFXEl}+xV6g6C2Z(!^HqOEspPkR9;Y2AIawM+HN%uwVr+NESTEig zg&Am_IkucqvzvVu%YHs~gZW&T6B$0Wa=< z{!N3Y6Gh8UP#eQ@UzMQdzF?}k$?u#{`D#nPlbJ5`nWm>!=|bf_)5d~{I%*0k$kAqK zEg}>9h58L#*DZ4SCQEJi#5*oxx0)3O5VgPxJ{r&|(|VNN1^-%drsG;>$(N11e(>{M z#>*IV)FS1xekp#)7PYgy8|w&@hT~5GJ=dYDGdP10k@PNi_iI-_g|gI&r@-hvTMDep zcYnRFqW09#X|GChh|D3jQmimf+ zEEi(iuDFclx2HetRhnO~WihP`FWeX%Y!4@IUJc;M3H~YC`NIg@O6+xfbf~x>PiGlO zBj^=xO-os;+fM`v&=p_-78KVW!cT1$9>MLuY5^bE?N3`^T>j zK6*<|TcmYVx^&!qku>tAd(K(ScegWAt2!1|;G!XG73ir#&TrUo(R-vfz!vZGa;1Om zWaQQuRB*3Ev!zX6Dq?Il{6}d_{IVIB)kLt?uARoiO|}n>qp!Z{mtK-~u|BlAT(1JW z3m&+mMO%FR@r8#~bsf&SqO<=8Z};KU)W7Kco=!qtAql-pZvrB{1tPtRN-v596a@sO z_Y$h1NbkLO6cCV5L+{e1cSJxyL@<}%^E-Q={hWQyeeTSid;fvVWX+mP*80BY^PY8m zeo7p9^@4SR(HmQM=Fd@)N^r+qA@aoaL*4H!iZ7x4(zH^Etv;VkioDv_StCDfWK=s+ z6VA}opS7GW^8Y$W!%nnWhv2RpSA3=NXAgg4+Ot|-hDb3R{i0&~z@q3J@xbExRLi}` zEq*6J)MAYdr|*wYbkSH$TjyPh?lt^N;x265l`6kFQ%+|czd-9{{FS+{!uij%ut{&C!fxbd= zO}`x2fr)a~MO}4(sl*DEaI@ zSh|?*^*w9&>~rvT>Gu+;-+8x^?{U)7<(9hN#nfltvyV$x-^2VaH5P| zH#^E5h+JU|WjY~y&W>V)ManlKZb(GR17U2Flx#vMJyeHQIO&i;WKpilqOwXes8gCF zxUQN+=u+kAJQOD+PtGGxzNo31XWCgy-zm;O$QRWaTB0f|PkysJvZ*$558F9V-4S3w zD)FL2YnH?W6!}pQB+rcO<5LykQmGo1E1`+>kPfP257A{N(TGBNXoh+7Ax|MH$`swk z#@+Yqy6?MoKM3wNN$57s?>4LNHt)J)?%J7J{mH^x(%__fTcyk9MZGO^s3kKA8wF_~ zn$)emD-g>PVL-}JPD0J4_Dx((YLJw5kdT!^C>TrXfF)Gn3p08FVv#4@XjZe80NK@J zLX%YkXFA_l^j`I=q42`&=|itPdTceq!qFJd!AdU+P=$+npbauWLM#vo3R>vZ&#yj9 zMXemmYlS3;gvx`$m_ywsQSNwZkqN?45};^ikPmZcge!_MT^&s!5-S9XV-9i{WkGnO z^zcX*!C~TdeHrVTZQI?Mm*U|sKsT8Z{PF%{=nnJ$0k8ST(B1!yt=YLQyq@eX{L|L_ zTp#<#(A{6QW^ZZaZ(H-f58eG&ShKP)@jpdgSEsvHrhER8di~#2%|C|jKK~zK%?`Hi zzrY%7FXr#mYj;OW&p&L@% z_rx8lswudlG2pM2yZ>ryQvR`TmynR)Q}V&HsKL9a>TN-tTYjxe?q4f+FRxebGAo{@ zmtQwuZBlZq5{oU~7cK;|%)TX^eM{2es}mO&cP(t9qN2kiBLA6v4Gj$m2nznEurZA< zxEGsb`Y!XI!p6zP^>1Ed5S{byyykl7?z;J^6qGFIpDg2-B4g^ejQ<~p?p#9u z3$I~&72)#Yh27H^C2G=k7Pf!GnuMF8C=t=W`>zkoZ0?#^8$GbnG_yDSkFC20*TUwS z*GS#7lvmM}RsPTBtGEnO>|dI%fAbmvF~$GZ)^PAkvh&?$#hvTaE2V=utTw;v?h2U$d1CLsr(St6@4*`@M+~o7$5K}RHT6nX z$E_M?T=!MS>_^O(|46--->o7k0uxCAdnPXlo2Vol-h7#BeDWWu*U#{`Si$WN-Ix zs<`74dudl94Au`+G73{_kJhm9+AO7`w~%Avk8arc7-a2+$-&H?%$V53hYnMw;#9CG zn`G2HUECAz-`nmRhid~_Y)9Uzn`Ez)NGOrq!jp&c!duf`RPU~aHaX20O zomzJ3(a2m_!epd&&6nH&MxK)Oxc-8-lhM48U^^8%K;nk(cL*2VgENMcMdb?_q@^gu z@CODJy$hIC5VD;`dsY?wE6GUP2h|)L7&Hv2 zOS$_V(k2iX?$V@DhG0O>K#0m+CnBF+beimAkJ0P~H9_IRcFq%GjsEe;4E`u%cc3a> z@4YbM5t;k8Q9^2ed>siw?%Susp6A1kUwfG1QZ#++4YK7i7e-!KEv~XwBD(VQX0mSx zbPZ256AQxUe(<5{U}EA6#3gZ^fbJ9xQOR`$HyEAY#`xm64-HmJMuane06xPZd;pD>O@Oz(O>`EQ{ zV-dw$>3-)qlnaJnnS-6{SVQwimdGeGM`hvE>)#Pn`opmLIlgZ|B@KS-`EI$=6#arE z?WCkOkG&pxTRbIEa+8{ySW1ff7OYaf9r-5;q?5^R3 zi?fBde#c+FhTZ&gzRuQ#iZ4y7`g5^=lhyoD7thR}%adtq(esYkYhH8N8}6rmMV@`l zYuFmj!(R~n#cQzbB(i_;nrtFojsL}K=m)b&q_F?L^O{gG$vvlJ>%?hvXOp2WA%prM zD}hK_{`ZJ`vg&B$m^8)JQH*rWyGoMP$|CRK$mew|Hq3S(Z1$DeaD-6KJc8D^6GPrC z`COUxXN3v^T>7cbfDXE--~)TG@DINHSLtga1Jy3^Br^HRXYKEE`i?n#euHkBx&oX9 z!BQU*@_>)GM1!4f+!;TLl4O;E*ok#8JH6J>;whqj?ac|>&mN%L4}@!y5Q@~GzaqXs zBJRMblCqzpq-g_WT%3@yQW2Dcg_<~;N6tZ9vzJ(Tv8PmQ41&yA{==M#V_0UMZsV7+ zF*Pdo4ccTNN49_zaqw}598sl95m^sMSm1{{tm|fz!Mw;o51>Ap@Hw$PB;TkXNEBF? zd;SB3C0V_}5{FP`aTxPx9McJ`UpFIYDnQzlX4;5SynP8piBQM2VM`=3K_y1E$yyMS zSqYB#2?s$)ZnA?6zppYf<1VoaRo%C-7?Cjx{i{crf$QI#O8a6&8r}l&R_{5r-1^iQ zXiOGFor?%|VkC!ei8ZQp#U!LYR~=l*7Fe8O_ki!HoL@XZ!ETqxFzl<44czg&Cte2T zaI7+p6R70j(jW;G5F>Um3&ZI&)HNBSOpaD*s_xr;EY;F5rOXwbfH)ga!ci>3vOtt# zei6oh_9 z=Dhl$)R_d3R4YS-8-UW?L>9@m%0Yg!zqv#B9;ADvIf3GG=Rl}D<81!)#i;R3C_L9m z^i68txkG4-060`p;+C8XLsBEj&d^Otf`Yd+?i_NU5ow*ACfm?S4!W4|=(;r6S5XJi z?C|fAVLI!0WKCF&`^&sE_={X}O#!xeNAX2E8v^FP`b~yw6F&}ah*6z6=Mt6Iz!xMH<36?J?{=T$lNCa7*#`uMvN$`fO6&Z55`AQIuYN zF5S?!n%u=0I;K9KH)G4d=wdustuFmzQIL+;#YFa#aj43-ZoT-6Njb6GhF``s>n!al zaHvzIz%e`HkET;{reOk8TJttsxfHyCr|j*@`>Zo&BaOp-j$&v5R|=vpmKy%`P^W!) z-rqg9cGP$V4A6I_<>*Hj-ow{cZ0Q5dHWoEOr<8n?B9OPlLyHNGIe1C9ZP4U=W#Hp$QSaZWCV4eaMB zZ$xRFP=4%F?8CVCEIll_f<03Y7Vr;CU|xu$pKhwAqb83|axyhYCLXW-ptRX&|G?)t#mb=O2uTT?+K09Y`jy_ z3j!0M==KzjeHi*>dA_3pK!NQ^y)9M}QXaNIKIAK9>-JD?^t29ZU#az#2@Rr%>_Z(7?^`>eVj1QISff~{=^fBuAmyqB0NU|4B>U9bRraV-tG>H zrQx!DV^qK}%l%|R3iw1v;Wld8mq@zd>}vFoiO^Y>$ku1ViPXb}YJwZW{q*(tebAMG ze?cu3=W+nX>3U9%XfhG+2@nE8FkX(+xC2x{;;d_To_vs^xNcAq7=k4lfvh-g4H~M& z9Jat|%Igp1J_7&DcD*(uI444q9Q+++5O_J*>yTPVG{o|ddgm!H-Dzpd`^+5=OoCe> ze<}@`!-M%u2NC4pw{5DsNjth1hY=&lG>^ho=}yTTcu5lYy?;>? z5JW0Qxrl%7Pzvf~7(5XgOx#F#?nJ_4L-6*H`q3f2{yDXhsN+2>5oLhp#}!(ZyU$wC zoFAtvfLT$gi5`d2J%iB5&ZhS|AUK1*1&!7if`w8pjU!0+F!T zXiR%3WQI}L1Tx4&Hco=S<>W_fOYjJdeuM_$Y(OTWF6->%_{EfKUzlZc=}l^=@SlX z40gR`kgS*!i~=M1s-^js3G$xUd#EKu%DkyRd>HXdB4y`##E!xhtz2!A!e{J(0YJG; zF02d`V)V+c9w|lqPGyIwg2)siSZb|DTBD|N{j5>~I?Yf$wQUC>mYhn&m5kXz6f#h> zmneD508{SiEGH?L(Ujj4KW87%c_Cs0xXTn+ixU-owN6sZ73D}T_& zEF!E#DZj-3Cp|^RbS6DA^Xl$95=h#a2ja3%DcK2VAI+kx&m7mxj{B1CZJX93mQA#h z4KhP)?Vx<{r*o$91$|2d@Y=I{Kd96?wvafWC^FWI@HW^zWR26|+j&{H$gNW~5mmv2*sZr|P5@U_DphXPX{u1|&CE z+3{qOAd2@Ksuf{X@5G`XW2@JLDva@~Nf9}OWz1IsH5GN4S*dhCG|QRik;G;2HnJeJ zZP^V$;Z{4E9YzXHIe5NIiQp$yLL5D0QWKup46u;VGnv;By|$x1s$0B~(N9+YZLR2< zsvH^CVn$0fv<0QeAp+#I3m0_A)EdJy=^q;KGfX`wpxQU5!b}^OE3GmwQ>ib_BnbGB zV4H1k&QD4QLE6_Cn*=|1m>1}LS?haYU+G2jb2B!&%Ije#Xo^; zo6-0!24i)Ta>99Dz#y)ad3e56*sj$h_EQlr@JYLkD89uYpiS$zR!k6nIM6n}+D3+G z!43c=;3jKK^VvLX^EYg6kAA|d)GnYEe*qf72w%CrgcP1X z@6^F`+8))Cr_oi)0RlpBVxca{qfDDU*n@dMY`@NC>@)pdSE6_)IH1!E(oMSZ*$7dd zTH5Vo)Z>!dc{dj9HrMrp0;(7V4U%Oe)B%2!wCh2-UPVEX-km=JdM*V4b#3_VmR_lq z9%)FgGp@V^hUwPD)N8)LiXUOhRQn!sWF*RB;|8G}Oz?$IfSWu+RynNCwD4X_-z{g1 z&RCae6my6UY)uewkLnjeBn>sgf;|T)I6nIv^_$t2zR((wckY*pZGa&LeU7RS0)uiZ z-BK%q=$u~CvED&%j=SElNajA3OBjAMB364I6qMNteHjI~1ohDndI%E0Z^NA1K%72ZzZKj|Z&8tkpu0VrhP z;n?Uf1I^y-5MfOVp)T-!e-vKRC2u=OW7z)$e+)L3l6rZ4z@EZKIsO|AXZ)4|!I|?n zk@wup`6zltlUNSTV}{UX&`l2lTPcM-;RQ5f#V_YeZ&8k?eWF*of)iK*sKK%et>V*5 z8l23O+#Qsg3K5>Rl;fCv7=p6MZY+f)1MnXNOogY#A%(6L zseE%&@PI*av8*%!2&XWEMKn}+uwtB{-#;2~cBBzAna&=hJ8!9g1bp_E`9g^q0O9w& zW1&%Ph3=*U4wpPV_AMNSUvdS6F}^Y-q=KP#w?g) zhyu|S+nf_jw$RK%@!JBbJCyeblT>OsPYnrTYt2j_0NnNf>(&J@&iRYHb63L33>jt) z1{o1Qsv$Z`uiIZlily_6Eoh0&Q9Mt!My&k0oYaPVNzdTISwa^3<|!~`6B$cjR_I7ZYT!5MsTQrUw0z z`K6S~+&VaCf@Y<$ZF&B9jwl;L8$m=XLsj|EIaAFS7!z1p7lI&tfe-vE4yBYXwrnDa zTsOZ0`KGIK9QhgwkowZERJLQ}UxCV|t;Gm7;5W~6+@DYVkSvmbtl6tYi0uG}bEcwI z?z5n6iyOG!=RP=RPoQ zwZbe%3A_JX-?{NZ7+QF}POsRZa4`3~UxqlA^z{I&Usn{%N<)4Vf_RCwGza);sKTgd zR$uN(V6qn4pdHKkmHfNV*zYnmN96cRzj0dpMR@P^a`vndNjKPN0}j8F+5@ZGiOW2wpj408FG}V>vyVo0p812kE*^X z!@*tIXySFDvRTjoHrnS0r(ljn_H@pBTPJ=Q&_;a-SYK&;=fI!x*WH!W1}dnx{iO}n zV0yz`2vUkSOQ@V37-uAE_cJ#@!3$Y+$J#a0-?^x!2zp5(`1cbeOCtF{zT zl820m-)%Z*r+F;RuAk)JuTsc9p>P{+*Nzn?Ex0>2rmU#MOIqe?DzVh*2z{rP;hFux z=EjXRS6Rs!+=JpY(ueo1jGgXi65b+ROfzqs8b>TrskfP=%V7J$$eEsfdSa?IEJqqI zGDdTEX1JA5nCj&G?Xg8K_~-N6YR6wOm0nAFV^2LUB0F)+*4BPgq9uORmLuhs?Q>Oy z_XNl)m5C>sM+z@#gAa@Th|CMCq!FCFY_IdLsqPG6EVplwUOlWvM)TC~%Vvf)SGJZn zn}a)#v-67Sps$$8kjboFHR?eIgB9YrrR0S|Y+-8#d>rpA4Adj|0*p9WQ?3&i9zxnq zpK%%vHCo9pyhgN-(~n}Xq3*|t20aB86a`rt8Es82_U z^wfz&1-IqEU&&3)LS+y~^jN}3^LlG;kdU|Am{Xn9jEC{rOettwM;%@{P5l`CxF7KAzixPtBS0LXabv81LR(Z=-~-QscWZgNTVjBunSFt9 zQL0l%Ur*X&la)7f_S5`D(E+S0A1q!EO$C{{@%OtR*yYSl$M3T zJY|pEH@0T8YxVu3H=d+CEi~P9D5q3Ul{@D9_$2GmpZr{X-?OHNN!%GpV<%WbHCD6`O|VX z&+!=Bdoc;KC|%X31(es2yof}8WBOL=NFymSkB8tNUdRnynRvMS(snmc@sV>;*H!2g zdpmv=4}C{P)2Wk{(o>d3OyZf?E*S3}-s4ZVdAFPQ0|Q%6OAnZ?CZ1KxC@@6Yn2T^56U^1U8OlYO zQcAs}LBIY?ywbaQc|NsAx_pNR`MHuSf~yreeDd{ab^C zMEIW6Kh({nmk-?k?i!kxOER%tI!e?TB5L2wOcyAQ@ZP2VV6FjrZp5KbX&3D;h$7Yx z!%)zU-z%nhsLPd@NTrt_2j1^2VvMb=^e&8v*$4GgflC8M(M~g{P|7lpmfE*)TjKt; z6ve#m5YgE8LE&?Z)TjF3zmf4us`1Ew#UUORwQZjyC(+etomtn#2R0hWZ zppsqgGudM$zVjF2-MPsZoUSd+VMKdxYAa4Re1wIRG0HnPiunKqQb4Iouff-~2u(?m z`6^TadMA!ZGxL|g1&deV0xx8+@e0eT+DIAPwI6^w!J! zz~oEp;^sNZwEm?HDAMz-@af933Wg)c`)|}CVNKEUUS>N&IdNaQVkg+!8?dz7W)=^Q z8WgGagzmt8XCyG@3kj|sAOZzUVql3*A{te2^9Z_Dm1cCLn%hf$KQw7T6hGVZ$tsfK($X4eiSF4F0Eo>2S+IE$m;TH_ zh**Q|iows4jTHxkTG_*h#N>D`=c?P8%8zuwQ0~u|;D;vOH`t^e>o-*3Dx)88+B}!` z?~M;!*YeaD?AH0BPxhrenlv(&u=)#QmrrfJ>qi>S+wP)XW(SBCCJvC)Mx*ARSGpGH zRZ(rS0az1^3Ldl`XqPO{!tA1X;9XBM&D9%LQI}7kfR<{F6!oRb5Bxf~rqUVQ$EtCX zZ#8HXO(824xZs+|Z2`UcNphm-0OUZ;1KB;0@_(-eCKHNsFoP0}lZ@T;xfpnF@zZfq zu&+k<`M09`yhTIgh?2lui#_YS;65SxH>>WENuTtBM>cjE?(Ndpo^|9;;-k(|Dx+f` zh!ieJJG`{|Fw`nt6--!1^)cy*PMm{zPmP!rx+u*h+pUhNU2yDR2N%rpUEp+dkcr`~ zgPO&4LRx^nTMcY;@$EafldD%Y8;d&8aVl=)p^x+@v)3G7!M5Bs%AxA-;uo1n1tl|* zE;l|*9ep3HZ#R?|Anl{^HQ}^4eO1X2ujNr?a*gfKI&@ZM&pYNG=cvbaP)bN|R^00# z=EWHuS;@QiYfj2G-Fx+UDHw!YNSnN!#+{pBC^{ND<}04W`yNEo(fxKH|HVfiy9b)6 zYeji<)A(JacJQID1jfDi!M%4! zWVEI?$|Hy7{fRqhL+T8kIIMz}_p+hR|X^34bPk@wG$-naW1jrHZws6vkHCvpIE8US6@~)?j+DVL~Ps%_$obQ$e-~A#$oUdhZ9x8+S6j9jLCU@4p zCm3u6f?O z>g-y0eamrVCvi$A$h3ZJCjPKi#cZNOalh2*IG^el#fQB*@%5}h732j-!Y4B7woc4P zbHwTZh|0A?Gd=QW5a^z2%+jq`bLs1CJ_*oaux_@Zfh$#O8AvA~QnC(79IhOw9iY2S zq~|1SqC*wh4-%-SU^sz#w^Utam8>oSnc1Sr~=wz7-i0$cH>;?~{?#^5j`w80`#HU!UhyaAOR6$+v`aABu8GRjyBT)aW3|rauuX)F z@2$;6Y-uzHeQNjh?s)?14S>b4*UMZPbdRAbaMdWT!5_g-Tze*(LapqS!-Qg?#uRU9 z?i_>sjnE_xhruwAzax>{n|-3UFN9w$5TTi4>?lHCM@4o!7f{XKc{PdEwF%i?yW__! zm|Cy7GTMvMkeUMJKBowc6hd20Vtv<%^bCq71p7mf{rSexYjr3O1a{y&$ELk+!KAlz zzt?IZ*tl8YO+HCVOKA2<{|dI-E{)IEVxV7j%mQzm*Mvq46sPZY|u^s!U|8|+Bvv8gMeY%WR<+o$*?g0*%3ZB7Ual$-`veA%@}7+T~=O^bLjq5;~|i;;S%v zOcpG;U<4ofjN%&;y*;6l8;z5=TX*a6M49-wWXRq7p5xL56KT8SvfX#TFc=2n4alF~ zeX|NKxtu@{XNxJIKXLNkV#EP7M6lZ?e0k(g$aeLDC((6{fq=4 z&d7lKULdB7L3qlzAWi{s^PbziKrjcb&y=Z8L`o33X~C3*LZp)uYq+$ICGnTiWa1_u z?$~p}=Fa^D;8Rm0m6_IrUC5V8Y0}yOavP4$XWjR+(Ztc&Un<)>UJySZ?i+UEp3cdR zsDE}Z&}q`;@$^73_D#q%@$7_q!L(oUmYXFeD$ zM>d;;H5Hh%*~i$Jgk{gpS3gQ%VFzJY7Fc(rKIlfaWZZC6w&?X)xFJJqrMu8#L)nH7 zYt)TI;)V4LEeOn7v}7-^f(eIiPz)+qQioeibtmL9QM^W3LirbLlr3;gCYD8@l8)t2 zljTS^(Ut|>8|e7R*BOy(lq6dlQ!aNd`|ViWr7&c@e+)34u&mk!}eN8C%t zx0in0SvtA5bo$sj^2#CyFZ|5MKs1NjhTusQ`IVV5M<-&cvQO^9Y3)>^msHLsgcCvf3IFK{JN}=0!k^!M z|NQ>@=fUr@Z@{coGs znDEEHV8XMFvF|&J-?kS1%TU)fCR|!yo?lzpTAAKj{;QWev$8a~^mTP{VsoMYe@ViT z#krxynUTrG`H_W%q4~M~+1d5!j=ve<-^tv6j&ofz!tSZ5rLneuGQ#=M*4dGknUS`C zpXl1_DgB2eY#Scv#P+uLb~W{MwDh%K$8sCnT0RWbr2o?p)(?zS4s`r8mizC9u<_au z{-5``u1mRjh56an`&?OB8L6o$VFeX`H*&8H;q^q9cX7itBm7rG_$s^n+7LcVE3-@e zPeVBG3;o*=Cd9}0dfkadqobo^{?!nMgrb7{Ts=cj|H=rjd%4Ewlz%e9zlXYBI{ham zysqZzM*i2iu73;XzPs%mf7>JafAoaTQJk)x|4s^h9iRR++V%8B;T_pWR(5}@!o-`R zK_X)2HcziNyskUC_f1XzhJ_lYFAR(=wGB+wb?&KX7)qMjDkAk{m9_tl=-!rBzgC5! z|E>!E&gY8A@d(S^5R$ziDE;5gb%p%5p0LJ-_tj4DH|YI?DYn1Dxm@o0^isCB)k>pG zBA78QynE&8nstRkY0|HE7y9aoMzWNH$hh6bITU17Uy*1DK!`eBbn>(^v>HmU=ep_~ zD(s(@Jt#A98~&yBA9Gz5vXU!}4TP4>!JF_d& zL)oatoPi)mI>neqReD+Pla4Dyac;cKmo=V8_XeAqPp{LZh1n=$TgMPT6Kh>ffAI($Ke#j6oQXY1^UZL!Hks}6&phhEgN^hVw! zA^s0FnRSsI2niLg48*oOk&!9~9zPI9ObLbv8IW;3Mi^N38Cw%Ro>@(@2@QuQQHXuW zRONV)1l6!3BhpY|C0l>2Vgn$DUlM>h$KtO4<&VDVxGY>&xv65Or`6#%2bXK4!cKsY)bO7V)=EfouXwoCyR)yux3Cpiz5V zsGRk1cdx2FVscaWJn90-y;0Da7fT*;3+7)>v!1TZNmE~@8c9a9r>q`>8cieF*`D}- zNqjC+9YPjgp;gU}WWBcv?kW|WpuWVHB~{oFI_rz2c7%Jh+w4a!w~I9JCib5arMCt=(l=qD*| zw;C-<1$d1XNiyY2tGsc#b*8c~Blg{i030PW1KzNNuEh_#ZYzJ}kvB-UC(pZBuI`OV z97T$AC2hk_?>yL(_@!~3Yzc3pyS-r`1(ESEoH*R*FsT53$TsB{Xm~i+jVW(-p$yVu z2M(@&T7`T=lSMNIdm$yrx&G)nhH<$)r*ykHx_&!j`=y3HTbCSSIOsbL_c$d}Ii@4w zbS2+!bL^|i*Cc?D6KMeg_tuiEwg&`fKl;heqHEM0-72$Ay{9tuhpa;!FZD3kqzR=g zIUf5?9?Mh}iSis>;j%TZ=Bb8+CiTR&g(*K~<33WO#zAXYykbLT4RSJ+>G>#}O(|X} z*bl!BhEOT=2|R*^>!?XSq%xUAT!SN!+gw zPtWr>KAWO|PhGR$DD^m@Sf@bXL0|v<=HvI(Q3XOzH3!V*juRUP3q;=b4Om?qC;h(& z=T7$xziIxFaTrx3zoj|iIrk&;e6UFIXCH3F_u@wuUN==jrZoI^1lNNaPmPQy+R^M~ zW!PpTsp23<1XztIPBte`ZZ9FW4}?ZBQiLM}$Hih~ka-;%_?%3h(3{F2+F&$QTe%8I zd1li2u!RPiB0m0pdD)W^!LRL8n|2JgBT+R5tNGMUzR1mcv8$r*h*wCk#+}dgT~%Kb zI(|3s5_5agU{#yU=uXT6*rx)Z1^K?|%;F z$ni;dR6vGEcva(0XG`%={EV{~^OcKEcQ7GEB!`gmuFX9!;d`#1e(hM3bI$#m65$|A z@4N`*rpTdMH~hx=$VWNNJZMyk=s;QhuCsr&c>heBSzFFhqMP1nZ(~ zHyKhK>${P>^XLSw`Ybe?JOh*yp}EH0P8sYgz`CTYcA==Qcb}dtF8X|TvSO}ytD6*D zB06{PQOM|98K(JNq={q<^K(Aj&=&y^mo{n$6h!`Lp>gDEcDZJ-vdry2wJzA?P_v(J zOzEvdQON`4=3iNfhKLR8kTd&FDjkHz$x`Y>Phi7Xp)C!*H&qBEMQn)k4RhX@tcxcP zC1h_kBRJ0L5Lm;V(0zAy_H8lbw)*p6il(mc+QKu6T}IZNJilBKl&23LMchgrIwHsc z(R|A~fe2-8q6RYZ{36xRCd+Z>wuU3#ix@*0(_u=4sAppCatL~Ufov@9k$S^~-Pg@# zH+fW&t8kP19%>MjGt8c@lR3^P*-$2o3M4oRn<49jfBSQ$au7tl(l3!CqFIUz3sgS3;t#iRc=oJ%)y-Xr(t2>q^Qomc;_aBj4Wzt`r? zDs^6+fNy%sE&mqI{c~FVu66&Z{_nZ@KWB|2tp{&E_ke_Cop?ZPhq?xVR51Ua*d;P} z;)u5Zl7o~|*9DL0G6S0Z6M*c>RzJk{r-sLwwLqx#k}LJ*Q)u31Cas<7kAw z6BD3#k4KHhlST)M%>;o*!DsCBw>123qxANBrE}DvByPS+d;wzazDSgC0|$vg&08hs zVAkZ|86tl-BjG!05OUR92B2W5Mu=!J@NJbn*MQ26{k|$D#Oj$Ihe_Z=D9!yTdD7Sb zLwDbf>`(!Bz@I?ySCAh8D%ed!4}`-1h^sNuO@2wdBJYa|9VZA91JSuQqSjo4Cfy7u zY(qDHh6NQrOvVD0{x1w`!qe&XIFhNo-UALr&x9TTPx(SI&Bg`-n73aEm^!Nr4 z{Pj`WSS;XL50jIQP)?5YZ;UL(!rIOw7m55EAZ+KNku)_d?-7BQE8OPFq(O(&xyqzP zad@uEq?7*CJ0`D)F_EU%1>Hv7{kMX_)nT_*D1Rh%v!e-St*Ggu zQS^QiCLZF|Z!$s3$Mo(HUJ6Nez-QSN@=NLZaljQ14le-_u8`7vjQuka>t4kAyBokL z1L22`JYYpWkGBh=%-?8DN$B%4}RoD`SMn%@UrH$eBK z;IWQUrx%Lh@JR0AuJ49+vSVe&N28SA4XD>eNw&9$*U{9Qq9hwOX`5kbL3GZ0(D$OI zKqfv3RjtHMyZoOOMv^JwU)f@AhsL*8(o>T0w5|=QD4@We^DB(zY?OG8;kq?WJ;h0a zV+XDMqW;!S_Ha3Knw#XI0ofIMCb*j5RFvxVA?YqaebyK7Leu?%;VqLX*N+wMb$>B@ z2MvxKO=_oncF%luMwHcc%QlYyXG6*WLQNf#ZHA?8(ovU*0_lg;sRj{BSV{|fU-f>< zS{vV71L`LoDN+$xF&`DR*@3q9XLuk>LnGLDpB3>6zOEev2zcmcgAR-!1drzHGZx%^ z=KIiq`WDWqU|uHp+=i52loUXLY%ZvS{C#g9lI@RDrN?|Z16L(Ay5eF)}uD#x{hxov#u*~v2< zsMpR(Q|M7jCZtxa{AIYy|fLha70uBz3-Fsf1zyS&v zg!)m*0;98)%bLYUyyy-aG(9>%(14h=niw}qII$Z9Nlt~!k}_;lZeD+REuf$|alP5y zbGek(&XS6Q1JPg5aBc;6jyg?E1-Db`6OmJ=`Po$03jU_{oed&BB3m|y07b$!aSw<) zJ#F~Y3ZGw4ugSh^Hvv{|ldiKX4L*KP6bm77W1AGE^+UfFSjj%>P4b<+zK2;BZ+homL$zBc~vf0$;u zkk?O{Kwr^RJ#xlJ(=_#oF)>=Zu|0Ex9_(SOZDf=d3;6yf5Pjt*$o1MbR7nM z3NF)jvKPQ*Q#+LqMZ;k`*(JI|`D0vHYq*>Yzprp>gx=V6OJ;swjV zXiuv#*iWp>R;YJLt-~Rpr=z;V-QvkB3Oarv3U?=V;mh7~34$P8PIHGSHf05C9EClV z=$giSA~NiZYth%C9#I|XTavj@F$g#d5w{vA7vX%vh0V1K1+yI2%$ z;blKj2YKzjUP;RUHmr--xqHSL+h(EF8buo-1hi=PbPwvobo%@ueba^mL(E!b7PNBd zfQ&c8pghoLF|>Jtv0lY4Uurg9!aIb92yFXFa)&n-G^1K*IX!?adHUBE!)3_9Cpjbh z$Ajn0dh>(rDb7O#Iar*$)?ztr;tPh=bl|P`XadooSA7dU?v(Kh3GC!+zAT|&Zou|k6&9AqE}(c8gJN*X&VHl&e$2|v{V zdiUu(y@9^;afKlb)eJaME5qCP$pqwtx$Okm(NMG@5h=%%L57B<5WRlOXuwM6o2E(g z40Rhz+I1bko{}yz3Q)5Aay?04A_eha2Q(_+q=OTLhT~2{I+ji}l!+_|iXs1;DIZ6b z-J@n;W!Thkl60kW*5djN!OX(s=$D-7pUjg9SE74xV#9VIi1M1Rj#93SLB-|_14!qz zJM5yN#jUfxwuW}xVI)U$hDVcLjts@@zqKC9>fjc1|xKne3KZ|zoq^-?Yn zKg1YUz%6}%`Y4vC-xfCGgaZ}eAzW)DmG4HJL5k#xz3{TJOf@K zOtJWl&T$CXT>ScEa{ipf!_!f1*AX~vUHY6qJ6*Ftg854DvYWtpi700*dTfbktn^7N zDJXOK`O1tFX4zf{NTgh%w_gd0?f#h#|8dzh9q`rPaGJeM9mu5h9s+O`@Zi?fTIf;| zV)^;es)V9$p-wv)=97RgElbGM5W1Yf6FUsE-FuR=OH8?W_($+86X5$sSD3yJ=Gg!3d+R$D z>?#J3&R~i6-6wt}a*GABmI-gJ1Y-2yT7M4h40kkF_K7<7B?As_jU6&p-JY#v0Q&*2 zT50I4kByJI8M3Z_|3x692XxO4b~!i*;NOqGa2%>4zAxVxTCAj@dq+w-@`Dr8mK}3Q zN^?Xrc1+IEZ%J_s!hGV%oB~+@yzfru)wPJ4#Rs9ZS{VvG-9pLae0VDP(#8#jC{e;9GE7qKX#eO6i?Vzk7yOw96 zRWwpr&?q*DQx#nQ4}kjIF)hDFg*YZ&S>^;^#9PxVQwzNtfkH>J%KR=UYYugsPdUYo zrfN<(U!75m{j7e);Bk|u#SegIwWlosXe!A0*WWadONE@V4@yAQS59G}@9nHKsH~&D zs>>&~yHMQG#oePzNX|JC#~)|9d!B*s|?S* z4QkVE*Wp}N%Zo9jP+A#0hQ{U24B@*a=F;QeuE!fgSxQ+7kKfuRP7o+EDi$u7F-{4> zDoL+=|6C1((yzl`kzC|eUL@x3%b#lu0SN_N!$(8(((W@4jUd-xoKGv54{|_%UDviw^HuKsV3oWvJmyrVI9^c{y zR7x7KI57F5&mVov<$d)^f_iFc^25Z}G#;DSyCxudeSj1IUkQ7_VQ%qKUjt6Xj_`j-HS0ONB`+SCItwPKJw`%VO!09HD3FrncJYXzQT#=kR3f zAoh9^mh3`#Jh4i`;usJQ)mty~96>ca9*2@a&6k#5W7O=y>|OVyve{leuF5G7Bq4al z_ClM->O*^c@1^hJ!Riuww$H+c(kk2bH^S3wFLfsKbZLG(-bjr5kYixVqX%>*7yT4| zQ_Nb=&aBJO74(>JVQ4q=B7%EA-JI=-rp7DIcQ@_kp3$93;)=I*`x8<3o?mV!2Q(&? z)6SKi?d&nil7k8d^FW268I@(GJxBREmo+hH zbxWfIoF@gv8RR9iZ>!;R%+IK-n63x%ZR9%3WubOE`=5fx9m&-{Xg)~3?WcPM!(-wx zn+W4I6r8955u!f@c=&x^Cem?g0O@ZyeyF0}(1AI(sI*mh9ZR`wKWf1zdHr#1)t7IQvTA?lO_eP z7DS@_lcKXB71PQKk21d9ROlZyy(?|vDy8~iX=F$6uF#si(422xBkf|G@Z&|ffPOVF z){b%(uxFa70qJN*n@DjRb0B#~3}vw=XRdu;@U=K*d$Jy=Te}UNQ4I7tLa7 z#v|&5MG|QaMp-n4F7|jcGh8j$jAJf%!bWe+7plI});{xa%Stjgo=a~&QB$Syd%N*`d{aBq&`KUCrz^Op9lFLOHW}D<~RwmcN zgBs$6cxO_Nxu`U}ggz2I0NPpoe~)J$XeCcglD#K)9n5=`vv)7wcq%8bTI!indY$=c zwd`|uWeRD)LndqnG;&c&zBRYc8^~rY7RMx7{V*)#JJUvYB)q>c$!PY6f_6eo^*vJF z)qYq9dmukQqg9d>?KW)(UQ;b)%Dr?@_AHxZ%On0^R|{H)QM~C$kqa6R*SEsrNKa2A zj5~dvpRPV&GoQEeS)H~YFJ-wzH>#LEqph6z$$H}N-gv7FAr7RR{}f3xY-FskT+^Mx zoR2qALy~-)QjlFUX01k^Ur1z&Y^{eJT=l#WvyONa-KFmNhMZP<(Pc~U} z#gArpS3Qs%EVt>DpA~C;vpF$a)SuR0#cM7=I!&ganQ7V)B+|i54EI!g3Tms@p#d#K zOe+!x2}~(uOtxnyxBn6`XTAtmPx$_(8&3!bqv(i|rD-*Vy7e)DqtUU5{l|6rxSL${ zV$S`VMdp9QFcMc-tq3V{L%qCQKn&2^zhRDUa!I)tJ|Y`#z4fZ09e2*(r*Hth9- z6H8@6L{;30Chrb5av(ZP)i(o|L4M3$EjMQ3%(vSVO>6hu?L;Wwg=s7s?cg*?< z0zZkr;4~)d8h(F>$?VnpJ=#np(3|9C{bFEs?Df-JsuSB&NwX_6T2MWE!Nu^~c!1g3_dwT-am zb-^*gF0~j%J~~03I>ic`zVP9mc0geufV)9L=?hqi8E8=C>VF?XxFZy+d`X1O)+0|B zBH0v)QK3}YTE901iL^(m;t;iF_GU22$&d3y*eJN~cj{k48iXM-T99H3qzWYFWIgmD zK|jK@3%Vj>Ap%Wx8PK{xlFN`Yf5);l>J94-!BiS7UV4+tBs(xAzXFg)$PWzD4k9v@ zNm>U>kaD9(jLtG$i2dyC?7=V)++AYukrw2Vl`z=y-eo{vL0y5UUF^S;=C`+WSjoe+MJOl<#Fb3_wI?v#G*8Y-QS%JC)WH_8j(Si=h zvr!Lc>TUEM`HhP8=!hy*6&X`9re3q_($dX!5gG{frdWvGo6XXYp= zfotMeUWp*}ht;KVuoJ21TC}3?@n-NLG*fJF+F&g0bRZ=rHR1mj z7DxE=m$S*n<>5#YRDIe1QGDJ6~M`eEZ4M)7q5Zf1RTW<_K*g*90aO#xy@|otR zisT)m#z{+%Hqbza(rIedX_oK(qDEm=Q@cxtZMwn_3wDuoq8iZvI zn0FYI>>HFab>6ziC3u97{9e_M91i`;YnUrP%$zgZ2%1G8L)JSCBTZG}K|}2zQV6qN z;h3Qyxe#Q3Hk(T~*&L+33Sp+MT??L#$sE!i#)6p|p}+owUmG^B3jv~W_=rN%h&Dxf z5T<3PR%~K+SV0 z&l^pIyHg2T6D?|@hTYSWgiqoyD#BbdBeh)+_aD!C{E|u;4%J#8b)LWx8dwBx#I05u z9;m@?VXfib&lWV1CKPN-p?uNW-8fo+Pz3IRjpK;LV|wORoQP)AxcQ~{ou#A-Q!UgY zxM|6UXrXePDCL!`Eh;jVXffZ)4DnGXFPj;3(d zRr(ZZuwL=4!9 ztHZ@|$Vex*)d>2fc&q3zqK|Qo7Ks&Vlk2&*#&N32VJ`b-T0mr_m3d)=Wuq||2Ksob zSs@?Hw;Ikhw-LxDUcq9ZW;SSLHrLrSY#fb|xmx+m(v`e-{S{$ObG)il7>@>S3_UW| zacy_rDh^#<84uHm_u&->ZL9;zT0JRdqi#| z8=!ok27D8>zpK*TdF> z9BTqyGk|H~AfEwDd*)ieahSA@wC6u8A&!=_bT0KjOk4^fMeLN9J&Z>pf?gli@JE|3 z9KK!vnWOY;DURwnjvB;{8dZ*(Opg9JoSS~sR(90ha`blasAJ)%bN8t0Ux#zWj{8)O z`%R7qoQ?ygWX zpTE40e_7bFYEau(zq`-3sIlS!agy8dZAxXg<u($<7tcP;k<(9h+WMPk zB>kNg?f?JAfY1Je1itv^YVThX_~!Gc|A>MAUhVxC4E*u$vgp^HslPGs#m4fV!@c8w z$3-``Kdo$UeAryyU!UIHSlIpahYFrwU)%XOvAH_CvoieeDtP&C6}-7P@Q=9Y|E7Ycr@N--_D94b-(HE`a=c3Z~kXl^iLJs^FLH@anEpJ zSASmTKz2ueR(mgcySMGlzuMp&bYC>Nr8}Xi>#xLURBc-*x-VK)UR6>0HxDkz&&|rt z%goF`^WgZ5l7E};Eoty6s`o9d_AIDH+hC`hQgmPRK}N+Yg8DBNoRXT-5u%rv_{VlH zGCC$IItJ~5!x7KX^%{%RGIUVXB&qm$NNDi0kf+aH{JRH!{I>@-Of1$=VZ|Yq^Cs$89CpQ~=S4$fwGb?*jb4z1$Tf_T*1VxoCUG@GE z6h+ftC3Qo26+JlxEm2b|$$RR5>tA6hWg&@w%ZhS~EAxxU^9tYN`4}Uqe9BSGOSWXqIrSMpd zHdUfmd+o(yG}6kZvx2G~ejIJCUaYlw;>1T)`%>NuyF6%sLTp3gp)NG`-*O;T2oTXC~B>&{h1Zj`o7=nbA2sqj&axEumV+{#8d;oPs#xS^R;>O2_lAqC6i#Wpz=Xt9 zei4|>MZ4*h>(mSRD{i3BONHm41b`pvu_h=OSt&XDmuxGF?y|*5(PvRa84q_1)l90csa1~sD_|;Xds7uvDpD!}ZCTl^{#??UT#WCr zaY+79k58@XVU;M6rCtreK^^MplyBSTe%RhyUiHJ#CTH|!s8X#agHXxobBV{&KruhO z@{U5*bIbEFfxUT3_=|IKQyu!F5=Zp~%ke2uBI0lc!QIzSQHTJkqvT?_Mu%N_4%Tho zaijZIlt)yZ~-m)r>{!3%U&^v!2E1s^i(-l=bOKY#zR z+S?X=%a>8`8v{~+VJ{{Y=HMOzLT5!+jJk3E$cj276H~y6d@jMXp0WSGWJTN0Gsryq?XSU{$Rl0hKJ;SoF~o*LJtG5q>}@*S-xVk>Cl-JK1K5LoVyiED(Q1B;+CQq z%;?4Ho}kot8XW4Aa9LqwB*EMfwr<-wn+c&K2{ItrXFX&$a^F)z2O^npiyifbedO%` zb_WMvYxrb$OsXks(8boYEJHuagr*-LCmq^B_N2F64r%0Afb=im33})T&3CFHk;jtK zks+)iM3(9@Wlkt%BbR&8;lq;ANjjl)b}BP7+MknKZ*?oEV_p(ZtFR&)SkZ+6reQ^- za2qR1H+AsQ1P{m)E#7sJMc$XZFhP?_db?qTr+CmPDWz%9P?9k7+BzG&8^Pi;YzKA9 z%CkEYNkC~0s9}*0vy%IAq_dQW#OlQ*bwOi}Y>J`8xhxV)rRl-PTw$EF$QXi!3=H^u z9`t}+^m`e8KYJ=w%Q+jIzoj9(;G#s@QFXdtyD^NKOKGwTo}<7kwf8oGBp_zi&O{ZaK37;crLpz2`)#~8temDR!(VA3cpgdMM~^3 z!{AbAU2#6HU^s(`8+&hvqHm;N*3$&hfwo(-M5^6&B5B;-%r@@+tQazbnk8RGBW4}j zXFa@P=o66*LH_r_(8*9E0;q4Gebcn|v3$i-;FHO8+X$_}9Bk9-9+WkMT02&uMUmKv zbgLCl{WK`+rzL--Q9JI&YsH#atB8m9nSL}Q7YAX`o`)fahdO`Y>LK(=af`_}+ z{Z!M*ca-D8NLd-yuLzTv=W|OGE^mh_o0F93m6z7NVFg7=?8y>&RPmzxzRwt_Pc@flcXIO$u9rA_)og5?ONRpKTT3a)jk6NSbyH`_Ew;?aT7x;XZ z&zKP+T(YkKpXZTWygiciExtoO`~Yfq5ZWrt_~vHV*uT?Y3)qIZw?(OcmLN5I|Kr0{ zLQB($fl+IL|MF7gI#m<=(Eb0u+N=FJXyxbHby+4!QRnC2t-A!%c&+d7bCd1?jz&lD{YH7Y#2mqbwe^u^^SRaD|<5fLt<+( zD6e4F39x{YoQgi4Y$_H=hf`wiG3mR2wLsi2rs30lo@e#WnM~&{bxJK8Ed6U{&?{8; zGMOE*i3kh*B{Bl11$F7=f;idpmxjx|N|7GIqKlRolIul84yI8P#ZC>~=|_M>koI(d zd~h52Ef*rL_ALYTvd-sVqM({Sz_}t)F3%fyRARq7cdfdU|0G~KG5a#f0=fF6Zz_D1 zn)Y@oY?|FBL1fFH0-GB5o)drg?T_Cp-7iL%nSJ-nZ?JLPG9qqEf6Afs=ECmwFZEpw zpo=lIaW0;0TPB8?(}%Q@m)XQFRYPjTyCkRhK_1R$2m0%C+5 zNqZ=M3i>VAxnuQkDNYk#uM^p$FrcQ-Vb?GC0{~G0H)_-HM1+PI3i3WZTmwnT5}}cd z;h{$r;a4b8Ap$YEeq`!Gx!6rBGz=5RAa}fmIWNInTVeOFBOVBne}dmHw;@DlHP!SZ z-6~)K`>>~Kk^QJBwdqKDM3|%x9?Jzu4MsRVCSIL9@z+~<;*xIhbtPh!VecLeJCbQa zbxdTCOQg#_EYuVljwCB(BCZo4iLOB6>JzLMfE?>U=j)=?-gqho(SWlCwkahk0UIT2?#i|>>i^1uCMknoZsFD zPkkp|#E{4gPAs=ex``gxPy;qILAQF(urQ^)7AUje?C{5U&hlJq1^7|xvEPP)0RbS; zCcdLW6tABBQ#aQw7husqR4@SS;OY~pC*a@K`}3lRKP2gWhu(XZq%DW#lOh1@Catg+!z?9$&?9 ztf*KWMu2&Y1dt*VXo-|DDvg927~~?nEWizHbA9FKye`19I7P2K``~L?^c8NfUM1io z3B*fgVENE!KXTp{g$9@<1Z82AqDY)=;$D82{rv=JFC_YiNcVo@opxs1eV_H=_sssO zi|XSh2=Kf_!y;e|Q`e1`U!_yv_&3_I31wpshmiTL;NvFgEj%0a?K_@CsFb&@D` zM<$CRhUS9jk?X+%)7Vez@K3ynKHUZa!(4=R-g$N**29I)ttxHHh??rKWkwIkd=NluX9F)bwTPOj4@(OGQ5> z;Cn0FXt`7(m5?qx-$6rBKBmldxy`x;zA=m+)+Qgot$E0~vyz{(!9%S%WBqE+P* zL!~j?6>Lwi-~C}PD+F#u%1FW?aX%DvH6YrD@-G9*lW2T@szEB`A$~6_`PfQ?3*^I@ zfLRH^7*xe=R6*eI2gj^x_bF!r9!OQrQ&n?bRuYC+wi5Whd036rlisPJz^M*V{y-sJ z5Ib&0Jt0sd&{SjVQ~f2WYBETnl`-86Byrv(cB(18JuB5oX;FV2MZPIxy z{&WrA3Y^%2vRs2Yrm_zD6V5|Gas9pI8Nn+Qv>d0WjG9&jxKqP+L>Fz|KyyScVP2uL zPZ!7od>L&ZMgI(%T~)o$L;d~mwb+roL`hw8bd3dNdb>6sI|u4V5e4LS&-jx1D?CJR<)NURKxA7t1X}{9IjP~ zh~h49-~nx$UQ;WcPgBrF3l?U39HPZ1du90+~uH{Fhf=l~ycY%-^k7Is-Ay~9OxlS7oWzd`kA z$pK5iq?$6-0vI~$IbrQlXKnz&dnS8I=f--ILVKXowW%-3a;~9e(ooqOvhpAJvNByV z(0;LCQ8g`KqOPBJI*QnbvFT1LR!hV*L*mdRQU z%0LD!pz&;&eMW_YDYl*NId_dzq5KdEUpneFO~|^%kWq1mkzjYov2u6~?86EWc-uja z8UsQthfPwdz8t~s+yG}Q6tNw{C>f9VjuC`mhi1D@6{BAU1ckLvYz zsxvny)KCt+Y{j20@ueZ(J{r{%tPC83p_rgnGOvm2-&w-jJLt$!KVX%X)a-N=JVCW1 zHGGs~z`)BU51%)X!XDl8@!1+!$qj4_0-abTcdw=ld^z@M6=oUKsWT1X%mHp`8GAY= z$+jj`&&NQ8eYh5sKiq*;_xIloCXd3#u{=ZzI$(>u^q8H%%Nkfz@RZiY(0%F7Dcf$n z!qE}$G;OEg`m^Bk zX{+-oX_-3nB*?A%tm^rUZO^Q+&j|j;tZMzV5)o`ddO*!~4h)?Qs2|l$dN(9BqI<$7 zoC~m?z;cfPqK`1;pRcSY$T(lYp2aN?ZjAW}zK0;@G$R3E>A)~5Y*3qaGwqk9B<7f%Z{0V>o@hE z0K{|@Zk+(~*(`{8tS6rAjV#$SS!iu8<@gwE*%HX4|HyZ1yCjLZ27)i!K$r00^Y^A# z@!(5q+R*)6vJ`Eo#w+qoBC`4k07f@|;z4HcO0v5X=#Yhq$&Y>{f`0D&BvQC0Em-;M z7&zyn_j?BHot7e}8-oXHEY_p!{4nFh9lj&uv^9{LR!15Vch0XRu zYf6X?;}ryoxdxyI37dWa_Rjzg9SHI2`jcB?DE%av~N5UT^lw85M5J`eyf zz~{}jQhU*pz@i6PQrB9+3AqkEdP8@XM+d^w4bEE!=bjzr6kvg;M+<)+VAUV;B6di9 zjx-BrPU)e$xvM18hxNY?YuCVy)mcp|`gt@22 z+}*=}OpZQAl!W)y`m?J%psx8^S$g-^Z!*_OVCFfcH^X%P;Q=TKZ_V>_?$j9x^XJy* z)l$K*MTS1Bp3k^RRnKYww$DT0+jnQ5_%DntkI3Eu%WEIRA3zDaPxXDyefa^;XJ>@a z!%Lkn-}v9-L%&FVo+({}lKq}!M||k;L@xjXtG~~OUmtHy0)$MLt=0?H`sW%O%|66m zfb(Ml+vBU($4v=9w+^7=wd4MqEbtWCe@fm?3^mk+zREjpVE6{wXtKS%oP?j5>(`_t ze8MW6#Ic<>p9G|*h^89vJ+Q6~%QW;t=$hD=^35@Gdv7 zyx;jlX@7djIN||1E1GR`V%~x?@{08O)vNB;+LUZ=+^JNsmMWYX^{laV6ZA8?hE>p)w>odn#0?{^psr< zhv;l3yTtrjrwDq>Ywyj0c;Q#sCbcIo{hna#kqaft@6u~Fy8BzAS9?Dynu~&-^C{YO zCI0aEkd-;n6oRwqk=@Q3ls44yX(<2QTZgbiDtmJc;c=r--Ok4KM8*Vv$zvus>( zM80e(d%vkUPxt_lK~4V9H1Gn zDka!4DcvN=t&tW&`h|U9n0MbG4JOPnl`P{}H5jQTOQ5fM-?7;^iK|qN#7NpVrA$+Q zUZLRFlhny1)Ki-qU)+l>jp{*SgA$X1lxTX9y>ifkv1|E`XD-CGH>FhBD#(8&9Z$xX zynY7f~_5 zdZEz($yS9i?GSzAdw*9t3>WW`llll@RVH_wAN7Ly4@fhqQr~fCxG$uafduR>Ow@PY zxccrfzMycnEOldWc0OsLm%I^uxaqIi(Hy|>@MEz|d1d>0h?_49o3g5U*Ql58P`84IHdptv$BRxZ`@j$eBk^k5sb_pZY41y&CmH5Zvi_+~we%PVn0j45ij&J+ z5g=o~5jneYcRshHDEqGO&JK)RKMsbXAhh1*R28`1yLp5G8OW=ZW&r>9zC${W^Cykb zMVU*m(z6-Db*B=Rv_X_7my~pj-NX50kUG+ZZ^If(TS)$PFBd0hRw#jr)_NBgb>c@r}5z3APdhCIkd4@TWq|&dQ{9!#r*LrrNdNd^|3^D`UCYVF!{Jin} zl?8@%_epW#z`bhAXgk=PX4I+>`)_Z2uB=L!zR~UM%f*^9dw~&BS<(m@eLD5E7Cc(P zkr}4iV0E^#4_XSO-t1GUyHce)of%DW$>M^X>YtKbzhWa$Qr0tZ+ z{nRi|p#t0k6>)-@zG#TwGu+4IvaUr1s{8|)jIQQBzg>a&DhJL!%RNOfDUqvEF>Qo9 znqxC33`1eXuQXgV`oE{yW{$DGge2T@*^OirG!`7z4GE>T&p8V8Rq8%|DBd7A?;ea@ zb^qBzeqDWHaliTM2fwNqJq1k~($i{QV7QsT3z}UNX=3{sOz>2VJ2}bUIon+}hMLZR zxa(^(-P@%Ie!qH(&P`*{$D-=uNudIdg{q2gaS?7BbS|c0uokAbXKqeUdML&W76ixD z*)``3XUagY^C>W2`J-G=52{L<^XQS(Hv$&RlM67TffJ)jIKkSF4F&U89^Mg8Yomh| zT8DByoNWo&-|#y%_quXP7+xr~u%uNk4!kzVs*iV7Q>4L38Wd^hfs~T6(c{YB4a!)l z7%JK>){N#=BQ~U)w8E)BqA&UW+6C(5U{AAtbt=*Vk0V)zz4J}x*YH0~qlqb%F5v^! zFKd#jG#Hl>AAEihy`kh#dkH|0-1NvoY^p1Xm57q&! z$S!pRPw;`bDS_kX&|X5yPTwi1RPNfGbk@7p@zLO-%&9Unwg-5R&|^(bde=+|{;%~U zEfi`NrEt?&Tm^k7%uyZCF?Kb77isAw=r01LaR+{32u3`sc(y|?ngXiPK(gD{GT5GI zSC()eCTWmt&t&375Q=FxI@FiWifvCm1t+hkodvxN$aAU2?@c)EUB+q512E2w=_r2d z--}QYQw^bae?r{Pc%s&qSDb@Kr1aBD@-aa+oMrzcV1n6KC%Txg=I~boP1z9~Po@Zr zaJQGDaRm@>-p($iaoO|5ETWCzDv%^4M1#k3MrTbTe76D{;y&Ux{$Z@5W(%)L37IsZpZOU5-c@-cb1t z2zvUk2>$%=E2)cFE5R3AJ!o{|*bh-rKxXhwX-zgMvik1e@X82$QIG|&dRsPzYqq8L zu;lb{`iZ*}>xj&;;P(+SB|4A%9C&bn2klS}RYCXLwekc+*Pipb3q0UJ^ctghkC@F` zPpYPq30*<4x^nscT~)8NJv4aoQ^5B?&dx9I8h$QM)FRp74qdtU#>K1ANQw#LZls(Wa$P<&U%tSksHJP^O@AOu0WavHmpixO`=AG1EEg;J9YANUL<`R`{94U`d5S%5Zp_>A=-g;yP{2 zo#S4+;J2wE?UmK-K7K^cEeJnUC`qXgB%8jg#>NPMz|+()RGU;s5Zsb5Vq0R< zMm2v}83#6e8^$J@Do-+KPxyo_GCG*Z_YTOJH~M*hZAeZIqDgH57)gL3+YAU3*&_WM zh~zXnGvqm*36HechDd3t4_4GBBZte8N>NNBL+foLEHSuT%6G`r@{UIaK^jrRh=JBt zB}2X#4E3V*JORDVvfxnyv!1q)k(+>;s2hz0CJc5xO)T%xM$6b5-sm(D!pOPALO;y} zwf?s`vGv*PgPHQN>%-ZS@@zFiokp?UsX$i;i8vcU<7G>S$at_8csnreMQ{9zrv7Nt z(PZxdm$30+8RGu%7~a_AVArhQ*b~txY)JtO5l!u=x|pX_QPtCwDVencTtbo`(({8S zqNmhv7mu~WB(M>!`0DBe)4ZSw7wRPmnG?`hIA}7~J3JRsxL*SLq23TSOM=}25($nk zg+tnKqO&{N4|uhX*gz9KoQVCtgkkM`Ujn0z?rWo1`-AZ{5#4nqT@)%UEmI@q4A%xu zh)LfY(TaT3l;)&PXuzEQ(*Yc8)Ok}g`HKz71COZ?0gZ*cFI&Le2v%S;R%TS7q`bp$kxW>4Qk$k+{lL=%*Y-&=1@Jeq^eDH z|4B1QKiV*~Zfvo8YF^FgsmJ|b$28hxqYc!wBE5lBjX~(+=siEk3@_+5fGENICj&xW z+tm>r8#N8PR!lU#U&_Vpdqr#qpNi6(v;4S}a6+BJrNKO!@ls2hzrZYP$uz;y3?WaI z{20XSQ4nd9VAG%I0sc_iVU{!Tfk2YgjfhyES_skkp`;VJ-J=q<{-LE{9O2SJU`v7# z61F%UPB*`VE{=+0N9%g1g?29xB;`p4&}&KP-;p&hIWdjiL59hWOK@Wzw1q7ehJQ(& zY2#Zdw9`fH&klB5Z0$!o*I^!DhA$$*5g&EYebHPf^4SijT>u^{Di0n&uYj_=ELk1( zK>B&4EMR08IYQnAM2eyq)BIak@(gSwhuU`ZRVec ziSy~_Ttzn!-Ig0m(J#n}G4(lun{BR?S1|k`Vw$V#!%Stl8}J=#3uVI7`Gi^TdDcku zcjZ@93L9KvCWiKQN;GzNUeA6%Ccc}8a+xsY7h72EK;DKJ6LCyH=h?T!tYd6Sfhnl5 z_=3@FE|M?3*sx%$1lJzj!Ey3klcl&%(#0)G;V|Pt&6LiWA+v3%Ov-GusgmxHU1-GB zTT7GYz-=|nOHne@y{(0}Gg`T=_u6oRN=t-e#|V#FERVy;WM>~@D)W5D%qa~|+R}W` z@rl`*<*wtyBsS#9j!hSJ6Zx*)BvhIMR3*CW=tM64!`dlwm%yyfrOfGJV4?2oUH64u zk1nY`*Q|THyWW!|S>$`Zkwgw0k$R$gk57qBoc5mN5kAvedl#}7Bt|S$sQ+}qIa3hn z^>Ob-0)C?&i^T7}&^)A9cVtLc3`V+R7{7D1p37}TL8+C$%OkNO+yTMlmE(q(@#D;cN1c&Sur8p`9W~|F*1g$ z;N%nD={m*f2FK~9*y)za>9)z~j??L`|LI<&=Wy#wFB^wai7>Zyl15NOU^Hc|DGm!u zq*rTtQ^CZ3S0a;o?70}>aR;6&6#p@o*O$|T-5hz`<_l0^i8di zyc?f?e=oth1=mpL|-8yl2xWu+kpKTR*J#~fM zx)74w60p*M$Vhxn*6CZ2-sM!2O_}Fy$a9LQ_$2NuS5i_B8}G(eA3DklX3h&1@e9`f z#egvk&N490xywy%%Ay&EE~J`2^OxIiR{7ddg|&ON;tO#iuNegF3h;jIf?9{89=GCE z;5{NG|AH9CKg07fu{jGy5hyZ6Y1D)CL(Zt5e32@jl4e9dJ_#f-7S)PJta_<*7b$ob zv<3Mb5bdS#4k^qShM(`J!3omjL{f6%8E}GiNFHArT}BFA398PUK6w1Z<8fHPRV(V! zOnkxoF4BS#bkzZJTlX_z!sB0j+_`;az<7nA3j5j>b*CJu%aw(3&;LsH@?oN#%aA{= zj&UsNu?ZN2!TcQu6Az>BKXcyCzpl@JU7y`tpZ&T**%C?fdOy>u=F}ezbmcdVtRRUK}j{EqbqZ=T7%O9`CLkZZG{M zdXGL${v~=h_qRXoZms_p)Vsa<{!h+3`H#r&KRNHe7Jfg?_55q(cW{1wZMx%MBEKCU z-ghp&fA?>Z-#xA%0mba%W#i{8nGjDPR^{!h_c)IFH{C+E#< z@BR1A?|-qpmH+Jg7Ubt;XTOXuD$mNwL|fkUjPw`Pe{_BW%bWa58y}a{qb;vbLAiVW z>xa3ooU>~jv#RV~7TIJ}TBVh*gi!t^dec%;dY(xoB>W+IqoZT~LcNg@5s0wxzYD*X z$;IfxFPiiEKY8l+*x%dN-^1I_&CAyyu}C+*5Z(6Gh{@MWi2BR&Dn)y!MCB?*WW&Q> z%7tc0hh#{;$dGsuEB-V=_-U$OP|9DNm&-4K{ZG!z_Lu1WqwO2`H|k~dih1GgfUf%5 zJG(#lgY!C@TRT+1h0x6Rk%pGZKTxm21CPH@uZHe@H0o7UH-Mv2uab_Kk)`B4jekYG zf)a`XVhVTvxWLh(m+w!}d*^?PUT$$FE>T8KQ3ehX`a4qe?82a1jHv(2c?-DQ_d$a^ zb45i%iFmb=Sn38WRkmmUh4VTp1j&RE$Yws=Xf6CF=Pe$j<8D42FBbk{`hPfY-|3vW zo^|v629Uwks5TRCJ>HnUFp~T)&iirf$vQ~^_LU?Hd}?60*$z%_bSaty7wKF6nyb~; zfUf#_wR7br1K;?vj3gkQ<)@wEY!cC-tK_#9! z$aZKMi~g>1ip7InH0RayiY~G-Pc9~-xbG(XP2L?hiSah>*BO2QDw)}dk;7q~JJb%3 zg&}2`>CKwLCrUrL&Ud%B7!*nm)ZZ}Un8PauQr86JB>k)u%Ut)SEO82x2c3vLoB?~R zz&+CEys2dCNVaqrJ0090qX~<-4ly7S?DHiiia-#{;3*EdCl!E!&AV)?2%N&@>_ay*2v^m-}_=R`#zRnHNBKQm73&_&xTP(+2LBu>Ttz6eVs zR?#_kQ(ltb0k>XOpI<7IPAqZbcBo8q@vgwpuiNYWnx+K;XeCrI)J3W2B7BmBxL!;z zNuo`DRAHNaJC}=v*wC^Bt8;nE6YIMfP@mzukBa99yB)n*kE})&%q3si1gP_AS|wV>Nv_)PPh>>I|kW!Yp+E}($Aw=GMJ32CMU&tJnK^a zYViTiLEmsS|55-C9IH|3tDc{b(G!Ji+uM;T(O{}y+49t!{i;!TS4T62qPZVL6+R@@ zeBDm{q%5qFkr#=Idl06SP?P+ozZm7LSaL1kIx+A`X>)v@MNyqZT=7KAMa@BAlcofOw*9zUc4hfUiJWb+S%q&I$N)oIvDfkKr+uqrB z#^+W~Do7d)6~aXKl_b{CY~F zEJg`?eEpCr+Q=!Y;XZ~RdLAM_K9Jl-sr9qaOf$vwEDJb2>F1C-kA{>0;-(G&pl}{z zI$qRT6ArLHJdd@3*k`t?2@0aCzAiVqEEVtsE^UGT!g>F!`l=5r&|IL9e^h-(hE=34 zl2CtEeMdC@AKLCSs;S3a^gJbmB&6)nJE4Q12Bd=+dg!5ufJhURqDT_~6$v$j7OHeZ zQ?O7JkS5X;kY1#NH0dB9O0h7U-}%p(bMHBKt(jT(u9cVjP1fEocKJS^$969{qo+vh zf4A!EY`z+zhF;LK8mDYrwvZ@sV^=1iFOmb}#Ejrin+G&t9fz+3rFR7Mt0s~ag$6Ma zI}3_+Vkdx&M3~GT!N$Ve&1fG{n1j!MrZ-CWvPV!P_t!{|hF!BpdJc;?$K7I_UUhZ~ zD~aL7eWNqxdnUKowe#tNbOg1v6IenR+3$7e))P_yL04Z7WodzNacNVwQeP;J<1peag`agMQZUnw+GctF$(|AmXZf`u z2E8Hxq2yyWNO?vYD*^aPh#5F%FkJ@DP-@yWquP{se0gabsZj$G33C|bzgavVt3qXF zC$1{@)TdWu=|2Iu^qegem~;R`Rs|Iv1UyEsW1y1#wH5KC znN9FnH~qD*f<-m5E;S{F_y;Z?;}Pw5^tL4Q%2Ur!>M;?z$Bt}1Jgrk&l8Socm-V?m zEQ^?D&F4mZCp=hfGrq}IU6dLe@A zNf6UeLOHSsaK~d^jtwa%>ieb;^bU60)qt6#!8#I_P8!(dkwUg*Q@EaMXzTR*+PaHC zK>eXvI#--OfUSRQ!3!Yt)jub^->;f)45sQPPts=8sPdBrM)rjZ5nAofm&(RMM3_9) zyzDT_&^QydIM%VWpfRD&*vBQntsbQc$qzo-*sHw1Hz`8uPw|;S4=6%BMJG6D!kY-g zy37!nr%DMiGFooQ%=aHj3Ys{!2H5(RI*zA)5`+0PCY5|<`iAk;9Ca4iFbcgsiRQs zos2Qt&JwRZiTk#K-~4F_Sf)=mL>FGR&Ap;TqXkpW6iM9B*@&l4;RS@ARq+^3Ypklk z8#H4u`?RKlhuoP?SoR*LCi!=uy(=Bfg?bC)n_AjMq{*mii6zGxt-WhzVLj}uWP-1c zb}GaIG?@|<8cE72bRlAOyXto3%BF-+S6@WD-5Sp~=*>r&3*R~25?crEqD<5AP(ETN$|Hkle=fh znrJ_n9nCEJA7uyL@M%iTbM@A{<=KBW-Ao%M$NGNOH2m4}PHdQ7F*&H8`m-I_-!Oad zFV)v!0$rkh*sSUUv(#&x|1YZVUPgc8vSR;H-~GSesi=3Ss&BA>0WJ?VjiWK>4=%S9 zWMp*vBcu2x!YN`dnoFq#{n|TXygMX=nNxQ@el<+GdG6o?JcK1}07Qd1IWkgiqNk#I z<^^^^Z3OinLCOpQAO^K9rO1+vyeDoQy#A%CPsCxaH-}l;VQ@hB z-w&bWM{fD&H&;SVH_NN!b2bM6o9Q&L@hf6)L)r#H=t>NC7#-RiMV-f(ABUMkYeQ9< zQ9pj5s5sa*4)u&ea|4U~*^E%bu+ef7>*R>^f>`bqbe9kyZw>I2geL5uHpPIGP!%@} z>?9PnRKXZjfgGpMm<@)V3pB(k0i`sYHv?P*WK^G6c!2XmVG_u>ics(_YMvU=hC%+B z19i#3=@eOw#v`itBj^XE_ZV5M#{HF7K_?W5y)|%xg=y9xoom%iDUqCC+|3ufRp8gLkd7=btRk^qjVesq=o@OikF5FoaJKso--z}P%DQY-{i z^__XI1F@lXcG?k}uqz3rzzzVq4~LOy8F5vItTml+W&07OngnUukcAa_wC|%eTG}lf z;tM39LL#BtEunTbPS-NQ{Xls5F3>sW{{*l7mlRNqrZCV#O|MY2{3-T~(rq7rb{vp6 z=Y~Ae0w(T`@9+#W2wM^Ea;<6c=--tsrhxOIRTv-xb3+))99hhA6U!u{3_y24qbD?| z{Q*P<9$4~5ZS25CEYSNq=S1BD1e5_m_ftqG`S&Wbd<=^=gz1MO@R0=>L;;UcP$xI- zpE-h~29R@e%sMuJo_jz_dZ6h9vso#NSskOA1i&4NV(>+*IYCY;!lcd8K|bl%qDk~J zP&zdH?Q)d!07g?Th0f>9N+q9z5cswR>J2tk2AvkUgYwCsam}Qeo)Zkl!h`jJj12Gy z0VQPynZu&?n-L-@j6%#v$L7cM^N%k_Co>Kvw|O%v{fr?yf#2?4IKN_Sy9;w8*d{0g z&J@&VDx3Qevsosc=~ue5j<9_iX=pR!5tUJR2ejabaF)nwt3W!O#KaVYLT*sNl@yfH zYldHr2zLr(75DgtGRga9Hk}!qp2$e&18t~FhiYI?2fo*Kv*`xYfl7aKz1zpvkt>WS zL<&tb6}1wL;NQu8tpqQl0AC3(I*k+n14Q8>AL>7eWrY8+0VHu}+^ZGGLRBUGbK2%; zwNh~WMDqJW;2aJ)MmY_z5j&1iZB)h|7?>*ovO1RwCdM4jgAVq>*{rFqny0XDs>t!Z zQ&v~B!oh3Ynr_(t^8ow$Yc6b-D8?sr;>txR5w?M$g+XY)Vx+f2VYYaI4GZ9n5+GcG zTp&R9WsvGgs5in-gg?cEjxli_rA{vRv83~#Ke46K2^N9}!xMj^&DWh4|SpaK^(C@x*UcNYU>Q;YwWvdJG6)5+xAbj(RO1MF)c zY|S7C;w<^@gx7lv$Ds%t8^oW1loBeckS2W%hg=i~KCILIz{N*VksEU?n`?PHk|l3! zild^ReE1rL!*C^FoF|`aZfLRJbw=O@b3`kxrd`9F^iXpYu(Jd$m4G~;A}fKcIpu^l z3bE4V$Br`4pWM@n^okn)xi5@+4xEHcv|_j5ny9)yHSmUp#-Z zpNyonho)5By_Xav$}l>Xcym24v%;ZzMSJKV(AeEN+oxQ+3S=<%AodEq!4zAEUgmuc zT6!N^XLkB=y<{vE)HX*?Hy6mZ=5~2Q%Xp41Xd|$iQe$38%j#H@coRzJ#OR$`9Pz7` zNh5o`o*5Q}n$_tfe)hPBC_C3RBznZN2C_n86s%leQJM2b#QyY#EwA;9zjW5rxvlV&Q z=3Pve|Ngs_v5oD!$Aa(MFwKAN<0oEle9q$PB>-zzo8wZOop&2)Hk(bN-`o4pewE@& zR)sSfwZv4lIQY~J`!v!M8~D}m35JaUv{mV`Tsu>(43){^Jx2XZt&at(K}jta;CK+6 zeTs>1VXEbzt}Wc9#e26pW4Dd5vRRuKZvbcCmI4-Hx$qAFmg)B9k^1w$+fxMVyA1&d zQ*a3tIUj?@O7ss=Bcb#3NwBsXBs_jK{|=?ed0{iVjIPX)|! zh8*_m^G@v8FlT}82OJ-JQf2vcmHF7t!#{xqM}h`>7<>jV=3)!x#Ptl(d=ELkH*#=Y z1ekJ14E^|>0g)TWfcR~;9J^uge0KnP*s2!?g`p8!tY)_X)!Q8Jua4f8`)uem!eI7! zK&IRKm4du{0G$(q^$y^i%X<4Fu+qo@z6L1fj!Ct>p*MRLB!lrk3rMRm-q#pq6l}Zy za=e8;`OyqVh#l~wfy47QkpF7JWPiYHca*yaxO97Reh;=^A#?Q)u>PC%)ivPxMLyH5 zNv+gT6Jj@$(}c6kI0JF0(O6r1i`DlwP<@*t$rxyQIGx_!%Q!d`R5?vII6Y)+0E*{m zJ-H3^znl3QK44B9VbGZIPMWfko;9f&GDOeNqx=5M*V<`JZz4Ei&a$?|0XqneUl#%5 z!!OI>Vtar+G)t?Hzl(^x;&0gzgPh^zQTvVmuqaaf9I|Z&Y0%UfPH#Jwg8A1 z8(Z0YD$6`dX5PD{eLo&}dwZc(YtCf8_E`^bG{bgg8UW9p#*m9aW(!7wi%d!Lc7jV_ zv$~J(*p{{y9r70lgJ0;JzBtU!{q9|g11$^@mryNpM)`AAO{cA4vz1`0-QTY!yI=I@ zXBl@V?h%(6%oa_}K1g^iJI;UA68r*pT5-r|$hF_}L$F2j@l|;x8KY@(X|@K>ZRPK*j`p!;^|3_E0$PN07ZK?#`l1$7mEkY_U<-xn6P6t zzkI-tHbJuE%79~g78-$_LHpCU@8^Eba&(yhojt7I&h72l@0nJ1Oq`r!y-*JHoMV$d zhu%4K&nc2Fs*>`y5ZaQ(&kjT`J{FXNWZQuT;oyf9Q#&V_qbfE?7 zQV5V-#`@*-_`e&uI56k6A11p$xGteH)V~5|TfpEhGZ8LB1qTSw)6%TFm9zew=1_gY zx~0BxHvi{n!vTKxKw)>6F8@&2oK7}xiGO|;bmve5y{hH2$KbTlukj;M4S3wJ1Q5Sw zh5(t=qf``2oC6E~5#YebZc`3KoL`_L9-TuDLzCdpN5|O8A99t)J)7vLCZJrk*Y6x! z_YyoVcBB3qbCm;2Z{if4OmC$+@T?3-{R@bm!gSQ%Oed8)pQR4E9hedCSxN=kyp#4o zGV92scU(Em)Neq)@oeCq-}6s6>QJXp^-&wm0i#csA@Ybu=AWDw!Oz<1fq6#k0@Nco z%@(xDY-jD;Gt3rs|A(A+6K}N0kb0Iu(^ntMWf*=&eiU$%b}lDkZ+`@FTb_Qv*ZD{F zl{B~Icb9$@s87w!Fh}Wf9xXR!7 zHEF&bhD1+Ja#|&f89RMoZa*`?q4B)!=WHae&7RArw6Rfha)9+>oS&pH3!Z(^Ikp+o zTIF__cm*GYLP=Wz&rV$bQGIiH7S0!|-EHWV8}!l{OKv>&`4c?uP3#W&NA=xLFGx`+ zJU6JQyTbY_SllZk<%&`lRGq(O=EBP6*3A3pI}NRqK%zwyEFL}T6BrDW*ro@+4T9A3zQ1x4TitLM>3uk0RRq2LX z#8Ag3LK`O%uos~6e@)p}2tBIL6QP`A@0?yIAMdhvH9bMg76tS{R$vuyhG?<@&K#?i*XH1buOp z*W;%%)vG;PQc=n`63fsxIhmunYALac!6On5mwegF-evScE<_}xatam7nA-^7j!9Sc zC_Rz?#EGc=y>B6*ZZnG)tPKW3Tf%CqS69gG%WjiV&u%o_4qp|NxS3Zt%vx4|@eF5S z;ssb%;lwmp%{%O6r42Q%E+1T$5YBxle96@7#abG0YHG&XgU`6PoZ^Y`ghq&?Uw)6i zYlbyQ_tW{F3%>WxViWh>J}1gWm)sdlF~-H4s_ibN5U{lu#cU?Ip5~tZuW{Ko)1M}b zm+tj;?oskk>h%Qm7WH2QaEU#>glOAv@y$h{8~V4-E~E-|U9xTbwc6OJ{@1k8`-un# zvi{L}@nsf$+ADr-sXSeR-A6h*_C(8`Uj(u+zyu8+|lVvXKy$^xGgkn9G zo+fhBe%1eL^|o=RHQwbPC5{iPi*jWJK98 zal#@TFAzqyCATLhiRfd`zTr^&2$J6^=sn<<zcW6k zx2O0RQ&^Z*DV(i6l=0)$WeM6&P5sMUWX{lCqT~%nVHWYW9nQ_D5+@7cX^N%FE!0veOxDrXd?Ed8JT{{h_qhMW>O$ z8XS7087$8_7}h!cT6lQ<1wJaJDfwmkIqNrgNvHcszKvQU-WMP$?atw0MujgYAs?8K zuft3n%UPsywy^>!$@#P1}OqAINA(x0Bh$x`<0WRX`77ji+N8kGl!4+)pqYtnERYlGtQA>6DefX z%9^j&3^9jn4t;IHtS!5U-Op|`0KMcxUnTY0EU>&4`EdQuNf|e8XW=J~L!wlt%e(6C zGxXb~jxv$ghWxSdMDk4zSHJj${5dG+GnbhdekUX2Z*;EWa}`wk z{kQxx_}@L6%8AII}O_C|c&LgDGf?-{)hQ{EH}hxoqK_8v z$&YVsd5(RnQba@E3R-MCjbj5YJq*w-+KvBqLyJ}N#(~aBMf`>C5k-+5W?!?Pqv+dX zx&~(rHvK~w%&{~i=)9ZnwaCK|b3C%R_=6&+CRUix$$vUd_cF14>+RD+?Seno9`lH7 zd2qN7;PVP>Pz;}}`&6}uF2=onKaFYTWK@FC9B%IX7KTI{w2RX19k?~Q(ka)=O!y?; zNS)n(dQW%VqI~0aMB9&f&Zv#cm+s%hw{g`r|KX8%eFB+2m_2BErgk;Ji1`)0C>@sj zP`CLnf48Uhww`FXMt~1;{mKb%L#NKUIp#leg)T=Iqsd{(AxTmx3L9d?2B|s+%G#Aj z9OL~VKWAS5-7XZFADp+?74pEE~bKp=%xWLV$%L~;gsSf zm1s;JVu2-|G-g#&NwNT_HH=1yGXhCXf%M!@7$c*I>rMP|5KKhtO*ascQ&Z?SqHl^c zuSI^f3#n;1t*T)s!jQ5N*dxJHQH*>vRH^rRUFUKrNj*F z(`|W_5@tQ4G<+3YWs{@~KxoxqB5-Eca1Jq6sOrlnI?`=!r23`9wssmV3u!V>d%XLR zTny*?>BA-`rH=`2O)_wu;FkK) zJtEdRPI9%m?WdzolEfu~c8rfmhp(JoO<+d?{t~sK-3g~NBcbcq15x6Um4!oHNR0lF z+#oqP%sN7+q@zYccf~Ju^f~0@k`u>j=Xn({#v3DOiHG6aqFrK_)*)AUU?Zf? z%Fx6zmG)#@7ZlbJZ>{Ca+NDbky~KKY%hlz-gspLl3z&umPKhkpB_M@hB8`r zBJpiGMIE_uAMy4fN0u@NH^66q0`IfM!XjA$g$X0AidlXOOjF6#2V{5~!cBs`qKNStX8C z6BpxJ)jGQ0Gv=anlAK{wGneARN*W)DCtWc40*B5n>3@Amdf7v2IKBFckbk;$<1>u? zT>47=`(h!o$$&x80L->1VTTveF%9`HqJJ8Y)lfmJc#|o-?hjCm$)^77Ez@|nIH&2B z+JW9Moay&)(&rviZTDWfE$&8ElD`uZRhUp)(lfjdInL4jtvwJ2iy1VEO*>6>d*Y?K z@egnH)4v-aXCQKEVh)YSSqr8R$+N$BW9%FI`=rf^uq^ddf_o5Z)kQkVq9Mv3pGY0# zeg)ZUj3){AO?M8a5VE&<&4qGFCodsvm&tQ#5JWsOeqn%em|gyIU^ZgtmSoK2e&&!H z+41`W6A_+^XO7ejPS9 zm~^Q9VyW*E1DU-VUidrS_qlFTg`(aEOPAjetl5W#T2aaBxL2*_-?~T4MM-Ay=50jy zjGei+l(t3W=fcj8JH$B9bCO6gA|LcQv3A({PtQmr!ts=OOzzX>iNfxDHo9g>rkWSk zo=!+vq(Usk48uH(N2#5CWXy0OwG+8JxEa_n&@k$Axh#n?PkH6As-Q@fV9=>rou4LpvXnCC%Xp%dO%$R04)j2vH*hRj3Hle!a5gMjYJyhFirBGcSJ#Llu zs>7xe6Uz-bJ#Wc~;!f`#VlOhEA;zoPW?Yt@Tp^yc`YZuwQ;3}mr&_RQa zhl%{2n7B>%J`rzO1hEWyg;-P@dnwwQ%|)`{B*!zze4=(oj}LvpXSuOK^>wZ$6^Q4% zef~nSy%>)y=$*<_<1eUy*}R1K=fn*&+f6A=wM5#*yG<8&7Ceie?oLB$rjc$&GHLSI z^f1gES{pY;!U)b|UrHo#Z>9z!FLzhNnT2LnF_|5%*DU_nkxAE1wcU7s;3Sc0YEu65 z@Yk7@jOj^C_5y>wp3dM@8e~ZnrcTWN^MLZC)MkY@e8YIQevSkb_X<>A4)dPbd}tA# z8<#gZ#^Q5z7cu<(1EhDRS)dfPeA&T4bjs=QTI@qeW-;O~XKiTi7pAW)%^#R12Na%s zj*n^^Klw1ybbGvD{8|LwaeADIp4pzEZ{!9a#3wgS>bpZ%s3lX`weO|z$CH<*AX#+` zP7cP_Va;>Z_^hVhcux@$*u?3}t@*GL`(jQTqMar&!!}G}p8FiZG7@4J8FzfyJbb`G z(8{FOk#JD!bg;uNbYp>A$63TAwz}@imr&UkuNJWJS7S-TpOn4?e@2|VQUZsMFP!)4 zNBhmzQ0Kb>Ctf=)x-fjiAoEpQCRNJJ==%_TTWS$FCv~x{)taCJ91k z#AZ8;Tr7%Bv;(Xns54WTOqskTMfnA<97zq`B=@d)lfOpNH7}JETpi%o4*^}G^`c|M z+~okv^I{~%n)q-HvsRv{>0;NFkzU28b_jBYL*Ercd$L@Y%M2&$p8O4=2kKgz-t54H_s6CVAM?{s+%>acD?su1) zgTB@ltuX&_nX-0Tp1LU^zc^*hcGW9!%=~NUcGE=r*J+#`tEB5mr!C2S9__IIrSX;&yV6lE_JsJmV|j3X=Lqr5y6Qr8pm)?cKhe%x`V%-{+H-@%0-baz& zfj3(e8pA0Lt-808Fl^;KtL*`|$f0e*U8@~WH>F-}c8ifCv^aW}Z>40c^nKjq`>rtH zA*MHc&95L9FZ`4|Y(Dy8y>7T6~vTahFAJm-Wgn+s$3} zd%GObyPS`Axt{HEzuo2O@L_mM_v2LaMj%Scfh>K6>HM=jEXQ{l@$VKBv&~z#LdSBr{xkpUZ!t9(f7fSmgvZa%afBP)1YNm8zCvY8 zH1;o1Vn~etSwj=x{yw%QSn5i$u+l=5^~qho=!3w=2SLvcg5Mt8?>KlccJOfJAmrfS z(Y-rXiZL+yz`0)f+m|4L&ii2}JvVL!&W+v?a)mUfIO`IZj~KrNs^dRpnr(T(ZmOk37{85h6M4W<&>uL}uHF6xv z)PieeqAxy%5CFza*xgof>l{VM_S4@1qK7?KY&Ihy>`M204wC=FFmCaXuB2dCZh-ty1=t)JgF_rGuL?QNWP&;P#+uPpt4 z1dONtD_}f2*886U<9~AJ|DqT7z5B1Z^V-Mq|CBqoc6R(rFaCI{7r*;Ay?EgNMeF?U zbn$=JIye6}ZgJ_;XHN^C7EucesZahvi~l`zeta4_KY#nM_?} zm~rABI5jn;D)M@KLP88V_CFHmQ@1#rc>mhJ(Bh&;|DeSIq2Z^MvwuLakKesJz5)Ls z7XN$bY?&1FpV4Cdm~6f1Typehw}--MyS#Jx}%GCvq~Ut#h2r1#7$O7XNqdY<$Jt`ij1pmA$EjospRh z-q=dVz(NaeekvJXxOPKL(^v)fzl@&$Wf;q-OJLQ+)>{-l+KrIduuC<^^|(R1W~ zA3bB9-C6~cuZza%d`QGVM_H_l%{o(v{|Cdk>&>(NC*V@a9LB1W!SJW- zWYvE+j0+8N4XQniQ>@-tseSNX>#=aG^WZbAc{%aMZCE8<&-k;HH+^MRFE}9WN;Q4A zG0UN`@aX^!JrloCt+xihHsi8|T$m$MitlHSGo;m*g5j1JQ|zf>EN1aj^oYO}pDWjTPoa_!l>?R}Q673K zxbSM?#I%bw^XJwcw}>;*WQ`Kc&7iZ2v5F)+ zxsbQtQXZNOov`-hw~nu%t-^n%mSU}J15=BunTrgbwX=KP()Q7`Ietqr^(iSytfMmgNUBk;Z3?NQqC+dlRsTjnNU2nkZ7cH+g~Iln<(ymkHN zXZtBa!$8QAtmgMacitkkYfRtjG0>Oxnmg{!E)mN7`xP}y@vyTbP>>l(t3WG@=)Babt0jwI4cCt84hsDGMJ=1!J}DMH8P~M zZRMvG_LG~>_e}%OBRjOc)-bed-{yiEjt{qLV?VMx_y`uopLu1vf1va{H1giEu1Vpi zJ|r6wd3%@?&ZjfKdAU#rEF&QKQ=#RYkn~LeGKqpE5yEJq-)A) zmj%0-h?%nJ#&8}0570%t404^Ztevgw=3j+CTpg*fA&?J4qL3O^NBQ*<%Ty>i42fnm zJkc#cP|q%@=2F2PPsNcw@}OH14f#gYMV=LJFGm)4TA`AbeBYf7!RxgN*v*wz+0*E` z&XbdStn;HneWhTE`zY+ozZu5pc>bY}am^xt@a%44DBNY}@bsB_)A*n0`HOaE=-Gdw zXEIy{@yNC9e)9i;=-I>ed)9c*Q-!x(yD;Ng@b)J+e}})1V|OVK{@nH1 zmZm*L+fw{e^|JD^0$>5?DY7`X>?6&iEZP_Gid^jEsw zWT~-00R8D~foYvUie;s1;qtcY?|reOBF%$QLbbBUBw0|+>x-Sr_D-a38gbq%tbRLd zDnbWul{Jqycw_WB?7=N}BlHipEBNsD=bU_nAfnHIgJspjA(fccmeLIH-iPGMpMsVQ zIoMAcQomA7cps@kqV_Zh;IkVdU$2PNA!p@i%U4D!w*}3NRusLz
TzQ2Y`80jUJ>VuPvXXzKvD(i3LppDpXkiia5ZYKPJwk8M}Ek)?i^rD9n_09 zyO1p!c0-BBrGH2yo;Z4!OIf(R4Mw~y-@~xL3w1HtU`l_2ctvrded!o`W1oDn=X$&m zw}`U(s%LNuJ1;;jgR2?FkAn5D`N0^EJ4}c;FaY!Ej&xob1ElX|9U_ar*2ieQv3^K*|JW_(HqK zq!gvoq-Fx%_41>vG%)b#4qK6{-OEaZAaR7f_^pPQDIzS(@A{n!?P+f{<@zWx8XV}+ zliBm)a5ULm*pE%3H6i0X{k*P$%Z1$xr5MsrSeQct?-9k(m2V-(V-7JaZH-WAHrS0? z+HqWhM7C|gk`O%Y0FEOnW8?W~l(cI(lJ{=1!{E|==PW^$JN1)m5;d>2M7BH=@AI5K zK)vH+-}3Em;A^8I3UZwvp@*zW5C8H1HyA?gtp&l73OaUy*J%5(^; z!O3r3$Y?%5FNJkF>bbcBiV!?jjB19db~c@;zIEu}Cpgh8n7+3#$HXB@F6GWVyS^WJ z5_0F`d+`ZQeTmLTKceK1*r1M_->*Dc@qeT;cstxtlS+q_6o+5mL50zPnGfk{tvTuO zpmC<@|TG~h}0JX|Mmqf$nMm&xrF0np}rxiN@vnbr<1f#=Rabco|X02FMy$0CO z=boMqQ9{DxU?l)NPZXG!!7X{q{zPpzqc#8-Hx+nA05?0q9<+w*%!glsn1J0Z=`?h2 zb^zy3UHs^XRtiJDBl!9N^pIj!Cv={kmCZUM^5;E(QP`Ii9d$he5OF(Qf^((V;%sJ% zyg54Bx6_zg0>EiUAk7>%&2B+XG{VmApzhRq(pADV_1Ge;Ns~pyqd8x?-AE=M{(ZeD zdfJ#|65#6;vphzkF{vk>z5GW0dv1lQ`ax*@7#xqPu zM(^@X62RdY6vLj}VTy>?w79tgfCNAZci6m}VC z#sRURw`qfPVRZqYF%C+a3_*%XH!PDp#0hX27`+Dc^~WRuVuBu;mRy0@#h@lJ5$ZU^ zMks0%i_pLVmrf|Kg$mRXE=+b%n_)gF`f(B?kx4X&MZ%pGgF!uY1mD0Se$53~Q(<9P za3B`BffEg=K&FkP$OoPR#(<{ey)cD9F&nhL4J$fS9175W9l**-02(`}(iD)mr3`0>%(IMIAU0T&^WsS{9m0=ktykpltYdel8SLr^`va()#i8aL8N(>ZofFKB z^31?CN1)Q?21|_0F%gMoLGJAexo4hLACqI!05c`gWL2Q9?T{S&k%~5CC`~S-nLXn? z@iV}mk3-!JQ(me|%o}5h3wR{uC~#nP;q!p#>3yukQN&7AoRTHrN<|TL!_? zU}6B5D^xJi28TjOP}xdoH!$q#(A=DuOMzGbz#vz#kPJU=Ix}RP1@dBW;;b96@%k>u zf)o!q8H0h(ro=*M3&6YdTLi?OHK4AqbRPZK-UB%FW2E;<2{^$5lXE=Ewq!N#RABw- z=b|u~Gr-wS5q7#K^t)L7BZNXUi()8po`!C4qF`|WSxU*YeVa)-11GBpw0dV*JViBC zQW4MZrmh!0z6sSa0P5(FrDB>Oo!kb=)6;^v>RWsvpLPL<3cwH@DGWgSg{R((*D;U< zEQ1mTeD@V=;2lPh=-1nar zfh*%c^F@U>P_B|JYC9-~r1U4wj1Qwxs}(SHECBt5V)v|cy;nv*&+yR)8Ac_`ie3EL zoOL@mSe9BYn~w?hkp8+B_{KXGW0sFp;yQ0FefGq&^n-tT{OrmE zAV%+Cl%(g44PC+jnpQJK$BICqVCuE@ziEVRAv3Dqy91omV)Q-)IaUkJ&}Nm->`YNgb@^fc5w133J`3%S?5d13gXq2UswA(0i@)L=-8Z2-|0wa(SI{W7Rmtta_2 zfy^3OG4HzXn~GNOdB!$QTz&To^peTEar#8caP|dznc=&6DbLrj?9DIuI`23ATB@V3 zWJJ=v-;OmHlj1xt1>a}lF24HyM^WP>ZPnjj1~fVBLZw2fs?9~IO^->gp$Z7uamqBdzLIOX zk>4=A+j?x+R^s1sL-0MFU^A+x?UiM-O-r+OPP;5^y8-Y0KUV?M>2`Cq4@}AL-F+w^ zr}hZJeAs-OC0zfPD!WsoknQgeBSo!@G9L?k-ruk@(cI(`lLnTjKBmRu-Qs`?Mjd3! zmh1UUP^Y$FqhMY;z@C@0&@dV7^nrNNh=0M;VM+V|O6r)9>5PrT`^9lcOk?`4c1^Li zM$Nyw+uSub(gZT=3?sIKXxk~$pF$%(d1!P+(Yl!Re7Xbbye!xSZfT!x>8P^PQ?g?( zQv>e2)XWGZT7jnxy)6Xgf#nT;?p&q-_3yT*|$57x(mds zaH1DF*LgWVZ1gi$cG134IGE<^_3VYq45E5<`ERkEo$i~`_{2c$;V_ndjz!4}yGGIu zF|_pkkp^Dy4!vvd0h{#|2=<*jnNi1Xu}(;H@7fJ}wGUVjyPt1xsl)+Vy~CeUyI?b? z1@lPa;(*2cAcA(pHGjy64_^_-ey<0Uc=hvH&;YTh-)=_zyEL0bd|sr_FkRBHQ?6>M zD%+K_+|Y-BY%ZJQyHP9Rh=tk6EzMy9dMx0T!tFo6om}<@F96p+V+m~^2s5mad}#YE zuIL%otMTI=^J4^=QMlQd>*+g*mNCNoNNO%y_#alk8KGjn$%C&Gt<+I7;%G^(YAhdj z)Stf^89rov;R(-qIBk{mnV2-~ zA^4dtf6S7|^b9d$JlJ{jP5-klM4NWXz_E806 zKV|ku*enb^<>53nvc*b61MPQ&RuE?I41lXKh-`20dGEJ}Tdds()?+^I!rMU749m{7 zS?<4ZXK!dG1)8xl|CmaLYBFRg19%^@(qKS5f8opC(9`_{0>}kn`-LpoDI^ysM+mU- zXV$%9et>3?US?5ldrsjmOKUI7?;ap=Yl_8bN|lzzk1+dg0A7s)wAB~SdoSGyTck6a zw{@C;&3{#hEnOX34l!=^k(x{55EN~jpbXsY&2Nt*RzZ?-e4K^CG7<0odgqr zN_QqSBv*We>BOuz)M?s{mWJUk+^u3IWOkY8WnwospXm)1q?qbAovxk$98Ea$;A~BV zSrrrta?vm zMo(iI+k=_<12~^Ue*|b2UePuFU6J=P`JDIF4re-hjnhz_eVgyS_~0Ts>GR0n`SOsh zuSIk(OcwX|x4P8PpYnu6LMP_S00mx}^BBY+262UEbFrOa>+gKFmuZ|=qX4>=`jF-R zz}j#Xv`u|eplR#7+&6{YHHgo*2%inMqy-kU(PG56(TKH705Jw2%8{%45i@$k-GXhF zwTZsQle1{IS8vfF#*&W^Dt8cq2~bb<`-LxdO^IW2gX18d?~uVIhTY9ER+xDA8DBgdLI3jI($w_a6BeOM%Yho(GJnw7@OG;cV6OY; zIB1a|@MAD^+x1b9b@?Kj&rc6iv_RwZ=jnr9f2f$ik5SxGn*IGzKDHn!bf~}wiQk9U z;yUQjM{Cf-K7X+DBLuU+#y;!1ZOfij{{G=M@TG4bk^fO5=X0Uq@c=7LO!@bqON)=G zG#MO6tb)G?N%iTEfX*hMIu9V*qdV>ZsXV_ww=+2Re{XL(kdGgI69OFP4*xbb=Jr0Q zIXPJo>D!8GIWl!R7Ek)=tA<|6o0@IdIW4pLpL~r!Z@PTCB&dJUeSU{+_eU$?w<_&> zT-*tb;J>10?F_=aW)y<&U(s`Guw5Hz*IdkquV12s(|ie^ENYymo%z}kns%0J-Ipt6 zp(Hwu(}215=IKH#IhVix7CjFn(-*il*0|F=HojR4L~>tVw=8Wg;l8CkG=7zbJwoq z&Fa9p8Hya6Nmz!|`t`2di;t%x{4GNJi;depJhhu05V1Bt5*mo8|WS5a3tAWn5*O^rNC|2I<&1}5Afwjj0+x0w;UrxPS)_Nh6_)K@) z?sssN#|7Q&X8XSn!u|Tr$#xlf2OjyYog{Wgw8{pED!X4Zylk@JKhZ%HDX1|rjxmof&Cyv<1Ats+ommUje~lOE9<^s?qTq4nGO?p2yk zI++=8sIl}Hxz3Am1wJ%=+(FWd<)1;57H5R?kCEqPt_{W2l1@IoxiI*`mJ=wXW4q|h z9~KC|H85T9i)ncD6C7%QFNTL|#VH((Xm~WO4Rzmodh|jWldn=)q^=K%>y6=-mKcap z<9j|}UYIH)>}f=S&|HuI^SR2;2z?{%Y~`WUXldXpNbAv4DgEAPCF7c_Q9>nqSyFr| zHFh+OTbpS_d*aXXOQwds>b1up@`tF|+)wuYw5i{-+;FE2rSE}ghF}m=0K_aM)XcYF zKHXCPQpCyq{6Wt=5`K;-{xMcJTy6RALa-^br*cg7UFa9G8zQrbpd)3qc>QXKXVzty zZRF)fvS+Wjlk{08Y3dc}SlcY(#uzssn;x`W$W-(BP5w!DRkJ#<;eUF}}al5WSdRt?x}c6LL%TG>rPhQxJ@v>in+GxyTiwUC#B~^-bm$NExYhOI*#C|90wJT&^UcR*h|pGdPS}L^*1+bG`?z!gtH}$9k)ub9idAE z9Y)4^4ae03*TC`GYgzo=uW>`t?ZnoSJj{iCZ5?EBI4H&$|6sK9HHb-gw7Es|%ueX_ z%grgY7(t=$c>R&0L1Y)jet8eyydM(}aT1awI=}SA74g3ZEuUvt zK;FVI@V!s%Q2itm9ws7$_Et*2z+y)9<2qT2u9t=;w3{J(AoNCIJ~;-?ZXbu1m}RO& z@NnZjy<7b4*53{p^#_Qox8@4D4>mhgGb90b^$S^jmYwudT*>YaEHEnr6NzDR0~r+- z66ajpG-lTlld$xXW2<0|&0QohaHud_&FV;qn?;|is3=Vc=DN(;7uo4sB$HW!r<(P| z1r}m>E-o1syBMxFq77d~kPY>?hbjKydEK>Zs?4PpnJ&V-7*7o)16Hw;43@CCb^{Z; zF3T9YIX>1`okmHo<8Lfj-mv3?$y*XzN1-AQo4NY1+8)U`I>-yRi%>Jk*N9-va7>?^ z6z48Ct3|{j?>xrN(K;)+9_C6u5jR_L?~F0b#KX&j(@4taJdi}SLarhB<}!GS*%xpD zl4+kCj7Vg5g)FDFhOW99huM%w)lYMONV}z-v7MlEy&YTUsh<~al5)5%62En}!|fMP zcmu>U5UA_#$230kf6;c|@oYc--v4b$1n=0pF>4E@YF5mcHH#Lds6DH8TU*S=o>jXP zMNyP08id+=Z?zRwMYVqUd_L!#?{%(ouG@94KYq7c{_{`%i{yQOJ)V4i{GSp=A3j%} zk3`!yB#XN%W9}#S?D#ZO){3Zq;9S^xmi}Rq7vf7iHk&eRD)G5QF94h@l^Q?QYDMaz z+B#x-swWL&jjYyrCbY!W%k$23#THfnh5dId_RYThH)Y8|{QQj|Wld~}O*n?6cfp3Txm)fCI)u6f<3)s|zoNqtGANa^7(4Eb(%l#%AupgkcQ ztj$UVKJ?>I$yNR#+kNU!_AxcA20mYsEHaZt6>$==GMFFl8sSE7k8_$VlEJ3w1#a#~ z$?V6_94eB&Q7KUN7*v7bO0|st`1p=syp4<)&xc%I(2YY^jFsd?chI6`QniF*G~P}K zm)5Hq%T5!~g|MIA!n0BZXM-Saww1#u>3*d1U5aq#vXCFLR6T$Ku5+@n`$yFef^F6F zRDK$OBAl1T(Ml*5N>;8W;%Y4@-0onO^*$JJ+}4z%a?!ZRnkMp-QmPsr`F^ug2N+W&)BPs- zI-MJ=D(De#aEndVRLraoobWw8KJR40KtWAQG|k$0{ouoS-JJHrtH5`Rv+mu9?jlB_ z;i;Ujv#SE6Y8NCw=TBaK5+C_J^0b=f1LG^%R_Qh+HtHN4uiZX7^+(k=9#3CBV>6T_ zzdA9J_!HWnb_th|HTd%<;HYVdXXNUg>00xj&^;B7Z`FyLO$xDSg>zcaNzRLJD&W1{ zk5=AjYa+g|OmYwp+84o3Fi!cEB8ExgQ<>7oF#h%-0=cl^_Eb=Zpj>MxKN89&Kt@M4 z_&xp1wu4z7Lue5nE|ky$Q({@~Fzi4^n;}1hfJiN%Tzehd@ifdl)a~uJPxa;3lsfrc zUkhocQ>S(c@i29daWi2%MT@BeMmpVQsDy+Q+*Cjp73h!OJFld8ApJQYMjnVH4~W+| zetJ#$CRW9ARxt|k`3LSjf~Q)Z4(kL1v64_JrM{qo#^$qP)l;Fr#!BQQ!D_0~PTr~= zXDyRBNzGQQ-U${BQoit4w&AChN(J#Scib`VsyjoLp=DzNgdq3Pias%X7G3vS<5Mt< zT4xD5BviN9z%tk_8#Xkp51=kgnfC#BXs6zRP>WE)VwIE*JXJFM+a6)NBbQaXfbIiC zXXbRbD_u_{aP#due8NQ|4c>f?QtKm1GD`(N(CGN?aJ=UoP9wibovuLj z_MC=~q-wNdS6NxNkFxj?{w&%Dm3pfOvMtYq?7oVw$3<_cM>^ulaW^GeaWAk+d^;Mw znd|{1y(z*m_-n55aMe@)#3WTsC<*aP0dh5h>Op?o9~62fPE$-iQo=E8Y&5Sxzc(zi zyB*g%#$Rm^A5*l~yPhprfJTLay6O(^e#1)S_kzJ zKfMxBE$#`rl8Mpj%*NJ0f30?@(V*AEW7ll8t!N9wYw{cOKbP^hC+x*Th`ZZ@KN-W& z`fy0zC3Ty{3uy>0)l;i0xEx!^Cat5hT%*x%hkOzmJ4i=1+Rr&gGBB>%IAlC9sfvEC z8t>cMzih2LrP@;{uheDzIyU!3U;V&UD7Nn^b70I27{AnYWgA?{jb$oS3#(xuXYOB9 z)mSt}Z>A3JvI$HR0{013N`=r>u2=+cXU_+{?1Oexr8tBp>T=`h^H3;OcMS36Jf#0; z{m>A4XlZ!xmuhcR{9uLuhw}b}B?-+xJnD=msJlAobK_gYPxQk=dPgj9;bnc3{){`p z!;c~~Eq?M_)+l)uV>9w9)KO4aF=Bb>)GkxKSZX z6+)4O%ac)YUN~{+z}2m5S2ZX@3Hz~FGYtZ-p_{zjYnePz(;X!DjbwgwmdB4ZooNUy zya?MeR8Z^0(HfO|7SNIc%)H~G{YJZiBkF16p=eGeg#^e;AWP@L9Jx+S0mq$phlCJ2PlsExa$tnGST z;_4z(qR^@K>4|+@Hqz3x{)X!AUX|_3snzc|XHqV;fhj4T_kJZjOP8iB@d`HkRo=p8 z7RHmlko-t`4JXQ?D~m`o`AYnAsHxbA=>&TtA71fC8`Fs{b-qsp07~;w3Y8#*nKYAl z1$odj``!VyXgqnc4cyIbUTi-brrwp^F{O~Y(v6R*d|*(!GQT#D&i(zzP?`>E}dwJ+~ENZqgd@wVR5)G>zqZHW2% zv@uwIW8+iS<_)vEwR06^6za)ltpoavbm)&IkQ$6+2I;(xTc`(@MGYOOmL%3fY6i=0 zbd4F^tp;l1iRCJpzi+QIc9B`rnx6?0)7iI>*&xv*%xY|!9YXK734B}*3#OTW67E+>|L zZ!8J3Snfs4|M?vw&`uF1M?rj(g5)cNG(Gl;ewjRK8I-;ZE?tILfmqBf>)Mwar>z^e zmg~-}DHv8@d@D3JS7_B&=+cerVfbK2oJ3hv<8p*M4cYruhzfrdLm~yQ;mX+7%Pw(> z9-p{!qHrcF-bP@xktv$vCZ)s$8wzG|YlYB;fSB(O6ikC&w)yM~+!E4*{$>V!(@bSj zj}v5wx=N9yU_W{|L|_{Vtf@NLzCC-1K&?vgF$pt}i98Z?JBu@~v+eL)73JV}BY4R3 zXKiqK<((rTqU@m>!uG9xWB`sf^wz_-ph(TPYbt!1;(-FZT5O7w>-r2E27DWaH#dyb zH}LghlSdnOeK$;_HeT_rr8l*k`3`6(qL+H@?zbr;zuNcP6__t3iNK-}W}zqsvK%&0 zVH(xdS$v}gZVvZJuEV;lp>v&kW5dgH}G2SyJh;j8_UnPkKQl!;co3(^J1H49d<|Db&J&_le=Pb)Wy|KN^{(e%TP`1IiaE-$x; zNQk1ZE{^}4AN@H${PS03_P@x>)Bj#xp8q(wIR1+Fmw0^n^ZVXE{_^|LU;gsfx5fV< z!93ns_*ZmxV+0?a-C3Xcr#QR!@5R~wGr?TiSQuEHAKRG2{T-bh`uFJUe?u@QrUw64 zg4s1Ox%8ikvma-MTL0VP>}F5%zZ1-s!M=YH%%1k9e+cH#yPW@=o9(RW9eCT*|E8<2 z{$p!NCk~&R{cj0oW(__!``;1FH?PZH7yq9LX6-)&)2H~|U#;1KH~(vE*5=<^v-4rh z|7y)Xzw_Tg%s?M>;(z33@1>OBbF(IxG`z)p;uqxY^PeoHL1H0ZVQR+Y;qj$TO!~h? zXQOhJBXg9(Gvq=t@wwTX&yu8qQ>6XTh=62K|70P*B!MR{uH$pFe-~%Dy%MFqc=>k-4oYt%#D6*SI00DlV<^Pi|I33MqW!w&35b zS$?s<@FlOPJnujF@_#NbN35lv5D$QbPX5Zxk{p4*kiA>S8n3U~^EkaL`I7OU3(dn(4B53(9c}c$`7=^NVI~&;WW~$oyb1b{|U8h!;nur7;p_;i#GxHgU zyo2uYy-=@>orN!r)k~iO!>PujYZeyogpdbn_czt9^2YtvDzpk4MoGhE%^ z1aS+!yrrQmY8Q~Y9l!t11vx@ed;4m_Z>#D2`_|Z!&vl=p_E%!!g2L-HqR4%!ZLtWw zu`Zd2+@W2|V+K zVC{?!C`n%{ot5x@&5vOCF#H1c8w^tnP`4|Hq*2&1bQTw2fjz$hhqGqUxe4f`kvC*v zIA0hxjpap^zIl@g3JfgNFsHgodsswcFF1C+JpjAyJ~D9+lNGG_VW$Sm@C#OQvw317 zjd)-usY;4a8+dZK!R(^zy;wY|+R3uJ-IKfR&`1^!e-4EpshTh_9FAQ1jr1bu9()sE+I8>d^>IPKus_vM?8>1_TOB8@H*XwU@87z{N8Q{p0wg(qDN;+AQkEclT z>VdSPWYnTCc@k#o@_MdJ=k>&bO$gC390> zfBW<6ut)6b@?^^6>i5}Z_0^xtpWpDoV`x4BIjWtA zU%A=CXeDSN@K0{`2#wMyq{+bjotxEQh(_0S~D)9_?y5s2!dYwd`ZQ8i6E z9w6~jfMVwI)*I6K?=UU+b1P?-gdGHU@mbKKhEdg&Lf2R@UdLTx-zg zK?206@KhC^HJ2pB>e0KfVRy;$6r6~O9dJe$#?~NCTQd6^`RETMky5=^l?qujdwn{TZj0c=$FZi@ju5X>G)hx z`Y;@*#5Kpt?95<-_*Bi-(FysU-0U9d7&di*2fRHF-HHL=w9GirX1)`qIg2}oD3pq8 zO&}$`d5tZBC{yN86Oh^te?l`esc97WDhz)SOWey#UdP$<_^^WYm@3rKY0c}(?dEiFvx!&lw+4IdwmmcXL*s`x zRpqmscUR~}DYZ9*-WaRl8tR)gG4b5#x$-!^vDLRVd50+2Xo-Gnu~CHCCenMK&vIWD z@cr8G=0rHl+Wy!y_K==4;^WFf+at4Z=o3ym*O7FyY`rkt>vEBoF3N|3&@We3zMQW= z3R-))VBThvR6HJcrPzMVsaaCwek}--YAaY1jCNta1SX zk1A0quXOBJI7>wbv8HK_{qi2J6s5@@~&vLYt=Dfd?mpwEzNXJ2;?ow9&t+ zzUovh-zBtDTPFm#BImiq z&U3C?Q+evNPm7y?)N^xOg3-xGGR2<=Afqgp^AhJ zMX1HYA??K&ty#(wlK2AFANk}mO$ZUI4w5Hc=^jPIFH!;=OFw`SDvDO2QIZj1P!i^Q zGqvNcQqq=8-2{>w9><5zIe3V60L$TK#S6#uKmE4!XdWDtP29Pb1F{?cB$1BSWBd{S zWV=K26F6pu!fxw+q?)|m7-axCy+A>$Lf(~?J&9BN3nwrBtE1Nx?5I;a*8;Q#$7t;f zA3CD7A!!S_x4R{Qm0bYS$e-Le8$dfg>+uepe|`9RJrAJu&;%Yzb~hQQ4xv8AfF2Q0 zT;+$55I*gV1YC-r`!bLc5kmFe6O{w-g-I^=8_x&~X_grt;p4BXWK>J~0K+X9e(}?p zhML99fmz?)dDL!7$)68&4-T_$i@Nu9GI*OjoX3=E+mk0%oN*7&-OL=?lpYyOgcm&w z(OIFIK}5KkL=eFseYD}Q70N8-a1xtve^V81Cc^{q5YnS?2p8SXur0|E(M1htK$=R- zEVLox4mm8+uM~V!o$45g2HQlYMat(FTr+rh?eL0>MueLmYz;ZB0XYH`zm-B`31RHR zdWR)c!`{z#LZV{3pWl2G3=KsOgxxSmrquKeyiveomrMWy@S#oWuNZRPP@MzD@C^d( zeG;@2zly-E_^MK^WE0EoEob2oD(m<0aW_eaGdVI52?yPwogoyHIM1G%gvGOjbUwe% zVd7;bm#3zQk{yvDcfniJi3d2x`3%L)vqWMaimlIhofUX;OR2Q!#hG_P1gq#w1T-Cpvu+D05xZ07XX0fwC$p#;G?v}(DW*$bV;Ao zP4OgGW<_@y1|bL=xpL`rS|>a+CJ955 zlo7+MlFZEPDU&4-k%=WtA%>-A#wa9$85p*+K8vTna#F~4Qiw3md<|B7EJKf+$xi$l z`fkP{SAhA?YrxSw2m3kmL2Wt~ncaG>+yMvLW*F;ba+hthA9UakAvvnca~UI&$ZK=3 zHtD104rwxgO4iHH?|5=;>wnY0h9alizQf47;E|&}3`Y zEO1FFF!IX7c91{{^4J7#ESuBU3c#l`3wd{xCS?FILB_fBe33WY<^}Pzgy4b41;n+! zQXjadlPGsW+<@8wLz`l9&g2mRMxKizSKmS+!a}`RCCF^iS7eT)Y{^cjftLn7X*O^) z!$|H7koOkd3uLQcgbf|ioAfd1Y60y5r4&55M1&<6o7dif9L?k~w;ekF?APQZ6!(>j zDUq*&j$ViCsGVm49#4rBQ-K7zolZ8~77Y4xK6^9(kQBtCaPI5zX=j zSSzqGC@;-M(h6qS*pybx(sE_xdKAmJPgsI7s|G zN}hX2YA9KCN4zqjqk-&u!N`|}aQDc&8jsIh#Z zRSaa~a{=f~Xi zl%en9Zq$fl-{QN2v%?LRb8q!s95sXh@%!}BaSg7e4Hml%(**DDmRDF8fZ1gz$J!wT zo{bX44cfa6VAl6~JPoq2n$MxN_Fg3FN{#KFjs6rWnl10GDr%n1sUqiSy|nn>%hHVz z5W$rihuaBaDF_fewTWNqe>>NP^Cf<92B_wkY+Go@^q~X*L61_S)M0b}uJVIraL`=C zwO{Y_NNVMeN~moLte9c5Ec6_=DAPO}o0S?3tXstD3GY6+#u> z`GkH~abO>9^5I{~`AQ$%S{iZzg1hGUpb$)@f==YTIYOy1OutRkr!BamM(kI!9#4}p zVLP~>sC6vqRS>z49Qf>uGNh(uHoqpnz3qKai?&_EEzWj|+K=&sP4dXZR}|zvEntdP zX73W!f;c`}Bxbpel#K>^DMXk=1q#D>(sf7M&MD)a6&+!g|Cb-Gm|x^yto$}o&zFz`ipQvD;*x~`ULRs$F&D0;<5gB zhiM)cRK)|2grV4)>L>GHKT~C5&%tdAV7Jo2;1amQMh{(}5mSKm{AWJgg!P(i88@S*%>iHR?t`Bs(J*a-LC|0v(vL_ z!ypNOq%f4k0%q%0r^!;n^K=k`m`LweeULy)%RC`whWWv#9!!2L^M-Bh$Pqb7CVCu$5W* zlW9xs0ij@xFgKc#-;6I8XxpCxA(cS3z&wl3tZU0;xqOGwm1GwJ`Ep<(bZe!&U2YK$ zTVU{+Q_Y>_-cuE4zrnr_Ja|bsodASb!mw^7*COUq`p05f9n&dk?A_QZbpabU8tGpH zJ8rXO3sc{IJ1jp180Hy&Dgf=j2dR=iy!tQfe%9&)Z=<9C1AElFVyX*B z-Jc@uSb?oCwc+7$>Wo;@Dm8LOJ820n-uzAkTBG%D?6=aaTOZZ%0*nJWd4%5dT79vy zM&?yOD@xn0)PxX4N+4E&gHQAkus~CK{R4Wnw{)_Jv`4yty_K@$;s&7=at1CIi7C~r zU6SpX3kqF>6x5o#10s1}ndguiZz<;hLU*fG#w$A?(sy6E@6mq}T%$7RhlGv*oZHvy zH=3SqnXn_@uCB}5Z1xEP83VLMi2x1hFpD1 zq}2#o6uE6pSF03F=Dk7(o9gN)#N<_IMr`j_?J(OhC6m(!QqeXgzLgDIb8+9M7T+gL z-C1PM@Yj1wY?HpV57Z3;wTVg}6bT0poJHJeU;hC{W{J0{XyO%>`wxcp-I0@kbnW2| zf_O(8xu<2Y0XNuR(EI3I^NoI8Ea;*}KJ<_Rd8mRs(zclocA|N@sI>cMUx8;Y(B=rR zIpj?W#37*10}_u!VO*~Okrzi4NAqM?B*Z}jhx9&F<-E{Rg1A{8woZQzo;xsdciMR? znqEESKOYaZt&r#r_E-7TC6PecD3!rASV~3cDp~$%(04-B?@jwhw^Jb?CWe(i^fc9U5_eKz6^FKWkP#QKKx$gc z+ptYOsEZcu)7!APPjm#%sx}YK=uQr)yiO6wpK@Ud&&3$cAIvjfL;BvqX5K-ThMdAU z#Z0O>khfvTLB^C9D?Per9#qQv)>P$(;I?nSIF6)lzXC$P!Mem?wL?G>btS9bqPQe> z4u0B9t$IOlY};}AK>Xs3_rdS0#}^lhzvH{tIJ^>P4`6jmbagDSZ*KwCJ4!easMgYM zxO(1H(QgntZ2|Rdh7jOF2s*b+MBs(YM}(15(xmDScOw5KFaOES7S%9zRz9ig_F6+F z(h9Tf}CKaS`Ng@+}gx&^fla&DMk0_)a)F{Eip5BmR&Fu8=_h;&zh9HTjj4y0D`>XKR zgr-~8R|Nsp;OqwWnY-?bB)mV!27Mnp#1F;NtgGM4bP6kbMHbCrdEt}R;>J-lIBe&8 zus}^U#7|X^@aoGFd-e5Ov)^e|OPZY7+c}qcAsY$?WO0Ye z-a(ycRZ8fHe>tY==DN>(V<6f;mp|K02|B91IbK|+x42`}tH~`AU&zNCSrO!(8up@SSge;)Y2M%xfj+} z*-E0MxO80ZNli|Io;tEfBklNEjGrZZHNGD`p?m#CFQl6f`~;gg&E@5Wu2+d1;Ty4t zd~$Q{z2t!A&?jNJa+A|oO(=~UXLvg2==GU|}~S}1?Z_wx7{?vSqj+Q}Q|gsXpW zWniAo?z7k~>r%DkkEO5vMD}Y}@jc)D-2&c$8s&~d_U$E>=Bn+Lx*6He1(pY2OSVe` zoT?6*cYRtu)pE!*-myuH)ZF}3a-37p;@5lMqwR)Eu-BJJ@vJHfu8D}kdfSUj@9tml zk0+zozLBwels@`M9aef%!FT4Df2;4DUzWm8MM1`oemkYbH2#^WQ_Ipqid)%*kFsHp zm>=@pE6oa;4Rw5AQz@qSD_-ef@bHq(0qwu<@msP~&5h%^`^x=Q894}jzx?klvr~*} z!iMRLC-y!>p=R*N4|he73A->^4+gU?cN6i}r(<>{p!I0tqt7?1x5Pq8gs$xb1TNwhpTKwF_=~Y#j zSvk8NNi;(YBRR!t8Q0AuL6u;`WhySU%=Up8N|}dh$^KoBL%;B)Iu1|>DXSfL4slvx zdoP-B1<*;mI2RuVx^3+1>%W0S+1`g`!+t$`p&k*e+bek>iO)HEn~4DtAPKs2^=M&L zro{E4?0#O_uSeuTm!XC99?CeC_XfPO@#{5E0a_2zC{ON~Ye5fjm{ci&WV8>6U&UPh zbBwsSZ#-J$DE!OM?c!9=2>WqVF-y3-bNc0nUO`$Fq<|$V!)~RRR+^hJGvq2(3?;|+ zhNv9=NDmu-=2T#eCGXEesR|$kaPp}S0YBUthgN@SwkR{L%zOLiW!Vn$+{Bu;R(H65 zkH7BoJkRjbE6!KH*w7tk(vKR{jS!qErKFw3pl7i!D7(ra-(#31IC$)-NgY&`vJH}t z4YIDA!ygqoRXB7P7xG35d~EBzJ>~OV2S#Y4N5*25x9UN&$Sm+&Rtu2)F(x~e<(hr1PRp)rui3?lG^nm5&#?#!-m|7}F^lp1p?dZF;Vx2?Wi+ba z*e$-RGE5zuqSM4z6XZ6eDlJD}`Dn8Kp{)JQ-N1X3v4d3|nk6yCeVLP!@8zDm-EpEY zH0zV)sTJ?2a*GVoPCLALqg$;qs=Y6Lnrf;UlO>!MCd6)`o}n|;W<0P*hDE2{g0RH?{-TjZjk#qke@V|CABxkxgX30L?h#tiT674_DH_ z(%AM9u(&>WREu_Mn(uo|U$jt|0_p=_w|Zwr;*;ZttQ0qSjL)xXRg`_(dw|Yea>~F+aF+Q_eha3Fxcd#PoWrkYq`v1{_fD z^!jeZpii0Ds8bZ?gNUZRPmm(xBZJ03!ScJDm6i%F=v#rq0HLHGyvga_&p-@!Z$ovY z!WV|d>xCJV>RktVU(@?towXw-vSP%mTZ-z)P3I<_C4xd*Zn$}51gZG7 z9op}htI#6n=D#V9Wc;Fa^`B~id&lW5lPtUvp~a4$GWgnExfQKle+7ys*OYFj6gm8Z zrJiT(dxt!&@>E>H-?N+8bO z>id#*|0~yo^QM`YL^p-^@l@H!fVIZ2BF-FN#R|6Dj!DgN(*vhBQWoGRZ908rR@|%1 zFAq-DJ}i{1`JJ9!ehW^2^61gr(H}GMt!PHEHUZ@`oNMO}rbk{gck!iC?=RJ$q1H0w zP>wmT)dXow(3Z(J;TtT^eyB0XGYTQkr)*94E>r{euja1SNzD0AUrc;Vcpm?Anemn0 zr%#3S%pRAUqBAFQ@wdL;=>HWy+!p>jT`|Jr)zgC>=aU8U=Vx87%-5y8#FMXm3X-nA z7gl-u_qXWhTc53xvsrdGyO zWb!nAVjCIj`H{7?V|e=}yQJd7;|};Z$a{+nZbxy}r@#sQh(UBVEWhnBQvTr5X%we? zCIq#~?5siLvYnR;vV9V^qu}QU(VcXz8qwfz%@UGrSF?_kKaD=u6Mt?PZkO(Fy~Pvv z$Sa?%_%l$?_&Mv7LU6~->}{nJC2ww3`r=ecc`S1(oZkXVu}4S~jHP75YSv@5u~?mP ztnT_>^70Nzmp)yW0Z*5qWS5a@m$7k|iCx!SpDxpgF0<4w^Wv_1^jc>oWKTRpjm62m>@>Df8a9s6ccwM!jR>O< zJwnNpI2>6B6!i@i>9v*W+77*`1NAaPU7b4O^qM={nQ&iFb+M_536kirRxS@m%D0E8 z#VrjReH3y;qyI34{{oHaYF=*|N#RJzj-|2>j420pL0@|Z}%rs)oBD~8Iyr&12A_likVk=Vz zy({|l{$r~8|DoFUU#6-rPyW5y_FvYj|2Hypda#0@sy_X{O;w+6jN!v=dzJZf$WX_J`uVbm|2H*M_qMjW;^n)7s>*V_8p1SuN~rr7_pTLP-5gQX z6k6Hz=C6_J!qVcx;-Uh4yDhaeH~+7E+sl93sZLLOTK+!pbwlv$w|;-^RKN2sto1CY z@px6?ocGsGwO!U5>#PE+^fHUI()lo!f9z0um{oF0N>Wl%VqzkGs`{Uu>d45bpopmd zfJ5g0z@el-;}-@0*rCV10r<7*|LC~k*Q#~n{=*LC>Z9HNoe$;Q4$uB)s#^Nl3#p(a z@qiRO91{K;4)Oi7Q|%RxheKRGe*aYsJ#}-zPgUDFxRz;1KYU=1S3|jCqB&w>QKI7b zl-pgr9lCF0WcHUGGBB~!HT+u*X&K?Cs%3TW%Kk4q)e9srBV!ul4_~w!N9CFr(nh{yI`VIJD1^RGXc|p|WK5X+s6gTD!4=^}teyAwRJBwii;owRK%@8W z@q#VmARYGc&j^u0bN2$Bgich>Ta+Gr8-ExLsr;gEf$N4vf`t4$teTLZ`|(_&!t-n8 z6O)uDVa*?Y>`oiK%SRip>_vndwp{I(-?wfIYk)oT^XDjd6qUsJmQmDGp`*)&tL=gR zpmp%;Q!v)pmxRG_Ih15$O5YE%5(UVSRYi?GSKGg7^c=!D1z6<>VDk|yknfbr8%K9( zDXQ2bsKSKbZ>`2j%QzOOEJPX&Sd14pu{uDyOcwP{m{r3PJE!aJ2Et7E`{kuC_(mR+ zrLDnGq(^1|n3ob;fEWcA+o_JPtI#2f*iK4}8cevqDlv6#ea-Q_8(FLpB~brBna4GQ z7WJ4$6|LeXyI!mmg&OaSUED6mgi-XK0m;{>_y91#;j?KJ5Akuz&Gp?W*LqAjepl6o z$FNlCcA(T7#BI@Tktyn7*!D^>XTirwCTe}gC94otdu z)Fr;p8LLBrh4PddCp9qq6ulq#%M(<|N6LvyD%P@~y?y&ii7fTocL-_dwm!1?Rl1hS z=;j&)mrC+gDqTTnYY@AzN=(PC7#$#4>pjBy75&h9+0(T*sufBi<*$dkIT+pQLnjp1 z-zgzXORJ2ov+`CWId@JZ^@JG5eLOV$_NC$!C~WON1Yu-S`lTDR0PwOh-Kh#AtMPsi zt!W^y9-L8CSQQPqI(d(H$73gq+%5U_V+BnSqW?kUj7L>1{3Cv_fv z8Qvz6(M&j^N(g6^VtqVlpj<#*f1*43i_A;a#n~x&5?V6z5urNf{^#5(sZHNhWZLZm zs-}Y4LB@d9xa|%LGS zU8sw8mcnEtZK2ni3fKY%=Xrv;0`oW!;q6elH_YRtiu;;4s%&~B0jyrkW=;bl^El29 zMX!ZYIcaKMwGv{(T^;Bq;53JVogzy!sxtjxjRG9;e<6xvhqh3?j*Va=!O7y$cxY?5KdE_-LYtRN#B{w)IKPHs zrbC{Oh%ytYeVoEqWm4lFOj2pQ66IkVkIhhGNfH+jD3lk$CwPtJFy8GXy!OZ4rg46w z;l?IR$E*9uixhNEswP{3*;}PQ;|XdZoh6^yq7jD}$yC?Z^7dSUwUx%4nua1=1ZkCs zbqy+iI#p>NUXbCu%Nz#r!f*p2__--o@M8kDjlkU*IY^S+4qL}y*VWT?j1!GFdRR}m zP-sb7( zRzg5v;wk4J$<7&z#)RXQHB)XRs}0(|t(-$oN3-(8qk{S(3TPOc>L6KhX=U8p%8c0$ zhfQ#aPq16jjCiG5n~TyW%+4Q<+Z`m5x-Yx( z)$IxNv1jaqec)%zfFyytdzHyo%vppK*NQr*XlR`%Afl)lt7E`L2a5}uZiKrXzgI;F zL7iJ%G!1t49H_%OyfMD)t-W`oAtMHp$wHQIznDhoqzCmh}7(t7Kxw_CX6j6?+i=MVmjyMgh1PIk8&g{oAvqbdOuCX3gL~wWfH~qPFNoG@5g#dOogUJR}?je zVF$0j|ME6grX{fcb9$%blFIY8%;#%8v>@W&$JEz?^%bnC=dH;i^BIz1p|oYs zl}DHYA3Bj05PnyJfH4HLo>bLvpgNywE1LW&pA_JS(lmuFsXpfkp}IZ#_{I@sIhVfe zVYpN#L1_r*sy+oVjHt85cM}7N%cnYlQ_$v`khbMRpdrHOnuk!HlGbyOg?oDUM*Xbt?N^H_|rRPM$KQZbwhDAmeCz{fFK3LPC- z#&UW{eVGqg!zkT%RQQ1a6cAQsBlt-;-9eNWxYn1tBZAn5N$-r>9Edc^41r@vMF7HM zPtaHzWZf}wt1NzZI-XRVutA(~4Q_Rl5ORV5Hu(UFTM#M#a2bBU0A%^y({Rm9bb}w* zWOCIkNF+Dc{pG--6e4lRL{m+}$czFOhxzhDsN)c1@T+P4+i=JuYqHXO>L3gOp$vx0 z9COzu`MQkmiJ#l8k>`5^A;jV-U=U;{gqoZ`wKJc15l(IAPcC&U6|RZlk)cCnrH+gz zJ~U2Gi-vX*fbK-6+Z3mVN0Zk~051?g7~IPftnMukfS=M%Yhm*O2s~ zzF&B=a-^mo;_LN=B=B1}kap;tpb2y8p#_FPOT#pJJb-yS5`xSui@?UyaVuYr zi<4UGG}HaHhlvDWf=HK7%c8B#l1D1bk|OrtRDRZE^C8r4KqM#nl=d~Ci{)&3!W>f0 zoZ!aWO)-Wa1YoV@v_L*TU~Q3pOufkuWx4XCraFdfA_%2WkYgZ(oA4zG=S!cT&nZIb zk`I09nb=R2sMyu0tIUBdYwG<1PS!O_Ti%;0Bd)Gx{NI-)wnHFUnFQvC)V9_Dtuq-M zL>mrJ;p2FVAtA(GZHtNI0^{;wRZSq`o?&vWBPLI;563O8cQ?NSmER zdK9&x1R)|+h&#J({vkdinmh?#ZMy>p+6hYK1))#ZJgkUlWdwm6T2IMBsoZ7(8B^eJ zi%86d?AjTX9vm9*;kEM2YdS$_FF&BCPq}wU{o0p`N><&8{GL+Yc=HOM>IsC)QR5I zt+Ih_@XYdbpxe1BMqQDJkf<}?mGY<@Oh_W#ou|4&X(nK%H=0k)Qb7BrxbyIaJto%G zkgiGgMGMQzdpiLsaNrqG>B0@wFO2v}&ukBI`Qps2vO=`Ei~%1(c54zAdO5$w`k)go9?A$Nfj~FI|PsiPBj_fXox-8qCO`)mU@kV zj7JdQb58H}c?lh{`I+2|@uSF;p@|&@>3B=#|ME{oeBd^qOLi11XAKB&y072fOknr? zawi~j`Qezf#$iU_i$43@q?Skc_3ZX%6%NqI$x0jJXQ8i~M@WcIGt$NKNtUk@R7gYT zeMy|hNkl_FR$Mty4DZsj>J#F=1U_)qY?p2Oyq?|(fc98F74ftk3+WWLpepn~b&)it z*0){!`a}TLxvap4&e}iud`e$$BZGeIkONv;+M7r|xn-g1fuFvRHK17q`Z&xBW1$#S20~VQn5AREEsw=G0FysbF%>&RdsSq!y?T zN1ZdsVeFf$%dCZx7JN2f)20q)&<}=7w06}*wA&ke zrqqEO33ng=?4YXbeuKpZBD={9v)tM4=()0M2?J6VJtaOpkGwi34PJr7+k=C(9M~A@ zggPd!2yx`0U6HO@@fHmCgrQ-s?9rFFGRay8B#y|YYkH(4(^c!BqTOx^nK=;$Qw=&sPwN|I+_(fN{A+hb|*rNF1xrl2=O0EpFLZWQislh?|v)WBV~ z^+NBw5oQi>1)MJXS9rdV5PnHc>YQxV^N|Ni<(Ze}2TFN*Y+>CKu=4d_t&eOB`|@8v zt3A6GniFgcBYRw)@|&4%h42`Ve66pP+_3>N*+M& zji&kx2Zi>9a*q1PjIEROd%0#PS!yaPFo=jS>j(g(mg8Z@BM(-Fi4BI5lSm-25j_!< z^hZX--cWijUMmefCK0qEof13M}-cA8{@|*FY2y~}^x~@(k#)*{rXj(s%kTPi` zC}|kv^-05Rh9jJ+D+-A4Bzs-}f1!X49{?ELX17vil98jtNz>20rb!Cs>KCM{|nY;N?uZa|kMyFk_a$MrD~aypZ6dh(-o$(372sQCPXg2sd! zy)wAC#_r=E+(LSw#GdOCRPe!yj&pR zoXr?nH4dE{BOykKuF|;c$FVcXS@n^(0e>o&;~mya50+)z_4%#ncUcF)E9)r*%dSu9 zK~}o2fYm%}%E@7{?;_ZdfMC<*&TS5Qr#9f2k|8_~FuWS{(^v#g4{uFdQ&J6rpZ(c9 z8Q(C1t*0Z`W^@@8@^s=3@PFD&R^0w+w_-xLF`2aW5ZNcTsH5Rdna{D>iP$N&y5pfs zFCqMOW@I~3&#(GmYi1Zsgxr0WcZcZ@oqiQytoQ%%c9#!rt_!~RkpKx0NP?E)UK~oX zBEj7$Pzo&$#jS-FDM5n=*Wzx)ibHXS;!bgQij~sxu=d((pEWak&Y5#wJbyyo218W4VhMX3H&jf7v~frA=^uXOrZWn&7@0_2Md6m4&hdR27!`*H56 z*x13e$u0oB^CQ>JObtLS3L6)4p>?cAAVGZMKqbk&WTJUA7J!{efMt4oR4jj?qfWwi z3}L4s$!y-7IR|ADU^q)$rr=D#c+b5}t`)OJUPN5?$ec|>uKm8MyW;;X^NK^z-deHI@4(MO~B1bl((=j#1+IviuL3{=qa0 zj7ssJ)|Y!TB-YhptS$s8i)sfgwdNERJ^N;D6H6iIiG~KYI%ngFGp>k|qjFba6|A|Q;C&oL|D%x4 z1gQ<|O3gmqjLN43`8HUGuT&1C>OSpHL3gRCQpTUMxu1%R3?b-7As732S55i&7|b{n z34E2`CT|h(8w1;v#pH3@8e=P(oYW;R7!(>c46iJMm$*50c8g zhZN8q{oEJ`C0yL-pk{Ld%c>?kf;t@PTC}4+IC8cxTiuw7zTKrvu}%k?TEykJ(_m<4 zs-F*&f&H$|i5}Xe`Q7?X;ZYWDMjz)69Az$>)@#?$upS6d_yA7f^~82(ilW z#HivRPz*h<)Ri~A%FZT>dAq~T`|WZo^E8j4o!5Q%x50?Mvb3N6ci-w{Gxo#WcoLiEbnXS?y2}pRJtwbBFpeHL_afFy zj(xgGSzku>ohvlwaSy~<8V7pceu4`jeI*R| zxZcxp6{bN@;*iKDcDNZOppKjmzyAZF?ij-t9n3F2CrdHwy-a``7r;y6c^t(a_9mvB zJKUqj@Xp#4g}M`ObP9Z)eSWzh*u?(bi0^taDIAA~;ju8^I46&bgdb!_<9lr68a=H9 zKrR>%iV742@Bt@*C+u;9kVYB5y1M|@O<%Gi-Otu%VPBr0p8CMBcg@W^4%4K`S0Qrb z#?q}jlY~zIULhOf#IT1xGWVcI6;Rvzm{u+L;W`8xWXc*YS?}~*l1TBhuT>K4J;0l@ zAzSYE6_l3*Dxf_3@~WAfN)%rvsH48O?!5wR)uhm%?g8>f2%|fq%{iRBDjJ?STK`ns zlG=h8iGP(@I@!)>87zFi;oKLS36%Eoz9mcmU|@(#jq@x5gJFp~U>n+?Ani(8RUahj zYkMg3n`#C*{@LjJ&k~t%fQS1GI5;b$NxCMa%G%N)9=$khMd^h^Q7FdPki;aIXtpVG z==PhDT2gfwxzR)&5gF{$Of*Q&=yA8jHZP&<;=}J!FQs$H@5JEGkHo@eQMp zy|!q-25hkD{YXsDxu;OFQl?}56XcKGnq|U-?6p**47x=y=!}%_sv<=h8416tkSM?M z8?S&^B?Uba!H><< z$DYVWlZz|EWVWd+tP%~;jx%E0(!rv}I!v zcL2NL1fKfQw9d45`^E<Yh#e_&G9pLPS|-GUK4Vc&8d4x83Zn?y<9a@3 z=&TFw1|&L%HI|kOT7>c8+T^6=W)8ohtxhg%(oY43B4235*n&D|KUAB|7fuWyBP= z^)B<%PKvv%=}qC6wHQ{I{0NpRJLC8jlZ)4FQ}Ij%YMdmbTe%cHZDEnEl>~hK zaqP#5G&6h5h@1z57JEoY5iIl#N}4>=mzR~|blQttirjTc|E2A{O)b@>E87GP$P}7J z9gyZ@(%$j8b8y7&OauCuCz{2I@1*&9lMZEW!Xp4H)?ED&Q4}ZxN!#wC#|B^}S}< zB>JQ4VENnj*9dDf+C{Wl_$}|jhuNG-nxdX!EEfV?iJ&3$;!xk3TNuA$*we3;J3;nh zQ1|OjhOw0=0v=_MvFlDM%+qSPh|@vv5N0{%gD%maDZ|;McLJI{eOdXOG2Bs?)8Dof z`0rB2UXyd>E^b@8%l~E%PkCP%#@9~iMJ$GD8#Z6I{^c&8Jr<$%!JiICT}WOi(h%W7 z`K&4kTuLZy>&HKraxv`DhUWvb^lE;zMbIE$4-KVOMb?}YbkfzT%@`@PW?b9BBX8>*&5MiBf4C+LHg7|d&Kk#E zA(X}ZisnbNmA2#e0zAxzn(ks-j~(UwCdHqy-o1aZhaaVxC|kgUU$M8cn*Xg@`u1u^2c z&s4X^?1pr?eo9nm-|>||2#G~kupYDdavI{8nFVnJI(hJ=ooS`{@TEI z5it@&rJj?+mrEze;k?HY(Cc*D6L2l(xx(#NkA_f?xAMYgJwW1jMvYHIs&?TI_m$HD zK;O-JAw?lS_V5TE@aZUa2Rrpf>C2Jxdb9SibvsNUZ^_%@6QYyi+*$VL-c8pzvD zVXjYHnlGGv2nk4oTHA#Lhf9RVfg%?BCTK-|S@#FPy+~u+~kz1Yg9UG5J@<)gE;sPFJVO>YMDeo(FDisL`A3V-vgoH+jN5y=mw+A(u zkFzoLb(xdS-Nr=pDVJA`b58;5hN8GWk4?gpGx6~59${&-A8LkcXq8;6A~MH^h=Dmj zm6D!Mh=NJn-L$Tqo)k__z{T)eg(FA-lSj0)-m#&AB$ILJH;WmUB&7eFHqd`RBVoX00&k}2H_Am$WO#RFe!6S{$zibf@Hy_w1l zS4k{P_-5FE3Yj!wnhro}CqjWr7h(CU$dyTgm#_(C&S^HP>75lGm57Lmb)A^P>DO<1 z>`9RQeVt!s#hggQI-PVKrv`MyVkY~f6ow&PUAk{Lb-}6)bo~&=j^~2%gyX50di_wVq(7-1B+R0}@ z*E(NVpCkJ8ca5JF(GsD+bGe3dj-inwF`D?h(@9QqiAMdpH)^xAUp0P35xoh?=zIQ= zvsA4y*hN2}9Hnn!TrqjAX=m^>L;zr{X#X4Nx{xB4Z;Nd_{>5tl^yROtCh zR4+y^O2;ljdyIfln|O82Q$S(e*|PDwMJnJjN!YuoXz|S@_-CVQC{ZO&->mzL4Re3g*VZADIg_ebr;ZkHOc$w|VD}?^5PsYN#AHjJO zi|5but`9@kBOqsa%fDp7C$jJ?sktX$fAp>801pEc+RKW<)-9|k_lO(}hiBzw+Pg^{ zJHMii0#`N`XM=?%CsD?`qmL?vjcGqG{lE%KQCZl5%s|t1?|&G5(qM(&KV>aeMW2m( zUxWdA2#Lx~^o-hOuS)_e^kz?%sY##hd231>=p)c{SNPZDWKDNj#pX8&ULyt(ZL2J` zIuw^-2x1^rLS#1+@aL52$3@+{^G&?lO#(LEF;1s-KI+u#ofUjuJ)!CT*s`TcmH4jD z>jXL9RXw<)``CXc{|_mDmxK^S2IO2TL3AlxA6#FT_O4%)e{ zjBOF!W;_dFw*YTyZvi)o%#Pp>`eiIgrZj(nUux1(%llZ!ZjOaN1bk3 zO2%*28sq65#pp?HxL7JXAK|H@S?)R+Prk9bq_mhLH$AEU<|$xK8@(}?6!-RWd&vKr zD_7Vc#n!EHxCzCEpSZ*w_LPM}Hozlj2QNSz?=p-v66M>v6Xdn^^V$;pd@IVKBX4M{ z7QUsiY8v}{Fj@`_himIOzrM^>kD_MaCB=SHz8g_vt!%TF{(JB>>0Y)tIGwu8`N>{< zns&g;y#k-`kfR*0AR9$Yz6k1qoc7(~+D244ckb36v&yce!A`}9ux-HWWZZyCfqh2L z<=UYA`{(e^&2D||eiCZ0X?lNVZol<%{|j@H3Nx@2`=H|+@Ue7kyud-X4@ghhwkPNy zTw{YK>|h{0q__59$S0(6`e5Yp;Oiyu0rue-S9S1-&A6PsACNa&?XcdVAlPGP`e^@M z!XaM}PV4OU{E^8W41(iOe^{l^RyJ+FeVDsUisv}6zncGQT`nv!*>=;%f=vI(7AX&6 z_C+cWti{B3=i9420dDcw&`TIld(%N@IyV5-)J#<|m{$@|k#;Jh)u)s*r&Qag)K{l8IA^qEXLKxQ^nzy$@@I^CXG~US!G##xd44R8 zXQ_pLmK%5{mv|hE-% zeixnjE*88}sAW^K5@dC=n4W1kxfdqm+jO?(+JInh*u&E zj$h!3(gwR4p3my@_3fQUR90$yrMRO4CEHc#0Xg4m{z% zH}KkXE)2NKweIlTD&Ewvmhr5d*8)e4qrlH-fVyOOMprS_Pr{X4FMInMpMQPx1?}R? zNf0Wf$l~i|r^lOzoxC;h^1MyFSG{hPD{d~_?iu|ezDn-48GoCq#<}(-yGF2F`w3qA z%X?^Sy-C%m4Jgq3eta7`9^)SDsNhg=joQ2nBxH21$8iDrkEa|zU_d%n1ix#05iWH6 zW+mv!7mtra9)3=|qO3S>^+=mGf98%iLF9pmS${XjcV%Ah0$CZF!J|&BpDv1DIG`>w z)CV%jkmD4i0Bd{CH2))9AxFaMy_MVhK=RyIMA&rt_s9Fl@$7ddvp1jI ze*}zrRI&hH((r4OuQXjDKeGYqKKyL>fUG1#1{T~TBzd%2bycVX+sLpZz6RSA7M+g( z9muh41igBtz5F!1A_y@Zl7c<0uY-k3&pqn~Ud?`I_Lls0JK^{YL+xjiptr^Ui-Z1e z)~kP99R4`l{4Wi~z59mZ)$ztXh`u=9xHw)vI^MfFTDjNI=ZCB3`-^7>D`)%52Zvj` z2it!SC|+)i{uxlbchHC5hX02S`p7M}Tc2mL34mi@<)^}U0>pRv9VCxpmP z{^_9ql}>cAv%eS61#&{h|L7*Z<9>|f;x#a~cy46=FaE4@pH9^Ir+}8b?;bpvWa4^(Td9`)j@WPY3;fy7}! zbg}2{vO*vwONCLLI?1l?Z6oSfX5f1xlO1|!b%mpE@;u4bX2sz`y{ongx^~rMIKYTz z5+7Qxwu~KuhwrbUqB4N3Nc8Mw9qMR*w%XR+2gWb;R>2eZj=zbRQ?fsVolQi+C-^ z$qHu*50rb5Wa7=3U~Q^{EzY>Az;r@Nr10p7Uq|MIQ${HQ*ST)gn-HXjvS#wdA#o8& zx88_W*veg&Hl>B(y6ABxqrxzG^`HoXsUAoqw)5-Ja6S^nul{mntoU(?`9)hP^xb_L zzQpg|P5A+frepA^*knFRWwM%EN@qWkDUfs$&|ytQG8gZtiej_HMm>#wgi4&ec&8N& zHrYev;Xjx$lhnfPGSl`X4cN>s%(uzS$9eud`lC?v-8hIkhT#6nWEusD4FdD|Y)805 zWFsufT6cp@%79OYO|qbP@1VL~6Qo(bg<>``_J=*&kCL-c9?c?o_lPQYG{M%Pc!40U zM4@Txe7jOv5zj_as^@xJsdQ^YQ_7Om^XLm&FNw8yXwoi5J)A4Z^nWI-oJA?W4>5$-Yvq^{wQH}tK#C=0?*6P!*%SHD;8j8W( zzppnE|7a-QThE(=y8pi#ih4U(xWaO-0q9Evca?r=&IjdmgP#2d8aqiELPZn`3tCIr zenS2nyjYzN=~cQ$33?f`ZHKjR7q#m7i8wXG1ke?q(r;mmg)rK3&u0qHKS>;wbkNFI z27bea@kXzhQ6@a>>zT&PA9zIW@omE*nSQUbka)>gGgP(U8rw4Xnn4}fGWF&zl za4>Jvt|MhI1?{71qEFCGaBCV?++J6~IAP z?zf@hEB!#D#w=7fuFqSvd(@LUAQA(#qd1#25Qx+v_j+dyP=;V@>>Ng7@J6gtTS83U z?$WgoV>1Mtehx33Odb$6;{^F>M)5h&!OD;o@OencZ$-7(09vVc*;)a!=X5)YJMg#j z+K5pta(IN*0 zGp2&V4n_6ACZhqBBZ|BEU#IWRx@fu3m<$N7yMr=y=|8#k*}*h%g9gq@I#`SJoQt9n zLh=t?Ie{FOwg&!A^2x@;NQm;(>_{753gujxRIM!}ce98nl$CP>vf6VO-NRL}6UH-X z8!JY^NRvo{ba};qvZG`#-fggXL!u>f#9T(ZM55r=zSsA*w2SxSZ44a#9AbYRAA~_& z5md**lHzdPxwg-2aEZ4DqaoCG;;#(V8(Jf6y6)zQtPHnOS*KXI?hzWPjC3Dbr~Y}} z3n!>T1*>dK{8;If=W;pBJuzWs|Ix1zSru2HvdQ-1$AJDwRYKj+CYR@rL1TjIq<=LO zmjDBM{KNs7cWAF8AL|ykVdC^P1k%3tV5$T#@ae5FI>X&B9VmD(P(nh?ITlg4pA0MOImzV{l-~Y$8*97@jl+Bp=WjH z=x9eFSuD0i2`?mn&pl3}WBk_l127(+{t9V^wWnE^S;zuUh^l6^9wPzPd}p-hyj^GK zuM;kB^*N}xx=ra|t(|!hd_YP$}SPx$NLjw zcgkJRSAP7jIti$Or#M=HFzyV_GheM{EG@q`0homEg>ZymFCDZ>8E)70d@!ATn1c-O zSww}Ew|AY3=OpMVlkC+$hKi@R02fZcRY50^q#J>x50<1a?et4bbo?nM8x+TzM?J{noeL*~o$>h9TWRW>Gg|9pPrKu3f|)8^ zM%*CO75c7LG(bAQ4FpdJ4X{u_n39B+-R9PD5+cTm@0N{OnMv@A7SdM_ZjVJftq2XU zHhaJWp+O77;q@RmrQs%rzEXe;es?~nbqB$LXZLuO2Ru~)zHcl3aKhFPz`28C(^rHO zvEC0s6Krb$-?Iv1ND{aRK{k9N%2>@?jSbR*9P8>Kwe^snh0jy9pzt<=Ipep1iD*P9 zEFoI_bspUQok->%g!hgcYt{c3E4~y;7qb#vE*TN%9zj!&lDuOE5h&^mk;5V;k=)Q2 zd`$-oP3)VKm`8AIB}MGe6T;w3tXm;SL}I}ALc((A&>~iRT+q8hcer?>D+VHP7(rMw z8s*Xpdq_)g?u%nGngFE3$o0jsJON#ufG`Dv>^vYG!VscNf;Ha{8%_k}2+WJo;1A?T z!TxxmX-{eB$fvU4Bb*a$&OyeSsg2?8hJilgSWS*%kky~(Sh@zjb(a826O51m$w8fhfC zR-av8C-Ff3(|fhyK}=#Ob}sM!H}oLS8zhp>PfPU zPcI|F;%-aVV)kC^C#L2>pMRI})fD6QM+V?D6ipHiW+4MJJ*dp1YdRZ+DI2dDi%=6h?HewVv+4DWw zy*aVi(V2Y3;zB82(?s~f#o}ZsVhh(fylxnxHss<;5Jjb2KH{9fd-#dSQNfi~7Rif{ z%W0s?)NK?uxOvLdn78GM;b4+_T8V4iD0MWKSC5`;g)7dwC+aw#Z;74fq9mndP|#_f z^8#8BPM+g+@D?Ig3kw^?%;!mqZ%FGzN*EYR>e`DM z*(^+NN_2G#JBlR>QXbkVLGlbrTRU^o*+}}|KWrW-9U&^~(Jq;^5$&2M8B8e?!!AzR zE9-VG)px$%Uo2Z=lWLeJ-nSuVODWg749&&))ZAIDJysT!1;AM?J-2x(IsXYwnYeYn z96gLtjf`gY{lias6=5;Zmk?|+SNdlIq@_2d`1?;u_eJguAlL6J3#E(H5aoc%isyTk zBc`vqXM6}&OXPTSnFl4UPe>Q(syg8L$9MCj50oM0H&xp)RW7_`9Tkby3!I~#MpST7vjM^}Mf^0O|N#$+LASmoKp4!(=-p13F*oayK z^eSL`Ef* zl*>S=kf$OfWFnQ&E({lCaPwf(Js`|&vT*PuFGwY+eky5H(KKDrJblvC{#3>vPsnXA z!x7qo7uRg23?5o&#z1ebd@9p@S3)$2S3+1UIXehiPzJl~x8#*b_YM-TE;MLDTY0fD zT~b^3e>UH5$;?JKb~x2JhSjI~eldHBaZ@6ls{EM%T8BB*ocXj7C*1NJkL=9W;B^HE z+}w=e)d2Of{B27D@`7wE5O+S6yew%U5Uo8}Xw{wmJR)7*0cjxG0I@DMlb7DJ#YT>1 z>8B;cjA5k^&2|}Qd?GJ6hel_IZ+m!2XSYpDhen55bTu@fD+LWxnqi1kmXe2Tz7vD48$SSJh#jADs4JSWiyzuC^SuYd z4d9;Es~;}MWk_6pQ!js~Rj)+XNivD$KGgb>xyy@#H1w7jZ?6j&hwX0H9oXEhb{ZOv zFPYZdEPd5)7}OMW+KQhwz`g~_=fD?k?$LeQUn}{gUBs+nv3YW|y+f%WvYDi4zZV$L z(ShnI9ICcxCh~2DTiFftsoc+%_B@I1n}xOp+nK(#8=$A+k6S@8nQ;cCz=$R-yj{}lkYSP|JRC@rKTqN!qA~o_H z{q_B80mrcP`S7;sFf4i)%sarW*@P86f>Sft0S8yx8E9|_EaP`VDk~|6VRvj}H|t|9 z_+xsyqnlDKdv~SM^X!nmTZ?i^C_Yuau*n$Axkj?_>s1a~W!eN|-2_5&L>ave(_|b_ zgHd@f@(o`=X3@L)F)Pt| z#4O;4{CvM){S|2U*R8r&rlp;_F#&@Zr{gpU)9hnC_0BWQSuxnUp&Bb;1L zc>b?3(~lM>2OJIaL!=Rf3GhbmmFalY0=nBouh(2>+@O8*9E;x=i0+FYyis;#y4MLK z=1@ZJP7Lz8+2r{!$s;kEO;uu7cq8@+o`V>0X-Ps$43hZpO`9EkY050iDL@1tXMT98 z<)Z{j6k^h1LUGt*pt-EHI?tTdiP!dRbmiM!garDxmJwA8OmFhyL&&x_WRuU z4u@;I>mbarLFU?ZU6YN5d*)5I1Uy~+DGgS9xfY+Yiq+nyr6#Q#Iia5}!Gr=@?eeRs z5gBkntO$t5R>0{f?AK_RFPbC>cxDww;KjV36e_n$F_(0m0nURU!Xb=bvD5;Q_d~=8 zviIUN5Ub(7g4Jemb-+usbc>pbCohQ28|R25C+5)i25^aEJ@?Zp z_OD!brj2Vs0ICveMlo@y(UAz*!GRya;RPm|`|mNx`3w1&E#|6e`LTmKf}?Xxv{!0J zO!-G#SqDy%dxTJYpGcD0qr--Di4%fvcrwiE9$e8}q_zFqd?tIPgLMhw+n0~6g@)lX z)c$9&hcmpp;EcVbbcqlX@KL12jst|8keDfhDptJKzf}Tlbg#o0oR$vPybHj=yJSuP z>}xxp5t`i(eR|~#6u_KkoD4D{i|K=9 z`@lp8*67;5Gx;6Bk0jA(5AV|9Ud}X)0{XD_OA^U_MX6&U-gcfNxP=5{;x}A}1-kZz z5%&vZF(muNCz683V|tVGJ%%F;6Y%K>JOm9FDh%sht0tkltX3mu_(W3mYyQ^1;nm1B z-XsQ9H%y-RJESu6`5i2Rh3Gi+m_hSOT@u8z@gq#)2p5n*K=(3^28#S}v^oBB7ZVNU zdsQ0+mp6wwWRSSfkf>0T*n+QqW1`W}oB;q7a+9Fhj9WYe;p@9zW@8CxISu&-!jrPr z=KLtB{mLsN-rty^4QZ{-TFVxx%P<^nn)4TT7y%6et<95jrh^hRXy__Q6#|%G>i@M~ zt*?>9h9n^*txnQhmy4tl^8w6_bx5J1iGph^IRP>tZ26#nI%uj!4Sv-HepxQNf2>#c zm`O)a%ckh;j%PBVqXu_ImY&4TQp|VSs8eZ|8?}rR7pN}kRpGPH#Uo1(3^J{(aLpg; zaj6s>{eFJF{nbXPWbT%JDD`T&xgikj`NUm_ZZWGhMnu;z$=Q4$esKE23QAGaGF`~E z*gQug>d(xPA$N#!>X<5u@NsIX(7m&p|7=g#ZRqU!IBvR?7au&F(X`MVK@%nXW2ZQS zJX#`{ddb)UnVNj@8!U3}w7b+~L$u|ZsebZp*jC5WaQxk6QIW*rL0O&GVRlGeFLzB! z#jk{TPnMpV+i(MJ)-7xqjif8eQ1zs^(k%6?m3rlhjwD$1XoX3D3%hjY@9!FoSP$n9 z>TuqbsMr6LGI!2$HYhDD+{QIOjmQ}H*X)W}?8k3~QK>wlSgC!%E6)IhF+8Cd-rwv? zB5>nVig|kw-9B8n7A8ZV7tW{1l@+Vm$lQXvrMw|m`lR;~s)XakkQ^qBKJW{_$7 zz(!j1${eT)671Y+e{xq7^%eJSpBP({;py#waI#&r!vo|1|D>V>(L7jTIl#GxSpB20 zbq75=I68g8@+n~#>WFewQ_G~8UuU0xIC5C?)dd%^k^APe8OqMC`!7(s82(vOvnQuFG27Q(Lvb%}q5OGsA&sFNW1Pm8wFO;4++tObx*4L0Q^Al-Hjp@GG z#(F)UsoygE4R8_PZ}>jZbY=;s45~$LOdzK)`GG7wY^*9Mg48tGm?&RAsD&-lmwW&b z{2)pKTX@4o4jU(JKjm~X4kZ~>Kq>h0?K)J~GQYtx<;qvs>Z3_3xw;Nir^YJF>|su} zQRFuZ^SpJo_tpi_j?>quyA#!cS4I9dH*~qNx+!G&pRiM3Rao65=U4TL+k}fvTYB2d z)doF%=+KyKNhlhi*kIps<@3aVVH~7W6NuyK}Gpi|u%tmx2+Fv4!B8e@|C2wlAyX5DdK zW>x#Md~5#pHmJl65IfKC08Zv%c*OV5?m3FSa0`nF+kR>cRva>@Vba( zfm%dZ?=8HArKr|vujB8q4R#R^DIdnck&xR6o<~%Z<2b6<{Kve3J_PSpaXo`N=)6yu zxT9CU@RN~2-2oxW}pAvl_ykV>L;4wP}zO$}$Q!RyHjAS^O7}#t75E2eOMfbco6fAiW4R+CXmOd(XU{O zZCV^?Zb9vPU>4{j6iYi0=?Q*rPT%4uEsQv#i;pw+%Vv({j2sO~2IQS3B|*jWEuEKs zC~dEpM^KG4<13j zyY&SyC&vBg##g)JNtuaDkzqut<|}k1F9NJQJ&K@ako zBC66DY<5+}D>uOf=8)Hk2&+=*og!d?q} zi;{XYToz#}mTR;#9oLwrKcHoAmJ>p*==b%|;r&$8%gYh0miUlj$Azb_%$)0lz%4*; zD5L%_YV6PE?GBy?3$HK;18V4Q91$do*#N@ac9o(`FULk>TzA=y_)2>}F2hyaiCX$& zZvq2*h8Lxw?Ol{X{fNhkl~l##-P~%Bb8O0wXq~e?%#&mxj?L?{JF`zkHl0y(W(FqL zLIN8Uccm!%@QG%&xqduzOReZ?Lt62<0Z6;!0~)W*M#~2JCzfGO!<}pluFuP4m|QGs z?JNbf<(lP)U5)B^wgqTFLwzO(sr$`VdA_sKckP@RSi=bq2n-&xBE&X3KW zok&e{G|5QJk4rRETNrxnw#d!XrAH2FUktt0dTcR~CwK9sZ@-7X;C)LV*UMO=LtXt| zxvuJ-&vJbacLEm;xSY`61Tufz&riP+V5hotR#UZWaY&l``c1oPhHr0ymSo;>nBS%_ zjpp^Mg)EP?fWTQ(Yh>ltYJy~jPzq7FSDj4XmR!}-itrq1P@Ljg;pLv|G=eHYM#=W5 zsAl>Lu6F}VjgIkk)nVw4?}noIPR+79et{_xu&L8~6I|7Lkz)99{}o}#7kYxXRf$UnB<pn6F zxqB{dio2g_c^>IU?Jc!%E}fzBmfu_PbD~Ljbhmvx@x1I`qVO}ErLf=&k`OI$_atUv zWbBV-`Rqp5ah=7%kNK|Gt4LBZX}U_5UY77zFVoKXWbdNzYsX(>hfgkN)hX*xpS%aY zC*7Sd()_|KJpR>tM|~SJk$(L!@#ZxCi`SOm@{g~H#5CHm!H3QAGt68 zT>hh>DB*LKxO}@U|KVopi_c}<@*fSw+f9iNb%MY9`|~6;3XP{aRD8I8C*q-*5=5F5Mwu2?iIjX$6QPDiC!G|= z0|}z%?-)=(r(tHDbpL7rr8{#n&2fg!XuhIx`5aQs-1#`w_uo7e5(HVxl z6#}yGcXlGBK6jvmWWekJwE8^w0yUkTZ8%Kfcw|6KW*q=G2c9HGM-@a$JPuFjK$@Hw zn<9W#5x-N;>%VI#%2u4UYd7;gyakE!$ONKE$?3=jcXU4Ysx%-D(xC)$LveV~q$H() z?;)bdQBjK0AYhGbM2D==P%x>Tq)B0y!a_d0R`eeyvkk{PsE zMA8Zo73ETBeZHbdgdq@l4t#FcC*avA@4}CKG=#L#Xb-(D46_3o5&PTS-)67_GBSo& zo+uEoqrWxmPYmdf6sioeMh}>57XBBd=|SW8fJThA`~NaW`t$qt|Hje$r>fwej^^s% z-%y(Gd*A-GMS8h0d|wqj{G%%P*Bt4$k$-`jm5t?vjn%oem7SHbt<~wR<%x~usi~Fa zjis;u+#;R-zt|$3ogDlxVZncZnvtge0BXj^TE`~$`YQhdHLW9q_n_vVZNdJ(=1995 zOTXp&{`a8f&qdPS%$Clymadeh_QZyc`oB!gzsU<$GzFE{`<2%Fmel=O82ppfWd4oS zBqk=r#l`)Xyx_l+HF5b1A4vXe3ns?K^m^&sw*~){H6bCP|H3u?em?)EFo=rzTVC*u zy_1{0qpO{x+r6y$+cas~Uv0rZr%99kHBHLz75n&I6qiTzzm+v~Z(Q$3N&jRuuJ*Q8 zHjZYNcEt)$tzH=4hXwC@g8DD-L5=C3J;8fWqw!Z#@J~=9C95u?r1`(mG=EW=|Bw`9 zU>Bxm6a2SH!3YqgLPch~Kahycu&*MkGZ@04l%_C7D`@r|d!BFWk2zB8I!O%0n2p*P zR_)^dL}}yh-jZ4c>y^|w zTSd7{IUa)|z9~nQl^+#O(Ef|K>eZPFvq81F?7U)R)Qd)ex6w?fZ#4Y`0pk^?@Nt}8 z{QC<+;mU5)J#GJNgMgEdeH{4 zt|2j|wqOCeSxKl6+}BnRXUwUq==TaAx9LNKwhD7pk|bs1UiCam(urzX>duA_JmWW3 zV#`h-Qx}}Zda1d6XuTP)Kd`YREx$&*A{7hn%6wMNqzj8Mg)wfZn^^ANCj}{VXi`W_ zrx<0FYssMxqDzIxeA=E(GDz|nU>T($neQbxhzS($gdxjECFL$2XQk}VmTQvNL)`fB z9h30QcvfhF&7PgnZ_s?M!{^sSN!n9)SPZIWjRWSArS#_eMa`FcC7F*&icp1edBqeO z;iQ0F<%hyLo1aGI7D$b->>DhU+@{Ytq%HZoR;5^q`qJQu%sR%I4ooGZ@4A%skD8us z4m=kkcTk+JV*i{v9^=Cma0G|x#w9$-RpaN-Qn=}~l;vaVrS5FZa+-czi zs6vRQsHLbL1K6c*2#8&}Sqr?9)UYgUmmK-MlSj)1NH{b)U`1AH{Q<=X-@nSP{xp`X zJ_{P}VX4!3uDrB}9UX$Z#RhHVd}F?))RgS1ECUnrMGHXB;-Y*=}8T zc)385$YR)rVUKsU<&aCvCFAmqWrx#h*?h2Bn+`~A0^yBFoN}lV-Mx36* zkIf{j@*i7i?nghiGlRKqc5)LPZvI7SZuTpB?~{V}l;-DQ{q`Soq*q5jkK6v3BfY0I zx2Jt9pZ=I5J-+=uD$o7vd{Xa!NNI9DCUp6#KL4Owd{7WN1QlLXnk5y-zp!|C{i1I< z{jA;}Qh|lH_)00wKdKDeWeKb4uM=QSa<&h*iyknx16;#k^j|5H>H9oXtnnc}U6f(b zDe%!ZoZ&0sT4d)srbBen(8~ilw@!J;ogpjaMLYw729(VU6Nr*T1U(d;Sd#U4n}bbi zt^~6g0<*(HP`|<~cSeWQdQb`ZPAFRQxxN&e9ce#bCO?dZ1PYv(6pZ9`M$^+E{gqi1 zCzXv#ZXZ~X77D_LeNtv90xz-2J~6Yi3!_zBg=5I3QNvgR2rG?U<`rPB6)3v9*SRq& z3TcjSa-X9yPzMf~63npn3THFU!8vwgzLCS|%IRpO>xozsLo{Ll?^MQFO=W|CM0DAj zdU}xsX{Sjc!f%Nb>e%Sp9%I`vGBqLJ4m_!f*ma44jxn;#FeIy!Fj98P^tm<5$qOqI z#$zBR1>zpWS{Y4{&oL%SHNL(JcN}p_tI_Ne0r_G4FLK{lN;a{#ogPhl)!T{bw$Us&8(&2dBs#b2vY zKr}WYr(ex@Onh#G_ncIV%v3kvfT>RYn>vAYMiX`J4X<#8Bl~2L4!~K>}+r z$_G{oM3-X6?t0cuE**mV=#jBz6?q@U6Ya%W&{OE(+(<{6;>3BWHFsTN4e)JE;nc$i zzA5w5jhCM*BFgNnlo#gj<}YjOhszw?2N%BGT-LRL%bkLi7uP7R>ibm7kMe!7M${x5 zMkC7I3Y3@j46Yhyhs)pA4K5wMziL_mfAZ*6{&tpf)x4w1eWaE7?NX{6=P2Tn*LEty z_4rlm_3$U3tHI^pq_X#QMIG|`_DHY798wVl-w!`M883Knz)h0U>^H_iGMWCAFnyj6 zQ?)2?I14&0DUjl~vo;v7&WVlgh4sDw1j0T`Zg|}r3LWP#PSLM@EC&RbjwgbNyLxGZ zd;#fg5zYtXbSw{&g(JPz=WS}4U?jjtM+gWcc%9~sych3fDau!~rax!NSGcfQH$5I0F`@a{AQPv$!TIY9*y5L+spaWzjj^-vqowRF8A@_^q? zISuA8+ezz50*1$<1u!;e*W<1EaoFXRU#)un&)Th!!UZu$Wyyt4h*?~ zN7A3`%2okzQ_AlZ^1>T7_@F{Rs>_ugh>fY9!?pl=0g9MHYm88x$(Z!J0)V2qGE(Sk z?oz$jbG|maUGeobt*5iS^h!E}stjGd5cF&3FuHl(>qjaLidPkVd{M)#xg1~Z2e*t zO?A-!snh*()n@@YvvAmW&KExb7zDydxHG}!A_^eg@~Eu4po1W}8S}B{P6e!|%kpRv z$^$+4Nq^F5^S>trXN$CB3VVPi+f8=YC+kw`@Qb~v!SX;uw%vauK0pbu{iOEZc z{@Iw|5^~@21F8fOtVE-2O%v>10wNP2(PIurP@m>tv64E3L?vG1vxgf(V>? zS$Ady;@}l&t%~~_Wd3|Y{%_^{e=%YHf26(jUzF{_uT2fikQd!DG!hC(cY}1wh;#@@ z2m+ES%?v%1v~+iOH%NCVUDBb5D0}X8ueF}FpZ9t9=iQ(8U$}lcuk$><$05W)`Qu}d z#A48p2aXhnS@5J|xV)<@SZuyggu^R17c&r!iH9-euD&lSE)w$0E2P{Y1ZHQd2^Z0| z!yjn~NsSM-6fqrti7!tjVrv(iZy1`084Q1dk5L`$3=4Z(#BAgx><$IGUBcF{-wdon zuw=vDQ;7<&8!OB;S6-kntZ~B?f~Fsq2Xp%VT1k6 zMw%&F?;pOv4}_{|=>@mUCv0?Fz$NRDJkzoIQ)6PrwKrfUlTB@%CM}y#&6tC6 z{z)D^ec%Z$W=jSrJ2Ran#p(Rx(09ll1b5jbcNq67Vl zD4%poY9^ZFdY(7hi(w=NWSv1s#Y(1ZvP1Yv+v~AyUg0mEL4poT-=kJ=u7wiF!jY|_ zMWA?uMtTfaxFMAc{z{^MBya9eN{zZeB0D7xCW)(ER*7rcqe``@N46XPW)sE}&EAhu7FSmXt)BBB#;<2j}p zwMzg8S_yA102}w&b6+w%Jjx(ivZ=+IF1@A!mnN~qa>MQ#7_vz}ATafp*u`?g&;CM~ zWdm72v#7nqUTWsoxn`I}Ev9QdK5_U6q=_>P*o8H==+%{cGb>Xg^;AnD?MBu`kmTO9 zHqO+xjy{ilLE8R}jeRBa@lsnsP!J|@s<~j>NnpEEc6;q*;M|H?(!CnhKm=g&i}=ZK zdzE|!W_HKdkd6iPR)|hv@hx%QsQ5e=@MZM*nHp)-3(nDRQa?%wX1Ss^@W{!2MG75s zl=RkNWD^X1Gr9H!wtkUD_yWHofXVRI;bKXANBrfi)<1KdGRRs|zK(lw;(PC&W=u5t zG6KyA*ff{8@lxm|tvK3b!^NQq`4I(W8%ag0lyF&NMt%L`sb0eDZhvG$u~8RSH&XCU zOqRQ0o2naR(YJ+#7RS}RM&7HX(?K54M<&~k(Tyzd5r;_tS)6DOxGPi*T=>rV;T~NNk2LXdFbd*fS5;!FUeq|=F@6%bMT8B)HB?x(eWfTiz zg;(Z57Gq2jm<~wOQR@C|Ef^)~gO<(85VTF^+PxA-L+gp>mQc*4cMBy;OXqMkCXI+B zVdo{tH^wZwYskVxBU&Bl&Sk8_WR%?%VO^$XPiK6j#ExUB~ z>5WZK4>$(os2jHuWp@>o;pEfd%^H7B$3**?_PNK3VwH}^IFcm8pqc|Jap>C_sb_cO(J31XPEIqM?Cw`_&l%XU!<2yjI1d{KFbGRxhNwXMqEWT^5gE1woM?B7nT);tx zswEi)KYbHGwNuzUw-usd-x5`6ke zY-G`wJ^9NvTc-!zKU){R*V)4lSSOb4eID3negZhQi+G+85$cRAY0o=}rQ+y} z%&rp!ONkfid|A01nmQ&%R){2i0WvcWL^y$TXCRaCkknB0hKIP&S+sNr!wOUC#0o3*d{_L^?aBw$SM!!%um_P&bhS!9_dJb*~@3>7vGLfFEt4!{V!9q zAVADTtNh`qWiT$0v5@q!S@}V|FtB?f&tFM?X9|!#%AC`?-Z33n&pNOrI?*ID7ReNj z{332$dHpixJKDr$AL|wI`2|_f4`pj#=y7O4$frP*~&^h_5%Z0G({#LH~*Qv<0GQL<}CD4A4*U4}vkGz}F`?#55ND^-L2l6-!1{amKgqQKDI|f|LlJFJt-|o(+MOq@VMPxm+GNi#5nVy6MTP7 zq`)pW@JS?|fw;Ni8yY%Vm-vSPd=yFpWY-1Zlhfo6s*8zMXmQzN&LxQIZ{2_rvaFF@7?XV?Rwy|Y$pmRlt#BeBSR{L#-Lc_g(OrMzCrd}Qsz5FP;`rGf8$YM?yOna{+L8-NDywz|ZWAVE4+j_)PDNIVo zQ&DV&I{cEW*%{PK1tA~H3VOU9+bHkC6w0$LMpG@HkdqrLM(RE4l22e5%%?=X@a8PX z!ns64=CjC(lhTCI*go%u>SeVGbBuaKO&V`}bnRiRBfd&xu>QUxM`fL+bX@}N)6w7N zE!>suw>~6l-Fa~2D-d%50UHf9A>r9H}|iDcJ?Sgj~n1q}=gJzncRGYb)X z_B=7+;dI4NgiEf8y1ITLU;`3b#PO7jdv@xmF$A;tXw$G18|(3w`CK5!t-v(5U+Be` z2XhTCUUz~h^NiI<>P2mWc7%*Q7M#LIleP1|DKU(et7yJG?Qd-UwOYHN;B^TSF+VFg zj{S1^M{;N`Ba6JrB22L5ZJyiQNH4SAaO=2v$n?7=s~E}MrVdxn=^Lwft$~;gay}(a z>jX1Gm}v^zdoQEp*8|U=B@*4vN!qE6qvAFz^ev_DBb07!k|^Co?F&B*yhSN>f0%@u z7gfGpTwmZrhspgMxvW_kZyHk2V2Z-qWgF?w}4si&TU5P z9^RHOy-c@9Yvl0CW2pHX;dTB%)d18Ds>68|?f8~^lWD7=-D{JI4;)@-WLxDvcZdDO z>mco$(z6Y&@b|Kog?k-Mt9(67Y)i}*d{ZIvXx zU+mp3rW{eynK))294x8V@y&QFm^*t7Pg1^f6DwAhycPc2x=DV^IwnjS%d$bPum?(U z?xb)PUaSJ{zJ*S~wXE@zO&3b&9)U$yf;Q!cs`|N0`orkDp;lF10ITVKgo(nIkzFz| z2?q9aj=N}r84+cSaIENv=T^S!{EA}V`FKKqEr-9i5t63R<*~RLry}O>SOiMnh6YD&spmM{xd_ng0Ev^9<-r6kkv{a%~)>Sv+v zOU%*t6l9EFuc*A$Z8U?XT~l!tKMQCrYWqIAWCDXC4F~2a_X=2GAls2%-8smzGAcW;5jOE@BDs{(>_`Zq6GiMYP89%k>vPvEMgF|Wk7=X+M+d%-BdwS(bhyJroSYNbvgT*dBG zhGNrh;UdRWj0Z+TYN}lJu}fTRDapinVvYp?pEuRNzN+bEnvc2HRWu65{r^H92{^(E8OT@d8zS z?{dlI8sg;g_V^{KDuq>l81mY0=ND4aUEzZ`B>k>47A!TDQc-2 zc|u(yZ6vH{78VDD2VA2)+N>V@SR9nbeiIuaVT~&N3@Iz!zllq1vt|=s8rBMZlaMcA z!)drQVmR<7slLtTktg*VTl3Kmb4L2*fAg&+7Xxv3Do#ifk4$d=<4i4pwNGnr|sW4F({p;xQ73krgOWC2U1NC!F#>=YE{1C~&*FL9{Uk0E}a%E0{W-c=e z#^a`L(!kSawT&z*>mGdpUM_yUD^#H`oA{WHU&pQ*ZLw|NC}C+h1X0m4Kag&2W3PCF zq_vI^j%jApt04BUmDm&eBsxJ9NEG4FwDI+GU0k>_TOXz%JXsbuioM2{`S}1t^Ws^F#S(5VRif;vBUq4C5$dD4=*ll zF7*GMJe*q?|2p6MWwz(bZ1>XK*xzKrm;Wt!_&1r*{-0#R(A0Rx^z6Yv&A-Tm)_;%* z-G5gPhr1g8R(;GhrLE-uQ}xk+@_dZ;R}X)#9Qs@~Fjm|*+}hGm&@-6ZJ(S(im)YK* z*4CHO((_L^q2_;XABI&nqsWBPe}oVJ#u9RKvOZ;IgcMews)rww65|u%QQ8l`;(G7G zy0`yM9-@RFpNj0$%WP6ht&)q)J{FlI78;?*g!iO>lL>8s=CQHJ$fzik@Z;ZDLTDH~ zC^+28a@bq*MO~iE@6R$OIIYfUxLQ`8x zK~r2-O;q}+h}2VIDHTBp<-dD}D9Oho0U7Qm(*M+ZJQinvB+m9of{jOvgHMH1yZyQ2q`%Sw)28y@bTXU>46i;G^@D+Ah6-wZ>8u@RrLu@m)$OW8z^(ZCw z3L}w6{~0@!(XdQxvUBJwFzpSeSNkh=Xs6Rr%f`DZQ*P4=DFeNQ>elX-4EJolwOa1{ zn@p(c^#Y-i0XbAWd4bVm{9+tx6&s_;PaM9CdB4(e-mY5joqm+g3E#sKs<4lSRs=Qi z#}R%!w6dFqDJfcW0j~0{3=GOx(pOr{j~kYM-3zi+W~ok&nlJ(&04* zHWJO>hu%o$*}xY;7}O$PvMl+9^e81x1thP3-CTbA0Pf882x(!QjrJ9rVo#9q3<(~W zTjtT%kS(38p8Nn4P|>!=ko=gXUY^0a@g7AcFj=58-Nbrq!1N-x=iKc!<=%LF1VS0g zm9@Dro8cjnj&q=?0N9Wf0na;#K#crnYHLkp{C56H6--GgGQ|e{C(AN2G_(5NI)XNz z6ETK`H>~Vm=8KHGrL64-yu=%AFS1*AwK)z)-%PojWh}_5AvARy>SzYUtxIokc5EgTNvNz*r<-?lrEe$G25&KFL~Ia-DT8 zRB$bNmw+je&HE>)BcjKe8j$vWV0*8#Yr2m_?w*2-w;LL!?$U;l@B6$Cb~O@Pt_k5R z2@$*w=ckyMCaZ7&X>gScN&ILt8vuRw1%??VjpOqfY;fzeZb>+~G_Xm7Un%Cjyme~6 zxGlS$pLF`=Xl-=OH5003!)dFs0+?_;#d#Rn{~1?9tX@-1EpNBQW5ttY!SBaC&zg~M zh}%v+%w2wTmE@;N^rY~?5Hp3=li-pU+)5onnLY-W)yuEhw;N>AzhW6Dkp?`BHGSSg z;96Di;poS=Dl=@#Y;49qlNn4kWwFDSp9m6$GYs=C6iOPYf1M9SD2mA{5Gx36*^$SH z%aiEo*UC0?3Ote3-rT+wB9r?%$+$v->wDY{g0TXe~BXh_KRr)!N&ck72ITVdU{f~UkQL)2ZszH?j{?zkGJM~$Q9m>&M#KQlI9S#pEiCrLLBlB4PZ(@ft zH_#bHP%wG+SMK2)+&7WIbR|QkFx{J{e%yBaD^)hSE{M28Z|9F%jPl}V7I@0Maula7 z^afN^BRfw+QpoJbT9>gu7fw1u>A4EE#;SV_z=s0r0xDcz&YQyhN%87Lf<@1C?j-_T zf*zp?Dqrv|iM+j@FxrVJ_dg>~eP1#IJrD=O0y$`)ZQJxuf(c})WC{K1|~WN z^W@>Z56%~}pZsc?4!9cRxuP~#YuSM3OY8}(xb&3>CB^!plqY+awz7T5Za0}gvg4-F zAn-!htC|qkY{q`(ao5f;PU|qhH<%MUmF)#@AP-gQSl$p)FFrk@0K?TzejwYRBJ`n6 zyy!;}rE~67xlKCf>#eXp)S$V$pT;-B784Z697uNs{UHE;_F|bN^CdV0moX7U+@n!i z@Rad*QD2GCws}yMfS+Uu_L9*(H_*$i29~wY(1_0J?VfMVAE+h#Rw%abUTixvV>&~& zqc(gNdJRqSA>;#LOp{D0KM1KmGO!ioTSpv2oiD&4%iW9VQx-;bG&pAuNCmeDtkeBj zK$cPhl@{4se3y%k4J>aapl>e4fAfVogQiQr<1dKg>14@hml_9=5xt~NSGnyWo;{*s z=|T(43)c3{bm}T}#zE}MnTp41H5)SSKwiDWdGqx!u&xu_{VIe|9k7wI?gE`WMBrFj z!g04-c#|G7o|03?sPA@=A^2qf)Du|mQ1oI=u~7t$T7-~!LK(2DBT^#RDeJxbV9CxN zDRi9dq`|G=02c-vaP9o|2;D2iAqzuWU`~va@yAH=J#J6huzTY@2aCK@T%u#F8!ndk zF_+DatUe?B!|6b7{mVX}(6}ZS zdpQ3Flx_TK177$tY8?L{#*q3v+;d-rE++X){O}Z^GVf(sbeB#tC5FRu1_ioUmtY>p z9pX2!fyBjGP7DqkOuq~8@hGe#oXD9zDlu5o(yo|Fy^xP?aZP=UF&r1nMOP4#(_&1I z!PciFuOk%^H1QBmLp)sr>00HRN765+`mm3nFCDYHn2cL~*Y70I4Y`i3B?39Pg_;l= zZvd|usaq_L!=VzJR1-}D!sF-BzIR(tqUIrG&5O9SyKRnpt>zKK@r$I^yB*$`<}umO z;NS(nU4b!-anJF~%wKnVGDIztVVYMtw7>UNv|6S=j$ajs|31);X_+n5ye^Sf#$Z+m zm_tQK7+ijTgPn^lDkHAbYPFB7a9HOjGQT&pN^ZaW(7Ngy`1X^F6-xu73bH> zQE8ks0i=$l0VDg1SyuE@@R~H#0@t%oo*W|6E3!XD@F4d6_D6YGy(v(I zs$UMbrt)`?`xVoFOo?z5-8ya zHc83?EoQfOCXNqA0QNnv5B50`RZ##PIEW7h)FZi=M2Ovji0ML!B9wtBWkUCLoI_r3 zP7z9_n?RLhR}UNpvS-g3rU<@I5_$^*YwO}M0YovIp8o7!!HprXu0V{9K(iuO{N%7? z*-%&(K1>_D*AV6>LiG-yvF3n4l;I&NRMz))_*mI+)d6@^GQ}#CE|C=*djmTjhWIGU zm1sksj)r;?hh*51c36?c@DiSz6K%WrVesMp{!V1!{|@6E%X5&>o{AJ={br9W9J?E@ z5Jp;TM;5!z)>lXP#hjon*$-n1<7l10&L4apYs@hf!9}UB7=Vwhj9}1-)C$03i$?=u z(OynQF5*D0CNYK!!N0OF+f-h&e$>R$AxnS)y-+|I&9b18c?-=viytttAleC_E4B+g zM{^Ob#$7M++k-_cHb#zo#Q5#6_TZc_TNY;(Eg(k@`;>xaG5Jl`J_rK|!N|tBvjYZ` zX?rNy0zvvcAH(ONj7L|b?f{YC{Z=H=K_pDZZ?BP%Si!h$nvQ;pBFvxg1RBFa89rzZ zuq~MdbKu3qJ=o`cyy^0w#Uj>L3ANP%G`s+HI3R|I#>gg$mGK@{Cai_Nv}@q1&-UP2 zbbIF#1471V+XE@Ot}L$5&pCHz}b?lr$o_!((EZ!Z2G0Z{$`$k+fMPe#k9-r|U)6MtN3>I5==LdzP0#_EUL+9{IC zaU&ky0=g*~KR;rfr!bx;9==K4RY`(Ck;7paQB8=!`FNsc}ock^h*3O6|MsjhluwKGL z^S!g>LqNMO;J5pf-QlrfoKrC7z`VRR#scB1eD*kaH#wZqAipn&&T9<-VOXvzP>-9i6&oF;f)Uddn33mO_4NTp5%`N zFPS1<4!HJxLd=`2A}4Dc)+GhAa8M9#@vGppmPv(7D8Lk6?08k2C025XiGyW#zy6D)hcuM3j6M;D+v9#HgLsR ziR-Hv6Ap5|r36PX92iv_9z(KJumSVt%;p1{in@`Orfg-Ln>K3tD z*u6|R@5X)2AQEIJWUA4_r$t?{%n;H&rq_f~>$b!LB)n(sQ{PF0u9)7~o!HE}Zm7lG(WULes z2i(%AyI%lKKvNsa?IG4=$%w#2)}(E;-l~)j|B{bWqo5wGjNk&sXz6oawDa7vv|0z0 z9UB2!#jWeK?y0TRYH1xB!L8xqRHn34C#oGFWZ}DS9RdpZg{|Z#K7f8}c`|w%&PL0v zue_`p1!Y77=0=4t7gb+sHK@7`M_qp0sL^zz4fDJ)8NC&@UQa~ZMSiDzR#HAK`*G(L zU=j{O7w>r&T#K!SQkpabA*-vRX_^2S!+YZ^uRJ>HP8e!r<~_smoe z7#$u-C-?4%oXQyZ5Xmt8Vz`2T2<8GJLJrwjbcOQuV_NiO-f{Xes^fIygiJ9wIs!rA z{ej)M7{p*mz$naow6u)lG7-q}qxOvi;_#_r%YebVQ5%vm=u`ttwgDHtF=T2OOLl;f z5)BNfBEm=@j^vAez^DZM+cH<&D(p{axSu8qq0ic2$m;TNAex(g-=UVK5d9N?3(K0w z%ECsQG}EG zy1kqHbT)A-K7kuB2`o%9Y5>{56p>;XR~z}f1VDcOxiN@uoIMQfQ!L;hGfl)=iLXws ze>kow&>TsI$@P0OXMN@ntHu!7f{)&N@eRl`CO-)u49mmLj-Aa~pM;%3(9tZP9Fy(% z0b$%!3#Gu(t4Ryl*|0in#tZ`P_6eZNoycK!3ONRLt+cG}G2l^gSf9*-E?{O)WM`qP zH_j6Uj970BK#--DI%DBvi!k0rw3M<#6`llDZz*8oL|)&j;$pHC%maj)EF=le z>zps)5f4lgFF%`V54i%}`7LKE87HI2(8SwU6M29?_hrVPBFH17sQWU2k8R|gB?Abu#Z{g~?ylLx ztJ(+Z_u31KkXM4GZ{d-!kRLYykHC_2H1(%-ZA}R#{Gc2M4Uc@fOvy@COQur zixGtV5vR8ZdAK{_D?#F~4dFAG%!MxUh-B*U zyHf|_#x7<+XXN$<#yye%r^~(j5pmqR=C6kUx?d9!aod2;Dpe)$wGGk??FnSLgt;uc zzq}A3J{dHnxEKc>JSJB8aE4F3?APAGmU%^N<|6iojQaJrQeO(U_oUzN!l2y;oZJAS zrKIk&vg*W@YG^I)Z!*18pfB}%cwCpk2{7*i%t`>Fr^;x&KR})xIvZD50oO3uT?~s; zLf2kQWc4&RF$cj6CLezJ;muq38_WO#P~nAt_l?ZdB?<43aXMwLu)?*;& zlZ!VYSpgB%jB^F=Mun!?Id;HlI90hprE+Zys6OVE7aqB=G;yLc1>A@@Z{h+5%wSs_ zknkP8i@=|{KfU#Jzgy6D`65L=Q#n8LfN{hHUngUH0b5te}L_i|I&%1~^U2o!(&AVi=Ajt7_9lgfPqXLJy-(&rQOkmZ> zR7i30_;cNo8iEe+Y z!MA4>3?NJIk-4R@e3Pd_f@w7~U10D zP!z#7czUwirtsbUOE4O(>{M42!>MuEBc;R?X@U8_7jsk zuUb1U2a__%oyDoB=egWm=dRX>H`sEGO9kuR4VdNeI8~3%s)h=h(1;Yy*cPiqR7(eL z#1T>xi?oheAl4DAyvxbdl4>jzsfiYdi&d>asxbmY^hKiP2umV(T&zU2x0N}S>A53P z+%6K;gJ}wMa0P}imN@8cON&N6v*c)gVFOFu0av%wbV&BVD=vPucz>2j8JCTphTdsy00JQb7?i&%wm+%& z3{^1FMSnq7P^qh1IUXyNaj@zTf#r|s@O93O*0rvGGuF*Ggp_UJ?XPd;66U%FgMqX0 z`YdMhn}m2CTCZHqeKr&=z94#!Fu$rBZVRx|BPA#6Z@`YYcw6PUfk*DbD9JfTO*@2 zhXpg%q_mwHi0^CY$FqE0ODqjk`Ls!^Tk#`oWyLO!Vn*U%tn|XR=@Mvuur~L(*EF*i zMN%CH-|A>2o);`@Fx};n(I(mN&$VNsA!a|Yf0@9htZ-mof>8KCyOoVP826Xs5Ivi% zm@?rTl|+-NM))Q9hrNVEC5jUUs<)3H*ofWd4a!s$EhS6zFugko7=7RO_+;-xUT8D+ z$hLKjR4bsZ&gMO#5{pCnbgleDA$r#zZ~_5DN?YP4t5^0co8(^E9Gzjai(2C<2=o)3 zRoEeXI8aWRyqheS6yYi#;m00d!_gbSDx0mZY192xfmelWJKJk48#kz^hwkCj9Mkq& z(s_wW_Q6`nXcd}t*6JDbS;A9BF^YuJZ0qN;EKx-4Fj-z291<86NOs&yDFH4|0kX(- zD$wQNjwO;!xm2TMWuj`&$g|ktw6g6>j&ihn96RW3B}bhD6$$%*H-q=T*`QMt1{B* ze-YNRwPU|MHI!Ub11&29GpJuYDajgVBWN|zd<&)0Pr1h?#k5!8H36ZNQj;mmcO-la z50QpBEHGJDCKqRj=G&g&v}~5`<>dovgGe{FO)n6g)AZA#^(i*II412khN&`9BTUT* zR`qd#3h&gAwA$1x30j|IfjBGj*e(v12LXKqmH`wZ!>sxgTP>+7k>Ns!0{aKGiV@mz zENH(r738td;3PHn{MR}-)iT0qlX2`-e=^hP_5DBSsZ}MHc-b;k&wLIoKIw_L$FYpZi*(y^!cZ|m0mRTOOa1Jqw z(GGo|V{sU&UQrQx+Ix{1oJI@}d)vLTc51}ZwpCuK0T+$+zO#pEBgv#K-YkBVA!Omp z81}<-Bz88+dT@LF_=9hn#d(}(58nZ{77i1k^Y&B8Do{Af!#S~7G9gwjlA|z)?grj# z!`|T4*I_p5@lKOW%_C9a?ym!hUkAvK$@PMV=e;{{nkD;?>*MA;M3w9<%|toGw=2iHb|*t(5|d){%4M1ch5H_ zvD9#2~hI!LH*pazHm|3Cyb1W6u(bp_Bj)~lLD~sjd zWqVe>iMzF~up+~3Wy<5QU+r|MX+pB^HLOn(fR*91alUq~@-1KX{Y8Fs0mD_!I5m8h ztf8lNinEg2o|xv#=R!km?8#0JuUj`DISiU{ziI1aXhk4-;Z5QX_JU*XM!rimk4_RK zX4DC3{i?96d}(S$$Ys2OKk?Ix%8xWa3&bpk4e3_P-Hpw=W5aoNT@mAa6~`=j@WtCp z<56^CR`oAtQ~H>0Jj?Ib!M6mjKlswmcSqaKuAO)eii=zkMmw#qoq9eVd}7Jx)kFFI z4Ce2EmbA#Y2)}Tf7wYc$ivy6L0)u?`6Q(@Lj&j#PN6g>Px|h2o2`y zf>U-Q;pY_|imyq=e{Ei7EsPu~Yu%FgX}%JE;yGcIEng$OiPF8$D2Sy53(SHzWI$hZVqVt$L-O$ipX9@>aPEW7 zFMnQ-kHpXGDe58!A(yB>y%LGE*eY%LrnH;K>7$*~UicTei0T>KL;tE6a75yh=zLo6 zH800=j0UVa1jtclyQw~9QM7EGs!^vkE*A4-Gk73X04ReH)5&g`i^mT&)irfX-o{}@ zLeStCC(9uNn{jqQPjc{N<4e1xA%SQQWw+sy>FWiw>lK#J9;Q{k@>~dwv7BUg3Vj0Z z$I_TzXaITwoZJ}VJmP_lRU`6e%DuR$#qzyAQ!yf?r{RN$9%nl3ECGVE*BewxQ`Q1q(j|= ziJ}q9N4N-I45gEcf%Wbp2M)1L;(|2CdbIi=IxLFQD#T0SkY`kIHSQ=r<~WL{{Q}!; z^6QV}suZb%h z2))I_#@SJc7KoET1a1PH7ZV^T`xKxuk_K*V*H^Cv#;~3vU4Mb$__4H+J^gj+7yg76 z5{Tlwa1CY>rP=V_wy~+z@S4~z<%5XlGbCBe18FxZ)4>`OvB}B;gu`?((-90=`<;v1 zpR+hd?-R_`YF&up>@?2p`a`KYq2E65M20t{B22F$8Yk5QVGpq^Mlr?^*xnku+v7;8 zrwRU}6)Hmk=8{16fDab#_|f<^79=knveFhYQwA2pP?wB?B!Z5j9 zFd%|Dv2g9&eW^|~dED#h1ToDl^8hVyh&Eb?wsw%V*c81Dct02+Q#@Q}ha{dR4a!qX zPoAPJ*P)x!dElWdp8`RmN6I26o{EyfY7uBRSga<~bnm7g^T2;g5L&)a;du@)^&{@7 zVAF!vy1X8`M+yiE*@+fAJg_yG5)^IItDOc55{LUPafn&8Dg73V~)#O(xg{5TOBM z9jKj;jKG7`DVla2Lyu?Q+vbzkwJTis>_D*>N8xDj0KukEhy5Uu<7a;&b#AB#QtQA5 zk^~s}cym-$o;#X0I*7)u=}zbZ)5Gl5D#L`usCWHsQsyvTat613uB>E@`@}Q#PC$cU z2|yI-CqwZ=b{4c>1p6_8^>M>-^bvS;F=q5c&&y%iJs2^+7oFol#*pwxL1Y9yIPG`b zSsldMe<>LxbneQU+O-tRVbtO!bnZaS`*b$`Ecg>>S$h;3q0N>GHHh~LnuaTnPmx?N z8Wr1N6-60Is^!LTuqRikA-mKjREAux3Gi5lid`_P=~w6-!t|5FqnzLyTeuGor5i!f z?zjnSV-T9Gm6nXEw>SL7c1DRt%Ma+`-uM8_8my;i9MA_UJJTU6R-Mi=AUQ-bv%=Tg zR;M*O0z~?2YK&(z*K`@5l?y+KB(t|a$_qrW| zVC>z<*PukvZURuni)l&t7&n0vmiYyTKCaN(H4kF*2;W`Y=t4WO?Am<(-RGbvHB1oc zzQ{V+pT#JR`QDq4p-^?|`HkY++|aI>6Evz>F7UzH#%Q9!xJu!Qn=5HoRVI284vzef))8f~skJ>uQE=azzhW<|`c;kvk*Z-Z0UBieYB ztgt{FxAZBh>vGDX4+3yX93iW1=* z0ULbcIC3gGA)$KPkjEl$$fC=fKtl?dfU&Ce%;pgd$z&e}j)~150W+k_#Cg`%N$e+y z=p9=g2)|U+W$Zj-N?!oSwu#h~0T$xNPl5vhxIQ*v;*y?K(xi*v!i)%=kPzXA{=lb6 zyHj^-ILv7$GP{i4Th6AMHf)IR2IT=Fyxr@jSV+-rL0fjgoxm*PQ>f)R73195j`#Zo z&s}_SCb&HhQgsk(~7q1UPvn};>8gAKlr;bMZ5H+`{@rf>S)sp zm7+T#+gQ~M&e(_5_%__yw$sToOwBv_FDHD*cX?BgRJpIF9S;xJ_>{i9`l4=BMGcOm z;9(rVI3#fRLbqF4S}<$kFkNRJo5Uv{g<4DOhN>J~+!nN+XzrE4Q@-1Go@l8a+EWKb ze_}gYoP8-Ne%Sw3jp_ZXDIff#&?66gtyP+o?A~pL3&J=NQ&We+x6G+pxodbV_i=x`Kb>Ub`*{)`VQ_T&=%A$gb%hA&!iM!9q2v4Sc(!b3&O(nc+1WF#;8dDt z=?x%cKL++|cu5AXX!If2?6~$bOF`R9As79%N8iZX1y0-(uha07Y?ug?r<9E$N+aLjIfRg z7v}dIX3l8=)VQfU-<;yx?tO28<^9#|Y>Z&e@to-@w9@kQla6%0dC=kY&RFz{dW15zv-iESIYP@M^F`xH?SN7TTS`#a}nz{ z5E`Zk{vKclaux+U>|?&0@RSeQ(1h=UHQ$KEYyH@-z3hl!BEM<6yKv~Wi`_4z_Fcc(*uY1) z$za&fYq%3MB(nK7yzp)$>{slf2mfN|c*)O0(y(zFoGaXS#|AkIr}MKPe-~w#MacMJ z+W*_wHue95i@v+s`wNY}I=cN={P6qb(beVg<@sOb!+&wnoBu2yqMC>QQ9eBXw*Kwp z;9up#wX=iO)59+)C>rHzJK9-1*!rig?c2Y&=#9PYuiNV@TN`^D3w!H-;n0g4UuVC5 z*ibKY{!`~TFnRgU!kyMI{Q{+F&TyK^ApA4K$j>e^~5%hIZ| z%FBuqnz~}^JELmbBWl`EM09X@b3j?sf4bUG3B>gDR1^^%SX7C^p;5ZF`1p9=qI$1_ zT95o1_nb=CoWERcPM<1lGSmK(i#GlT7rhwtc*zrc$W`JmS6g&+0v!Igs0~F#2Zx0E z2L!!)AApJ<8XzM*KLqJS=b*^ve~Q{Xyj|YBbw-KW{y{{mNBo6DD~Dw$g#L?&hCBU# zBcdZ&TqBuXqyCeK4s*2r8;5RqF8M)O4TVFeJ$@Yeh|kQ*-q_ssxv7=m3rmCN=K3%* zT|?8qxM%|tb)Dxb8qX9}^~7}zWt6leon}*nGPZ$Et7pD*;0(nR>mef8UFe$~r*5+T8yAf- zwy}csHZrqS;%W5jUDBruwR2VfX>4QtUsb*PKhyvJ_|GsKHjg>Zu}w~inp4g-40Ar@ zlya&Z3OQDy!{#u`=L(HfDsqfDZ^|(|oyj4`3YC4mF7IDH-~Zt8cbm+d$YZndDO^N+@AyuZBoKVzHS1s*;vTEN8{zCJoPdCLmk`_qb;!u6unGi_wS zlODaUv&RKE-Ssc~jnFD$lE;Ug_`3^Ap|_aL&sfs7 zpBna`DJe=jk*^mPu7Ga;nQ&%kTO2^nYt73u&$MA~B4kZ*2Z%Tk!)8SLF~{}XrRi9} z6v-sOs>&HY5VQ;RuJ*k%cJ@pf$-$JzedL(_3-6@m6F; zMRW2!-INnrz||o+ zFKd(v&410d7d8bFwL4BM<+w`iT{ZT@Ix~n|N;sn^-P}+=4UJRt`PdL$+5RwYIrH>K z$`#Mku|m4HsYj<-R~$4%L~t=A9Q><-LxQssqavd0#mWo4E+gO(e76fcHEpYS&MeWUCRltw!FW|&`(pj=M9ftMoTT`C zso`&&l06(RbHcu;T`g|G_EhHJno+Ks&_%N`o~tS*H{iRcaNoy2oG%2O__p2xQ3wRe zfRvYZPq<+`js`URNxN*YrXoX;w}lSW9ZQgqHl*Cpuf>jm!N>0dca%p<-HS{Sp$gad zDqFRea@6VEKc9+t_!bJ}9t>(`q%`zfuRoX_bUu(wJ( zx956wW^93GQ_TG{pa|9{QFUxgJI~JRJipK+_Ehiz z1OZo}jo=J5$i|1xW^hcIT7eRN|7)$z^9eY5u|mR&r?xr20TL_y{hN^z9^e${CMsHa zyFpw5UdiS-?cr{ZTUYg+8md98ne^wCa2ZaWuvPq znX+4=Xl8EF>Q2k7uqssw%6y_w6Dz^GSgP!2-s3jD{kXoj^wjOH9*=|VtY*G4OoDmu zW$~SCx>cE4R#&gD?#>eirA(vTyzjc(&ePG}vNP|x`ffz+Je%e#*X}g$4|}?kvusta zJJQvE>%&g&CZ$||$$TJcd?#jzdgklAw-+<2kmZmRIxUBfOvVR^B+1orWUPWfURqc$; z(GXXHESQDMfae*P5y=D-eM0@0LYkeDYAHS$*Fk+IGNf?I)r_;)X|No$An8u&AdU-K z_E*SA|MvR+*{z*g0>_Dv_AFsswXnvoa?zY2}s~~7vs6!7fu5iBlax93m2<}0p$Y`<1pG0{Mg**DIt&=y_|`fi{w;VQ9T{L z=8U=*eg*obhFl#|DUs%N^muNB?(ZKr5-UL~0{`@IDJGM^4b7*3m95D5z zh8#m3g0>eg^n&j;x4Ol!`C})L6Id%*!9LwzsKcA*y|9vARlhpk7VA|W7oL5Q@zcbt z_e*H(`+Djmg@ahG3~A9FJaL=ujP@soeW6gAmkCz#1x^akR%)G*&q+Nd)+}PBuqzJe z{Pd4Y)Q{ij7|)YAR_35)p3zl39T}rQI^?;x6*n*9WqjK!IbD3Vhb~p_!$VVPX*#u5 z71eu!vk!u<`B@ZCt;QhFEumHoXM3A;qFhEP@3Kc)<_AFX4 zAL`XUS!QI*ypo5Ex*qMl(46P4trR#T!n`_$tj!8VG`*536OLMOU7Vq{W))Uz{+m_- zYqD3&7`1Rz-jynzu?-`74ZLD&-=|3)viNCl*8eK0#mw;A3NACy=OIPv{7u7XRN$%E z%zc!(Ghnf&0z63ghB^U~(_f?vt6=y z)GGe-30|a}_y^o+@&nPZv;o|Nm5bR0x8ynhx4I?u%z~4KI8|c~BDYlQ%iBE{6&y0; zF)~UWy_bg$sintpv>4`q*m5|(w_bz})dMm)ViV~J|FlUyU7~mZ?o5z8yG8XYIx_oZ z9KVK6Kwy^O0f3mwx71M2L3MUvGy5hpLWY_|E=6s2gTXUK#dq|tI_9_ zou>_1oS*U;B7E~4qzM8f63cahlK+=07poC=x{KeAc(|!h@%MyS>`84Di)~M6IRV73 zXt$?ezU_CP3u32_5rS?KfIYcd6#p&;MgbA|6@e%$d@lr^01%64u$@hQ4=NG>U_AAN z!>=)uhbdAy#_jkQ?Z6HQ(iPUItxx^s@hgA= z9ua^)(yPG0S9oVJ3D9Xy76B{<;Vh&lc>2de8L%}JJjx5QgMrP`Ab!oTZ2)9HLr%k! zZiTCHBOv5-ZA|4Pi}lfK=Hhk*SxpQ-3+8a@ae8>=WVXY_8K>;yUn}f^-iChqWS%)|!|H zN%F%al|rcH+SKO|L4JP-3+2gbcEl2sfjhPWEHTa4h2$VIF-wsej7-RLO-LprM7gGb z#vaD(C16fG)Yun1bLZhtp+rG1NkJ4mv@?~bhSa+pXQv1_;N#u*3FDhE0MC1oocW+4 z^VAbIYaKxSJJliaAx|j3{yuOik?1WNtL_>L#qj*0a%g489=Z3#T*1*89`*O!9w8}~ z`x&axEZgsb_BvVHjwBA5Yg*}92s}v8l_*+~9bG}3r}9f9iIb=_7Aiq`Kl_H*6A&WH z&i+ZYA4fpeLlW-U%W{tRglF+3&z`>H{xk%nV}N+C;7=#;&0=@f>|CJsIYp0ih;=!M z4$`Px%LKp3T+XTOKIyV)2Jj)yB ze;b@|6I}gB%bRsZq_K$mF2M=moi5BCz`I2Nn%OU4;9m%7L5jc^0(e@n!ru;DRKP#d z!oKPSzuWAxHeC><6y>gU^%InrR;0QN@N%ik#wRIWnSs?`e%@FQ(Bh>8wg_u%Y2yGW z?`axyQ!CK_C8!YcmyHuN!||8xrP_E@G+XJ>Spoe5pcsOBKBO@Y$SEkgdvpsKT?cM| z4*;v)WYQiKd1WEC2(AE_On^^dpZ8x^pL+`bg95_Pytmch;|J82W?+atsP4lx%0nRE zUh70{^`;x};Q%o2s{E2O(N9k-|HsKAA48}u@$Emc&k#d+b$wfQJN2?e5S=vF!d3ilRvYG$PGXrq)CCtU>M+JdC5HZ(`o1hu= zZ1YP>QZd^i;5G&rb07>3;)=uS4g_G6s-P{Z!Pgg5CZWpKGWsU!4Hr|=3=Q{PDM%WZ z5D5t4+KSLI1Wkm3{Tb48Ves;Y*&n>oUr)?X2CNi^|qXI8IOsFx*UzpG!ija1Y5pA!0sRX4q^D|w51VXM`sx4T!P z^@6^|W->su>e>HIZ{V}8t`sqv=vb)fX0o+6^;%gqh1Y@H4}|QvQzo#=m-$NNNt*HIMZ{u3%z-*bc?uqv5zEuT5l8wrwMTH*$-sdjUz zewj~a=ucX5Rf%A%fwNV}lkR|u``7nzgDL4>%e;H+)-B~ygsrWC3ynzIdqd5*&y@5& za!Vh?e!$DXGA{5-aLqvBR;PCE@S$uUkKxzkmVVxvuVJ|s{#7DagT^^D6T;4nhS|>a z93>d4A_9S#>q!H;N39D%QRuVVnG&9awI6>YT z;;0$xXf!Csz}L702uBXrd%`I9Bi7Rd?`gJRGVEc&}jhYN5O!=>r2`0~RHSS>W1&O8s?wlPhvhWuTb&A2)F+y&TNV z&U5$Fb@M6Q#rwduyhxtuMQ&Ch+v)_=@F`=ucCaOLj>XnJ$o=c)5G!w7+8-8Ese ze>Rt>KmoAQ=F{y$9F@KY5G%is(L-?iWjp(c^<5~3A?&RU%u5<}osF$+Vc8*llH30C zau71#1Nbjjw4E&djq%% z6a92Jz{ISP->pyfuY+dR_RGg9%Z_oI0%H|~7BJVNS zNzBzT58(w5!1_=`nDqeY%!}keE%36S?3kT;w0?Vy^{Qk|2 z`1#ugk#J7PzL#;De~*)Wzx(zeKVsLL$bhrwj-;%gQU=0M`z!N%%<28^;a~b_=G%XO z>MIe64M6VbJNf_6MaSSp`*8I4^XRYMEStvQV3}jWMVB!hdIdZM?QvMe|{68*QY6_vEa{!-*mB#d86w`op1nCbC>*-9@BqB%s3G&QLD zR3F(&D~9s7GIWWNIj8Un2&EozXkJMMX1ZXux3iU&OnQ?vJaERy65SNQ=LcoRukAW@r02Cab7I#ney})6M4pc}T(O`O`;5 zJkXC3+9aN>TGcWvl*6W65C`{Q8U^+4j`GCc9B=D)EN#djfQm*vxw(?|s|kv`V~G z!ZR^{txDuMD{G9sBDao*My)8)WwTxg-Pb{An&Kasicc9 zyna9~e;f2!z8s5FNo*%7$%!xZm0Fi1c`dT;rsDl6Vs2W`pXA=4TqEKZ-L4TH z7DW|xR`&B)zv#bLv6k2yp%>WHkO~fbf38f>JHNS#zOXo90treRbtZRwyjcA0N87on z1BFC`*(Wr-io?g_pM=%MWFCpKPG*+r*lKr`{Vm(Bso@XX3VT=UAhlb`w)r<;4&!Xm121te~;K(<J3*oE-O zq8a_BJ%;RP6gtXz_v6m6Z^CC~zS99|(K{+bQt;m?W7pME7X9MFA55|0o^aBHbd zJjPBRUDpaDWJ@HjShXYZwEAL98!uG)oP%L$h}nH%^l))yu>tum0)4R^lBH-)f5eyZ z@Y)AE`}#P8G_MRLQ}x78H*@%$hGq)M=ouY%wuwubUBhc{T@%o##2uOU5}Ek-0>QV+1S4of36yJw+2m_X z_(ZwMu9$s#His~`;b$ETs1b*odvem-#g>N5$dUBnCG;>X^lzott6a?$nvpX(p=ST& zKBoW^_>2vU`jSlM5aICVwlyB?&tuz`5fs1d%xC&6MprghGZ$iAIG&y_Uh+c3-cUo^ z^;tP+^&)eW9pzP$oE_s+0Kaykw2VjKdA0EIWaMWVd`41;X{0cpT zHa&cr`3>eQuO9N!Z2ajcnTCDIQY}1bJjfQCOlXnKEDbb@vdhrnYo~FyDC5D&38`_z ziokVF|Kjuu@ppg8XycWx9Itg96PJ5=(TVOpGVAuSGEOgPzRF}pEPeX0B=oa;S4hA~ zVEj}TT2w00mZT-89Q(@_ zA9MvwXRY#_Gw~OC0)XuwSqiIUQ*rawT81RF!7yVAM;b$r4{oFW-Ng9qe#^cb6X&W_ z%XhzchLJ3*-3ldcCh*Tq{`u-#(y0?_248dL#l%^IY6yGT{#0(hlFu^Izw1q0&Zb; z`HGe$ONC{9qpq3Vz4JtK@wV*ksU?m@3_tc9juCf8qv)SyKXJ2A+Iz0Y$lS=W9de^o z=J}4Aly{nq-uxHPiMn$B^`q|YT=glS^Ni6~uP43lu!Rx$DO000a{q^6*!!CrVL_|z ze@1GVbdqu&G9|#JMm}5KJYOQ*3n&%P&4sct}%f4~2(jGfzKy+_jrj zyCiPHMdzp~$zln%-mv|6ah!DD>`oVR-G8D$^`4E8os8f`imO5oN%dCN_VLX`U}E^k z+m5=z^|ZJL$bt;xcUDi`1kOK+HkFAY-_$wEW*bY)%lJVw@TX=UvOX_JGqr5v^y^3B zc5llk)>U4c{PAk$E?W2Wow(>9S^iIDl|~JEyP<8@^QWV$G^w4h!|#VjX1!Z-P_}9| zco=#v^qHd;D7|-DSqCGh|808ibgW%#%6oY--e%f^ym-3pS9<%M$Fv7g^q5xx4gANj7+eyG zx(e{WBQ7WKFM8cfJ>S;3_SJejxBl*Jj6dxS^^t`{CHm}mK zfuSKeT#Qm(cAyi+^6Hyp4|3DqDp!eJ^C9o)CA>=7bi)q;NF@i)((3|9I|Llq%&pJE zpNXYRzboY7T?|heugL8h{g@Wn;-eOOwxC74#Bjw8f_LR)CWAxlxFk4@Q0<2CggBIj zk+^J&z%GO%vu+%z+wNuXeYAvX*P@z1&>?e2lOfj&wd0PaZvNbIe7pkc(3bN&p9u9i z%wpEaCVJ#GIX_meO+E3mU|Z#8Rt5oBQ$HKdPTglDgWhml|t&&Q34btyXP<2jTH%D@iEMHh4S!ES6jP1m(n5ONShA1aZ zp%bt1z@my$pnsYk;Z2N^I#aXFqBN=v*-hJ;O*33gO9elsFPp?vCdydgdoWTgi3|8A z&1n}W%FQC^E^+v8_Gvur9bI~SI9>edIlS#IJ#9DfDg|{^6@-!gMpK09Q=M z#bY{$>$@5?dW$!8=PQhe%RR0Bg-!asbjKu9Ww8c2ULw7tY}BGlvZtJ3Oht8+DE7YT zZ6r0P73`erckD}qSS8Wo7zC?+nrv1B|18FNUhcDmJZaluEi zVE;&x02|@BYYb?phdl`LEml3z->S*Ayj0DS!p3&V-%gjzfR-{EFImNo_7_F+@|9)? zNu6e6ivzF62^cVIa_~oO%NknhfR*6lT?iX+6a=yJrL#dBnH9V5eomj-j7UL1kE3C1 zp8gDN?4YcVIZL1137EcN$V#DKaOA3>x!4T-?X2q^SjzEuRiC2_CXDS3EJYTo#>IyA zx4VKruUXm&3*xi?I>_QHil6>MD)_>MC4o~wf(Zu6GK3H_=^D50`fgB#N_8Y+ADSBQw6(@#t;x$2=ra|bsai%dnLQoymIukkdZ|3&bE`$U#ooM7>|SP1uWGgNPh-{O?+W&2(^xkxW%HF%w zH+}Q`PfhauNBn~r%8!rYO9XgZlE+^;8=rf|ZFVK4+e|iuD+t`#pb3He;N_SCe%?ztYg^$IBT!%Q`n|xDUoh2B+mewQaa*i#65VOjQHq5 zu*=V}5~u8nGrbGyd*kr`^#Bb5zr16<(wv-Yj1bFO7Bo z$@+dYdqWuxN_F?1J@M-^%dz3|HG!jA>@l{&W zwsKTGcrxAKQy=

gjs|Q2DFoxY=RGz#IeC?LKcV551l~+lutEIBUf#0{LOhD{T5- zEdGkM^x5;h^S>vlo`qK&q|c7$Cdp;&xq% zk}03b;exJ}@dhl}4W3f7HGhRfANou&{lrJ?_Vgd_F(bV=+u^HM1I>kq3 zpSxk|N2KTYoi$Ol@$=7IjQ8^Ef1XC1Uc4>ecqx^1z9ZR4Y@sQV2fOTbSDp@y_MxHp zec>s0qNZ|)1adA11vXo(ZZM?wO z=wK<+rm~%L$!EnotIRCyaiM4`X|CjZ!^_txH;VYDt{L|x`Y-s2jaL?sOny6&WBc=i zO|M7AEtfxDX=+}Um3e$F@A_8Q$F%-@y8rh|kyj7%N?(9iYtO9qa;cHduDx1x|p&FqtWy?_nivqiVp)*$mAa93B z>*F?%@iRQChF4kNO#Kqtg7V2c0c#hhI($V7YKK!VP_B}>L?CbfL6?3(mlvVm<$s(h zjDL9$M6??(*7mM+ud1PqS3)+*kQ*!gk3QTa&p%E~{(O9;8v6S&bg$ZCr(YC93$Eef z__^pbR}y@;{|2=Vh*{paaTuKEUzjPi`Ei(?(>CN&f9$KHyu$Ezh-hFw`Wny1YG=o0 zTL+9WwOJ|hgI{zDp|B;OwIyh_CFHUt?6)OydrLH73z@YgR=y?vZcCzbOLAmOYH3UQ z_tr7)ZItLXT47s8Yx}s_wyevxoZq(m?XZUInA7-VSx#Q10iKh=JjxILA1<0d*==xx zRf5{7(GIV{htpicRsUZuI&JPjcak~-Ol+*3>J}=t`=DYNOhp9f~*KkZ+a{;;n3XZ;aloiG1y~!E2KSwoUj+ z)4tWPO!6&ClAs0u@lEi&eXGH%ZtptJQJDHf6lYz}P7OAm#1)%tG#<Gw!-HD z2fB9;NM2E~&9_M8DB|eBEB=F6WOO_}Qk4*0pAQLkiI(GwCQ&0wHXt8fMX!GR6Ymw} z5KRt5a>3P#Z*TlL{1g37E8n0g!8aIUPp$PwCOF#Ob(AAMZ@T;Q(q3P=UHz+@L@#2! M*@nUq_^kK;0imIg6951J literal 0 HcmV?d00001 diff --git a/docs/assets/python_portfolio/pendulum_swing_up.gif b/docs/assets/python_portfolio/pendulum_swing_up.gif new file mode 100644 index 0000000000000000000000000000000000000000..5dc49e2e1ab9ff6e67b749b9f428605ce968302a GIT binary patch literal 513484 zcmWieXIK(m8^!@qKoM}{$^q`ZbCd)3HqoWZ)C2l6c80hiD_l!z>%71scE@$ zXJ+n9bKzcPxJ@(O-s}3E=X^Tn%en4zo^wBsm5rsIzV|kp0Vn|gU>$D#{k{43H}mfS zleNEge84?fjhG{yDe( zgR!+fv$;0IT%Fojo84HM{I&djV|jAp|8e}s^3<=TZ$B4Df6fp8SQuSf{Ju8-ZEbFN zZFXq&{|v4&2Dc{r=ND%eXUA6_p%Ec=y~t#y-xDbxnUCoF40+8tWe!AD#QwIs2_^_FE_8|8#u& zHaIuhHS@K7`fJ=8oRF;^xM8&Gj`+^)>Z%HMQ@m z-c?srSG}&TEPGq^=0$D&vxfG{H?NA{yss=PE-T3|EqPH=R8UY{T3C=*P(ZJIo}QbN zo%Q@#Vnuy)VOdyVRajwVa_+0^Ipt5EX5N2V_T8|EsF2Xe8#lv) z38DWHLazmfT)9T@3;565@2aOypgTU`qKBXBC2touFP95m&KEp!=iKd`E^0=lD}~b( z!)ekX_a$y5%Uq?}>X61ha@PC;A zpe%qHRMfhH-Wm(#Q*`gH$ZJnPN!eyuSLSyn3u#@Q?5-^Mn2I(_61Ax+{FE;5QtJMx z>c!_L>b^Z$HgAi*JlDImHu>poaepp0mQ&2Ox@54xI$hDDr~2h^F|NQi+qS0k>npdn zSEqVvUVVFmZ%-1ldsjC8HgLGq}$zsQX5Oa0eWX8Ob;RMtj* zmb22sl~Nsk^c7sr`a5~pZ&+JY(*WsrfA3$TesPofH+S#Z@l#)vC?hO@K?=ABnI<3Y zJOnu$zr4V6r?2i~I;`o(TXfhY(`qUP_Fya|DLN1gcr+`_<4;9^c zR=5A;&#R?n$;}bji{uw*=gJR|dZ#(&Q{qQ<<@r+9KaHhJ*q??VG+TwFxDEQkGS3sS z&#V_R{Z#!6lc{57Vwzee`gs`!@+bTRTfi{kBpp?pQUN_ zulkCc)#CO`uY9kNSZr0@8`q)z z@)y*)ub6?2ml3M8Njhq{FYaWU*2qguoaUh8$!hG?w@vg3Oa*#Be(}c?Y6N6+jQrZ4 z*Pd^bN>Dla!GBwf44cG#`+{u+G^VKc@&8RVGQNcnKhuGBL56)s`7IbvLfh>htqvaF zG?5GtZR;w3riz=1iM2v%_NeLgsn;1l=|^!VR(TuGqS_O=Ii?tOg9^QGm$2&wAMN+Y zE2nSKE;KJ|-$1_woZZR9G_L7`!!S6p^-wvuzw$5rxlDndI^8Ce9VPaASdPeG3`%K| zE%t~9D!sKS>JMc~Ohd_7S)O;KLV8R;CJ!rVVwm*xi%-O`+cfL+UOUZ6PJ)V}9+hZu z3sTVRQ*?x^$Q*fSTweS=-o#`GVtADV5d(c<3&R7k%Yj@58d=`l>>*}r2V^j))jU}o zWCD9Us9!5YMK54F5r>8R+b?T zJyQgZIY4iV2Gi1CuBT6{KD8l@{LpU$6lw>_b#s4_3eVO)8TK&HV7Za)0o&}H@ig6h zO|$_0YHN1)$DZiVo5;&~V2Lx?X2q3GRuYOr-MraatmFiOt=N^}Jds?!Grh-B0y9*1 zD0ERYQv24ei7i<@c1g#OcziC4koUpseWAYQ>hvvP zEk3ALwT)Ot*tW!sJXMZa=TG1|W5zdU$HSk-ViXJK)_u#(9_VDELZl{3f$tmz=E zRn4iLGQtC~gFIK0!q`~VQrTsLEoo1OM)Y$Dg}0ceX@SgR5sd+d&HELh5Gx?keIk_^#Xt~fLjE<$qd5|;g zYjd?rvHT|4eu0nDC9ib^JPiN}wB6GK`cnND{ATs8#Nvlq##TYK*p@VpH*5(9?wl5*91rAfU zLGc9ZfXyco63i+f%v!A*WZWuN*}!&fica*LYQEW}yqXo-UCYW``;U4eTPl&R z=Z8K+-WnycBKlmM%OD`E;)ay+q>fQ>E-0@c1G>A7-f>w~H8)T`^Ad+&jw*9wma&RO((n!&77p%ra-Y`qNnWAiU@nzrb zEe8if|8vI6;=?UN8jQWH*8=9#!0=tNj}wZTbYU{belhWdl_9|xj1UZcaHgUIZg%+- zxVP&+cCEjuH@h>x%d>PJ)NuQ--K?_C)?Ny`&Cbh4jv2gjkEs{=y*23fvj~%&gT1Do zoTJA@`@MgQ6!hY4P+=|!qHKd2k+tKOwLgn~WaAM_?zy^|fX}el8WX-$=a_vDE4dhG z+}Cq48h$B(yX!%7{hs7X@Uj70h=-uHO6#puSJZi`(TAz>=g+ByydE=JOYenG=5yXr zlNSMrQ)OFXr}+nBPjAb=eJUY(i`uRWzEM$k>oIBH+nU1ntAaZZNm@J z+r8M90Fm`th~Wqix0kigXV?8dy%3++OT>BSWld5&dJrBl)-Kwy63a7_txL+n^AA%$ z8noQx5*CR*{H=4E#Sol9oiH#J=sAer{x$m`7|zDar_zlQfkvEkkvq$6yqh9%{2P_> z%6$-Zk>jx$pEp|p9liiS{$?N;Sa>ENgo8(oN`$ZBk!u9FtIi#fTGBgj9H#{@s*@zC zM}E1l2~rbGKC~jM3&qkgrc4IB9RTNtiudX8V&r3u4q_kA`szq>%ggf` zLMhgnloSjF4uaqJnn_KnrKXHg zAFvLnG@-^xl3pJq zRR|?l=_OaYCBKVIuFXuYuT5?oOKv_$ZV^gp(@W`a4|Z7o#+B+cCMVb zLxeBlkd1QZ;Wtx+2Sus;)-2R*ZlKbEE{csB2_->m7?*U4QsS&JhcrY7L94ffcVh^- z(E>jQ;dw~BkJ?OO%X1s7Jwe4G7u31()ww>S)KRUVX9+x$Zm1dH1GqP0rveEYg+B>+ z02$P}RSdESqz-FvWurMeDv%2U*4vr9U@|Zqn@zi=cz*NM;LM_`u-sQ3@LmTP+c>helKYNQIK{OeXgp z0Fk7S-~>~F>pls){lv%y)=NY5CvaWbNpHtLUmt)Ey*C>~Bew?Nn&YZ0;v*d<@}L+t ziAA1-#CPG4gbFwl#r^4#A`6!}1GqCW4_`+;tHeJ0%hL1BwtDO`2=|Uag-Am|815t5 zwJ#)xki^S*rkFVL99EBhz7|=5Go}1HM(^KQ9dO z6)tuqK|eG9W8yIkhUtC4Yu12LAJHdkTVfcaA5yKw;Tizq0pGSd1&q@27%6AbAF#D% zIxD!Hcm~R`WoNaNgVO$OrCh}69(f9W#JChq$jVB;1_C1aC-NCU#8~wk_dTR$5J*=Y zymQJz5s&O0AS%d^hYf6Z57ggsXS|5n~LVX zx+VHtsfJ}!hLJffaOc##UZKx>Q&rnk=BI0!o zWQXY4XY%s#T2tK>_L_ml91&2`5cxJ9S$Ng^M_u#9-$;)4rR9gsTy`I?>UHLtcNhHe zlciga^01Y2AjCr0eqkx#)_kY8Er|_?8QSy2f$J!D)Tx38XO-*MUV&uzKK{AY9rlBN z29Ib)a~7z>bMp9T?HVc-k6giVCEn6RuCBMFiGV|91|QUCtq-X(fZP+RJZ3<3160bopBmRc~8_HPjmn|2LW6KXw%=yJk8vb zJ;x`>4ES~$;zLVljl=iP9#f-J3bco;hrq`7<^1_jm>%&Hx!Pz@7|_Xa+Qg!P(3>n&R-M z`v6e0yhgM9p0fhcvqCwuBF(d+)3f4#XVKzwl16jVo^!I%bMiTJik@?h7)S`6U0r-$ z(`a6!nLV(AT{~y~bo0Ey^t{o=yv~DpW1|Ig&jkzd1?TdeO6Q(UFJa5^4@aX9F=8-948A9xPpYy>xwg=}PqMQyL8On%x__ zcq3;ys(JbD^m6pyX<_tkAWR;ko)adNng= zRZw-sPki~=^z4Jbt3u*y`N6Y=2mnNMHPUmfYgs&XFK8~4vw!KRc@~(vg1oW9gIr-#+xS+)6w2Kc$(`eVGt0+XmiV=d znOQ#J#T;nfl+WE#JUc6vJ1f<{toC79gY{-vhBdnr%~Z#dvM~@48m*vI%Pm z6SFNCGs}hrsW3tIGdqr~9h}6jv+?dZuU*%eUANrbOKQ7{Odzmg8!xfqfLY3JUTQVk zx&B};&~t|)W{2MhfF0n7P~Q*r+7FM}kIdbV`mld@WPn0;g=f$DU-1Uw*P@LWt ze7)z@ci_2k;1RtRMTZESbvt1Ma3nw+2S7ptzjIi>=@N(e#)pMohea`mCAo*C9}Wvy zK+P8R2qIg2>Ou9{xuhFw#y8d_Bmiu902crVQ$I@0J*xEF77yNee0Ela0MW(*`dEJk zB#wuSk4Lbz+CSjD56BJ8qc|4j9St%4bL*)hlP-e0iDxfNW##eH#$sGT-3 zQL${JIFa*f=St6)d&XTFUetW;(G(R|aNbWy1*hR-VYjQ?20&pe#(;4t*=NFjPIo@P zaKq!YJEdYp9kBkrIxd^nv6g4es`9>=alGioEx(U2_DTJR=eDo(WgEuG_QWN754~{6 zwakvf_&+?ZHH;Oz9L}n~M;1*#b%fguPC?oBs#nE*@oWm}xcj@!;&X;PE=!%X^#U$7 z7ruIzXNVkoX{y0R%Ch7@!FP1=ORiOJPKYTqB9Is_;q~`!ze7*t$6PN~^zh0Nx2-~4 z^!01-_r)#qZ%P63dO(O~Z^;HirxtHY6#=iI$$-Wwj5HhAs1 zOkz83B^m5qDXg?S`PEJyw7;^RDC!kCqWmy;4OW~^cSd!IMbhd>awdg&#aS03@5(*S zeO#Mrq4Ivg*=~oBCn>|*(pav1LTjx`iWAp@Nt&ffwZp{R06@?%`~biq)lBD7(?+M2u{WuqQQ&qC4M6{mv4NqQ2QvR(ZuhP1OL4&ccpNARfrJHxsYof8dV@+AIce@#T8n$ zn2m@(1Snj**T#D}7HOF|D71w((eyks6#f~Y7uX8bpen^Cis0nih?g*UOj2VDF7HyD zq-8C}i>H1rsZ)Sm_sY|N*Ea695uE12VN0v=>DdDg3qp~F3$TokrJyURF?VI@?jX?3 zD>)IY2bCnF(0gl)9H;Q4gg@&X1`6FoVL@FWNyOfoACU1omd-A} zR{IJrWZ=27odJuhlnM@tHw+)Qs;ZN-_q+|}aog|~@wn+@((xolWboxRZ~ogBSua$M zH-qjxB!T&Ejvc=Qt-tvYP0oA00edhTQ95^&Lwg!8=i4JOD}f8Ir|0h8G1bk!jPgG7 z_$=xsB{QmQAP9Lc<2FUU%LJ*!lj0g@h6kP3Dj-lLr6*}!(nTbA_u`e1KTqAbXxMmG z(||XZ0j`z9{tD`=OdwD(v&~}+7t5Y?-Jer>mdmSy$Kp$0yl&RTpG0R89*6XJKlVwF zl9wK&=POs?<~jUqAHK!|KpaPQoc*g|q3B#mG^!Jq{7W*-hR#Wl#y)ZV&4cA?#|j&4 zTIfMhl$gnDa$A|afBphfa_#9LMn#0N;irM9dt3$<-EG4-}HhoE>=d#xDaAkx%x_ zFq3e(p5QnTN6l8APvL9%I2xL-Q{-_Kd?>`e*Td7DebD-}|Lzhpx-C)Bm9>4%6I|ff zVcnIJ$#egzU%|;R(8qVjY`g{}GtE&G3%?aV(WWsNCqQ4xY;-us>8aBhSswD)mU%EH z5Ns%|Q1=H5U^ifx<}yta6c`L}k@N~fj|h$%%7daTWZs?ot?3p%QlR&6q&7Ss9!>@E zM5E#jLVqKTe@F{kHns{y_{2(kCf)z~=Oe0;YWQQfQcg8eR^IKf_ulQZJPbaGv$R2T zP*y5n^^OGayWrQ{%1}8uEJRmZ18N*<77Q+dC`X!Nqo#+;0`7OGjLIb5z^Q}tQ6I4w zS+jN_B3S>R&9kTC6V^ed;Br0yS>ht7-+~6jbbhtGcHq>dqoc{Hl5T5&E^d&Rv)h?!PU9D*tGq3b;}Y3E3$SP30nKrC=^3qu)saSFqfL>TZp9flvi{3w|X^ z9Xi5rh+woqx{|S`iCC~`*!8=MXZX5{u=h^uo19U7e({M&8oI%DpJrQZ7^r4^>xz3^^~ zc1onp8o=Y*ZBSOf{>Tg}Q#@?T#% z%OL%#*UlTyzHz(`Kn6(X^DS9_yl`9$w}R5jy25T2!V<-A9?bD5U{miy;^vESbPmDo zbQEsDbXfhVokaIFk0BbFN0x>&M}zJb7+kxQfbTg+eWrhjhf8Jq-DfZ$PJhK|CB|H` z`t)YI=CnpC0U-5`>HT)P(HnVFC`gV~p#r4sJUA~?n><_sIXzc-*T*ioBLmYbDg6+J{m1PT&L-Xr5zf{l#)36;%t`;Gs7n;iCKOVlh4u)Q| z_mx-#SV~_Nt*i5_kOC50MK>hlMbzDmvC9w59MyNusFOxsHyl zE8=d+yr4`))LeP+R+(uo~9=E>SE7bqJ8*igbI%B)ijGVb4g1axbyKOiT)GM+1d zu1tIo59MEz;w*mIe4!%22}|)KLKF{RCvXV?IErIr!V(5xzXG|a4#u}Y*eI#6$wW>9 z#0Jd?A8FB$zAr2c4gs*AgaTP70qh|FTF-OoBsT!g?9I=TM?&@}unDlHflVJv67@5Z zV3Pi9x0?QG{mYdU1LMSq*10j&at??Q-BK?l6TA)*FVG+Y1Bqt`62M#uzGJW;{Chf7 zsDNSWQ3~l$s*93pchyc2ej4wDhMi|{@RjNF8&Cm6a(!lO{@W7<3rN9nqIyNLNMMau z?-^6=4*#+=g_9gNA}PVO5L+RV_A^KbAfCS>L(xaXkr^Ll4Y|a8c|b7F9mqEvgSn#< za*6SvVc3ZkNNyfE24I#=IAO5>^JD`Dl|bC;*l*AhLiOTh_4C7M34Tl!&c-;cEzMwt zZZM!F8)bH(u$$%Xgp5Kpq*1{nay#`Ib+92;yQTFquB+`Jibi0+F+{6_1l=*%4DaV0YTO+Z#7P~@5aF;_2iwx(3D^^$%%00Qusaqq zH3TD|*gbG3dbo+g~uFi*_hTwwclZoC335~6iYI71Y^@@?1=J@9jLHXj5q0c!LQtN4P0o~%P zY+_s#17>>wxiJB|E2Ilz#$$#kF=%TLGd2bV&ZWlbluGG5djhkD_>94P20q{ZBQj?| z;?lP7&^}w7$z$K0V4KYDg-W>F0{&DjAUXlCCzH;7@AXQ|1 zB6PXW!5j(Jib>dFCrZp%?D|tH&c;%S`cXxWxp{1Q##1C92O ztQCyzI)ep0rnLUCS9Vk)wSEW5G?)P$nn1hGp9ozy7%-cI1bieIi*{k*NDkS7j#-lS zIfS0#KZ%$~S#L&s07$jIuqV5=r)&fkp6LK$+Eyrkp60Y$%Yx)E+3sTFt)XD-0mLow z3BL@$`n*;^<`+vM$GuvJKeR5fFp0aCY}ySz=f-ZRM?GS57EI4}W5h?|A^t?wjDe=# zKkS|AW7PlyirinmVrr3*>FR_A75`?51EBw(A-@-}fR4fN+4xdtm*Sh?C}ow245`V& zfn2I>&Op9_3?R(UDq`ea=oy!xoj-Z z-a5g`y>hFNQ$n6{9z903I3G)-obRS65s2pvRmX!ka4T#qEIvMjK*}gNA7A@exP(hb z$fmDR?&~bkMPC(SNWji-~^n64|Ku7~C*{u5}_ap;JRewb%N6MV)J1BE)X@!vwvC1gj&S^rcHV>o6r9pB}F!-cF~ zaf=ckC6QFz;#4TcLgukd3fUsg?Uviy{4|5wIKP9WCz(#>En_k=#_>YH26>>@&+`-o z45!d(9d$z=f9QD`hsSY~PYC0;jv;PXuscrt)cN?E)?nj`FRt{2%LIx!fc=UP={NLJ zSvf?Ca#E&4`5sp7VjsvG>Ul!6divlFvTZvyXO$dmD)r`kB*BHdniMlU= zSop=cSmL?#*iOTXOShWED4)6)y)rW0voiti_yif!xl?g$fy4yqHcAjpB$yUgCv6q8 zn0Nu3(5!(C^%jw{ZDGIO;)sIWVa7uX`=-9aI4z$sNsq!j5^m$-A*U!XJme-P#UBT` zBM)&uxVWMMmt=UxK>?E8o@XQ9Y^W3p-{$buBLQJRbM=H2KNxSIdU`ETiSDBhWdpX% zDUZ&n^!b1RATYxRXq|V40AhpAv$QPdwO!{=E%~T%`0B*Z>pk|>51-eMCu(@IAu{I; z|M^mg`TJw@Dq}N$W&FOId;yp**z!>BtPJJ@zOE~RpOBKcv6rpUbCRye2r8I&1=7q7 z#I0~VfyReG(;t?wD}D!C4v@}YS#%BecU>Z>F-R92KN<0pFLW)sk1l#FEqacU+;aTA z1eUyIulR5*`HTY5@&fwuAiwY{-bPp4_rPbdSG0u|OjZ5R_6z^LuD2?JR{wXoWPr^s zaLjIR+CG|sa)UTRVb+-mj{)(aP%eccAEk;p!#!UW4jW;{eDvP3O5bvfzzS(&PHk!a zcR80P9YB^{A&&ZBb9`AQT}z3wu>Y2pl63@cJch2GcjM0FR5-O9`;;e$fcCE)HY9M| zaD(vzIQ}&y?cO(wg#r*&Y$_^785Uh_{z%*rxgp);&)0@0g)4dQYRtM;3S{-~8)dw= zh{L#|{yA6~PtzPx9}KM%?u|hr2|gL9_y`8;`|50R>}dfo&efw3+j5r$tfRO z|1W`3Ldj?Lyv$#vv<)O5{1ThnG>yy-7IprpvOTq>A8UTMIwm}YvovQ8lY zT)u#5@1T-sH&%=4j|@AcfE$N}W@?Iqm=_OmHj}NcIjDEEzh;T3>kXPT;x-*8iswKF z5I@z9y@og70o3?BQCs7mFr1s*spHWbLhgZ;=xtT z7L*Emd5`7;|KPVvW*FMW5aH8u!_p7O(Vse;o0fi#jDZ|C-GWF`_<_{+hLmLna?glr z@5X*so|!bjM&=GUe0^irn!{ZWITw!6e!19MejV_ElUJzh2yUr*;wt+uukN7%g(?*r zA>Oc-IOoulwQ0{KaPhaT6D|NQfJ!c91G20#Iim0oyx!DrA~QFWnUCV|%XHeFhHnZ%8D)7IU*{FKMW8iJ>RP3X5yKRJ8fBMnS{pbg!8?0(G{Nr=M&Tbpju z-(3^?wqaI8_D3b;oolmRN$?G%IAtb;x0S`vBo2S8g)u1BwD?fQfSeqWlt;OTinm;$ zgaJB>Qe5)8Lvjfm|1U~M#+yJnv6%^&gOFU*t!ABxpnmSi%{# zjT9WI9zY&G+CH*K7C|eoTi$2;=4HM-^D`c8bX;y%ER`KdiJ@2U6BBT9vm{Kyc{!rx zN&?S%qHyOI_)_9j8PO39Q5}L^T%nk_G46DG0CG4kqKO{A(#CR-n!5KXyA+nU@#YSW zl2{y>6tE{?O!a7t-95T-hui>YIj_MCnr^uXUJh^6Sqqp<{HN{nW3Z!35}`b^Zm5$_ zoFj5*k96rD*M9@Xb`!Z)F7|(Qo%Acu5dwx}es?fW7`BMaSqU4!9}FF^k>etDbJYai zr)&hKou$upx~q4^E*+oHz5A05vK-y5!|51j^a++@J;wZF4zC)C;$ zD!;#UWhF{P7P;XdfuJNWH%P8LDICCl0tfUlB~iS7d8JaFzQ(dM0K9JQ(gPq3bZnC* zR5g=LA0Mkt1;sLea_S(_KoXz)t#jD8()W+#+7DgU5JDx%MYKH@wtuyaPW;jwE7qOb z-@Z{3(8cn<-9!FeTm1dmj50#TbZ-!%v?=Z+uQERZi#n@vC$|WSBAa zOue_@S{tpSRWET+{NLXi>njrZRSJwWrB|yGkE)XXvN{!$5l_B%Tv0m+`Y~3?)tRWj z`{;VOd7XcfvC!IeD4(}U;-}wL*AGMIWc<+_06YLD{5&EBAYXm;JogD1!s+XTJLhBL zIdnp?V;~!Tjq5|zqZk>hB<}J@&ToQ`qXyn6ADM8@9iKVC9D{=*U@o#mZk;;(4K@Cz zqk~`fTrYUPML>VUo@(}Hz)H`3hv}h7>>`n9vSi#TSD%8F*hC346w1c9Q(LpgpgZH# z1&=E?3lMT?*6EJ^s@?M`lG%}FXT8BVGEzMaJp|KqrH9Y^J$iYHs+ld657XTPIFF(Z zt4l^vES%3MDg)Ps&~lv9dvUQ;rMd;G)glXK0f0mxJ3<~e@cqR5a&+2__v`_KCV&xC z{B{58QBvsP_-(lyUYTwumu?$Oaxal)m z3}B;9p*TD0aMhLT;R^xIkJa1#>i!Nx_YKz=Tdnb-m^!%OS|d66K~kCg7x7=BPpMj4 z-Sgb43b;fm|0Ji@l+*i-Z+mIxyhUyg?H+f2G9JHr=SPMsC)VW2EqhK2XGA$+;zZ!z zcS~kK_sTXGxG)n4KZVxr6bsR7HGT2m@aRogR!nPcqN1(^(~x&WW#jR2u$h_A08ia`1-Odr!iAE%^b8 zulVy{KjX=6u&w7EOg0yZpptN4QI|j3BgpK#_&kB#5t4(Gd3O58%NIsY;kYuq)0?(# z!>cSL&o=2y{MV2j()+klRCg+D!eNp3wNaHpt5{G{-|uwHKm7 z8x2ik{^SMitiJm2*Otqq1--HP+1Qx%-gSu|D{BOi*fEPfLWOhED(cwP^T3Yt;-Hwe z=2!MNBn{KZ4saSaA@TY3(e`}wQ=8aWh24dvO&2p- zmr-vea!W``sP>%OvNb+k^v_l-j$hUi1Zeeq<|5afQmDmOimSk;bLr%nog70CCOTK= z3pB}FYLyP&52-E?KVGqzKsh~lH!B~3HGNJrrOfby2z)TWM@C#RAOjm40RWxJJ9z0^ zD9t_(Gm&e%*}q-gBCEC{_iGD^OELd<&x}tN7?qq(3cZ=<+H@5vUPTgtwn9CR72Vnu zM=KxJlwC1YVqF?89j%E!0dv<&5~k5y#j626=9?z{uCp-1+G;zcgY{4lgUv2W&4(Y# z2jCz!Wf}c)`88k;b!56&bo-WYwUZniiRZdhPe{pCz)t?K&4^XxdsWn==v()VRQVsq zm}deY9X+oF0bmIynXM9&fkh>)EeKQ8e^;gU6>eKgRvC9v&L~glOOGu)DF5+elzxY2 zDda7E+2-nhDNo+{=e%p^g{v-ua2@RSv*6LD;S*c$InPyF5~@6I*cDg;*9U=+F7TUg zMvEzaLQf33|NZ9FbaAc-=X#tL!J=dD9MVTu?)wNTF71-A3O8!kpUA%m)YB;Hwb7;>D~zw4>0a~&^7R(R~2l+hv^0(jya@`nNC zyG@dd7J+DYa|mbZ`H+WWk%xzM$V|GOLf}@~8#YCAb18{?4>=?`GwgBzd58$q!mZ=m z9bzu#(2MO=s+E_aKVLs+uxQpgs)DN@^|m(i@w+4H5BqLKIJMwv6T)+Dp*t` zs_8y=(K#y(^ldP!Bb$EzIafD)TW7~U8445!=-wgf_yEqKPD)deBN2!E8Vp97E=sD! zPIyx+l<0fvWZDp)Fv(#F;77k+-_qM?<4;S&GM$5%<>z#AP9J4$u zlOOG)h~6L-t5Mf-$(*(Wj1?4^+XXWuq7u-CPVgTkfwrv-G!KfK{1rQB?->lg4;x=iC}_HR6$ zB@(CGSc$w@Xs|d}`%weFVWl_KI?o;+3A*RNgD-yj^+da>G}>u1neW&|<_&^MXi>hIN*G z_g$S58=CxO{!EAjDz;W3=Dz?APdy#d>=;)+;dsm{Xmjp6WZ59})37Ht|ARHia&mLx z%o{*C#>DksjRJR!<*x;BY>_sT-xyOsG*`p%3u?Il#yY}3)-b%d$Ku_$<|7ZDzjmv& zq0AUnfL8?@SGPpk*~L6D=Ge#68-vIQTI_FxjWlQ88y59uOK+%~@`@g1&j!43I~RB< z?$Cn5`NIQbi2!41DC?P@_c*oGW4Tg3!a~XV-EM7o^YystHVcUn{HR#r$vqgpL3jfA zn(nI2Fa-nP>U1vK2Y}kA{FC3{(LJZ_$*`SR%yn}m>)7K{=1bjZaSY2d2kmXakL@t| z8kWcSQAy{2)&ZC70MuSA%+8!*zrbZ~V!KE$Zj6hqLj>VRq1}{_cra(#i)PONiurv{3308#d}R&Qu9H|)ynBL2y5^E}NBZx9C&j?d4rVEJMsdj#RnPla=G0b<|%v{6&+ zI3l>HCrNb*wY<3J44C%jd_8qq)sIQ?0=S(OsC#BW7UV2!)p|HXxQ{Uo_cgyubYNtt zKbRjaBsx$@vLI}wg0z{U)Ngjct)Bp8kwJ6vg~k@C#Z^INfVh<@*k;9h_eghNe9l=&I=MAnEYzmg*d`7KM&f)-iTz@QSS*Lk2;QOj zK$OqPJxFFzo-6_BZr!~&VLvAbDFmK8_hN?{mVE@XT8 zqM=ge%=C0JW(+=^nQc!7uxHZ5*Rh2OAP)Ho2}JOEK3f=Z-( z!)JbS|Fc);KG-bzJtm1}UHMd*Dyjb2*dAoJ<7?_RCpNagBT%$W@Nx8epx-qO|U9gpuxi=~|IkhaeBv-;t z6et7+Uz&g(%UMqnPlT3;Qb+(w3H5<|Vtfg~6q{I7lJr_W`CUnJy*%h&;lEM-{%Fbl z>A;k}mHQj=sYxZk0a4DDl9bYtm>;Ya0lk1&OYs?YBIP<+XWeehVZ^l=Fg&JV9%d07;gHocN2vIeyEfKh;tY_mZJRjUnF%zf?A02ek7yRi$x}<`XKy$a^<7bgZ~jlsifO|SI%vDaJkEu+)L8E zORn@(sNyIwQ+|czU9$Ph6?V*8sQ3Q1RC%Sw)BTeQQD{>3*I-fAV(F`UNz&AIqf2qz z01*0*nG&E)C41eXWF0RM&~V75R!O=Y@6%*j-00mahMxPmsZ{a>AjWu6b+1Raw%w?r zUAH<*x58X1(C*y`*+%+Rdy?#zXvE2`7u7nHu%Y$N=F45#lF+1_k0O_b9sw`?eN`+J zJF44vtZcA5|L3r#`AC(@+h|8HzwgUW|A_~yOoczI zvA~LCwho40f4?P;>}~lL!a{Bedu?I70uZVluYWGn&_0TkIa6~@9n~C#=fK8C-5b{y zPcO`b+a5J}{rTc`tp8to>3_5F!JxD&V!&^!M&@g!!D$N5pC|f**2-Vq6Ze}FWWR*w zxQd4G+A>@ve>wiVZF#+ehDLV0s>_1ah^RHzi9mM#d2nhO-+_F78_O$b{`88DR z3^em6#lu%8Sc>n)wRV$Ac!5UC2tn-kB=fZSre|f)>eJ_^JO%sdKqBF)!nyA{H-EV@ zd2D*b%;jxeHDY@zi+7n0HY-3OCUBt`Ks7lM7cPd9WxOC|9pEp>z7z}qP!MZq2ZR6gHS%9 zj573AZ1K%uS4kWk9(lfuT}6G_#LnEPf8LnETGDvi}6&f1_LlPlvpb914N zg86*P%cgHb5OVk;-B!!o194xvnm!~uh@m>*VK4B@Mt|&ZU*^$04WQx8N$un*+MSd>L)$( zyR{V-!OjxoD+Gd!S6?3{yy4K`&1k)XeCWC1Z#)pI$7sv1QMX{eW&cv~4IOZoA3HQj zG3#AFxU^^b;;|L)mKaON6blec-_x7;1#Yi)fA73xU+J__6CBIq>m<<$(hZZNsGkhK z*}%LhaVkWD2P_&V3O*&Cw0q0?klRPXkQn25(0tHlF)ktT)g zGUtEH@B2x0iTHs<<Mc1n5v;0+ zoZ77zRq{(vs7FAu*0})L*(CP#6tK^}j8CPLN_!J<-iV-DK!=kwyd&PD;Kp5SP?TUg zrTV`r>#OYE2+3sXVTU0L{R!Be+nGMrmSd|LVdf2#t|Kksu@K7RR$542hOl$yRH_Us}<)1qkyq07upO{^CFnV(fHzDc) z(ZJ+O>IiVW)tzfEpzm_ZV|hee4$Hsm4jtnGIDg5sYzkm_huBdSBq3!e+d6oBufct# z_l4q@UGo->z3S?gSNor`6)(sbhid@|*Lsb8~~cFevu}0fSQ@w z9A$S>4h0ugdXm%``*#^W&R?o*COQ7l_2qQE_c;2~66fgl^&^fiAy{>y#_wWkcTMV* z=P>8o2aV*)3ax|OHx&<=a_$E{jv$#?$b4?S+coojy!h_3T*aZAR&#w-O)U*U7sAx| zW$f2=XZ4Pmtzr%v#91DfhJr~?c0dsefBwdu0K;aA(zWFBT~RBF7An&@7!Nm@YC-ES zZPD>=I^|U)5AF$OT;tqood^q4#Ks)fhn#q5rqOdZub`6TY9Q&#Q67%u3EcWZfK7pd zl=sYZKVgG{;@KuVLWj+EDRASRiJ_aH<5R;0Pu~AjVIHY7q7--W9(f(|^YI29o9Y3) zBe4ib#!ENlPpVUT$0UCM{TXShD?*!NG6`&g$;WV<$~S>_7^LEmbwAVQ|dc2HnBIRXY4$_ z@luPWxK7VH=G}g2;Z#~NZTUEodOt}D|Dvl^w}bkwRf3f$q0C@yl74YnrqPZJ^XbB! zgZ+i^FJ9rl9xz_3f;?i$%V&V42wEv}v6pdR{)Nh<`kJ;~p=Q>}| zFKXOFi^uhy_kbC0b6Z7f#^%kK+{(GDSj(v8kBUr906Dmk=H5=tzzM5M?YQAR*Y{Oo z1u&BSCEG`@wkqeSNjVxf}xJTtd{LFZ{G`+o{mpb*TIxF2+@xVPwLa_ z4&8n|zc(WPY(&F>NHe-WrqlOiLFu=CpHVOH_G6vWdVdq+LF&R_&;8K2x}!z^S9%)2 zO~704uOL{5-)uC5I09hj{D!qM+&+uY<|BG14G4&obNKF#8%(*11=2nYN;B)$i(DT! zA{GEP1XVR&GSn4!K<*_UoNtxATR53*`1prEoFJ8@pYFrG-ZMvh-U62O-hMiTt#z$U*!QcF=`hr*_3t#Xqszf;gaL` z$vw1DB)nA-$_1IwJ)|UqYITTss!ddqQy%}%=qSjcHBDZL8vg_iqOvozSsuecv#=7R z#?D1~bL!S#AKECEg*Vqk;RL}-4_|hPhm60&G~`&X0bqX1O!56`*OnZUPqy-d{>G%S z)uyKStidRWdzd2m0F9)0vt{VfjH-A$Hceb~jZCDpSJf@;5&Iw;Eyv?@&8XVzd?;1u z8OcBvxK_D*JxS#K^O9Sa=;zsW--aZ>3MRIX(p$uKtpSDj%qA|p#gLfNObN>{&n5nv)3`_4sV-;zS9vi z#}SXnW8(Bn3}(*8pX>8bQt#%luj5HyRHhf+xWC0XR!#b9G`&c=e#^ik&NO3Cs#y8g zmeI3jqA8x{MTy4eFpQ%@44R6ekkv;Rb!Hl_n5|bpMyh|?*#r>w!7=oalNvLD^-fKa zbh)E;H%ouko%+fb6|O$-?v2DvH;lfh^r>*R+ReJ#wkJ*H_f5oN9urkeBO}8C0&#qZ z`>h^__%=?$F zuKQv?<_6tfepney(KmQKUjumldNbjM%fq3TuTa^>dTFr?iS97h?UzkjEFBzKzFgCz zFB_*87qM0M7S`Nkb4Gqup4ZLJdoAG^Wno1`7K&7!CGV4SLfgqtH8NEcTM~ug%HKmVP7jy-ijC*ePh1{0o z7k96qIy~WNOgO*Vsn(4LqARg8c)HtrV7V!qZ-#>C{`*T+kp)k*xJj1#5|z;*g+IPE zEdV%vY=*15VdDjEo$-2ik|&5G60t!MU@^?mn@^AP=7JiV9^EO2t#dCq3df)|-qDNx z9gmF{3}ZVzg(#&QM&11!4joLJkT; z#=X>SLn*yy)Yz+$X!XB5RE9xoocNeX+2cdnKzcreOjL}#K1ZsPIv=laMx@+M9?ipU zfX3ScGNom4Y8^n<0%Oe>MTD$_1ee*O>ea12SC#@EhAr*oG%{r~EZpkSj-9BjsWf5i zZnv<;re)ZBOA`)aOIYO^ERo+__T0)Ik9)Y@#dbym%yn)14oe}h5antm z!l+%ab@`0>$Oy?eeJbqC8rvuhu!BFge5m3@4`O zipv5kMYgroXzE*SeNto`9ii6OrpN}Ebop3f5gDP|?QCYejUo0b?Fx#mlo>QKJ+ z#s9Rg-96hsW>X0~NZtoqz6HM8Br-iv03K(!oqOKXCU*fyfR_q-&pX&ElL%xZ9dfZw zysJ(GjU6%2xjOA>5{`3WkCT7(Vfy|a_v*uCZeH#iwEU{9QTuB|@+w}cDwZiUuZcBR zM91M`$nyV}Kd}H0SXOhq@8*B>7eXff!JZc#7@i&+Fs1 zCLte@#p?inU%M3iwxpEA%Z&u{r+{u%a*7>rNg$~bZ-P~jU@h1>)My=pA+;Dgv_$gS zBEeyK>?L?Ip11677*?5^>;xbJAPzhFq;AGd3kEXH*uY{jBcfo62|#}uj_YL#R~qow zogbM`j66C?C-^IP1NMJgX`C+5P-VJPWmZw;eL87PIxoNZNnPw>LIiwHxLC&U_TFTk z$Rl~!vC$0tJ!W&1VZ#waW0lRr%m^P7?I!1}=_|0IAOba619nKPxuITb+0CP1v+GtN z+#J(rxGQROaF5NLdl#{CsVPpy1KJJ2QSpWCXRmybyLn(KzRqon_={$wPd9h_lk#^$^YxANIs8+xn_N4L$9zBS8VAd6)lL;6my?m8nq zkmhok@ni+god!P(CpF=t$T{T7Lh|j0vJyQ=a#kHfdLMNYaGZuajE$n;>7?H2Lv}ql zFO?1J_6nE&?n7@0u%^w1ZN-xI!MVEON&pYX9-7^@WB;WI@6&1~7cuYy9*%7^D;W1j zm7Daz%I75<+Y_5bSYtE^UO7Tq=tY@jl8H&>H?hiRN4J!tZ&?#$rV>?lkK}K{Q4HSb_yZLa?igsDO3jK& z-wybg4#*;V9S9R|b2pY*|T~Ti}UYKb+ihoN3=_-Q`czJ%7AMgDnz@}~VnxwQP?V-zd!wKHQ z+{@r$NtNw%-l?A~b2u$+RfED~E>SPu%W}R-GhUc91}CMKLZBj~Yd7hd_*SxKcW~bJ z*yRSYtah-s-{e*AVBhRu0k3eOR%SoY!*gvok*>ykpaW5_U49;xWgLs@GF?Fj#}W@K zJ2hQr9%rKsj8mGI_qHj~SxU`zUy;q(2v>d;_bX_u`;FouoddG)+V1w|F>(W$RcU!) z?##SE#%|p0`wYCW4$gENgdCc^D38~r{vHv{fn9-HxiG4)z~k~cQAjWV&6R;hnB}o= zqDkD73^RYJOBR^A<@XiT_hp1qmHYU%ZdXY?wUd8Y&TKvlM>=%5!w0*Z zlgCHG)vVJgqluIVZQE;7`V0w_yh5gZS~NSM#R*SbQlGdambr|)EE$t=4Hqt&`A{-_ z;_6XWS~UHLh^$u@xYMP1Y^!*kY7C{)_x5eO>YF50Y+?*Hu@igOHf5X9YVW1u&zA%! zfyO)3UB1s9_)5w_&Eprj2QJL(8if>dgNIP0T86b|jf}eV4oPFbr!2%v_KVl8yHB5i zynhIJwRJuL9ckX-?)18XKhxo2c{p>R+*5D+fy z7fLx3N^B8ne_)Hd{fc1jOWP)N?t(6!QSDMsHtcxq!x|1Z$cEKdC!TF%~mn7jI)feu<*> zjm>0EVDb%kV;(ID1`iT~DO}<*e^3@JCvE7&3o+A*Wh5xxO>n%MoXni8)*y*JO_=No z-9zENzQQq-lg!9PZaGB8&Loj`#iPT+|Hvg|o2TT*s)0~6t0o-_a&e?<>VF^gN|^FW z<(Yr9Ay17+@&%@msHG`}r=2w>JIV)(XDZ$X`0ik0pQ0g z3`F%FPWl>NcK`VO#+PSzv;H)s<-E$WJ56(EX*c6PF^g|knXOAf(S)!_sb}tqfmr+) zc$o+O zza7c=Y)))Oe9KH$m3+YU*|%MH^O<87F(al5-qNgn_4oy^~3 zKcjWXa^5jNsEE&&-XVZj^NdUXCDQ?b+#6p$a$Y{JQ1LmS;&T?HJrpvdQ28yOk~lI~ zv65AJs8BUDSNW^C>RVRTABF1q^9s_I>Y--GSLbe4_JW$rrFy3=?RaOpI=x2pD1T?( zq1f9M(Z}m}L^T?m((DqZP}jFnq7&$>e^FN>P=EX4iFr$Xj%F#{YjsolkZh#D3! zjUwRLIF6)s=I#BABXp)SE|aVKeXMoUVoTFk#h3DyJOzQxDIFE6~;X$nO_HIf}`7Y;Q(p+8M6WP^2S7Pqwm5XHDS- zgZBRS6g-{zXPtchomCM%6mnhCL1IM(WMNxfT(6r#1;Ol;VM>8;Oi+)=Lg&gw-`U%C zJ9fecHrZ3fyo^xl>iKMcb~Z6wzlcIV(Y(E4Aq~jVn|#@x#}81z_kO4A_HqWu`Rm^4 zf3JfZJX_7hS@m3W_O}G_7eyFD=UQI2=E#In#o6}hv9sypMt*mWJe=*3oay-%G^*CA zn-EIVZqe|wH3zgjkazjX6g{>ZHujEvG(LNXfny*q!sihH@4iq6s?GVvQmkLq>nIP_lb*BkNXejpn_8va`&2od3QroqHsh}~^TV{MMrmb!VeN5< z=-&PHksAhv`JZ_1ul~xpc}E+u{l3j{Y54{7*00~|aNh4exx8Z60K?o#nIhkqV!`It z?i2Qrym=}{mz&ZmJzed~@UE>l4|tIpWlGSx@{pt=0##+O4Dk**qBUfPGG_~DzSYOP zKk|2n2V}|%ps?h8H>VQ+fqZqGJ&ZL^C76AOf9z2_>&`E|wzAdSz>iL_ z?W2kOkH_vypAERCjfv+XT=x?QG-S8(lHNpUFJE*#%k6&lx%kcbB-ctXQ2?N-mjMG) zvMR+O^ExA`*c5`u#ou^ev-r4-ZyDu4xD2d1_rUl1X)oNfL#BBgup$QdKuI7I_rdGHa)0Fa^zf zmMkS4_cukXvd9z}puWqfa?RCLg1!_5&rb^OI3n_hhJj+yTH}M~lt-+7DLKHcaWzTL zt!X1I9sncH9&&5hi+a7+yg#aUv+-~`-o54b#*ll{#R=sBW7AJvY=`}|7Gv-=?(EOi zRNuj9R$Jt&a=(sryBlgkF_LO-N<72tCkcG_!R z!}YV4HM?Cil!2H$R&=;E$LZV_3z%#%W@A1`Ytw_b?K`UP1CkXdl%}nEtBWgrmeqF zgPUr3Va_WE*07^Ow`bUWQWyq=6#_0S+AqKT{Pgk5_wlcvoIkUvj|ZQK+3ep+W~Q`Q zn!FbR#`C&V_xlYyTVHaTGhM8>hb2Stq*@>XC5YSB20znv@)UK)g(9S8ko}Kt1|x+D zHd0<<0Tcm~rnbc@^rZ4=E4-)&N$iFe!{{lV^`po^hc|@n^Wb#$jURRLd}O?7sb6cC zvP==M-0I-~t4L~dQsbC=>~ASNe7cFqw*%g^6F~Y~X&nFwV`s8D+lJ~?=*{*hFDIKR zqa8mj14r`Jz?Cz&Impz=cL5d;Cjy!<>*%8GIi5V2#RPQN|Vrviq9 z9@VX01qle=>SKd`OVF3YE=!z_{v$z}z0cSiNf6VUAKmU$n3z;MR`X9l1D8RFKPX3$ zf(}CwP$;X!$|t2Q3jAX+qHaE$w4n51>8F&J*FxnQyQrW-V`U74=c@_*a`x~rIw>h| z>H(cU4S6V7>>%E%wM5BZST7a&`Q{VvP7XtCZ#u6iP=3Y%aLpuHtJ}LM8Ly?D!>j5d zx?1dYylM8B}&<+=HW`h{*ez{TChC^1IPTKu+mZztPb(omrX zJ)dfSx461JqhctPm~fB+0Qtio@HE9#GjA^ani)DOc$m{k$`%o-2BGHbmdlX;n6 zQT%;4Ze~igI|`01BjchJW?aDCV9F*(p5!HmY^re)P%uNTrojn^sdpU8D-!#qbL)51 zqe!{K>8+g6Gqz9=(aW!r>}qsr+-*yr^g~4A-MBeE=Ci)V;kN4Iq~cozKf|-Q7-n_j_XfJjr>T{O1T?D zHxHvrD8;e$$=eUzP?dbD1=cZ!d;4H-7ztRI9gfnr7)&HY$`u5d#-1}&EA7?Bhzl=s zf9LN|*Zgsv1Rr*mCDw^nMRRn*aFS3B#{LeRiXH#gh*jRu!#j6?U9p*MJn!J&n5R}BNhH7om_=2^A^ z2RI8?E9GbOlh3BF0opT3O`cf}+;;9@^1iO9_Eya=019INJj;2gO;jK8I`GpAS0~Ww&)l!F1Inb*g>wN8p+IuFhHeDQW z%ZHMyFOzV=aO8IzK|CR}mtSw%o_1d+J&b-9yDswVY}md1Y6u==f_ip7RTXkvk^E=p z`ZHME!=M{%RjIVy{%b68@=k(;NW0WGweUmD>oh-O-L2J0&ok7~33&5M$RFl6#L5m5{COqX7iu#W<2V4Kuv<}Bb9>yaW z#-|;2%_;19OcP5MNhA_NB?a=Y%~(@tzL(Uni&Qg}LLER}VxZ-C%ITCaJME}PPEl7e zyT^?}z9A;Q=_(wBg_dHWE#wIuf(czS@gL<9`eG8AW5`8kqJod3Sm6L9 z>Z-*I^rMgSX(JOGH>v+=6aq(na6mJNq#8V+IV4Fub>% z&+|8Y0kQ*_HV$0p0B>=_x;!A9s#?Lp!_SX%W@m{hQQsMB2XcOg=YEj4Se<1C;*$r| z`EUEbAT1Mx!)Z^f4X+ydnC6@;POhnQ(@llq`8wVJP~=7a)aL_m9$kc>FhaQb?UyD5 zNC7`alE;AtJ;Z>xvKSddA$bJKxfJTjRO&exGyz3|m=N$f0Leig!Hg;2FBceX7qESR zv*K~?7JjD20CTA~cNCb#&a?hzrdYEU6*J`XNawSAfE=(8(-gf8G)W$wdY-#@{vcl> zmD;PBx)lpKeZ)=)lcoo#IkM()XbDizXBk51SyOK3){uvFz2!M9;ewZ@Z5Ijw^B)N- zhd}{kND`N2Bi(bl>jX+ag<_vLYF}Mq+1xT&uMI$&KxT+9-I9m%S3_c|A^a)a2NVEv zd+6IU1TX4U6QS_BW$7Pz&tEL~`Pfnk)^{S&B;a(XJRHPBx6JcNS&3yuUJ9@f4iLo` znT!>UD8TcpX{0{T{y=53Zo|Wiv*l_)-u}>9tx{XvoSv+=CjnK*gNRqn<@%H5oQFVf zJjwVRGaLr}99R4$uG+JVS{cTwh=s^N%RUIe-;UAtp(vtI6n)jSZ@CNEctHD8l`<w>0E)@em{>ddnFE9d=C^t z){rp4mk%f*hmr5R`B-{_mEOQ;2a0;4%JysH2`I{ zIw)J+9G=X_7$96t>T7-7mQ5ILOq+s*rC@otx8cfQ&zL84tjI{qp8E8ScV@3u2caJV z>>4=HpzEXnX={+q1suXwcgwjrQ>4!O1tTz&B-fHm{-UuK3jYQ$CF7y|2CHY~c{77b z4!b}=s!Q&^t^&lB|7vVZ{1I0815UYIYL6rVD>Aqdnz91R`i3YoQl<3)q}Q#RGQPmx zV0~+`v<(1qGXQxo6J-S@px>K1VBnQ>Ug1C~gT?&Ydx7oSE$#M$Eg|bITs8pVlo0Pw zSEE$m)L@g#5V6V6ngNC+vByG;>DmG|VHe!q{9}~#PYh4SD7PF$fS6E4QlD80s~Kx3 zLqo0Te0^Lz> zkFUrcBA15)IL4HL&fo>79=4h;+LrN z=_4V&NXR@tR=R`yAysceIrX$T;2Jmh5f-9Y?TO3grx~YhKY-@!47}NC`$`!|yxk#_ zM=Ye*XV|1HEmNur+^J8v8f%3Q@W2O@fdIn;Qa^JKApYYGs=9>B52E9YWZV#66a+H{ zBFGPg55lB3hCjL3<*@@y_4upvoazJ*Iy_pFE_ToVMaLD?ydBO-Y~iULZ5%fiZqzVfYCUx!ssvJv!SAPj+o zwF9h(2Wf&3e$}Ji=R*%$Te(-v6j1}d++>^OW53G>+^n*^+w6 zM*fJpljn@_wIL`DNS|UxJy9t73b^QHkJxb2TuMKi8AzG{euN=otsyZ)5=pe9CjCq% z&Jrd#ctE$CCwS3dR=;jLg~>wpX)4FbMfuMn#sID{kS2=-7u6sL6_n?Fjt<>*RBQ9Z2~3~AdL zdfhUbhlR}3n_6kj-aun{4mFR3rbP~$XHa0dnhv(ZIRI?Fc4UwP*qPSGou5cYItI*Y z`}j1tHGzAs*_G>@0l}W7{}b9H$^#;GYPU{owq=Xf@5D{MD6iuI&S1aq;K+Wglh0O)1Q99c0@Cfyg!BJ7(lb<2ipLs_|?DUUIBRG21yMOU#ylAc9-tuv~cZ= z2;|O-RU&+=SB-Lu^((Kwf_}u4W5+0tQ!2@9Xljs(Av2kG|G-br7EodcATqLK_eo;g zpv%%Af0DIM<@%Q!-}uHsnD*5@tM7c`oE^(l6gD(v2iI+LCuWxOSlx`67UqVizjN(v zxL2lowaW$?BB+wSXa1;8H~hTfLFE$#+o-159iy&FA%b?*5N5)3@uQoLxv0GQZSdZv zhKh6AUSk#~B0gwq(D}#fcD5KSZMGwjF*#{Uyb>mcDn!@n!c%B{hj1f zrPvE|+0Smf=V80ENul$jyX$GPb$eAUf8lV{*QTUmJN-RQAPX0X$~9Y3(s9VnSQ|AE z`Wv%NzOqMzNf--C^4V>oQX&PzBSlES6)FcprUw*Nl9Zngq}C2-X{C^ShYI0Rt15dx zmf*rkd!-5stXydh;^08k&ud0M&)OkBu#~jp5aQT+z;JF{EuUahO+XR$+ zcXsLM#pw}hfA_1H*h~(?)k`_V+1gb|c@K>L7?eDZ)siiT1c zaLPZv##gt|4?NLSS^Rtd1hRWtOLYe1KJ%-jw*7swVu0ZKz8yn^M}0bDzrZZnVZe3RFpG&)5wya(Pkbt56e#G8o^DV^M z4LZ<+stm7@GQ*Q=UzXyDh(zL_3wq*Tz%tqQ(WX4SdlM~;2Ta3nKDLaGpkNTQVkS!j z0N~dQ3&=z1Wn7ws-PYxdLuq2zENt{YkFV=oCDY&9&ra}ZzY@17OShQhH+U_7?FmKK z*mom5I+Es^<I{oK@+X^F9qC3&Ii{Oxj!`Ul?%HMj3p+w>$=luYedM2lFQ z6Jkc9O|$7^uP(O8h*>209-2(G{4TWo2=~vuW;JtQ(;dq|NwqL@xK_i(Y_V8&`<`G` zinRL%yVv3O@W+ofI<=uF^KX_fd z(Ma?tGyTxOb)IhLUaog_6TO`8r#$t<@>_lubKm2oW}8d^8-bn8tZHX~^P-T!q+0;>8mqvNuLp|%Rq93R{o(T* zKIi1VA4TWW2LV4Kb?1#-S&j3t#v(5<_V;hglzV@EF}~7C4#m`qlR*J)x=TVEMx(`VLRd#Ie+=RUrF z=7{%owI~+ZOtT10klm1T)YOXlyj7ejz_OD2E?3g2{Qb1oW;TfVeRqc0+olcs!lb#4 zoQgXadKL3eTeK>@gqszKnJTItQ+=vpx2@lQiYi~PCwX(=+DZ8dxtINbtfes7OiyB* zG%rebKjb3U>SqyvDah*=)$hxr@34kgTP(}Xf{KZOjTVZCnMS(sa zV8%6SZwptSX&lp%_=uhC-_E(`cSFkOoqzHeNZeQbnZ*O9RKtlCfLZ+H|dy$uUYQSCGT&QR30Sm z=-opShUd4)HL-j@&a_BH`eVbvE6fLeeMlDq?C)oLH{`tuP0(^5C4}43=m>1}m*{jQ(3gD)2K*8+3WtTKFd=MAtd2Y+`%0xp+EIDk; zsZUD91BR)y;}#l&Fj9Mxi13@x_@F`o>}T5AnkH$_)w77z9#FW_1VnHu5)wM5ts7;M zo}bPSQqj>hE2>Q|HhUzZ^H>+tZ1OTa;+v=|#lQ{Jcv4Hj9nN6+mS6oKcvz^0vZhUn zd1yHI4y*_L#HPal83s|nJ4jdf8@M<;&%#!(OPd=*@A!%6xG#4w6_pxz7n$bFh<=y< za%Sjf`99~6Snyr(yM#shW-^RUbu~V9Pqi^K#*|<8N=Ab z47wR+%){fY3nWKF>kz96hRSnnuLVC7#%ju*c0aj~E6UZ0>7?~%?oqPmNkK=1LqU%< zWyub^xEUELu?bJu7g>2iM{nbw7P<^h(Z#xTt8p&DNGZS*G0zBSZZt|$X&IeBEBrFn z{k|*lJ*Q$}zwXOdFA8rAoyd0gDm<+LPVQ1ZQv5PU=KEmXYuC*`knkl450cVI85Wie=4Pc8C(d;R`neaQJl=7u-hAl4BRZ8?=M5XbPh2D6pH`nlEEC%|%K z+q6Ytx}eCX!ZrBEd@JkpyQRd+K;<6~k1S=|dwpsWgI(-JB4(N_WZbfHoULgU=O!4R z)>Z_&y2PK);%84Bo7*znuL~@!=05!}671$}_nWM~5gjnS=(g25zqpem+xCNc-~0Q$ zuNND>AOHMu4~1AQlU(=fpbo)CT(?@GboA@u_=}CvvRb7p_UpM3;*sEJwZ``SlyKW7 zi5Q@72WvJ4OHLiqs%;1`F2q0-(^I1tV>;OmLi?on^EhoT)fk%5PNZGq9(YLG*X(MD z;0cn-mx@O=t&vm!)Bf5a^et_uwWhok{BliNBPu=_*W*- zJlZMv*6HFUfHT-AHiO&Fa z`3>Xrp=pfv`PVMpu8OtyFmyp@5vg^9lBL|Ci_`pOjnc2Km(oWmCp`FhO@ z)j$*=;+YdEDx-b=pFL=GEzJv!q#B_lw;CgZ{lLFYl@~T6S=GUg){y!O6t8F};Y=S%U#RZ(>{qLRA0ez$XYX9OtH z$vUbF5D7&@i`L?K%+&RV)h#8#hEfsF08xgmLc5BTItgGDhMW-@aql!*Z%X}cP>Jz1~TbK-{B@#_lxomh1gg3zz7;R z?SG6l1I-~01lcDG8t#{xv)etm(;ip}Y2X1FCMCjMFxqaDR2vZ0N=L3<4SAFSHiSh# z2JqiukFkh}HpYMrn4@@hG_j)E;S1M1=*c~Uie6LVbWS1muoyb?t6MMHj}OXWGvOgl z{rEX8oOM*+q}F34?KIJWHJyH#d4Dhlh|6eoK*T&IYDd9hfWc0Y^o;}b$Y={>j9VRP zKuIKevn`2T=eekEejRJNm9{@Kx!ftlfLTjhUs*GP5VonwP!j2R3VE7AnvkuTtfX5_ zrI)Ltt1a4BNFP%aq#GHb&bAqSj~Uz;p(jpH9_BJ|dnW={qF1w^*Ivg^3+{bSg{zCu z#ic~0n31>9llvarYQ7w757O`7dHzvKugF`slM1L_0(}cK)KcNl)>jpw5D!??lOMfzm!o`BAZ`SFtGE6aCByX{ z79F!NI`b=bYj{1uaBGJ_=Mti;Pky5e|Jf$naBpYyCJU(Xn8YkW5C7BfNXh6}-{_Z> z(TR)E?;xYo1f#QTqw{j3i&mq{VWU3_Mt^sVh?hnHY7FpSNP_a!a$rdBW5`@FkYEgX zB8DOd1FgVNwqdCLq=f!coduEsh5@3P00zKs5F;r1f2EoK%Vj?O-(BW^qs;$sna_W2 z{u5>XetNQhcKqYy*Y4TT))meC>uBdnXFmRKI`hH)*2#aoG%xJ_SpA#hd?hj$wsjJkYg(G> zy5E;IeyC}vud1uByKAu36GwWLO z3yZ@m8vnyF|4VAle~Zt&BsjF%#v~xyefyRvU|@9jS}$QPXjcfvZaF3 zJ-mF~JbeDeH1m5VJa+fFl9!!bJsq8~kDOd>9h|NIO*Y?q_{jXe-CavtGjr>Ism-Rh zt#!@q3{CIl$w^)@%{Ds5x<+@k^lz)_n4tg3G%KR@{;$!jtbGMEOUSEV0nPu>nT5rb z{{b}rPo4RHqnWSNn`i!B)|$&kvGw|E(^&roG=D%IYY$nN;EbJW_*U+VH9t1$VE{Y6t! zWA2}kBUS&UE+5XQsN2@N#+b*j ze$f~fktdCDfCRt1qcqQPoS-%fkI>^&5R}5Bws4x5sNrD&jM7IB{yY?;Ks}pkoS@TM zqTI%{FJ^8G>ci5cTfQlZ{Vt~%xsRcwiK#>mJ|@W>@$Ln5(ug%ChUDxn?0Lmwb^hm& z0h1KDk7joCnZh*ohVk+rwl-etR1owZQUL{F{vlOL`s_ zk1Ihqw(%*$!{l#JRodN-h9p9R&x3}KjmP-0QNr6LY8=tLl9}K}W0zs_*>5Os6(Xqv z8WHFJRZUVLeIAv)RFRYn@#WNX_b1q~*aQkn&P$j&Wr1>ZQv~jk4yQGMj77#O zCj`n5Iw^G|g(Mvmya&+VIf5{StrN|+@gx;P#$4sVtfngLfEoXr$D{(3lypL1Mdv z3vcjL91p{1Wm6PcX7ypCPfp5D=9Crb4(8jy7nnRu{5))kiboYwKI}rwq5qr?FPKEV zW*!{w0s|)yi==1q6EVZf%CIT2hT)TM8PB&*Q7&%l;$LYrm{N;Lcv}4p=oHo6ioiO` zepV9bL4gzw^yu)9BY}eQXmDos**<|UM%pzX`65QL-KY*U3t5T9^qf+xbE=0lD5PPO ziwt2ANXDsRbm@`EAH5&BlpoYBA1H{TzcY0UaV6ApUS1ySy;6ERdb�DareM6nqA@ct&o0H-gJ@JX%O+F4?9I_ zWV5k)m=v$=Hf&iPgO9@^NoR7`)+551ZYH`|%nJ(2RwsD;BsRoU`lP*uB zAB`gZWv^kt&*$j%yRj&pL6fYX>2MFyYs-QuV2X42-x19KBwqDwgZh z8THIM%HGs3R`@b7`n35d=OCe2>ATLSfVrdG)8S&3-vh)?A?HVL0MsQYi0)Vz>oK0( zphT5va4bsUI1iRsqJCX>JkIj?E%Qi;rtIK&QowOOH+8ADmhMDa)^UNLL8(*` zKor$>q|P@Ai6TK*!ASwDWJ1iY3?g0+>K#=l7b$vdmR^kDFGJvd95b)#I+SzATSQXa zknw=pGk3p}@z-4WKa|~PP?KM~`1=q-2qA>fJ0$epd(k9>UIamkg3_BPy;+k0As|So zQbY+IL8K{FrPlxf0YOm#0Rd3~Q4vcH&;IRa&vVXy&zW;(?pMi+OeUFolC`eS`d)4l z(lkse$MfFx<2V z64BIu!d;<5^&atM;XdQT@LJV+@AV2@zf$pQ;0uy9ed;pJ+uX-tRcnoYDS&VFjC6ww z@}d7b%PVsrCSg15ym~0+e1Oak4@vo{5dmE2IgM9bab*G1s#^9~!z|jFED)E4_YH2P zpEcN4aN(t8P`0S6pKKbq$vlHT&k-1uDWs#xnzTyLIuT0dD_+3)#u+`b(v(V=^#d!} zw|kJ{`A*7bhs|u{RtI%s`EK~1*3*qjb9F8^D)J)fxUE2=Xr|EuBIN73&iWC{AKF49 zNs9K4kQQ7#kBbi}*_qlNuHVncuX_#ytpaUgbv-IYldbPw zwg=W;WQXrFLWyGX;c^p9CF$aOZ>UJs=!x1UQZQ#E_pgC?TqBNrqx_0mn{#Gg7rpSi zVq(|gQotlIf`9qE?#uY_{3#C9aGqTste<2VR(jU+!KpIKECbNVM4vK!d1*?DPk%93x0u*?45SyZmwV>VbSGZ{?1 zWzwF%*SQwmyTk>W?y>igf}!3L>Wh))QkDmudmdVv(pj{|{`;rDN!qKnph%Qg=rq@9 z;T40SI7a&rOJ!EkcaDJ;k0?DX@5|t~LUnHk%|{Nf&rWdf(>1Qi9GJgB^L7`H~EQ`>0G(PuU)A^^!X<1ACnoEcV zo4Z0UX($T&S%ZLz;gecroUf$YVoL=ECfT@B44?3e)jUj?eP7;!e*1eYB&R^=HL3(N zSv|}yATDY1Wg9ao5J9B)YNEEm=ec|$EIIwuw#3O35AGPtHscR~5tlG0TW&ekl>MNM z*fW?FJg+1!y!3;pS!TpWK|MqppBJJMifcDj19E-!cf58RY1yfozl&0b>TA3 zhz1H<39Cb9I80;a>T5#Kbq#A)u4`@6!V3s7mN>+X9+zT2#FIRs_dWh`7B?T3`w~BB zvuH5yV?07N@gTPwH!GEZd+dH|>}x&ps}AxcgvQ1)jC1(1IOP1xB*gRBlN5Env^aey z87I`f2M;RQ$t|Tqo5YDpiEU3g8SNvY=^8bXLfo{vPPcrDKl5Ja|5tT+K{f;sS{t8M z-3q=~>U0CC$G(zQ|L^KDTO1^%^xxIxL#HPF^r86lk%IKG_H^1p`s86cT`;497#uhN zltgCeK2EEO1{>isg#B5Aw7BehVD{*YKpaqe7eu3g-Y(oW>t&`;tjz`jEQ0xNE}@G^z(W`5NdIBe(seQ33#Z)1xGTgku|9kTcnvVhd9Jx_XYOInS3%`# zJ90>Vfa$F%47R9z;%5Jf1^_XD+*yE%kbd;@g)I8pou7gOf5t>BaQ6fmXuiON4!4H6i%$UOLMdRyKxl_p;eg}~ISt54| z3(eP|u>mR@jfDn8pusNaQBBTyjH>h~?0l_ml@;4@*%y-R6|sR}C*h6U_t?qH7g#j( z?*Tb7&}{2~t44dU-%{Kl1pBXL_z@aj;ZVrtt&-;hNyCRvqc}3cp&xo+6A9S~gQ6=) z?l%BKgJ#e>tK+&eP)J=sdG`*`JJZCsh-HPnF%B;Kf+NGvJTdY3ottt-6oQz%S_`8< z5neOC+KHxsf*vS|4jJ3!tXIFACug4HE0_GW)UnX@ph+N??hM8PwF*nXOkjgrLFX~` zs!1Fr>b$JVh07o*Ho{wd~O{*1iyMDjBuZYdOy;T zjS)_ILWQq{v(=*D4gTiWi=5}^9NFsd=t!vO6G37j!u0{tU06jrO>$Weaa$4LbtL{} z6ei;pz|vdH7EyIe8__k2cqUZcEcbwws+SW94}Dx6a0M~x?yL`%z}E=s?}A9eiU!MB za~eP?hazyVXyQ@bSW{X55kJ4R2`^W~tHL0F#x;<|S=`<~>zJ{K5HAO7GW0vfs$ zkXog{9kR&LQY1OjeD9Nx_$ikAD=$R~=yl3j!he}`pE+>^cjRYNq2yi2)GlX?HUbsN zK`v$M>UCjz0D+xt1UEgzF#O?NbmA>k8A}%RC>mr@+5qBWL6^bn!>c|&Q0pRaTt%UL ztZpbb<$rh82T?7|I&>z(;os1lZEGi+56kf z{3SY8*vHoS!W|ICR}JKsTf+L<5d`4OGW=%`T%%Phx7gV(96F8g2zESPCF<0b>@02V zOn7|F!<+fNFfRO}*ppvY?c+|(4&6gnyZQW5ROmpg5!VAcNhbnY`HM3LT>-`b{xt)* z44(x6fm}@W3^e?}3*P1hRGbXEi_KaLa|F852df|QNHa+fccJBh6X^uDHuvw*Q z5C-rF$=R^WnoVclP>T7v48@m1_e)_Pil6mv#lZHSndAvqAtVg}f{H>8#l@L%Tp$d+ zn}_gRiHki^=*>R+S4{c z0yONxlf8h~!r@&#gF)Be&`^nXgm0!g$LHf7Z#3-FV(Iod4&5B!ZfR-Bjv6n`X}$D1 z5R-69qo%rbWOjPw>QMHh7Y4S4Typh~vJJ-mvP!;_$GCU9kNP)?(hF21O zowr2Tm;!`F?yk`KJUrkGfP^ZN(+3Nv25>%DX02X^KlK_pE7d0k+ z3Gqh#1aLlstSen>u9Pwc(RUFjWH~Z3#o;Pm?4!*0OJ9iE7p8xKG zI)_2E#HC$M74nb<`ph5vGa8!dXDN@aSQWw+u!Ap0(jjYf^z}~&3>pIFy8UznR`K)n z=d4CGYI_J}m&Mu$o!e7^8Sl`5J=4*ySu^W|me7k~cyW zARg@g=B$0A_RFC@aw6_~`qa_ysUrXlOojegeu{lsA+{Hu$bJ09V`C;jF~yF8O;0!p zDXN&NNnF=i#|2)dH%t3a5}ti!T6NkB?$`=tNrd2gm&K`XKv}Fg;ZR06d(QF{GnYBn za%1i;#4|&Nj^wNZK$QMG+^T!~rHONjKDr6uOw8fy+kp<;ojP2C&?({vKg$XXW<{8m zQ;z3DrkP@Q*_b0BV&RUpSwa{p{9Qdl5LK+hH9Oo&PeH8!BiKKwSAU;Y{cO%A$;FAK zaY>#){I1Jo?5@*}k8}cX9)#;KX93&1;NS2q1*BJ-49w;m3Tvw|qN?=xp}Si)0MX4p zdMW(-@gNRBzv~Ucg0c>a01+o(_bCm0e8O!j3dyB#(hg#1AFPO>+z+-z9xa`e25o*q zl-xM}U%zxiY^m4NF-XI-ib8~}@C#f*6!$>n36y}pHdlY{Snjd8h_AG^e#A&3vY#Si z9oPit66oj3pnKcO)b>|v%khMP;G|E?sP(ajr^kC?GY;Hwc#efO+nvS*6~bqw%FjUq zpMl=%HD24Im|X;mRrBKZ^G2cF*gOr5k5dC*EHsKF)2#s#qR$$*whXuVDw#9X*{+B< zPL>E({e-;n5Xc2^d@S{TuZ&1gkN!~#A7C`Tq!+qG>rlJhhm&_jCW#Ph5_lxcN8@ zyLg{F9!yCekf;Zwy-92*qAwT{T>mW{_)Uyyx8fdmkkoNWog?Z4Z^(T+j!ObbwH61> zq$;YmrRtaK{Vw%A3ei73GLYP#m)Spy@#G2pfTHfk?Q$x@@5WDY?ObL}LEIK&+OB!$ zV9UXFgU;GGm0e_6aNrFOvyyPn5_|1Uo#%!>WO@(M_zC1Xi`a=!M%_Ji9|1xz@zcTc z2zUVP{$I9IW$F(l@AY1I=<_Xbmx32K5af~HOCQ$skszl?g0aK1GN+CA`q zO}?V!u6QY%9F=2U5h}i{nM~gT-nawkwOvLNSvdZyx{M`ph`~Mf9geHZ@JqbLx|dgK z2^ruaMaZXe48^Iy#3#sG(lUkN#)S+=Z1A4AGn8TDh}h7I7f@7O(~#>q^?bd!|>@_AT9oG=iNEXg>}f0usg!9+9DS1+;u`7ui<<-9ER>QLy#$SXk2EVF zOd@RyQn5%}fwxu3xzqcfWR}x;CdtjWNkAk$EU`@U&|Xsqa;1zl zz-{S~xyb#H0f<=KT9e)r%i_d4VIO^HM&E(VuTWcgR%zYw~C%`ci>_=Hi_$%HD=S}v_z}g<+&9Goi9`zJ}gia7d^K?H3gM%DI^wd^{n1@ z4ft8=EO}cmFF!DroOD{}M4E3=UU5JEKCwqxLD)hS`c5Zg!65kR1yZ49VIE0%D~1t4 zy3&0q)$phMNf1!DRwf_T5z_R-w{t7(o_KM<=^LbiQW)m7v%U@x%8W=#{ z*fFz7b^T#OxS>4RYG9n_>b(7n@9s@DB>C4|oI$a`{mJNX(mbhIWQlpR`M27-!A|gvR7pQ);APks|8^m~-6?g?w z?`X^)U1*nDEjST0B#$0x99J*DrnDoFYX5?1vuO$`hQB2P2A&k;=HzDf9nT%`h4Ee~ zOZje%^)oaj*Na6coC-pP)Tkq%vLJqZdnu1eN=6VMOK1vliq~Nw9TOCR55P&igim9V z{Fs=7E5xE(dr?`r6z!{m?|D~h8rnZipSWn_k-dXR(mT?)4cam%+DDN!_UV*6*%D{q zj{O$0xRc?K^D^abqjj5?jqjmXG@(7CHlvi>>UvIg!Njp@WIys!_yRmccyaXjz7sME2LEZ-vc=fH!hVI zL0;*0w7}r(k@RHQT*<@eO|-6%BVi!>gvE%I*@xO`l6qA9cVUdB!L|)1Ju61)6HWgP z5P~k9t?ZobRS2JEFPb^fz6J3Io<9=0=08(;;!QA?-C4qcu32-x_mt>~!_)k>2bH50 zK@tw7Yyl2h+P&x%_1oKp)95qh_HPumx)rDLH52*fl_u03+9w(#hl(#HUz8pd%4F4$ zQl^#W1ixj2wqMx@w`20Wz|z$hP9X}tY&UN$Wh$NV@=9mqitadlFQn_&@HQaws+3}T zVdw#0q_c`0LQ{CLZUA-b=iMDIr#hNb_=vWQ*@~6bN8Zv%ElP`w<)xTK_PR1~^@Q6H zFxrEs`iJfaQarkNz@{m>I=Z-t1rTBfh=2HDRWWQ4`07*1IU~d4>k~nmus-qZOF_CNwpO^6F)krTY{#RNVLK;sU%%qU>q=SWooH@#qem>t{YD@RR_tAl?u z{^95&$%%GwsXeJr@r2wy_ZxW~kT7Bf-@nc-^16zDxsT!b`IeONioC8R!tY~5+jMcO zV0FS|3_Rk__|-na=(WkZeC9k0{tttyN2^|{2aDoQ7dH4`3qxqph~~a+m%yPr9!lHy zoZfuA^{eCXmDN^*+!E+s6n0_#VZ^F?>dqT*JiF_knCI6;2(KZWIdCzbL*GR~b>X zwH3K4E9;$|_)+XYyFX@Q(Y{-CirP2arm z{2EE+Y4m(42j={A-PRTJpA-3YRe|4s(rzAH6-Pl1U%n~)sCRW*G3b%WM*KD3mwCIl%=>Ps&{L7};3X(#Aupat?QSBQ0 zQfN?X&+S_MZJ`tQqD(T4p69ziUq8ppB3-?&^yKkq54&xvg+3{yha_;VH`})p;U{!- z_32_=(WWmrco`#}i{aZ55Unu!a88tomy?I4Pw-MBu`$0ZmT<;nJ4H^yb59~$vA-k1 z?)VnytbuTM-|Z$$TQF$EDJkn$uNuyjW{PD5j6c=(C|tN&tE2p+0ojMk=_q_rc3`St z5c)(nx?kLhr8VvOXt`m;FH;pQ{fHi;kLU@{U98sv4j|`Wh$e@Rh{w`<%k+oLL4yv_Lt)CC6+h86 z9f>33++Mb1J})qYm;6eKtQbXBq717FO4(3`uT~g-K1X&0SsXcJsV50LiIRiR!-+u% z?>-icHrbAzND@p;sYui~N=m7)WW=ltpYE_c-7&I1I&ylt|Kvgca}1NEU{|vK2*J`a z5kE{q;PYqk-gqla&}iX7=k1RcDMG_P9W7%0z;UxfmwEBx2>j)Pp<-?8B`B*D&Abdb zRw_Dn+1UEU;fOX=VXU^o>Oj=KJMp^{w3OGn=D<+4tYE;Y_jVF0#)}kAHgk{0Rof2L zNOSOw9=qA9C%?zaD#p9l(rahOP3nxTrN^HgXgmYi_G(vHdX;Nw(gyu#L(#P10a0!w zW~74l3`!dtXc!-$O{~!-4`@?&(cjTu{|XsrHO<{2l9>0R<{eWr(~-Rksk5(Gr5 zow(6qcXf24qF`d-z>eX=W2drh^!(Sv>cPZ}_GBY=lHImE`mE zBpY}k+-F$OhbI{UXwuhoM^X(5V4OUWHuQo5(nF_zD}7=m$QmukdT-74q9`P^HA`0o z5+m)HD-BWMg+v7LCGU>*180))C(jC!9e5x-8g+J}5N3Z!qEdTKsf`$NHlmNZ}y6B9PebbiGRQccr;4?g0aT5^%aOX_rp4q|cxUwq9W4 zPX%wIC9&V~CXKBKmZQRid4j{dkjiM8Ao~DKEN+DKyIfyDeyPD0>L+L2AarM*zk ziZ7T>ib=aD01AW>ov%|9*y z=vxeV2UnaVBr+%|ea@wlZ>g+~T zft;M1OI<$G6z@hP5ABSaN65PbEIUhgkamQgFkv7SZ)g?LrW!`k+uE7{f4=zyDyFtX5@8>uM{K;J(GBNc2?ociym-OWkEtRHP__z3yEiL>rVwqzf2xE?VoW*-J3LVG;<&FLSDs@h+pV4WseAQ%IyK4>0ya2og(1D zby~0X8t2j!-1R$O668I{a5j%|*|I$>+;b3yG^E~+3|59b%;4ruew|uCIO{&mu%=|tQLL7! zL}J5-6c7YBJ?6R_qkuOq^I1M$=lt$)uI!`Y1!LQC%e)I|eec9IWeGvx)%uE2+J#`l z32`X+^IW;LB#r5_t>f}}jK0iwf3M*+C5Fs^iO;Ek7vu*fX;U%ei9c+_Uy_7fuN3a( zpQ+XR$@OfinNgp-(&9n3GElBqX7uqh_BB8f)qeTB_(sJayLPs%yjB^g=y9A^93qup zErT~bNfeLw@&0A$bn;Tt@f|v*=ENEF_{GNZ9fhRxsVRYY&twYdK2C`dLPS5t`EZL* z@LwcBZ?Ep*;Z6<~>XHyZFsQYW`_PDF5zm59g>O>$Y}He4n2}wXPP*$Sni^ z37)^=hnK)V)+=C70_R4&a@^cej3M8~AV@i2sPCmYPb1@t5L{Bg_FZfX#P|1>k0NXi$o*3;-R#YrSl8 z^wz=}gh5*0k|o=nM*+N)csu=0LIbrQfE*yfSpnedU=(1)FL!d>8j*a5w522HsSU(K zKliY&4MdP#lWIU-^x&-X!Fx;q33IAh{L=_LvGxRH6QM>BTuiJ1d0U1QG)M#R+xy9@ zCPWdY5a%TQ#mf#pgqkGp&5#sXCOPEB^&9HE#P_tETLiwduKr|ed2r*w_N`}rykmZ_ zdlHsCpcA{?0d92S@_@Y15}~HqS{+;j+i?QodrzosyddcClZRcBN6wE}yOB`%$Kx)% zra*uR7UdUk;*|^}X8B^CC|M68c4&6V9*Ac&D9E174jxS9x3d5EIDkZNx=<;*^^*x7 zHmXRk%fq&Vouk2CO(Dh;A&C$%fcYouzv6(yz^082?bDlu2_%*lUltAa$X&-|NJ;MG zCH~R3pW%QQUB%AOFH5rI!_S}N_%FuT2Sq|l_=dvtBL~h3mt$wjWFQ+BhRsYbFWun( z7|`=cO1L*1TGAD}YZ8fjsHvd!3cuD+0iFtuGi-H#-=0r$>`T8I{ESg({DH#68Ib}K)NS}2!m^o1jQ2=Cw#4U3WYCwCxfJLNlr zJQBOI75j6y!(X1TR+^4r{juK{F|Z+2E@V+Ew;2%(d@eclNe2IQJOWoLB!y(9V)ZKI z?thhv#El7+OY4o{HluZ4NLuhVXk$7_c%$1Yt`|j zaeqHB`rW=2L&Sk5%Nu#W{5O}GYozNJl!Nx8MAA6P4{ZA~h6!lqBP?aYFb}!#?P6ev zMZIdqJqhFqSwjRlj5ThX$;?ZzJV5Z^U2TNt73!DI2MKDi7S5{0{1Q5XVJCeW-k*<~ zVj8?224;HM;R;Df2u}%8KgTFv-pIHYbuBK?VkarCEpof?BB;no=mfczMAR@R|4lxC zF@6*>4Zc&9+~^uC^QudK`OVc;*g-TY?oJFXE8&#_<>PSyYb_zMX1Q46kUtK$AQ`HZ z1h+kNYP8{!{zyEZ#Ff}MoML=jO?6kQCz(&3)%py?34Zb7muR`oAk&ivaRT2b-NTtA zFHas<+!L8ixWAot%?cP0b>Mx78#cb+m6BpX9v7TX+!T(vAI1OZ_@xPPtiMWru}lFI zf|>Z;(Wxf@<@eR>9w=Vh7avU8>@8830jLAhAVivRg6rZfGp z=G_;dgcO5hlbv#X?&b$ZoJIJQoJzrkI6h2NuHN@Jy{PB4Om-)$N}pd}-5LrC0~6#1 zt1sM`MP0F&jpbea9wrL9jL$R#027|Y`jd(-A0IdRqgc+(D;G%g@M3(QV);_|SB=%o zG5$wMq53PIIPAuk{3+(9He1!OL0mY>z}7wf$8WB=1ffpVUJa0WwC<*K~A ze4qYR`M(b=!)%^eexxp-?OZsU=A ztXkOLZZma@X(Q#U(lzSe*;eZBTsVD3`OM{m$>6_BC-6*AxAX28kPZ#cwhG4iGZYSy zNnDC9^AHSQ;#)6n`y@z;SZs|e0DU}0sZF3%qtXX^rka#x=n@Zqo;+@12} z0HA`cgN62k5*;?KHUTg+LtUXdGN7mQjk`?xS`xVDR+TB`}Zca^?ho?$FbDu-?m*#8qp; zyx^Jacvtl20Ee*jUwKQ|i+6Zgw9aZJ+Bn0g#S}$xv({88*veMZHB%NR*lKovYx`}( zJ!=ulOQC~?VC7gvd%bA63RAtvi%A_Dcl8cBBFm;cf4pHQn0SJn<0aF}gjIaoH3oxD z!hZC{tJ$ir+>%IF?;;8*~u9)kNuRkPPXP^npsCm+vA{Hc~{(7r#&(btqdsQPd znQC__G)iQNTe3TC8FFeyhzXT6-I*fjE4awSA_qo66h%=Gsra0a*ct((&-$TE{L!_jI3x*sH{w>3a=kZa%Xw_9r3i;|Uur6JNK!fvH#%`!3q6BR*3IeDIg1mc zK~gsOiK&t5iK4PEAouWmA~5B$E2(LGVy5K8pL1baXegcn^|5>&x~%nTd#GLitMLS+ zFBLa)PSUhi2&s{1!@^W1|9F)($^)yl$nY6r!)O7&3H9?7Tl;fIly=boY=BA_R3s=| zvJ>r?)?1Wc63OCBwL?sER z%+yXs|21PK^OOga^13JG0L5*(b+G4=HQCoOn8GrNHR*ZH*dyr#8Vzof@sHxj9Cdc6TG-5Rf- zUYn$793Y>M@v7Ko|7Ctss-ZT)TFoqo zkhnm^w|mD6^mKbBn&~l!Z&T>=NH&+oQz#0T&6sv(Y4FRimqa<=`nmr8r>_lkh!gDc z0)xzU5TX@qVSJ$g)fLW?opW~$)Tx6S2T)shfn$=KZEl2wOJ?dyYZ6*gBj;o{?c|!l z0r=FhB*)yFgJo@YMG4Ja1Ch7~!T}PDmT^-eInatu;Sjtd)KyY@ORkd1&7g6DWE(tLJDxQ4!5uoJ9Vd0GdUvb~EFfx$mVp3Ks2;X8%UeVI!{_MI7dgcsMPIc9rLJ6In@KmW7(qV=Ak7W2B6M9nkr&jOw%JW4yoPbO>A?f6~{ zw4gYTaEIzuCp3j5YYA*O+sgDZq@IpMsv3H+dwff|D`{NpFll<8DfxI~M)r&Kp?xUt z`-kVmiVbeE9WSCdJh?C+kcWj%wUyP!y?8^@ygz#B*A1>f<)=Fz)ybq?6NUKG z_m^M4wYk;B7-%`0+1+Qkfmq%3HaLnQe<|>8OKar(q%%FIX`GR;7a}A(a{do)Y43oX zu5+pUqCQUgb=19{kT;F2>gEckxToO7pX2mT>}Nhgo4+p!DZcSK3_PR_~uV*>hLpyP)iVM}ZPZsj-eNPFh(u zVYn;DTjIAJej4D%_awZR|FKjMY!ZI`Xb8+BX z%rc7)4~JkWF1!?y#8-XnJmi8J3tB9w zv}0xI*B=JbwbY(vJ}Ki+oV(fOOjD0Cf_mx962}Q|7jhP$bD--dk{^rG&B99sc`a2E zg|4l*Es(deK)>q6go)mWw`j47KJu)$qCQawKQEHTa(m~k4cYPAC)6%m67mVps)MJk zvNuXqQc5#P1%025K10*a=RRTL-L+oP@@a{hE?OnO?JmVGPa55; zusb^{OM7SPYk)mt&{8~*ni z*Rk#W=K?A>*9C30d2t|9%WWB-dlvgL7fc=CroSt(UX?DQL?OOJV_DgN6PC*D3{z8m znB@qImU5*lgeaFAfDVuixi>7Go+l!h_eTb&Lr#?7?K@RfbxCqsip;E;!R)7+#AV!X zJdkMfRyKmaIzn77Qnor$RW3@mI_iX6w0U*3yOqvHlRB8vRqtjb=-|W#f(Mg z20}bBaJ7aY9&LuKk-K_%@Ji(1RUa0!Lb>bn)z{z3-PowU@mcO>pZJ^H`_8{VxIk)L z5b`d9n}qBOH&x{mb!!q&$S0ZCB-zU+yVN9~mk+pY(_zUXDVpcfjn$_m8sQSZ$_y&B zf;-&YTz&&d0rz{6FqZjD*M3IGFf#5-X`BSIU6YZY_;i&1@dPe$n1U*5y zGQ(#O$X2UUnc??@_V=1)>g3t}GL1;TcVu@(vw`G4AOwi=HTg9C#?og68s51b&>bzcBH3L%t z-LXzlYcx%bWYImi;Fx>g!a3wLJ>#sdBDXsiKZ|_Mn#3QzK{a(JN@Q}drB?I0R@tm` zXi%yB#~2{-2@t4t(Dy_$aer|@N_opPTASeFof# zgVv|1ig_%%VlC_YYvgg3wL`C}dtTkU{nuZwKsl$DS;Y<4Qc@oaRW@zqHeEUn2#c|G%w_kH_n`oFR7;>*>Sga7G$=U@IW-uLZ)dEce!Xa7ll zx9Fq)Nq*l=bR2u%#aY_??9|-!*y2>zvHG2z?EgpoPEQQZ(K`O|zSE=KWAurMu|e8s z@7Qq9G5H-F==n$e{!98k>*#;l+}qvSF*$wAe;*EwJ%83&@qF-D{Z@DPHFP~aR=k59 z50C9{M_cogC(ZN+Y5&0A#$)*VxcM0V{-^paudV+F_!gEoWVSxTKX`nr;$cihb4*1O zwe;S-lDl_GsFOKf$KLnOo&22K-2cJ8X}8j!5qr1^F8*TY8aF)IIr>J#n z&2+hCj-uySYwe3_XqX0X=gh>zx;7-{&Di6*myf*qSGzmwiZBm-UYIXER(_3s5b}QP zAN5Q8{HnyPF&Bdg{RS1cZEsxZ7rn*h9Oy8m5-#=bdhvP%mFL`g{%F)K`j8Sqs<**S z_Oeh{V)ZyviTu<`8(|A#9@1{Tx=t(Rd#3ni{?T;z$9#>d#P;^R_am2HIRu5EtP@Xj z6d93YmA;VH^Yyij5K{efKqYp@no;;v&nuz(0_o?~qk2PHQf92}pFjKa3wDw-)MWQD z_JHe*9OY`<#EZMu=r^TwX^zTBy0HS=Ca>?|nV^;A!QRI(4?^(TZQMJMmYwGYZ#ngZ zrS@7eW=*h#7RjQZkGRTKB1gpOB@xe z`|6BX<~U%)Aru;;fQWa0&?jSiRaTob-Mq#BCCnc~~Mp_n^=Fb?Yy+c)u{(x~?Ps^beeBb`~2x=9zp{cJsP=yYTtU|;CJx6m} zs%i%;E?tMu)}#YFB=2Ixpt*s#QO((h=0&mtB-5{4+RB8UCm$Q`x-p$ejb-6G$I~*7 zKIc$AAX!z9UYL3H2<;B_mS%1X0IcG_e(4;l|v(w6kUV zyJ`T5G2&R0#Ab8n?oPM`W?bmqPw%Edk4{uz`&p8&H=@(7bUF6EJ{p+UE)bNiF^!Nq zcxW^Cpol9YP>u1m#dNvwN9BByz~%c6q0@J#>rk(*(%Yv83>}Mr7=7oqM@?o;PguT* z-9tx>SA@J5DH;Ey9jXVappe==cb?Z(e#1RDub6v;MjA_8iKea%bc&%bPDiC0lRKC0T$)r*NUmrCYq|K~T2INxDTZ^z1HC zkX8!T8^Mt4%ecR=JF{9?_HpMo3WgRgYc>S*@ptYfH;kJ@ye<2MU(r3Ec2VJRBmGC( za-zDYS#=l(^Zk;-dt^)7GVVJg1G0vDsSfF7yw#S2if8xI+-PO|Z6kxKSN3js!O8`P zEr&FV{-u7)g2~gAgr}E_ey|)ie6@Ewo>ngYV`TWm(OxDVR)J)-8o>(hQ^>Xz zk^-Y6=7#%Ol=KQ|Ijd3Yv-{Zvv8@n7n< zBkNwFEWwH@U~g@1b5Gs;s#(O6>Cgu*NawWZBl$t4ialP>S0rSdujQtTdjI)nYg*5Q z&N~J%p?WdWDF{c5&bqv9pyJ?NaZw2ON=%AgMV7P^LkZga6(?YTK3piA*AY;}hQJrfOieuEwj~r{~-X_?+ z0heV))~{-P?HSpdA=$SG_9w7-rYJd6?b6M|glfiuF@Uq(p(DQhH>lu(8fqFr+Q<=m-d4~Pt|kxz>zpnWvdkKWO$S zI1%Lo?#B5AtQ!*$VJ@Z-V2ssIpL{OQ5c0j;!N36hw%M`Gd}N6XL@m>rlHd{7D(rYU zJ>Rim8j=$PG#fFhurLXyn0kUnSNz7AE%^!pT_k2Q4e0%SiSk$YE+Bgg(b5fskxs6frsXPxxJQ#+o6D~U;O$>Jq< zbzfiQ$QVD?qfW)QYh1ta4QT%@LESB=nGbbOwmTi_8!xLTXcf3v3MEIb4FCxZ=t&uP zJvh=}x;yWJWH(|%vO+VDD-?6DjuLjAWHmP^hi$+1UW)S)Lr84$PCo=|o7UPkoasA) zJ-1=;z2g1Tyk3ZbF{}HqsC@l5pN*94rH(?l2}#5?9E^g6Z*UMu&fUsF^2 z!}s+7(hS7%NDoDICo9-e3+~6B8G|eapSl@>7%C{^M-at>(H7497q1AxE^jM(^xm$) zIw2LVOlhWh``bQW6Wel2R&0*Y?XB(OrQI!7vesbFw>RUv7A%a>95<$yUE*6&f1I*- z&D_$XU9j`=WTil$lwo)O2qbIB=paJalXLB9uF}XOp{0D0RF|czd7GM@+dBo}vVxJH z5c*G~$zd8xD5dL`V=!*EoSH=bqaqEth^5`^;@@lX42iLl8zuYsZM$|-j>9TrpZ1Gh z|K8A_>X?k1{Ce-#?_)RANl&pqC=>a!X?d!1=Fa3nmC>Iqhs@5|>Kpyq-QKNXmdtZ) zliwPy{`pwz2a@Ws|K42uXD4W?LgF{&`;)FepTaY{mOj}3=zRU>bG*PUcJ+23=h~ky z=0CA8fZB-h8bL}GfB^@4CHpVqcMGmvW6f)XJvY6ls#?>lDbGmu?_S{ucO!GSw=z%kqZ)h>y z9EwXYaAdY_yaw~WZrpp5Wrf86KonrctDx{FG&m%`OK!z+Gw51d0+25hD9;EYZJ3K+ z|E#2(oOlhw+JX7-17DAsgljm9kT)@hpQE=)dmU?{W6lwtOw5r*Jj6t)Mkt*n*sI7R zF79#$IRg09;Z>z6 zK_;2X@Caa5Vhaxbj0t{un)IFPn)&igmc1*cBYavFDLup_mL_%vw?=<|(CHfG>~=2m zZ?c*(%I6@=+W-!ZcGyXEPJ#oVh<<|&bLw4S8Vez<<={eImOvim{C8?Xd=R2JUI0nI z3e>pW;f7EuJ%`lN)X(Ou(NsRY5UN5I8xkagr-^)Mj_q*fi3Qjc5>c{{&g%`|<4t0v zW;Ee09#ScMeM~Rp5YIm-b#B7HCL*9^;yqHy8jilqj!fg>suB4Jm3Wxr9PuiJGa7AI zxyxyT269m0%MN?*zJDnN=;K4W$Sp`Ie?39!_ACSkn3FFa!62kx@cX_1=}v=Y^dSibJzOI z%9_Y3_f>)GNh#k>!2MtYo2$#vzfJ580lZ8O;Qx!X`-*DvZ`5@idLZo$y%UNGNS7+b z(7T3?H0ezg1f(cvf|O7V9Z>`X0qISoN-s(=fCAFHfFQk!X7PRhx%QrOuDK5O*kj}@ z$w5YPkT>~V&z%HQz3RSY5 zc^61SPNg&abtR`PCdQVRHq`TN5>`bB8|968b$~3Ql`Oi52QU(|s3a)=V9n?WPr3=0 ztxsr3XjyI*;-_f!t42!1Xa!$PMwJoDjELmhj1=m zIC$ZK{4RD2!iDw?E6Asc_<9jV)+R> zumcogZU^ih{kmF!7pccsU{xlWSokSSo#zKY#CDm(}KjHA#upcel&b=f%4QI8kPet zZnGbZ(OU*#D0f3|winX(!=9e$u9 zs_Hw4U|zBfA1H;x2eO}(5)IIlN~j!Ge2&#G1l?n&ed-Rv0TloercZs>njsI z!CuB7>d+Zf3v`DhdqN-q@dZR%c8a)uB)5vJ{FWmS;{!V*AciFt@&UU#mV<|Z=( zI|@30>550^GRNfdcad?P6jSAvqxpf8qtLv>M9IX`CUmrGY#r$@Etr3EPxhHiOu@!0kF&!Z38IrSx}Eh=n$qa^0r_XxbDEY#sHv(u3l3ht5Hy zhffK3zJvIH0+*uUg6B11s9KR`Xm49j|2(Zi6Eu?uZw`rhJ&BZy1Goq@PfI(wFgn{z z@KKx(Ee;vO%n)zi*O5b}c#s{w+ee`ax$bLRVnJKMi7N*B#3D&CpUJ{15~q9n#Rx!$YqEk5RCnSi}zueOQzV|i4)*`P0G0+9MC}N zkk8Fa7b!9-*M*yIW_(5LO|Vf52myj#A%o{fBN=m>a^Rgs!$J>0otUmRtVV1p%cW2i z?JQt2PWSsf%P@+O73niw4JV(b*Rb!4p4YX$r($aeoaql|9I*LUUSauG9wT8dgQU|e zh4TAoJgsLknjg_LRC^!_1Wk8xsg6H!rm%WYpqC4x3hB!Z4^M1!b1)*SZG)dcsp`(! z=?QepSi~j)TJ=5Qrw?M4Kv$*kMZSInx-h}zFcI42sFz3+X#>`k9x)syLn(!MzBWr+w2>)d0NRBm z(_1D}HDu}B0=geDekeu=H$g?wh{@1)-wXubG2JSL+`4Z@ByoZqIm=kp8!F(bmrIs9 z12JSw4|E9Iz6>Oz7=L0Q+bz%zs!JO=bnj8+uwC|F=q#iW=p_-MwGSP`J|X+$yNPKh z-D_{UGDTPQ^ps^bg3oaMs91yT|!;;=+L8Xodvp#&L}1k5W-@>u>^vagLcUt9^=NnpHur5 zg&3@yk$8=~H$?BG{q=D^_>Ia&UO6NG{O|xkm-}`0{Rr^%H6ZD?(2q(2RLSZ-mP973 z#U#x26A(ureoQ6eTR#m61V^|>4^d9B53gTUUEWRsM;cJZI0xBoSbHosPj`ql?QBrv zLb!8NNvN7E!;IS>*ZPU@NMHE=a7676)>|0$d1zfK0kFvFZ3_fePJ+RbA)iB>+b~@n zD7~$$Ynf#YYL|gp_$NBaHOgJ`z?~g^^x|a|K=A&rUQK}9lI&Q5XZ^Trjt zxFwfMA&a1k+@yg1)+pGkzkw)YI<)t_>_JBcH+~H>wF5{i3a6l4vBW3cWwc@TuuoY} zUgRL25}pX!!{

DQNgIntWZG=7a!ES3>mVtdsqE*JzO-pF@Zod@Ge$_9*{Ih8N_8 z0BHW&9UOA@u z3S4{V_x&yUj%_hLA8K99Ur?37d>alAzEHmaF9c`A$bC>b(5D{5Bx=`{VYH-`z@_|z zl1)kgbdhHbckD6v4hD&m;ltTXRt+*ytry79}RFqB3fL%%&t4rtmJ0W<%qZEE7dFJ)h>hPuO6AZ-pac1?PJ8dt~e|q*iqKDj&YTv z&gaixD$e>6kfV@lbSRtUt|K9IZnf&?u%y#xi_{R^^WAqkH)JeKskyAAd&~KarLKhs z9e9qFA@_W^e&>-=M0mMkR5mU}dd;?c3b^EZJ;rmc`%@TF{`-mV9Q{0aw*)teVWCiv z=zZPdG_F>7JLVg=iu+_)+=1`F>Fwri&VIdI>dn+dev<&U)L8ZPx+1J*iS`e>md>AnK=yuWQsDs?h1KSIVui!8QBfIS<1UfkL% zdcek9r-V=Jo7dC(M6trVrmjiOpk*L4?(FyC<=>6@W)~?&!D6KXhP58q<2Vm`MEW}c z2}eruh+FEUz`eX0^>G36FTz55{Qa6&R{DB9{+>M_;e7tJ*5t)No{mb7yx?b(@oFQN z7q=gs>p#cczsA&_=P2{*IxZk~tDo4H$5iWefE0Y$HZ)pe;nb9}Z%I&jOhMx!N4NjI zTMAZ6bV*5+ZI-K9Ir_*{ym539B}DgSwCW(;Gko5^d}tduH#nx<`UHu$3))^8i;$bw zp}+G~$nQsmbo%$*sOMCrji10^6n}kiN~~y1 zL792s@8_s%x!xWiSVsn5@l}5&vL@YVJa~)ek?-${l3kUM-S}tL&VJ?#iIVNT6&LbXA!x~e zJK2>dZB16Q@J8GDq+1U}yqOphNVxX{F9@k@t=<7_%2 zImu?V<#B~PN1rL=o5$&dC2KP4F(`?zcxbG=rm*>NOqALp6Nw2f>PYj5bscRgnA$Bi zdzGGj2@gA}jB+V*MCc1TadsbT2AX-X{c6jQuNTxF!((_EUzt*#%J&I<#K(mXj75Zoo*g2Hn(z%DW8pgd}sW0p=OY_j)F0k@{YI z3j)u;6|L{-CEiNAykV4icTlhYAg(`0G(uru)BQf%D|LR!Z(;f_vdO4-*0w)i(O&m4 zB>CAE5VK?kI}GjxjJ|ZkR$Y`4pe4`1kLMH-@ey#k9Gp z97f-Id>@wDCE|ADcuYCA**HhAm`n*VDQ7K|aHq@qo!`)befEk(F%)i^WKpGmG|9erYA@*>CQ7TIBe`g1e5 z)y`LYlC-BWtibrK?6(&Zn#4=3w5El0wMh_|o7vnIg6AXOFpG>I+{C_43-?mS{rP4~yx4SrYk^;fv;de_M5{*L3NI6$CM@ zBKFr?Nv3s?d>c|78{}_GHD=CrV*-ud zNnCy!-!s>r3gtxERy=*5Y(^gC#syQsd+;_VGg``NH-RSa0Cd`|e@0Xo<#(``tn z-dp4ka-+l-X|F@;x^f#5BJM!h#WtR?_u6R1NbbRImQ$2pqxRLw*Auu-4D+HiBJECz zEq1w}tN1nii^HGA5qMdI%5-mn-%}bxkUaTt_S0%~ju)qpc)>t^Y2OPL3d{Gujxks4 zdJ=iwtho5F@frk3X?fO!Vvy}s(jX!g-~zG{5E=G@`+H{6GhMAErT3n#y|B<+^CDBm4-P8&Np-70e# z@w63>AJ>Y1SP^lde)oqVtD*q|Dh!*>ELUKu1^%xoYNlPib)vpE$OcpozPe{IHMQ9k z=cavj&v$8UeC2+|t>KpY0ne7NZ~V=Kyzt@-b}F15Xb5alSGyPL_Veo>>Yz5#@7tz0 z{4-{MyR~X6Zn@wW9gIyu+EQer-+4rRP`NOk*1N^Ke6#3sng+7=K(*cHAdiKSFxijj zIFBVTIp=AHpERolBtfKZnettP&83@wqL|Zj^7Rr;bIh1asgviE7nXSb2Yd1PoOeV5 z9=L>?sbuz_E>R$(B)vXba!e@kj_PO@+wcNr(`q~m^Y1^gU0e&6a`HOvU;lE=_nmcy zqv!nZSdQt+V(q|cN97;hxm1fz!{?m5!aCqVnlM`&mV(pD=(iMW1t6RB2bDggb4X2p z&@~C#=?7>&eR+Jp6&%ZlqS9V|_t2j(Ezh5reXMFA4vdR;!XEbMNb`x4fJBPbqvZ3D z_I-Uf#i*Vg+65(@ox6|2oSlxDBo$;t#DFdub>3x=&0S?jvHE&Xwmlsc-i3=fir(}S zTev}#F#D6|_BNB=RZ`qm@rP z!N>ae$%~I}C!S-9>LH3n!8wg5g){=cGF)tVLwF|PxBNXwZeu=r`LSyAss{py2A=~o#%SW_QBjgeLJjM zE2H~od-okB2nfsM%F6mwNYy@H2-Jox(Tz6K=y4l}NvljxDbftum3B8MPOD5y+39}# zPRdK*U0Qv73MlfaZkzccpU6)Gm4>xVp%Tv)OdfcyVv>5WuoqGNjP*QSCti9HIO6z z`|~pi{jihI_xbU9^>z2I_1}Nie?kwjmxsAxvzn6XW*VaBAlC@f#(L_IJgW2`>psQM(`b7WX0&`(3lV(xR zliy)ZAI%;y0wM3I(l2w4A?s;)q5e zqx1#9`t~=sMUsvT!do=by>>xViYY#pVdSCUg9XLdO3KWyU;b#s&CADcCNlF|-a60e ziXxOUgn;$kF)|)sK!S0*%goMB$>d5uynC{%seK7Qr>tuSuQ@TMWnZBk*KgGrzgX>XxY=^ zuVtnB_5K28@!Xg(cvM~)cJp5G4a0AY!6ulA{$B?va+UAX7BJQ@dHVQNxj_m88D?>S zn1K6cIYW>u(=O@i&0i#*L**xjyEg<9T!{VQudc#fh{<IxeaMCoV zIW_O0jI~@hx9xuIXZFoAb%3m0@BJc?H^Rcd%>3?5|3@XpOGQK{NsEGgQ^d@8hcop^ zX)$ha{P1MV1!LhlF-FqFeR%0$iPMj9e484TW#NjVroxnH&uI9XrA66N4;e(yloszL zo8lnlK9aW=lwc9cj7ckO7EJXvqTfSpslO?~#*`Q*)i_M=S?)@F|M|*b%U@UxtrdUB znB2`hW5cLG{QlBI-%eTK&RfRUw$#R~LvQX~Qq5vaHX9nnnpZN_=XKwFYgYXJl_kH( z`z&Q74*aD>;8vlPzVp|~TPu^tO7SPA#S+PwS{bYIty=xi2vCzvud00J;Fpml)ljLQp^N}W_`+^&Kf!SftthFMbO;jmYvB+YYc|WFQYli zCtP#B58I8{Y56+Z_tl{ot@RCm*b=`KdgtWQtPA+tD8O$$8S&75CJGg$+>9qu^?2Aa z?!e~EyODclY4!vf%{ALFRJ{e3Qg$bi?k1i++TQ(OuH%wzSkAZ6HY>MAs)3i0iKSqe zo&D0zygidWGt!~r!3-*3mYo~#($ZT%Zg=Sy4DoR+#r=Dxqn%J1452l_$&6qZoJg!n zJN>pewlhz{$2+DNb00@&EhqzsUlS#!!adN~D$71LS2#lD`;&)+yPTY4V0#C9M|Tb$pt)|yN~ zQP;^NyaF%%#+FMcO{Lf`O$aW3OkAP)n=o?j8uflPKnxjF&ZA0L zfAQMmvpelBXTr!Uw>i*SBhxU|JD$g6(_fbDnb&_rxkly&#MjHD%J^=$$GDrn?IB4v9}ifui&R8Y#l_1hF&^$X*E(>&s%gZf}*mU)sgJqM}k zL6pzV7Gw)tq=>n$gNdK#qWU|?WWPZ&bN}QTN#+`t`Z{HY;dX+&YKI~oD(W6qk8~-T zR*qiiO9)dE4Bsp7R!48E>x657A`Sz#HQd8b(zZ_vw$JLk&u)T^f*^m6uG}_Tqq!Nq zLk)fSB+URCt*dSn2Kt4woO{M<+;cxsP5#1DQ?(-_9Z=MQGcRNBF|5lvMf{x~PRrlF zJHqo8-xSWt`H4b{=_v?9 z!l4{}8BxK626vxN3FsYB{otm6Km|yB+q1 zJV}Kyn!%twO2;IgxU(Y|Zdc@Ag2ZcK?)Gx}b8RhdeVU5hD zFTx``z-A4%q7&ZU&25a`p)J8l-PpG`T?1V_ctZakaOBSupgnwj#8ShAu!wsiMqvp)YH_B1XmNax5Kgt0<=YlM1_qHl3IjcRshnA0s{)an z+12b5yL0Ye2ITRygmC}yi|+~4&u*MZ?Qmay3k`mL68zzKtdD}$j5_YdP{N1cus+;9 z%<)}RaI##GZq7-pecH?5h&OU)Z)jk;?x(@&l;b(4MoT$}52qLCR*D$>@Ho=%_%s{w z$U!aQZDD|^eLU-B>bI|DY$74W7LQAggTv;|vgh#e7HLzR?%kM2m0uzXNM1FV$HiB0 zC32@~H{w4;J&waa%56{$z#ezo2Uk7~Cfeg1HzT$`zE2v9`B?bKk`p1#6{8kj^=^gyYt~h)o;N2mW(|3*_X3X^zj##0FtHPVLLAkx|xcaGOp+O zNpD4*19YK&Y3N1VG4|Md z{mfF%eOtV8_XaLY?NjgaX~lW63VW>W^7j$=w39?U_5?1}uVJH=?A_epgkIjfVahZ4*sZlmS*rreX{`u$n{Y|4e{ z;^~E~q~nc7ww7;rmwEm=Z@A~eCHUK>$6VoPbMk$!yCr|o_QxW9wJyB}B@Zg5#%shC zycVYV#?#Hby-6xh8t2#+iEK|i&6bs=Egx;H1fm}2Y813T24BBWzxEFg81+boD`4Fj zubOxzj;w?82s@(OkZQdGU2_l*vIR37XQ zj+F2@6RIlOboZ2-2}<#_Ae%ia)q(YBvy@e-(~dkUIxy73$MNLf&U^ zLr43xRzidKNAslEx44IIY)0WN(!Gid0ta8v-V~gp->dd-%9lXjwkP@x+Q>|tUl%2U zRB-QXUn7iEQ&|MLk#t9$O7ZWX4<~=5_~yZu`EDFZ890(% zzT}o6jj-#;9ddqrPJeJdGzm-fN30rV=^yJ!?`8CCF_m#Vv@-mJZAwRMK8$k!MMWl& zOQ26pdD&hWc_f(u^DFA)(&|xD@=tl;?9Rykw-R4_8i(X~U*w_z7ZNbwW6bMQht=MS zF>mH$#;IN9qjS;x)z8P;DX0}m^z?O7;%9epyWB+O^4KGUpR-d7YRT)#>l(+;y+0v& zTU1goVNFkR*#+`IiiJq)4;x38#-F|smx_23}o+tK9XrO;W zsV`hF=_ZJ9C)i@nrUn1y|{6j3k z0%;4)4dANlr_O>}Wkm^rA^ZYwgQ9dpKEyS!b;t4B;}Hje198>0_zFwvuC&CMq=Qq|KX*SEQrJFlgC8AbudD z)J)$52vG`l&>5B{nT19BsgwHc8i6&@aQ1miylTI&g{_)nPCvL8qb`MTn(!-s^5?2O z#np*+`nt+UWf4b)l8J7qx~haw5oi9Z-#;1GRj0LxxLzyy{x8(audD7d2eSI2hD7+c z3)x_%n7<`Nyf3>X>g9BG>ibAtU0sXleZQ*{_0hGW&8hv~OY}B#VtF6j*~;%HmrSon zeP|d874y%#IeF`*FD$9xP&*Fz^Hwc&FrK4(cJEfYs)@4ZvJ%puMwOR-Fa8m zFmZJnj?AfehzxUelt*7T?0yFA`XYV8!?sJDpwMlO)+$J3srp@#X%zS3o;hVFQcvx= zE%rAg-9uhpY*T_JVwA+%68SZ(>C&RO4PP@fSc6gQJE7m{02J+=kypVxw1{Ujc4QWn z?{&J3<2XS>0tpr(Y~}s1)dx$)b5BWWL{3$B%|8~QblzWys+q%OK)pq52ft;o z*xX-9C15p3$Z~J{*2N#}AufwkRN2SeXBk86JZK^jPhx2m}IWoWDM2A*)t=P=i6gNJ~>J*8v94?45Cp4@%j*ThSI z2OQIKFFEe+^eAu~)UND%Cq+ZO%th$5Q$Z~0xp?0ADCUmBgmsb`Ry~vMzqr=#-T%$C{v*=(f8$z<2fr2% zwifoc7B3==`#)#@;adM=p>gm3!nHOQzO2s=A53>I{#agIn*ArwxHv!YV~)5y_ig-t z$}?Vs8UMT3`mcG$3$C?1);TxUIs2_+_Upy1{UXmeJK8!u@?Wghf6FsYe`(t6$@~Ar zwFW+4w@Q{#ozdePX?T3^{v zS3O(c{r-LR{~KxiKdn|#@jq7Ud2P!D)C$Qj{|9Pa(5?TlTCZ|v(^Pwt-T&cQDXFRd zInNjy7Z)27`;XX)ijKJmGnV1*wmXUZXS#JEwgLl#F2t7ei+8t^@(p9NFY=5U5t;H& z{zGheUx+Oq|9d|Emwe-_y@UTRT+8kM;abKPb|UWBVokX$Nr``~mbaE6#?;o(*h=q~ z<%QU~h%{>a8*Qom+ij^_xGiovVoByMeQ)yr*=dyb+nD}TQ}`tt{p^2t8UwHE{ab8d^7L97{ENTg zFMj3u53$umP51NRn3}5dXt8a7UD;IJ7IYPPf}EAR4Sd;6ax-)g@okC1~P%^&Tpr67HML^$&6@z}GJp&Kz8$tEk9Hlk6`3_-8EUUxHc$o0jG~V@Yz# z^nBjoI|-uF`jrjR6&0|NkM2XPy&dFp`Ub5M3hjw!ho*L_yYc_(G;+JVRHfP*vDMfW zsLgq1BXfm_ZO*724j*{vZmBxgz{so4{x@GcOt7HH@m7DCsg-IpEPT$Q>NI^yJxPf2 zyAxe^&~R)MvX<-CwQ~36L>;(HnyM(BvqO-qETeuR^}-6#jT-g|liaNI{ab==q|j;x zjH-`tiN-+);|?gxUsOt5^P}!RAis_A4e-ss?0!x3bj078TG%}%S;T?xLcW34Q5El+ z?{dqFTiQO4#VUfs77{9r%y|~D;ZdkEo4<};)Cf+FufkBhg%;E31xYT1A+

EeZHVZUXnDi_HDJl9bVDs%*I$# zE7-V>oCz}gmi%;MvvKnx*iyk-HO~81YA}zxTwa;BsJ@wSmvCP?8p77Xj(i0~QpimF z>VV#gkkEfc*CqPC=*1}JdS~vGYbR&mxmmHWOFDznlhtr>@ldYt%NV3LWwi}=uSkuR zePi;T-fmkg#_Oj*Y-0Ki-lSKV{DvjOL9(Zj2WU>cl$&>Zi~2DR{X<@d-z?qA4##W) zxoU)spZ+|Ya8AGX@S)kuvZG0_nyX$@KE0yH)BfZ4j%VbepWU%JUnFfE&tYlAPUbJf z*2x0?O8LoRoZLmUo1iUrx}0Kh|8yn8t^9QLRp77FA30HCXKVTC_s`ag3d_$nNETf`n}yoBYwWq#o~Rw+jphnd~ZN*`+T3ME&k`=tA+QU z!wI*FKS$Gn+kcMdqs0H7ET>Psc&yaw1LA zXLl;qZdJ22E~NN_N#>cMCNaDDk{_U#Bey*eQ4(gUVXRdGF+b%1Op4ew7z889Kf?l7V^YKG7o z{xyP5R7C?%UX@HwYh1Rff#J=4=kNnN#uH6Q#9lJMQ`3&XgKe*HnltK9!NU6FI=tdx z(S`z-q;%~v9wd`X#?n(t(w`eqK5yy#W)rm39hR|dT-w-20)GNp4#Y1G!{U*Ww*f)! z<o3wl6Sv}5$ z`YLZYqQW$T$re}U?d01(R zTHQ%khc^&>3`%*+yuboXZ!U88McMpY(GiQPU#`L^U(*|Tw0iy!z8aarXS)1cZKC}( zuZxlR?`cNXnc+-F+_j=NR@$zOk|-)_35Dt%LG?_(*kDe5zU87k`N_W6W1Ct(vvwAY zkW?&NZVF5Esm?dMVq|PR#z{^_$L2Mid1|FDUY%V(oV5wy^QENckJi`Z=>IqhqXn9Wu6xOlVgoX?pnhD8PEW61KW>;b3FphvpV_cFZk(90eZj!%RFvgJG2Im z^v}K|EKqO7Z|iG;o?YJQ0PhWYUoZv;<68Pv-FZzG_An|tltV4jrxQndnZgCm@HyeK zrvIGt(Z_VDgLSA9{iyN12xA6H7rYZit7Od8#|v6FDOZ&j5rl&CA$IOMSjojjoXCU^ zjp=6{us%S3k^%a1qAd)jCo@f<;Q58t((5padzQi44K0YKJntuvjSE0%s`jRRUnTEP z@Acw+q6oC~(7?DbL^82E>7^IpiZ&bR@=rsxxVLXs>K?FN84(l~2e-w-Ur{iqtzHu+ zPkb(WZb`i2P@R11-1QY@#^*FeBL{9-=CX51UYju{8n^0{ioGx<0&OiiLo!~SKND5k zt|2jRB&=bu#I?T@DK0nt>H$h^_?~O+nYn5k+CbLtVZt{7Q^~vJutt;_GF-SI*~wPH zk^TqK&oC1GoFRHLv!P8>X_FTw7-AyX4yI((Ri#sI7@2>R1UO?5Ru7 zR@U1Gj{$vwvoQGlhGlM;a_bUDl)3gO zR5%)^anZ=>({Owv3CE@Ivr-C0eWvN~JA!c(F?SoK45iE43c0+YAb3@Cmde0{ez&wJaGt#iHb&b}6~ z+)0ln;%OoR?F2Xzf&#Khs^{n@dn6~8CwLGU#sR@`VhOW2KG_K#rnWmVraeVJu{Ion zqcp`#WMhw4zBYW{?ISjt0DawNE43mCi%bW~YfU2vgw@Ei{yU*CZx zplDa@;aV&q`{QJr0Q`$9d>tDii$?sS_8!poZgf>a=rHqPAk^T%?^vwX8|-~mN(})=fqyu9 z+6-VD?%$#1ynqU;-XOUcr;bO?RpeKF7@+A43-jjG4*@&|wu42i zVIk)%WX1Nd9RTsQlBTc#84*QG$qV_~1`JOq?-B^&`-~Mj;7($62S8;`5$;GHD!Tyw zvBN2)38eWz66b01L5NWla0x)vW5M`&=o!}c3XcmH!I)0c0cT}E zvwX-h)+7m9fi?>iD)tP_x{P6~PA_*5H`*XbOwdKoZ3P4qTu36%rMysW)VH6l_ZTod2=S}83!CGH^RH9!MseQW{ECPq%B69}|XoHXo0eKksiX&`K0nfrJb#197{Uk49^5F#i*-v}C3Nyn=GV#J<9 z5I_uL!8r7NX`O`S&Ts>HMi2n{*cP3Oiu>|RyW7{TOdk1xBn@0Q4Wk)`*Ij|F>IRhL zApCrQivduIU9$a3+Q+Lfxn#~*1@hyZ`_Z?bf*%kTOi*%QMi7zq6&R{=8Z)$Sp{oOg z7CLfP1%ASrQVdf+!eo2}$f#7^OR)fX12tuCdY&T(l7Q$peHyzC-jyJ0&LI!sr8ON7 z*}TTW`b?7IgyA|HzKcjPy{_cR$B8G<3_nN_lvKU54ycS#lPV+pBoM4c86=6kW(mrD zG%P8HCSV8d=}OUz)-e5$(T?&Zcc2-;B7S3FAgdQ6FOX~i)wBz+=B_+A94azQL5{=+ z?c_NnhhkJyB$2|8(~YjF7IE~sodT*iciBUGI6com-3 z4dKCpS8^oC>5$6yU^+?LiDVk_T6#7Vl%gFR@>#|&5@lzarM=+vh?xH~5t8E|8>KYcgU3GuMVX3G4w4I4$>>XrQ4&B0f$V{L;yl^i z#@oOchASDwmLU0BHka-~yB&}u;1yW%kjPY08{`8`DA`pY4GTXa!U72JwqD4qO85~5 z79CAX34$XjsfH@y$3%Gd{M)N;FW9TfpbPJt_@x@F;Y{y~1&1jlb_L0}PD_#dK^IqT;!qEfEKzl+&&;8H#{Yo^S$Ov< zGQ3}ri7H)Wp}2Vm61eYRJ73sF(LhyIx7w#Pk_Jeo)7vRlKfRdY;BTB<;(05Hkf9Wv zac1y{m7_e(_KT_qAlR)oPn8BpV4i#ot6B^`D-y+Q0F7lvr*RQz~ ztx{+W?6-B1JLD^eBX1hC(U2jmH=Rm%5HD0gB4^|_ajg<$JwlSU->)l%N%Vyq^rfN?0hy2GOMlo?SNF+YLV!OZrikrM-#L3vqL=N>m%54?)qE`+Q0wWbDO&^FiRGdFXB>weG2ttwHAysn?Gx zid^QXX?;zZK9nI-abR}o4sUond;$I<(W%f8iE_#nG=fdVMdASXA%OUjLp}D>>Dr$` zLFz_$)#!Xb(!6pM;Se)j)A*{pN7&KPc@SdL0tEFV?fwAp8D;#meDh;Y_bk5iLuxfz zWRX=P>+TrqgYlufhF6LTi%Q(V@qCwEL5%IK>_$$GoHzE)TV=?4poYk#yWb-_?>IfX zSVcyv?tEh<`!1|H(Yf@VUPvM4H{;JuNlJj)fXKiK^oi|GwyS^a<+o*7=)6rq(M%-2 z;xGx9{9dyJmgW1XXf*z6i=Myjju{rjQ8j80L23$3yr;OVJj2lKrEr&&b=@Eb#EGP& zZ~!xNA{|2&+j6hgc{21qo){Dzr&yr!vjxx~3Tzhg{BFWp#;l6{^tA=YkB0JwzI>mz zMt7BwMWPIkVrR&WQWCBL>oba19Q729zIWExzG0wB-2p-gbMj=15qVc#Aq=xA^Cr6& z!-I@ukuKp3?3-0HG7p4GS`_$xDRm7h%9(tTsH$RsD@D%FuV0&gZ}NR0Q~@Gpt!pRy znCY#|E-krH&rALxx$>qu&6`Cb3{kK-!6()v=R%3$nXH=S_nOO|*SNMr7+6(SuC-4= zN5`rjLN|C}zG6Sn4`w5X(>`|Ab*Bu)%GaZ3Rs!;-n(c?%^A?6kdo!;F8@0Jz>Stu0 zt6bZu@y97HMHo1M1VLN`kwL40Z?CV?g)!TV%^;DubhXs}=*UJWx_u(7n zs`?%(3~EDmX64q%q^2*(tzx?+%UhZ$MiP?mqVDDnr`?&20K9JHU zN*lAk&crSs&iwkpr8simre93%siKJoa$Os@BO|#zo({x6wiX+bI8I<7-M6D?-DYjI zLS^mN`R(G!X@3wm!HG0}IJ#h;Mb0}m*<=XI>Rrz5-4_)5IFj)X>A4>>{QE-L``26d zpow0|JVTrH#i@+UJq#9j(>XGZgxT-F<@?~#NIfST~N(SySy)OnwC;$94p&WWu`!uh6`xc_AMoq+cQbU%Mbl6aIoTlog3r^&qkH1Gde zZbj-F{n@QK{~>O?p7VFBRbi8dq@4JBtNW+7?BA_RH5t+*%mNA2uK!;#C z;nr+7#3ZxLC-~1_(FW!n`;G`$)3sNY4;DpYx%`;U>rqN}DHODf0>e|>pR$w@-8;7r z)=FOJW|#NV9A1bmwitEy%mtEM*e~;jo-FI*`?Ip6Oer%p#@>tF@jNVCHn|(P`$nE> z+_q=_9WJ-OEFHe&^}`J*xSmi!Sr2Ehec9UCc7GlnZOts@D_72J9UpGZ^=988eQCH@ z|19+2virCIM^hj)hyo(?&XuY(JmC^*v{&*g)gaJK>UAY;O5gS{&Y8yFEnTkP=9G5T%q3Z`5+)bMj~n`VXo^tG&|8gO8+i zg$nbH3j|6{o`Xe8maFx}TQ63yCDef$gKJ+jt{Gm4tr|nQx$tW@6@KK`3^g7AYZ+i3RvBr4SK0_F_ghbPlm3ktpRcf53QGOAw7W6Ro}&+mcRU4SvR7a9 za_BH>rqvYmAoTwbgX#=j1%C)4grC`i#yk zBB8}=DXAbLjU|G_5aWh=8QpW%p)6>UaVs2bcZSOJ5XIk#D0f{;{RrM0&oYNy4_tW_ zrmis<4Qo{VnR)R(39CZRrug!x*dOQlKX}r_XXf)OvL?*@h4gD5*VAaJ_`%v^o`%EK zWsqjC3*Ilj-jE+kTo zUUuj4vHDP|)fgTJRH3vO@yIKZ(KwN4MLp+5wS<(eaDxuK&T@q3n=XjRb$8Wm-aDrT z6BOKO4|E(vuo9f^TC%HxagItnY*X^u>@AY%!?tP2us{l(f^CI`;KP& z@%#TDL?l7Pto@F?YZSF5v1hHQy{WdSDvF{B5us@8QB`WsqNu(1s@ZCb+N(8dwc59z z_vgB<@9*=yzTe+EzyF-Wahwx>B(HOOJnye>3L@jbQuHC1@4miC-ue71#Tu^w+iPw1 zqtKXaH$l0XL7m0xNm)SmDE20-#v&{^Pg4NTKJ?7^`fBnJWABMsCZl*waU#H~Q)+xO zW+Bv6{bj~_oX^m(I!GpC;P-n`j@*&`Lk0|)29x6TXv3TBm!^p5^Hr!HW9A2>rbdFG6t>h-8n!*%`_6i4VgbUX-C zgA`K-@s-ftCC_YlzAQcz&l#M2FTUj0)DIC%U@eVUOz1GRww+vgjk2Z<+ubpo8HFV@o2-+Zx=OaU#U+(+pT@-xkjMPHg3MxYdfC&!ya2;%o@KA_{SEvx2H(9f zBQ{@I&ZJ8#B|Nzztyb^J*Z2Hcl#bx`Zk`8O1z>k!dfiTT;@} zcj=2nhWjYl$}?w9SEg_8$TVHYJp+EjS)SeOzp-)Y`@u=sjrbkgyB2d8!}HsmM$`{)K0GrBuq zS3W8925_!SD+NYbL*ASvIsRiDf`J;Tyt-*nn2 z9l?QxbVtxzmd$p8yZt#Edd%E8U(eV@J4(1 z)2Fr$842g;Q=@E8gNsnw_d$cEQ-`rn>6T)kHG|UGzJ&9Y)$iJA@t6ePG_iuUcgjC= z-C_ZMZT;c0|Mgo-RE{Xg_EvkAx+8d{qxf85C}}R|FXC&( z`#}+Qe+On3Pk%CfnmtUddHjws^mUT-e{d<~rW0mr!@~d5Q$i;O07+)ugG!pPTkGhlqtpMRN zie4er=AIzur8+6H)g7={X-_=b6t%Jobo=&rKzZAtO+s!_Mk}YYzkRk~BcMEx;iA6NP?&4LhSTNSihHy`+ zTe7Z;y&~$w_IZ6?+zpy&Sry^S6nJqAsnDyXdtM3&R-p8e%Hsw0@bwa8t-2!*R96}~ zt7F0W&S?=up_mCl2VGF8Ykb8-lCUrrnxt7Liq}`c8+^wb%xD_nA=+DbXg=f?urI?` zTAEBP@*HbZ-F08#FUip!$%-y>6I3J#0Mblw)r-kyAij(x(uUITBJdhu3CD9v=jz%8 zjy!d{xZw+cS0hSU`Exw8`I zY+dyiLAsevuVjZ>F3r!;p8Va9fj!q!I#W{Z}FQyQ4$bX$<({BF{`b-BBM;lNkUtt?*5BMXI+8*W|9#{o&4?EXcRCk&5D7i{ zRP1=(d6~B~FpMXD3>~vMFyvbsT@4*DZ=^HhNu6AK*~UQtC>Z5nN8P~2uWPm5AjU`V zST8v7arRh8E6U6FxfSyLvF5EUAeP2zWM>re_9&{1zwGbWXM3%q(g@;RL*t`S6gVSE z%Es`#HRd>9ZFv;@yLI&X%82FhE$@k2A`m{NA3*X-$Q(K7m*xb)WMV{x@?ieG%J*AG zYr3cKn|WY9AP_{I8pDm%(4L(8vOnubh?~zMk zo98UC&?D#ijN#$@LBO2S1aBo+vd~m&;r-PMbwkeFvlZksIC<)+&XELN+%^IbW9O&M zRLoUhcbZpNm`4l})K1KAj1lg^XQ;F&PD@g42h&sR_tSayjefE6bj1T>e5@+w3*TpjO> zGdVGd3Z4BJRv2q00WGu{%lu-TN}M4hkv)$3h>!nhwLrj?+xbT$F`C`9Qj zk;SydXlTsFam=M;m{KWN;W2agu-h(j#OOX0*UJRkN~l+1R7SkD`4TQ?5W5&*S$AWA ze~#=0VjQ}JlSO<=lKUh}!T~zTR0FJ1D=lc9=+a+8xk;Z&<3D9BT-}!yIJ=m02+Ic` zak*jm#{!>|`sScP`3x9qj@H}0yRiT%%CeU><`Z)n2y!K`?-W<)A-V+yblsGY>iMU?H2}Tt>HS>?K)}a--qG5QgPh^ z#%viMd*wb9(I)F)=S#!PvURJQ=O-#Ph_dJNU*tYbtdlY2j$iU|MS20ILn>$P3NU=| zUdRYrc!4!+4I@6TwV#jr*ung{s}j3-GApgH5Yh))kyu>Sa@c5#ZGX9VxQ<(3CI++_ zaw0!iGxyL-B@d`N3>C&mv)4q3H4{8Xu}B2A8#*9ydK06ZK!?BUQC^{FjJ+pII< zCBtKEw6E?+tnV$H?@DUPywKi~aJ!kL;)vI_N&<24GLuwTak9cawJeg?LUgjmTe-wL zH7pL-OdV+_4zFJQsUmEc7s!5E`54&`6LJlPbfCiP@@`4GP9k|U!Hi(F3>E?|y7Uv# z-X4N>aQj(mDLYB=05Fu&>6UD=X5_KTrzKz{zn*?DwS*f^ZCu94Lw?h6uic+XQmB(i zTfazknNBP<8wYPHuG(9cAVt@R2!y@hhO1vrLMj*$yY6mWsPw`$3Cxd5+puP`;#KU5J5<0 znMZh4F&iV;k3bA#*$TP0842(VHuikPi@5ai0pr8BTp3!GbBKhht?J?R_}r~{n4t3q z;ve$6rAo3fX*b+PHX~0^~AVSM^a`$=ytC0R-6!iuFnP=+zz5{9Yhrs z6j!c;`xn6jPVP|5CLyYqVr6cLyusqjj8l+Ji>}+-S{ok2IWx4em5cC%Q z!}#6l({H*tX}%`3HH2MjKYTr|^%9psWzfF+6|}d+vbQX_w<5o{s=c>nxwr1Iw-LCv zN!Z&;+uLr4l_-OJD}sDagX}K)?40iHgZ2+t_74U3kL34%Xzw3e?w@$57H35V%qcqo>URG2UJNQ zs^}POmT$(OP6w$z-HA22339&^LQE2l9X?2&^F1}m>>cc2Oo!dS5%)(M^1|;hSwWxr z&NGTLYObq|;<=i|VC3siNYKSjW-dpkQyI5TOm`jK2wPmG*^zMikx228=({7afg|yc zM-rR=EVjzG4&r@ZN#5it|KkiM7kb3obtrq8Ii`_uYa`0HBsU2A5Z9O+EyeU0{79aT z;ifv#wWgc(9@vu}Xs|@tuJdkthBi&*;; zNdD2-Xv2Mfxi`lIc$)28B*yW?>`wA6N1`>(|MpErtJ~mLWCwN595%)N5#Rs^c$z8+ zbY9~fX%+PV`|8PBfEMc5Jw09e@#%xRCs9rT^I-6Q`rWesC%^mqpXkEg?<`{}x)9 z{W!Jpq5FT4yX{wU_rHY}{u|!?a)oz$U;e+uyYEMPCx%)_NBTzxuUZQoSFMFBzxy9} zx8?oRRbQc}tF@|Upu4@Hv#s$8@?Oc^&gPod=DO;Zw(Pdv7cIS4gg3pZyR)J6U43=^ z+c)d^n5q27Z|Z7l-c(dolvI@Dm)100MHfm-i;D{L|HJR*zs^mrZo-u}1Qx#i_trw% z%h#D%nemxL3#sVOiOTtDSAsX?AHtiM7@v?37Z-OGU5JT^y&}928nW5{1$jO6O|KNMp7HJf zAiQW@Q>6B-fBY`mNKySiy9@IFJG}c(Zb4F6=(@6?gc85FBA=K7ujox)k(>XM-<44P z55J4~-}+r?TZ!0z{O({PZx!wcsBf-Snm_d4{jOl|bNNR*Da0GjjW7RCzxz*dL3Z_h z+Vd>^m-_W(v*lKI(m1TfoMtMV7(a_NVw@UCWjTa@`Q3NE%M7Ami7NYuN0kc;Bk$gP z?ZEP|*eY0hH(Jv@ddZOiS$<}<26VXZRX?kMn>>YAl<(L{An5Wlf0sck_4?u%+hZ$4 zZB5bH6eBrCEe(3+kh^XLZXrBMk&|$vO8+J&0Zb!xj>by${oZF(^mL;)e3?;W@L**- zyK45kFDIz)UDg`4xBfhO6I%9rk66T0KHczbj|t8CJ(Rwrg#)D}~IuBeu$g`uD%tHmp1b0?ECiV+HYhH5o2XOetP z-^&#t`@u8c>{=P`OFtmJuo=3q)Xz~vxpu$;0rplf(c>6FS^7B(YGFx+qcV(_O*=_?e5UXS@7y}=D zxn;>?`XpY6gSM?00%3yLX%2f$n23u zMx2ltn0o&Vwk8(fRVK>)*hrlqOj6Pqyk{Kga@`=~V{ zqmUg(RBQOcC}o(Q81n{G z1P6bj2xpxJ*piMs>+o_76CK>?-jlTXF8Fx7i~?7TA|dVc%$WVk8YRZ1ELo~xKa;NfHqUzP_} z1Dl9{JDT2FbbpZrBIJyE#>jGe45e3tU$?_Vz{D8NlZ}@Lkl2A~YNu z^YO?4gcC+LwtNTfLt8pX-emH0U!$Q*{87J1mpO{kEaBCbM+5DoZ^ed8afF@Q(ABLW zKHH#*HYoq4KVui5nbn(ET0avE{|xHySxrHu87_?Gajlidkf`RV-h4%w z^t$eQ@u||-!)AZxw_A4MK#39M^i*lI#4=y3DXgwhkraUQ)A+kr9$)dP+Lle{I~1z+ z5#Q@8W7$WYb@!|0TepT*U3o1<;+8xR~EEe%JhQY%j3oV&Nd+UF)XNe#n=L#q;rZ?Pp{A;TIQQ z0d$R>RK^G3oURHg$;R$$;|B!g(D)eL-X0<2!&uwjE4IB9+*0F*2~U2nBIue1b&UO< zJFYMYT;2+X-^@Kq+do9oIEqE_QS8heq<=*TRX>B1?P=iMwna~CgQgC{)f_b}f&jVV? z$%SJGbyO~oTRTj{$;tkBkt0BQ84fgLo`Vqfq^P{Q#i!AKeL`AlHX-LVuHlh*F{!lZ zFwRJLQAzX`-|L@|{_R`B^gZ&;le9ikPdQwqi0@r}@$EMX4wN4%qZ)i8|MayB&cHui zb_03I{6`}ITSA@4B6`>fpU_|HIl70mexYlRHGhuZQTx$E7KU+h6r`MuKHELo#=3iWtj47(4~paPW0W~CB3N$*a-rr zmJDk1hh<7Vr8Ir&$B&67zq3XU_(FR6>)q2YOQ6UB7X6PhDb-LS9E@?1+Go09+C`18 zhCU<1O;7$sL_#(J9xz<6_%d|=0KAb)x8WpsxCGrE0A6;glr4o%V8N!+c&$0;Pb3>x zHEjK#E7`E`)xqREkx!XmOTK>*`&j^RV#HQ3hzFz`L>%1&KgkOtCkwiM$tSbyY)b2g zC(qOSh*i(CbflIBQ*{XhQ>wK%(H$V6I5^Fvukf-I?e^`fBjVJcyzte>gtBVtw=&R+ zP9S*=@B$mH`}py-0Gn`WVz(7s8369X5~Fpg!^j?!clrM^^9ZU5C&vZ9B9AJAliv-L zmkNYeGU=5q#q@XaULv97D8LmICeMRhIzdINss6d{Zw24ECM=Al-p-{XKZKE+(yUCl zww6Tu`u~+Rq3FXC2Wp~-SfcLfq!~S+9V~e|kAQ?Hl0}?JNhf(zn1(hViZ(mPbK;^P zI7h0yJMT~E?vcXZFrkLl+>_2@*z76rabIImvTX(^(HC6FxjQVMxKV>O`M;Q;HCwOTbqE znqfd{+z@F*Ds}W)SS{+YKSgA+m0+r{*wYgDVKIE0;h8Lnu80)Ad7id+2HgTA$pxoV z)P&?;k>mqd=-p=qq-QOjq3B@K+aFkPtiV@Dn)soNZUhutO`%W{sXX|!ROm|dGk<-T zDw7X2+`?!4Or^j{o0>vwG8wW=dAD&k^+>v+OC-2&f-c&HsvHS^4yQSXgZFgcvepSp zB-j`Pw$+)=)d_oK75$j_0ym`nEHUO`9=IExO`}KCh5(D0z|S8Oe+vOwn1CoJhVdGx z2PBfhnfB2kbM)Cg$wTH%tf43$S=H6ya0INN3$(NpG)tn|hrFs#gd3R9p5($ICFD57X z03lwh(3VW*XGpk7DNXwU6^j!Ij0!0df|NW)yb*#+Q^_?RfN|B(qiUPd?n2)bDxih4 z0X?wO3ErIxM&zd4iWPNAk2bkn&70{i_Uq-GM3M}bA;Tu{S8yOvl=zFG*ale2w+W=K zDLuVOpBtiGO)4vEE~~D#z>q;Hd7xBzDVAH^oCiO17VqF*V2S6QO zP5pDik*TJFf`{y&+G;XZ`w15IGMA$n2UD45!Xn|r2awOM1xJpEYYlI&`$d@?1{oded+iBl}M=0D;H=AfeA&Tp&+ASY*xM8B!bMY zZjB>I@U+ZNH~+r0cv%LgE*qk!X_2wUP=`s?Bp%ZhprGeS|2rCVfdJT<6W3cQ*l{Op zd_t&l0(K0bebiNvmtNDzaP>9a@`TinSncm*CA!OyRr5qS8P@AWe(A@5rJBHAq*DdM zA2pg%Q+pEFC*RVb3dqSIyT0Tov5GP*_>u%#*9Ax4hhLQyHV?8AuhFD-Qjq|#4FnlE zDj~?0`dcp4rX0GCOfVqP^&!DV=ZdcPwbz$)r{K0a%hZmttbh6fqlM^dNeqaeP(VWx z1of7Zo_r@40+eb@IiWj20Rj%_LW-fDk!o-NFaUD3q0ps&U2kweH~R1|0TR5_R$HKk z)${T#Ye_(Z$cWYx3?w{LK~4KDzEj88*?4@AQ+oij((U|!>MWpV9t|P?nfq7>3Hk1;Vl)qDxV#Nd z6oNnV!rIJ;UK3}GH&JJE3j6yGx04F|ni-E`8iOY%z3>E8!8}#b0o_Xk6}dBPpcBXX z1YYGk&@ctt8-P|o$aax!RECg{P`7XGp;dt7|o7sVAxf7;uS_ zWGz2eOV?|LfRj+X3H38+{)tubMrrC#0`NIchCDlX2=ZO97Tflnj(}=h>IB`J396kk zyPDrQgcsD26VQ!=p3Do0FY`^K_h@i4kUkTJ%q7@|)In$sMM4EUh%`zkp_ygM5r@qCFiItWQ3Gh?kXn9a<4h*oW=669>IyODy+d8dxbSpNobgP$Guq3-(tsU35 ztFQx-;IRtbGohO#)x!^94iVU0EZsJi`U}VCWfT2qD;$OBD?`pA>sst0_&r{5i05?; z!DoNwhh5&$2qDqITj4bJ@EDUyhMK`=G@6cN3cPn2(sGGhWYvrd>K_Is^>Gk}m&m)S zaErKV#xBqURn3&d3hK#Bgxi=l(_9&H&PG;j>S~_hOpEek8Wjf@LYYV}M=is&vZ^hP zs;w~Qb~3n+!uOFVVP@mb4`8M_3z{Jg`aZNKh52B)0cwoWzp}1o)@TyggoK@7VJ#En z5NC)j?q)p_mT(QW`iuc5(I-4WFJ|yXiJx}YmdUOHx^QWabfsnG9%Cs$z=|fQGD)y? zY~2_9)q4+%7AGhH32r^0;~%BJOFNX*M*nn7Bc<%YY8#9AL0ZTG-H{orX4$&uUV^RQ zLN^WlpEmk|QH=?yP>q_;ZUu7b5d!Zbz!L~MJ`@FGEwpjz=4pUY;Yy1LE}Tm$0fdX^ z{Uo(3PRkm`a5tVRy0S(^mYJt1Xaw19O`_ip8Mn)e?b_uwXk>>qskYlUVt9<7m*X^#8 z_@USI9bI}M_LBhtw+Qb>=^jnEOa>XTeK~#Cb zg=-qjH%h$jSo3TQS6P0`nN8**MqLZXOZB*2m?cx;64`+KD zV1z#qT01y!|4H}QM{1l`R(6SI%a?A?m$uW0o)mV%zI;YW7GU-mG^(KCDabhbd*@m& zQPynbxjsnS7ZmpuZkD~liCZvA*AA-eVqwBtKSd;{OQ0Y7l5^0fsgH8jl)R)x=SfQF zNP) zdp5BXw=K#rl@9iqD3E29a5Vh;QN42lGo91XTuIqX7D0t!xhcdYcc?007hSP-yyws! zc2!)MPo}<|PeH-6hNCif>W@!GPZ-iZ^Ljr5WZ&Q$HA9L6782R|_>MSq!H<>^EJ{rq}T*yMBUnqtDy7 z;oL^C-cgBXa6N4~)W%rm<%yv@fii;xH>TRbvD3HZe5-M8W`pYrUNXaMmn4SX(E?fI zO-yb@?MO>Vh1NCczB>Ix+}w|(8}IuK-U`Zp!6%Ca)1U`LGgszm^sgVTF_u$aq-=>` zU~%_Ek(XkwKi+Fxv)4D(rj4jTELD(iO!mvvS@25SSWgi|gOUuHHJfc}%-fr#oQe#t zOV?v=L!eY;_bRsOvzXreI>gvNewi?6c)QCzSCJ|LTD}^jCI4xZ-2PgQgC z{sJno$$^tMZ_K)PH;>v$+CCic{;uH{+5E#U;K46wbil{TBIXvF%HxFs&ib2QwZ2u9 zJA|d%>`l^)ADlQwpUO5CnlXAbE>|>z=ay6aQmvYB@T#DXH>4I%rg6MujkOU!XS~JE zvXP2zpSUx%WJnmF3hK0yMx&lYXAh#QgJXZwo#*YJKWq~GKcwD?2w@75{E-wWx8fDA zHprlJ$txOxu*`HQ{hTaiP4i9A-228%a;_!i-8XN#&%ElD`JZ^dq6)m=d7UYqR?x62 zA5Q^eoo9Vu{Fmau7oz7NA05VUhyv2llJ(@_fFfTs!p}JLcU>-zJ{u}o?2fF?`^2?* znPQFSH@v6BI=Ti&Zry1+k#!H`GLahKzY+N5LGeSYi1WU-H^p~<^i*M*hw;lrB%d^gSz9z z%7ba^U;6{Fm#AMmO_%V_+o#x4F7=lMr|!Te+qV+8-pFGf-NT^uBBK4 zq#Lha)_B3uH;B)ve)Q$R8FV9l-OmMoE$q4!hDQu&Oo+M(YeZC_qi*_Rpbr~0xU1H1 zh!9P>NEaoZq=6`L7YF)$2B3gQqW_JQyjBZS8lfZ_-STGkIDLiuM>DTu9f7W_xFd}t zxM|#-@6&Al#Qu$HI4TS4%DEhLQ+^yAsLJme{n~UO#TRV8oNqmbb<+l{FLPE^YtVl` zh zh)1*ZFL!Z$YB$U(F+2nD7`r<-_@tI5t4S_QaZ5uW_N|2RvE<`APm&wc`?x^&crNeB zzfi;J;b`F)KDj||V6<64*M0#)qSUK-XlexM!3`XuHljN+eW~3Cyv$Ar2tt7oCEczt z=SBS&Kh;0_))lALfCfYSEeIARjOL;DTyrR9DozX8v$iHJ20mhH$)n20N+~;X$(YMz z*4&@S4oZ$FeI%*~<^5e_Ec>El}-VX%Bul-;N0Uz3oq1OTlyXGIBrTNrgWh| zA+>o|5$M%@k#*Qy)cRHHL0^K2sfct<%y!g+&~;_UUmwyRu0YH0A3e$XlU3AlI!1g< zHp>4EHrGkzVJ|T(O?oJ78AGYywXSp4)rG3JChJ-eioL7%VC8z>0;h| z1xL%iGRMv?lG7}N{pPGRGln9Yv7DFPmwzn6$hqfsNjJOXn6AJxXJ{jfTNkjjKs2sq ziAx#J4vM*fLC}|47d&8CMGhzk9$L({Z;T~2A0o-2VuZS2L@hr!i-R}Q3eK;t$W2@Z zx%6aful1SSm67VYO)|}weH%7JK*Mf`4B}VEs17U8XltIFguaBYC;^NV*Unk+% zetbm7{~kgnZ}H;V1H4IS!Atiz;z-dPm&S^DjE8OoRkw3=$G$H&&M=b-t!2p3OMq^_ z6LkQkCf`#L{V*7~@8UoT|K6J41B!cR0?|8`IA5lXnHQr*AIZE@ye4e=RwUGij{O}005JC&1-d6iuXPBP zQ6ZrO`d{-m7SBKKG9E>eXg16jkKPZ2>yzjJqU+(uh3~`9O>4tGJh?nsQ6F@`MXas) zd_7(KsJcISixkMWPM>AW9++A8XQ}7a`KL2p-4;Y#Z1S!_yE9fDnbC0%OOwNv`r=;W zz0QtEFwih7xh$AC#=&AVS04#Z^))FQlR*mUg7ysv-^AK`8b$FXjJqN-L&5|dPs&sC zs2&nXcM!;KLA063!J>ga)3Uk%y@@2f@@WXeQMO_`8Rwl7Wl%O#s z_)<2a1{RHJMC)wHO14tqx6qhev;=?8VN&SFR--iR{XN+sY^}*4i(-oFRkqW_D4_QZ zx((xcjj}cNDL^#U@MeJ4)dMJ&Pnv4S8c4%F4P5M$_@%byulWGL}SRy2NVAR0f&D+@+BX)gui^{XQh=;-TW zMC0T-#~t10csSM~>OOy;7Y#RihIDpp9ibYphh)r%(<6x!eevpkUOB#VI(m1(>A>Nq zO!^U5&+U%egZ=3&fQj6SBA!Hra7`%zM1@x35SDZBOH&OpsIlEel&}T{=4)Gq>PL`t zW9?q)dqVx!^dsutjDAb1wxCQr)`U0ap?VB{O&NTCVi1u#G=D)!ZIXw2)Lx_sZ@0iY zV%1HB2WZ)4%kYL*4e=7Zy7pGW4Mdd|o9x|!H_yBn+nEgZIYt)-vEs-g9X45?`O)XH zo%r*}m{C=i5?ye}(B)@C_^bt`782drn)_9@`i&dYvZ3Lm?dTebj6B5%(r&JTs$iVqM06=+uK?$0874UtG?1hlI^DRs@ zc6YRGZ}b)Kv-iK0gkTHrBLHMNqpHUijN7A3yEsiI4syx>19E#J!uQr> z0~WWA3{C%@F`DFSyI{lPCPu*{SgNoT7#C3stL}_68DTXtww}uLQkfC&|T{_b|%0QAEcTVyG#7;D+H0Aa4IKw@YQUeSyR`>Vz83{<)9Q#8?Oz zX4Ub>D64)T!&wMcnkn05SK1Mke|C7LesJRg8;!Ls^u%JKl93a5XH{@hgr$!F=`JS9 zjJeG_;Kid7*$zK^IlV>TAG*gFwex4QZ>@Ek$SnsnW>rrtBMxTIIIVI$XViw?DQCCY zFSK9AZS^j=Sr%Z;1n<6cks!85L?PH!!i?G?1&F4jZ9iU!o1;GJidz-0%|-)mPhMyg zAU-~{wn_}3d&~t6at8(Xefm80$vzb0kzxA98u3$+irQi45<7ZCh#dj%6hWA=Yz=PO8zbV-=A^5TKg|PWtrIAZu(S}N>>#2(MDD? z8WAfB0j8$d2ISc~g!V>a$#h6~?>Ugq7RYA~WJAI$49>9yL+%DOwWo4m2B+K%Z5zeA zoK+HlL<*ZN!i3iR1hf5QVbqNSd+tobWoGDz}$YJL6Q2}s;JAvOH@2zV$wZ3q< zxUk@jjbuSlr9N5kuY1;*y0Dk~1qZhEm;m{(+J8-5oGOfhv4Sadxu_w9=}47|^C;Z; z$4zBhzC8PS=7ISZ!ZyZnaRDSXMUwT{Q^pR(X&fUI(F)Vb=pr}x)k5A=l39W zJG){^D7ji=f33T`pG1 z(+Ahdi?3?qj(d#+yLQk$VpnI-%E86z#YCT$MH^0P%`C^=W66~-f#NnOMfiiGOPYtY zwzH3dnTIFAUE5jCm{l=w<0omux5$G@d+m&WeS6)5{AYH+_!T~`iB!;8bq7->^nFiV z@fGxtwv4*hzBYeVNHN|7HZ>$;YXhrL5xT=f;V%z1V4*o4K69IwCnp5&#wc4N=&AN9 z76kXww>vK&uZ9y(Z8MDupQ|H zyag~S+}eKCARL|M;j>2|?%6*m*($6ec)@#8H4|yV!!%nQ4op-zQnGrnaX9H16K5b2}P4ksOxvO!e&V~b;`D|u`9%P+ zTaefUFX%ci7b50>NXyO9hSnJ$0W6-8S9YNeqF1@p%qS-%#j0 z806k3+h4deCdJQFdk4@)6tpuHi@;33Wd|JcdI4kyeThX6e-KEj3ei$DaR+j=Qy(f= z5l%dR`OQ)TxQIXt-Kat}y9iyszJmIAMz`EvmRUd!XUCG5X)EqMC^ zzeUl9?JTzY{wN2Z9yhyx1aG=L$6s2dpXeeZL0kJkEQMZf)DUc;FBK@QYtI64!+?Lb zV~?5<_a8^U5#*~BE=a)Gftbmoj1WIR|LJvhllOG5cmfx)@9&l#TqC(r`G>keUCL`E-uu-LpF6*z(}Uaxo~+$x6gK-k zWHlp`u*lIP!0`CKpsbe z$v6(eWRVoRXMgVvgx-1(7RCB>k_wFZS8?G0(T#^*lkwU*;OQkY2x$YI=sP7nMw#sE zbPw}UPUKn<|5;qPUF)@d^v?lE{T-6q4TkaTM3cj{7)DH4F6!y)Sbj)6j1{IVN{7#v(7>SDwKE2h;XKhS#934u@ z9)yTsXiIl`(hM$$L02K9m#GB;W}a!k0{0`LxkAqKFj$LK^t#8wthPz$RoJi0v?N*- zxL8kqCRq5Tysj35@KdEwv@Djy zeX<^%1k2-%-86`+3K6Sn+F?)RujLjUGAPH@_2*8@zMDKY zWJ_YH-Cv@Ek|WgjHrWglL}EmC+NBa~pd#IOT@E^(0>6D#T;RI7cHO`vL`7yu;2OWo zrT)#VR+$lrr)x1I(j#^Ux5Z~wZj38xQ2)@6-}-%HV!W*4P;Z7ZOm^zmQMT-~k;d@# zEBgbP~3WX zCyAs|#$@h%+jwx7B;yqk3T({ng||imPh) z^7rl+^&iJH>y97BfG1DY0gs9VEFrx?gBl}$sVv86gRf&@;+Y4+0k3Xz76g`ofqUE~ zU7KtVxM?$^RgB+t(I-{o1yy*U<|Wf<$rr=vc$s|nXOa5dQ)p}n)arC9qL?ORI z8m6fB?u7=wu%c{ptra}U9i<~t&QfB>O*EtAH{drCN!79FhV^Su?L@@XIVTjR9!^ro zjlCW%o5=N_0)CblaWVR7m9MePx_VCy29)B)*wgG>F3o~dgQzSJ)t=L@~EzOs7oXabguvhe4Sk=7NNnZ z1egC+R|;a&5kjC~xHWX%8>S>#L}E?xDBLcszLEjg zk0dCOtW?&X`?QInyFZhH)bLe7f69@^`XuO>3mrkuOEU$?)477FrgZ+M^L@ywSShWf z3`-EaHUhufiVkXGopRf^`GlLpFmJL7Yj`%jpQ!!7L*^~vCDc7TH=OSm}!(WS>*|E2?q>foq z`$tm8HnC-v*gi{anB({B`%yGI>|80&l`euBzdwQg0dZd{&(mOHSLLBZT4);*D zIHLodLxa786iC1CZGTUDJLyB+z;J!D;f2agkTUS$C{puf!oc#ZBk&{@{98}); z@IMwg_X_L&M)ec33ewXv{umH6XW9I|8vV1|Z+W)sLj+Q>=|8|S>zYlT#1Jd{U zABQ-Ix&IjAEcFI|@O0QTtSkI)LmY@X$H+@n@sGp*4bo2%vn*^V`%prG^s_R?G6~lw zV2VY9uk$9ZHxlminKV|+)VqzqDf^pBJ8bCZ!7P)es!y%lyDoDr_&ysOnu1-f{*p>U zJiH(wGt_4XO+cQWNmjpSM`Is0~VrOq{)ho6*kYB*l!wiiE~fB*KP`5|0X8?VGz~t>T+jUF@X$miRmO>!EK}xglJdt&5}#(FzT#^1Y>!>o z%y;a|MnU{2*vg(J%Z4@2QgVjmk5GVoDajQ(&MTI+eLNNh&g;4o4&0L1Fik{~?}_PW ze(YM(i48CRT9sjL45ac>*%3XdN2Ew026_PwI*uQmJx!t$Ln~xSQs)4ECU}oj_1uG> zB99@pY6}hvaNXNFJ;-}*Caa0#+jWP^U$@#0Ea+U?fh_;(X1HWCvWxGZuE#UZl*4 z2E5SW`5ZL3Sr=(xiuy?jlcD(>0{SF&zXqdY&%EL_T`wmX<-rOe>8dJ>DBS2Fu z&<-oc3DxTT>f=D5R79lDlL{)q`8m2BB~Qa-7K8n(URbHBaRvc%PXd_5FVDumEs zHB>nc1)Q-uW{sveIR+uJ0S>lg)q(t^WO9<_K7Koa{*j>W8AT(p^1a)vwq}}BGoz`5 zb++Vb*JygbBHe(40>~q$i$!Uqzz3JYkljTmz@GVyz1zvmlKC!*H!U>F8}g-{*k~EL zj1`a~>2$VY`njcmlCgKL)NX+hZ3`X{v_x%|IcdQ}Ofsun%%ycM`DdhK!Yf3rZTvTM z93Qu4sn((7LQK(-CxFdHg-Rur>zxd@i8R6zTW}PUn|6LhdAW(8?k%ubyyb^`La%*I z)x@>JRS*x5;T5z950JT$Vb~Z>E~QfXMU^w)&pE*!0!CbU{UvdI&bjdIolCcshpyF* z)W5Ewk~-pO8K=w(4HVKOy}Q?}<^ohGvh4;M_#j z-;n;fN6|JtkEVt`AH6wlZyD0zUoe^f@$tChWTg7p@zDIAAIEPKmO()bzmhnB=6ib+ z{SX;c9V5;WrJ`E1Ei|V@WzsB8MbH+tH;2g3qJ-G9wX{Ze=)+N+>_UxUVRD`=?#(B? z^5MHlxSCk+dm%h3pTiN{dvqxkX}wuPvT-;96YuPFpI(a2yaddpEHD+Ny@mlbI;{u` zKjOI+U>NoM7oIK0M$oil&RsPDuWVYtzpEM!WkdnG_B3SvM#Fcq7)RvIt8x`iy-?86 zuq#M}7J3!l5G##kIU~?RjDLCcHD&?sE3t(90ydzf4UV+KPy?kw23{;5Tv85BKhQ!z z%)jKLZh+N^RVR>qFVeD=bR2iE$IT16HzS^J6oWk3apHeSn5gNN4_v1QCFh9|7;pjS zu;J0UOHWqND^4JMSh%;A@%KA#nhZ9$uG2>4k_4M1bS&f+< zA|1gihOVqo)v_J1EagT_ZC=(^(h!DTWo(z+W#gGLz-~_->MO@4v$hX0fRea@e`ksLa&_Eb#n3X zH^&K(Ng{)v&lbJLJt4lyv;(bxD-WkN+2l^e!qNS4{*J89V6Z$mVfNWgZwW4`8{y;k zlCR^xIC|8mD$wdM5+Va^__)WW8)eUoo;=r(aej5KzqtBgPU@3lnrAg(Yfy^^PNDhC zd>d!A-C|aFzo*IgKezbI=3KZX5K7BHRYKPO!u+uI+)#Qci zeP?)hV)-RRBD6CmlvS8BR-P7$@_dp4a5Xyd9XUDd`cp4@wK@d)if&*6H9ZB|E=Qo70L~e^`6)lVxF30PmOalAM`I4luffgjg}vTT9})+8@qwLg_Rqpt z3oyV?fJV7|n7lcSAS=Sy@&4oq^RZ8i42hw;G;l~1Rf7T-QaxFXU|4gD+rvaPbX{9n zaSB<>6JDJnu#jxT6Uf1lWBR$Dy6?coe#-?2rRE}{o=oncX{ll-uke*`uyotR z>nA<_lZSdn_H~E%7zQkG6C- zhT3#PruD;KswxvoS$}OHA-1wJ*bweKOpHP@P2`=l9p-?A46k(Hl>$%Pz-2nB6k+Uh zR`M=G86LRi2DRQfU+I)CqYx92u3XnFpij-7?~WWx2MmMnj8mfSlKW9Di8#wdp+w+O zBVt_=SUqKEcL&N)2_-a43Sx+mG9*DBaDb@1YvF<%BUth|?VNZ zwI`HeQC(2hj2d7n1jZv2%p;Y}AS}P#pbU=zs0VcOmU>9-3p1){YEtYCe|oOR9Jo9V z(Ii1=91@THu8>5}pC*V6q#DkaB-PM#XfoGUOW@ zm|A%(9C7PRZ2`hJ`=YVBokHF^2}oZ^1Oypr5=tC}qkkA`v~!gp^B|Sv?qaVfO%xiEaKe%n zkk_-EiNR76@$e%M^SC1e*okS%?S7#-NHQ0??Zdo5z^g8n^VH(Z0rd|xR}IWF8&UCJ z^=Jl&kYIVplsvP58{p{^7q9?3U7)7cqFzS9&AvcHz^o(>=!F^KuJ9R;DPWPe*i}VFFOmv$pZ)_OfpA~9L0DB>j%JOHcgKUM}p&hy@lIEbj znlt=m4CEk4%No4LsYZK|KJ?@HHwus^xeW3qB^rY9lh-r^$$~Ez9*9`E0M$j{;JP!` zib5{MNQ6Aq7$-A&C7~6~Y|G(I1~F1D73>nBlm}xE1}{3aq~A?)jxgq6F#swU8iJY- zb&mJH@0f0?P<>y3ZL$aNJHmo}7bd5{Yx z0hEgkDb3-OMGkmVtZvE2H;V$S>vFtlF?lHk++@5Ec9`J>N%<0r$2&HveY0g%GCF5u%(g||dtKrV4U_`vO2nYi2wqjH6_9P} z4s&2`@)#!K%@Ok@AJ#WU37m_!a=IxyIBrF0mhUsIWewaVc~Wc}_4H0mK3omVBH&CE z4zUR7ASS0eGMz4PLev_X*_k#M66oX^PVlgBAIAM4n2v9&Lf%^`c9)BYvN4)ks1tt; zic89!%fngW%U9I+4*Vn+PF$dGY3%%xLVbdP8b{sPNuF?{f+S-fOUI3J)y*V*TXVL@PK{ z#-h1^=k}_7FPAqO-rc)n5v?1E_8%ia3pEiVO&EFNp4r#>1TOhUoGWje`LVABXfQ~M(%8^yfTyGjbp|Y zRhB=zF***x1l}0WTJ0YkNW4u1sQn0ZkHn%YH5T(>{EE(`XxgyNmc8=$ zm?B~%{sYNA+H-GCd7x>8{%Y@8JZ(`juYUMteSw=bzbzGK?vr#I^}~(YHe3OiIUsq z73ms6tn$sjfBk8tQmr{wcysHQp(>gDw0Zuk(UF3qPy;K{tI+G~qBZfi_T#gl9n!LZr zT{o$4Y1y@4`KQ8^mecaN4)wiW;?LSe-ux*qm6e91OwCKIA?@`S;OdgUucNE@V))_@ zdzUDO>7=z*;`~?5|42HYnJGT|o|{QsVRp^?`f5SQ@_5mTlmFV_CjfJOjn8>~_{D16 z^14O$dW_D;ZM}7S;f(?Etqr!gjegPfZ-JGf!=YYC*?Wd4+|X z>({UUQJ45E(&@fQ7-b>p6DtcibnCd2o#cN7v$S`7V-R+Jwas1}Yf@E-oI0a6<;5|3 z>AL)vm1%yvu1m;8emfVq%k`dz7fIW=ZinyN*F!%GL@NpzeL@~&Z+GalO;$Oqx1WFe zOo$iap5sk zKvga>l`_N$RHgX`q`xACP{cYw2~qG7nTvSq(eVS;8#$ zOtvvyp9L-@SEzzX{B;?>ZMdV+H0TXW6$(o*;zcV0LSr4lourOYfomo&s9CS-&$rt%MF}FSks*{XZam z=&JGchVS1vCXlq}E-am3WqBqIHWbSOpH!n0Fz3NqG#oDSc_*GmchCHgzvi6#lYa27 z&>z}8IYBb0hghepFOpDtLC90SH!9Z%r^j}K0^O`-{Mbfq&?Z*pGeQQvyCdH4lI#h3<{f3zWnJ>h&F-qggE&b5PTK<(-Aqq-s zWocAbVdT|Pby<^5#*pWB=wj!UD_`oiw91m3^$2!u`J?$dbV#BQH)}gyP>*hjDf1!} zStm(-S#(msF3qVpO%r#k(bhF5jJ5g-AyBzwFZUk&! z;>9S0#H_iA=+qg%^&;y_Jeyu%5GVjB{^S|GOLGIuAePq7!KiO|19S%Ho%b{v069g9 z7u%eXly1~>0{w8Da=4A-TAGbk5NmNssvS$a;aP80j0ar`SG%3=+Gn^-r@hN*>!_aF z;+pgPkL_}7^gw!=M3BC^dyy!+dZ?q{)#8LyawOj)_v1GW>R+2f=?Osw$pdO>K!e!N zV$;hOx=nRcqp4pdaFRdV8rP4&dT-W$Xy2})@=lr?LoU(f3$y6b59&U!li+YWA$gf!&o#;AkYG`VAy)!cUS2MJ zY!@R?`g1k?;>CdCE<8`=x$d7~~5AG0x06SbS%obWqa?a}XDBS3ehl zz8OugQsZUMVo0yQ*krB?)6eyHq@Yh3WNOA9X5D4`eic=15M!dJU zOWM3?EfvQkG2D1aKuh(i65=y4;$r9wgf3A#UNQu6u>{^Z9&Po7j?C3Bs!vuvAeA2BNkwqM6mXxg zo?3?1N9X4cbSKHdA))BtSC`hFX)y*jvxK@OoLFaVCzX`q$o~H{I3rZrPCy z*fGn5*O}Nk4j{k%xTQ4fY+@HkmUk_05KQst#+%w`bB)o8Tlu8{LT^m4S6#%kGTot4 z;UBUtQQjLkr`0n~0%CWA^@~u{Muz4igoF#~ifw(dJqhm^8^6sV&6-UEL7u@wU z@+HicDF&!)5!$Xywk_QF_5woM6-_;2y5En4cyG#c&9NPDU z&L430`yl7C?|U>2%3>^Jn?4E()!$(;Ap_lL3w~^yvje1}}KYNvfVA1zO5M0MRT;*QMXK^?avz3XrbYo4%qEH?tYfr8kex*+)G z#*>)Wov@B-G~-O`idZNO&Zk$UnZ(3iAHY*pO3SX|`TC^cup9MEUJqnvbU`!}TxCO% zc{E%E?-n4riIhXCo_SL|45~d*W_NBvw5hFOGlSOK`grLC+ak8c0o8DnzK@Y}FfAHB zOYqBxoQw6ULEpjuRt#b=O<;nZb)BuFqbiqiQ9e%RnKRVMq}!U3ckN+z-_m;Vvu%T& zYzsFI+0R|gycxZa!Zmn8U!a_I3;hHt8{})L*CyjGe&vl27Z5gIQ|qozKD|!bi}{Gm z9}v~>7OZPKQ}*JgOR&v{n;-j?UQG}NH*Lge($tn!J5mr#zQBQ8N%yXGML)@)bztfpKw9W|BGa~;dKDJm^?_FLXr zl|qAdp=fd%?CwI)?t{G)or3RMRc>FO^v|M#dahGUC1#g#+IMHFtu$Obm4scF9;ikO z$SSl7ii~kuk94kaI5RuWd{(1r>~2|%ay^Zhr2PW5Q=sPx}9-pemJdst5xUI41DJN{JW}Hcb+cSt!EDx zpTC^$d3%B51Nv%rnAvf9rO!g5I8$m9&s0s5I!DPoeepmRZJ{sUK|bln$E%DWtl_7F zlJ~uRB_m`eaDxFb7!&p3#{7)T8Z$KJh<^L>_t?U>;-X`i4?EI*^9%RopEGuY&Uxmo ztw`sbu4K17=Jt>NTDZbyCKa_)^#15;lR*FMe8-EXykD=NJkYO^md32MthOluzkBY! z{iW85-3ULqdG<$Ai&t9hf?-Z_0AGn=E7^{TR9_7m&H`a-gZmX%U$wa}pF3=hPwsz_ zeBXzUD$F(+cbB@( z9B7mC%4k|&@KJn4*rXc_vmxbPvYS86XlsWmnX;WABd#~VC4 zfL%s1j_&nUa`*B82G^C|fkaXUrr#D5y93814Cb(gX}VW2AyhV6KWueFM3`Q%h>+z( zXu>?{!eJo(LIF&2f7+fl1BS*enbrss5=;61YV;zEvp+1YH(tY#UxUifk?v}czM@U{ zm9iHJ7>OvLAUM>>=UOMIx!<9|D06t=f_dR;ZD|aU7+C;Tx|bpdASchswhHA#aEIp8hdl0Mi#A#tJD65gtu%V$Um4OTwmoH0rscP_sJ`Go} zrbMU#Kz9X9IR-%QEJ0r;^Kv?>>BwKdMQPyquWrqOxJfLIK~k-Mp_pK&h{c#3^@r#I zVUFnGpH8L{d75Vj1@c4n9b!WHYV)y7#sK&5N_^BOQyNdB*U4<1yaTjT@4tan@H7+ z)J!y#u&a3&zCaw8pskXoca)%|;v*s_I9yo`u5ReD-@?48;0<#dj36jaG?Ri+^z-)m zS>X4PR3IqYd|zfDNn}juQ_>53w5M>atPuDXVU#~CJwa)Z?AC^rT^&<%8fui6{PjbbxE4J9vibN@kBCCdA$4$`vXYmeaBV5M0b;RM;Y7RAtYKa-m+B2v(Y?czyU; zMruZzsNEkA2Js_ru}jMi7~*LK!_15;$A8+6wba!5e;iNL`ViA*gq62)(}FdFuCx%P z#XPMdXFfRSVw8az+50Kyb}hu75n$eQiZichc6m6``kGFVOIIZrtHAn>(BXmm{-aU zif9MW@>R1{$i6c@Ki_-~XZpAZ?y3dN7?Zslts~n+Z-xuqzS1YY(it8W!6oHLc#zo0 z$c+}_8D;qesMr9FzT*cgnyydSdC}M1hmmBdaL=rT7VszdRVU^SEZtfQ*2U2u(2&WV69!=;;N z^=u=7obcRN0t75tGqOv2S)61bVm%kB!cKAgOSk=xZsqM(VcbaZoYGR^t{#(|7t!p_8?}M-ZdGHcFp2Qn zHuTobpZIJDF$;@9e^#yg>B#nYw@7a~{|T^?hI54e8c*6rT#8$C2afFF7Mr~Sa-)mi z-neSBfkW#Ai@Ljfrb<5A7%T!8FD<1W-7>^~i3_KV4qDjjau1sPl9jTNT?O`T|B_3; znkVK_kd4b}4Et`i=^f{u-$$1b2lgIWETg}fBB!Kh^BKaGQ7ePoyR|3=IaZU;8C z!?eBwKi*+x*abLt5#qbZbGs}CyR6o`Z097`Zu#cp?qoVHXQcV2mii`9IGyLaeCxaX z$GZXyd#Kd1f@VrewwI;qmucwt(#B8hu9#rN-oHWm9J?>>K~C!Ees1F~+re`%AIV8> zkusBet&gCCRQ_=|ja4;-FLW~#$tL5aQ(ND+Uwxw{*f%F5TkjVP}2d4^B{wGFtKo8&cVy* zbr3}=HohL!i#hbk!(Ota)4*dAYFf<7BRepRE)5V&6F5XD+4e2;jCi`iIf&D_quURU zTqBO$QjgqAjy#%OJ^5!~;Zayu0Lh|0@n%IXq51Z-?W@h#k<#3pv$L&(b!Sk`R8YiR1Cnn+REfI3y z;^~m6>JwbheO#(!zrVG#_if?u z-{Rs=-`78Gug`7&^>gOi`ltQX@vXI)t(EbA?Tf!IzW>|$-&`Oa&i%75US9m4`{KXj z;+5IK#ksNNnf`w(i$6{;PW3HL^-|smEKK!GPK~WkcK$2$|8a8U?_PLzy!Z21`@hA- z@Bb|>{`kIa=KY(6k%q5r;ge&7W2BJ}qdk9@#l(?!|5+9jhq_0HdPW8)#6Mx6_phwD zeqgw@xA*U?xVN*lrIXOr(bCgiONopBE{lshy8js$H`X>aRM#{%WWDL6SpP|lZ`Vq% zuVkAx)>bUMyi{9LS^27@ytJsID6O=nnF9Tnlol5i<`op=Qk4If#pPK!IT@K**jG(~ zg;jrB|CF-$L4H+w#y^_kRHM0M^i0C}>=a5>OtJnGG^k_s=!Df6Kd1{xvan zarJWiufEvD`kJ$)jUz?*m%sh2L|ZjeUOrP!E>rG|x4zkbi;Hy(Ewl|S{_cyWeK4s?t60Nlv^dE&aPMHdZdOxIPI}sT@2+Wrei8 ziTb-QcBNs92~Uv`ubKMz&%Rh>%SGc{O=6cHb@gfNW>hBH{Sp0|lQhgh*PT-bZW$`S zOSsB<%E%i7)DW7^b3tQ5ni{@*C{@nLKXG3)3^8CTJ}beLaK$(rYJqHgv(O>}uZOqw z?~bCc(#l>8bdZ0b^^UI6{7;$W>%*_p^;ddie7~Yc-0a?wGtc-ubPR3}ixm6fkQSAj z_9!oJSR_7-?Xvs;#4zT$;lnIm z8vuUrUTZ`my;aiV`;JZlGIP zbqjPHG7iMU1H+{}LQNpcgCaB*D=WIGLdm6C#+S$&#pqY;;~qv$+zswJkFyTGloIG$ zOR{=46<2j`bBnB*#Q0f#jq=P+_S6dS)6JHD!T4&cF>ljG)?`FX_nN_chthyGa!dU~ zEzOry(rZ440ZLz-p>jvtY``SZ3ocmJRmdsH@yhg=?s2;Ank`tKk|88JY6ZA$;(ckA z?Z5YO#uv#I%6NHVifMb*NZ}Xs)G;=>>OX)anzCPs?|9N-=5l1ZwA~TayO2#ZO@UJ7 zB}E@!dTD>x^1tym zICHw9TFs!cn&w({x(2S*UjCRFapuQHx@)gVb74u{*SO3}@KKK3CKG8t#_rbXJUCR4V*J=v%|M2_oKP(r-KzUm6{~7vU++3JUax0P&vf{=q zvid2peJl+J672M@cQ$Wh-BjqtuIZ2yuOd18T%4d(Sxm0^5QJovScVN-FG{hMrh_P^ zpKNHKM$0?S=NWlE@~Y`IWn{f*VH9vLT_-evKitKfvmHGCiZ-}sVi=FYn^@fRn}{|F zxE<%{0=_k_3M43qix@pw>}tCbE6Fcn-K8+S&5e9#3}N7Fd7Kl^D~Sw2DF{w&#Dy%ySY^A@-DtjwH~Rg>Z^MnG_qaDo;<`C!mja!g$`RvL4Fx>2ZR}@lNq|HtpDT%W zTB?gt9&KVQ7ZmlRdG`^a4dw2a-h4#!?n5s95|lR2%=>JUHx#NW8TDKzM+heYTWNb2 zO^wJzdw=P>qB1I&W7@MCUO?t&mvp)ENF?rh8~rfWbJcH811$K$Fv0S$24%HU_~#Fy z&l%pM8fjE2NvDWxM_-8mKN8kuQX}1>VA5g8udZ&`OrjeByQ*j4!}BE5x-=4fFo!;zd*s!-VwW<%2#7JL$?OI8n_u1o@Aba~CEn zIP`l^D-0Aeio`b{!AbU$R$*up&LCb%o#Brc-QIL^L$!yOgzCnVE5ge`(Ro+tL}IGC z4vZa{qzyF0W4NwYVjeaWYyCo62M>GST#?s{_{ja%=&8H%vqw-@<~>sK!96D`?J~XJ z=|KEzsoJPYT+Em|zJmOXzL0*P@RESvj4-J2#W-dpm@*dfisgURUeP1si{78j&fQj7HAYx$`ns3VGHW|NZt-u> zzSU!7s;p!lX}9K=O55rEK)fsNs{M#+yL_)Ws+(`WO{ke>*IR|hng35+GKxboLWyUL zQQ?_f)u2nX2cKVTe3}9?8=E07oi==K%v#XhpYC&Z_dBYGGG1bKS5achFV~PgtzGy+ z-GlqGADvah*+g7)X+4+4bj;e4@6{zsPDOq8ITkd{u1g6k%84)&8M1@dr@b>>Q+#~^U>V`_L!rS+6N;uBY&xo*0yK6^SEFj}8|JiM;?mKNqj*N`I_L9gT^&-~58Fpptm zL;w5_5?)^r1wwo=w)-)bHmXE_N?3lD+}WT z-=yoBCaj#aw}1;5!Rwy~-b~4YLP8fH4ME4P?s*A;wh-=$d6PbY;0r2F`34<3FbyoCgR@W3 zX7pZ4>#x<;#!y|6AYZ59T*33z*6+>thSF%4xHe7<&M*ey8ON!4x=swB{b%shZqB@i zjs|jWn8W}HTh5EjkGtHdK``Fm9Nlhj7G7pEm41K2$XoVCoAqsFWlrH&`7%AV7({$+ zeLG45XP{h~cSK#&jwF}%3P>%+-5vkE{b>HY*%1)sDD!m3>_(sbvqjtmm>|t;N^{-e zXG9-M;pYy47t3bUr>VL@-@erR($csAB35T@jpOoegx28QF7|9Q7+sK$wJU&wyAcG5 zJ~G;I9yaqcpXG9YkXFoZ?^{2gh=SfB*hRDLoj^K zK!9?&4BUCI&YCe?o|cnh$Oq9dJp@`(JUfn_DVyIVCmmjV}` zb4*-LLfwEPs8|$&=qSCZ;e%1vu;d`-1Prx30QY3YZplNj0Jf?Ig7pEv^I^V(0=#pX z$9%xql-@DuG1^sUXiRX&l6#Zk*-{D6gMRYGz)v|KgkjO6M(j?T>-p|?*Xzi>qCc=) zrqlZ88-Uw-VJQzE(R2pd20Y5ZGv5=TW3P%Kf@nJ<86|)y zdFCo2LoyydmK#Zpz zPBvR{K($GBufL4H=LS+F>3-#&v%5V#n5L_3bXlOw5B6%m{E0&JeV%j$F^m}rVj$m$ zaQI%huWE!uS^Di$tun5p7)%m_7OVrEp-Q$$RT;zCcET%&$$^rvOaM8R%Wg;YsHhZ~ zd(3>~o->pRKX%WN>ZYo6g!{U}n8Db1H6RQPKSIGHe3+O5;Ku;`Au5gv3rNjUe=nB=At(<4_go-l6sE4iUUo!fGBUk1%<@!>z7v zOSy;e5MR!018Q?*3`2w4F)u`ROEb+u%V^9CM(sx!rA$0rhk?~c3O0l;_P*(hddz2O zoE-#VsSa|1n9F8yCQO_#S*rk(Q$T|{V6?+*MgUqEwf!xwYv#dd@(Ppu3-(DkIiZp- zfTZ48PKG5sFR6kJQ5ky;G`3KY_K0Bu!`wpPSwt~^M=^Ox=zPI2Pwuc~E<*U-tfo=S z`|@y&y-EQW5yL?iK4NiP4Z05pe*qFwsDbj;@pPG+m6aE?Bfy(Qh=W1kA?@SuHO#dl z)m`#b5@a;w7!ZBB%dCIM&}R-!R%Y696l!#Wg(>r7YB6ym$Vb2<4km{AGq)n67~1ImQtOs)8wdjf~88OX%6mm7~>qnMqbj~k?EN4OvXWHiI~ zo$8l768Fw=w(r0w=KgpP^G_cpQ{`qLkLogkA(aRzS@7f>mwKkn@|?4{u%O~$UKJGE z=39W2eL_G#Xd1Hv@wl~ntv^cMVSf1v?{N-zNo0<{R)4xvUHaE{25~If=r@Ro;22oOdk3D}H0U-whWrIc`T1*u_ z;0TK5otx%~W)gS_ZYMJTTo3H7WhUm2#H9VI~dy_p{`KY=X zNK{@seR6Z%hap1sop1wQhb~l$3?h|U0k+9;-p#StpY)Deu)2>*Csca1(IS78V!*m}XNJGj#%Eg|y04)+kt^rKne3-W! zVQd<}tzqCzCUAESa_QQ|(H{)od}^6}E4UHGE050)&au0d%PQ|McYXoL_COG-8<9sP zZ#r~T&*nc2Tu=s5P+;WZ-ApOqu@rE6!Ybv!t{{sDCif9l6h6?CAkDl8mMs;o3xKOV z!m9@S`z)va1AVyD2e!qmSg6*8PbwE3fOp@}S`9BeeV9Z-#wDkba(r5sM^wx|^<@!D zxXp>X%OZ((w$MFGIj!PB$H@koB3*^&hpr`cFof$ci4#G6{OTeuNJ`tc>|x+}Dp?X; z0vHfu8;gcIM*zd(vN`!}WkdzA#ma}C)cDEL=N8YiW&sGj^7zvK{Z(;Y+A~1j_iq z!&do55iQ6!6gBZFz~%_gmQR>E4=g)2$Rv=wK;Tc6h;!E#wsqQ~YF=w;ee4sScP8OB z@a07@%IsarFMu5C-Otn{!QYEc+~(BVgwkU#ph6yw@EILGMJIAtuB~eJCbV zekoY0hlU$w+A433&Z$XSF-LXfGku<7uKHyN)lzXZQ}+5OgE`Iq4#SA`r|c5Qks5Pk z?u@A5vZ$7OCzHM)P~4-gHC&PGztdh7$f#=rc~i{&x7vrA!Of@<9Jz5`&(q#`?(&_#gmy@uYo1jKbM&?;P; z(g4PNU=s41ei774PZ&-Y=nJ+XWIS!YVJry^5BoeDF$!1`7)Hf>It_f>eJZ47fu@QL zx?5FV*EAkw&Xvmow>wN3U$ax?o1ICT?()e;!FhkQ`{YKT8HBmdE19$Mu7LxI0cq+g1bOBBx zGDK!zNqa8;@sQD=Vkk_;dN@?_msmJTWF@Im|ga}t*cpp zaXi9T4iInzC}00}-(6U2I1Uuh)9l<}J(xiHuIMl_80L;cJG(YJ5dN2eCxKcnZ(u&L z8h)RaCAChJwY~4Y1(F{yUa3UL$9!b!r1JYg_x6m|=SRyU`zLyWCkX5*>z+RY9s$0D z;L1JW#nLxOYdu%p8}>gq=ftqH4OD$sQsf`!!u}GYT4Y=)gllT8h^ZR{oxn*aZh?&J z*+8}fvWMLK6JA(G5_TiJ*Q5jJjqxm8#J&>wQ;`IEzIgPv?-~`)kS4%#dCj6BopC()=HNarV6vx>e&4ckh}| zt}AOg2)Pno)J)m3B>F6y#}1d}1}41?r${U6Gi_dMmUUfsui++lnN_6)Td^*ckpK-9 z)$2_kU7NaFw)y@#m@6|ksIlpkzPRd2jsKQl`Y)ohs+`P99C4-gz4`+8B)db-0 zeSE+e0|sn#siTqZ21k$X2I&p~DHU{sF-CWYpmc*YNJ)2xgmfqt0wRL7XTSUV-RIut z-Y3p^_>*%uXNSY#EWWSLn+GbtK13WEu6-xCPE0C(>9u1ghs@qj61*LsFZc#57>qNg}Dyr|?h0 z&gR@rnoKO}rTt9K&G$xM>2p`nHgkR((Yp1dPFDpUS1?N-JPrdDa;0iiwyokY!Nq{m zvc)>qTKa^xn1{|hbzONw68hp}+%40IvyzfC0(Rrz=;Au3aOq?x^vp8j_b;oMTFnf&)Qy6_$aXs0ii&lM%YEw-+hP=Ye z%t$kI8c9JhS7RFcLEOS7{%wGzoylTGovw5Dipa5H*CDMW&*!$%?|u$btiHp(8FhaX zVlPF=`_jZW;&E+ldNC?Ilm@=_8K@fl`aipNRdwHo=@q7)gk~QWvpdR_v~K#`g(2*r_EAf{mL$-RAf%LMPC1J`43et zPH7aCFz%mrD|l9Ez^Oul0S! zBR8?*KRI7wgkTz+M?l(38S*XuE*1>l>6` zXB--OxM%LX_WC3t-C1yfTQ#C2N(|^#`}chymoM|X+lgN(51Y(ABS7g^OaZf#)AgK=J0*&^5&6S!(os zm)$%S1_6An{%Q0eoISnj$3V+pbTmJ+lHSA1%JG0K6 zoQrklV-YnIrwD&?f2>-T5xA+WJ~~hkrzSplkTbTYRxgC8L8Gs=S{l{ogTn1>cH@dPLc*!VCE+GDXb5-3qZdQ>oM#g+j zVccBz2Mr4m=OkPzLv&pJ5ou3&UM)lkk?g#QiWq~J8MXlQ-_^>-4bcNwavqALwr z-`94yAa}MNqR$o^Y5pz6|M+=xENAb#G{5nM$_V-jSp$}Hb1#zuwef877H^|i-A41f zLseS!{DQAOu%D5CFJ|QQDk~FTspehD`WwUa@VUZld6*Yd82Lxzc+*)i@rEE523_mh zNXyn>&)PSppYWRubss{$ml{N+i|^5{{;nTu@E@U)EFD?>eNERm>n!*h{K$H=nY#=h z=ufyWE*)nYIL})g9)di}g#OaG)HD=&ZlSDb8(ocsr><8^-O}5b?qN_tizOf)!oUgr z5)phhek9&+*~6RPAl`@x6V7YIYju`XI(m~M?LWQ!VLlW}A776E>$X2J&3W~dXiXDu zmJilCcm;jRu0TV}6(53bt?d;tK}D}Z2g2a{{@`FHm-xg2X_;ex$YYlK8h_sK^>R}L z01w#GUkGrM3?LfiNzDuXJ~r=WTwG8e{N+gDcv?&HG$6Kc$qBwi9Uj^&l6A9`T-M8c zXt0wmDCeyib;mgUXDBYxNQkXSDPmN1^lUCG&-LdzbA9yD*}KKYgV6@LaZy`5CN$9X zkW2QJTart2W_evBqtW{0Vw3uVhDav(z4fV`g!9}H`#OPC8<$@9&yF*{o5fzTsCw}? z8h?YkV*A%;MD&Eze`*ydA5_eBTubVlf6kKFS)a$LMLV;+JyMt5F!c|+=ur5z1J&MG zOpd-Nm+t+b==rlE_T5Fjzzv@+jt>>jdE18d&&W%UrG@0^z_TIwKDJY&qiwS;1@7*4 zqtJ_PD)RS;GFZAG^&#CGI&8c=v1SuN$)e(N;k1H)h^_O|uI^qcv_@{_z^okwzMe(D-bj|HkN@SMe986`1c zn*t5_WfSWB3LUcT2D6aZbm#Sc5zf;s*$4r(B^Sz=2;vX4KCwZ*aVSgX7bP+_kCW9| z*~^aZK0o#DTM|g5bls*|NT;ebfkjffIxOBCpCvs<;2^(56gU++4zxX|kNLBuU*Lu^ z9>a>6%HC6Yce=M0oU;pD!|%SxOjR7Yn38jV8;66>%TzLI=rq=?n6&&_{zCUvVyTMr z6{yC9)1G9xg6&eS?b$uf(bK;_bE@8*rChwk^(z-&Z9fRPEdnW}#2jWdVTZSlQ$2t~ z&_FJ_QsGeN52o*S$!^C{U|{iEKi|Szwtv_PvB6SkfIAzL-8AG91YfvwRAju_jgZ?( z@}MW7e{$y>r>D;n88t}fs2qm?h(JbVhad9s;0$;CP1BcuZ3o-|i*9dyO|p+E(~&?* z={r-*Sd||vKD{6;Nu~LLW3GOXjou{W@R-K(Bos6=Y}jzmN^v%dcQU=loLZdf?U}kug7r zv*)$57Y6F3M&UXr7O%!Kj8X=G1i4k*PhyB^pFz9IW(krFmx-D*u)ql55Xz}dO;Hv>LINfzXzaR7-z5s z6|gGRM>)mobzGxNI(S5@MT3PN3y2_gvG#)u>!F{xbfWCA0)t;6Vk z4FhgLuO+@8ais$y}qV9(yce%l=+#q>&koNrGg|)iKPYp2bm^U3*SO;h|U%U2` z+8YPdW!A)<(k(qKN;Si*vw_3)vvoda$Jyud*{RG)+;5_;R3j9fnO^<~3 zv4C|Wx@uS^l+`Cz*w`|JaOpz0TqUsXT1yN&E{7ZZ43n0oM9~zZmMDe0U8g27JoqSt z%i))(;uMFcRHHILL&6+nico)V-0GVoRbmd7Q_>Z@=s_;)>PQURp(kUHQFk^q)RK}T z+4aN^bYqP*O}#WEB8UGxn(8S??6k)@ZfdwJ>&XUBX~<7u!2oYRO$i`K*%~zso$TMt z9Lr+pbHmYBsmjx9^_L|zW2OxR^$CBm-pk`$`f4JdrWt-u$E9gMoK_n}v@KmoOorgZ z*wt$ek*{`D*M>7hne`2I4Dh&9-G^mEmo~t=3kDN)$n{7ZBu!V|9IMKmNOf$$X#>nz zFsR64IszJMg=iqzDTu33RB+TiF4+b%oaQm}R>;$xEF4q}=+vrq;5wCw0!TLkZ3!dk z^F{&lAlqHGgo1Q#=zPpoiltoVk{wRd3HIII=nDpHaS_|qI{14?F9SuSH*OTLhW)cS zN3~+Cw>y0cEgEl+!8scrVi?Ji!LK1&hM&Q7MWi%G^DN~iwkY&1SYxyk8O{% zJ>%4>9ghRxZRd^o+?QC&NolUqv+3kTzD#JY<(3+=SB#q}krr31nU!2Ek*ANuvY5q# z2RB*=eLf?xy8vGQCG8a>e=#)wx=H-0sk5;zh{{Aw*jyr6z0A)b76;IdUDnxU#p>w27K zmNBOr=pKAE*nP?Di0)Gaql+e600TK=+n`@3_F>y9Z+*1#(>w4ZK$yQ(cs&?wFpVl- z#Yg)u`WKO67(kzZrqY5eacwwgAn=M?4b8I_y@fT;zT*rfeLQ1u|I8`_H|i7!k_f^2 zo`MpN<`I%~pO8i%ck8eRHiWfP|4yu5ntDe0ntz&(bW;lH(dx|ES_005>N}{k+~!%E zRb)BcCovOvti&R@Z3^6?q|G*7cwJ@-d#1mBE7U@H^J!z$TE-T(CVMDf*^aMpIg50u za;vZ^3Ji`gzt@R; zEbmoeheJR^{);`m_A@tby>tdGLI#3IHt_6OiQdK1syO=_+i5u4o&I^z z88UjyZ`mJ?BNuU5(#+~5-2nx#RQc`m(-Zj`%>>viOLpi zSW6v$dO^#58r=h7%f+96wqRKMa%C5o4!`%fav~0L@96=k=75(PrQNuPM%evTS|x!g z*qeh1cm8q4>Bquu0F^_HO(LXmtP$458RfFKWt^zF%i%1Wg3G>~aiiUElPyDOBS|e# zK#E;dI=dC?8)N@nHW(^HTh%xkCGK6-9h*o0*Z&Ck@QB}@#N0U6oH<669RL$UGeFTQ zBAIvQfjR*==4-IE&O24j1NWQ(!@q~pVANqOG@c%ZVF&k-7uKRVG{x{>5DFXt^uz*TUM>R8o@aqLX8BZZkR#RA4nCLYSQ>>%NO>27r6r6-q^G&^ zJRZCvIyTfIMIzn{V`=G1-C~iil6i4m{H~|p-!t9yAWL(%l|f5Y&}AHWV2_X08k%_S zzVmqeE^+jO4a=e1-}hEnA|uOKZ8%E3JzG!fBRbHo>w!CQl{XTFHV|R7H1xpbd{CeU zBxsSETgOnLCrIU)FfX9kFgD}vyNf&(bQ;JY zBT=EiN9f(M8M`kM89V>jXXJ!>nGy6hEMruLkY*=+YZme;;W3Z`aP0XxB_u*Nnt%Jo zf`8FFw>9jiXE#sorhhzQ1aGl;sz?#7S(2I~KObwQ-cM^k$Vt=@H{5!+n-Y73-aeVE z_;Ld0kD>*y6fMF63?1$`+D;)3z^ru^vA&ClY3tBAIWdM00X{gAAh2Y z%lTj#Kzr_1NwCJ|-b|++U*A7xaXQ`%FlSzB@In?+x))9<#hGSj8oo)$d?2`1EZe%)$?02QLS;PNGG^d}o}%cO5CG`BbXS<5 z@jfOkeLI%S1-_~=PXS~Kgwu(Cj?g8?Izmacy@2oJQlV*~iy5gVG?_Q}&mZp49TBqZ z650t@_pC(0qO#!F)D*BX*c}WqIsGUc6DD-~J74ORvI&u8#Oripl}<`aG}r@&`n7+m z9w&lzyt=D*hl=^?`pexIeycXSOi>>OkZ&8#YQXKO7$(Lf!5A8@{`P_SD}d$`Uvn$^ zdoL0bUsJVH#V_8I;)wqt9^{MvgY})#%u+&-rMDz`lKV}A(HBBk$=Kg-p})NOyoK>a z-=Ke%9Am#`Mp8H(7$P&*BR$%6024)EMQ(qE z;At*owPlH|>)`D-bwFkE0`BQru?AZvEVFf3-S7+I8^!*gE`>KcNu|LWTvjKs()=7} zn%}*~w)%NO@eJHT)ap?`*8DA+?{@rEzFIDhhdfqA+_k~3r4G7$7! zLAxd33+tz(Rf%F+vP%&TjNJyL8k z`>lw-f)7OW72VvUjVQV9{ZaaPLGrZ5sOo8pZeMC$dv3v)v^d)6q=AvQMg>LGXSog< zqzA(x4_CApyoj~Jb`S|}B{;Xi>~Je_MfpySxRUkIyTE*9;v11d^(GE+ajN6CT*O37 zOd8kagrWbSWE9Zs^BM0T^Rv(jTD`PsKDFe8reN+29o=?)vcSUj>BpM7@;sJY!^Xz$ zB|OXwc*k~wRZ}nX1bI`JdzugS^1N%jm)+9_=3UJTN#he7`5GRqCe;1mgYXBq7cm-z zQz#rG6~Gt_BBWSzfI9HJ4W6c!LPSy=eDuNgsqOdMNfFr(e|jTtQIvX_@Oo9i3(cx& zw{m@xf{3bu90Y8^Q~mC>V#1?cf-mXZbJh zL}_ywG|;-;!X3=XyEmI3-c}57td{Y8TT`H%__=JW>(RV7qsI|j!`F>pB4k6d?K!R9>-u>{t(b=xn3SfG3bO3H>nk~@{L4NFYiLvTWlobVO3GuKJY-3&0Y%?x z=E^dCyLri)|= z$*0$Fe)~su7j1T-tyTwi9eYbrTzsI$nBrjG8?C2ueP}2;9IufB9{j471m+Ic#s)u6 zvps*z{m``PR{775gGq++pSill6~DC5(8p=|3AJ8n+z1hnHmudWsdzR*`FsNT_>Ksj z#v@j|(uMRAN7||mq;>yRU0|G&zA>G2!x>dq7V z?xd9bQsUR8*LU#VQ=O7JsMXg*v{3I#jt%5pw=QCdMl^LK9LNQ(VG^d{W|Vjal&l)C z9--nR-h_kI+^^uE{&YPa_G8r2_ zjl6lQVqC|RmRIefnEV9-nS_CR#no{W&L&_Se@j?q^J4EB(xVbJOtTvBk?vYPR~Wy| zLB{shasgxRbVF9!oW9@X8s?obcC<@5UH0P@I1U{riI%4%Kzfk+8%f&+*Fd|8$A|AC$KPKp(aS2&8v#$gz_7-mPRjWd^ZnF^8s^1 zkC`W_OLV5~+zv8H<=se?1(sSg)i?s6pqs!9u(LG{9}#qc)nhNItzWNHQn_Y}P%fEf z01A=s6(X6{)3V49q6Ru|nYQ?}A;3f4@xM}3hclovy(e7pCZl*!-Lu4pr0SG)l9P6c zw5!F_*$oX#HT(lD*<0cw+&8S@s*j6BduZET+G-0``CH9n%H4m4uuomt?8Tr_J4RXHOGd_C@)QShb5u zo>#sceBW;bQ7&u(K+N1BykMm(wwvYAgTX%UgnPW+&|vK&F+@=a<(p& zGDJ(2s|$ZL$?RILP?4@NtN&=x(zVj?Sh~(t_>;|2R{);@GSAoGo$OA^EQbzek($%g z!HjieSmjbX=?07evJpsf9aC7Xovz3AXn9g*9L->ol7WT~4h!)XNO7vh+ZmPdW*uvm z)G8nPGHEnfYk^PbyP<5gcFUhta3@ZB_nhVI;LFdE6`u-s9&sHG5HraQ(72q&92W0U zy#%8jB2Phln{Z0e@jgE4PYFzi`*Vz1QazkOu}F31uWvdZ%Ns&d9q+-9*IL!G989u& zmA1gn0yDJ+CozW#@7n@8OJlzTs*wW!m4TS~X9nWO|2NZm|KFI_{(om$SO3nmPXAY? zb@_4QKQ$o!JJb3X`M0xK&q*hmF zYiCTk2|Y@{o#r70HYWaj4PWM*X&8W8^-Yt2Ne5f)oV+-}BVw$glo4tW{)#PEq}@SS!>&FoY*K$>QIomXCjsyO;mJXCOSR?f;R1(7fwc zt1VwB{x6_qX5~mwTaOUhM&|bVCN@X|OATE!HKYkb%Sc7TNJ&j!QB{v%v}EoW{F7

q)vvnF4^y}U- ztFfPGE}zO3bDb>s52khBsq;A^hT?{9Yt=$2GE=}IA&Y6~h2X(y{-hpksn)v1XKS+U zlR>cAGYiSQ@mibMaEgo=-qUAuErAFB#w4B;IU_69PUqn_{=y))BaqWS%u4zXOM4P0K|o!+Ax_*GJpSe%bM0^+rN zWsOtzcKTx|E4_3%>=O8?6r>|&i&~ql1ig82%@G4*)MM0#i-8vdqa-j&e9{+rm-FbU zmuz)!^7*dzP7kJDIG(olFOyGbV^pBss=-k=#?ny4Uj}cfB|_aM5Svgp2g#!P5GP5% z%@OJ-W{)Zk#{`~=dC`sR+HN9wd8MQLOPxkcWj`%!RY(B31pDDfRLAwszh{9Wj#|Xl96;awdre(6HLJuL`4o*GzmJ_qqGj1N_FkR9W!EVCC+k`KQwXtq{wln`PE5qz0a5ZSQ5W-XMZ> zTSZh)Mg`A?Bh|ir8tDntU1*dFeUuZ$RW5&kh?;hDX}smG6QDX|sCzagHb%xjDb%Zw zHb!yHxKK!9pnKmSTgdOGD$&sGclxX}8pm4Xdccnz;@ZOB18XSCz*5F$%YmiT76S8& zblDT4M$1aSygDg(IzFw+OK%xJ1f40Ry$wx}P3tuyWFYKq`0%5QQX;h&&H<|W8|eeY zK?QVjPqf(=N)z#&w04-%WaBha*sCA!3dXX1^-?IMWHKazTY22+g0@Gra z<{?i&f%S`snIfQ8dC6#KQW200%xZL&3SY@D0?CdKgzwea-+&Z@wL2?mGEOo4`g@W3 zz&i|Gr?Fy5#Sl;A5bMS%R&KhOI(&TS=FihO1f&Ftk3$Y~vYz3P`X#ivv zU{-^gcX@(HdA~ZoU^Wx^fqUJMJpGFf_Y*TWcgYIzER*K4SSk&7Q}YLO^Qf_a1a5W{ zzgOw65h7U!3p_><^35J%E&jzmZt{KFu9w6P*du6yrw^3&sj zVH9Eejo465DOR7n=m%sR9;yKc31elx%EUH|2hZJ8q|^DiBAlk=$VO@xFOp^J=QkB^ zluQO`g_Mw_Ye`ke*0zt6D7mwl3o2|t3Wb5<#1z_s$DSz%K;p-H0yc6vdlbK=L>ao97&bv!gjrIrszQ z`5Ne;K|eW)m~Rd>R@3*afpwynK|EpiJ=I2k=6r7b^n3>8j=5Aw>(ivk4Gjg$Q(vrk zKrP`9XnA#?U!>{!PlWIBJ0MwHETi!SGD)}xOQLnd3&cE!rKHZeGRf*`x`kmv;rr^b zv)`tF1YXvW4tROlJp=FVlX8SZD-b=5V$W5|gg)EOqls&vs>_$j!BwLj6$?)*l<&g_ zEyf?!YQhgVH58A$j3@GZq3;ENkBu`=Lg>!#qUj@)5(!74tAq{`ahM92udf=-D3?b6XucPc6nh?zGMjsUP-#EzGnWi>9>_IBWyP*LNf+ zj**so-e{h|`N4vna5z`LK5-KpI<>0X)!Fb(6H|4XV3A_-wGj|nJe#t_0i8x7uzfJD zSi+<9$kwb#DQsMkx>obLsSeMQ|8_$)!EZs3?oj{o@K`lF44U!L(S+&(Qq1SC@ z)|!_EP1j6q)w<8Nq&h7sps9B*RHgPx?941@5}MU`gtD0$m&0yAhG80-4Ml$R^_*)O z2jN(*Pcfe1*9xD)Z7H18hjg18&z<2+h>W#7GNz*k(S$R z6U0V=Qeb@3c89+BseP*`^#jfFrc{G~Pc}@P2O=F^-!Cc58cAEJbbfTb|I@6TMH@h$ zF5CNK=Ii5MzjgpLo&98nr_pS`cfm%TgG{rhSjFFa(A3UhK10Il+wXnN>%kD|l(Q5{ zEt-d?o#Wbu=NZp>He>M2!xL7s=l`HrannOt&W7Le-~N6lH}`5beD=ODsEDEt{E&fo z{#!{05P&pN05D4c{k+uK)*}>Tu)FuDnYToA=epFeX~|W0{(Nw#eE9nHZglMw&nGW! zB%pEc`^%UcY#L9VvL^|^xTS_pZo-`)b@NHAd4GhwXd(e>a3CMynf_yI%v&b>g@Dlf zSIXAz75p|sxhDerSZ@MSL4THg2XO$PqZmp+?C6 z;r?EBzV4OP#eer(i-!9_onV|^q8G^ITErD--?8a^_J)uu;^<%;!Ih@XBh@ zqKd29e<}6m-0+Lw{YW?Y0Rq{=N>Zyuc`%nU5AtjBQ}2=Sect`cfh4(naTkOhMtqG{ z1y3RTKqdf?HDKYCrq30nilD*I6APXxg_Avgim?DXqa*i$$xz71JapCxGAQ=M5K0Ux z3I#QV`M(ca2ZU2xJVB>ZW^|h8JJ22j27TPBN6DAxpYtFAw&HT%00*k z6p|{2VTMNVdO_`Tqm6T^3pKThg$2bvXo)3wphW`raMC00bclJ!#)^+6 zbLF7v(4v0{peBW5XN&<1V$?63$h~mT_(rByZvJy8s=87zfS5XT9=lhm^HUYP#4Di{ z3@)EXQ=l>Bfne(5ILO(3)iDb74p_7t)aFVAlV{U}7ARe2?{{Z-Z4B1X)W^Z7;*H7Q z1>PlFh!tBvMFht8m;vhH)Ue%nB^>nCsmYrowl#C;owbCg+;)4XREYp;$M0;xYfxQW z94#zDk%(06ei8^KrhhKH3+41x)89lTvj+u0VN?@Ns5~UeH#nFSkpf$Y-6N)YUzFTF zm=aK>H%OxQS{(DS5;`pgDV~RLI5CCEiUVx!R=$BaT)|n2O+t8JHFyvVBSs?yNbhNZ zEI6SU$rB#J_`dT)zuhma zEC+u|!S7^y4JUKG{>S+?Ckh%G=(%T1UI?T1%W(#$XFb!PI+vq{HG4+Fh@TiI^2TQf zu&~RCWsef4$v(}NScgbm``Db(WL?wD7(ZoiglFqKdEZGIJo{4ApdCDj#k<|RNs5DA^5x5x#wF%~n zD^F*C3N5`heCNh=`zdt9m_nUjYi!&i0YD9mkbJ(Mguz3TgUmR|IWq*Cz=diV=6>vWncXtp!$n|_Z(IM*(UtnOInyy)3o7(~k&D#|K46v5ph zkNEpQC-Ib$X`gY)n=v^MI=!1EIs|gpF1^hKZW<`j3NC$$VZP!hw&jQ-HGw2UpV5^* z6t>}(rhvt*P+wt%^b>SHRWYPOONmVigImjq=qnW81Azk2^$Gcecn%*QWj|KTee+84 zpiIehZ({LyQfIxd&Q#B?X>5yV`v&x;P+sBqpUCsmDhXz$k)qV57!s|LO5JoY4-c69 zoLVx?WX2dAAy)HvfvQxYCi4d@UI9u6rD<5MN-q;X$fXb3fJ~z*A~4lzumD0|B}=;G z>jczy4O;8t^h1pJ&vkkpkh<4}BDsxTT%i0BFpXmaVrE(l;@~g6$i6*LOL|6q@vYV` zrx*mIya*)Q38cx+pxj5$d;w5NA)qgJsV|^ZgQdE!(zv#CXwCuDxZU)VJe_soa-?d} zk8y2LZ|a;hrWX&NAMW1ngHe_KtR6|H9K3HKv{%2O!TEld!qJ=Rn=#FgeyT{P7eE;0 zwG;IVD3}Eek-nrl5+fq`9xDs*D|{eFjRv(;H}Dz-!5D+<#rPU2bdH?l)@tb0HX!Av z+M*9^k7VgKH{iqr^?#zFvCtZ(N6q>DWZ3}fYlL-EnhOXjg4FkUh_;$vt&39Nlw0g5}N zx>Ri;@U;gn425nK`)OE%BAU4%Vlwg8Gz=Mxv&pt8pH-@IK(!v2&KKdt@ZLrAI6feO zC~l?|8Wa!hIi=gT@xIW*W{B9L)B`=(_QSrJv~IGd?%ubMcRnv#0W=%dud+>Fv45KgNlFyB0zoQ2Aa%)mkuMPr8Lha!M{=(PvwpVRC@j&|<-Pbz{gvZ)XMFa*BfhDc9gVHEB9J-I+RFS zduVhcWrQGfF_7A(yI}^dL|F&xVP$y~Sc4XTE}!ym50EVuk)uzIuAB_vLWEx&O%ELW z(wN!>Okt%7mQD1VKn>2!lZ&wNf88BL>U7);BIvL1h)Au%V&9U?0Z=+@os#a30Q4Tk z@V*`thEJp9cIkRRSPEZkODpys$*QLeLTGmbmv^bJ;WSHPg^oQApN(l&`hj_1%CE)* z1l%@2PSc=BMGzSu8!3bJpklviEgx!``tr>{!JiO~_ECSJ zR}_ma1AY5=M>J-(sdP3Wi*4~A9+d2j(+t@H^|m72wi5DcQ~swP^i>ax%0VkccCMJV zTGXU)`gERKV>U8s!X=R0jlnaomzoA3<^xa9&LueML zlk(J<$V?Ebt4wE5PfK`xy?{b%s!r?Lsn^&sg?54OEKpx_CTLCL+7GzrYG|{?RLD4p z|ICw<<$>|2+m6C?lsCv?5TwH5Z|tOa5*x`Wmk~3S-Kr zv`B`Y&Qp3@0~$|hex?_*`7F)U(X}V*a-5cQ+9FM;p6(v-QrWJCNkbpt!;7iUvSaL_ z%}zAgDB^ek&E%iwG0Jb}3h6#8nUT$?^Ka1w6|GSOZQUO<`^?5l9mHz%77{_eIiOEl zqSi*bOEfi4gGbQ#dFy?lqNAh&9|%KPg>iCe<)=q3rVq#8^e&MMRNiZL5h2=!1fe9M zWL(hPI9(|0FRj?;XbDK6HUetZ4IQ!Gv2~;FSP^09qa%B!?ijg!U)Hy9JD{H z0qX}LjOhpd!qoe;@qJo(r?afi#E`@A)VDB_*HBREns@7>g2}jtt;SFTz29yWiBu#K z8m?OW*-=V3sgG`j{0o8`Cmp~@v?IS64kR&tYs>LT9uK5?S0t%)zg59`vEvKvK=>I6 znnVylBBu>{foa3ytDYiCA#GXzG!iO6DI;6H6VI# z(yIYrj(6w#bkGZ8HWXp8<NSMu=bwsKyw247P{O$aGo1{bEsb`{%bzjnww*Wt_DS+C36go z>!%~P)b75N#e5AcGUYxN4J7E&>XuJRCiB#IgKm$;97#C?6T*I zkLhpoH)^v*om578)1S)&_}^T^f16xyS-<#h9db=#ehpao7t_+n`!7uE?ywiEpx@^W zP)jn`#H~e@%iy`jQ_~~e9ASsP$g5Z?{d{SE-Qgg!_lAiLz{|afc^%^t&1BsI`ESRj z1g51@hy#8!FRVW?9?7@(gskTMcDT-J`I*49X3ifxL>5W5_-|4FKDQJZV!r=nd*oS% zGkmA2td&0v`wtAmvZ`mK+KRudxv2**zALJRiD96tN$x4T7Yj4TA*LU%co2EqDwd0lk zUYNQNnAQcPKNG0Ys7iJVGtWV4;378I@v&JEit*d-T-xpUo`C-wtE&a2A$eu+;O z1@=RG9g3nCbw%ko&-KI^5?qVIpMMP2e?Dm5GIL(FQ2$gJl>eK;X?rCpHucT0yE;yl*jvp~K)-;`4*`_QM7oYn4A#>A z#agTjnq%z#-w*ri?#~C@T?|?&{<(j=dOOs?x!SXXk+seTpZmQh@=4+SHCiGYLl?bV zwusGKS=^5&_dHb^Md6-{*T*lP=)U8uAM1N0Xuv{$-D+`20{yz0EXf`htMdAf4bwvJ z)3E#|4bvZAE6vk9DE<=87WH9ZIh8EhlN~G19d)bc@ zF{>-ROTzBTy3(m7L*eG)PheU{5jSLdf>Ofusd&ZE+A5a|sZZQ!8HwbP{gJV0aT;!% z46l$&;EeRt>9ljWybjq!N=C^-3{bRM@R$my5^;U#pyr)xl2Dczx8Wuri@})HEM~vN zxC^<<>)F0p%;^{|7rOCO@9t#=$18XoVpv?wk+DVk5kE74bg;TQYbbASnOt#G2I?Y% zr^`<=uK={1%g16|;b(&5bWFiyffPWkuUDKJ1@dVQjioHp?Bk+BL|ifa>M$7j#P1x= z6u|bk{MnEDmeCPu!iA+Q3vys(SdBiq;1oy9K_;!=q~hBe%|vJ8SpjrOC@ODZ8ThRu zy-Bp-G2g<`^@?9RsTrp^%t6iZXm^59JS8N_6}>euAOg!82s3XI`U?19FtkTF^`^VW zX7N6NIyf7h<)v}KhEo(YZGRFri?LzhS4}w<+s1H}l71jnpBx>&>~XzEWmBpBY+xA; zY+@x9T*_hPOnymGmakdusQT? zJ?hMmu@+OdRGPvwPJGXrI+%N~b8JP>XumPezK81-;gz=9?>)#z%OA``U@gM?NpUxX z;4)+pF~ZG+;Br!K&yn&=;avoZ!J$pq&Z5RjQq3|tPr7=>>9Y&@xn;DuIJ;4nz;Ok6 zcBzL@JMo#eWKFjdNV1f0el<+^PfE1Fj-p*de0?BYw|C|eLknG-r;nmwc+cpDk=RJa zA5Nw`LYyvNxONvrHI{nhMBY&V>iJ5SVOTyEPr0mM7Zs@(Td>zOkJ=AqQo43y0A>xcAc zR&Le{g-P&Ns6>sHU*Mb=GM&`Hjf|3uKIJq9Dsh?%Fy>@4c^+Ig@ykmW0#|oeay zBQHvZXi*+_-fpqBj}TQ9j%sQguq{B1+P@cm0bu&cpG0W9#3!o;L|d&g55hG)@6`HL z8t-q>+z}Og7c~}TrSz6~0MOBUBgqBVy?fXf5Z2L60---5Ps4V0?}!Ec1<$E5c3i3c z{PR^i&4rl+FZYUO)@CjM#tZESO`3^(@NTDF@~Ufm3W}5C`S^FN$I+e}Jb%SCeR9@M*TuZ9*;)dlMHO+~++PEn?f+Se z@O#O<+I`ZtEa-UXa_cSmL__rZIO@3S>wA2a?c=3LFTDO@?luqA{8h(L??W}V1J=!5 ztZWa*FHganKKBCRISXuITe4i#RRW7!$;*!bn{Mv_Omb)Ozabv%cdoZlzvf$5sCgKy>q}iX4QAZrr_t)nO_as2Bc}s7l!WgqQy#moU&rT zn7V4=*ecoifqIV!dMR6=CvDM{tNe*;0su*r-y&adaOdOs>tf&fe0eyUSty2;?TJsy zqiDW*ACR{-P){t*SPvJrMp~l_)I81|q=ord1EqX3n9ehPK1-;0)K&HNb^igjxK!~| z-ksM747(3jxF`7sGg!Jqy$fkI}TD*SdVG zWw)sL4A*P=Thk{?Vna~d{^MxQu2R^=h&5z1PEf)7k#)NEpF;4o=eft24V;Hwj6F%OyWxi=@G`C1bEEtY;!lc{h z-XF&Ku|?Yof&Ibbo^})SsJ0j!w)adm#tAsXuO*n6Q{aY6pd-4R!lJE__EnlCOCUQ0 zdZ`K#X8porTo>bnadFa(3et@OD9TlhwCYcIL=2y+VTdmvnpHq0V@!jPq}hDs(@i}z z#}wMDhpMyD12Eajj?-BJ(fAJRL`;tlb7(mw7LL;tB4?DmK^7tLE3M>f)8&0q;1f!K zXk)CS5U#{ER<=Ng&t=~>I*B3Du_iU2NB1nHmJ1aD3$saQx~20l7HPom!1?di zldFx!Sp&w22Xh3eAp=*2-dK2X+a$`@*a8^~_E%!e9uKG2OL<`OEelBa5i%#kZ=G}D z%hkW_jsGSYGEgm^TTkZuEtK4z17%~7MGFkdsT_m|-0eAO1gQlM2zM|&wbpH%HhsQs zgiJHR^VI7fSnKu*nMsBkGOrnfLuUn}%!ET{We^LZ^=2Fvjf(Xw@5@lg2xDo7rG0?W z;ilFZ#_Yt7L}qip6EQp@U8)IwWhYw>K_g&1TTk*+dftjL_pUx^F_ zq>sgrYNj?-&zn1BZ!gW0)thbrX<+3mNgT?Snz0rr3;?zAt+Dqm&jKWLo<-Qwl>wa2 zj^ySy#Z4#@qcA$gv4m$+-y-^Nr6kn;PrHG5}iELs6X>> zI^jxkwdr{)dG+)+j!n$hmY+~teBM=YGz6=FFTqGuPxpCX<KTc41_f#y+E zhiC%f-T;K^eC04xe$FhsAF}92s~JdhEdn&ho;tk&Y7GIkFIl&JNO;be0c^f4(H=$} z9ZAdwgon)`8%^MLlW}gOJ~pIZU8B;Lsu+W<(m%1VVT=Q=zqk)uIOpXrog-Z;zuUN( zQ4)_bL_wslz22po>${#|tram4pOmh(^cX>?!dT&TnUiyeZA9+O>xB_ZaFH22UQErr zV_vo-(PCOjW9t@V{`KpUgd3nCe)%EsymonGLt!Hu1ogDGd_5LY@9LWvI@k{n|>NM^4XK7Ifp*e zpK{U2qN9;9Ki>TCGG0M#%3NyIl4a%O`pRsW!0qgq@#Zn`8N->U?c7nh7KVb)Kc+#; zUc-I`-^lQ`#9}TaHPh(U4t9|x62x(q(jSk~vs=|BZgMu6v@Nkyo|`}TV5gsG2lGk> z&faB-K&{&_9+fy;GB0{K*{lK+rMx2VHLKxECD+6`lc}1gE&6XC?u?XU>>n|%OGyzE zLOl2gRM%z#%@ay??ODaMB&A%lQHuw^P>A1#WO_t)2hI7=hcOfP)-|rsv7u3RjrLzu zRW>GQfT1x$uQs^H5X$0{u50TKlZ#R;PA66O9rYeGGCFc`t?M1lau4v!gfnD(-H6Kg zWHOCWa<={Izw!kV6;50pkPr0{G>!raf;=LNP(m?w_Zq7#X+V}IMr6X52{y}4=vAS- z`9Z|aV5IK)imI_d*d4?L^0D*w4S7^RC@LUrd#?nv(+CO+X@G!`k%##DWY_MWOzFwIXSUyzGL$#*L8Be4Ni-QU1eILXi-*&(n{9h zh(KDiu{e5X(7O<$_a!$QSDPQ`ro?*1TX{jq-Z^^0UwAW@J<{E|%Iby`+>HPxzjmS) zFxib3+;*`0%*8!n7xuYKo7yh_b4B%MGeI&ldD~Rgxcr^Z*@0?v-UxS2%}k7uzO z8O{xxQ#yk?2f7;ux5)}NAK)cAWjwE;NyN&%oPopgPU#u@&Nzd}SG--l2~-(#>S-wZ zXO2LLrK1 zUwfJ9poz-a`_Y9nB{O=FW_TY?wDWwxquyk z)a?$49h628sU<;Ya)XvVPj?s;Cwp;t zMThKb9AMX$F4q1@tPqvnjTpAavHG0*|i!F z8w?5W@WX4}#G_D;nCS06r+UUuDMxk&wFv*-{3HcO?9lh=$%?<6%Gvc92ie4cH|YIB z!jN40I6@ME548-~)g)v1Hf~@{_DBG^^duR1?i(pU`QrSJpowuzGZ8b6_!{iV73YFLQVAt_`+M{C&$sa-`o8U*J*90%l zT1)`~F*EYR;83QSd!#XWR^Wi3qME?1Z#Q|okg_=9n>sK|DJZY#T;ttSywlIL(#>N0 zcQ`Qk8jd*rkT3C`uk1lk%YEd#!(a|9aUDg``0R1M?t1p4z?!|!sGH9|bRsXfC@xDt z?$1GkkA8jl-jH23(D445I!QgE%qKSEbmaY2SM;ZF2!(DFu>KKfc*kknlKo=8#<_#^ z7KUPoj2<7g<392TG#wT4o=Y}Hem63IJK4?+;eD&D5B=%BTY7@g_VeF~_>dyioX<7C z5g24Zm_KTjB(kHBx9J(!oqQ$lcS8`xVomh$8&Hk}zM%yfP$s5gRjLY0WFDY8d4&Hk zN9rAzGLS@dMuB$zFQ&zG&12_?tLJ}aTB4vzUNvVy%Q}zU6Fvgdav865JLMlq6TXu> zw0kOm%UA!KX_-Yu=_=}d{wg$CW>#ue<^FA*2hn|-y!G=pky)%mUy|6vGtv15_nA7+ zpE3{otG%|zs~(<<+vYvDf)DSVORRQ;Q{Y<{^)DpXdt#Vw(8&4Ekvd(~(r=Mr*Tqe>KUB7meGzOd=>@RHY#d|-em+<-( zsMXJ+0ef`tOTj;(yXaPpm(Amqn4ucK!-E_jOP5X}jDUpCkMpmeXGR~de`&{@Y+dzw zG>yLg``3?7a>!X|+cP3%-uX~6*1&wzjh6FVdSc316E~o~JXgfE)a^X!F8NuLn~@e5 zTxhN*=DCnVg-<$R)Jy!_v0`rp6Q6aqSsId`NC6gN6+SmVkUrV(7z%!|Lj+1x1YjWd z29KM0lY!(rXz7{NYdEntWe%k3N(D2#_;i~JCOgs|h&f-T)fE6+f^9{Mvt1etU?hD~ z$$OvZb)4R-R2}eSvh-Z-cY*vcQyvU#OB87qq-YW?kQu|OX_ud3*tBDQT^o}6s4P7!yYNhUL}9P(57YW3jZ>q# zE;IIrX^rcNw98BwDP77;ni~9JS`t-#hG@t3$A))5ZhSMiZ*?6$=al`2X}xZTFL<_I z!WVr${$W}RA#%$>d+l;7AwT~xEhYvj`De{CuF@yf493!jy7YYpd~&2CucR)=4SOU_ zMdgRQ;C|%>F&k!j>*5wX5Ki=)hJJ3Jp2Uyak{0vETQ7@pKCA9Gb1NAkh8|OFiA#C? z96HhO4mQLfeEiHfoFGb+JC0+Kd>!qPHiCdmHD1$Z~*I6 zYT#i4qd?y&(c+^6Yrf*0q?}n}F_5|qCf^tk@gb2?_y8|b5Tq%4RN5Jm>A;cPYU`-!rC#wVlI_-mdR)=WMxWZqGz?%qb-s>Te)EwXwfl%BP);^-s&6 z*8jJ5(Dcgk_VVcV@(97DtSnD%E)H!j4E#U3l&P8Vo$2@gH!h`neZ2j@xs;>P+W+09 zv>pxQ{y`~i@jLZT|Lszy#s()wdxvqu|BeU|T*~NR=McfA{1p-E>uLWxAJo&){C0G# zc3`OP!$9ZzmX7u}W$$}B+Wyd#vephlGN`?!zO}iwxv7qzQ|jxg>T4^j8tZFoUK3(L zi4ARk)r1H}#c=JV;cBLCZDna?S$=s%1)(Wa`l_h7=ub+huplp|up~P-FDv_HW@biw z=BwxBjsIpUgrJabLG?e4%B$4>lTn!qpvXWy>w3V4L`8-nkRhRnr_Y`TJ`H&i80`P# z>EGcXLQ}{BQ>Y!8EgzanKq(?mUU2*TmrHr*>Fe^)+tJ129|fU5H074n{l7Vitkcs< zz5g;Q_l+%#%4oq0V+*>YAUygn1&?juw%-4XruaNX@CX{iieCu+2Tg&5tSt`s6&gpZJ^cqw8Ehz@ zK)q)sw*YOYPu-8r{X^|-l0XIQRMPa%GsO>=cpX44xl0T41l>AE=C< zxIVGdjx41;!E>W2>|N0xso)am5xd42aEhXNcQEa`+6iT78uDT8h=jpqXwURjWvMAuqCci z7w30*9hI$?tN>(GzXtwVs3~;TjFA^-)pB$PG|sFg8N%nxU!2tHm_+9BncJ|%Ll|h) z4j~Mi&yBxv;o^VM01EZ4YO%~@dA_v51+dy=ZmL>?CpT4ZG$z{KTx(3!QA>~)+Q~;z zHs+xkq2`6^e!>ja>I^D;8>)8IldQQQ8(|Xxz;#N~B2deB^E^-Bt)23+SMHOx#7Yv=xyV-) z&V+&xNRQNo?FQVRL&IB4)156fN|<8?iIs>$LT)|$`3 z#cl{?p-M=#E7<(tW`OUPq%yLpShHMcB4y3E$D8&7W$Bf-{n8JSaTtHPOfl%3G7VmP zxEVD38rLkl$1(AaVbj`Vij*tVBySU1+_;cpX=}CQi9V&49A%F;i)E3v#MRN;C_p|a z(Oj{#9tBcgk=Lr2yxkklqgmWKdZ+s5L1^?+(w_WoMapNYDRIm?)%Pz+$0SmC%n_Ty zN@Qc3<)iCXWe?{XbRgrJZ&i=JwoaU_Ur7lu>UeW}eT&A^Y+G&oKA|8KG{!ZaL$ce` zs6*OI3ZAAkMXm93$CPJ$y05H2jC^NF*Cq=HbLs|_`tm~nijEA$Y`6``IECv`FUNLK z9#BWOYY7x<#b;PRY1ywHrRwlp>@S+4!3YH~bBgx2xc@~{98FJIsqxSM&=emNwYVAR zADZGN$Z(xCpZ@;`nj$waVEptXIiI>jP)BdjEbAnt%&1Bkt7AG^luZMCn_IAK}w zdrA!bN>{#RxtG;*Ep_&o$3;WXti=YqO2v0<6*0-?p1iSzxtZ9aWX7CG)}ozKHTH@e zI9eiHsdZYKNDjjHScoS;9wLyUfH{Z@m&y2KaiB>Fb#|!YEfV~!TCA2uQYFZCvPx!G zQOo|ryhwgOT0`T&PU8pQL-FNx}`s!gcjQ#N=H%Q)t7XQPOt zN!S6q<5k@N9zV?r<$`i@SNf7t_))3~7a#D}&k1X-#!jZ&o}?Bv2GUW2jjzcPs~*O> zh*9LAY7lN3`SSE{ldbj|D1;I+AdKM7kk@ZNdXk2O#`d3>^J{bgGu6z5AvYL!i&h+f zw<3D(KmA@#6D-+hMPi) zC9sFr7?t*B5#|py;+k^0s-SJUsV`n3pB|m5Rt&O1dCcMO0-xoLkek^Yfq4TKwAh~M zG(ZG(f{M+=`}GJ%u%5fV;W_2g4WXxVjws8-Otu=nBS}dlGHT&*m=O7(l8wLUfu;Np9 zU>lPlv&(xJlf}ERm$9>MP4meTZ}EQ`l?%nasfl!lsymYotE_;+PMR z_v=r&W`f8C*v;P@I`#$dETc@0GZ=T(Ff!mN0kyAh*N|WA@01~T!VCi-?VjgiB#2V= z&?J>d&ll4tH`~^kMlX7mLNP?>whdy{7G2HtXVjA}V_JD=lEfRmxck{QiASp|qWTY_fF$D)u6S(NDa+-M+ zzhk{}409#r(zlO0yixp%h&gP_g?a(@{8Z=p!s^p=7oBx)8t_FJL=X}YC4&m1?8~QS zGY$O+3nMC{p}0T{>5zFzhfv8gi6J5Mx{?*%)T=X)k71#o1wg1H3eS8}IFJO^LCk_9 zA|@hY&L<_Du!A%Z%19C3iQN0r?!7uC;%bOCk->9)GI@MEu}KLpt~tg z|A~wG7=jMb zM3H1i&0Gfg=uN#>N>`KtG53xc(y^$6v)_^=V;GC^4Ey6_)>TDK10lJPyH7V^LE#jR zg0$jWbT?fIhk5~80%MJJ2T_%eP|^ z$4&=8VZ&eU#GxQDVm^d^4-r`zY7tA5(j9+L;-@&y86F0|1Er22f(?D6--Ob{5P`P6 z36ImqvK^xc&z{HPy}>`c!C-FMhOk(JBU(d#NXrg*3-=RzV^|`!yq%wVvAOgPCF@g5{Xq4 ziJfK>lEz1@1%C8>u4fS1f>nyHBU+&#(Fw^H*+;Y-GvqB+V2Z?8KL!4uSO7@@;AdFs z^EA_7HKWeN=$3guJm<e4Wk;NKyHb zj^&h$c$O>WZ=TlRo&rrn_`BoFxhTocY`W@fg6`acs3ikU6R3_+ZAY}$VX<<%8BiS6 z_aoX17}cRF6?tMTRuV!6qd8j5Em5b1z7d?nDgcD0^B~48?Pd+t} zKbz@(i{3)rg~`Z-vLFcJG)I1=g}17lS-v?QI}S-C0bfzfo5Q+XJ4Ri@&=!To_Cyyo zTT$)U5^AZ3sx;5z6QF2hLsUwOdnK{Nt)QKMxdg=D~biW z%`w&vh>bB6&~+Em7Y5{G)nj0T>aK(J(raapLCilHl5jPigozinG6i3h%i&umDx%IM z0_i6Lo}8w27St;RUoWwPuy^QbzJ_pWGqe$Lb7_h)-zIwL4L*l~V^piJ7DQ;)`?oRB z+KIUM9aC_9uFq>|crL^cgX0W^2#WPdM}$%MiYQ!~P=ydtf5+J|bT%3>vC5G!`^+%V zi9kNWK)l7|BwX0@g8D0%JPj#LBc7YvFp)V)8fs`9xbqFtg1afOO`6=>R0vf=OH46fF zV<9`LRxE3#!K=Vk2<&YaRYaKTmYsb#CMko`cq`24IGN#tB&0%B9}sIxZW?&=!WC+t zN6pyE8UYcy1LXTgpK(Mh9TxkTaG%fKlNN$V^K?=q-hF;WuRZF_P~jWcO;$f?yN#^SYTj&$7ZKI}X}kn75Eut;9AK{<5}E+P;dsfPWi9 zttn&zQnP~|$%Hw)TUQ$r>oiQnQTWDB6zdD1CfId^$)>I}9cV(Z_=W z>*np)t~>$4v0JgO@_5d*760x-h5_Y%R1)13uj(4CBoon8#*Wm?W9}2HssE3 z1D#YzyU0x-C>RTR^poyG41^s<5hMyJq}D5tf?Z5QSPBSVGAJ>m>AE@`Nj$Rkk;;aI z=9yDh7BPs2i#ETN&ai}~a)I0m?-y$kOZzFm$LI;fhMOjeB@+E9zU{$oQf}-FfsnnDpw6GVef7hl#*N5#hJ;T!v-aumN zgH?>UeWG`nepI_=kRhes9@HR2SE2h27bCT|AH7#Qb@p|=Ijb3K28H|WP*_-BQZZ2U z83WhgaN4CWnEDDHyMV`$_bWplOHyy)Xvgy#rH>j;ap2J~fVCQ>=g|-cG^Q#?cbvbO zRIUFOYD&M8xRe9Ri??CIuTq^1jTJ?L2Qc6dM%52Rs63Uxhexr-QcIjtV=J$Q!PZ)w zVa+_Akc5yHqhnfZSP>9P+~P{Jn-eP_NvsJ1Tw=4e)mAub`))nc9aD|gt&N-an58kL zJHSy{W&uMGydQlZ`lbQd7wCw@S3&wO$P;48d}8Z=GWdD}^Iy`*=ISEV0u`$nR9l0q z7}9q-+V6~6!8iC6nHaJ=$|#Rj5DvoBO9>3ev_}})<0EQSNTz7$s>BEYFZnJevCn?k ze(_$D4a1C|+W4Bc#7hzZd~r9B%f+M`(yl-~{S$P61+S!RiXRkB;=tT?SD#TVp=E$5 z+ntD91{fX}?lr8xvLq^}e#e*mzV8`pC%TFT8W{|x_yH-E2#pmpegROU`o6l=;WN{1 zK1UR+hb^5a?ew;Jrjho<<8jv%tD30$U82n+>boEFbE`K=xq5F(kp)A7r%IPd3&@>+ z4?qs?MqG~F7+J}sl76&oLzB2b^8xZEcdzxJD6hIPE}ym@yRQo+?Vl$9ms^$ zfkN;w$^#5oq^ZRdMrwYCP+d&zEF(LX1RsmO2_B^1cn3Kl{P#K3X)vbeTKH1UkX}a0 z%~=g8?_?`B1Lh`1_)be~*sakQ5JpPc@2lXh)$W??qqgCNq4o?iDQcyH723qFY-;DA z#4p~Hpr`N8pN*btsm)>i=LjbnRD_>XL$`$N&nwFfN|xrzc`suC zkZ-^BZ$8(~K4iokLXzGq$t^?EYM`#(Utc%Gof>ObNHDxsffn4?EWHUel7O@QrO4LnRi7+64H36S5*}8+^kW%bJ*li zo5-hd_^*P{f6x?lfGi}1Jt|7x7QkZmS3xKtB`Vr37mhTxRfd~P84zg7a!)3KrsT@W zeRb?#GwD>NP-yrLG~XrA6oER_#$p$BBL^YaQB=0v~5+>o$0%0c#ru;Ph?xLwVah>Ysh`WOX~~o^$!LI zQW+N&wTPkk8&TCief$R|S@xuwL7dYWp3ZmQC8?fh95{4iNVUVe;UjO{0d2Vd zstNqq{d0Fcgt6{OlacFZar%ARXUD?o#@RblO*8I~+CoEM;;W8U{Z7$=Wj4 z^sr?t7(U~9lj?GZtXp;ZA~ikZg#oNA{nFmmpAT9^*))6&rAJ>HaHh|rE8;b=bmJ;A z@xdF33Wq%th2FW9kucZQkM6z76nqW1pZI5P-8}+1Bx5EzS0fnS-mE+E&e!ItGD;Yf z+?4rvANx}u$Ew6+~)z57!F{x3QM;}>vq03>pLZI!FM9{*HO)l&XUk1HxUI-dzyR*?#w=`mMfgfpTt?%8%`UN1>-%c&h97Hfpw2zN@{Xxbf?- z{E+i~cguU5nf;G0?=NR-ZmxuU&$){~{*qVE8N&8{DC_5GXY9%^I^L@%AY9m{HDGl) zK$SdP;5mp@3(qQ#fhoI&zX#cse-7xxmuYn&+1Y`Lfn1#+N>4dFseL0nL;Xq{j920-P_0oFJNEk^s>lyBWMK?;-dX_<0 zrFfVCq)_WB=;k0~s_7>`aWMwbvpf+_j74pX&4=mKC|^rTXBfEhT!Y5Vzb@HcCjWf{ zTJK06Dwf8}SFTz+NS-yKT8`qoEu+UqlADCQ8n@X=$JM2&OPkUH;5T*-5-=y9$biz_ zzX%N)dbrz>In<^rRiI!*9*+-yUfR0)^|rL3J3Nw}l#T+_sxTr9#c_DfYVs+}>iE8j z$SyqAkZhWWv;#W8D&2t`odpfay0^T~JOo;fS}^{h4p#8v?FEwVn`6H=a)^x#WPP24y=PB`1rPVY?w>tunK29$QnK$(~+K7$*eK)U-uR>V0m4jq{j-y-~=Zk{}6nyh@u zuN#h5G_OngR=OCd18&RA65lda-TC{$lBzI9fG=>s#eKX$LEMwPFKxLU--e?``M-Q>tR+`8f8Nt85ZOQV`#U zh6s*n%Tjy}wUbGa(&(Gp5xl_818S5b>9Y7<%^uBa+a|GhAw)}Zmh_6T|4aIxXBUNC zmvmOKnXC2ii_CN%>IW~?XN+)ar0yp%JNnAai}_p&IC;qPqD^)l3B9^>PZ#CVUqiSw zcw=^0_`_3PzH31x6Xf1Qm*Jnp&kN&2{U7s$FCFv_vZegovzZNM>z2KxMyr@E z;q+qv$h1;Tvoo!(+mw~#JWioZO(#6AD+R!hp0}36m}1HHe|jMWf7sD<><1r$5g#Sg z5%@CUYY_(CVWi^okf>$ZaQ4rzzK;O$y-v%y>0aH7E+o#oQC05q`zAR?oc~yy!xjhD zl4+TS8(b~IdrHC8t})4(KjP%VebZqo`B!yn^pzLvx6t2&`r}TvP6Ic^p0{K?h@%O6 z+wY(}MbQOqg%`Wz_)v^WyZ{+m3%~+-Q)aEl*H{{V~(;B{p6J9 z?-8r2PxaA$t5=)t-bb2r)nlT*8*qB+wpbgy?GBck@9)ITlYgPA9M$g-A+)qfV)26p zKrVJ5w`eqv2a-1q*!WOAo(UZpKYn{*BT-2L1KEsFK(p2ZXzcNb8^%sLMQM*Ugupyn=D3{ zdLZ+klJ$2df24~G@Yc-z$rkPk2o~;)#CD*(a|HAVKT=8kM+Y2D@m{UdH884`Ipd|? zjmc9UT@Pfad=%?FMN-#Z1aE)1fA5l&Hc24q?N8+4`Mn5N-G&&16FUQbLcQuO4jDuj zVdBl*n4J>xuqz^vLSay#cA`&}7kJmL9j@9M;IHn}+zvldGHq@{hD8D?dta?a$g&hj z8**q%_UAJU=6l44_aH1)s}X_yN%{a9Sif?o*pgYSZCHEgEwtY~^vNxt>Fk^P_te87 zN_-Vs5s>%cL{WlL=s;lUYr&#@qN1&!u!5A2Ei$@8%!9=F2)PV^rFVqhQCI=s?NH&z zPTrw5<{??Dh}(9^7HUJ+m`IORoe0>_fTJOn*$}QfBwIGrt0^(~b?B`>W!Fo9K{HAw z-(ch(cGP^>c_Vt@B|twPFrjQT31AMoGrUk7Jy47yd`61d5I^tHxNvV6lVM1akGgFa z!7gaH3Q$}#A4X>kQI!EKt;jZi8EpZKw|@0$Ky>yT6#%AgEI1Tk4N?Yy`bLnekM1a4npa0Tq7vo8UohPm#mbP=Y28YOhyYx0Jn zo1@;QXgjLr9h5|L6dWg}bJ60BBc_Tz+CmZ(H!FMJQ7q_nGAdyE%rKyQG%0R>B3}p_q*5eX&F|+<7L%1E; zZ7W0mR18aO@fCyN0qQV4RpYrKoPotua>fw&!g$Yc$|BVwF~bmlZxnnqd1uPvF5i$$ z8BVVQXSFnCpNbxEB%S?YZqGN3S1pj^7&2=I7^qHd-kWxhFn;TA@fkI>*D&q%7~R=0 zWzb>a^ljRg58Y{qwD2a=2i|s)O;Ikx`LbVEyJ8u$F)>B3~)5FS%IvDyu zMp(<2u%$MXC)q3{2mos_H_6E>7$U~c7NdM}jCNGj!aD$s-Rcp6fCpSwq;!M4?Et&Y z>C@RbdC0p*hG?CRRLu4K{7LhtHnVFu{p=ndZjo5*)y0HnMm#v~(cghu!=uEwjfZgl5Um&$1igxVzOx zXv091DQMxvWwxfvxuG9G*2YI-97TB2z?lX zQs<1p<>H3kI2;S;&!NXFK~rWJ^KqV};~(gi#-?bRZPucf)N7LwWVUB|qy{*f<^3hN z_w4rLJX{rEU2GYSO|_V^yb@zGm$PKuX?yN-Pop+DJ#}iMieqha`G7I$bU*j2KZ6pn z^^f*k*+2#*g!Sbn=WnqUIANd5i}U`}5|f>+ft1}r^op`QfYN<+eZb~KjN$$3r8|%B zcSaLkJZ6v_Tm@<8EN-T(FxpQY+v&Jf(2u;7!Yu2um~T6+b!DOqTuIj+r>Ip;(?n)V zF$1ZdFqnK_W(j@CS`A0r3W6$Q1z5Lbea;?MV%Y92g52mGg@+-U%q~ zhUBjtCyc9HVDmwsW)pQOgV9QB@ z!5QmG$SNBb4wXNO+?jZ1x8k)_F~7UY@AZH~ZLv}CE)wRX1m8@9uIleNuoII9xQ*v^5|<65xcEd9szpwe~fh z@xF=++H@6h;cN!lcyh+P-bgSispk3Hsdq?EEL`pc(HJbdgcO(rs$9{;L}U3jY7%XX zmQ(eko$!GXR(Vj{s3%vRgw7m^v9WVHr{qvMbGnACEo;DEnBWA{R<#oQu6LmrBJj*Za++wGuDC59xZi!3R-_cIkgYr_65D>@tm#*mA zol`=09Y7V8x>h*Cm|%<%;6MjjP1IO9R;8sT8e{x=^sCAk3iZ>RUZd+lgRO1W=SZGE@QpP1T*8es}QwnAb(%_{bEX z6_Tm?3mX@Og`stf{0F%FjdqSrr0c=D-8J82l$l9{Lz#%9NhIkZ!zZ#=OZ+Pa*aI%E z;was2q?L6f);!!h0h~vpAdgCZ$OL=AcR3C9Vb*>Z{3u4(_x!^Sspo?F$G98B^0}sYHY{y2R z^%x2_2)P^fCWrGeJYVRm(tNZ$1`VeH6QLY*PhnD#Lba5tM;I6m@gDwa+Y7?Jbs)@A z5VBwrv#K2-c`qjiy^t1vLy-LHee&&Q&0e#|fN0xrlYQgb{>i#6&4ERyJm3%P!wDGR z{%u0e2Q|X?C`%A=A$GuiXDt>zc(^qilW~B9p?Y$U54io6g?x6aQ2G}xe8f?8^weKQ z;%;QDJFWT=Q$5)WJl6~SB0NUwPc+#EVKADZf=FI*!T`+QpS@%@!iRgGcLibmMq_Ve ztT`BvZLTPC9p#^ycZCQ?OVrZYQ zbTm?BcB`Rmqmu|xB1@h;bCIs<5Ky|Tz(OXIbl!qJY{L=W-*?dX{*xJb!Lg)Hoa+LF z=wN7TZc~}xcWcBUzAt%i#ksHTgvpexrEWjekfLZ9nQhoffT+ag3jpa~4Trp-{{47I zum8Ie^qNi%l}ePa0~au>Mm(G1g%sKoN%X7uJSV&+_HgQ_fzz`_m*A+8r@DI9wpP^2 z=x+_!hgb2GKjoi&8H!iGN(0BPGKHS&1Xa|Der(APtik@opLvo-(Iqh11=BOxbVx9k zZvgPdRMrZ?*jeHql7Tix!EZa>$hrn=&MdtMU?}g2+e)Y0RwXaIIz73w)wvV)y7YH= z21>@{t66zSui#~EU(AeTNZ@90;?ZTFjyoLq>>Qf3_#9vO0?kB(mU_s4$Nj<4YKh)M z@PE)0nuEEWvi3eGTRPH*xTkHG;nj-szo%QsETC%o) z{@@@6PIS%iPS*WUo@q_zB^g_#qTVu^^pmW={V@G z@3LRYjTRWX-CKt1V6}f}O7MDQObE@ZTz-bPc(OmFu5rcqf<&ep&%qX zkG7GVQY|hp*cNI`i5gjw=S|dNb(@i9(&kMt@Bt~LAjLQp_);zI>fO5P$xAne=P2x% zpwe==*RvX{o^w8#>Q>RhpUu#DYfOOAsSvFd#oL&Iq;6^v$O{Q)rpQN-JcV!^9{EDq z>7(7C6zt%~udGA$6@^OZ-jO^!G z*=9t`UpJc8VwAjW>S?Ixot`GOins3T%Zivwfk4%*-{ylQ3{r;4>5<#(KP5VdEeVqv z$qyouT_BM~2v+)gt7H$f#$c(NcNb!brF+=s)1*G~mhN$$uky8lKC@{dydF$Y*Ly&$ z)llSP!Yi5Veu;%=etApP#dT`S>jau|d%SJj;|4i_rf505G%M0my7W(EbTOBiw6MO; z)qeH(ne2=WTYvsrHq(9CIj2wQjat?`4g{KFoqnJ*$+8b$dc3`zrzW~Upeb43TA@hU z^Xu|!&Y(;wEd)C%a4lX*oDu1Ft2kxyg>`6)p`xH5h$ttRbIillK}B&_Mm9NnJ5LFa zuJ$wSx8fHejtN8QK1a;cZLor1;FosNc97<)-g*WiBT6xl-+e}z$CN) zZAW8~T4KTmVg`0Q$r*!*j#Pk46>IJ^RBuE8FBM0$><2xGUCVp3S; zW}j;W^0T1OG^XR`L=d8reJmp`mIuaRNy_(10uw2EkLJQvDp3F6*G!RGppS+^UgG| zI;l&4_lr*wDKunHSD(?V%zrJpe8`DV5E^;LFH}FPXXK;aoTx1H>O$&G_3k-;J^&;p@0<}wm zIYLySbfzm}PKkzLI%dYHmyvrF=xfDb%jVzT64P z1(OwNY|iSi(2b+C$qFrl1S~dMQoNbJRseoQ;4QTE>Ft_7z5MP&A+h+Dp(5+CeaD_A zJF1pJ8SBnaNvAKl;Zs<4f*Tvj#y`G<{Yig_x5%c(~AOz=!KL#nTS}rU#70|vL9+wDRAXijQ z<%_*|sQJU>_VS;CkWs9W-xRsekOXu0L$uby(Ok4$1&R>ko>gIqUxV7WsiqSaL^;zM-UXB-*LktgaDwE^e;kaI0<0kR$) z7N|{3{I3X(+y9E-Fp@;!f1LdOe*F9U(eI0+-{%MT^Us$TN0%3ezy7=){5n7Qd4BZs z{P4&5;pN%qpJ)3&zkT`jb?5&S!8zXgOB${JTN<73ul_?C&HWz=IA1r%{+l$~TO0j{ zG;05sG+O(grP1miX7q7=abk6WkiY5wXa45DwQoL6cP>wLEl(1z&V}jWxv8PK$)Ux` zp4IWTh4J?bWA7Hm+ULjK9gf!jhc3!m7-`*Wi`%Uam>uhx9d4N&Zk`?|=%T)nKf0(H zH}nBVphZJHxWRTp_-3%bYv4osKXp;-=r}YEyB8tSSEx~SnF zx+t}&J*KvG=e6TzvDHSN$wsc>A7+%Tx0cKiVOc{Mn#4Bc}1^s z^73A0XQgBp{--qZE36?fqs0`}`J_K7oXQkTT3TvS@}CY)Tzq^?Y+Q6qEIK+SDmsQ> zj8Y;HosPW!GDgo4&qBh&{WSiTMgc+3{zxPL0FT@%`}8t`G}1%AR7GaWJWF}x`^3xp zPX|ZPKY`o(U*zbo4vv?-le?{h>pi=Fb#QLjdB4{EFJtsKJo3~rzIp3^?%*ig(Eq!D zBX?c*-vt~o8C6l~8^V7Va3quj#FhBP6nRAzctqs6h2^+~Axa4J#e?KcKT+omwn0qT^bq1w0V7ARFEoF_fh_51ZS{eS36%w z3M{kHP%-sa1m|x3%MQC~YQk}lXZ9_wos{ZgADgNc-Vh=Mnn>w|N3nK&{+{8l z;T;(LJF!!~7(FGQpqxT@olOzj0DeZg+X4 zy)_`bT0!hh);Pei^mbJwjhHBD_; zVPoXlQ7XTo>|MQyRn;A84LjD4QUFTzEy1EO6p5PPSUBwWS3A>nAkVz&4rpgRR+2R$ zPhE_zp-`=ti-c3{3P*9C1sk2?U4-zkAMP#_c;i0nXo(u9row@|$qSNib>*F+#x(HE;RJM_BVpF{~DbKb`r6qFq-q+IY;6ny)NRNvUWDS zH*7uW&dXpzDe@P)R-&6fWV3?1dL;d^y!4@td5)-Rskk0B_rlErnU}O3)&jV30dS+j zcQ!!(F&8r?wG1NrIrSH!-$AGSBlx1urNnZy@}+89#6!k6{w~foqAJ;X&+e&xZl&)3 zkTy!@TbOL&{csYfwiR@KkK6GRrFfbT+Fa84Tp{*OcQu83>lx@-Uae_n4L|#>B8&>* zT&j$>51+P#e@-6Xmph4f{Udm`2L(PE%X@!BhQ^8fmLX3zK0zP@~(+8NZYEMdWyt!L#_k?RChx4R$Uz@%=h9g2pnf>_Drei`*(1|3Kr7ZiM*qpXZ z(VCKA!(x)x+J>rpM}>M{QQBo)xrxvX!(y|XaE(!YeP_PUJQhdaCXLSQr74(MzAoqeUWRL~Y&iGW9EFu@pOT zSt~2C3xX+J8mRNQ77QonTc2!A3dC?xIq+9ve3~!C_@3lqU=fV?Mq@Si6U|{_ zNmWV-2f~I{I4N=x`q;JkVvi|B7~4MTWt@l%H5Hj!PVeehEG$B= z2~5G5-FjChjJGa`eMUo--E=HTX4Cik!5-=nJ?b}&`%2S!VYnHE{N%t8Y`H$gp)#Cj zL(2wREI@vdqIohN?{k;cb;vu+A2La}_zMP_Mrt!{E`4D-J_1mf; zczdX5MyJMA5#y8iM-sAnnnR3cuXUdX#EwuXFGn4W$ntthud(zcXsU8rC60U@KU&`_ za9x0)2XRFb6wTAOL>9+JaoJZTRf&2RpJ~I&7K${#<)(>>%oGo5zJy#9@T=j7tky*) zP!>$=>KGN1u7^2O-d;mRK+#*lK1!J9<1CH5^_PqW(X4_7w-d)d2)q4>qC8b1DHuhAdGk|LsHQz_~# zFwSWFO!s18yaJ~y&raH9V31O8mnZQ|4r=4XZJ*OzIs`C%WsPD;v1IeT)K&3f4V#@4 zP`4pCXh6Q9FW30oyA|8hxS`?h@i@~-@08xaYX#k%Vd490G{H}?1G3#7cTF-xIby|7 zAtNHG2t{>~1rh)8X#jDXuhjW*7M~7Q-yOy0$@5F(5?{1(XUF`vV_zwkb<6AJHv~5> ztx^ej?9(c@Ir}AdLa&%Oz0Y8Ze1TuVUgoPr^M*zoiOh45RkBSfZf5k2qzW$@`kf8z zDv#!eELs{aDp|d~d*$`yoX{;*{x1Q}KNsd-w6wI2f4LO(bCHT{ZF_FM6>{h2(xydg z$E)$Ju+E=vwli8y+O{38jsARl_@edce~I7_6y}J}ng6#44)h+CiE~2zY&VW6{VNLy zi_!pftwGeh!7TnXTqN|tDvKLD^Xc=I?Y?4gr`4(^n$tfTjiB178gS7z9=qHlucXKB-~hO8hcd`T=WsU;V|~h zo}^G^CGdvaxwLT{Al;DFt57#owrJQ(#I1gvq_2_{sE@ywih*8);S#)y`zS?ms{#r8dccfbW~36G+pp)!sZIhAud=8^D-!b;CkTwamjvI6+nBsv2I z>)&UdG@zXdorp4quN|b&G|e*@B1t@FKB_X{K%w19);xW@W2o!WaobNfQ3EvS4(oR; z6C)Z*ixq6Sz`RFg=`f0toQi@FV^|FW6&s+pUPZDjvpu(r)UmpX1;Gw(-x%lyGoeA& zR8}b|<_{P6tpH|89q5cD|BCzB#F>-z9tdIP*ie9Lhj3AmAr^v0P^q#0+sItcsJS9| z#AGa_ULYUK_SGGe;EveBqL#5RuoV=igNy?anMH^f!EhT+-VGcPl+8L+2k_;w8WF>= z2gHHc8$}n`qOjoCb%@0xL_{9qqLIx0fM|B_H5(C^+E}4K+=A1Vu=_e*Cm2Y~G)2TK zPz-Z7veO!rGKrL^BL(9~y5c}D0CSl4CQ_lDlc)$Rpo~RP-C_B$$SwC6e^6q8H?m#? zNsWaqPx`ic5dC9`uq?I#D$Hy-QRF#8G>~*Z39(R=6hTfJZG-eaxZ2ZAMpD$4DOlyz z8*e~JCnNOWTzbU0>)>Me*KLLtDEK$kQMeAd`ylzQ6fi2H`qmzi=mp=!hWZylX`s}G za>MiMqMsiDg-MYXI%(iyrn0)|$!)~=JS8#@0acKZj8&Xfy~vbx!kjS{&JI7WXp<2k z{iBFYxd=R0g!*U&U#5bXsTt;Z(qIPgNH_Ag!U@J;gqkPmDGeHZu}QvbRvp%Ms;l9u$Y z0aSD{`*aQjjYV!0v4p$JtYLxoMgBi~GBqmQWO9>gz5`M zT*-&18UyOQ#K;Q6fMc8!65N>p=?r2v&1kK zLw{hUBx9j-$0@X)eRwH5FKp2DAbIkM$3V1`_%Vjd_iFZp#^ z{|CvGVptLg$#TINeTH*e91WSo-wtpS6mXLo( z2e>yW=e11Es`u2=kruW@d?lb(C@lI8#cQv!-#NxEyQ9`AEPdMr{sgGA1I!H%{B|(Z z!Jwumb3*E&!G6Fv^^P+J^cuK}s6f2N0#cIdyV<@ErptUo8I!PVe|pH5mhUmq+fq1+ zizs+>lQLQkrB8wD_rYywih}hvk0dJ%AD$G`c+Vl{1l;~88Mc`gB?V@zXQm%$3hE)a ztQ7h@9|d}Y?`@Ym?7+TkJSy>wliFmJ$piS^4a$!Q+xd_>6BX}RZ`0hzpN$PHBiSu` z*g^{+36qGeSkz`6{4ftvs!^>>z~oIyGg-mgc~i4A4R^My3-v-{IvzhzW`38QuWSYL zvU3FDfxIF(ITl((@yOMO?wdf@w=ZCVtDB#nXA`ONCLxnnSbjQkM&p1N?vbT>kmwaq zYXPuXi5Y}c(N7r|dst|e)de474YyG@^3cCnGigO&+CsGt2QsO(J%%sMXl!jSCGvrNTD@IJPV5re~5)DDf2OG$=ZoGBIGL-D@FMRa8G9 zJPOcs0z3nv&{T#XEb;-mX%$E|h-#|5>efkNiExMAy~W5_Opd3Iz7v~Y7QuD6QL~n? zYXB>psm{|IsdlW?ocJ&hcKQJ;HeSc6T^z`#+b$9Kr>g*R+qC6&6wMOhKip`xi@NJx z&pah9{F7m~o27sS`AJ-QUWW02kkV;HEaEqG%6_2qljqzpN3Rqh|5H2oNVsp(B9Df{ zrsP2~=H)MqqBGj>M@6AS>sU735pSV|9Tb!_s0%zLZQc;S8P|@cpt6#ylK>QZxAqPd zk%o(HYQN{N51j@HY$~+c*F&$rdOY7($0+Jwk;N5C;d{ptd)xPHq$wccl7GIQYsJTp zl>t-15`&~5XMm=IpD5T}2o8&yD}r4Gpj+KH5NdhFage*0ms!1#&w{Fw3nFtf+s7D4EvDE zxAg-Zs$%{-g|dmf0}JR+aCB(V;5&OzHx{+-&}8@%by*H5u0wS`7PqqoEmOJ-??8f! zP!#9Z-&6({nHEW_A?B(6)45)bin)wBV>{pK7IlV?v&g;k*Mgy8_v(hw!TDKM(1R2J zb2GDK61i&0@J@{Z-a8nSHu9n#)rDsLfV=)XAJPZFa!-vmoB|TCh@q+Cx9$&EKcnNL zflHt<95|rcBLGfBFKMu^rJS~;6fYHzz1_2%+9`z=^Xy=eg<9iChSXXtau0jb0oc*7h))F6X9YICQvk6G)BTx#JmLmx zMEYFJIyn{o)ZxsKfS&R;%3&MOE(ERDgG%ss&Ge_o^|PopS~w`IQhj28@%drLCE6guMPWbHH4V z^<1c=uz^_*fVu%V_rAh>2|ttV!YMyA*VP5U^j-=u%&L3Ck||aC47q-MxHoW~q;8)W zE6`OCa-V{%olIwrMa~?dI@s8gJW!|*C$?KC-{dTS-5v} z*?h%pnvEi#sHbtD5iV2IS`R#r0L^zt?kK#LRD5T@2MsyBapfMz%^=+KH{5IECA(Tc zJs^aLey@03Iu0|4A+DOyvLX8?*PX1_i_d|S0n{^qoggIJ*C8HJxS(ehBH1(fhQn5# zag{0}T`j8&5H~YeM71-x@9?gH8Di)rL@IdRG%%#~sIFp^`2j2Q%9|$zTmAPZ7oYpQ za_pakGj-lL?GfO0-l=b)P#rz&B>D-v++wu+h-ajU`%`Ys8jHy1=jmVr%7(usIKULx zU%z^8`;)Bq3Y;NNZFz`g?OineEm3?AwtByIN*I#$p79F?yOXq8{gxRA-=U6o@qdsh zSo;wOti15zSOkW&z|U&76q*Ds|K0-jwm(fJ+hl3UW&lVK=ka@A8E!&yyk$=-bN%=N z$gJ{jQt&1?6#b-;b;dl3-iFGfKnn=SZR)xZu`;se!=g6(e#`9f&>dC9yv0R>DFsY! z9E=zQ#P%Z}GZUBOx1We#tCc*71+Gs3vCq(1!sz51 z2Dh&*RJI(t?M9*f-$^U}KoSqEW+S(S^zT~W$gSG|!x2E-rqg#+)aXe}`&)I%P^G`aMm5SC< z06t&l01?Ih8)?*^IQ62L*FiE};tGehs@%TSKho%)zVWvHKM@>KBmvKN(!XsiaK0n~ zeCs|WCghufpBX)ZBV-VuAS4mTM-%gj2y~Yzx2>j2Bim1NIs7dIgL%ni%Q~O&d*YGh zA6|Pi2^J^ttCitOBX@@e?!2PUheuCkPw~%JH8oFH25XBt?0Aw~AT{0sjv;OhzG@u# zcYkb_6GbjRyV>iOc)>It64D7YoiH~6nftuMOo-R=5h4RSE(FU z=u>gifUCic#On3g&zkA!aoBs;H{G1wtTo`hpyG$(^BMg*Sb8tj%1D@*$>8`(jM#Lq zbP9=uRm{|LwUD^R4=ZfoaS3VoGyhnrOrTLqTKl+k<$9fp%7|F{PLs@6)2Xg=jpGen zp*i$)uc9BveA9!>JazHKkclLjy+$!rCUL2Ik7##QQgxs#h%rS&;e@?Pf~s*JUtFmU zAcsC?0JpS2EHI9qHRAlh>4ucav7v$3uiBioErT`M3o|D)RtJ(eYaIW`e53-3Mj2u%=VfjZQ(%3s;?!>^@GJhq`OXp1u4gRb}al z$j7s9t{PbHxkhfJe{i_=b>LN*&No+ByEhHUv4}bOiEB76HC1$(=z8uVmdNcp_BQKU z^R_#gJw)wQ(uwuM68}>#!o4U)61-&xVt;JCNh(=G#?8PO=5Gl7~)BdP;?4q$cFSvHD7lw+El%hAfW^ zf3R`zpGx?yrx9d%`?JC&&NseQwjEywPhEa;uEG_r>rd z{ofdW1rMjQDwn8?XkFQj9u@laq(c5~$`nO{xIe+F=>-Wx@1n z(STD}&7ad#q2n4Srfh7k-nb3Fk$j@TZf$(!dgR9aq^He`stMcQep)|29rd|nV&oDm z^TxfaThArm$t{@wI(Gg0tFzCd4{m(_^*j8`pUl*6?a=do0)CF3zd@tj7{1caeXmZZ z_Kbu=yeuIL0r6$xu5pNG-TKDLYOR1+J_JBHAzS))@i0?U5Co5{@ z&0{bJreYS_mNCt32)T|G(7TEvW~dUIOox9;!Kql;mbO8GmAHhBVOQSw>LsA^tn_d( zk>fB0qtnMHG9vm*WRLR1-yyP3S`Ue0zqUa>2li%VE`dj@+=oP2E=BSU8Pd}@20`8> zOkeUL;^r$oJ>qh#sH0U0CKf@>yLw#y1YY7amBs2_>5b-DGpI_%$jJb`xRH8DJFBRf z%dItyK&LyG@zR~9+aWn|E*T7d?p;Bdr{B*UDq%?oLK2Yr_s&scJ*m`nZ zf;a!JCbRq3 z2}v}gV-xO`$8s{8($|&f2SqdSPsS!Ht5yyGQqO@tvZSGbr^QVSGh;-w6yAq5{c_;$ z?Ew*P%}PbYz1^lVbQaG*?uVx=dky?A@;;c=*AMgj;<$WEe@e2n@;;N_REhCGC7#ot z@zE_5Y<|%Wk6s$_fqr!Vdvpq0uuf*r3wCdBWbeBEbtk(_} z51S6`$YVF_#DfjYc37=1gqA#{nSH)^+^|3|X!Bbgt^K`E`U55-F|T^;OIe>|cjivI z>1up-zVB-b=VJR@%!79g^itz{?E-43csvkP6lcjg5u@7Vyms-tq_eII=|X6`Jj~UG z`;L!E22-rU;DzGiSIf5uO{rrR68&OGXOUN(@+=^B`d0A?)m7e1X0f2C{PYtt8^Bba z5#M|k{TDP+JL=Xcj+;(%8~b*-0e34@;J@ zeDlP7X=UL>f=QcSFQhZTka#e()Yg-)r3bOVC&rH-x>DZ$?X8r#*rbF8q-N-Dwt-O) z1Lq&P#Q5zjM0r+Gfdu~14DNyp2|N4D?TyaUu7H~zJcB+rcZ3uyG0O8m5>#5Du(3Yz zy#1*OAceq}X7;%);_F4;O})@Fscc4@SaCinFeW$%2uj<>@YjWP3EP}c>-w%*9XSC? z_4QR*wH*&kG-js-;4g$7G;^LOhxdN}Rdm&bvIx4qr})d%|G}?oAa#X4zBzY@fB*>d z*nNPPIJf7^tHjO*r{BlHpGDr+U;1IUl#yss#fZ28 zji$ObE(LG>n)i_(oM_)YP~yj128$jiqE=E#Tlbq!y>cBa@%+g4rk@EGnj69bN-zIF`!ezcS2 zZnuC`he;8LZ4B4edD?U6G&HbXRgV>&t8=llqiV6^nQ71bY8BpD&Wpcmq|k2KXRok%Kw~WbW0B9UJ(U@+G zt|gtTAjkPVQpp=gDmRGpQ#UWIB{@I>j<}p~K-ea84T$*+8x-vvI3LqA8q&#B5)f;Y-3PDHW4cB% zP!nkg@?s08_Nf3o^q=>^4uc8h`0VlleLRyBmfS8vuI7aS6}2jU>Pb>LP+4|DwCs)U z$3z8v)jPupUTifv?RF7e9%<|+MpMt3!ZguIfo4p#(k$Wlip1E_1oh(=V=<~^vVWUt z8{YWM@<{w)Et{qO9KNGLYcy+>qs4_S-~oH9QgSyq>6r`JNnkk6Pl2S6bV`G*ER=j- zh5V745-~Z_Pvi^4!q^sxBEJyDvP>rBq=R#9XM@e^sLvB($G~Wob^#b|q{%Fy+l(|n z7QZ>B0!t)<#$RD!R{--ybp}-)R5;A6Pb7`Bo#cHH#36^gBg;h3NJhdrn#WRYJYcPC z7D?OV@kOI#{6xa!=$ZiR7<*Dm)d-^9u!(YZO%a-}Z+ghnexjUCMMw+Yxq++3O+_zA zFwt@%`MZEIHl9osGbe$vBB-M(v8MDtH;3kVOezMS^0+1S8Z4QUfSP$IWNT!7eRC!u$^n` zP?_xbb!~=BPBJyVC0injF^e~mdaz=~suxQSkPW-v5wzBj^%Z{3A*tc z-yG5noCXP}H%%8Fa;CwtWQVH@G9q>&p4x5+3l-JbsWK1E#4W3to!f9sPfsn>om{LY zgRRGB8-1Lsh89#P3oSRDOWT}G4@=tzoJ%&lR6wt~zAxq-p4Ly#Ib+%EqTTJ}w9uTM zWAI~9sw398ZMH3FX;?m4fZA!?wur7bGb=YZZB7o%vJ-8181vf+t`Rq53v<93C*j#g zt`~pxN@%!F(K3MbVaZ9_u%mhV8o^Rpzc@OS$00}swqQ&CM0mq3qw99lg{BTRD`L`v zL7yvqwUeAh@V$Ovs?D~^||-W6yQr*T=$#0_pTa8FN~>f@MUJ-sZk=K*u%;78N!zK!`_tg2HI}%R-c?G zNKPw!C)M$i*nM72dg*$Q`;XVoCPP$A3^_B^mHk#00=B%{ZflpoG5B)6GW}kRPl5>n z#CZ$-^XL61@L4>At6xR)Xpc0bVX zJ64T~AEGimWkO={oAYOjB~F8!k0Og>-cvQ^mUV^5H-2--B&_wLCsiC0j{9=(URn^P zdTi9&*cGjrK155O7QCFW=)&T8Zj0Z}EZ*Ag=CONDCvmGi70wpOTn!$W6lBpk#)p#g z{;WuoN}H$sTYj%*@HyL?o|ho)2Jd@{SMUT+@BOU4t3nJu2|j;rUT9f=@&RPDwis{; z9h?UZ&r9?ZPxkt=-s#b$BDKQX&ZSvy8n6E57~$1t#PqzstsOr8$SuAUhBoF}F*-IPc8u0&(IztQ41}1?c2<&BR(xWBgfM#QgkNmL-KQc|W${zx;UlHCiWNNP8<%aTTNL=MxN?Yav}84}|H+f6q#t z%DC+3@r4dv@rPc~JD(6|Zy{;hteHTy)eaFq-+=x4y(}=2=wp3cnm6CQJ@zsaG#@j6 z%3~|@Hs8+g1yy|9C#PnumxaCltSJdh;8*RpRM`Z)d(< z$&PS%@#SOY(2i;*yO1#1s5C3sp)R$_kcoI6bEhoY>QsZ1MY}%%WZN>v;Pc-{acUTDw^_Pp~>mp4O@b-^lRcxSSPCnaswXU6v;s ztHHW?w?5Zpwc-;f>JV={M69+PDw)lFXm2;vp*+9KrFb<*{p434*ewfkt5ixsMso4Z zc%oFI7bR@GfaR2Z&e^j8R+5-tmT*cTK2T4HB;R&fcCT z)lrjeQJ)2`KgJYHOi+}Ec@vt2kjiib+ zHr4ZK*h`7MMxhUe7);HtbYIT7b@|5tKCEY+N#=F5yqTwPB(c8QuJz#R@#2Jq*53=L zG@9Lcw!wj49~QmX6=$=J?C?WJwLO;yKyT{L>I5WZ3~s#L_-VI?M%?2%Yvnt~hR8!)TP*&&-UV6z8NtbIXE5eFelmQQ zbht7mX8M@RB4w{ka=O$+kk2Va>1D5x#Xk`onYk*b))4bmD!eqIYC0`pZ$RhO-w4jQ zLzVneTgXPh8(lSj7?D}B+R2B-Jfkzto_5Je>Y_;Du~0VDB?Kz2u|RS<>Z6_ zCA#%wN}pF@K6X=j>c^ge8`AcjxoWG}-w4jdHb`HULUeh|-n@gn_&$xw?Pxy&Bikde0 z;MCZ1)7ee*a& z|5KXn?13`D%&)JUb&B+{6%DZMrBVF!vkk95uIn{Pm3?TnY~@hNl0)=wZkMAsYn4Q=KRLh%Fg3@^M%Vn zygM;>`rtziQMLM(9-OjIe;?7MQC*oS=M{f-*1yuoML=*$&L-pBn6J-PFQ;>~qU*iV z9V5PiQgn*G5&2j4Q>P~>inI~w$5nO;b5i02TaMbl5gb|0bQR1KWu%;f@n?<<=0z=f z1ZQT?gfEnYnK1ZjyC>sq+A~-?W$S$Xs@|4EX|O>7$AhVESw)8|6WvagFk8Q~W%~;b zorMJc;8DTwIo^7!tQpSVX|uDJ=@Fc9r}MeSX1=ml6{yLwHFc+^$kFXLOE?oWpnb4r<$LtZnM4DwP`(l>Wjly*O^bvpPqJ(Tkrlk zwcT@y|zT;ZE!?Mq`zKuUNiC%^me%AW_vX-yq`|FG6cRnme(SG;NJoCnWq~5vl zr?Il++3BAvI+w5g+!;L~MBA6tS^xR#$EO>Pzop(hJp*Do%u6UgAy)nIK8U>>R~?Fq zfk$J(=~ud8)^%~Wf81wQF7LU`gA!+7!ou{1IN4I_ND^J-LtI=pdqZ7WJxtCxu zu@g8(1$CJf&c02JqyaA;8%5v>sK^l170cNgvC4mih>%XH&rq4^Ulp}RB;JkZwHN8< z{p}5iGYRfLxS3qsU@uaV@)ui}SX~ zpkii%8N2AzywrMS@7a^A);T1z8G~~jU0Dr^#sqHzV_TVXYxSY2ew&_1MunL|iOez( zRoXIMX0{m9TyCf>W1UkuTc*@pVR2o?rbOmtg>`eK-II?7?{GF4kLJg2zhxZyWajF# zo2z`aWob?`m2=Gv&DEE#%et(}ylS6rt_drAFLir2N&BHrmIeB`){53<4m~w^zT(Y@^m-#-P z;v}`G1!p1TZ8z)kN_CD)_mH0pTReWnv=is$UzZs1v$O4L>GG4$(@s|gavBo=`(B|x z3S_-cax3VZwtk7ziYe!+RyZ5m29C!lrg?Qqy&qf?NX=DDdG-mT$HwzqCZjep{xb$E zs}|}HB*`cAsFX&kv~U#@`26J7{$ScgR=4#vN_tY+)V%q~-TfMJa#@k26;v8NKIf5{ zPm)yY-IOH)-_jI3QQ$zGvtlslrQC|lD}Rx+&wlFEv9*M%c&=-SiuXl!-zDJlMGkJ_ zDN7!kdbRB$>25<0O2#m~T#3`G=6iZdeBKYL66Qc(YQZ|UI6yMHUFgOC3xsK33X z)&IS>w6{iAP;>v;TiRKE@t+E6Wn*o1WpR@_wM?DgcsIHB?&W{RmZ)!E{y&T@y?QnM zpAhO_3Tkn7;Qe&l|B_kS`tKmr(s<|RuEYavC)O3%Z)cK2_6t$%kwElPbBqFW)Z~R1;Pk;TBIQ^kaUu*yR zzw=M{EJTeO=Rf}Gn4WrjS35iT_+1s%G_6XP;fAu&+X`MIca0k#j^9zg@^NIiaiiY_ z-t$Aiq^W$W1fL`0`nR<7h&3GI^TY7At!r}8|12$C&S+ft60%N| zpa@JRl`@-L+6=;K#$7-p&K;`nu951rS`ClV1egDomM#}e7tO}KXVcYd`ks9u?lzEZ zs)Rn)Hv9g=yUCUp%a z6>}F%_CGwz)nxh6`Yw)5m1oYGQD=S*Cpp|gQH0o%C)J+#4cWRu#i1hnhnDtejX^(E zG?_UPhE9~naG2^)_msx1P9mi&Ly-HMtC>diQoyw#bSUgJlR?hpl~iEQLRWubgX8qI zK=ny7)kh4K#WbaMANQ7pgyo;J?Jvzi_`GHhi{L1gpb!S7FPQCemWt||ALn?eqpSH+ zGLUIped;3X7gZn(kMSUq|O_AsBM(x`BvH#21ZC*vd0I9QHqcQEBv|e z`pwsc9Kj!@`HN&|8X$1r6Inb+MU3`Zy7vj;mpT5OziO5Vzm8dBeS_Zo8xfR_GBjxab(qe4h><{tpJfYJ+TT}4>zKiL zN2X)5%{cZ|T4{5$V8fnSl76GrNnH)D!bnmcuo zpEOjrIcq+p=9SqObXHn`(NyI*YuTP%J7?)z+)T-wM)oStxqY2$dxL|+-K}5${5g*v23MSsPT|4-!A1hTu{^pqjSH` z1iO)f2SInABua&3=?A|RzoL|Gt|}HTpdk!A_RioP(7j|3DaJ3#oAoqEjQOZf%nY1R z`~uORqs)N5))t@RAUYLP^*LE4{x!u|7bDz|<72Jc%FelLoi8Brd?8fi{Gt-raq`Qbw<7q zAms&iTlV(`%LqN05t(31(r3;qopmQ0yp4rkduVmnr<3tx+!HIPl?(%DzSmEhf14epKZ}!^<|7)C!kk`-(9*OvQ{yDrLoZ@#qyv7h?F?a53wTVeFIZbvq$9~bUO-^%Y2BU42z2OB>9`41?E3y9j(>7l6)w5$1 z4(0w%FmKXr%7ytPo6)D126)yufmX4Q&ksb93c4~M7o<~-Y1q??et(w`5FIb57Ic$B z&*=H2IK0MgVRO~;S}cPMjn1?k67**E?km98eAoxc7kYJknc!e{VBf>e@9s2_;u}-s zMOLL!GiY35s42qpyTVVng1hGfSb`VVSVQ=3?>mljoE{Pi^ZFQ^_9b{G!aC$$J`l^g z#;aO`7Zpl`bFr@>2D_S@9*t{mS^vvF*~USGe!-g-|4;s@Ys38OwZ(t?r|aP&O|-4n z?(f;qL*y?i?7#XagSMmz^It1G6K#WPFLpAbeyw6r?L&@vj6mA2wbQf@y>Lsn0rmc3 zQM|j}*cs|m)Q~%CU>(CK(@fGm_!=tiP)~Tio9WMot{7%=Bs47J)@j%ZIuJIfkRp=h z4S4bNfCi5p6~(=iE`~F=-Dh4R?CF}U(o0KG3*3@0RaiWaqI9A{i`(8HC-KI)?jIt; z7bvxyX_`UzJI=2CA$Q!V{=BcJ%MBvnt4 z;>H~i+TwqGElLl=Qz$4x^sv1~T2Kwr^S6A^l-1(;F;KtQ}wL^Mf< z*@k+ZIT$)c<)?xI;AooybWB&jw8~D*iy}V^PZ(!j6n7qJYB{`>q&WegOyXFUwvqK} z_MaQL-r}G_4gi*nFBJ_GZNmm_M6-%S&OkZiw&R#Z*scR0WvO_^SZSD)a(PZnt0K@s zZ#rdhJ^^4XoFt|m!ASxv4Qq}@Gw@k~F!a*Ua{};Hjh9OuVCO-sPm-+KkZmBC?JjEp z2o~?o_8pKVQ0Sj)*gbdT9xj>*otQ`xen&;5QW5E50%CsG;Z|%t?lAuy=p`v&Oo8o2 z5$K8(NSz=Zjt4wm!BgXenCq^+(j_w%BbFvf`TGF3Ul7a+R6{{s!6tugCFSIim?s$z z6yOCs=L73Bz&+$u1vuj}+xu>EV3AOb6i`=g_CTNKDm0cQi%niVG}J2e)pItOBU@q} zLnxW)s+8nt9^(qp7ZP?1ZK=+qlYTW-?Nbj^9EeRa59kN6UEJi(v}A+j=MG?D5D;kSkP_UG zHmQKQmIq8K7&nz<@q1*Vf*HUJ&>gDp>JY@tFN3)ov8+He8H9u?01`z=Z5}=`4xW}!Rln51}I70>a-C_9r+&(GrSq;fiGT-&!tcjMSvJ9mpwgzV#q3{lQuvdU3w&rI+(_1WYu0a2hmsbA3X zY}?TO?z|BNR#VVT0w({K*G&eM^iDNkiI95Sis}6}LX46fhAH^^iuE@De#je8K72f| zNGD<&6++X?+$U#78pr>#2Xy=a!T~h#xsb9SD5frtk4Fr8^(43vjQx&2u`E0q!ux|TuFZ)QNX0bw1YzsDJ+|H$dD^3 zQwp%hxW~b>WZYeyWkx@hEOh6 z9>iHpo?I4KVOS%3DC+5j9HwGsS~tt$a3NR`b{mb1FG7@;!qzNN@7$s19irt-@RAIu ziSC^6DQJ&6Fbq7>jw?}=0{3<24R6EPKw^XK=zI;y25G!>5$s73J$2;fSAUO*hGqjx zONOz6pzg5Y?!3P361Lq(=qz}0QIdp&WV{o8$wO-MJBQ*3H!CWXZIv>SNeVdOwg2%Um{GR{j~1rK0r zznRp|QLB1-YGK8(TEQ?%4>Zlv|MLSRw|5=4U;4LjsKf@E?G%8aZ6j;Ij9mVIgv;%W!%AHt76j&e^S@{gcT@}K{XV+1-I zNwZ4$LylKTmEC=;hR#h@Sb;2QWK!LUNJide?wA513+fo$VOLx6t z6rzRN0@Xq0bwk-3Vb=&Os{l^tJKL@ippQAt`nZm1sui;Q@D{A?1V8GVC8{9_s3V}( zs4UlF(a!+EW<2uXIpm%@niva*VKi3>PfQ7@K^h1~oMdhK)*cNe%J=#k>pb%BY!O^+ z5s3nv+FZapO>*_EIZdrRWFNq!i-`fAPl2XwBMypOwiT7p0GNg)qwA1b@gls9U>Z)) z+>?>T<7res?2u~xJ{I+x%)yjb`S=@n>r^eC|Czk6<*^6YWl1t>fv5i=`fMs{$q!)0 zbrm>(#N3hVU}5)DKs@CfQ}7cD)>DpIiuWnE>f%z!v5XtZ#^Kv+g$kLr<5g%bNgxVQea?M8=iF!AYkhzF{s()lz4l&vU)S|~J$m`^NE6%c4OLc+(gRi#s9)$H z)`Q`#DU5;m(7(=z2qbpK0uk~Xwi-@&N)wfXz>lwkEQG^^bb)R+;Vv(Q+gGf~PWj-+ z{P36~vNiyuMiGYLhrbU0u<-WFK$lqF5lKP;VKxpn7SRngcoy!3bAx|=L`lCqC9@0Y zVD1N#1yRs`QfCl=Bf^=#SktD8!gIPI)p%sV%?N`}sV~5qMhnj$G=L_%U_Xyw<8_mA z0%W>##Jj>|lU*P+0eCGAb_#%IG2k5lm}Q4x7hbSd>uvy4*S&~v8`;L88{!i;?Zn=& ziXr^D(g#zThTuUa`4O0MwI>K!URU^=X!sbX3Z4e-n`+srrDyo{jT8vN#4fd*)I|*& zz}PH?$#^7ed@=EK5ybMYmJ-;O@W(@ZGKh{uW)7xE z(rhd=&H(N106m+C^1Oi5JviU#f=?eKS~lPo^r9*OeW~VuCW2PP^ALSGd()*&fFs^k zBwO|({P+X0@t6G9U)92V%H&_eOn#tH?-}3YP)|77QTWQSRM@%6hiYrG*8qso+&2cL z2TBk;JJSCbED&F46D0YI`DzT#4WZio9L0c0mbU>a)}BR2)r7tY(y_0O$dJP592^--*T&C%ih5lWA=7FWzi~gjwUq+C)9*14uC^&7(5o@qU=~Y% zsKVk==)I3gF0o0wwEi{vWE7@=_#?6u1`6F*uPWD9g9_LG%ECL?`ctlXq7P=ktC^We zGj0V0=PCBx9=+*KY240x=hm^GmiL5@_xK98aG+&&_HXzsE2veU^J)X|cX%MhCO%#i zMSW70D0Bdz%@Yp$kb?i~ZI)9-)@y}#-_&;BFyo*i!$E@kZa4yZJ@}=dFOJlD)N-a; zVShjwF?-$kiVo3H1D|3k4a|2lzqy-JDiiB%#d$lKo=<7|n-q>I8Ki+b#z&k%5MC44 z$J(ke%)WrSO+YDw#-}+FAQ1LdAO3C({N6*`D1Dcp05-g}Pw7nGT2@j#g;oHQVs7m72zG22;megg^3=VYn&%m*B8N0E`pV}}E3(&JghGNp@dSX% z$%i!ZpMRNCwEtC&eoX-w`s#0=_o5g=X7{+WLBUONt0ItY89><43&vxI88IUYIyax` z!XL(!e!mQ@DS(~BSH*AY!^Y&{VUOXGL8}Z(1n>3W7uRTv>LDlPwG+#-b@3@i3+#XM zm&Bl#UgVn0=4W6@h>+iJK)3qJe@aUjQCbDL>`#oUaa00UeON?n7aJ|m!59Kz?-pd! zeWm*HcIs1>fDw#>cJ#Z>ze!8Z6NTEbG9lOY5%vk;338wTn=9{m%Fd8asTR6eMB$ZiS9{+cc-z);McT(Tnl@W7(&>Hczmt`{4_o4~)<1i$)5 zhVB>}HWB3A_D=(ex8vW2Irr>FGD*~(fPE(_z+Cw-k9oq|{)vP^f}W^Z+=0OjRleta z;(9YinQ!t<@+E{im-AWXDtJuP=XO&7FPWQM9H2$TX%{cf{Gp~99RRv0($@LqA0Kkp zhw%03PRZ~k`hSu?T&goa)?3)yeK8CBfKaj);Po?&qZI)gIH&2(2%aTGUEH&ox0Wz>ePn)S z?%qr_^uVLjQdb-e2R`HXd{ksG1^UR}yp-Ux%3)>IN8V@o{IH*{0Znad_R=Cl1Bu#s#;Y|~lx2l+pF9rykP=3Zi!DUIZe>f~0%&5*-F z855x(%}(XK>5D|R$|c!GbUAF1GhOMVa?h+@GV6umR;9^)9;s>D((uMW?i&NpnuKR3 zV&a!)w-NEx$8NHp^v4mXR}YeXc6S@S`nk$FeB$hzkZOF7~N@0XvSQ#`(1z{$9C?|LDB(0cA{ahBNa zPq6??@YT)hdzRHl?g5=EDH z9N&vPvH^|KubOg_S|AeHH+mV*TQp!SYe~)Gf6TUl56&H62R~8Wc&c@bQw; zCTI4WXQoy6V)(obrhej8oLOJ!fRBDDpfm~O?U;-zv<0HRP`hVal#Ag zm7K;vTf+rcogU&5Ia5^w@b^w^WlD(|tHzIL+Tg=~6Mcgx zG8SwoM)#1?RuZobS2@nDvAFa7c+hN|e`eu;LHe?~Fs(#y|hLt4jARp=-Q zHr0fJK3|%#Wg*WQ#B8*3?n`10;HL(S~LM82|cPr|d>st$c zq35M?I_2k?ihG)jtZ>u200j=YIz<$X4)L5ebQ@(!9!B2If?>HmC8IDpR>HkBARo9p z`5gSTnsAY1U0Pg?%5a5#@zTX~UE|?ZD<0rUs-eK4Y-W+*jM&Y6Zm>m|>@3>a4%zg) z%SPgd=~xbk=%M=xSRFAJf`3#&^B$}`QD8R1dZ8Y>?Ph#g`FcQ7AJThSDLEqhvA*(* z9$c^H`sfjRXup39x2(%=$|G#)rV(9f2!|etEtC{u(lXF5s7%>owxc}5w}ya+hT^oGT8fwc zciSUUrs=o-dIk|N3Rw7;$NVPgy0iHRXa8rl6sW0UOy`#Jce#iBWukESX)zIX^JR3$ z%cI&&I&~`0`r97lqM|Uo{g`E==xu>2$nei&+P~ZbwLv$viP$IE6PGLvjFPJE8Yvy~ z!!Q;_H6Vv^DzP}JS^sKlL=6^1;=?|fs$mstKF&{t0IUxvm!t3}x*(5AE*hGwqZkwc z;eaYUs<&7WUI+gw?5Xc({(0@HfdHqxv(@3TkVt${pE*2z01!ic0OPJFHr}(w&ANZV zBVu(?|H3|8Dj7?tbv$j;6*ytV3}EL~B0_;yCVSN+6qRyixZvw=i|4vf3IbqF%Eig% z<*Ly84o;T*{Ig%c2~M3_q+EF$lTfTGhhaU~p6jmMH(E$bq5MJL*NfTiri-%iqb;qz zg2fv5WQyUCw!rpCywTFy7JVOA5|r&HmjJ1bn;(f~^Dsu%%{SXTss(8tZ&$x$Tz0kh z0vDZ~de^9>E;ar0y(1VEKVCU%HtW?n8~e2`?u*2T7uBC+`pU6sFTVOjrMyxLwp(TK z4B*u__>ms5H7Y8Up2I@}P;!%g&2%l?+x{WKR=a0u2&N~BP9iVV`*6DuTR-8MxUXs4 zv(XIG<9`#HwjcUtFO(!aohK)OdvRk4_LzXZ0QO3y>L;9;sa^f#eu|_W6W8Ig5{GmM ze%+z`_ScH)Z;ZMI4ywO6@d&#>e?EWjVOT!#TUFZJFLHU`1}MFwN;H5Ow&mF%WC+{DDS(Op7qcQ9>_m| z=O!Tl7`swCTHzdhgyCh}dd&$*Woxx#Yq-FHsk*U;?H#{?i5M~ZWY-#B+0L80A29(^ zC=|g1KnsL~OjtRc<{iYF0(;PVPrX+z`hK}sZ;yX&HhAS@6Jw}+UB zG-S+S$RoLm#M*q7+o^8|rTha9vImBlLAW!NZ_?pl8(Q$$dX+p%Zf~RxDbB5gYKuQomN%BtDv;2R zK zFGSt%?hgzItsn8&Z(w}o1Lov|V1`<`le(noz>~9A)}R+#eC6A3A@+U5bCUx;C8Q_u ziY__oShz-Y3tG!MLQ5LY_l)Ub2hH`TGQ%T)zneyVcDQE2VE7*r0^vwM`)HzIY-nD* z8|6@RUk5&4Ii)=$s*2=BB79K7YltCMW>7S|s95OUkP1oFKu7o>Y6#U|ui+)rjgb|O zDnNCHYZyxpzx)#`YjIajyywMPJOu!iBgg3RhYEq~!5H>M;D-BzHD6QaWlT})$hGOZ zb*BcCCfG-~8jlbU10P#(BLdXoT;7+1x~3I@lG&i>jQWHjHXQ2H7gOyoPMzX^h@}lRvloV zQ70NX>U;9x)p`FSvc2g?fYMWmKYX?vw5 ztL+dxqor?mx}8=iwaO03-4G_zu4hkuA7&U65pcib^8Se&_AOue?-e{)2Kl=T+TV+$ zUWyc+yNMVq*lvU%VTCo}a?HZ%%OxdNTUuY39BUUYfJLEA3&_YRNd!-#iO#v+-{nGE z-vwqX@f2#k?VuqzBiR+s#t+GRGWQV!Csg%TMhlB3(ZwkJp_9ZB1VaelBQ@xCn++ARsZT`Y(T=fqx0nPSI#5IRa#_ zXsdc<#|!1rc!{sH7#yt^L=SC>iA!lS62Y>ULcnSeR0vQ~(I^@V28ZZXOJ{OVvqPi} zG2BxRfvR$5#ux*YPNY$UbSBYfmK4Y|`Y2i}1fs_T`NaqEIih8>gjh3SW&4Q(E{$|W zRU*p4)^^oeg%ajWSnlAdhe}urDy(G`_IPhv++ZdOKJ!BnV&?#~)y0~##&}Cd24tGl zqtH@aK<)>nbWD)2f@qg>%D-+j8lOoNI3P(jz{IO)pHc|d#1v-57%OcOZ9RK~2E^bo zLF65P_SGcr*`{7=V6-pgoJv$lAB~n9=>vy|pBuOHsbY`WAsFaG%p4SL{V*aR#_I3b z9fQQP?rx7l66tC75GL%C0ID>31GJ)92Y060D#0N;B+3#Z*b_0~g@@+KH>gw|+mnab)2 zaQmEmUR7J(J{k?+w;F4EP>%eX%FXH7ke&GH{cu9~-mYmLD)KHt>`n+ULU)5h2D00Ner@-k zGd(7&h}254tRzP~<6cAuvMt0et6+xuCt1qG~ zVBU|p(_|`xR|%SIaoBHsGi#pID+*yL;636<&6(XcfMsH3<@XYv;(9^|p7D1Qy&@ zT$K`)n5EGD(yc_bDtLNhFvZ@X{mq z_Q}PmzHLnb#g+O?B(PecPw*ZMXbEqzzFZ*^#OfZ{-#iapfBdF${V(;D^hQLIK>x-Q zEysw7ai?|OCmtf(DUvm`5G!{jsK&u}i(EUcl_hr`=k$XrhddC)`L_O>op$rj85d5b z%g$qQ-SLun1y)sVea^}E9YrMpao1(vGc~=Gpze~p@8cq~Ii2r;*Wd3-Ir6`F8ND9- zk#FtYcGbtN%2yRcsFA3qEXwG0)sJtr6r(h`T|Hjn64YG-dYa7qX$*Q@g%t41no3VT z(4>sHhAp_d$?ZKx?CFvN13$iKwBM0ZxSMVMg>WXT*}^SgLi_b~mf^UwyoZ}Y+WUsS z7lwGdau>WwU2}rkD(+h3eW>yo%nBi1wC`or^xuH3w=P?J2eb6Pd8a55LE(d^b(H z@1?b?g?OB`bI_8_LxLJXm5=HZJ-`gaTr|$b%rQt_9$s#;#b;2R%m8(zZSZTbIBG9> z+aHSaRuSAWGP)2$ZBOlG?D)gi5K}$udRDbA_AB-66ckr^7aPf=eJvZp{f7`A+Ub|T zaqw%l#i~fn0564|s7w)0Ou(3FxPTne9Ao7Moy`LescSji?rc4F9(o+LlDS3g&Vls# z%(9oh>OuDn$xaDb9D6Y}v(585&&^GWUx?<0+=Npc;u$}m4&XYyKt#MMIjFWd^0x9M zP+n)hN9WyoB>6L+0yV-bMUU9>{q!>2ZO@$}&~r52yV!C4{8+43kes|R>6-cMwYB@C zLBy+$V^}vqb}AWaI*zM$mulekUS#C&kEz=s*{Y~-tt~z|uiOt~L2@yOig!uxOG$on z(-(tJ^N)Se06*HR`&R+WZP|NTG>jzHLzE_I^7~7++%$E^-Oytz6o;BE9l+Xs!n*}XfKsxI+zPKjnI5`-i`2kW|9lZeul!-=sf@dRbG36^1_X^pVup!%Ff{d}hEZ z=m+=TOTOn7tOSqL2>&xoNL)5Z^r?)fdZPub4;+dHnQu{ehtEHJ4?$C5pE^E|F4%?b zMBJN8xAs!8<&ORar>pyj2cN85AXVp!2O);E%Fz1HDj zmxR$*gwfUoH?_}*{xlQ)y~)aZL4_fNXu0v$n~7ndJ(0vT|I$Cv8jvvrjL)e?aFL~` zMf1=qKPvZNX-OfDs&Lymap=9*ou{Pj3-MIb>E%( z4n>v2$%9?ad2#G5jfs=de404V4x~bQ7Vgof*SBhodwd<4a1%*-z5S#{^1W)3IsT-T!%dcz8#g9mgWx9acD; zjzbR;(OBLgsVRMo{zqDhQta& zOy4LYoUTfh?cGt|URGY?dR=e;DN6XkksZm7uqEI8E5 zibLcf{xCE|Rw7A|WG9WmtuL0&S^1PF$T>r+uDd8ls>77ZM%#8_iiL#5hcU9`YGA#* znwp0_8;ZpnW+zc%jSj5gB>1G73s1{4jax!H`urF;g7h zN43`Y6xNqVjuuJJ;|73_y1{>Lom|eN*DqYe`Sc%nDZ5Q|eUnKrwe0`eDl$xtKN5ZO zaU&5qK%XY9P0K)-Ia-p54ZJHhMxM0A)cIa8Qj1+^GsibIEzMtST=R6$*$vu6gYVxWdp zy^T+e$oeN@&7$b?ATp}vX8{Z!rQ5%=8v7gEscSBwcm1QQ$&pzyh+|LFcb8b-k2W!> z51UqV+^z^4{HgpaE+6MiVs5yFRu0Yr%)$L=5hHv;Es^`eUKSjT7H+tfKX?6c`|7F{FRMcmt~D&GHbl-6!Casv?(x;!Gk}X{N1ya3RDnH%iXt|BG1MHBRD7m(& zjus08&#-0@R{BrzKho0MUDbvd2wgF!3Xj&&iW;`~R$2-(rYV7PXfWL9aPZs7&_Co5 z;eM0BA?Uk9)09%joj-LeEzM_{5EBS}puClq<})6(l_ZSZN=s3OFYZ{0{39(HxXh>R z;-I<9e>hdCBjpO~9P(D=xMUHAOi$WMWEXU}c)im$ZeTEt#o|9OHs zAi|+X8WakQHSZBs;-YGz3SrPU;E0LOF@|Tk0U}S-#43k>!6#Yp=DO)wZQ@X@X55#4j;OE?GqPeN(Jz+Rk?ZiWnub#gLWe9rMmPk zsG=+5yplv@_u+h{iKPHOYeF|rIpCdobDuufQv!f7mF-mD!Tb6epFt_+wc8;R_X+S@ z_{qY(zqZDMNGtTAS!C7>hDs8wQ&?$7tkor?e@vX9o0q$`3@v8s!Ga2OE2whm8@_JiITiFTDf<`2+u=Om) z0Hz)Qq~YQIlO&vc4c#X0szc&ksf3E7=Rz^^Re|Ggm;X}pAXcT}w{M*S8T!qS4iZ9P z6v2u>pkgO+sMifC=_-*?OAqx&;b^g{Rj6-E@4xj=H~+nV67V^S*ZECu_i@xzNTNyP zarVp_(`n0~!nH_B1pfvLMeC5df@oTL)dq)H>+txRZ2CQ$K*&J@RBY0gA zXI=ZK4-NNZbQ40JX@^wgbzbgqAX=;=v#xw%_}d*2aRI#yjKEUam#Ua z`@TG%_jxSbQ+T*}ySD(gMrs$)sQ&1Wd+z_qL?|TF`A!$ z5)bF_Ha|M`3hj0EH@^HlbaVM{jxb}!e`LTy;35#KeE$#olyue`tGO(%zlZ-rLsP z(DJ^%v9aMFHLI?wrn;i4ss6SXE3c}~c-M}tZQClh+9)*qhs=7Vd#h%xR?RAVQ(XME@n71p(*LGrWoN$#DQ|pQ((tsT-mj$LU*If-h19#ZcGfK`{I75p zHtxR^WG|yad+fO|5m6zb|KwxOf}Usx^UH|L$eww?C<|jKW}^w*PN03#h@UUYFl3+c_6Ed44q8+UP3D z(cvIzwNd>YyiA9Ef^3VYm=*;ErnsOm`C_us{B(uYqsKi^Dsf!h%B`36)-HT9Ls z^A3Ja>eVx*yY)lW?`o)f|?UM$9Bknz&qiXA+~g{u9RhN`joO2dzW? zm4d>4*He5djh`J#l(Hj zR6VRw8dV7;t~wrA^S-Os0Wvr*)108r;H{?Lu`BEoE_^Sn+|GF>df!P9V^CKi*&6+s zNP>oGP?0cyaR`pdJW|)7psZ3!8wIWG`LHL0)s+Sw> zG2CAgB%BFPK!)mhrkjbs5Vn>RtL4AGgA!f!*%-ZjNsg?!JzdM!b-LC`QvZ;$?yuW~ z&j5;E0}NB(JL+;yPeH9va-OFhnqib?6wEdrEU8ngGKLx{kFlKogb3AsULQ>h_a6T5 z*i0pCch&$AyH%PPR*2L{rYF0fvF*=>@-D5Q8FQaw)A1Mrt5j_wKOw8|vg8%HXo7A@ zoL;8gssxFT@WUFk7m#Jp%5gr=rp^udo)WbW@=0Rh>3b~HKJGtSe3SJ$A48E>Zm(qC z9GyzHMTs?bRN0-Ae%iF7Oh7a!=j2xzq|22D31kl#@Q#aLsjyJR-##3ze-(Tc>AEI{ z`T(fB3*|&HmfT+2?8+dzZd@y$9a~IIu7_sil_UuyXSGs?xl8sr-nHyyBoVzIwJ9Q+ z-r=miR&N~5s03%1c`(ZRupT8zWg^U&<>^nAzsp#CZzvWPkoGd=l>&FBWcR|T<4%f^ zXhO|>ORNlg)Qm(hl|6~l6P4TNp{>A;(O(Spd-RH_b3j;@RTCZ+&>Y>--QXF{F%+EA zWu}8~SO9uCW^x)y=o{`}Q(^(MQ@o475SLU2X7aFP#F$0j=xE$Y2!V(|xL#&4gKB_i z3rEZBI~0GDWbbOBToAU#vdo|?FP|#q<#eGb*_br?dRI3@gT)r-24x(4Pv?s!_9Tmj z^+O2icTU#Jqw6|}&m2QOvvKfKtxD6}=dQ)Pd?~H>Roe-c1XbH|ha$sAn|~<59;MS* za&R;ue?Z-#f$h=O@|TR}ryfc^vMD93k&K6DJBr~8aGno3Mj)ANrGQAzS+HprjOEBj zoA6y(!F@J@N)rA-iG~4(xk$%VBAdo5$rk@vtpj71&I9|@Kpme~uH{=^G--MvbGqWx z3m{hlWn3yA?Eo-U#CMW1iEWyNx%a5leyx~GIkR{Ms3W1Ds~t|GgK(2ZNADpASQS|NaIDTVwL0 zKEg2k*IvwX70e3j_cyxj#n3>;GeTg(78n)+X;r+2WAB~W1T)=~Sph+!-pS3SWVZ{e ziYck2vEpoWL#8SstmA}~;-23HHEfXj-U&Ii>~w=GfjE`zO?3I?<4;6=^hx6hc}OO5 z7vC;=!;gM7LyJhgd(?y=!-Twhpe_7ZRpfoElzIjbEX*`ww9M*h6w>ZMaa~qx0zI2u z&cnQP8HB7DPkP>>La#%M!h^BEf?C+&V!O_Si%tkdA1@lR7fnJsZT9;vgaC1 z(WC3yiQJ7d<()i5V*PNAKkLTbsKF7Ef|xMKE7pvk@;AED07BgC(m|E*wLZRgf}*Ys zF%{2;xM92xZMfoYh%@wT)~n9CvSerK1^x|=zPF2&;0V0@1pcX>s0U8=QVBA91Up5- z!W{?|3}BJ)Q2ZvN=PPWq(?~&Cf%SF~HnI>GBO%XMNUjxy zZw;bVFGy|*>Uo{9VEQ6~{QF8^rhr%&~Yr**SKHVv@1>*olR=7`5 z1pX>?72p?9jKIvfLhDIyyd+|!;4#8vH@EWBIub}&&p4d|pXnm)5+hSHHKhjHA?>iO zh+vX&Qq5+J7n*pB3qGumDP9W>8H@#|k_AUg*0vyGqAi2j;)&59-vY?DI@moV+&?8K zr~tBogta%@xFU%`$H1u#vS4obk}x!mhRhbCag5}+{z-$@Cw0fd`v&8J5kwU&;I}AV zzoFQLes!_+7>I})xdGmpcjBZ8;0_KZ#{!$E15f<~Uat_{9};r~;H`(l@^Ez1){L7- zQjiVo%t_rboA*ut4WpOOHz#<>kgrD!1I>JBQPDF2DfsLVR~rg`fHE4Pr8sGUPniH_ zt)ch^WR18q*CSYWgr)6GTEOpd=zvJ#^ks@&hJLd_D612kMus^|KcifjdxskyKfo1& zim${_?1V?hnE*JCU|lw_NnD!73R%HQr0p7biyf|!LN>tiB-fNiktY<0Cf1OF%W%aA zpCk@j$2~F(LKZ@>aG0_tJa~dRSeRsSHHlD#Dgl>8uLL{wf;>ISCQxE|zd~|*m_1h* zc3OumJ|gS%dj5R{#)r(h)u;9qVKH5htrXZmeU#;8lufqD_7O?wCXJfR?JXeFn{&DJK*Dd_z5ra2ATeNlwUDJvl9jdquNRL_7Cs2T7uqdaV<{H_=72BIBQZyTyaq(g_5C8@cjirmZmPp;9srxu6Ao})Oy18y^5qoxH{u4+I5wF!)}%Gyri;+#2clDs|wia%<2XzxsVKV2BWPl8uRiCUAP(#8JpG3!0^d3xY*lM&% zPA^Q5iy(Hb^TxL+)tmAY@(vwkkT(hfRN`9KXlWsfd~V}(<*po8H}$o2Z;4pa zIUl8KHr#q+gdIQNpG25Gjki$wz*!!W|9%Lc%cl{)1L=Q++tPGB0SbPL` zW98Vwy;;Be<~zw7qV7!2-J#h8y39*RQ-4CufA|Qge%UOlS zm0L8mShh^wh!_y9SXmASn67qErgnk7qZU~>cf7dwwIG(y$?MDkA0WgxiZ3h1>8k5r z=C?v#)8$NY0k5n{7#L064QZ0mq93~mC4QUxs*(!w(bZ*=Up#MtSHwy8s6&sdoJk4fISN-T=y0_jk;vc}a3-gILVj$f5P~BO{8bw^DrrMV z5sm{<6yjaog^2o9u+9kVPQ!Eb`{>a{A3GGny9RNJpESma+!9LhrYhiggh|3G$0^8a zyw+Qu>1R8*x(eaAm3lBqIQoYWtVod4MUtaP02ZbR|D`Y@*qLxD^<#%kz-HBR|B zw0q~?^mr!&dPKzUwrhQ@gl_!-BwFbj7Zt$G--P#i8U(FM z+v|HcKP&gUQciv<++7EW{hhjxq@))fnYjHtSEoJ|CJT`w-tHpZ0Zg@Ph1_bAhkz+< z?mGGL=t9JE6G~O>&+Ydfh*j-;h8X* znEsqL9$|RF9G%EWLx?gK2crlg^sifN)}eeaKl@Z*@>$5FfM~s>Q)inZJF=cAWFA(S zFa3rc(p(O&c?&OtX8$PMJN zmb~ml9$t@8=i7l#=YJ!r|K^GWp5T}PH4GpAYW_~Rr?fIIwm*(!qNJCaV4df?OJWn7 z83Iw_m?A|~E#9g29bnX+Laaf#^f$g)-)?5%X`(wAq`Y@r;EpSBFGb?T@2P=R3Q7PR zzAkQHk2(;Fp#CTUs$V6u`9@sNSeOVWIGUaNi}koB)6Az3LBj8b!hdltOGd(Oo=d2& zj{c+o+^-wUL4w@@Uj%xVp*N{_VnoTDPeqZFfOi9MdqKo=E4ZuR2L3TPux=+%5w@B_ z$df{8BZWtIykVE3eA&jxr9csSpz4QZ{N(+0YM&z43$nWMm4F43S0E6dLe}jCdG7U% zp*}1vm0q*}5~mMa3*Q@_OM7v>Bp|XyGTvz-OTnPH%iXvuDl%p?l~HY%Kz+RNAWaIB zLf23)^Sq1ed)FMD(jF+4F!pjYb1Kcvio#$S-d6F6V;nU7%7o{mDr6sCup}4o3egrj z17SIMura7lc~q0N>0)$5pW11>4<{y5GdZ|N^O_3w1rGcs*J+6$*F#J!t3I9G#WOxJ zkD(9|M3~PWZ%`~V-WY7z*^e7W0s$q5N-olTonVgF%0FS0z$9|Vx?{P%DH8iL-c`u# zALU`j6UM?b{76WXB8#_&yE)C-*d&0(nw-0!gHH#+)=6HLv=2PvBTWAyG@eW6sVZN4 zj%Ng3&4YV+l6%M@{vIfQPvgkLy}PG0cK0#jsUF1}M&da4(!UB2eLV`tZ}(2?gw1@; z7d@29U`mE$6dgKnf|~&^_~$?}mEYdN@thP~hbq8XC6zF^xaZ-uuj|5nifqbDe>})= zFg(BRQri3KhYCCQ=`Z2c-wlu9ZDEuxcPM+m!GYG3qee8Iko=o<8G8_*HPGP!jL;r%7z*~33>j*YP@n$!%N;8i= zZ2`FbJ70nMP(Yz`7d?gm%B-5Lzp5M!Wm1TwMX{3ZgUocQ1=> zLgybZi}P!j7qHfSp=qh_rO}i7R>D@-pq%ldZe1k?R`4XR-zt<28GI_fUFFUnhN%9uK~<{CyFblM%Mn z|M$CG#PNiZnwoxfzy*0}joY2a*V%ZvmjNqqAgjs&F}9W)7{iE4O%tZYp7)Bf@!8a(Vm59I#7QU2Ya zT4!!yC$D%XN_;{BUX`ftMEu}>?h(7gZjS{1#%(WFTyiGnmDhS^sNy_HsUtrI)l#b*`fmFo1jqFgk;&B zNEd0Ta_Q{^KEVYicgiB=ofJ#edZie@nKt)ku3{dpS|KLcw{>?Fu&sbmg}W1Pz76c# zbfxyA?9P23q4JL+$iuzttSjXTA&;`8~@Ohm5`wEF}g^M>1G#+ix71FOgL+e zy?`p4P#RgoT>+0>o|7;{;SK5dcLP zw|A@wst8ZSZ#MdJ{q^i|og%klclgY1RH1y~-3pqJ}*9k+zEXyP$J`To@OaQnzsqu>3t-nUo%e##A7Y%9|tjVVm~rMuJ$Oo7@RJyg!+ zW#M~u`q7epg_psfg;++IknAcJ{rUj)+cUr@$2H7(t`myxOmlmutEfv93>GyUCTSt3 zzW>Jx4H7ZRneltW`eB{g_lco56C04Rf*sJ)rEU^T5h$(3OPy*?4@VZ4<^4c$5CVox zj4`h&A5~I4&3P~_{=i}=+{Kvh3SZk#4Ek0aX)^sQ&vz{uIC#kmQ6x786tKK{aaleu z>PP(X4k&3mjc;`HnP(|WDLj~O>pai~Cw03tTxxm=5 z`ZWP_)O^w(!ENVeT9ZWqe0|fTD?zF)EGiLvRyIUtBRKW#qki89?_~Dj7w&&@Jt(R^ zHA{fb@iVtM@fJC(emxv;`A!lJL{F1S#Xe}*UviS;8%J}`(1d;G*WY|Y7<*CST$-u^ zq14vL6`4<<^6K)?5*;k$_@C%tGu+Rq@cYFZZK0WSN7hoowLJR$F>9<75jX8{(vQ~A zI#U%|M`J=3wa?Vs`r~r4*|w|<eMc^31k<8-Z>et66r_>s`pAmUd`5FCBA4Eg-58o z5Tc6p7d7h>7_U#gUmt7q)d#9_AZC0*yYr%)!gQ8$yU=nXTyshWDr63_CSpw@HCmYZ zQ14gy&?a2x%O%H?p+5Rux8m~rg_*gEZ8e~alL^p)Tw1-iIx11`RZ#|>)=Z-TM!r~O zrIq1J=tW&=NRDk8Z)pe2*GNl$QzEZhtuE){5o`4Kv7N4pt`nZ7?;RO>wJakH7{8Y9 z^5lk7ce$<9o|!UW9#no-`FsivaJV_j=d~Zo%pUe9E)(!3@^l@d#*4YMU#6dpVEe28}1omWf=|nAZSzWTlK_#u(%T>-67)nfwV5}EURPIf4Gl> zJfG!GwGHF@>YxP`%<|vL<{i#3?eRr-WFD2;J~AO7baD0@qW6Q~a+WOm0!|vShejU7 z-JXUDcot2outItvjAh&V*;X#6vZUCj1pfkWueG5awd+tRQBLiuX8AF{dvqQ?_p??{ z9aknZ`{p57`J>;(TBlZ>h$GyGq)-FG;fao_O& zAS6a2v1cn*QG0K(x5lPc>{+XJwIz~>*%&oiTC-?TyQsZaZA#IiC`yYCqa%;&9@l-{ z&vW1Z{Ep*y9Ou9JGskhB-|y%3dE+&%>CjS+K5A+f{mMsieUx(Jl}~G0aWALGH(JCW zj#$kfU&8n=p80lp&bqKCCHE>++*o|vIdPGftH&VgBL8_2`Q&3lH_u0Ja7zZkod?;) zDUU2FCG4}Gzh<&fCLGA5$%QJg?sec%U27?diboYz2-)=)8U+lAh*D{~)$|{8nQvwk z(hZu8dz(OIsuOjpCY5B8dmU4Jn)tkww{hKWd)Go-DQ#rH75!;0<5G(7#G}`}pYq}g zN1N}DRr17Y&O~+Ej&$=kX;D?R7`MqEr1Z_&wUoT>ljI_bV)0=g`_}KINrF{LQe~oy zqAW~`udJlB0ovNDm1NnCs`3X}ItJLwm6qo0t;S0DI)=VabwD-I8jVyYD52k2SP>&M z@cHtpMO&vfwBI~maX`A&pd(%OsL5z6EAggGhVjFv2|b5#&2o7_l*i!vV5O&XqGt2Z z?ALKNO}Y!aH6N69kHKWdJ@pPiy%|No-a82%qVAXA@<+6K1PdKS`={TP^}a+&i#QGm z^-}OxOSBk2^zy-o&!?jsfs%C0WZ8rYCCF`ANSG)j97r7sOfkkX{b_%qex!G3&}3ab z6dOjfIwpoQ=rlgBQ_g;1KR1jCNV(s^qyaNHCo~_*j3kC7zc+rUafT$(Rmqr)XcOiQ zN&)=*FAS)bTjcEe(>jXfQ<$i*RN8h5tofRm9mQUv4An~Aa_Am80`}oN%q48JFd&J! z$*{>HQ+rj?MKW=RT7sA`%4aBtL06OuGsJSK9B)35<4Hpk5*?q@m`xj*DJK418oT+e zs3kM|N(U3>OtV6iLD^F8f}=MMsJlU}T*MxP**_njw<1GPHq`O62Nx>$VI@2Lh@NIw^ zI2!a^)Mz{vyuUk9fdWR);4Un%q3FbWVAiyexbut5Vuv@;y`7_k#C1o)V0P|qtRjXd zF{Bl&KTc@fYIG0+p9q7OlZbM=9pQ0cQXDHuQRaED>0GE8rViwD#soc@l(3gyevwQ2 zn`TM0qbHfQk#jPE4TVKDmc&it2*zp-U}`zSt1tpBbNBPgp7(j`>cZ2Pzpdktp%MUx zROcR1^t202;e?W9K2N8EL5!YY9x?NikBy0T6A40Qm3fIXRx|p0+PEkz+aHFY*FcVP zR!-)b=OY%FC3DQ~46d#a#%zIOn^Tn`+|DDCR(1p3Nl^j6wEOat0P3CvHRw5u^?+D|hjBgK5mBT54kX zivuaeb*B4llYD7}!BwoP5W%XsT&^h7z|)#v46NsAwZg9&Dl|Pok$IFk0al_k4ySQJ zWglHAjK$1i72hiODqjC#6%d=k$756qG)^C(FqZ*)ExZ{GFiAMWjp%^&bP2nT3HC(| z!AGU_M9?Xg26l)C2wVc38M$*UQd`+ls?Q9;DXaMQbn^BRez%|6&{mynDqUbX&^*Do z2iqyS{BZ4|p~v!x;n;)Evh{bCA8|k2ELD2EU~kq2C|+HDdN(^2_^ueom`xiW%$c(K z9UPoS2pj}+NQ0jVykl(}k<7lChy?!r4z8@plxuxg#SF(}w;b)`>D~}thEvxHfSV{C zsM?03Z^H^g>~MKwdSV1M0K-Y1E$wPI2AmjGWF2r|G-&DY^41Ew5=HjfoWuAVIyHJN zo{otv8MhJD(FwI-OROmpbmuPEWvMKY4=CtF@tbL_QjMLmu@8NRG6KgG89=WNPSZwa z8%pV$DmE_ToMz{+6*E}Ua^V`LC*ec$8g9u6g9PeOJBNun{|R2}S0l*Ab*6>C-&-L5 zaxmT>e1EXuyrR{1_`{i;ti$Zj`{P>=BC?!MbX^PwfOz8%Kf^zqsug{~eK_Avvtn|& z7<8GNUUGs1NBckIK@>h)FQa_1u469OJAjE?5A_TlP(+|B02X??W1&K8mln!CdVS4! z)x^#bf&lRYHn1aa_G1ZpBkP>2A6U(o64|EkK0uVx#&i~ti*p^ar-7=eVRk0yRT9~} zIv5D;?3zHmN(voVBB%O1K`22lmXq(zqp>Q_3O1#}(h|CWCjww0?k`;~31}F*+rvRdy1hJ~C3RTc$LaEV)50 z{SOhnR*l9=x>8_2>OG@j{Q2ScA9o{TU4N;K&$qV-DbjXq9%g$V>E6c~evv6`@_0Pq zkz>4S+lt*ZW?>9mXT%Ttrbrv_dfaFsT6!rxwa&RQv>o@Y#WoLU6S#dt%H7ajTg^>XbWzRB{CDE7%= z<(WwxHfJJ7#(j%T-s{t5lbqdJv{Ivi^CvlD$E@D1d*TgLQ3{K?ED=n*>YO4;A*vKZ zn|9*TB<1l>*VVRT#A|fswgVArbY{DR9l-=MmPnjC;eDOAIJ?)EU8XyoxytO>X1+jhyh$P5x#A7Q7@VOr`=gybrvBjqsw_zs>f9^)pNtZWM|@;v-eCzK zm>#Cn3C!l~cR}8w-{y|7`&j)Jst{hjf_u#+GIr!l`rJwFg5dIqt-hV-zq5R0Ha;gPCR%!e zi@QEIKhlh(@)bkCpICYH?^fx0ohXcJH|1656@Pq8_znTvCnl30uY`-N>tkQYiVt07LQoZ#|X+4mB_-Ivb zot`?HcIAuDJabk3XEeEz`d@>sDxRRz_k4$oFu9KpLc>!&Bph*)2Vr0ibnKH=14~st z=w|0n0s~d4j}IWD6uNo-uPeXM>GPZkg3slNQ7Nxpt_QMpBm7z#Dg1)Cho5@B#sWbn z&Vhg%sdChj8IMb=+M|wmySe3hupNS-;+T_@j8GBQoA9JUaaIkU7b)=Wlhrl=i9M*K zbS=|1{8*~H5Ek`np=MA5ffat1%;o*9SD4IDaUj?+YwSt#)$ZFh`B;;pHd)vXGIEP! z*Gk)kajY}t+Eu@AlPpY+kA3=rbrjf*rhpu$JW|79S-t?o4SPxUrxtImQ+JKAiXJpy z2&|;AKw+{FlVd*W$ta}RPyR&5Phhkf0X_+qi~nA&9_VRbjA8pMG^#3RnL*X9rg2ry zTLL`T01v_^sMke+ekBBu5|Ch^!TQf2($A+n$3<+BxiDWb@&c513Hw^8m~f)CoK3n= zbHs>i`+Ed=?gRBR3IlYuI}-2F6PbnZzP`HkR4+kWfw7=%0o!ANHJBmc?VQu>XulLC zXd2La0KQMMM=^*-C{bmH#Jved`lb4uB}AP8RuOv9o*Qv=EhA?HAF4QgeEzkbM;ZjT zo^#sKb5<9ewE?v)h^8ng>BkV!H8=a2bAq%bh3uy+HGt_5KYd9qA^K%x`tFyv>wwXy zbBqBV;G3ZVsQ=Z~ngHI>g`JrE=-9wPMx05+8wGx|rQfa2q-E z0>kdr>KQ)BwEB5wkdMn+4_94uCyv~i0RwZ*@NVE;TbE?JYlNp}35pN0zw#yVnGm$) zL0;a37ZPd6x?3K0(V1eugxccd-l@0TXPhjjyCDHl1V>~t|0Y3v<7C*ryHua3w^4){ zaE|5u9`9NA5{ev)q%pLM#KiqEAbV4xkQ(=tPBEBii}lX7OY*f8xrv}i!#3OzE9vM{ z_EzNkRqqFjH!gnIQbe&-uiU4F<~{Uk{oayB=KLpf%|-Xa({RU(i&p@!mH#4`%jbya zKfG8lk95ND6^m-0W8R@u4u#Nz-OFAUkyk;G&G&?V44Wz4DIFy!Fp($iJsY+Jax=|> z-#$6m`*v-*NKGNn-qJ#7_5ozEQtFJx@)69i!a}W8XsYBnvnJbC(ZkKjmu|zEV*Wox z-z9kSyS6v&SP06=&CW7ML)o;@pZ33WjJ`z|wPQdeM)8B-1lKaTSt~bRlttb^=5+?G zD1)Qt@frJOTxZ_WmtL%Dh>g2ZlT9vXvFGL-!->UQ!!1Oa)9JTIlNgHeFNeP($Jn58 z{&XQ;nGOl4r13>-Z&Pk3{NwU9RT#s!gLkh~M8`TeHsi(C%#AAiw?WQ$u<%73o7#CIAuly*CkCw{`m#0zUwJ-18_r*0c7GA8Wt z?ev03OxQirt%djA(rju@X(+{kHe<`o?rfb%((oarhV?jGxF=PVjPfPcc=z37KoR< zEY@s$>sK}%Qp4OYX@`+kG|lTA?J=>^m%S|GpN=a2d2@U>4$UYV#^hFFWo}}sdy}*c z&QdKp)H{=8W^_5ztR&UW1sZNpUi~9GZ%$&OSGqQOFlWYZ+$s0g$)RbOlkAN|hkMHV-`^o7RmCgji}tQT3Y8C=SD+RL zuReGEdLyflC27+5OiOP_2hLl<+g<9vkNfSXNn0l?_enm>4rv;sKfhT1>Q`H8kl=N3Ud0y8 z>RO6ZY<2Na(G-9NLmXEnf@M953UIZu7xH&Nha&oF6uLeIo-WD4waG(cxy1Ng$%B?Z zb_0B)vX6bXPJ{}Epfd!g0Osow)qjJ(i)JQp^+|#>RCyUZOQ?9e>Vyqrd6@+I;D(YJ z*z{yxmd2&{wNp#fF?M}maxq!YQr+&04l;DlF+IxH*222&sn7T4jf0P z`jJO6+m)Nbu!qVwC^ZHPl&zadQA~%i#4+*nTUP4xC{l1t#{nr%A5vV=YsmVuG74B3 zA@i_fU}u{yy=E!gY%1w-<%9%Vvm0THbF-UeH=X7KSXCJpgpl8+L+D@m83%13&cJf8 zdi=n+aVKd@&*Z2PZmP^8zTZ0jbIJw)-jE5mBV>MMfS{tvqI8HP{}phwmp0Hl)BFnd zI#sc!uu=~N5M1=+2i-MwR<9JbrDDWRkHMNn$#omHvTVE7c&5P1SG#vSPoXu-8WJUw zSpa&(;B*`SCVAtIdQ&O6wzt+qG>k|t0BhG8@*WWaa7N9QivO_FcpJ>_Csp|djHzX60vD~zEBhTzxT3g3fMB;6pAP0 zgu?%fIvvwwOLsKCy!Yoin&SFWFGEWmUQN`E@x{`hbW45uT~QCd>&v4SEe$yj(-cca z84Dq06>{t#i!rGO(F8tCip^C|;o-4(I_)wgO{_RuJ=N6CmXd}!P?-$Gq$}EdZR^O> z@A|d$G67tR8kqyiaV3kdiB6~pBEFxx!no(>-TcE46ef0xaKXC2qIi_(+noT`n)`P3fL?tkg%b8?9XaNbKXcM=9F;khT%)0l{g_$;2f+SSlOUqvZnUxtK*Y zfAq_E;F}#adYuW1Hk_{P3m?w$9A5fo;IeC`AC0c*utuJJuaLsX5BomqDNqNOC^0+$ z=PJLhkOzl)8vChV$G{E{AupUdi9Ri6qfG4jpNCx6966Py2Uwb3KB(D7sQ~AL|B0X) z|Gz}D{s#p0&tld;b6Nijg8J87*4uv|sJ;IgLH*d8KHUCq2%;uY`{nJ`@&B|>BmZij{uMqgy`9-w?0LV?_kRBJ>HYUg*6RGg$Jw@(+3uB@u9cb2 z|ME`L9mivj*Cx9z)zd*&+UHmIc3%cB%?>WTXT#)i6vy6T!2 z70(;mFX7XR=M~xYZTQ-@oo5bPMdn*iO#jV3nf=2)6&P(iGFZ>on|$JTX`d>emHroe zD)}Ga)17CR>ggZwDZJ!mXvxd>x!SAQ$dydBEzW0g;%RmX@57N=Qlj zXF6*kmVY^tYS@k8$(@h{EIuwi;qJZo|BXNC;vUK0{V)C`5}wW*l6oWP?te>Xc?Y<9 z_&K}zIHJAnojg?C!)uJ>|0$qsZlW#iTr6yzLv@XBSUQ@R+Z&kun}9N~xJ+mLUjpi% z{7LLTqglfL7R?e6Q|1>{;=8WME26+FtnlBWS(;Y=8qM;i<}#=&>P-MMia3tc7568? z_>2k+LKbWP13@8P27mDyWHh+7Se!0o`F}^VIs^Atm82@PLR9|+L0v|(eD#XNsg(+i znx8McuxnftRhWLHS#`5teM>obOSIB$?zz+WKM+*J`!VY%ZwEmWJ|7=NT zS&J%EmPd>7$^!d+CL14w%^QL5`WSLkADGhPH<|B|mtx8>(qzLDq_xBxHmk=@gUz{5 z*UJkhkf#Zuk|@tTW>I~J@0&Os7T+?{BWx=yn0C*Hn0cpIh#11zteEnE3+hp>XT}2b zw5O!Bvm)x}`0nJ3yqO!;31RmrOl{PC1{Z@tl*S(cj|HFT1U(rfCeo-yGTv(pNZKhT z2pUZ%kjpI*gRZg+ywmca;rF!2eg1vy4%gk`E$tW@S>HmY<|^~lv#>feWCO{QO?hjq_d>D zeK32=^xBp@L}>%3{{xx8Y4z3kIfTCwSs5zGp#C*jph44Q`0)Hw(F3}}nBv^Pi@i$v z?_-FFDYx4ntA@pY9qbH!Q`F>{tNrz*BX=d{>*Y@8-$w(iLBEeh4IfKgBB-ywzfJ!e zg0cL*>z~v0M2WxuL{NV(4*n6%IvSQB{d+X)|0e`>@|g>2`=j-893fFf zmIg-hKS}qa%Ru<_kL;|z5>tMIF%K$c8M@-uXkV}%sp&y27HdG{8`@HO4RbK5^Xc~M zpos9>8&cuLKX{5LOSUhdo;%te%omlymhNYSizE_NzV~r|%fmOlE6vai#&I>D(9D1> za-#>_J+m!F5NwuE%%Hgg#a`xBGT{-Tl1OCZ*}P9q1#F#%TyNWCR~#*ki0l!p(r1+tt095k!rD?U$bx<(oiLqZ=?i<=$WgBV9tr=twx=i#}O z`FPn?LE$LaFo#4;y6yTB@e=^2xb{53_K{LsD4oA9QVQZFa;?(qUBlf^)cO(yI;1xV z1ViVuC?cawLk-Us1i{V+l;)%;KP56cH?sN2DQOYjh+=X{Wt*Bt*r7MAJGzWntX)D{ zdVdz;IcPaPBx4GUr~*FU@BGgvFGyd&NibT4E4kuIjdf^9G0mtHuV zHT(<1KBMYQ14UP8vQ!aO8Oo|AxzKKvL!2MuEE3813_jSL2sfx!r>mxUqOPBSTyHk= zOk%c>M;ZEo>RYN2jUGCy95!SOmlGNs#F2fWMJydWo6dFC-6qTiR~B9)bi4`IZcuj6 zI-$>dQ?2uz13tvGNgttx7JX|Vg{3=IDvh`BBB9y(2M8PjCBj;iyygWY=Oi8#T(t@R z9b%T^=OP*T0IN8SYQ|rgDLocCI*FtZ|RQEnP_u{>aVf9t?T6W z(i$UsxUf|7G@8S}5g85t{v@uAB7XBX8=r);(H22zxm+t*iPm`_LBC5DqJHu2VKTgo zehm8{%A3~os~PsyjgkY=YUQVyY~E@gl*F|rd^0lWpceL~U$3vPR7U6RJUPfRQnE=} zu@^e!!8RMavuQyh*>3Ta@qt3Leb*CIrFoIzN7_8Gu;A=8H^(GU+Ck5&_<<#!ih@Bq zY6g!WhzF~XU>Wh%#P%z-wsEu>x55I)j&x}{=TEuDM{g%~Q&-OGXAZ zy>l^F1Z}R=H{G{*d@)~X*8JS|&AyGXBs?j&xf&FOp`VDsW<%Fle1b10S2Q8aQhlOW z?sgVYR~F>%4`-}oik#wOo;&LaR~Cza%e{bb#XKB!b|H(`w_rGy`+F+*v-i+-$H^0E(}oxYi6>`&i#gsAKQ2 za|=i6{Cxv1a#9IbRMZBv-pxi595(4(soK3mlJ(Ad5k@4tge&A^f$>O3#E=iL@jU!E z$0}NIEqGYPSs2Fq`{O5#DL&vO@3~W_%`ROPKjc56k2%mvCY+pgYySBw^wbOVm?VYWQ3!^?LiR=e%rM)B?z8R%yDy=l&G%3H=#oZru+`%G)iB5 zBe}Zzk|OdN?uGS$tjZh^_cbW5w!hDw`)Yig7&S<`+TjC=j^Bn_&+lC|b6Y4n>)^id z0ZCdQBg4L9SictO%VkRbPKY~%Mo3;i20+m>Q1DEwJwJ3E1s0d%e5ycO90?=IgWZZj zji{(0bbQrpOy*`72o7~)xT!t^vB9}9Y}im8qh!`;v67%t0R1MC?2_Re!=U$3;O#gl zXB;e4j<(*7(-|8lFH1kkz`C~0dM7akNESl&iKPq{KfE52R1$R!Uay)-h~u!tV9BS1;UytA`>pk3=yHW9`h z$9Nz-v4l;>W0A#w8XTJoBe8&2S-E3_?~?b@{qhoQ6oQ2)(l*-(sV1fz>N7%i#oUEp z#YlP?9+*`Ten1h1?c;Ra@}RCymHjTT`;b`+N%PVGHWW<5VTY(Xd%#)}g$)5?QRx)$ zbhImobqEK{xRSDaDOe<5*U{nt8FFl7I&k7Ada3QcTXY-4iRRq%CmFZj#Sjc^ax5EM$bv8b`+K%%(Bb;}bCtB*V!0 zv}|v0BvbWfB{G1Ey|b9ebLnSjFGa^o7(GfZ*R@T1sn^~F0gMw4w1^Uiw_e5U!RDu- zuLwe6N!qipB$FBN-AKB!^{k-=s;VVy4!cTWm7lyXkuEGhXzo!(OB#jiV}3?3Pb6J+ z<<*8Ngic0&Ll`U%5T@Zxn{SIdK+%7aq!EI%=OJOulIawhk43&im(HP{GW4?*OqJBc zPGQ*?(gF$@G0l(wC= z@fCygBiJDI{oNxPSY3qrF!dbz5-89ywU^$$2@0Ne$wPv$D0g8VSQ~D|8NLVl$G8PJl#nC@h zrp?PO#vVbhM3Wz_LlQ5^Vn|h93l+m@Rb_wfo!%10q)I6{eszls<|H_WU~T^=DiV>? z>WKa|Pps|{y^uu#aOHZ-ZE(ms)gh7b@Jtf;xVSg?#pRU$0-FAU)B_obDIa^pFp&c; zl%(y6&_a<#OCN_$1lLsdSFtJ*Y%kMUJux$~5)uM1^-NBc7I;uH?2&ghrwT0#ivFr` zG=ftUstmiV%7ikIoe>#NAHDpgObh9O(*7X3kAi+e!KgmNluycfz4~Lnb@(gCK$t2 zPkCP-iIiDFHcvs_)ASw4$XjUoF*N82jD8eZAgc`XAr;Y2qd`xJ(68%^7R8k>dn#wx zX|dlyGj&%I(a`sCuk704cT!+}M~&ne-H@>722%O+94aw@P|D}5y~avqnjMYPkdGnY zYZM8A?_e+IX?G;)e@H@~P6KS&pg($`uczB7&07>Bpx*(|K=l29Vd{M({pt}F+fBe` z-P1-QaON`JQU~puPS1(yW;1_Hi2(i{@1_iUe!Zc5RE4%}2u`h{dNa2bOeZUIM1Q;w zi@pQ<%L%{3=}-9`imrdnkUx(b=(e}T&L5&Gnx~?^c>V&)jvu>*2=Nb2rkPsK|Jf10aqQ+ zjTZr{9Y+I-qa2i(1!0iOlF}gxViE)EyGH)`i2lvNZKMJ%2}Li37;i)lvrFAx*wvUv zqTf@i0j9y79duf-iGHqTKLo`Xkvbd&h6a>TA!1+mKxai^oPejnFwhY(Pbg%>>9mRK zxH0Ls#xZ)>B%Vh6tttQpcs4ygTtrdbF-f^Ga#J&!7fm1B6k)|fUqGA!YDR|<(;vTT zWY`$xn0ZCU4>3(-k{F(zupFf#Nz!!&(6I-PvZP(f&&cGJ;+d=CDYD|dk7T1-V(5Dd zID%D!n`s5sCb~d$m)CdVAtQbOu;?1x{*4A-XtREN)1dn(9g40~m5ywB%)dAa)x@Pg z^lV7yI$ax|r3!6mKAaLj2A8Bb`&5hQhYB9eqYa{&)}ejGF!gFijmLwG<>S4#N4d~+ zofBZ68W!s6IBhCH@JykwIiTU__95VP`*UbM3J`aA2YdNvZe@5^z)%=5{pU8Qj(erP zkclC($Mx=4?}H-9Z_G_6DP!C7lNT5V`k}! zH>u1mn8<*AEdxqs8YbIT0q?E!U0dJEEOy4yETu7XDe?#WVH9s6rr!oR4pcW;fWl4T zk6?6(u*g+X@MXLcmSU#-@nXLJ8pRn8t-~*dGoc_^ahR{!xco+-oD>-<4pfp3@-89| zf1&}oqQ(D8p&BOrgn=;*v;_F_LH&sQ>X+dh4KnYsnJkb(A(wI0SLjbvUqY4uRHxrUgVWX60LxVqpyhkixd6(FNrn)>J4UkOKbaw> zQ?Le=Z<uRMTgAeoo-g5@RPU&Z08tMHHq zuxoXPuHC2aB!7OBIbCc7y{-H9zV_R#`x=lU%Efz(wYL}%MW?adr@5$~GH`&)jico_ zh{qJX4iESED=#KVDB1}TptCY2F5nj2~;z)uuXgL0aT@hgxT zHQfj}1IPam)%1<3yU2KY&PT7HiQLkvPZQ8k%LV+*(olCU8m4mvc6P&ohp%i%h=8b~ zZ$nql=bkDjOd^%0zAa1swanNX;r(bo{gt|xLQIlOL~20F1(pQ(p;~;g(S4ElRS7^w zKO>3(er5Vk1jWG@HMa5Z(X2f4kCzCF)_IoY5<%U{RsD}>7HfTzDm8fH3f_;Y_h1*n zY4}9#?!|-`!zWaUt^|uw)NY}9>Nr^1jl+6>z6x~@kJYmNY*Xu$LesWq&G+Pm=bPk- z7R`g3EtGABmUcCVm(i?OR6Q+O-tqxt2Y)HKTDPC*K$z8hQ*6K552+o4@v9AHTCEwE z2rBhRzhw}i^l^lXqX9lcy|83GWB0?^31HOyM3Ma}Ni#U>(?xtC=Lvnl6KywlnQ(g3 zwL$Mf$-k!)emlJNWN}y2&cC;zyroK?{1MMKUc2fKx_U)*WZ{D{iNCT2P1rqjN=ekP z+N^dzKKw8|l@s>2rhPK^&rZH~tL6J{!ArAThgtYCoPPN8c8Cxy`)5IIP9>%!UR50~DZQK#L?RDQeA9T9 zef2k~(Mr5!gW-&q>~$n(VU=Jmd-ztp{xv1#GM+ZxId@~JVSX765?lZDkY}i?Oztfa zWju8GYm4xqBjHaBM8+?H6aRcW@ibs5}CY@D4qV()A?mu1yq9(&eov63K% zh}_ilscPXsRCb|ran=@I+`NG4j8=B0VPebi{InBe`J`NGZnG2j6oxvg`plY&Mx*m_a(UhIYsXWe*R^VSLEC4V@I(2*zxv;(?| zu*^0>_U|3`tu1W6{~&3d{TYG?c^Nf|1#xJeh6-Jtpk9ul8^Kt6+R;<~yCqkyQVGx@ zkNsGdS_i121~k4IZc?5#tZ;WVNs!2;36TQ7iW0DrS|ht?c1w{VGPmF)_7E=?aelD; z(R!S2h6Hm~)BxpuPX(=m5@W6do_lP$3<5%k8wgSEKhK)zxS99?Qs{nxFsVV|O)@%$ z?~AM+`bqk9(6}@TH`pK{e~uCrZ^?nx27}^`O|_V-VXLgnmmjTBuBnj$#=qZtYcX9x zruoywv5B~<>(^Z~E-Nk7l0N26tE7A2Z=T1kRzj##wJ;>(8OqL^8PKQ=0l2emiExF) zYs-(jUorI1;`cRNLJ}TsE0?Ct8f3_6B?5{9a3Ui-WLFR;54#;x$f}0*IoT7)n5zWB zIFMAvC|(8+9_yjL93wOb36wO!;Ppka%236gKmRg*#NKj-14^a97IeIQV6EzEbjcn~ zzn=lQGHABzAvRl*i$p@UnQ;cnL_78>jhUSZoyXQ=KvX>c#3@+&WUd%9x}#m#WXdVk zPhe9L3JXOgIc64dm zc|LPU z-R6)@tLoNRT{zDTR7I21wswK!AB9(BJN;>SCD0{c5DXVxk)HK^_LXliCi3-%%FDuf zCb$=iOL2yScDgJ@bQ2Dhn7>Xo4-{M5^=8lG!uQR3<=u{SjFumsTDaM7M1>HaKHL!A z%R#98B+>Y92zdy890tGTUrV~hUuPB?b)7RUxNdTJYqm9W+-)>YiiM7xTjG@%emj5~ zvz;!HLY4G4;2VlVs!}yO|JCj2-k`yi3fu2(Qz7>RviGv3^;vYO6FBgNHKIAW7~40s z?L(E&E?o{|JqS4S5^RyMnr#orlDr>t(HT;Xz58B!(HD3 zO1(GF0ktorLyTAp4-B^7T{9|rT1JMT2??%aWPQWB z>5!yPyS4}Yan?3>_j^Xl4t(Xy_c;|i_ZmhWvLBX=*Qx@)je8WDeX7<|n17#^9eMXU z*IUJz3XkvOHl4BpJgwMarmub`{a^1zs@QrNDb)DWe#2CpR^dz}0f zSA0sksBL|}U_|$8iPD*4;bzHRhyGe?!j*A4YOS;Dlj&M*o#o_=Z0BzisSgS>wBBVo ztAu$D4%Tb@Ev7`DOfGqx9zNj)51*PLhp(Tf^!@ZI%n)j zo9=Q$0meDIHhpT<{4*tQV#%;QDMgiZuK2)Bk*^64*8QFd?y<@@QWQ~er>?hwI|%m> z3cvchX*)U&6xFY7;3a8#lcIVsQJ^BeUWQ_g)){qot)80>FliLd8jWP7W{6d6!w@tR z*)%bPSDbVm)H)ip13kZpb)LqV29I$>DMB(5>g?a5JO;ilL@aQwYj8EFt!k%ee3saVxfX&Qw3p(`K`)FA) zDbMl>F*|DhifS?%QMJw2#8hh92Y~m<>Dd!FyGxLKeuGqP?R&qZ(6Q|wZ|XXjAb$b+ ztWi4N19}X_gLG1OIs-jWw8ZiFP)I6l_2NZP7_6LcIJ^wz6NcAA>Vu-S&-^qaJXjVv z^#2NLH4WeA629G(AtyP&KvwscVq~{(pg5y}4uQjn!ck*w*s>AQ-jcrei1>X+ zc(}*&m|;KT4103%jv{nAnL@&d5lBj^hgXtgY~MwMFPOm(Eh z5L#!*EZmkpKRUuezI{Cx-hjj$8G7g8RN2Ov&ubc+jN27uIW;rd95c#ak9PxQ@=NJq zaa}5-jrM5e9xIcYB6$qa_-X)CN5V@d$B8knij+M_j0`zB0Efz�vOJNMt}|ljF7u#H zGj9aDJ085 zD@8~iB-oPRixz!R1$KvLV%E*l03vuhEKl1MW=UGS42LP2YT-$YA|wWbr{%xBz#tWl zxu)#VIRCH$=K`DyHue6-=%0Zb*rO@S0-UeiKi(ZB1 zQIe_&e$!enl(g!FfPQY$+B~4hb5>act=iVQ1QpRl4b-A%VG2vgJWr!#LPi~mpIcdg;M1J)Llmr5NU0tUMq7im zJd?F!qMS~W)fAJu=>*QZ%R=36y{2?yWF058@Fu&}9!Ic1Zi7Vz!Nq9`7Pvv4=*#8q zOW5#b*2nXhsGDA+^Iyu|B}cuh^vvO}c~?^ow)eEnmt#FDMb!$d6eB2%DzPV`E076tke5+%qIBX_Mx52%qdgN_ErHAY2?xX(zuVyoCUwz1AtUm+~$z`jTf?7Y;e zQMBp@SXeL5(tEKSpKo-vm!gLHLy2pGt_WD?46378ex&x{t0LA?Ize@yA0gsW%Mbo8 z0M=py-)}bhod$n7?~G?lux2wVb+rpM83Q-3oTpq^Bt+Di zb_Y!Zmry!fhdC3IRn*|}8;p7zdC%9Gyj*{+kFelfkEd_GEY@bT87I@x0okx>k346K z7;3x4sXZcb^$D(&->qiJB^3Q03s_E`=)FiyNemyZ5bMF3P3;F=M7lvb;Z!RIb1=8TXET!t2phb3EbJv%vfLo?#$1% z3}q}_5!|GPDxcU>8cl8^)OY47>RbhP{JPY8agR+Gy=rL1ZHR9J|L&ljDG^pX_C6m& zzbN;IbJ@!=M0{z_W%v|nR$vgZ6Z6?1z?nTr&`p{}8Bzue{K=6|^nSJCJuBs7J-Imx z@rf#=Bw@sTFqPX0wF&~C-?#X_)2@|##rO2|+%rW`0WiMXLdNaRvKRczXU*QxE8=79 z-=<{R?jOZo4$dRNFIKV_ee-(SGT-kN$L}eoxX;h@hc9jy{gvi%lwO^ha`1_~IY(>DY1v z_~Xy)4Ex)|$drxw!BdyvA8KHP-aa)&U5Io3GI%Bh#+_UHnZcn7m+ya1ir~j)XZ;A* zqn9xhC}V^4?mwQz+m&g#d&dPz=gSAY46(!1@zuKe-x54z{VZD*`1o!(p?>jz`djVU z$sWnZUKF=vYTtF3_tV|cIiEZ&0AF`F^F-De>OZfPkqrH^Ya}%J{&2VD@ngNZ9S$GW z66wNwhsXO(JClWjErI8=uN!l&PTbpnonC9b#I-3NG%vNeAwmY2b2RolJcEh>C_YPX z`1cwF{=tiSZ8oWz`;)Pzqzk^x?Q7n*fv>69^alF@A5?z}WYRkN+#VJ9;_sK~P?1%K zwM$f6@#Jg6O%Y6MkZSL{wh@V;XTf=)3diCZQH{M?l?QF8udE8!$#3W+V!l*-Im);g zxOMwTpXTT(G&CtjViO{)4gJ#lR{)hP(L0*8&nY=F62zS=Bn=kOC;EhOgoxc268{uH z5(#=}V5!*a6Y|+B2;B}KXB8M=uHt(2h5vrp1TVpwC!y=^Lk+NpR1mGo)zS-b0c(my)Rg5=y@I6b#^L23OpTOHvF=UOg-=*wd2ljBUQ|0O0sPN=m$)mY# z(amSwh_z&`l4A|ld|N1R!-0H%*=`Z6Y#S~mLUx=Lq8b8XwWdybbL09Bc=2AyR@_O; zC|RTGp^Z|7EQw87ojS%895U*W*!o=+PR@5TA;=c2Hcg?<6RD2IhF&{GqE5rTBMYJ` zYNAfN|L7b&qLhvcGDd)IIfbOuE!rC#>gj=H3XU%MsoZ*krVlV)3h!=*zmcno4JwkMJO4F5^e>Ik~qjYeBm?~QhM31?vI9*M*9y`M=D9= zDic6a#3^5&RZ9_dtynla0k#li=R1ZT;icb&YY^c0@{b>=*cy(2hf{4NP;1}|U%nG3TzIy{-N5#{1TlBg)7jlfm$UQs+WkU$_3%v3_k7E~ zMnWO?4|5vvS-K}Ux|g0#zX;o>;a;kV0(PdRaGcHBC8&8(vFiT~kf}a<_xsM(%L^>h z5$OIz@Y&m*zun=xw!VMtkEE{hQ7o%VmP({~8iY?Ym#&>=7x2XhHL*1g3{0A-y31Lp5S8Ca2d@Km`H-V;|r8%ncoyBNB#$b;uvLfwDvUt z7aQeHD$i#N&u7SkbZai7S&Nn0Ug4w3KT=AKvc1e3barrWoBVty9UCKZOx1%v&DQwa z7H8Poe>sVjqRJGors5`Tult{ET*W56eZ(O|tbNj-dCjsm;2aGtX|#A2)^sB6^Ey;F zQT*0Ln4V~*1Rmh9w?4BFo4~dz_hLkJB|N|Uu4>BjgY`c1r;>KDty3zUM4%F zdY7z$X(XJSBMOaj$X|TNmf4Xri+171ty_0?gd*_lUm_OVCt7t81jK%JuEz)87WU*E zRcSmyECRb`eRXp4af;kKp;_nKokZ<>?$lmHfpkI$Uj_@a4$4}dxs5-IHA8XSW?1*f zAe)Dd8w@+4sYOK!GmSYXW*Vune8}~Dw1=|Q5YR2>YwVC87n$I0a)YuKTn?*s=n7z; zeBC&&$hUYVEMVZXeS~APR_3J^cxZ=#VH*v!hKO-Dm8X4BxM<;u`|8WnY}T2Yc)tI` z+kJjD*)DkB4Bl#YbnYv>?dK>_JS z5GfWwkvm>{&oz7Qd(S*?W<6`2|3TK7m6hZ8{Jt+6=C=#M>Mlln&y`f2VNQ?EieKo& z_s7xIej-NNUvQ;tqJ;aJDTONrDRxk$H%+2>Y%3TRiED0Gp&6>(zIJuwS?K&RV+~dIM=UC8;4kM@Q-lL&`1QwL1RRUs9u@ z&C(;n+==rw22=xW(&NfJ*9Symk=Kt=Uk;9N%*>Nb$+;?uL5; zQSs+1MOm8KrWg-HeXl^d_j_ETlLLI#?9+M=im|`{SGIDPsn)vqhDyS=US?H^@`#b)GI&~K zjz@R!Bm2kD%4N@=pPQ>C6~DB9Z1&a^Usn0`x#lcL=}1&V4*HRe%u4aFsgVwKG<)lz z)#jxQxbh+3?uGKnl;{#I>jKSFo0FaLhnaAmD>f?ou2t8F@+ptxh4JaZT4>Pu`OkYd zzRT1opZk4zO0JY=hT2Np>VC*LqlN(SoQO4fg8%?{?rEGrH?^mcKyoh@ATk)@upa7L zNjyO}E$JzrLxclZ!liR3sZ0`)V4B-VnAZvIlq&`x3Ic#rSEw98J)ul9NV?=X`b&}U z$Ttca**3K_QBs~^W442mky=#hay3b`ywm4Q zNmm^u)WAV?yn@t_Yy+M3cpxi5K&^E6_ZaVe@P+e+knND{d%_y0%H;GW+Y#FGh|bpk z7G&7L8vLRy3I+8u{N!J%7ta{V9S+y2_+)!aMcX7X zHjEiJwIB3knT{4XFEa=z(Kr~ycuVJgU&wsNF{Kw_H;wr4mEuy5UEIcEZ64c`S0-<} zAR1IQIP$=fm%p#X`T@KU>*0bLoKZ$mbpl+h=Ym>lLQ{!Jbw&Kjmvv0brk>Z-y%Y<) ztY<4UoiSDSO0NB~fmhjd&QS{gH;^-P(0kKlKkLWW^4}YWgwEuOJTFx~R85E!nk_Y{ zFEeld9}yJ!cIMS)HCgf+!yMvd&Ga_Kl~vkj?hjHbzuzXHmlDU*;5N(#8N&LZS7Mv? zi{RLAL$*((EIQrBD#?*IZJ(-U#qJYQ2TO(Rcg#7WbqWO%XU$|KTIpjVQ$5-MQO-|$ zEM9aKzOF%nxE;`tkp>^P*YTpB2|&5ezIBZ^**~LoMv|u~qu3WnDm@DOZ)K9)P<%r+ z?5@aur;_9?B9sxPboFiW9qc1D{rdEVsHQkGnsn8auwXiw7N-e>^{G z?EHN$9t;#&CZTWYB3G$?;81P}N~?##`agtyV5j>a1bRs4;BH~In*HzQX1T62pbX@~z6M2C^b; zxN6Nt;&9TfzKHodc-05TBbIHfZ>~Q-MsJT=xO+Dv>4G$Ue(pJzlD}n^Plx|C@^t#Ik*A%%eAA!E)7t+VdHS|K{`tQ~o{m<={w4C% zMvOeIu722Fo?Ka;``b5dFOB|1oZfFNjBb1w`VZwa^smb4|0+DaeK+;*pi|$@RQU)6qcWPF-ycMB>!jRMj{(L99KM5r**Xo!M;!B6MnNu4`_<*EHat zH+B*uPk4M)RYl1kzEs^rD4~;`Hw#Pk$39 zvHu`Wf`1Vw{{MkEsTltqd9wX?zDa?0p-PV7Pvi-|hPjJh>PwQJc+36l|Mg99^y{t=sto??Oga4$6-8J<{B zJ9ClI3*(cu=N1k_#$j~No$_uAaC!HjtouES)JXY@R+7mkx$lXP#q^tG(8x;7=16&z zY~%)fZ=Q&K!?|vK9~>fp^8m%CrxXa!cJpE!DKW@fN0#)q=qgq_ClM%J9S`QNTlhB0 z?Zo+0>5U-1S+Ux>sOeXQloy0;-9Cn|OGbWnF;lNDci)6((d2)F+k^YqbW2P4%SFl_ z%YA?*!Y8lL;z_A>Zh6PUL4s(%I^IgX8Ow59?no*z@Q?l{;H>%T#H)w=b{^YKfxl>R7_$Fq4QF-08*Z+U{CWX;_*yF)o zuCs$E6jcHIB1((E&31^@(kq}#8zk^wJ&ZPrD_|(r>Jz#-dEKU!Ti?hr?Q(k+(r%jD zNG?r1Hyn@j$%2SJVD6@y=VsXXsk_Ni&_w^hFisq=&ZCNNwn)MA&%Y!fiSB`-N@Vt;!6j74@@)i!cm;NR@6~E=mdeG%kWs z(B$mnwoip7?GOrzjI|;66@lZdWOR~tlC?%liBVTMp3#)9DK6&8>nG_bBTgaxO zn7dr;IZWl@0kq)`tQ61rp>%i|P8(YS=?t2zCRc{U$@N2zquSsUq~hB^k(QdE>RCEG zr9r^MyAb$nsrtk zJ#27zyIU%-s&GuYfY>Jh?88%P%mTEk4iHl-Z%-5d`* z%o>O7ax%(}5av@En=>tNQI+3;5F3B_jX+Odl{ z{iLWzSYC=JjeSYAh{dFeXo!hr#C1~>AfDHehFd#C<_7O8BTVlRIhUHnj~0q6+b-6T zmSNQzEw9d(Jt%B$YCA9@-)+D(=zGjUCa5Z+pS+SvY`wk6k4btVwWvrS&6c68&)*Bc zekD(Btg|;V?9vvlA@o&7=B04w*KnwALb%gc>k%F2xD0a7>GikoI!=`!S^ZBMLY&5t z;OFB@zOlxn^y?t1rM#Q|9(ldN(}?s3`-UCbGofvX%#BC-z5`Gt%OZNqETo4Bfvz~@ z@{eAibJZnUZaT|!)#PE4{=%+gQLhq)%idL{ECm=q@%TE316;myK(u z(MaWYT(eDFZN*clWjG}r+nsb69`$ttlgqJVF1|laZCzjP*e+G;hIw1}=27#fF6!YT zM((D!_0>`Odp7Jp=LQWLYSRAu$WtrwmeKvDPW}DPIcu8@1LEoW*uKv#4|te+W7}Vm zr(02vn|j-S{4?@I)6@lir9}XmERqcb)Mw_t!_n_M3ysCF4>RQ*|Nn0mq zHAzaE4Xj=|iw5SL8^@C}p!g1|+fXxae1xjf5XGHz$hgF~$o0Tap}yMFy$LuwOz7dJ zXMir^8vWO=`PE?B9*)iGqNg}@hHXKOt5+{hQ^J2Eif&vrFbJW_5iVjKlF*p&xJQqY zIo}5v_g{P-dHE#uK!tzse%4mjB`V+RCf3 z@YX~^1^_`o52_O+nF)$^BTXs;FZslXiWjf-)%|ue8oYpG4U=QoWrniDY2?=YbTytr zLcn+{$P|L+>pRFt0L?)cHGvpd%41rEgTLQ^pE#=5AP`S@;AaDzY6!@qM)+JKCH@@) zhgI-fP59vQ;~@P@s z2PVQvC;eZU1d$y=GmDVsQn;&;ppb%n&@;o`hq zu(d8o78=IyM3Y5_od7?(!3&F7b_nYx3C2;T5c^Ur6rKRzYBc2JVmtiT98YSxH07k^ zha`5MS$F}2mijb#^B{!9Iq_>+A}}QMutt8fF5uH(!oF|P%P38PwV4kRoES{iqX3T^ zj9WlLBw3+ja0-j5WT1yFaPm^NR(yC5gLE}bOo>}H5}I#NlE>K%jmiVRLOruQ$}_`&9gmKW9m@(i?6M{KA-cq)z- zPAD5~M}vr9j3)mu0}c^AA`!IB4R$O|JxMH#pDrYQoSNh;!G&>P0o zSHHad{^hOrjBM_dWFC}q^HSjx;lp{JULmArY_vD7im4t_AoHyu`H-0|*jE%Regg0? zBX@fzP0(1#SrFdW(gDT{M|?0AKJgPCdr$F+ONkop}?(@)#k z0{1CQd2v9)i@VBS0@J z2u1UKg4*XGCLc?)4X5BPY{CF!+zh)R77g=Bgd(j9A^o8&TKer)VXN_d= zl<>K}t7tevCC|q4;i{n7A+*()Q96metI&~-RtCFqPeKF6j|%mlhwd*ow_|8tvw%+# z)KL-v7hN2L3r#6PTI2$bKX8KjESP2n0lJD!x|~m9;!dm)QR4GnJrKgovxFN9z{hY+ z1YpK5VVq@td0VD**i?w1Z(BiYggCl}B2nYg0rf5dbV;Fo_CEZ}SxmzLEIhhpG^8cp zm{HJ)^aSvjzZ#PMp(ARC_Rt*e^1g@qL`_G7UgB!$C=gF--5W;Rw#Qgu?n!#<11;=! zF$FEj%mK`zI%Vu#BzGPxC#w7SAf{~s7C`ATN<#7((OCWy$#GlcGotp%2>gur-nxT- zE5ZwnDv>kf+&|${O?1Zh%jZlXppYU9k52mTULdl#CJ&4~;=RTKErLT^mWi=4IyF5w z;-Uu1)>`4zz;uD4EV>G&asH2`ykc$bZnJ?_4Fx=)RUbVHa=K%2n zSL-_g*{{B0y$2T!fd7i>4MRNU2bELjcZwhj=Wi;9xk_n*{9>4Bt1?#}p4@$uk;a7h#KP(e@6iidQ3;%f= z9tQ8F%_kAPJ;IA&dKdstmw{&=fCa4wIL4I2Cc+h{SZFxq8I|F-ZRPYxF!RjAUkgnyOQnS=Ch*Lybo)tL30% ziszXXLyAU&%U5{{u_Fvr7G0uS9ki1DEbX+!_aM?8i%Lv3yrq&%ndfaB6on}E#)I0e zU|(^tjxJJ&@z{=^AK_0m5L!T>X1Gj`;e^VL(Z;=dD@F^D=puhwJ^ugzBr#HRxjMUO zJ1~;hkIEqGs?0@hXmJ^)e2aMf1Qu@vSpd-NvC}hh_G*mL zK7-Q>bx}0^Q8Wv0Dyip!q1h6XUychgv;!2CDh!Iu10u}A7e;+}K>F5AqGqK@kOY^q zLoY4E+Md&40v7~5`UPnLw$%&oyB5aJ7e;fan91kmOk{m^Kwq$>yK@LzZl=3*Kx1>ih77>5e?;;7z>^F?y#ttcIfr|?Pks@GA63#y z1Vex1e3YvC_&yjqQ>n6h2#qlUE4^9Mn_S&6Eq|mx3pHl!J9rXGA64{9n|{B(YXTft zPq*6$zK}53y+OS*5m1mv(;Q#(`+%e;a8=pbN1&4U{S2ND{wUqCIhI2`cL2V~Q8j5< z+*_*#PEI&XF1oI814E=cxA+<-*Tb*Eal#v9)gs9jO~xSCZzIT{4S zll^vsGYi0hhVT&>EogafqT^sJ9_nGBO3pTVz*Fe`hOuG^{@MVpc^uS1c)^9F{EZXc zt0Jf_)4a+{qs{~AP5{~^B8Bkdwn}i43&R79#Ie-FW00g9$-M)HZVIZ4<1ziI%i&wZ zHF3QA@*U%#yR|0R4KN>yQvODD8|?T=9l(rpzu4S` zD_nv~UR)=RE-Q({4FI(0Kc{4|bk8u*BUxOA8B58w1J zk*5WgA*6JQ=$(#mR#Sd$6ixCNfr3uMAgayxH|SH1R)qvc4>lYvlS-cQltCrJ1-GKX z!B|NO$^7G+P>ENR-kR-M)QB4@-!_xmG{{w%?dY>yj|HT8x(g{s$68(Q04wUW-K5>O z>WR1|=9NBpVAGH8yvpEhR>9HAKQGsRyJ3*2Li7va*Pc|@Qin0x1}bvp*yXLwmAXjI zTf7$|j-%csk@0HZ-Lmyd>NvQ`iVIUEbbe4bBkRqU#&Vu<9NoV906ktIFcSRa%x52l z#2rp@@?@=ndlTJQJV!mdR~Nrjo!(Wk1e8}?Q)Kil=UEjn9DVvM(gK5X2B)OZRq+`N z3kzmDW}fo1C;hg1tqf>ZEK0SK61IB@z4nVDm@2862L2g^!B>#0Lby}8NrNdOjEPgs zyud?MZE^C~&95`uHCBsMp{5J^*-@X|x6}IG#BA_$zrZ*bAk*<~86P6UrF1K?EC_xe zCtG-Fl2Nesz*=y+2|iPP{Zmy_{Rb-NGS?F{_-4&}8MGhK_QPY#|GOSOK?mJb>xA>{sGF<)V28J#23kzhg< zuXOx!CjFY{Sv?SoNKi=gy)?Wz9(&{MNmf+X{G3EvC>a|eM!_iZ7H1P1Xr<`F_Uz$C z$eGJY$0f<0(?uhm7M8Wr!*D_`{`srzd%L(R%MTi}bmhx3EAKmO#Wr}n+jXtWkbj`? zF;bf)9wZ)TW)Co&RN1Xi=V(YRUb5N@FKIJ$N;r7K%1-+0ck5y5UYC|#PftvQ_c)2& z`<>|<@>I;kedYfB_?F)csZw$@S>MJjy^_opKPCgMSe^>(c{Ez%77&gzd;Gkk_s2o; za8H4|MV`YR+h@D%g$;Y37EOP#qHAK#etucgaN2jYVb*4Evvwv+)#n{raXePOiDBva z_U;nPGbp{ONdMz&`%dLL2!s`>hg7gNW4PvzW(~Be3H){nf;uxeLRi9@`~o7Q8^Vda z?J)eU`||+>TkA4NOkpy7B@yS+64pISl|(J8Y%7kK)R3#TCI!fJQKdPl^9v?MGPeyy zjCaq_=FkV*O4y1&>F%d-AQdBpZ9G;VBzNX=%7MHZ;JHH3FcVAyYFmWTr8i+%0~$E^ z+;|z<4%9i;ELc?2E92WT!q#g9`xL)R^5{3+#Mkk6Kif8nW27Kq6QS+Y%U&UU@U>9w z{Q=C+PJ<7xaGTef9`Ha(JxX+@NVCjbnZvt=J?BVQvn~Y6SmXe(uLcQQ(FS1|Qu0-2n9zN%b_ReaD0nopu6T3QBG7$_5Acx0p^Be@{isG!H5FC__F^H#s3CUJ|~5!5KK zGoDx?RE8BBO@QnGO*X^?SoGx_sTaB4YF zCTYK)xrBds3D_+LDmckSYpaPgWTE!#4WHDjJnCk;T@CwjSnWb8etTf_IrCr(V^X>l z$!X&reDnSMD&Oa@T=PZi$Li2@Uov5t^9OE^pSTPdC4cdW+o>6xMv8p*X&IT{RnfSi zKU3*aKR|ass;$xgVagiEZ2Om@)E}%{oIlDhT1`l`jVuN`vv`e9+YgFXZ|I*<`?iz! z-b76O4DyQU6JyO4&~XirC^IrmC{^CB(MxA^IN_43XN9`?FKmzj-!(fF0Qs)15qkI^ zTQ}rTh^C9bfURte0PBJ26n8}AI}%7V#N6w{QFN8=>LM}ciV6NR+czE)%^%N4-((K4 z-ACBI8_Y8ggceFH(!MgyeICG6FaUMad~Ju_w=D9qeD6^UzyJ2TmFoH#D`(7!A$#p- z9o{EjqBMW0+vL(;`{>A;xbOc)(sa)}d%^2bSHPz1vr|H&-{-*V0GmpnQQRQAw4gv$ zyW&Idg4bLEad`!%GbY47JiVAOZv7!5Xf1Kr_Ka|nui*g}nPGSP| z({T{h-Dj^v176u`OjlwfR+1ln+Iskuf4SpX(sI@VV7bf!j3sieZkbXsWm^yGOR-wN}990uoNlr%nEhKPqKdX zUfXyNXSyvc2ITlXSd)rsany=zh;D280F#~r?eU-q^JH8PVDNNh!8S;Q34PU1)DMMP z3zV|Z*B;0Ftv{_Ue^OK3-|i9p)g!ZBd(mM^U*`XO#VeuJCSvVYj)sMdY+K=eYhi~bg`iWZilV{)jBP@*CaP(u}YX zck}wa)?onR8S^TjFIGX2;jmjPrc91k#~wsG^I<5Er2mdY_}KJt#mO+$ zdapeyFNQ#0JrW-LK=+!b&X=F{1UB898jES| z>;v7Xu+Dc>DJ#Pu-DTzrWuqhuU$E6&*dl%`K`@hSbf6TZho-H$>&@g=G7zuO8n5&w z9w3`~%9m+MPtU3^stq)Eiiq@1y}3J>1Tl!R7}^c*LF$o*;I&0rM?L&{EVhdiPoC{4 zMT=M&7D9(Af4))3M?d6cS(c$NS|b~qff!hYB_rB@FEmQj!R)(&0rAN)B}zvN%udEl z&rn8W5z)3NayyoCnVGQluPO?r^f#jol`^VpG19wkjl>8+1P{Y$#6rJ`aqYm@{mewYI5&a_5@{G?0Z<9$>>OBpgR%E1^;0P_?O($vBRXWc(3Ng_q zMO}4e+y>2H#^OS6YpRH{_-7faKcDGCMZm64dq@I(Q^vFdv(na;_eE$mMbm@gB23q3 zykn>2Jja1eGah)|QKeZ6QD}YuIf=`xM@CJF+I7o~*$Ui*W8TCq&a~oK!d>P1>&o16 zbqN-NAZyMvc%721KAYmi6ybikg|AXsHXBpeBM}uO6m_OF@LWG{schC_5bt_B$CNO&G|k*|8bLoAr-8d! znE8Gtd;VF8WfTOI{fOP6LXivfzC7pIQVj(e>iz7b%nj`I#4__yU(xbKENl$>*gZC3 zur*c!9A#yaQu5&&C{m-O-mvnAR!ac?1e;l;-Ykf7M5(IqpXaNwQo_27Jo{i zcE^(CSAK{WjB@COl0GEsb-JGH<;E`>d3(xYR?n21C zl*TU_jX>&7K>3M?&$q(8x1-kjiuRgb^wlkR>Wo`h815kMJovOwas5tuFcX0>yEQ(- z#B}UE6-D{WDhHvaU5^MY}L#c&i>^1ej$+xUoT z7xmLe*n|gR7TXI+kPo|UccKuBKdmL@?LS0m869?^&Z(l`d4|Qpt&)~M#vOc&H8MJX zupA4xQ{Qy!NL>lD3}N(HX4*A(KQo$>pv&jG9aU|G>$0L&iH7xK+rQl-CSw#Ath^+` zx#etn6++}n!az*7nwHZ}Jqfd#mU|MZ@hkRL>|$?#o7kU=*o5_xaFmyOr?B_)a`WHMh9di@noK(x7?ZxaZbz6McO{C&xN zLcy|2mJku!z7c7;-$s@|_TV??OxQBU+~T+o>xl~isb0C^e(&L33&yt#x9;Axynoj_ za%&p>Crnl!zx5=DU8`>^(BP)b&6`2w+qKRS`V;fPa!yZn%I=74hdDUiqLq5)x_yD| zV7k_)B}>R%4TzSEgvM(K-sc?+I@fghWtF__^h^QtB_djG;#E?r(=BV!r+kF7qV-fO z=b92{8*Wl>`(ZabJEar@VOW0@z}5}5W1%%3pAT+6hrl>9qXrF}J+KY!JE=?zdp+UI zo89Z#JFyZVzS3n2NTeEeX<39#J@~^jBi*Qy2qTGbHNi-W!R7sW>x6WdvNy?6@NqYD zL{4PVHHpie8l`EZ?}TH?G*~1$`<;5s!{6IY#LWSdJt5t9Qx}eQqkJED@ICNYx&Kfl z?23|OEBR*yzZU)KtqHl$H1jsKYT$Dll`3&?^k*6I|Kvi`r$CNE$2v@>4L$DE=LYF zq=2+W_dSNz0Q$LqKuXmtqeP=%?cjnvOQc6eW9_Qr{@1d+(IqA!U?*1m-v zE^+l5XIz0&V5$KKqu3wGOenvX z&!hduHqAYkh;V8?M*c6-0vP`%j(jH8KN^l@WUf)(Krp`fqH@u*;zD-m-Z4Pns|;a6 z^79eDrMFVb+ze2FasNQ;hiaP-8RniB{p0<&T$oGa$8t6+tOEO-%vwurAZ!A!PrtXI zQXgX{&y5>yyPMt3$C~C3A4R1f-T2a3;X>B_w&>;P(JJ{Pp=^n}yyfCQzTJBav3|!J z=hN$;dF{fVOjc7c4kowZ<0Wg?-=b4iQ0nFKQDvXhn{P@unCHjm_}-7D!XHn?1cC?NhI~|!aUyfSadM$VP`mIX%N4HB zeR?wM)l$uqYZrt?MN))xp1e^EV^jL^e8oB&`{PJ#{kLsp3H!Hc^kmeW3(o5K)q+FY zkL{!)v!Em2^rj+Ln$vP=dHc@7_{*Q3Rr{&XoTc4AHOD;~FTEcX>=D;h`Frs3IhXqv z+kSn`hi{|(w<&!k#{HMnpFbbE$BW8|ddg0U8)U^E6>Ew8Uy&!K6m^Mb+zH%_baYKFyu&F%H~!(9{zRTCoTd3Q_3&~T%{%lj zUx%Wf%7J*{tdm7LX;QAA7+xh8n-ss5u^nP8m%iS}RK!?L{VsH*=O2-$aIL8tSK(^M z3SGv{RN2J-3nBO{y6iqjJ$(OhN{7C0zn@=Ks_--D*`L6cimyTtqcE-)Vsk6KJ zvLRf(OYL7Sp6b?L9SX>^^vm2h?1V<#LDKdF!M`m2vQ|n`GhUh^5Gz0Q5!NWlkR)g0aY)xd>bW!R<|NXNQ|{`rcdSbVQ%n_ zkavG^8g7d{#@~V&dLaR{&oC~7;)QVKtby|^;Lwv+oYWwT7iA$H&;!cDJ1t92+OuU* z)C_YCWuo-FWKx2lE0-rbu|w8zugN9D7?4p+=dzRb0cHGIVwrRUI%bq9HK;y`oR>K) zW`XGl8oIhT$#4+$_jlWLBkKl3xk%2BENES$`prQK+9)gqsW5tI{g%Q8@k;3qS#FHT zMDlZK+2)uhL)MQ)Mz8N(`P7?g85v;Fm(*{sb7moWi%TvyEfFtLEBdKjI75xi_THRd z#u3ZYBTL*GU)0ekX0`asq`+yY`Be%rm-Ggw&i3z)htW4)vFctrXOeW_Vm@=8k?6QC z-TE@*#H;p_@Gt)n!_K8FS8sK!cbw81sdi;Oi?BhrkqY(cy5Vo_vj}!y ztmkRtoyhn{QBuz$R1q5fL|D~;^<4lsTW5XYLY8<3H$#y~sVo~A%y z=q_KT4>{@qs5TpTv{N>`+RdxNij4n_QG$23NJUVbC)!+XF4d@OLqYKj z^X%Z&A*sCNU}AQ7onPQNxKb*2;a9>v@+$>W>DEdkMKpd4etl2hk|`G5kBK>Pnus^y z16>j9WfdwI-9pKPY>twwOlTRmxT6XUSXG}=c28z-Ve%;#wIFwK!~wpqR8A#>eB@rl z1vu_#r)2^88#>G|>f+1qFAM4ymN7-HFH@Jqqv_uGnHis-&E=B0# z&Tqkvm%b%2PJ#E)*aQ8rln}?9-uIN3&xBBh*2UdEA8tqOr)f)i0rL=426 z>qw>ENt@|nY*aW1@uDR^mul*!z*lKiZNN1lMQvh}q@mIQRz_EwdQUf!)VeOD=&0@D zo5dxALuBKuZm@LqikXY^vZ~%mVbIJI8w!b$T^MIRR%momgw%aKs1c%26t2yd8fO)y(mZlEbudu7a04iRI^v*mjLyD4mbUCWs;D8I z-AUE_p^O)B`3+u}6uzZgn4!MFNdX`|Cl!71d^}R6PJ@)wiC=+-naxK%pH|eF#>=TI z+FS+@cSz;5$6e$(b6lkM*@njQWGdz@S~~ZTieK>NOqCDbAEQXC2Lv#dsb~Oho`1R{ z?d$opAM)x^7nK>1bh=GNF6c)jot~!Z?BHO1Ridct7jw3W5c2No7qpOzn})3)KB{|S z7#8;&dDj37-{o4O6de;mnZOaFdV~{ou=liLqezRB1^@>!69xjes^q(_#fDZ4v2pL4 z%OZbs9z;C-{*KmoMLH#s#8$d()!pp7#)2sB)y=jw_p!N~0!ITTPukWwWF`A~3b+!o z+BP^gj0TYf+)1r%n?3cFV_t3(pAA4w#EY65&>$R|YP}70?J7b#@=Ju$;ELAMtH4@v zL!uXMH|q2!vA@}pa>)*2smAxV_f1!^6bAU-vSn_1pKJH_kia>GG+JuYynZ@RPTJf^ z$=V&WfIj@Xy_|@>|re&fcmDp~dF}V{>x=W_&Wqm{*8t>s02qRVDUXB;LCT*;dY6-3 zkgS2X4@jpDIwOEg5XPg^qz-xHZV0f?pL?E=$UH~_f+97KA{RmVDvz=X0d2^Gb|9#@ zqD}fhhkc-Mig4^KMldDpkeAE2TAyl@=~4Y1eU4Buz=bw-4>Sjvd9(LoCwPd*$m8@hWQ{5}?iT z%DQDDwrwGty@fC{N1&)fb1IBEA!xW>L0N>Bl$|2c0NlamI6I!I?BkI=;k%hae1U)gKqSI(w^u!xgcW%|&Fm)T=U(UR% zh;Xqv5}g8GOdZMnlo+kZH8uBj6v9pezN(vhNgEcfM@bk43@u*9h=zk;-&XY?xGY&t$j)uQz$p#Kny75_^`wqHlLBDUOx@qr&!OAal1ZYNzJ$R+;VWKZ#=RKZxSU_-M!E^xsNx zpueY|(D9d2Y$J3vcXhS>trR<2YFnG@+8V1HM#qU(v6L`W*w#ygivP&5y{@lGZs;Hu z*@!ri2o;Grw$hTK*4j-&EwJEP|-fK)H1P9FXj(aRQLlGasLBUy!Tg&P0!l3TvIk%QX*SiJX>7s z#w{B&%RenP(;I(sY{uqy?&+ESi&Zp5|9|D!gr!u3B$fYgMR7%bF~$G3$fj!khbs~v zK557W!1CXTMXkvXqW>teN!lugPFZk%(yA#MO8zfm@$w{SEK9-b)51_~@%W3s#i9Th zNi4FJP8S;$HY_|J%QGppxU_GxAzJ?KwN-Bnr|?_Ye02lM{*=$3A{$XG#?Otc3_NpY z=R$6~()K&NDG@+kky~RPh!yC z@~!a}x<)6^cSSr5DgEw3)Hf4Z9Nt07eA{gTw36}>8p$m9tL6OX$+2dgvxHC2Byh~p z$hksBenJs=C~x#&lF^o`o3w+)6yl{W%K>o8lSngjRd(fs`! zi@UcLZ84PuHz>;0n`XScnQkY^Hg(k`+wJlE(|cMIiR?tkG#`yO(O(E=9L8 zg2}J)XDQPP!LvIj6N^!vY=oDnD@%4IT4I6W6E8v?%648soFS9R43<}oGTmg$CKT^^ z4i2Y1DgwEnUld)0vzJmv4DD1ltuhPicr!5Y8Vo9%trS4Uj(0V3JLYJgk)IY!gePwb zeXjFT&V(1hIH3sDI!X|a`p}YHF`Dq`tE)E8Qj>ss5m$2+DsotDqIKr&{Vx{toEfx{ z6$etrsdR~K9}U(huODOs`LFNmno_R6)+nR%K4@pS@!(LSK!w2`e?`B|_%+$Lp_zWl z9q42Ob8&^|^)Gvw#srY0B0ZO;-!XBCnsp?po@AIKksDbh@^!*P|NZlEb|g!Ms-R-l zq~j4hveX~|qUjuqVC$9lntfuAM&bzYT=n4~rnvI^d&btm?;qR;&V7W<#YBEA z`fgQv%C-AmRQ&iD48ALl4`p^cSy4TUKUs~F-)9=CfT!w zqQuU&i~cII6<3{os%YFl+pYdnWUG7U_VaVo)}JEVkNuzjQe+zx_#+noH;Qc5Q)MK> z;qD3^?3zI`xN1>?$SbL3{UDE8(ocj?IGRo4O(b#tpPR|CXI`7ZH>nCqaHGo};#QEX z4zV)g56WP}FucQ2WK{TW%u`V4CiO<Kc!wdi4QOL^tLa*|SW_eRw5MAOXY zqi@T=Fo%_hBX`7&yr%9DD=3x>pEsVXRS*vEb~ZokSK74h3HPq_L}uG$zE5v^z&oiU zG0cW$(ZXrl?;%WhwVbg$QubGh7^&F@xtS)_9^!kL?bsQGw;8TTsH{imt`(w{CRMAj z)avE$VZt0dudyXtOfMIBg+CcRR}b3Z$*r~$_L;?Wezm9dpUJ7Dtize`PvL-;|A(_X z|AzYU8~;DdFvBdKW8aN^XDo#%Gsvzig{bVigi44q4942nvX&WJ_QqC(EZMV1i4;PV zG?q%G=Ii~s-q-cHuJgIh`JV6hA9()oJkRr7&hv45+{gV^^2j(&NSp?=%+p8wT3y-QbXKtbGaeiG*>D#}6p1P`<1 zi8MRRSAq=w@g~F6KRE%jtw$=_IF@wchWSeaUQkpOA|MimNgXp zR!t~V4@VUl2~NQQ4-Z8Ud8 zq|Np-jPMeb@xB@Z_4b;uyk?A4${a?Z#38mhHgl_wD537eW17h;NmvWi%H2pJ1B0h& zOOP%>&Z;k$hw~<~l}|ZSNu=!{03@WWc32J1}H+|82g} zYfQ4l=yTS_oIw=P8~A+k@WNh1uI`qi(HUhR;M$4I~rG z70$wgKDjdu$qu6{yzK}5*z|@}AIlGd3kL(*;|=LIM?Z)PNy9JEJoy@zJX)fc;onNZ zLzvK23EiK=*6EGee+FmeoqvuvjyK+0l!fX9{(RwzYRVh5TvsprIqGc;k(eA^-;Aa( z#^`YMg~vFsw%sG-m2OkCW5Y*OSshr}lvy#x)u#=H#{`)+iyd~e)!aXk*9Yk)PBnfN5qTFCi*$K5iRsl}WEu9Fy5H+Jt zPEQ~XecSp*KTP?FM6mcvW5NxLqs`Gq>%P|sb3L7MB2NTU#X(Gn+C!z58BmHGSPg~W!9TiIP%{AeFU-c}kiK^l|%Y9&RN zNIpi}=0JeQ?>kRg-{4&prSOOk;)57tNl*r-+2{E;Y<>{VP_M5~FeHvhM(ZZtu^V+2 zVZbq62^EB7qAml>932OPx!S#Sg0}D*&5UNb}1r zXn0tvCq_wBg!D2KxGA8Qz*nP46>>4SQ(8C}EJ-H-sM9 zxqGJ>jAE6?N&KY-CyqYb8sl5K_1!>YruX!Q(Gx&$(ASL$PICnYF_G?#(JUEiW)hg< zW4AK6(F@n_)J~d4-UQUKsNr1bL^sOL8t?@;q~dLlWdQe}xGz{vr#^ubAlUQn0Csfb z{yJ~!WEe96!LBW}Fo=3U$5{9A^1!(L=%#ET@J}=*7bw#z1_41sK9P|;7<35M8J!W! zWCU~n!7JSDtFC>sG9f5m9Og0?70XV?ZZB1fvO1aro*EC+AII+M35@kbNA4 z0{1Yl0;s&>Km!rz*8DZltx@zLNJRnAE_n{?2&8|3GpO2hKE7KA!#vjF!8|GJMn|K7=_-L#9*Ev z{#&(J60@5nYsqCLf^t9%$4e~i76|zVr2aC7Bbm-RcfeY2dNBgvXU>dzk$8s#in|4n z+{9sNj=-QRdkiJzpogi%8t7X}_i=;RXrZfbLhd{~52c#bQjnS-WWrj`NM+ct5RAhp z$S)Kp+8{dvxPzoZ%NwBcSTQ|=h^9*Y`;;?eX1<`{5UBXgY5Sw)ZtMwU2}B;c!;O48 zGvg2(eOVmVDhE7|iS*=zX)_!V`;H>=7lhYkWmJCZ54FI*nQ$9hXO6Na6}Yot^5dR` zi=1Rb{|!^bv*DC}a;I7YLz6I{R{7&^f_|WL4DE85J=0B(Nau9+C@ZsdgqG(8{RSX6 zR3|q?o@d7tD8VFrZ;TtH=UgB#%f+DGtAJwMZH*~V9T~O1guEI9uyjM0T{%91-~blj zFasE%WDd1(7YTU(w|o10sFI(kUj}4@WmeyOb(iqW8MQo2C!t(UG@eh-11#f z5Jw~Z22U{RDI*wo2^2B!u>HV*FMmunqH|C&MaX`3Je?!Q5g78*FJ|F+?U!Kmya3#g zl~0X)hDEvA3K1LNcus!aIrLv&D1*%E;s9z5MnQW}4Gn@SnTe${9C(le0|X7rhS$>B zmW~t+2C0?B_OaVI5GXFfp_tLoBU-bAMd{uw{^lWkdYEfwv)JeZ>y?{`-)#cS3P6f0 zlx!muc>^9!7kHP0{yW6RuugW#W&1<-W?|wOx&dL3`Or>9e|^gs!KgZGXj&4Se$M5n zvsP-uSBIm1QbYbLvqp{zTVgAYFWtW;(|nBE>SshiDL73#iz$+9?9SP>%Ki-(?!xf7 zf#yan+kgnUBIx9!mKoau%(|BT0J_7pLuMmFQE#z8FPi_Tv(`CXqLBzhD(K%@xud&W zY+7}EYBTqmIOWd1u0nd$^eSGdJkVv`4;n`90a5BLu4JlFChciq_F| zg@~7*a{}2XmqVDCT4OjEt{ipUD3TU{j6qFNs0RBS>k7p?WMm=$4eUlqJQYsD0-pr< zJ7SWLvTH|0x?dDz%}CUTaL&*em`$b+GgIDI4_9?6_=-=>O-56ker4fQQYGgA7C05DH6ah&6yjr6aQ@qAC-o?ZHY? zGg`ssqjf%*3g4kK+0~ey|DEs)!_3^!AmIcmF|VffvHql06wYw?lNzPbPrwA&%}G|> zH*A*#PWssdaPDNuGFAG^YeVO_u@>m)_D5R%GCY|CS_AZ~ZYy+({Tn^5`Hi8K{99^cSbr@cZYHC?GB70#ui+8&3Mx0ebfjW}E}UqMS|mS~ zZ%0c;KtUr+SIAE);3r?0ace7TXUYLj6#3dM06Q*0d-5}a8t2y?3xlIOSQY9U2o+4O zB4n^G0UTVqJuiRfF=)^X#kTpBo9nc^z+lvhGpLY~H$Rz|VhvjEuByebOpsCED5!R5 zmrTfAxHtrz`9uf}Qp2)(xI#T>ERxo`-VLQNaamJi&fWxs;V-S@ZBMQ&7v!sh8MKJn z>c`v}U1;=^cnVrAn623r`8s&OHwrn6gGW>D*IeUiyahOi3j7aJA-^&L(CaD6x@B43{b8s zGQD?Tspkcyn>}CveWK|8d*N|d z^uQ_tgg}CdUp~YWB3o0nnNksTpSgrFV;pMTt|6kuX#P4&;DIZuHyHJ^mim#7cyqvt zT;l9d0(9YAT)~rU4CFXCgbjKB<>FohaYXy(F#BM4y<^YRm1T`o=L|t7kW9yesRB;b z#X-U4#;r)UV^?0jwg%kEFP-XixcRs-(8|1**-f8#!nB;u?1{H7P1H_?o3OY+LZoi8 zV75S9vATfimt=G0XQ`j2O9F>F%+Xh!fiu>l=hFsigJ)UYkh7CaPIWJHH6Gz>xSlzV zrDjEcwtNM_L-s-h9jMUuH)7F^usEDju!t2i6$&@!)bzM*YE|@+egw*o&I_wp6sKx5 z=Y`FFW;D|*ZZ1A;jtvh_>zthhXIA;?oGf^8@&zAyn4LpiqC6UqzZu|=KhHva#Wpp6 zIT4dHcN8rOx>vt7{xiHpD)?AvtZlaT`5g@#RFwJ96?j6}3^rr!`&`mBtJrc@Dm)e=v$T%c6ijx5%DhSj=?!^6M3qzc;Ys zuh(h;>DP~q$JtMg`xs&&Y8W6y7t(heup0G0fm#Lk48@;BYcH;%kSBXzjXwadouNif zFt*GPY9bR?0Hrsx8a5zz6>B=>wc^gbD=I*o@JHdP5gf*MPzEquT3}N~^Px5fm$iN3 z$JLjM4eskCoLQr(14YsE4`^qSvGY21JSa_0BR?opkWh>fpdJi6(&fvpTUYPFddaXG zF>LEgsM>LK6AYZM;;YG-r%YJgJc)jV1yw%yG{N<`Kr${eYD3~1+Q$l*Qx;3hz>-aX za0)U&6ZORPp3si;bvpSl>PD?~-Bt|8))FG;!^~RUM=14+9F-29f_7PraudMI+j_^s zx9?v|5PQb``l8yaBPlP8W~y5d=%GV;J|6pn9K|8uyCTtQtX%K)cCVcH&iKPEbXM&i zE30A5*U;OX5);q*L6=pwhq+>k^iJp_UulYsu;S2?Y|BE_1%0vc zSGfIA3Zi9lVQvz*lm2N897;r;xSL7B15z@L zyX7!Zh1E-&@L)9|Dmw>RVqxgw$v)w-mt|Hy;0H($J zFS2&Z_Mqc0K~6DrBf>kj&TmHV5w9peX)ee)$~*AXJIW(H4VM!!zh0`_z(`8yB2g{n zZgvG6XTk)~br*R1U@}~Pe+C20k$=*Xbm5AgnidF^P4-hEVLOJfG*pWC#p;IcwooYDM%CG?eD?k_kWV1xtL1)UcJABjcQqm2!r_r&k= za%FFCNRjOdW97Cu-`bGspId1B={*d~5;zt=SIhJ*zuJ;inwD`dURYpDZ3C}osf{MpZGVU4VUV=Hk9<>(yi%aX1p>a{*Sowe9NQRj(oc(qtBl?lvi^njj}A? zee!;yTKN}n_~(z%{_`3Jt5k54$hMqOmDEU$GOZA1F{Bz$9YIYsJ9B}B$4r>b12o7E z2`N3{xMPfQHoc{6#AEh5l?QK645>jTgBsFAj(>X5u@E$(+?((C#=VkLsSLttCa3cu ze!$%`lzPIPd#Dht3r9Ydc_f??=fPU7Qlo4CT-{PhwlV?#y}<0Ote6*PbtUI$3^5ZS zFK-yT+}CG^ksx_Uoz*W7^`N}?E7d%i#^BZD!uDW{d@IUi+=JV@#@wSg3N*7?70$HtRIpvE)Pz@4;qEY(4j~ z?)YT&Qrgrka)W0mDVIB%E-2<#8cz&P%G^hoDwxG{YS5#{vqA>Y8_S7ih4p6>a-*Nr z)I94rQ1I7HU*f#r=d~_$hhz6u!6{9V*2+uL_;?-*$6>0+6zZq+OwqO5XFLjB?gu?B z{>l}wK`5e}b}r&qA{`I#WqPt!%5c;v<+SHidG0%IpuByd&Sf@Fz%KPyfu`TrKZ4}b zW9PDR{8a?-{>zXNL7tikxk9&y3!Ca!4U*c}*c$Oq$G?)c#)RmF7pd|0{6!zGWvaQm zUf7m~R$suFJF-0wZuDL%YgIU@bv@BDP@Ofd$4s?mqY6hUe$sx@kI2~rQEbde zd(cV4on~TEw|@B4>J3)nAzJiTP|34z__LD73NLI&&5`Y4eYb17FMFX{jTro=fdM-V zk4UfBJG3>{&hzx|g56kx;|ikvrG%lu>-H+q1+U|E*FYx&p-yHhQUw-GffRH45w*kXGpd)8=*MO|8X*#0)0e znyKp=+X!orT}KF&ry~UAFdE%*1GP$sYpG>!A*YV!L3=agPLM9CA-c^~oF3ghzFdy; zt;(sjDap#e^?_7iDtP#f(Wsx+nlyoGBdA)dM;J5@OEdlKX}GS!GtunrqmnoN+jm%I za0sLupG$CzL=p%Pi?MM5{fHpr!arO2J1BYF_Rk(7^n$m}qgTUcnKi}tuWeMJK+n9b zKX7JTGXUK)wRUIgDa9;PaB61bL)YsGXyqYHAXS)Dl5H1cY8)|QmnJqx)_-^IGVAql zu3HKkSvhW03yx`9D(5F?(uupr{0s071rro4HP)k1opXfijg?^WPdINZ;CJc9X;!(H zE;5>yk17<)mWAcbj%Br66Wp!7aEv7L9hBjoOsg#th>LJlPiQx=co@4mesbr6z~hpY z)KksOCQBp9b?jv|jA&`=^wDcsw((VZ}NlJ(Z} zxl1cpYwruUf=MY{AlZxioY9kFQ6_T9KP3**7b1#hDSoFWlja8c@InwC*QJ$LKl-)O zNf1Jj%96}i`PV!Q%Y?MwAHH~w(^OMe$a`UY;cEx+O3&D$qet8}Xh7du>3gp7!)l4U zZR)Sl6Go_DM9+Ts^NZ=IK<5M89$S8__uqL`Wb(%`*SuQi$Evrj-DY?DgA<~RuX{D* zuSwU?_49w%eyjM|Cnq~U4Gc2_F211S(E2F_iRbIu54&0~&d;Dv8)R}UdB||Vu0Bk- zQ48Id#-8?^IzAO@0OxK}eKG%@?c&;}Ne}MV<(zxJ z%FpiFQi^YG$9F}}zvq1r-x40+O_Eq}C}|4qL2g&55Jw)_?r?&w1HFY8S`@3DMqhPa zB~Y%+@m*WwWYk>Y^2El>-p*9+>KdC$kM4PTPU?r;xJZSnhVwGtU~Y~Je~gac@1=-F zBZZDDom_4gM^4LCa6rdXW5FkS9G$R=3e=!iYOhzdRE65i)I#)@(AZbZ?4qP=g?j3n2%zV1O$n(~kA~%2UU43Kd z2~ECpjj|`j@agjMD1c0z{qprgbz+x4IP%Vib@BY)xkA<6&l+0C*3rKSbn)!o!M{1l z;`}qW9$07lV?RfV18bh|%Z+|eQIM?E{^vSpuc!a**Aq9iZ%#=lKYk~Sy_i9eD;79s zc2b`Td8k;pD+B|tc0r`bU)q!OU7vM*;8v#z+Po+{X@ko?(Wq(LRcOkJf_3Ygu~<~L z!?zx-NaD|<5up83X9U_i1c*D}XIyVN1Uzwt2XP!q+4&j;@3ZhtHEx~hRho`(Q`JXL0oDnH^uCKxJkAoQ!||vHeo`3I zfNvoCxqUHD&zx~8F0vu+5&(PO6PFgO;s;4`YR|OTr+Sp<_;~b1-klNF`An0^Np zXkO6^+rtrB?Fh9^Bn~m!w_n)e$@~^e{lnMdj*ca{zeyVIC zKoX&kKS~nl5}qh5JjzC#vBxIt&j>mjj3R!;l8Y=(Ob(KUCO%>Z`Pi%0DQ8RDMl?ra zGsq-;BAWFQ8hRcLTO+9e&n-U0+~nwM&H^w;*Z8FmFu`3G?~}0iJH!)1tYNP4 z))D6uD5NH{IYpHj5 zvN92>arDHXV`3b3j`kea*y?hn?}Kkt z=3L6S#{;9xlJcTS`Bz{;Qp|-oRpn08^f~i1G&N1GG8$!5Cl-sFPoOxGTj$~^ z;t|oN>C)stvO}|-Q))aW>#1U-bXwy{-CKVK%3u!Z*|4>4hobYOo4%xb$>RR;s4Jki zj6P&_fj|RW(V1f>iJGTK zMhCs8Od%(Zf6#d4;Y*zqv1j+Pl>Fm4#n4nCteRGoI5b0!<*Yulb$vG~?9j1# z#=A`P`>ORjNh97h=m*z#Z-q@&*3R>anm_imPgvugEpn{z+G`tf8u0r3=DeyX6*Rn- z-p%}2aXin)>yJF7;LvL)`tl=$+u-+8|(~8jBFnsOk8HIKKwzugxtFZBRqUGN14Q&AxCeM{&WF-i-;iGw{ z*R=e?ZEu)W@MrwGldn?` zy-B8k7I-s(Z08y!#^-*&&z2M*LxO~iUJlvuD)J`r`})~kAHQr)zQg=! zXZ76HH){NuPw{gxRF%`ea>^k1^@ql=o4h6}k1HS%-nG0F4j!K>yjiZWe*QA*`_l{v zJ@t7mySwmzW&#NB0w#?3TGKywpCO6Qz4PVnxo%*U zay)RvDEDuj|EKV+Sj_WoqOU^erxD|ndc?8eds2n%n&drHk8NcJCGQJpTGUTY1BqfBX_mz?k&N@eA{h?V1Z)h|mwQ z{44RMJd0<(ZXee_aFd$3M6wYKf_34RvvnY{_fISh-E^gwUF2z!3Hkf-p~^Vs;UyA? zkEB=6xl<9en|{?tP+ZBIRF=9EhsAGsi2s!l5zi%k3jQjg)is8{@_ad-I5gzQ56Mpm z4T%z)+Wo4mA3A+)+}wJXp{%u+Y8o#ar}X&L-sI=qg?Sx5ziV$&woKxcQUrE%^iQ17 z{Yt9lvjBYh~K*>=UvxvcU0U4+Eiq(l~x6B1cw^ypU^3!r}uRI4Gz@k z;(Pt>iE81lLmSKM=!NlvP~+E|E+4LyhSa%=CSabqUxYJTXl)jqhyO?dSUq+lmp(JN}8s9!L6iHN^hZ zxMa>plI7TU7Hd-dd@V=}dmY+1-s>9nq@i!UY25sp#_ywlhBu9xei*3he$oCOt>0pm z$#u*@G%6b9&lheVd~>f?h|#F4^m+Nl^yK$=J`xt%_*3*osaxo9<@FSkW^+=0+901F zHX>_6`YB5UPO9{i_)n_YO3on10k4AZ$iC5woB3U8zKz!`;NkgK!*kuKyK4{rsQ>Dl zCCy*CTwn}~e;om>DPUFD>(~*wa2Musl9YANH?i{IAs-C&C?dbDd{Q`>X+=l`rldu_rBC@y01?}}ZW+UfogZ)E>A$<6huwUKJsgK|t^SSLQFTMx#UcCc zztm-BibL`~++CVaz=X!imHRU>i3fvmSfVjD-pz5u1A8-jek+|V(r&knh~DfFuO4xs zuRFnrmq~gmq(`Pv41K>ioG+wWE_&+3pA;QEYphsY8p znM!`49}=?uB^KZ8T9%)ylFJD3+mjhjGYS$|^=mqR+7Eg&zHBJjb-YYuF|XIrG8?01 zoMZb>k*!wN&i~7&Z=PduI?pn{u+LPKq@4OfJ7K}Onck?)biwGj62RFO`D6FX!V}W_ zZl^H@tuebgGanwyr*TT#;k>C4dP zm#->KEZv;V4QUr}A)^zwKOKq1;vB5BeIi@?qenNYKYe6PTz>ME!MJ>ZdzC51AwP^P z?bBh6iBsXpTELDS(-x0+?CEAvG&~n>XVt@#J)dxE7Vi|;kn!CW-@nf%k)r%m&LK>+ zv3D`WDZ1Cm=XRN?;O)`b14*(dn%~pp4bK3(LUxg{l>L3~>oAc-?mjjj41e}zpM%Xo zDMs!k-m+!BR}mMiVaNI%0O|R(H_}(i#Gl9%=?9S^ip-G_^ZEC=`@qCRB>;ROVKRxV=bmWC7R)B zH1`xdE%LFuhcj=rLVer%_g=poO5^={ErHy^i0n;%rAD5LW~De!gb#l~rcA&~S}o9M z>REOpvc~1aQ7)-@nfHJNkZI0+p2=EX;v)c0Ua)O>ax(j(hn%S4=k}k~50@j|x}kLs zSn{hMnb+}0(R)h!&ja@eAr{!a?@YX4hbKBU^-;Cwdd&r@j4yf=rkp%f8=gMq|B>PA zrqtGe&nYuY7?dvN{(7aP+y2q0PLqibzLV`<+=#zH%IbhOqPEFQ^F>&#tISG@=FD`G zy*i5{Swg{rMN9RA%H&fW7el~m|glpliof)r^)^LXi8V5%R`q=%7{{V z?&TN!4{B5{_2V?tCl@p%hFdK8%5ANs@3jhxeXRK%GzqVOyF6|066z8K#8@xpNi#Xz zUKjAr#pWM%B>vqqOd679dvi zkWwF(fvgp-adgOk&-w-0%hL!reDO_b3kHKg;a3SO0Y^o)p>p(>9toeFK3%LjIIi!E zM~Cw|IL z5>!~_-?k@du~kpThp}X^T^c@jG*y&jt10WJIP}Jtv#{@cbE)X1q)_s~R7R#I_K!2$ zNsFT*TP&nNX&Gc&GCZ9>oo#)5YC=Dt`ekNGH-?jk%@VHu=sxF-3JxB&GbzFoo-qW}nVA{hCTihsZn4C^+&|3)jR-9oIoBGMxMh&g56L)U9vL*l115 zr$23}|9a?WyuD=CzWc3CCMm!L{QE^!>ZpYCNTn;6#fyr|QupJ}D|wzxl6Y!QY|QAa z9i5KNxOqKO=}GgDkDB5<$tqa#x@(FE6&$a*q<{=Aa)i)5iIM00_*6{}iMy<2u~^}T47aJ+QQ zr)L=?on_Dkj?8!TM!quv&Gx~H%omsM#n%O1QN8`}v~y=`5Ae4?;5K-)%+T>Q*IswF zw20&-CJpU785x6mj&6%7Q4gDt&#(y^wadtBt+PW*{Y^Am1S9x6|A*=cZyspS#pc%yg;m!Fay}pl>T2HlHX~rcw-!uFD zaKihiIZ@53dw$@jLQ&Y+%5OzHSEHnzt9ifuF|EtBbB>qG{hoZ5f7Q#e{p`!c?<1va znQ5+krc)i`E@ce{0p&ou(maiJzN0AMk@b(c)xG9B;WqbHF78QLGaBNkb#+~~vWi0Q zRLDa8b=x_CzDDo0zyJHnPlWk_8NqICmbWUdf$?Y6 zQ?X;2#jO=@kVeKxcp6ck-7tRF9+0T2CmAjSc>wQ)mQapo5xc{T-NoF~{{E!@J)r;nvCa7L>CXZE@PPj3VEgcBg8v8o_m8i? zetiA&{nPJnTfe@2Io#j)z4!6Y-rBGIPrrB9|B+v-zvvr>|E*Q`pYm(@f0bVcN3FVl z%dh{tRrmJ$|7g|y5Bc?ZY5Yijt!}QpUt9T)T;0ll%hes>ulaZL|NrpU!c6}^`0Mfi zg1;s@{*hk~|1G~pO1}1GZgmhh8^ex5bw~JXdVFAZwDsTkYjUh}>gCu!eY*cHzy8&y z>uT%iYWTcXHEa$uSfsjucJ`i z!-~?3`p0*wTGmR={f|oBean?Xv;QJs&+mu-m;a(t9uzz%DJU%bZ~m*{M%fVoYY3&( z{YRhf&42dkauY`L02YL7ex_J0qboDvw8c=Jd z{ol-&+kcp^Bk=XFKApYmQNiqto%4UNFB8l2MrL+~rndjL{5q~@qN!`Fu49DNGWf4h zo&5i6s1ASbze06x|10~-DEv433Rx*|roHRQgj!tGbWA!?eQ~(4{6#L-W2DHesp4Pk z%eb%nh3KJwwU%t-Y99T+h0G>w%e&f-J zq*0_HKdr9~K9b~m%6x(>j+&`qSLyk_@h1gSm$N0#ij=bydS@RYc)=l-+*z~@#Nvfhz^dCE0u+mU1B`; z?>ooN&8OQ3d!Jvc1Ys`3%8LJ(RQ-&+p6NWn?KtVm)fPrpeJGv%0+)v@TQY|5UZ>#R zBWK>*{9$?Wo+Ne8bTGSe%R_IGI zzTC@PVX!Cv?LkiXdeuh@9&-raY3;{aK)RLAkQZM2!7#bx1)BRI?ty^(qz58loip8C zCR@ZRc6)R4A;r7d-Dse}aZ(FvrZ9P5Q)RZ=!jF@|nqS1aS#Fb3TW(IS1Dml;6$_PX zJ6HDcT5Ksl%C63;rqSks4AogbZY}mNj+5}K_s#)LifXq$mZ~NZ$+Urgh3c4ZJhi2e zj!SLhJ{UEdxX=UrfqSYA7S@qMB2FUpELADn-H=-&U#&b*n(yyE54%n~Ga@Q=GGf&qqTK8S{;$ghGU z$>lX#YB16-u4yhSTep8@MY}X5DBAy=1D+w@SA&~67b%6`JzN>>)4qg!;mEAP-i+6} z_JXtY{3Fd*Mz2(qf4q(A|1wR53?ELmbD$aK)-yUu$c!cSH{m(&Sw*alLUo^^6VDZ+ zE$u33pwC=$<>J{IFPNEv>@+j&W`;8Ps}>J7D;>Ta&B7(rbLzdvjgyB2c8+s+8~o+A z&}>aEJ!S}X9#yld@h6jf4;xvTQwi|4f|K9 z&P6p>Z*IQ?o-dXA_3v*wpKj;Q&g-j;Kj+6eQdGh}9DNOf%En|LEH_5bz(T3)6lT7m zZq^fY0+339$eQ-BJJDnLM=7jYLp`WSdK?Bpg_)T4au(2ua+XwfhoN5Hr}TJiDiz^l z`do0Hp78%6RJW7tI9kH{WT;;yawo+VQOZAPI-p*#lj>_(D)@S6;P}&>wBXcI;g6<+ zC+2t3#V#5Wh+5oHb&v?Sny_e6Z@P=zX)+LU-}o|9C%>QyZ}HrHo5RY?`{JwKaeZb= z!aHn+kIm#JhQ^gmSBiS-j6#CSq>Qm|0DEtBSv{L_t8*+Wi9kB$4>%KLa|1X|FtTmq z9uf`SK}Du2NHi)9X<|ZLbrFsRHOAeWwxc?gjh^^ZeOb(%i6T+Drs_#x zkr$hm800n9gGp|Ih*25T=MV@c@gw|A|7YC?pJj{=PER%nz<3|Q;>F=a1?Q+<)AErs z4#paH6L|bEi5V%Kfo`}sZAtFpRznBPWW5aGQJzgdm#|iHTV%*z z*u}rD+NxU11HI#P)Kn#~ZZ1DLjOf!&97bt<^%@~wmzH}!{N}tym_4!5++w%Y-&s0T za7fhia+Av`(1Yo-cI*f95bDI-n4B(4JO8kC9rspFzxsHL&Wb(ZW%VRgBeYD-j zF9^X?-dEjdhKI;qg=aR#;j)fZ|57&KpP>z&OT5P1=7pzsn>e1!#kBN`e`#!D4Ltma zYdJ>>6A68|EaB-hBuxtC>AkoyZ6sAsx;hC_e_t5H!~4Faz;Fni%=hPbr`Fb-p6IpQ zaS5YFpv_Lx)IsrYC<#-b3_Dto=E?|@lKyBlr2EuexH9q;rp}8L&K29*s}SPo6K87A zCxOZzGrn}WrM48J{;H9ksMQy3lep!-k`FszX(KKgvLkXAk6TFSyqZMmqmz5+XYYYgr1R+wcZdGPewascVRUL%9 zpohCSpAgq&go$;dTRnf`;@@@l`f4%|r}N@#`193NOC)aqwlTrz5)j%N9)9&WtflN5 zdnXTs&sCw}f$lDHwE4=NW@)zcC4;B@LQdCimY=;dXS2bSYxAn<%=h2)^#Cv3-?!y+ zEbbIrec5p{luE9D{P@Y(m!Mm}7nV>@S_iGRLkoYu-S~H?uKo8SJ^kOIy5H{(j*Ihm zPri!&`1>e;b`+{RWpZ+Zumn5X+RHaiPtZMF2JW`@$)4Fsc0OF;pJ*M>8sAC3by5Cm zIM_rl_+;jtLscUN028+Vo2U;!P_((81NX^J;UYaHqnJ31Xh^af@SJ~`1XEANr@B#A z(81)kCUGD^*Z9Mx_1(ysOTziFnY7gN)>q|J z;hjHnl`*F3q@aBhSnrzN9N{&*F|G&>;j9FV-w5oIvSri0+#-OKj^=0v?D2y8F@vg3 zShCcHf$%Sk36s-G`;=1zrg$(5L)-y85MWO1a*tST(03yDJ5SPkxSn>YfJ-q&WQqP< zVv-5f|GbyuGlsIR)s;EkbxF=&l|?Of9B{*|aQF`nqwMt&M1C;ml!?RE;>s<8+}}Lk zl0gOnvXXEoYV=1Z|0#=9{m-sv*id)*jX!g7?w2Zh@sFySers_dYZnnk!@zv5h8%NP zq1)WhIl%UKkIpz9c~qMDO4r?V0QETl##n(4I%;PcI=6({1))AlLzhAD)o$pPmQ#of z5Z>)(R}vQT8mI(d=LmOL@d&Jg%EA*^X$aIfR{GJBwMzqZlAv0i%}JXD7C&-Ml9Ak| zgsosAmm>iZLilo&>%ppCd<+c_hX1vOGULI!bR?0^kDl{H?IKl6^jn$k>^=boFo-yS zx0ih9Fc)YCIgezWO)vKsP;;4%KVGXB z6iBu(Jj>4|xF#7gN8wnDA=zrj(_$nIm*87V9L#F57dV9h-=xKTlxi>AcL=|_EW+^# zPHa9%}D_O>f;jZvK+F{2GxNB)-Y*{`^b14>a&eU^m6C|380X!w`OE8;}P%kWNU_0 z<63~mjdT|3d6ZiU49~=dC-BCw7~*1!jR~8%03TyR+Khe+OhEP#kduxHf4%G~zw-ry z*!n2IRa5E8hq5&rn6KUG{ij`TIjZ>|a9IsG|HQE{PZ71`$tvoAKL{R$0Ssd}`oxp6 z=gyDah~mIQ$e46k!_D8z83Rk9;f={E2C&MbhhYZv{u*MZ0rvfXa|Oe38-OO8WizWW zKVE`{)7kgw?0rz?1XtJ`1(mCFo0tC{a}U#J3@VxiTaQ8Y;lX>D1W#B-&;`IO0vH5t zUiXu*(gB`h3#A&9*-Tw+H!;D>P*{Uo9@_g@4+eules$$onS}9#6Ihnx?+eHVflxG8 zR4P4(hJ!8#bF585We?1Y0i-p98TtAcUobY2l_{Ai}OT-gAdN_*b zlahzeE5L-pmWF7pH)5C7i(q(xG(a_;>8_C5iR07Q_MEEF;PU%UpeZtvodpit&{;Bx z$x@etP?3^qs8R)!Z+NOzPxUJ>bk7F?^%tU@kWVOutGWvhsR>O`@_xlbsThv_-%cUk(99#iRMf@QT+t9UUIfh|?)ew|%bg4Kq2gN`i$8dZzBfj>g z$(jM#c$n}2Qd`%Q-%Gr&oVz3(Q6G8oSOJ3M-vA-prvYM~XsE4?1=lef{*VBz6~O8M z{uRe0`?-oc9KJ)TIfy-VJtZ@Ch1HOWorVczrk1&TN_}|4rHj3zZ*gkPk;gO!l9fz? zi@QD?KzFdiJ=zr5nV5Ge@C!PCRV$2v182t*Y1ovz-?(&xgIShaX)*0w1ZGbfTQktn z^BHO#%w$Lu9$&t#arBd=sS-@6i(#q(83LYYmwg&7T3eB}l(~{~bR1|6VP)M@#2{e=Za-w7aZ=j*bj|e08a#y#~PJ;IrLbrbT^bQGGKswt*K0 zVk`bgn`UfA+mEa}9B=uiEdT(-xf@*npe?R*=ug=`r&N6A3G~&a7hooqkp%5`p3kveKJI$C!)3PX>*v>X$h5p-m+k=k%N)%^IH_{iU;%7hNI1#NVFv?9zwnWBzUvl19k2w-Z1E8}rz>@P3OyLmKi> zzc#u0TdlhAMIIJ9`yAzN&}7vmHYTby>IY*IMIMrzu;wqLKRH7f6>5P0N$o@1AWbHx zz|r_Avb&Xd@;(CB5`p+p$m`s}%hHXSrz05jY3wD?Q8}>K8k&L?XWl_9Q{W8ROKd0i zN-f%eJhiTbo&`-Br{SfYxK$k+K$>MVSA-9o*RGD2g%bY%uy)@;P5tkp?}0!PLINug zdXdni6F@0aB=oAGN>zFj5Rj^vyw8&RDbpZ!8>iggjW&mRG{mR^*i;SzChpfY$dS|u@cU@ljOW(!UEIw%bJDWJwV(n zUB*y^B(5HDt+gN|BB0;KEq#+=VK}x{iw^~ z;)__oRoL+5`dj11V(Cx7d&KO?LChT-^nEn*nS<3snRhplG}XTsxXlrKh3`;vm4X5r z#ywGXZ?x1g_ssSe*-YIY_qz1BtU;bgev6SiQb8Kou0ms2zF|NpLxx{8hU`~)rEu?f zv4}o1Jq2;Vd_t>~2sf!?LodGYXTqquU2yG_!pQc$B&^x10rqSwjO)z8JJi{Vv)EOX z#Lx=7VFJ7kN$o_=15*M5dW9O;_rvcbHQzHFVu)X1vH>>q>uJ?#GtaA@JKw$LM(K*& z6Xb5olauL3EbQJHl}QtdjOJYu{XK7v6Me+JSu zwlDWr-`UrCQpdhB#5+pILw0@(@5$z!y>xpGdMG3zL1toFhF+0CGT#WMX>0aI(`208Jkm< zoi!Br6>?~Dlztt7cm*HBG3j4p;<|%4dHVsyqW3Q65T#2`|8a}*hqY8s+D`yko{YT6 za$KN!JRNxKT6}CG2e8R~ymUOpm$6~zG7SWMyWjMUd-~fGbzpS$U{&zs){WzN;1JXU zHlyf1eLcZlzLnXLa^t7|WrR@4Pt|HvDXC;p(;hg*}93t^22!Se4c#YkzT${b6U&rH|2TzIpmCQo*GTEVy1#io|Tc0*Tw)+)}qyG)!miB zoI63_4|*#$w*1;qSFTL&KJ0dtY>p5*cTur&i_$5RzW2W2`I^jM<3B8IY zB#NJrf~Nik@4>r?qe2)gLzxhri2Z2OpjcbpYYFlq;0n@2=&Si`7i!3+jbAGujC z>o$}<6f$Yh2&^lArt^tu5H)*9zmPu(a-QGY>oO@?UoQNfMJj9`{MKf5A3P^}^n_RpDWya@$ zTC6zFE|v2v))?tOgCS$@^C;0ppt|B`q6x!7X8co}@lhIksLGMUuEogW$zESNH4v56ylL3n$P^+pq~MN>86p%bqsg%Dx6uSl%IL zD~)J@a_gi&xKh+e2yO;oId9l+zt$1|@t*4d74Ms71%Xe(JDUY$sBDcrp)tiw?~im{lUyn3NClZA4Gb-&5~dG#f$#o>{} zg&qDaSn2jwtoyw)YVJB`b^-OT6jc8X9dy-6TIMAPNy9(G<>xGHDQ4lk)E`_2J&~aq zBq84EdTCLH0&8L!f*53By=}34mt{PD3EqWeYgZj=DWTp7LT2gW`g?>BRc*zU=%}|=vk=bs56s9ysIveRbhh)>l@ry`{le1_JqB5G`cgd1_#re zkk_mO1t2}ipPX$6CP)t-!1KACc#icjVVH!ahyl+k#ZF~cv6~F*ZfC~W>0a|~(#(BY z^pyNYW@&Sk&-hs+sG6?H5sSSKz0T{j`mBG1&xbuZqug$i@Dlg8Qt-O8M}q)XMOQ3M zrP`JtYN0yjT1(2RIOTIX9vm6vW6Y`tu8L1X@9)1=Fd5gspBA(lT-{d`?5$7jSx{d|^ir!-^|-uiUdMM6;#9tuDT; zel0|^t^8qjf!&sxkHo9^8nfahWHimp2%I{tNTyS%%AhBvvky#VP9tX|tztSYSToRK zLJIz?BJ)1OU)cozPFKD=8|C^Xj zE-UoEo6?^YFum~HGx8xAGYogbtUdpkE9qqMXos3g6VorRIL(IO)i+rINRpmf|{Z)cF3U584YmMS) za1k3#euxRz73ddR+X$aMt;o@({b6yr8jF~|P!4fyJhX(9Yzl}&1Hws^ez}%hCF*$s z0{}mYEukUjXrV{FR3$GZHMmGbD*K`N(ApeP9=|&XqxphguQVp5Z}a8qLOZUnh2?lM zOqcdwc*IcH9t?Ypo1PFkYAo{i^MsP^rg#}MO8A0pJ%1-Y5xK>dsvfn&bUAm_=23{1 z=Kb`kzdv=;Cyxn1QQOe3KhPJMzv=%Khjwis0NJw`=x(@3z*6AbbLeB3WgK1#-2T#xNgiUt) z&{T~F%00U*qK><{^42I;X%qUU!1a06+b@I4&l&Es1uwMgX{UdCPbtc{5qsHZ;2thK zDTTkagX7J*98aTPM(!)=2S|>C{uMQWI>E^RJ`OuieR_Ollw1zfPe!{;3; zf7y1m7sit9Oh% zZ8U$Ng!q>IX8YL)?dL89G`E*j*P)HZZ}-ye&O71JArh*be$kshU%$W0<)Y{Y_+3u( zaY4GpA6mb!ClZ+7qX%AauHIf4yq%^JZy)c{#||_9DYfMCgTg>!4imk&=o z&f7qDBre`+S_X=Ul;BUY|!ND@5z20eN!hMj>CGOSyxOr9NSy?qF~`ZS{GJgM6IB+pR_Ew%Qh8z zCHS~r-^QOYvi{*Nxc8*akC{={M;IJ>zBBIaz1=gbn{MV4E zQ%*c@dr>!|?R#J1k4>G->1U-)sF6{P25qQm6pvm{EjYC5|^T{C1Eb*o!kd6?*RvFG}eTM4p`Py^?<2Z9xgiuxKLdgg+G zKqHWm4%dbL?)${SgyF$qL9pxEnbBF0UX-#+904^hlleFUB%Q_SjrT5rUW?L8NXL3c zGw>7`ESYG91rFSO)5?sCAOG5e5fUMm!4*S| z@)jA<8#l@Kgx}P)jn*wP9j!W+p_PPcMUPgDa2=ke(fI~VmP{8;ajel(uY5@$pWgtg9%Jr!pt5GSHK3I>P~KV zK#5rB6H|V^B*UHlOZY$uJalZ1mbYho^1uq(<~TNjy8JY-=M)X$+#|NCT^{_z$c#66J4S!SbN7Ig6ZahGLiqA`atQYP8iSHgj1-;sg%8Rzb zJ#vw*4SBB4Gv&pH7B?YMQ)uA;IT4c^+pUor5#tbnv;EPIkEpqV8Hn|6P2%c_&A~PO zpbsWN79LMW35($C^Om`V5w${QcxE3*=n0;I`UxX(=GP3TCH!Y7AqKXF)4Vc7?g=O) zZ6mjn4)@9un$B3w^eUIyw!XsAz~-tu8M}xJlEK7K^t|$$+emI z?hIGS>DX5D^Zms042+ak^960_OIIRCA#srF(clkr{BO&!oS0?w7;eL06lZ}C9D1M6 zcV9f`(me6yCv9CBs2Bly$I)U`JSQ%OWv z^*xN;AFCvsb<$4n)-2Rn9O1)2QT(?BS>?b+vHAk1M zJa`)%*-p7K_cl?G-asbt-P^Yt14JldIYsd5gJJXgwpTa*WF&cL`Yj1OycPdGVj497 zUMCRf9a(RY67ugr{|cfnRV8KZvk)V$?ueqI2pW1(ki-3}PY4W@9R}?jhhB#?@1-kv z=Na22a{O(Pmw9huZLe|oIwHz>uWG1WR1ts-0wjC-pg4k_VV8O!{(?A>QI@D1XyfZh zyby?&Av(i6iTOuy`K;^nTh1p`9UWEd>(n=K?&^Raj&pFGJhsjc&g|G)Kck6!PQQT; zOH~os5Y|j((cKWe1f22QI2*qqUdNBl+K`k@5w|K)uM(G<#PZq*>eP$Mieb+(pV281 zp$KKU$b%Dqq7!^PpgP?`=L0TEe$MH3Vm0X1E3$^_1PZHqUX%v&-KM_Dg^FBUeQEfE z#0$>m5nd!%L%a6%bi}abx?I|}c$L6SLd0^c0v?v>eqy;5&utLDwDs`gyUR))H}DK& z2+kG{TifU@S9K4oEHz_+JhQuCLg6*ylE9f#j}JN}tNvV$DnvD$^-0I3!HnBO0zvik z{iiW5n-A?emzL0qFgZdABt^Y&X`{ zK#bX^n2pEUc?|~h$_Z=zb?lQ9uq$alQF6ES?Z>j&4*jx0W&hdNM-6eYJ6?|-eT=P2 zs}6gf9O+B*(XB>c$CuCe>7?(2*B_5)uQyC8m!t^RPkJ{$I!Bbf{@ljxvc0L10)R@p zjx{N0waHeuXZ9ZcG`+H0Z)f?^_iB&?v547E;aAu4iNfhUA(gp6Z4IxY0zE!IgwOGt;=nxM@oS2t%FUUFM<8_{?}b4*sB;ZveVReM zf~appJU6&M$;#Cdp9ivm)_4#@d_Jvr$*xEGSG`DbkrX&dCd4ZuC&L01`UGw;pZR=; z*uEO@JGSZYuluYvCh(*0*8mw7ZJ(2?t}*g67RI@+;=lCvigitrrR?^9#aEx^RkGXN zxX2Men=hApeB4AN0IXmD?lHOu3a0B19yE%Fz zKG$EH=w}#P1ecSdx%T);*bd!|TF|}Rn9S+Pz`|RehYt1!@j-;holfoO1Pi4c{>8Jf zE4eFrpPO+xD@sSW(W=$9_g4guMx8&ORTkTx`C>K0CtWPM9UK&o)^_-ML?Lkr+UOJmm#QtXbJTaWZFqj^TzC0M8-;g{zpY)vjJn#w_^ZL)tcggOgLfl21pKSy^*7b z$#3;%m-&KK>iu$v0FfvYOBLxA$&Cvb&@x1qv2 ze#gcl#ft4}PGokPvI@OnG(29eI_cd@uBMYNB*f=;{M~Kh{l%@sK&jUaH$<>_7ve!8 zRY9r5-!w9C<%%yp19kyU$!Bg^VNS~oPOoi4xs;h6Z6_^Tb8}x4V7VXi=mltD+TczB z1TsWy+zd~#4P`)rQ@x;Wf?yYMLI#pusQZ&oI5B}DVp|eg`1M_Cw{5`Udm{s42>LcE zCa%E?>MjVj3>kANOB1A99mf}3zvN3QGcT_H*jp>^TKt^~fGE+Ho!`3(^i=jX#P4jV zF}3Jux*`*0d6E^*dCx>m1rlh%J?3O&yZ^=Ba!Q}*71JT9duLCimzx=ShH)&)y)UAqm}MC+vqtrlrDFTTR(R!mmye*rIjSCeb&Dl=J(I*yTM;57q2<< zZO?F1Pcc`yLup$}Ok<(C_E#`F$}V?d3K8gd?j(_TzdUwSVSK;~1))UI&kTIhBO&ZG zcTpdo8`GdiRW@-oe+a7{IlJP3%em9x)Uf&;_Dp73i>khdMv}X!52AVm^- zSFMt?==BKklvK7bZ_ykVA+Se^fM$X|_iW;eN7||}nflqMnImF_p)ipW3y%WxN0P6& zk5S+-m^~?}zN8A39W;6LzT`n&qL)!GSHyEtalZL(RT*$02Sr1JdMut+kaz2& zws+M>C!Sg!;?ymuUMx71qg1lW^_ZVsl7_Zfh?I(1z2H|y>b1}}zH{;zR|B3%s>$mw zl6+Iw5muj!MJ-FpJP!?1GUxFwaM9;B1TRz9bub&Do|3hD#}!&=^503Wl-|CPK`@yR-@r{iDlfz{XY7S6K%Mc2nL|4u!2wdjUe)WMTIK*4X-M{j zCqnbZNoR{19t4Cy@%`RN8TP{mVI6J;K>U!#QNvx9QRtmZOGDVU)I`Lz4i;`StasHs zg_A5KEX+8-k24{{%;5@#;v;6-4Y!%6-R`JJjEaBOCBfw1i(4kP>WlYtA5o$WJ?}Q8#=~hA2Tw;=NsU~g zZv=fM&*ZLV*h+r}Ak>ix!KszeO`$8SgMvC-)bTd5^Yp}x8B5nj!(mnaO49ZC@~rv; zFAdOzswo09nqWA5_K_XQ7uHOMsGpTik|4QhGcXfdtAzNgr!Bc-rN|`--hdFZ?VL;m zuZF}a6rB<|?#6ejKCJiw&9X^uex%eXap`9DY~fLJrREnbxK|RTD{nL)bjN9R<0Ho59-}Gh+|58^z1O2C9*rV^se46kE<$5d&w19 z4@h5r^oTd6!&y9DWrrt1*!X z>Ys@p14JXQPaO_Xec~;JW-h$fQ2~4e;65?Vjj*D=!Sh|b9XGlf#>=)ZKxmlRe;cH6 z9pyBvB(c;Q5NZ1T?b2foj=i1Qh{TzzRfZ?xAI}@BF0QD49u;AJ@wx_A$7E|8Vk7>H zX75gF98=L-Y}2X7lelz6rSF%1^l}&MDu&-pEzts^>zp@t^K@YFRi?j|z5uQG{ zS%Bo@br+zp58YcgzZx_5K;WpVUMHY|ng3Jv5Eu=ShS7R>*;ZbxuXQ-rn@_SG7e?K# zmrf^qa(4rBa2U!$m6N1^8UAzQf&yQ$hTkpdZoEc+5BVCtUhpP1`ZfAng`weL)Fxri zPVkPV;RBi8d`Fo5(_5OuWTw&&DI#stp?8|GLT2uY4q4OiM1AS_M1GSm?6XnKjMul( z%rc@$WsWnf0~T|D|U&|6%pj z|5Y_DE>6E+c)2>?yE;d`dj3n&>L1l~FjfC%=H-6}n+_-b12zri?R5}#n{VyZ`EFNT zo1gv{Yz`T7TW`ut;?T-<%H z{#(+D%A0CUlnWL9J!xg@@W1h){}0||riL|9y=bJOX{4-acwXJ$ zU%W}?oR+lWMQYgU{}XT0`9JceX%3!$Rjq&kI7tg z+mrvZYV~itDP(Qn5w6VmAKql0+g9)NHm@O9w(g&*mB}+dJ2i&FT=rihf<;fSZ;lq4 zJg;*ic0d~yf9N|8lUf8eE-2TVYujyU#Ve?@+ic*bfTH$qn=V_q6=KY?1(=0RoIhd1 zoY(iu+u171CwE^0pPx0>{cPYt-xbSa;N3Wh-dv({Jh!2FM_{ko$YF}GtNICaO znxYjFX@*+Hc4BORNYMLOz=wbR%G6ytry(nUx`~BV0+**ZDvplf3W)$Qw*^!)v0G$o zQ18NYBI9di+%5VZA!H(#==1c;K`8gKc=eN=O;b@>-C`XK_%V=Rj7}us={&O2F2h5E zEmEzqKQ}XNJsDBK9;~U7$e6Y?k8YkD9XE%wi9}KkDMt2Z<@>^j4?l6| zE*rV85)mURQ#W}A*UPWcqq$sszyk@$07gbhQY`)c48=hYfZo*dCKsiAN4qlK)xG*`MVqAl9Ssz#_LJa`K2+XxzoL*o(hkUh|G6-w zf?Q7}rRq(z;X)wOMnlGvz*Rc+mf$Y;2)y`?e%ye`I`#zK18EUdd4qWyk~WH z0yCNYjz+2@Ljw&`gmibcraDyJu*`JxjiY^861ZLnKM$- zE_`1vcWG-+=ZHD9Sx1g3V^V7`*7_T^^McIDQe|iL)S@Lp&`UhWBJ^++gGHcCTnvm) z-bUPD2sEL--r6U<&J=WHx&bMZ{h`C1BRk(iCVRD{(_>aqMR&8NU%>5zh(Zgn=v-$nTs^)j<5di zq&bYyX$$c#2+s;B&Ab|guwTqY@SXPoG;C_KF~7LQONiz6QQGJ(=`h z2({#p6wl~V8T-^ntU7d*Bq6#o)LUAvXXQRxQs(!u^Sp-A46*ld;xKJ5g%PC&WUP(T z9>3@Yil3peff!Gh#1J_u^WrsWR9Yy938ANx`=cp_l#n9WVl8gtDRK+@m<)QcEWva% z%T~I# zFKM-4MEkN+p%qi?n`OzZXCCU%F8C31ZAM)oFIpDc->mhra8W|-SAe$QC@IpO1I-rd zfyLY+Egol@f@llE{qunXR(w|D1?V35CwKFlwe_4oR2U)T^j8CnDj6P|vu|o9k8rk- zBM=z2+oaBDy6QfWanC1D-o;{ObHDjG-e9mW8$>Lj!Cm_-Vb=krSXYq&`ODIpsbZf6 z+=F8pQO?&(5eM*@gYNoP$spww9&ufw~N>Dv9bGwf>wS1_-#ZO?bcWp+nV@ z{magpwX3)bi}*fjexy9Hd+GM+YzcEqm4Vqui~Q5Ms!J`^S0+B%w4ct`r?gP3R-f!w z@(iw2`Pbc;_|(?F?$*ittUkeP&sC9!MM~*eWA?t1fYTdGRXz1%Z)UO*CLW(ck^jN z+Pl76m-bM3)0_26AbJrZ5*Ga&&qWN3>tLVMa?WQ0BpM=gF$25Nco z_zcHLK}F0)3520q3o879EC?3Ss$=ClcG+O!zR;FbmsYm2rJ-UzRvHu;a$zryGt3aL zIyp_7;pil2x2<9pcmT2Nc0|)~f`v{2d|u9-4Iw$G2+s}aXO;c?Si2Sd&=_Xwtw9s= z!(j2k(RUpE-|9#ENFnhqAo|G$lI;BxM}tisW)a!>M(jsAZhQ&95>A!6Bv2?kqhPKnzFE zd!{YynIIaLXIhYWLFV1zP& zB#34~5T9vaXLH2sLV+Ah8;toaP!ANe4xg&Wty4-kiob*YuEnFjo>`(M$vI%xZ4I`x zc#5O%-RucqI*f~q;AH)ZGqSBN&NP!Vhbiy_{21JIBM2PaK2wr`JN!0_~=MXHdfR(s)6RkIRTIu}( zeCi5K+VEAr`6N1X?uXd8ya-@rQCI&69N)@5-Ab)g2$wDi^DW(HXGQLn6Ukcosz?0y zqlwbA5SWC5pRn+2S{NmeDN>nvpF{^;zyHXbb@zaau`2$+TX!v7p!Wa**%l@Nk$t3x zT)i>q9Ux*sDFA|gfqN((6msQ*2b`K8+Q6{vufff6G@OY*@)T39O7g{HH@bCrp;o$0 zObqxij;s|~oCdF068MvYy!7bop||cM%Q(FqO= zDH1F&JIm5?b; zO(dcxgR>$!60g82Cn+aTts`XNViBHGNNAKd&4ARC zAmPzWznrae2LQr(H%2{g=ybV?6>Ae(xG5-KXFb0vj&^;dxC&j;b9~j&mz79Vb;+}b z9!5SZVOgLAN0UjJ5SOS)ZSkqxTdk-{LnMv3AUM98v1k-xI7I`dhfLO=-|a57KnGj< zUKp=}KaAw0yC8dQS_*wLWLvZlxh{SgEf$~x6c2$ZB@n?u%mX)Qx4wV_2X#T-m0%tu z7eGHmdwWL=s7wUt1;NcY#6o@To3`3{Ekr>y9d#||l=EX5^Wcie3uybG+uocF#=!8E zC+B($yr<71@&F{PrgyZAdWPT01Ix4rzRbH!d<0ZTeq>B78HZ_C21L65(KpM>wWv?E z&Gig4qy}y#Y-ehPToArDJ>eD)=a(el+IrdQ3~QPwnytI&M|D;5Eug^PhDtXJ^K8|KmyjfF@vIM}TcNZT5VN)R$7n&aAf7JdOPcMH%r*1xa` zZ!?!vZ3l#tsJs5^>p5W+K!dJBGZc$(EonA+a?v5Z1maRBWu5>EO6vRy5ejb+xm`gz z;+ve}6uY51T6H%PWh5H&t5mvf- zOlPHaWfUj?XwsNyel`X3Og~^DgCH>=j%>IvjD608V}&;mB;Tk?neIGGThK4md1eF| z5lGL9rXMnC1{yjhK6SwGb_Ic~-y@)7aS);G)|=Qaci|3dBH{H4prnP^cW6NNFdj<1 zJa)4}kePBlyAbFuFtW%T+v6P5!-5W;graylkbl*bXrzJHCLN4e8gO#Qh!oPSzWZpF z1C^FYf5@J*!n(h#Ubp;19`Wp#bQpTjntQ`bk`h@69J z3omL^>^+&TXI=+E_F7SgFn!aDm1-#Tg`)AYu)D?_v$h=df7H#@AJ0JV8g8d_W%I9Z^uZ5sG4FvOaK*zbly zey~t{S!v$XgT?_lpr4Q29oM04IjT|0eZ#Y7xbl#uI2&=34MZs+7FQyMT9NAGFPVE7 zOFNMBg0vMinhpjiPAz<8fkp&lqf1ZNm6P!HQVwAxD7A;VB9JKubWUrNdEbcb1$2!5 z5Jb^}zK0^7*C1)$fFnxk5z{mdayw? zrALe2nJL0B+F9f<4`;Knn2j_u(oIwGEV+bbr;3&54-hpqErvxfjdx4B2PGwI{3O1z zX=rK2r?gsBOY;lsBWIC3F!&Vw0|^=;$n-tBvelIBDa|m%9DzC<6ExFShHEZ5ptkh~ zXivDstbyQirlK?^Mt}FIPnk?HB*^rHaO(Zr2P~Y2k?ke@e6-yf`M?!YAgHJHGjA5P z4m8`1K*rExJM*1s2i(YWG!B4iAxFG1&?GM5D%2y@v-rNM_0+k&_&Xy-FkS}TF?866 zi1CZ)UV{1o^WE^a3HX>60vv_-TmW3fz23RWEO7r^i8q_5!OU6r$Y3Yn_@_fw+e{pE zzCwOn0X_dB2O8~^(oUJmmYXh5nrLEkS$S>-tk$oLV-QVKt4(Vw^Oyz*@`Zm-&Q20&iNZ#8&iMKJ#1T?O5E^P_i@qL^pFd9H#b>l{!81@fRSyS__^= zeB4JgV>UgR-_cF?s(#ieoca*(_rnd@7P*+$TRM0zb$0Y`U;!?v?l(NJGP&Rk%wj%} zfp=a09~3E<5X#*&*H^J-1)2|idU2`S%njScblnWXyO8NwXER{5WK~H3wsH&c&KN<| zWTFZe_dpQ6;0tMyna%Xkp}kEhmtFf@q;T~lQv*YxCh($jB{iYD;`3_r8my*-F+C9M zHbplsH7DNxW^=aZe8YmhnwnB{7fTQAz8@f0w=(P8EF%lN`v}XaXUxGcW;%cNq5)_5 zbEr6P7sJ^XnKhmM0@vOy?bNQO$pG7C!2A@g3C6B>!(o{>dM*h1Bmd&z-&O}lAdb?t zvP$#WIRMa|>VOA=JOUX(F^pt@(T$|p00`dw%NBlDvywPR(>zOdrfci?)cJR}-GB3k zCeRGbO{#%Y0a!i&s}Tg4E^6x2$%X8)>eXs`?YUi6=s&wWJJ@(yU z#{uI-;O-ZVdySh~@}EA%-PS15JX^=cRqq;K0NUYTl0O5>KJzy8<)MehiI&{SX1cJW z8QWBf=1BL6IMN?3^6T^U!*dT0WiBy6qrWq)e;*Qn>9A<39YazbE-)Gbkvs|(xvTxFrwSNVfA!{#$3iq z{5k`Ixn|IdhK5?TqT}K+-{>d0i{+93qiXdZys79oLcEkQL&m8K&u#f=%w5GZpg(T= z!=)mPJAX4?M_ZncTgc(p;A!yg!Oi)p<6#Z%xx^>h4`}nOsk}++48m%`np(9|M`TcW z)BbX<_EqG!_>9*I6?%^kvA{RX5yQ;+b0M@qV>m5?}cN93}okC9Php&_dfoZkdVi!PvHf#%FRb1$U`MV^H_AL23ufvQEd9+|Ua!q0_hvNOon$OV zOZ#2&Q}XO!6IACd>ZUY=?MevsANbi#UjI`d=}AsZhsju}HHL9Oj{9DLgqC2!IPpU9 z7Aek9G(1>G)+K;mzLr-g6`Cx1=KgxRL-2aqSPLEPry8m3adeIRs~S__#fM+@=w3`C zEPZRris?bPxUrXv;SOKA+3FAakXp;Fk7Z`c6vjT^^q4BRmCPa!oYe#9Of$YEW2d^Sxk>A#wg&`ikisi=Y=NF3+F6rwp>??GksiDl>3**Yd9SlAh(M<{vVtEeLPf zXS*%exO;Sjj}_I}w&u5oem0>^y?(jHN2h)tx9Zu()&t=zs88Ep*gv@FWZbROPo2hl zoc8^ZKj!5bPNTEq(}-mSO{ zt&khaBSu`mM21Tj&8D<_r&2&?hRZ0pVJY{`9Xx}cN^dO}NQ>vqgWjsp#+x-aL;|Dx zv|J6fVLu<^&YgS3kP(A&CyE&_B2!na9u>tjC-7}{ujd?dCQZ`rIlhExKUgy;ekO6l zg}GNKDJ|krp#QY$9TJlyZi$bqH+A1@-0ba?Z6Skz9^mGeQU`AAJ--m7kOWHS4~@f? zx6-Ce^bGsZKicxA-Lm(A$TRD-u!6=n+rSTrXJjgX5W4npbZp(NH%)f%;8bG=Vnz?Z3iMavTFT9 zKRK-LUDm;mz_kL|ihQvQWMXbf`1BY1Z*AGS$DyxI&xzz4s1DNc%uu%tttY;B6;X_> ze?@OTc7+MVfR)$+I`}J!;4W4A0}4;M??!+!d*g>-zfx?3Q*pt2NMeDOep+Z^fh*u~)k49^asdqREZpxt}0QYx% zJe6A-2yTAtpEyejhR@mz+dB|yjX_!uD!9sd=5T%iW~H5F@Umy@7nU4AVEDRHC1a-( zj5W_8Ek%HVb*O?gb&hsvcQu`DN(T0`O)9NphOHf?&?h#>Sg-crxzY{Vr{^^{S4l+K zMn7v-UpZ^o-=jru@(#ltpRaF!*z0uA>6bL3QoC`+UA5X+C;imEnM5?nJM{FYBGdR=DYqH~?~r=0YXx!0SB7yTEu$Sh^1 zmEr4I)RBGXf->(hb*T{pi3jX*U{|7n<)cTTU}1}Xl@E&66Vq;^;z~ljwaH=2^JzZ9 zimQen70rFvsCQ?j;!)fcWw99p@J%PF+H(0oQZ%{b=F?0wF8%o4)cajlxkep+zL%%c z4UF_nR~W=UgN`ujseK zzyCU0MiZe+*%{4uxwbp^_t{#OV!^9&mHE|dSF7jQbIG=XQ3?eXHi`Kf(+Tf>ojdKC zAqaa|-LDjVEh@Ha?&lGpnLD~9T3phLR1YX_8E~a!qnOd*j>mVypc}_)6i)&QXR3DSNozkw@!w0pd~W-)*SR6yA+`McV7hfKr#} z4=F}=Ay-P*Y=TlS=%@H6x6p_SZ=HmmQHY%?y^QCH8DIg}9G&h>Y;N9YY= zn1^W2#C0ZBML4AQEp*n+p`N9=*$zb?7+-$q9{9MVx4WaqZJDkcG7uT5VS8?{$dE>tkJxF!t)f2Y)xlVm z2pwtT7TT*j(_Jq#s_%U+^;M!;rVEO@T+Zl_0Y}5&6p;`v$vBeFXb@;1eA_^HQ$Hgx zi&!F)dB|i23>_xLU_mea9fu-o5O#dfO^e(dAMNi7Jdx$Z!JF~P(echdHB)fylo+jt zL}!DvRsz2*cNzZ(|c)GcklY z8~hK-?mL?8|Ka~XA|w$Jd)J;-V%2JiS-Y{dMp0Ca7Nu6H7?GH<_g+EOZgn7LQ6u)K zDr!|#t+qzne7!%P>-t{bas7Vhe9y^$$)7oSot)?M_PG0R$66l^p(1I5DzMgd$~d?| z8mg^m8mmSLR7JI+P*6c8oORf68xo*Eh!rYNz}gNagcuxfUN;33-zg8Tr(??su!&0- zpM0COqHqffx{_9kb5e7(qs4E(MhzPEI3cMozfX(FVbWBKiI#7xz;?Xtz}dFoP>QCS z(Wo5#WbEK`oN8o6cQX%Y1j;cd!~l*rZf3#7uY-CmM^M4W*@WRVl43dt(H0CqXXK$h zbe2zzx8S2m{3b~G(QJK_i4U#h?Ta14Mq|maLHq&hsfB(=0d8p|8>jp#b+Erb17tM? ze9H44n+SSZkmSvA{fr_i{|hDwbn`Qm0YS}61|WyG-zCoL)wBWzslgHDAje(|mCIln z^8M^Cb_$Avd$tXcZmwP9M4Tw^-a;lmOZ@T00CnMZd9WBxY_;nc7C)>)!p47Qvj+i3 zsc{v*$CFO3IuMj=GC-)ti)A_V*=5rJ`ve~z)A@p|shm-$*El;b=yVB0_XA5_j|G3j zCP9G#_%Xghtoi;8gH)_JzZu^~{EHF9=sJpp2iqMpAz6uSPBfQr14_0{N+*FXP|R9I zZo~1UTtCl@zCKyr$|CO|HQatmDV9TTNJqJH%6*C2>)F(`4z_DEQ|cy24d68L3RF1s zX7;veYWq-*t(oR^R`twIZF(GM6j%Yps_!pHfx0CYZqMX}CY#%aV{o_1oKLhDa!Zzz~V$EIDI#@bU8GeB)i z1GXNDo2n+(^)q(#8L}mfob;Tg3XCBEF=FP?06JiQxuW=YA!- zzVunksBkKV*p4=PL;$BA3h~zs#T-tttzNxxmLnhYVnC|#Jq!kEh`vHF8V^@D2Jm#9UnQ9f>rk}#k z=jLnIenmx|H0PzVxceK_qMOjM0q*?>?kfcMJJ@$_BzOtf-6M2ivA1y)MM*vjg><$G zr|MRp6`d#sn*!{)j#D$N($-w#svX|^+FqEb)O=o;&F$~d@WH<7%kaX?D|wX6RR2fv zax6|R`eR7ytxrE*Qr$1i7g>%tV$5mHD>iYAp<50S=t>z~ig?uVBXoJU5WEY}{Ptrx zml(7CXL-GHc0IL_g6os#-Q{DqJMlz_opIrNpHIqnS(Xbw9kel>bbR_#iCu60RFUfN z*GKM-fco+)2TJKCBkdL7B~TaBr&vx$nktztane>FhA4NHZH|y~bnn=PS3I*&fSe=TA-JoH_TTyF^5O-V&^@UlwX9a7^Vt?O!Fj zu&l>qDn`@%%~<7=Zc;ID<_sBbNCGc_Rs=hrb%JAmC}u4!P2=@BrLMZ@3M_azyO86Z zXde^DQk>F3Y{^v*OS5O5nzqKpCdxXM8D=+oqV#WS;8V| z+wD71+ucf?mmyWTJ5cbmj=RkiuGxd@S@Y}Z+paes+k4imMs&ZC-^4CffCMq?&sEor zz*Zz)Y*`{;=1(Jbd)10f;$tSSBn)gdu;FqW7XI7qn_H|^UBYsTVxT+?RSH@ z(k|P=a$8;ZSrijMb0CAEMoy(p54uARXVaIc6KcmPv*zo0smo;{FktB<%W0okwjNka zuk!nsEo(}kEd|ixDirY1x=5G?qbce5fsdFKen zS@$4QY2UK}2DC%Y_JF=T8@M#H;^~J2-hKdOxau`>kl-2ag$L%|#boL%XTRDk)F)Ec zdANz-FhtmHHH$+p(z8R4M{nVNkBxqN3?ciOd$IENdzuoG6v9H zdallpgm`#=HvZ;SFfSIa!?Bgju|Lm`f%0MKFPO}}uk*IA75sov?4Vfr+cV{ZqIoOc z3W(#EJ%613uKhtF|M#rMRO-`c=XT$C4va+(1A7w~N|K-&$I8PQ&MtAW$AXV}jD|8n zD=(JNgIE8;F?4bFN<|No^)qtx_VXpYvz1BclO>W5jy&G&zt|oLfT=2uAExWWtntj2 zsuycy5AlTkz9Eo>$5B4N?Cc(UmV46Z)fC=OM_CkrPHA~{y8K7Ma|_A^6>czV#xGhj z;C*CH9b&*WCqOxHJ2sbDnf%p1HP%e*huIx^-bIN`@hoTMM}}k&Q<$GvA4Ox6hm8hK zdoD&tBiihNbbjvU04S1MJX&5nS~Lf1{qjfBHr)aCzVRoXX5jI=c9&rfN}HTmudc_p zOX#dn<*rINZWKoyem8%J;Esq1%O3|OkYXSSF=s{j zgE|{`oUtkIPH(|ahc5vVQ8Lqr=;$q8$LNfkSD=Qc?7be?SdGw3zHM&)=zX(lzwD-K zJ16zNSh^Bm!JXL1n~xDE0l1S8rk#dY-(?m-_+IIRIFeMsL(0zB;E%Rv*pd?yVvIgN z;CT=-j#T8P9~Kf6+bQOlc7yKnNocTUNbr|bS>%(|!@wR7ES+toOFMHJT{X%SDDJ$TPcs2V+1{ylHL4 zT$|jDQL_BeatHu^mETc9-a`&B`u+OCVEKX)#Z3tewNnH*8A68uOi#qj^*Xl8M9XqS zG~8v@A3skvr)ho@PV-!X0!bwvNfkF7B}RocDW$=;&^H*eAq z?L{04ci$b!(WF{A6rsqFyEpmlpQ=@XYS7^`a11|%fDQ(7pedBrC+|L(NO^a|d7NNg z{jaK31!@F;Kl00=VcxqiD&@ zY*L9O=$?3X`3v48yFSQ#@c?_rn6*CgPt|JoRDL_Y$e%ud1;U~`a@C5yA}n*B=v;bl z>bcMP)dw}N8%@5YpDXRJ^u#g0TpYR8A5>~M(T9JwySg@6ZPD=Hy7Z9};h|aLf!Sm6 zIk`aBV_rkf!!K z46~0{5zW;VltX2zqS>8teO{l6qLnd%Vg-SVAzSHIMY$FME32nsCFqEsv^SLzLgHmO z$(7!phz7hhj)$Q@9fYUqHdNtKCK+_vEFlYFyVoPuHbS~p^-b|u?+F+-|t!Sj4Q zPe}94mG)Jd`1t zX^{V%lQk#+;>3%pRS*>*A-n{Qsf~={0WN(K1ob4Kl%*xx^!u!Wnd6l%mbyGpDBA%) zRz_Gw6vI-MG!0YK#?nBHO=_Oie0MkVqj;G}!bE%AU`2658L~Qzzwu`LgZ& zDndV>B??II*9i1|3(ywE++@$wN+G_8fXUuv3)&!hFVhrx*Pe7AMERl0b49#T5X_FYtK#islUY+3vf#+a>%qd2$(d*TGi= z(%#<=Jx;Sg7*&E?CHO7^hcJ2KS?(;ZtRNr&%6Qnj@;LcxI5S z)mIKk1!%UuLPagf=}=fnm{vv=hi1@BlC|3#Lv8+f3psQ!bx)c$A5=l`9$ zZ2jLEpWg>-CqKXc`fsVr-lyZewWDvVzrHSBXqSVpE8lk4_rHAnw*BeX#`xaW(%#nM z-qyn2=KQzK#c%7=UpGH|U7z3iJooj#oXhw>&Sh(T_4D%T>f-jw#J{M^#QLY1*-y(` z%i~+iW6R64pO?m0K1{AIy#M&|!^ipYiN*QVxq;QW{*`}TegC2^#Q!hqvN`ep6Y#0} zcfe)*$b+`;n8OU@2h*>6?gX6w6|Yqm-H817a5=C zrso&JC9&!C^Jj!-wf}N1Ri$}^XHN*N|0XH{70v6V=Kq^^Dfq9F&jod9D^C13b-5_{ zLRP8{qK^` zWjXc#C+cGL-%%IkiH}$9?}>XZ4K|hEzf>bS>@^O|4MytkYL?g{bG|E~mmXKdKI(p65GGH7ooKqR6!4^^dGF zrcRD5#B`4i!#F4TS)pR;PSi>Z`_gVBqHlplmM%lem!|$H4!M$8r0G(*@lo@MVjr)jR(}affLcNhf0eqX8WM6@*H*yd4d?b+ z0>YF%TT(135FbXh8U#1sT%*a7zs?jeCL^!j%A=JKV~vjkd=o_7qy`Q#ra%Pr;bv39 zflTqW`|O{yoiL}CH_eA{;InBp(@7yT5(Ef%4=()asrje?DU~Wby(eF>Y?@R=H$f$C zA5&XaE_sD*JzmF~ZC$hgRO!m{gvLN}vogmWl94ZZDPsd^C{3OF@Z#_ZpK-G^bOvcX z`wLYD3L(oABr`Cz@k$V0$q53G7Xr{!K690<&tvo2ZMyko#$8i)*?@!rtb%7!TWVdj zTB+NHNe$y7uA&&K4)fJ}$@B`|+7BSp&m@EW7bG;RSdX9IAYF>N+ZwG&t?j8mg7l=|GG+AC``XkDt_aNpSd6S@mR^PT4N9i< zhuP;ZcKw?!Zyv@IsePapgH&dN%Ian zdFjWe$UBQ)K1vN~!qs|fLrEo*KF6}FsuOQXZGg;c$4Ea@J<==5FCKo4Txfl~Gz0y4 zzzU)I(%oyG%&uB|;o3S;3k;Y${cj#Q^eG)mJkEA$t&iCOKPU8b%*qJy&m=PFYbv^|3)_SQFkeQ zYUyK(h5FpW2hY%zP@Eq|1vae%_oha5Jm%od7uU8RO*8#WF6~kCU{MM9B~1kmMp`am zPw?sr#SML}H^h}E1?U39Rsq$#YrDK+M?-I+{wl{T)VB*h+Z!=~lGr?j9e@I~ATn!D zD-+iN*264XUv7)diY3aQ7o23fwo1<`xNh+#U0<9_C%KMw<91`@z;cgfCkFl;Q}Sqt z&dIEl3$|_t3(*uu3A1g9xWdNFfNCggpZeKB3Z+gemcn3Ai|Y{2B%mu;B91>5I84PS z3Jc0-B;DB;OaY}=h$;;Y?MOV}|KQ{*cEe!UT<~jp?Mf`Q$q*^WU%ld4S^ATX z!>sm^O6j1X_l{?W*+gg+BFgvm( z(FdVN`76+B<#z^S{&`0Q+s4(Zb3`YgJ1VB2 zCm?AJNl{$KB^P;fE%sp&M)kN9o=giUF@<$etJJpaDrastfeq0_* zOE5)TOKNRpp$ppzS0l6v$PD&B7-6*5#>Vo5Zb)h)`>d^qR?mf_VP*biR|ebf-VNti zR4DR<7sOT}a3v5))-r5|n~>?I$F5pS-z|*^S{v;v`pV4$kW%uo$JK>fv;ZM3gt@mU z26&ob^;Q--6gb4%h_%pLLM---Oz^Kc(MC}aY?GFJUbI>1rj#5&ZR`m*ma()~)K}y0 zZ*R%p5(GXa;o$`aRX23N`2G>uMAQ=(n6f#OioU;qFEpBE{D+I?U)8aP>t*lGk%*dJN*Bd?*uudI;)`j6)#G@WFWaS{eXKWc*12ey$ z2)pn4rs)uIJS}A`Uvx0|>cwGMORFuOO+$f0{VK(Uc}LAP;H9A_qD@S>jJHy%=>7_4 zQ>T46@Qmz*zg!)0zb)FNtuW|n`Lz0ksKTzjGq2NyvaFm zkdxz-uY}%f7+4d{ZI?YhULwH#DH`*fOKUqRz=I#xxrU{oy07B*s;9C?!PEuG^z5qe zw2qE`4Qtd+6!x>$Am*OORrfNY@oj;d7;L1A!D9{fU`s zq39q-OAt?RZLh+EN6F4aPFE24TMbvw#ma*#FV{ORBhDRxnZJLI+7-Tj*1UOU9hxoE zbfsfQC6_)8S=C*a(y@E*=K11>zdzf@JNAOc&zH~t{vtAT?#JEyy~a&G8NAtfm_7b` zQ=Wz{2h({}ee=(b9r$@KBWLXCDEw+0`L`7 zwJTJ3VL&Z{ibkAWokW9<1QALg1CdasQs|%)v>y+_l4wNsZ%qEuXDERnNoWU3P%;WS zNQBC!Li8G83GtCZ4B>%tRP z7*Olb*wiEdrJ%MGyi*_2N`f6ax&PK@_^S^$N3m@-f`}gQ9$Ryw1?|gJC{2!zeONoVa*OU>i;#OdD+1*6KYati4&?i7BNY zkwWVn6@zE<4u(HnkejoGckIh@{i5GPdoLiJV5=cCrS}2O)MP|%BSjYVD&568P7sy> zU`A0cNYC#J?^K3G*uo=hbAp-~^!VX=jSPM`%V$;Ws&2d@6!C)u`0#$Tvc4=~F4a_-UUb8D3OCazc{xb2IO)&=mT@7FIHx z$u$s1%YyBai|UeMSBb*Pex7LmV}L&(5)Tn=hu6SCR~Oi^CD}tH+^K)k_&%%@5$a{Z zc1aKcSzuaIVcg)RqQaQxBDI~a?2I~ZszYiZoLTi1?XBl$RlK!I3dB8b^(=8tp$04qP;k2Sw&HD)Id1T=(i(lYeOq}8(}`DS#}U} z$7XDtUp`GLv}T{yBS#_`Rpm;Mh`z=4Mz-P^*OfP^^r59TkSKq?RLU+C?06rx+z46& z7k$W~Y+r#z+hUWbVZ17^Mk4yXDqasye_R49--p=LLadO2A|YwO)HH!Mo&$XKqo#D4 z)cpH-GU~+o+7f6uP9plgKF4KqQ3}B~2lp}EHB_rjSC~OvWEJ?pevMOFGox8SID)o& z_0dUlv&aTbBZ>blh1)IJW*W_Ahu&B~DpY}6=o&ZUgX$ZR+O7IOz*=>z7ehWn$fVjS z8ilhqwaW&#?W`6TS<5AnsLSwv_;VTaw#bYZJV3hO{Fk8#FFjI)k zm@gHV=1V$R7gbG&Oqg%n2@ID*S9M5H?$oduNhi?AbVHHONfQ3}joAU>H8O+E)kt4v z7%KKvFg~BPTL2QcZ}2iF;SC7UfM=*c{F6ZHA-*E@w*weo^ZwxOq5_~(V^OQLZk{jn zV^V_A01JJ_`h1oKyxswVZdo*sr3O;C&tPm0TPFkPeo|0M%0_|&-tzpQ#|uFWMOl@7 zTZ9Q!!Z9GX+7>FgoIyV(rG7fEu#oG+Ofz2a$L9FHvW`Vt5ZO1?q0Fr;l3_gz{(u6p z%gwO2;zx9W7b64~eYsymck<|p8Pc(i(CPc|#}C3g0BOy?oyD#Y>G;z?>nM)h4d{av znkyxc1vFjY3a@V;Bc(n3QcUXYp-e|G&pv`yppj+^?oN~XCQX*x_5hZ6Os9Kak(-0T zv$+@lxtrUq`@U>cTmWE6vSm88nf4ug{;Sj_fuhEhOQyGU_z%q&+F|M7Jn93;-xA0L zm#4c8x0`vljI#M&4u21Rt*=R;fus#56T#s~TE$3;y$q(`W*Wa`^NpKcn|kSw)j=)n z252D#H*C=Bp<^+o))f#h#kNozKsc{lW<0RMM}A7(Pp{u5`IwL1OD5aojX7eMbfgM&3!mXG%B(TT*H4M>*n`_Nb^W+jTa5zdFOCG4^ng4|=Jc#r|HzI}a+ln`p?9d{!lput@mHwPYIfdyQc)T20uV z1qtRy6^eoYn@Bhk{jk&ob2vSX*~H705w7r?#aeuEY|KlqU*{?GxQ}wIT!W80A$(+m z=3I0oou|MqBFuP0D4HNa2_XAk>;N#BBd0I^V=FKZg0@s?OSMc#;af^@b6#3+BpN^j zGbYVIo#|&uw3H z^Vb=d>6ce|8DAooH%3j)uG8)yr$UDr&+oyD^Pu7dtTGSS75~D0D7x>?*hC?(dKKU%LFw%jD3x)M2_slFDs^O>Q@We)@gDartF|_+?J*Wv#QsW}$He=HD z&%kc5p!ynfH`w^E$=<#deK(z@7+iA?e%%p1_J%c3nmuG0e(62b`!-A1GNVR>4xc*Q zH3E(#qZXJ(8D~)dujeMir4SO5rD4F2rkidTJ}EPiDDlm3_%d9io+J8!POLQij`R%3 zc|Bfzg12eJC}M3PhTnsD+3*A1GkN&kQ6>U?*UR+846>~r(9ufDNHieqE2a3B%1N^0!Hmu!hc$SeIaW;^Cd8z4rCnZ})G z%R4WL>n5fqVRDa9t4+%VMkD#q!^`YmKJ1O+39SU}gnfo~1Z@HdmYtpix9QFTGgnH( zrIO$#6w6o8)bAtAP(}j{EbSLzzC~kpvMGC1UedZU9w1Owi%$Z60$eUmBJR^IkSXXH zp6>A;Y=9Z*_QsfI;dF<|CgUYjhJGzhOGXd#hXlK9#kyfPd)Ymi0G`dTatgj8c81#6 z%isAMm{TjZ1}pwhaxY+s(#1)>{0y>)BgOAbv12r$6uZFgJ+^VCnf;?VOVHPqp1}l` z<=vle*56h+ut(pADgItsO6ApThP9SR(WlkEHUHr~qm{4%d!oQ-6_U*C3CH;|#3HDy zC}282DOQmXVB}8)#sf$?q@>Enz!r-vUx z;DwP4=_>TRi1`f^W%d7Yxva0Q8; z&M_;ms?V?WqUKdyr$(;nP%!*w$%prP#D7p1BPy=#-t~($K!;BI1xzl|P0~5bwHH&7 z5cio!)PH+eu)&`?g#O6}!f`S|>&}{IbuH2ImKm>{Z=8`QT8X?zSj!ykoA;SCMz)`# zXodv+0#vC5;f7LPbGyrLd7Jn^*( zVQT;mX*uy&RniQI=*K*FxHAL1GyNtz_sZVKKh`ZjNnEQvIitll$P)$JNt@FZe8G3C zB(?UxeY*FX`iyL0{^f-uytG;mtZbkQ#0mN;&erLGHp-r3wUmjbh3*Cq-(;$c zXYFZ|1^+0vq%oc#+-7NUU2fCTD(S6p$*^_cprMr>$0l#wtYvI(Vu@KSuXzCLHmvxq z=G_|f4$&mj&v#*}66)(0S9HG&d0YzB7l^wQ81bcaaS?)Oz1`2!p$|+Hoxvs>(!QQ9 zHU3qG5%7L?IySXu+f)ISMS+M2TQaa+Ki@J$(J5N!NRu;<=C6%)cI5T>w{2Md!KLJa zDS#0FY{!9WT>C;QH)gNdh?V&JEH%?gymXyOegLcNp3AB2>YmSfr0pJO7j?3!1Edl( z$ICt56QuHVWf#JqGUcwP@s?#<7?TmDeQ8$K6FRI0gZr<%8Z-=lcr}^$yOu~$F6UMj zz3ap+;eFxTR}vmjN_|NnEHrUfU&oxWF?RB6rx{;$*3Gn%Guv=unRj3M>Pl_i>^CG2 zvCGsTy}w^QWD*!Ad<|hfXWmKMlP}XzI3}Km<7jk-%1g;@Bs8hN_@Ko~g4>;10GmogvdZo7g=Sn-s54fA zV6v1>vtsxlMQvwhR~tnwQYSef!#RRVvq0E2oA~?(C0iF9%bVP%#$>wpxUN={PL}yv zT1E+@ZW#78YU?>~KV3AytdJmgNGYrD!avhO&8frRn-lU`po4gmB6sjb3|N@cIM0Rc zj(KaMiZDgMhgGEHwsx9>Fx$6Bcl0{A)YO4>N&Zm=ZB{z`J( z1lr#zDq0Uz!RUYSwXOA2eG7HHAGSKc@TE;tAe0(tuU&wYlEp0iNwqu}G>80RenAdt z_5#Xpj682FmcF|62u1f$s&d*n-yeCtcVpis3DI5U+;PrUu6rOoqsRr9t(_b}$tvLIUlMK5T6(Yg;?nvE&H zWAtN@Nm;p~iTq0dbBW!n*8228^TiP$WydUrSJ$QSZ+s%?nm)YO@v%sX2)2G#+i=Rf zrmhx$&&z@n%PUZp_A|smwAKbAGCV6(3XfB^bWUEOVMq41kIT00*a`m`FN{0*;-+}{ zs?IJ5{<1BFYgk0iqFR^Gt@4*oKSt0G?0O-l3n%1T8{ipSkcwGWj+cr+hyEu{0J$WHaeV$Ra z_KEPR^ywgjpWu_8EF1a!8xPp38q4RcA?kK9El&=f#ntH0+)3u>IzX+eY2D}BnB}}4 z5K(VLv%PITktOp&WU}V@wV6K=+WZTHG*I&uD8*{r+l=H9+024fE1I0gGaK&%<^MDo z`_gw+kovV>7ZicZRj->?Ap%E6+Z?Ur<~HQ|&IfPhO8t=jM?}V{kp?*>X?bFC#;MjuNN;@hFUNN8an1N& ziRS#fS;2QJf;|^ttU(@|33+O;IvK>tvP7IgT~@-;03mNn>HNr%s^f0%!V;6ly`d+h zq=5bs?)mICTdFG^?8eO3-4(m?B#%v8B4jpWjUOf^ntXk*$lATjfd1j=>hq)Sj$n*k zwJ)DX({}3<-d$`+J&QpPwdikI>975KO}|{cU%Y$PdV)FssOS>ZUoB$TQB?Q-W%joY z@ADP;^LF7r`hBkam;=fw^r+T%VZITu5iZU@YEL8mM0>(y4m+=H`aHmxt`#uyJ69vU z7s};_x3g8E*;-> zu1|FD=$^L3oX?*pXlS@paC|uy0&j+;o}N6k#u$%`|F-M5N+*2!o5|C%_FE>c#0yiJ z(2*ZPar7p}B6jCgG8*;yLoiEh0 z9%~95W35kL`lnrEDtqhR_?BCz(-1i0Mua}c$v1lTf z>uVxh!D0d0NBruSR62(k(R-8EvL)rv!7YLdJ<5HcpfjzT{wy}{1^2yZ4$hG;oDo<3 zYpz(tN?lWePc9@us1yENl&FYD6RHSwak@62@Ao=3=b)=91A7er&>N^s?X#qqr zE1LH*I9{-imloZDS8@&&)$Sh{ zyhro`>{PEzws_?ANG@GE`k?u}_nmj2&XpZ?(Vpm7VbGifaQ>)>$1>L3@+~>)+CWs( z;OGSUv9TzC*yM`6F(lA>{C?2MyE{o-FJK*{W7&7m6zOgs>vt@yRx*^=YLIvBMkY0G z&{?C92Yi#d|GY*8jY3vkHb_5~q<}|q!Xvq-b(XrRLd*K`1w3bUmo6z77E|L|)uJlB zhf&XXiAGhf6^29iCE|5nmp{>EfJ?aS8=g)XChDvC#2BrvRx*@TTYC4luY+*D)Zg|g ztEAqyKY8b#)Bl>~l2E)sJQvOFL4(d|5Uw5VHcw{>H||^FaSjt3wgA2t5{Mm+DKoB8 zSMEPX85tE|gX}SqC&RiiBWPcJtgt|sMeOKhu^IFJxkO`Ju!g0_C|My?^P?p&Wt|S+ zH?pLOX3#RaA{e{rZ5kJ5y!r$bKls9xU;E2+hryc~32x&>bnd+;VvmTxXNyL=0ibx$ zYt8Mk2IuRcp&C|L4N=d|4QTrmwN5-JlD-_{aZ)FW7>@&~S`l>Tj*EPI3~?>v=LH~L zTTpsag5CCwrPOYZyo+~VOE4)-P`6WCk@$#=mCYDX|JW=0H&R>%R_zTTp)`j&46rsG z#3Hv>do0DtO)K${USSeeM=I1+Pzez?8wsRfq`&Gt!PSNpo#(DT7$>hAkBy8sEapIMag!0>3FTdLnGPDn=tzMiWhV-F@J8rTVVR6U*8PB_!)q2+NONQdMx=l2 zSK_$ZjSVeuDn&i8R|W#DPBr6F9H-zVsr2*74hnlH$eRahGhClBY{GEl z@stkLKty6>zZIVus@%SSEd-V~1R5j7n@qsjb6M1to#;C`G^p~~?L~2*yQY0v&9;I;`WchEaqU4XK?4!&lMsFD!d1#6<)I|MUm- zW4RJ~9<0l6Au%0rP{?JmTMlwAqXWTi`TDXtnHUYq82U(5@*{6<(RV4@DLBWf2yfc&_K|aFthz54V=}`;;ypR{kBrXz9b}w^ft) z?G=erz4P|H8(kKIcFFnGFU!W4G`q?7Q9yvp$K(?l!5^#(l^^AG?Q-+QY<&b2BjJb| z`y}5stROa&7pJYfd_@HF_Txg3;aIPyz+iaGJ&%ux$a;GUyEvy9#0dz&fn9mO+>~pZ z{o3Y?-+@yO;Or(y{DVC*x%2f8)&)UxciVu(+yUqWUE5#Ey>C$>hj}}C+h(TBOlRS* z0cCqX_Dj+y`kz>OZtSl$r(}+0v~Aop$l1bB|IEa`!+{{8#e)eK>d}p6c7$S%b5AP? z(Y#n#xwyght#~G2Akm&n)FqBEKashjbl7Av*dzGZC7WxZ!gvjQm8UCw?Xq;W(4gIh z17VucjE$BwnGl1S^v7#?nv8U zMwIAcQP?H(4=MOrqQe+LlOJ3Cp0Kod_u{H~p!g`q$#y>e{$R;nORw=)lW+L##lt?_ z|NVOD;o#DrlF7J6z^mBhxRuNxTkZsqJsJc|UbesoqwV1?k8(V9R}yWIn$int$rmGI z&a`H+DL0Xt4?Vn^(3^=aFR7};!@OJ|VISuMnZ)w$z$o!kgOlie912-26M~k(iH~n= z%b3L``%L?C+*dg8+~EcJH?r!5%O`I_llMQ~@R>dqkC9gfyen`%O3a?zHf~(Yvm$OB zb2+2Mm&Jy<$Z`CXLHx8Wu{p`CSl`B-gca`_-=L`!GKnQfG{3zS+$DLt`T5u8H>TU{ zwq9tCxY8omlPh8dpU}2WXz>SePO>RPCv_>GRDw<1)cgCvEmRAh2`ia#AkT9T zpN50aiNky7lkbUKfIf-!KZkcD7km;L_nuz`mx|-j91kZSgH)sBqipvQS3HDo0nk|5 zuMwlpuR-u}iC+I)v5VWx>LrP``&quemOQwhdhjG)LGj_KMACbx7&gs_fms=#OpFbh z|2}u^!BmN4EYs#8w>PyVFOKJb zag9>fl5;{q^5cZO_taihjUTLInIh6SY-xi){v4$E<-b1YlBF|IP@UoTL}eeVcKcNL zUNSb0s`T?c-?-CCZ#053uP6~2HzL3X3N$=QcaY<}%Bqa2|3^m!$CdfgCl~oA@zVzF zLsi;A@7ZGQdv{ay*#>4o*S-O5L2(naY4@SP-UuuLXMauvM!bJmEa92WbP%WfGtp&P z=w`!31KxZn7W&I0@#IkwJ{r}5ZLkIg!FTZ-U*%6HQU(>H_+#Y{XdVesn(yO+gAb2` zX$_u^QrG}P?ua`|?k5feiFH4SgVXLg5*GgMJ-Mf)e}`~UYxMEOxQp}R=mX|lVmQ75?+L&iD#9xmt}MK z-0$7W6GR6!9zQBMw{JMOvkkBzhBU&lfK^sqL>%ZP=rIMG?M3+-`J6VJsKpTwM+o~} zdt&o-Sh=H7Zz84|?{*IN$&Sv&sk%ZGPH#O?JHW_LozHa@6hOO_> zl4Xzf_HTA2rF@>7usyulHKw%w&E{!;-Qq4g=+{&7*&V4(w@2r5SFmrbEeYhdfc$W zI`*REW0)=HvvVvloug5%Y9j1wUyQ++n|<5)arqzW63;3$4PD4xWf?QufY4vD^5Eby zyeRoBzYYDhCsOX2d8bpbn=BEax6du}dVu;rs0-WZGcAdQ&yCSL5GF_4Uvd}gYB$m! zOO^%ntK*iA52|)zHFW{nO==v`C8e&)f$QrX=SsfQJ#k-I({alEA86g^Dmw6H4xa}9 zp)R~_23F_>8EW?I75At@I!X4E)2e{{FJ8}!7nZO8Iynp~qEXej*lh#SGaP5lw@4~2 zDepm$eOF39rCy=s7IK#~F3&-t9 zlbV^#e^D2k>(&EqT7ezZqPcE)2I;rzK!KacK;C}Q0>5FET;zwQTkJNEc7~X7VYlZ# z7X>nY7AsZawcQRF2$#6$kRWg-ZX|(>=W)xQ581k)E?god??!KBKgf?)t;OB_ErKiB zN`39Ai_CcE>6+~Vxm@37o^39gO)*SBQZ1fc))FEJN;QU-)*5n#u?fPl{i^3uciL;4 z>k6KLScF^0I`isn3D48KOCx;Mq+dCN3uIKss^5}+^G!5Xusuv~Te`7t^27A2gfoLU zcKd)2maek0^`QlalOXKgy6UeF$173xr)-W;g+JGO!X7A@0PtkUykWG z8sWT=9!8kvN^RQ2Pl47k$TWA$MC6(^eKq)QkY(;O?H6vSSjJM97e$=C*C(3Z$#E*i z(bTlS6g-s`s=6N0b>4U4dAN|p%{UNEdI38@v?t z#9QS{iaM(DChD*`S$o{o9rZb*MM)*JHCw&1hKe#=SY}t}8%mn~6ms;_0@-8&fhQ<#O*a1dOLaX(|i}A zdgy#5`qJ+bV^oIv=?LXjW6nz;3v7X0uw>BOsg4f~6+P=D++5mqIS`=(pA(OLqBuPP zwVV(u;zg-%Me1svkzQ0p?#7u?k5a$-5hrGDhTxV$so0z0ZLoJG9zyI{b=RW`a#xjw zG8iN*55VZbQuqNW#hirzp}{mIJ3E&m?Ujqk(3lj1ZfoXm9D=n;yPlcdtKnJ)@u=Sq zB*a-B5B1Wi?VjYEpw7~pjIs*8I#8rN4GoZEPq%p=nKtRx`wEA&%xo_lm z-gN>=t*3Od%{WHI^Q2#M@#0dfQ-i?lt~h#FRLOdQ_~7voqsISW>^`HKY}gia;3xo31A|tHY1rlCTg;R!~-&{4)9I;y7r3YoXgjF@C zj_qK$$hz@re4HwMA$y$tLp^7YW>&6c;rY=!U>AiDhYOzC+K=NTqxjTIb!vLj(Ysud zRBRg+B`rKKU!|BR`N19k&YjbWEqsl7X{$(zckWN^UtGg@R-&EkbtJxE*`mB^x(wED zc+P22&Dd8tFo2J6;!)+IiamBicgwgF{L4Q_a}(uk;lMyo^IL&;Tn|U3ki|iBCrs z5WB5e6u^T#=c6?IUC&afY89oV(+jTK-s|$UPCNB^(k$w4s_@V)In80oe(R{$nb|<1 z`eDxN4ZiOd-t+cM$&6jgOhk9;JRfxDm7JnGXYn}z0H9$jI-c3{y?pU{s_p2Nq;51t z43?6ubxO8#I4HiQ?8CP4Wzjk1!K`AAJr*^(3Cc*pxb~XaS}{lr&@K^K$JMUDH!uVf zKI;-`_B<`#qeI|xU`(!7e%h&x4Bdc>G5IOETV|3eNUeKAEvi|8*F}j!ljxt1q-#TR zoeSwD4$U(9SyJYbDFV)+#?As<8QhjmAE>^j8s(kwHcyS#ji1J$U%*6?yW7-_QhJ1J zYsy}379l$s7Nrq$;A)*E9`KRSUOL<_r9M|fxi;gE2CuVy{GL{#dZc2Z8HP#PA9T#Y zZxez^@m0*5U#zB|j2|r0)$lV5-ty7!IJ_e32MBBC4n(!Or@(AHL=PV9=rWABOCED=$H6*gHNI77b>at$b->at_O~i~)@z7L9*KXdr?Q zmm^Fj?1emR0UZF*pufCg2Fb$8)|KN4Y%^ABeL%<2+jWVd$lEVCR=5D=CnU3Zy$+6s zhM~V>V)nUuvrw#6uRgjEFIzWC0Eqw?qVwp|6F{YfPZ3k~UIJ20fQvme1y>K`{Tm+& zaAE~5YyhAq22xIJ;lT<~SOgGQ7znUdak<_fY41!E+odq*q7bO*pMdumh?_CU85+wZ za&!L3lsxu)}81y6@;~N0n_P29V`ycHyH<;$X-JNs|9Z#`Czm z4?SbB94VWkAXiJN30(dGQZ{hWx|yU=2Y1$@2wdrrUBt13NGVSA$ZrAn=+gpRIQk`A z2_*14D+c6 z*y0pXijiTP_?A6oz?u@w1EnVFyqjE3DzvlxeA^Cnpg3*BXNj3;iJ@wk~)N3}<)oQyTa z<&R07@s%=(l`(DW{)FfWluTAs?&7^pkp(Yd(8cC`GUm6s7irN-w0Rt5NFg3%K2&^` z+$)_5%IjP{DZ1%9-UNZ6ba;WvPZsSFVgW!jvP9t7t*NZJYWiPFkSVb0_!d}^I%DSfZ(0F7` z+RmH>%ej+#9LN;ET}Ss*-sV(mg^M6Zqf#&LqsNu4DTQfa>r(3Dj`K3bEj?fH$&@om zC;I*II{K~foYJfAAQy`s-*&lxiy(U!(ABr4fqs)F!$*5$OL2)S2N2vB$k&+N#eyNlYMP8VF{Ux&%1R#!E1v@ixK>u=D^`|PR@N$3m5v4YFPpb*S`SoOk11MDZPxgCR&6Uj`d<0y zuVNjzst&GHFYw7`Pbz&7ls1lgUEcLt^PJT!vQw0C_7Lub$kohdKC4%_<6~VW<30Lu zqr^U(WNxSM*rYXu)xi0xRUO}xSY}_0_#0n)hG%uRNI9^z3m5oY$#dS$ci!4Y_q~Nx zH)^%Y3Wa)csxNT=V&-g>VvliCDh1`=jS;H0Ceh}_pQEiLv zNCt_}9%Ag3tvVF@Q)6CO^lfh8v?`AJIl%*!}iu~ zMAev4D_!orL?z4lt~OgCo4PG?43&bXj%&xJRTwn{4jOE^+t}BbS3}eTRc1YCBS8We|bq7DT{d;hfdQo-GMwT*gHdo=4hxn8a_mcfxi{F+L`*7m3EE+mEDD0R>X%3br~dK$UfA@<0&>rC!S%GQ<35 zzmM_%12zBo@#XMf=kUk&?;ktAe|-7%B-^Q$=;2LC$kgn|4YkntZiwuX?mpf%OL%8XUb+v%;w|JwMvh769fOK=eMs~-wi)~ zJvKBk()W*ao)~WFA0K@+)b+Ce#gTOG?&S~Ud^O13`Ix@~>g=M9T)Y_&y z75}f0U+$TO9J7zvrgIOBXEU&a*`CFW!hh-Jf`b39oBwgm|2EG5)$$9b*UTJM{AdPc zwEOpIw4|iu_=LplxVZnWn;Qeo$T3tRDf-rJV&sk65mC3oB5nkSMO+IG|Hn1^2ZnlN zm0zS4*~I@ImE=`KWMYff2Yla|3RCN`h7>PSxxu9P%{c`D6eWDr=l;TtS7CcE2XF- zrJy6Jpp8Un9hX1)Xo~AwO2}!7%W6QF0JHxO)Qr01_n)XaD4Z+(X&{nuA9enJqGq0` z?2f_5J~&<}{`hZa{%_Q*2fvUVJYQID{|{=md$uy1e~w}|Sw7erQ02`eEfGubz;BbBg9TC z_C}S&N!mgpKmxw=PBNNL#!lQhDPwgL{%0{m6Tu5gB#W~hi-UoCea37+O>5Jp+=|QM z*u_J4>vOy!#UDxNKGYJy;1zhB$VzxUc8fh5?T(%FDls!!A^Dy&UQtUo!UnjZ@WlS4 zu544oI|tHOd4B#JaW*f#f1&0$+uI;5U5ixkg)^eY+d_KrN%#xqW0CUuKk!$eg?bht zH$?V0%>2ORG($0gwet@_vhRwr616wiE!y=w1&xzb3g?_|=M(XHFamg73j9hg!7Ei< zj%FBWW4mEG)ycPk(LKdf{8Zhjjk8Wy3f#MFbRL>Mi#j~X?}@bw@x15P3)PRm2OMlD z#Uvz$xYYV;O@6|<4})*$};hT{3CFe**U z4z^5g0cR)hwz84*38AwBdo|4vdF9$R)j@^VPn^_V;;Z_b9Isiy7?W#tt-L)!)zEv& zAsFjAplUgm8_RQR z7F+(6oZPjzDyrFnL7uJswdu4kaBLBLowd=Dc7IXR=JxSMG2=&@&ett6MQ}+u$tQ57 z>m|pRPkb8Id2zv<5xJTzr4`Y$aJOkR`;$KI>RyrF2Z8HGl8^C^mC$yUN3WQV@_zVK z@dZfa>2;w~Z)0yv*+2bu)bD$-+5fxX-~B#S8UDobxh1eq2UvfH^!I#%VRNuh#%B() z&@dgGwpvF<1w|uag^=z^?Cqo-3d+ijG`T1o9^@flb-obhW8N(?vlFX3TnLXC=$81k za}NV6LNM={_edR~W^=0|-UkCca{9Y*_{5^4icPPg<8HkDaFM{%fnL=cy9ur^hETtG zpL))2qOTQ0F5ms93{iYn_>fOsCN6G5ehbmJ4dS)P zwOzTI^)BQn#!oNJ7q@t<1!D8n z-5u!dH<2asjGI+leZ>3ivL~$*uH`kMgy+AeZoVn)iTB9saH~Zcy&iWdieP5P64Q_` zA}L<6UI?fn^|Dd|l{1`&Zr`>pm0Ijqew%xD4ptatMu*S}Vaug72Mrt?0v0WM} zQAUIBlfTNj8$vHH=*ZB%O;dQnRZ{N8{^fVx){5X|fAmnsd*5F0uoK?VvqD z?0S`JVqILkAV@Hu792aIfWW^|$YHCnuy~P!*rZ*_k4{CP6IQ0VM5nZ3EaQLVhk}PTQUNc&FC08BOskUCWm{R7&Tx|k>kWIyf$GVRqP&I zpt)q9k?8dLY&^`OzLD%6AVa->$;N#)t#~AzqjLqr$0tjro2pmIGB}Q^Lt;%3?FI2y zt~&1@5%zu{eY5(5Q?#%0Jv9bdC>MQp7ER1p)Qa#7ln4fuK~E`o2ex|TS+ zl^2U+ey?Uj?lu$P7l0BXq+K3%91^PY1oLv=)znA!ao_sJM zCfW3oeEUr^1z~VwaDVZxp)w+N;Q{iKn4df5Q1vof*{jRlb)W53nzwD5tO@{Y_B#SK zCQCU3EvE+bg_^SjHrDm_)y(GqI$w+)+qX4Qp=uo`l>6RRQjQ28k-ih(YYgZX8!vo< z@voV_p4=xjTbIB=+BXxf4|ZDWh8bGza}33 z-77!)eA909*W1>=`*qxD(7zF6?w-FXsmJF99D{!AO_1Os*e+Be`X);k63U=szi=EQ z6VN1%7tHSC02V67{`i5u@BEhA7)JW&7W?JB1SZ&Y_a4@q%-^ePs-7j8;wjcGR72}I zjvqVSqcaBd$Nz0To!p2(OCr*ai18TgL?NsXd3XA$zVQx*K)h8T1OI>^@#>O*l2LAzU8B8cWxghiI7tdLNJDOUg$sOUk>f>xC3QkiM`0Xx`nKF5kz%!#2}hOTH{_I*6&RzVzbL0OoG3` z11MQB_XZqQgFG)Av8TGiu2B(Nf_JTUqD^^#Bv)9nJ)*Y*1eRhuN9W1ag@)6d`_G@a z*`Wh2^c2>C&hK4+BNr~Q5QmLMq!La}(6qvLxRYJu*@8hM2b^Cpa0VVSy956UfZxU- z!qI#yW9%`$hzgViUKa7bD;@*{kpR)0SYizV;*gTis*C8~VTWiWCeolWboN}VoS-zP zO(_41I`#u^gqjEB;uKG@DG(-)IBTv9A^?sE_BS+;oh5l2o$?6&t>HplR5@qKf{&J?oLLJ~NSd^ru$bihx^5K$e%j!{=31iQ=COE-$lOl>1Jb2V774Hf^$IVtbfKq- z+yXh)NT~Zd0~^j z*(cra#{gobbr4YlT(?jNDLt;ud4TDS%nMyCTWGjY6nw+APy@|9&%~$c=#}K#LbOc< zCDD+6;t>}`4HWlPRL+poOy@=8#^;))I7~Ky!4dqd&_ub>$;b=4H%TtT~)PJ|jz zFf1C8wHU&7h(ZhzYuUfna$|wx-l>r2N0+@GIZ1M`R=_B6nqfp3D7b$67Y5-(Nc+Xt zPK~qP&=$qRKyEPLOL6G?)5mX~d5n0hZtz&`H@_&eqyFf2zET6yS`ParEQqSBI5ytE zNy^YpftIA4OF(mNVYrtN9Pk~wt$ECM8t;>Fy>s1&6RkJG=1WHU^{s*mUIo>Fj2a2M zVn3zp=P|HEI{VW)Zc;Z3(VjgV!7cQQ$Ibx33*bIfL^xHQp?650s^o{fgar>6O1i>8 zq=uk+Rs&3>y(FhY86sL2(T?Eu*MrVvvoq@;@D`pZOUv)`bV{+XJ^||7XHb~bQR?3fIFFJ3Z{XWfWrG}h`B0WkSplUJjXL4 zmrEj7{ye)!2MYk-=esQXJT=7%`-Cz72-L_DZ-6-csfA54`2LuXormDHm5iqJleDxL zeJg}vTlVRBBcAyrE)lM6X3zlpf^uEgZ!xf9yvODBa z1aMB#xn^iwrT#+<8W%8yD<93qg73SoXL>;k@x6*aY=<;7)&dOc8pby?@3t_p;xTx3 zJIN5Wae?ZCYSv)jG8!%i$l=ll?$vR&Svc*vW`@wXCxRe%54Zp zxPB42CwEw-3}2$^SV z6}`x5ob@E&84w%LGbXTKWcf*`-Oa==wKW6&)(64@oU4PMb}i=m1!3aZ-_0t2bIp9R z1JADN8E_gbWfD%v9X(@wfr;}*U)o|H>iA9*M=OU%IXZ{(F+i38vpeHrsVlr9^m<@t zA0n)ofqX-$Z|5Y)CVchR$U*$@==c;W#ZN=&o2-xA@cl-pE3OKc;Wgksxx z#^7fYeHe8Rbe{HSdS>AkqF7M4BzF||88L+hvv7?%rSs@*BAlmr*=}}8Q63X`8hKAb z9fUYf=v}csk7yZV*YD#I4?y@TacvMzcrJ1>@z7AtJ2^_MKhc~@uO_@5Aj}Rb2F$jQXJ;Q2JPs8MD0MfI|3Zbr$kfQ$#hmUk;~}P6gSW09om#v4_t2+A-sE0 zok=PJlCp&PAg$)pMA91@YVy-zY5Os*POO}Z6dYi|!?2!V={jGog4jSeorfgnC>`~3 z*&YXUTsw&UTdQaCIyU#D~{4Ja3ae zIENi)bjsd1icc!#v8LRVC}d4;hHZ!%L9V`8JE<2=?K_d*evh2sv9SMc|1X$pI*`J1yxoH=M3G`R%knbJ4~&Bshhq;O4P`Wg;R zwrRpC-Uw8`vT8DKaH7#&WHkJbp!a)27aN2|V1fr`YVtWxK4#Gw$7Q?=PGc%L8V0XP z+cvx+*4;>18-BdTN?Q4-vy4mTHOpUh;NzHMVP}!z4uHF9V6!aajOJg#IG*!$46Lx? zHW-L0j4I*|W>q1D>ltRR6pB!s!%(g}71C#;Z$Qwri9re9m{8b3-w#-ady?=WjyvG_4C1=hADu&pXsn1$#zK$tqR z=PRTl=i#jndEX_k+bm|ctN5630$0Ya{sUqsi8?hp&CAQN-^x3whbWcd z{JjJJI{FdopgpJ~g~ z)l0_uJF%;G1h)SUFkEH!)g>%_q$92=fL3x5*l;ez)Nv+)+v7INIuh4rg+9Oq6Kkor)2;uxVR)p~j^*C!kOh^-pcg0fJN_ea;1bKak)u7w>3tyS!AWt;QF57oVo2Rgep&S;8g1Ws|%sSJ5 zYJ%ekkuVYAjL@#Q^3c*KaFt9k)V*rlUVflwZ+~f zgOwYzpByt6p?5?|yeFN>w@o*MeU0)vWmtcp#0CN%1gu9tmEP9HJGN!S=?z5+R)jbX zt0u_o87hJoNJVB(t+-I{z+qeuokQw~3M&Ghb=U{c;J8BYJyDb{`-z^qs%29*S>wvA zgmpypc8;oK@N5(g7Yfm3l;)8kfo@1>uF$E_Yerw>z)XZ_VHDqX{G%rGJ#d+hlS!jzo3 z$H#l`6v0n|4x*q`k9GMXUy_Ebp=kb*&v6!>-p{cb|&<1AB&Vwmlu%6&zI%ShZBOZ)zuqP4?w7~*G@(aYHR>~6Hxsp zO8b-WSl%$a&-IqEj$7q=UiRir4I)w(dXV6z)YUs)8Bwn8I5`Q*m?fb)VV>?}+c`8qL(Hv2@PS_~}nNv_Pruv5g_8x|MO-U%r6y2~J=tKIHvh*JD`7bZC~T!{*z<{nx~0v(#>0Sw5N-|pU% zp&@N$3csV2tp;SmeZ2-8)+;wgKl9$NBoC&(dNJW)8GezVY;ftbPpCG>8$i)h;i5|C zjh5Lmw2@Gk&_KkC-wA{PI`*O%HT2o1LN7Q@SnJZ43&osIE|$l_-@U?fOw?)F`2q`f z^Ee_`Jgwt__BN4;HKdy})44GnooouRenjGB?rgX40Si`3{=;h6YFIbd4Bn(0Xk9M_ z(7bOD>lcP`<6a^1vYyHIJME8n0ZPK&bvL#5xm75R_UJ#KeQkt<{((*UdH>v*FD?o;g-f=nSz9O*9zYfH{c9B=dG&rC zw!PT#Lou+m%| z8Zct>dXa4U;dz?TJjcXJ0h&=Er}9f!q0mhyftnRA$T|1T<>AwfHbwHs<=eOBT0ueI zTM?9_KqI^WYx}_X0tE7o}C%&(h|B_!sBE#Z+5-Ja*{yaW=nTdFDbZLO+aoN0Z zP4t|j!1oWFT6k0O8--r)_^%*U3nM-v%nw);U)y}#iTh|#73ui9c|i*wPq-P7=N3N7 zd}7ZL9aCj>7y0~n@0SAJ!!PgTmRTjE?3U!)AKz=585N4T;M!h?jZWWqayIluEu#Gw zD`(zPW2MvsN%yDpGzyChrl(%FRq=kMIi|)Q13rX$44ux8#~haeWpL{D7>FjMHCFPb zRM1HJS>u7_| zkY9W&ynugp8qihemYGpVS%0js3p8fAijZ~gdIV@ycSg`zJD7#7Era7gYoSaS&R891 zTr~!G;of{x|I~4HaK>YO{`7}t(#XonZUVjAs5t)WAnK-ttbwBez`s?yIQP$th*Vpd zNLrdPuBW2IILS!rlvJCKFPL?p>#+h!a4BcvDoS3I4b_dXp6w~`V3?%KB?wEg?z9o` zvFC82y4iV}>x!D^AHzt!_P636zwFM$ket-|s@4G+jFV@E#f`Qo%n8(K)<#{0KJVN( zhc1~|8(lLEik(1NNJA_`X#vZo4kB&w$3$ZXuE{+yLR$cv;_?t~o=CDEA;UE_R`@r7x zqwtw4js`m^mLGY#2=iweXJ1yhr-%*8`jkb?pV?7+Wcm}K?t|R;WjuIqGk-O`6oe@-&FUcOo-t65{$@3Lc_OAd z-i#$9{%N7f$LVg*%E5+;(S@H+4tt*M_YC=%$Bx0q>r!6a{PlFtk?>KnhhTnszXxA| zI#ZuW$cf?{F)Wb~gVZlGBsM8FS%g!YEoZ3|6Cxe(e7p=mgdq(>XUDUzSlz5V0pM#< ze3RF(tiZW4Ab%ZNiWw?6u>6`k$m~cXpPHO_F?@f#@(bI(45|*XEDpH@=Q?``h$M(%H zHjzAtu~+B8XNfU#LWP5p(MP9&_Qbx+?q<)dWa?P9QnsP$A}9+}ip@LQ5it!9edT22E+A5y;HS{EDW zIvqH65zO;8yRqQ6Fqb1nRMB5Sn~mU9Lf2fRNPk9}h_m@29g9A^O|piZ9XL|o@sD>2 zQM{AqTBa8CqHW3tcugFsSq?dGIP7&FD!nN$=RbEPUYP8Rj3Sx^49~=70c$^S+<`u9 zt}{v4e3!8_4L36R#8=>3{#q|?`hn+EiHV~Bz^OVcK0h8!&O+b(dhXI^BxF3sh(5%) z+o{N7NilG90 zf%ZF~vpcLhk&evjNfz;}H>87xcQy2|Ft+g9+7l%o{KuPWH!a6ntU~j=XHeN`9!3!1RiQAXR#e?))i+vvC8TRQdkyb9r}Tmu*QF6J6EglBRptIn;M7 zU^P>x1IqhaioeHIT&8PAwBZi};t9nQTH55!X>b~#zSn%yb_CoAg^drtp=m=uw5q^$)4ma{@=vXaX9fgFFSuder z>m9CCBrHPKMnoE-7Gy5k2erN(FWc^>qJDPpNOE00nF!J$#%m)X zr3OMw6kJFXETkpCs&>(XnC+A=qE2pplxY#2xL^2F7HpVARh58%2YM3PbIEgE9(pJ}!0n0m_}MyNFx$EMIRJDRGCkxQ9uxgl8?-oRXF2 zRW_H1k-AzT;U|1Gqb%+Kq&t7Xwl-<&mGIxXs&tZ+?sJuj-<;kN!!^RX@nZRlmApPo zTU+15lO)|I6?!%~_-*7^$z0s`bs2ZBSBuI%gh0y0Wc?Wb&Hky*wUbvSM z)&ceEqkfGlYN*Z!a#RDzLOFyL8;Af0q8z2OylWIKp46xyHZ$wmv!nd7<2I?;o7D)` zy6ZI36BHNC-FsUxwgr?w;+REK_N&!O`d%nDMv)Ns^h8b~zSI;>a}UfT*P( z6Q)w;1z-_~?If{NMWs_@#1#XVtGoPT!mjtWa#@h336Zk!>5-@VvI}JUjaXhIqQL8W z=)f=N%Td%=Ia#Vq5Z}9e`{=1<0@^5|d8HzVbSZMueyZVeBuHjfmmJxdtxIYbhiqMh zM@=O&!4JRJDmpPXUZ}h5%%QnfU405apH@vIL{3W2Dv|59=kHX!1>b*A6ZAkgk*na# z+Y#2l^#DWx$5q!9FaczOkJb^Q=A6IayM9mX9+>sB;?kvs<7sZX;q0LUiml%SSdO!O zyA2J*@01-tSblsa(L2vdLOk;0ypF+adud#J=Y>)1(Ma}Br`BuYE;HF)E|Vg^_{UWk z6TVgu%{qhZc!SslA3(qQ`QIZ#_}5??2a6Q@Yti&=up}vt9$bHAvr~K8GgxD4`SmrPA?%G`^%&LMD|%4G)^!3EXn?Zp~VsJi>L=TrjzqD`-5LhtS! zVV@fMUUhRAc_56Ob!|K7oy`f#W%h7UyX0duII?!H`nuLb$Ll%<-w0D-FrI5v`)@Mu zpt|x9y|QoRb)nJgUw*dlnVnoY-M>QyybV+QJWDtOif=l1%8Q#67=Z{E2Dl#+`g*jh z;*0MdO9WKzICVEaPF@~@KOS@GIAjAE6fuAQ_0m_8E{obV1T%2mwNT-DtHt-s#RX?s zO~)r*{yYa{bXPa(M=Y8>F_MCjhEQ}9Jv<63bYXzJFF(Qf_MI<;b@03J-q4BzHjXf) zjZ@y>)qIQnSjexSIgyJW)s*fEylv;JMn_SpU#Rz?!gXIr9bd@E12R6UZ6K)GoK40* zbfwuVaO`X7y)3pj@OL%T zYJXvsD|<5`EU&X?Pdh_-FT8qk_{t1daKV3s{m+qI zvc@>b&AA6ud^C2tG;#6j^z>@g(`-Snkw^hqBpWOs`o`8LK#>s;QuDo z*SU0FNbiES(K|tQxhhSLo9E0-Uq}Q zyWWZJfcxPoZ*Rn3s%z9&p%^36jS9-)hmFrpZ$M7YmE=bbus}}JOp|z@YG}TO?PvbBjW*a-iz>JB<%M42U6y3> zN7P`i&xoYD_N;dT7MU2LMOV!ku3`sn? z6pEoFELHTogl;Dq!7R5D!=&!1{W_4Q8D-F>r7HGyDlc8#c%4U20&5Au|<<>84rXSKHXNKpM0ZVz$M9EWR(VokpR<-Hw zHrF?a@`W)&^6zEed^Vy<%%X9Ls);Vm3$Z8OTtStdTF6ugxDwP5mosAGA#E`3y30$3 zCL6Jr)lBe3S5<82SzJ?ntKd@otN~P2TWZ4YnMc~wSFSHB8NXDn;^L_M_|?VlT_}rP zVfVZpy@#J%-#H4X)G>C-YN|YmN)93**{UrREcyLr=_e7e3ijwp@I#Y^l;(krKL#!)YIw@^!?Zq>IPWDqZ*k;fF__hmBP!Pg|gvpgj2aq1vEq zci1!&wc~CzMweq96uGKeX7V9I>7`Xkl+Hcb!Z0m-g-n%x|9bt{Wx~XzSEogc5Va-- zNss(<4{nvzopt)GD(fhBTkBn3@9h40pXU>C-KyJIT9fN(UrMu|K}M`xZTi&}T;Tf} zC6ZTbBs+F93d5Gn@XQOQp+MH(gei z9Mh-4Sj62sEeU4=T;%K+zQkX*^twk<*K7TamNF1e4R7AM{B48=ndGr?QTDGK=R5X7 z>Ep+U8%}HMsOyMjAc1-xIPi5Xk9NClJa(%f#<;=&@?-7N-{0e}_aknVNY{76wLZVt z`^R~cM!g)yU`lHAX9 z`KodJRZlE1&GGtI8G(Pexcm2k7XI#+!){Ap0g8f2d3&|(!XvhM7ow{bY(3v@fIVB? zxLmE$RCTnJy<7W7N@T3cvt|A2_qs-`(YCJmKh@XfbChEJfEiO9V1ExKr>Tpw7xWZR zeq2g+7~YH2ZhFo92=1cZ0E#>JqE3v=h8!q5J^;&@wk&T0jDJC9EJR(;+fIN7}w zvk>Ph3@k6;%M^a(VFNsxIumb9A|Jr^2<9-=6VTcPyP3`pJ*=ki9j0rBkGfHl?H%lgGeBUtD3_YdW_i_*5*W@aDM% z&em&Y`Xp&NonzD+&t-)BcW8H5cJD23AVH$$C%k`~mx$Q!_q8XDsEfnr5!XCOsjP_1CXj{fHBUa_vIwiJIr&#V?HjJkZ zmhj=Lxw1r>fr8uNPnEwNgBtlw!#W;>+!x$D1dU*A(zV4+lII%{> zc{AYM8CY>wv$5CbmGt#z33GIIx$iM|Y?zUdfs?5*KFl9qP8N11j%w_+3tU=40BZ$) zPh7lz*O`5QXsRm547AgI{}rEd{W>7%x}%BZF&}DJVo^QSP`Rk;rb2b!=D8c5hD*X+ zYt*h!+rJnvIT+RsK4QFbZAHHJN+=5kLS-g;gUBCXB%S>Sclm^#pVZaW>ENKxgExwg z_RfpQ8)x_?ck2HTql9#O!+{8>Z|0Rt6GdfrZ#`JTw7HsPU?nEev^+~;}6fBx709PK$iAG z{Go}4AD6@nStu-`)hxW_L>?pepKaOuHEhRxt^Qnhca9tu@XX&?5M%4+pY-;B0Pr-B_{Tc<`o@(SOlF4Z>R(O7)Nw-dQjR@D z9{)}OoJaqpq*5u*bg+lLtGmuACfJ=MjWt|4pNQ%3d?^q%jB;K=IoyAqWCA>RY23^3 zKw@0HBoe98Hi;b^JspWPoi>R*`XcAJW@hbet#^creQ*x?H55H{iXWF5Y{~;Cxn$p# ztroKEbL;;wcb`E`HteGB10)byNa&q}4$_-6kMSs-Dw1>DDS%H7~09Aj}(9w3M^=q`|-ZNjJkZ$C0v?wwk(YR9ujBmwvgJRXB z;4D_)qI(d2_M{@W6qliPqOE=ntyqn_y+HcdPzzSHv&mQ2C4TkBE~i>xI5qBq{;nlG zuNOo>KWS7Ch(k{zt>V-q*g;i-o2HZeK1TPAs7$?kIt_mSyPbK=zygnhifyo8je*0? zp~X+*K=wB1Gwipg?*+_Ttc_JPDP&2Yjm3daG^wu~O(zF!mWp4h^c>87eF+h~WA#~t z7TtU*5F)mPGK;n2L_=JM9!LqIN5V-T2$*l(M|-*6dJ!E;+Jlm!j))U92A3GUi1tq? ziRukMQ{{gu30$fyiRlHh3w7Ng)tr~#j5#RLZ!b1hHF$ASf=jSAoy4z%L4*=A=+(W8 zpL{h=P!ZC1bv0t%j#VqgO$%VjLEXTDWNx?C>iY&Lw^W<$@HP$bgYC2@r8a-M8+g@| zi-cZf8>dTYVB^$qo!hwS=%lvrW*NThPNBqRAg6@Jvp+%!SHqdLK&haTyo0R+_AR~F zd69BEF;XNcy}-FFM4_5nB8PfDZ8xdRToLQNv{((93I>S^T8r*A%VQzrgSC?0H-s;j zqB>kQMve1ztWPK?mDZ}F_f1@-#!uX;IWD6}s+%Qr`>j|`W_2zwmiSeZiy?cyF}=my zrD2qq2Vf+WbC$?DE?mTH)8GNWu^p0>AxxN_gx{t7J*#u$0KVIUvxoGBt7Ny!hd*E3 zvR&?|X}I_TJv4SLdE2v=wp*V#QTb|Ms1ko69l2#5qZ`Vf=2$J znf)MEB^sk~=+S4IW2~Z9vl^epL?`4bCsafywf4WMMm~H3n!@xzVf57c{G! z#8l44iO!`|&Sn3Dn)mO#j*SJDo72;%*ST2o+WSYMH)=e?ps7AjHA5vrH3LAWzdjGy zqqzk`StYW6Ie->-Ji~&StYo|_o#!p(JuIt9m>%PMQWV7QKVU`fxm)TSm{-$S;erz- zZd+P)H9SVg28(^O&`OQ%^s+&3d66>tJTRwsu!Kh@gzxR@Y3+@8nNL=kcORI)Za>zb z*tv~%F9W4o9USUmzPUWuz-VI7J+?)?U$w;V{hHrl^|Bfj{lRHzVOA-I6}Pw$JJ-S_ zVr`d-#7#9nThUjU%bORl7u}yky{Qnt4_*x05WOxU;uZfVWhXOHxT%5_34cNXHfh9z0&@-1~nl-eg1!e+N1lM(|emUJDcudU2}TmCCUJ@Y>^)PFVX|j-a&Tk3>Az6gpIcT&>Ssrq|1sGIpI+~^pto!NzLh%tZyD-=(c#vy ziGMQGpL#obyW0pE>Yk3K?)K)+_U881#*b}H1fu; zP!ouDB%wYX85I#3MW|0FqF=T;iv**w|3!V8ptOAnO52Z6pLX~3bx0{PjmtHN$W#qW zlYfyY77$OUPycU9`yZlx=dPQb!+k=48fAaKOk3gKiMEvk!DpM9+9&<1KK&nv_J2{I zmiebXE&m_t)Bks`I(-M^r=hcC>mSeLa@gX=#*ZF!!Zf&O>J-7xMz z3J$&h0JTBV5ME$?*;M&oQ2Q!jQPq?5w>QTwZc(Dvb)w9E@O`DNVZc&ZVIfX~)6ija z=gVNj+vSgt8J3v4I4^ZxB{DfZ!NKw(&*+*?+F2vItdP`e9u#E>K(z!@@@I?zPjiJL zvE*7>@v&awULOL*2r-JMKbds zLs`sN@7dnNLW4k>-=Hrcd;+81l%AK+_-c-VA|&{09pX7Ko_RAX;Ok|)1kEbgm|<)G z@sdWZ2oRA;+Oal^79|=OO@id5n}q$@cH1sY6XuOIBepIz_MkG9!=*dOp|g;Wp73h> zmAWTvB5NA)tO(@h(<^8RWn>g85pvld{{-lhv0dF=WOZAt*+Rjzwm?q9MVnsutVnHA zKBHWJh%sDH!|MfbPqmZr+Ck$pt>`)Juf3=9caZMBjvUgm;BCEP_t0`=QbPG*o1mWJ zLnObRjHq_4W*x5@o>S97tp(z|Vc=eM*XcEDhc?QIm?#ld)<4&O_z8}`SE;&dBpdUI zL-rfDx|6%pHBA+j=Vk%K+tsAzmw?YEdZP`%BlG15tasMKxOO7;9vDD^?6mH-6b=RuldO?=SFy$ zvvH4=5Z+QIlMSqi+LXrivc^jYDl9`7Udx8FQpkQ8{kQ>41n-hx?lf!- zT|fNweND%8w7Q+rU5B;8q|GC(Bwea|ItN3kD(YLpUe|{cOg7q*N zl|0;=$KT%K{}7-yo=}d<1(4~q6SE!#gAHpny&Xh0W35Q2Tmc2jtn& z-%wjyr;|40FQ}bIVcFNo*nEVRi245vY8%nqc6qJK)>7~;`+*nFiU)RKd@J!WkjIx8 z`Q}!MPef#H98Wc~4cSk^T#Z7B;6nrQ5!!?sic8(N4hbyh!!>^6c-9N7fD(Wz}&{Q`zWaWg+o)3rFLW(X?r>DOQgcN%Ta5uxGEd+rvd)f1D4 zZElh_v>Uhh@RLGlh&~B*v1U%*QP>Kk#b+x(y7gX5&A5pq#LK@fOau~9N)(0HS^Y{# zrx?5IHC+_@^qCG_5kQl7L7T}6rLH{**9@4(LG58*Ulfi)R6tTOON*=iaYP{22*)U) zsVYt0ibCCUOFp9vi6tAYtzx7U6BEi zpVol&aOa&>mak`) z5d92)!QICmMy`&JF{ktBir#)~g(^3|IVnv9FUoD1ZOBol)`nr<%Oi{3x!bRO z*p^2)@#S+mS7wh@&iW+}Th=Drb&v8q9%<+^~IW1 zXs@4_h^USOO~UfCB~v_I+ixmSRajDGh_LeHe$teaF-xg|w#LIDO7&gfCI*$(xg(*u z241H$30_mTez1}^oz9&*~-KU_g0D*T2zAtenW z;r>Yi_^pPC?K*eX1W;sLu1ut(Q-e>;kF#)(U(|zpCPVNsr?PAecUUrF)eIa$94)n1 zLBb@mRAHZ|`1_!YKV(g}%DbZUm5GLqjNOU*2Z!#Azz9Q*pC> zZtT-GI!Va1ivi$Ong%RKPEtPDMLjwi8@zAyJ!9e5SNYFPBmN`bvwzxQxGpZ~uW{ZG zA64DD{-TRb#usQP!|_biA(S5zd`j4o0r&2^;`);tsT#lmv0PpnD~=#BOv~MIB`0PF z9)r!HUCe!HV5t~njJYx~WVlQI3=Y6>CmFK_)3mIB#N~11#I)U5C4&THjJ9{+L$jGB zSR1a_)9TMj8dKk=Pn-V8l1}FSBVDPe5G+TM=iX!&l7$%68^YlHy^FP5IF2a3iB6s2 z6|{SuDgQ}`YUh6LojyrU*b`hwuy};JG}7BR-JQAs5D55mW0FuZq*vt|yRfIWxTR&c z0z){AB;w&NhfrrI32jI~KNs9MW|YVIqGx92_?(;46r3tXJ<=t2n;{|)$U~E-O4H~a zC=?$^Rufne@kH5&qIVSfshR?NM0RXRw`)lS4xz$Hgmg>2bVWJ>VfNGr{s{nt1W9oL zCz&k{T>NC9oWkvW1nyo5qVS<=Or;NT2q8mKZFGi=7`q%LkbUrx-_)e$J=5~RF_DqN zI0daB@k|E}%pe>H-wr1A2`s91KUpyvZ-<;hA!hPW3jpKSQ81}16r842vgbmNCXi1oDwIb%xuhrbZz6|%?yKoLb&JELf4DfsY0Y&PpBty$w4Rpf#0^G&_Bij zq#?1bE7Zit*iO{WDBXLh)RXh=tR6Y21^MN82YPcCa*F86oJkHD-7B%G#^6n#H6q-_6jcAjdRYU?pGztLC&5DvW+M1Gt7&j2l&Dg2*8X^NT`kZ% z>o$_mXEgwQ06BFUw6B^X3<~_v#}U$=+;$#lM4U+M$nC}wv)Yp)R}=p06dFMn3xZO9 z1rSYR`R|{TXI(-KfvKZ<-N2KlJ(Ki{)SlMiso|013Gy+Qmhc zTctTU#{?q4uiT*h)fC%gd`CLa#zrPx9FTP^S_iJvE4VmNeD0SeNiA)}xSDJ8dtbKSMVfP64_PhDTu0KAWK{*;p6E9FLd z=Maa0drNPK*l3|wD7!Zp!;UhEkyHm*Au$E0yfFNADP52^88}(!MuwIT3dfN0M8Ax@ z7gx}e04i67_Inoq#tX9e^yOWIOojbk5o*Y|5H1q3G;;D}g`$PTB9(~rZa0}bicoo- zV&#lX6@Lm4qQs@Eu)i7@qzKDX%~8fXQsf?6>$Fp@<`O`1?1mdrT|4CLh&n(un9GMa zzm)u4wP%Jyu>u*H6U%ECo)pC^4rd#NVi-k#33*U1WE2WX)(ie?9{`l%xdhdDJE<^H zS-CM_ZBz;9Smr?3h^5PFZTvc;x+w2^j?@5ylEX9l<1%d`$`xr!s*a4%^zs=p;FUKg zH54)?QISth(717wc@++);(Y`3$J!~w6J^ACW%Wdf$;8n>erS9RMD;6d(H$D7VX~SC z{RpqhXeYz32!etse>e~Uf6(}-QWGq!)fx4%Dq$W9`q~?EnoIqqmNf?j$!MTHhSRLI z3m#o*wm3T)b|hcSD|_SNVST}s4ISyR-emE2!AEM4r!}Pe0BWBj_R|o`r=x61n0o~S zP)d)|3=|me035Xf)E-qcJckr{lZD4q#-hl=C8!T^#LYZuPaP<}!80auIryP8H$SC|gQJeuU3eKw}h28QGsU85|MkvV95j6o<-?F5ahdqM$R1+8E z(xlr$qibZD@X_&iipZfjnqPe>;ZPb_F1Y}dW&sBlbj1YE)ACn?YxFhDg#$rR z6noy#*drPd3Fzw;n%pvS7>M3Uf>@L>KWKUN z6HZKw=wh`6{V0x;D3z( zJHUi|^3n?Fx8Tp974jVv4ezcP2mlc^1&!uHepEv~0=ioFqBvoI_rZN^W1|LuF>A#HT!@rDjQty}qOFRy&AaFE{XJ47_;w7~XOtq3Oig`?-S`84@Dxuthx~X2;g+1V zhCD_OHueI1Kr%z(*ni)?xQz-%QA?r*?XD$=S_euZhZ&v?NPN5}8R8*fESL)x(Os^h z-8}XzWcvB~G+Ev|RtM_1VcI9EbKF3lIS@>Lh_**y{&KzD6FL9v?mQ`iB4cGC5gwJICuWl7urbgMFhSZYm^r-wWH#4 zW1g^iEHNO@oH85W$+eD#G@I{;_HBrk49$xC}Up{dtsken`-4QZ(~Mo`=NSC20Z0K z$BHwoa4dlAP?du2HemWbkooqqxX&_49ynu#=vO6eyl6X#vfAo5dfug*R3a^|d6noc zmZLRJi4(*wisE(rz2?w4v128WD$xdj!h`B_iQD>V?7CRq`a{*(pRJ?fj?`)@YG^n! zdd0`LivB}H2|g_Pa|NR^7RcpWH;81oFDZW1X%-NywLc1W!XFD;h(Sv>#13%bG-HYC zh0-8`;{y=gG0Gkj{8}PJr>J7s`HOZ&f@mpAGoWPcxB9y#Q5cKQo%K?Wr6d<%$28c{ zYzPaLhST_?0MSHWGlSNhM`&|Ypq$x#6dlxkBh(SURw;d^xFKp!q5I=v`-aDhc%CrQ zHU?)sxa(8LWEZO?pkNCxZjaw(YnAU#P@p4ZFS~7(CU2B_jCw@ka0Eq2xF7x=gd$Wn z9FhtsvTtf%9bV7#Gi8V2u4Uz2K8Vz}V(So0xUEx3OLkFBD&S3=gQ`dR*IOuk?P#Mt z&jLQG_R9bqQXvjcZ&NqmPK4i{oO?kle-rkjhOywk+|-TQv8&mC+2!&X1D#t>A!^cP z_}QVBBlG#wHpk)dffrO_g=HdsnfD>|J@ky&@#K5l$+eefmM;(QA1x#3`+>e`?d7UD zf!`~t$O|{P-d5e^CE3l$g=j+Pz_KKdCC(qKQsP(0Z10{**E9!NLJeQ~-Fgc(JEWQn zKEr%Gse+QbI*=*=)U2w=DRbyH?NtMxZQLD;#;Y;J^KOwDvzXPGP}{hDJTBN!fz35# ziB)co&F+${l487%8v%9C#rq^i&qFQS{?$#CSo5J;y&jI^|8*GP{Onw5Y6x3Y~Hp zjIl`;-u3=T16v%*hAyfeX0%hg2SGb?PSS$O0SMg${!q|Z+EZiHsv3rxLnWNqcugaU z;eXbrVPW+2lg1l534DgxlczPgdP$-jo!;q#n+6%I9!Wy9S_tx}e3|XB0?-2L0d13l zdRZjfSmd;CnnGfcNtd46$VN%J`L0Ek{e86)R*OBWn3oisJo>aQ`sr?8;wtjo4B}%{ z1HBrx>IA#r=%zxF1BMv^okVIISjA+=g7SwPH!7tcYv6bilfJQciX!sZeY<7v3=4A-C?Kg$FR! zPEm{f9 zBhh?!r-=f#dHBh?+#>h04ysdTMIOX2{(>X!6yfesKGl(dYV~o}tu<`Iui1kjQ`a(?>XYhTiq&dK?RZ5VSLqsvg2o$WzoaUVp_yPL8Nl3cOJmLi_%=_9 zen^l^hW=W~^&i-cT7(+7Of69vw^ci|J<8oDB0ckjF>1v1EvX?Nwe$gC#HGO z$9Mu>7X*?aL_!Ru@tciQB8H!M-OAP?h}*5M8~0m3wU2RRcc^T5YU063ds)5 zcwe2n2;C7uzj3OFF=y&fX!4MhVU$n3@mFx?<7UJo&q&IsXIRJ3#3w70DI^~pQ{bq? z6SF*zDuvL2gxm5YouVOyI023CSOW#lCfNxKLp5&yVNvegFu2Es2sV8-BP2D~?M?NM z0%)!MR*dJwO6fMwqHPOxV;KZpUeKxJslFlQluc0uI zPHy|Y}>)+X;g2c@qk2g_GI zn%oU7U6Tz1!L5w9iDh5cUW4fF2In@hHs5KH<}t0+W^90I-$oR_c%%6MQO$b%U{xL6 z)uU#f_vYFyN@h%%#1~11o0*L^Nv57HN?PfFH0PIaoC>_*m)Biu5mS}c71F4SepXG zZN(9GdVIdj=0B6Z*S4JZ^_UVE0?ktyvit0+v&*GT3yX1phKEp{Y6^+H`3Te_Gw~~j z8~(9G;E`ZlaN1L38Aaz?D&K;T^d=N};hT>$rANF!x1ro%UM!6Z#ucO+Hg6Ze)xVEY zT+58?y0UD8+z3?-DRFf1J%SsWbq1?cU|r#1VuG9kPh-lQv|Sx|bf8-_xV4*OLR@^kWvF3g}Tf6f`;&SQI3Ko>7lB*PK{=Y zE+_+o$7RXutv;n*A@rI#dWd;GG_zK+5u}=TqBLP6XK=gB_H<^LBVio%S${ydI>TJ# zEIw<+J%XPKWJWndBVg3yRLo zn@h=f7iTzB%e@@4;L++-6+v#PC}qG$tEtbsko_*ydaKWiE#GFHBI4bwEpK;onx5+D zwE9$ws7tvLBD?DQ^GQBSVfM&Ro4#%_rbKVOJ}Dt|guVrBZB7fbllT8BPAZ^LsZ>;o|ycB3GwJnz3Z%8_??)^l@lKqGEZH~E*z<#Ms zZawI-7OOht#XHR>IOSV+ol8nv-1BDWiTRuBANPnnj)k|%OWdj~0~(i?9ab=ZOE}1w zi+LQ&xN@(>CokPn{TedA*h8IZBe|MHQ!&gQ@p~*_o>$?H@WiJ**{pXxGou|CUYaL*Mm?DC+FFni-e1HLH08-XXtM{N4T4$QYXyT1gC# zTc4-gjglFULG^Avm18WIol2M>_Ni!Ge7L~OvWsHfwd=RNbnH{@j4^hfCQf~%pFZE1 zc~Um0^Fo%JF1%ID<9u*8aLf8$Bf&44Z?>+wC+47bG^gOtyd`)eS7+f6Ug$wLQZ^n5jaXA`pus)n}b{a2n zj6$ao->bGFyU^wdlB?(R-N2WB7brA0c)R}-bb0fVEtZIt`LB1!l(E(Yduts-Pyibgu;Gg# zXHyf)d$S~|7P=)ii)$MOE3=AXhSS9UK8F~|GX$>;^V|M>_dH~o1;K? z!6Id#dOuVh(2n-1X7axbXHRb$c&Z*6TreO+)HAB$;CM3>htY}Yz7azuNl&cmjP-zq zvd-ln!<5XqIfC3&_3X+7WdHy-@Nr`tM7M1XhQ7u7VE~!Iw~=DR(=&+e6b!)TjrNo* zs2R4`Oe1LkkJ2xjG>5RAhOXdNR4-M$^0VDZBnvS zTEsS~9jw@+MD*!+w%N>v{@DiObF;Jyg+6=(G}LYTlUvOz3>6pFfXS(awWVCA1{&($ zl$KYGiQVWMIMQ(t(!nA^)FgW2!(#y0P{V4F?NJ!Xq{44uaJ?{Rq%)l|3Va7!Xc!HS zngj;r>!!j7AVM1BZUv#(?6t9Cs56}>lo_o$fIR|cx({Sjhe4idmHO#`L^xqrYU+6y z^p;+vRe?6uVD;;PAXCmfyF|Ga<%SCEkdrbNOp+ZA77@g*jBEdl26xj-v4p=#0Wx;( z-b5qx>Yopy;dDXsQkdCrDZ(t|@;Fp)=tP0k~CesS-0=#8_4JjUsN zW!KHAQ}_gA49wT;vkoJx8%c!bS9TfYec);_U^PLJg*przDfgi=+NMj3>is@n8L%FY zg&eOkh1Grj15`w>1Ro=B;dxQM#-wPS;Ny@XKM|BMaYDT>`K_ zVdsLej#7FyuY_~NDpKzArv3&R-+WeFVp|&OT6#W~b*ewcBAb-A(|3;4W}Pxt&&vvJ zEIXe|q4+X}=y~<+QkRY|mFyD5eQ$hQJ}2~|{Ac*R`+3Ly%yPX_OUhKi^Nka}Hv{fkWxS0`yd9(@k z;uohf$CMd0qaWaDd3AU=%f7{598_uph%!qjKj%bvPQl!$OZ{nhkR+AAkpcXD5_W zJQ=t3Mbmub1Gn=Nm^PcPNj(f{EL%UTna6Dx%(h&_2HY&3Qcv@SJWfp-iymp%{) z9-fe~Sif$>dmXc`@B?vBu&(4%3@YrpTVb$m#gaI#%ALH5qK4Z6XpX&oR#Isppwi{$+>6$~a;Nh(4Pn)wqpSk|=6NgGIbnLmj@bcsVo6j)d{* z-GXCp-o_qw&9L)^FF$58#F19TV(l(&qP9rXf|F(StJNBp3kO>D_`!d8O{Iq!Zn|o@ zc@;@*RfbvtOGVQ{SHcXL^$lHtrG~(1j<8{8u#&4*Xtj%{7kK$3Oj8i-_rAybE2I1{ zl^myus0HG;Cqc+=#;;7hWZaVH+`6Q2<`^Ce<$PPacqerBHX7rK&zb_>kK2l}$aZY8 zh@Rf6XW5AT;TnwmbmPxfd^W2-|8^qgb!tWajp`doZD5tcv0x0h`h`Ji?~Q zUNf~IbDL&WZCv!ViJp7*=x@Td-H+-W(whJz2ycvP)J;ssF#ey|g-Q>R^gTwL*Bg3p}r#d-FZp!Ykrdkp$ z)=;>gM(E5(Y*jXP>_BcE3-~qtw4RNWxQ7NCKqOBknSHZ9a8moHOZtPeRhQ8#zOb47 zB2%^~Ojgyp=JnBigbqbM^5o6j;%-y=%Sc<(%p{=g|3kuN3iqt}#8 z=)M5Q#~+g(f`I$QO1I8jKfZS>zV=h-)a$cS!Pt`kwNxF;^CI;OnK##Dw@-z?eREKH zhxdJav-U^8&BjOhKUkmYt&?1|ki1p6PUome?l8m{xDn5CSYISHstZ3yH=bP*zwJnz9RQ_in1@*rd_^n@wOtpkHY5d=>`tR2=IpjyCvgpQiC!XCNeycOW zg_xbgOfF;I^IrB{_>Uio08Ii`YoE^wU>hR@@Icm!QsNg2cV65g259_tnkB-lUH`K# z{wKE20tC3pl{U$-!Y)5n(rj(^W@b{(cEW9^vt1U?ee!TG;gn-Wg6o=H|YIns^gI zD_~OLTI19m&3gTIQrGd{_2~o=w-erhBwmYrRw>Dq;aBw@w+BK^h~%GErgEkiFM`wmZ(_@F@YbYl2LbTx#Eu)&=;_b`i0ULTHd}^`Tw?RC`G&!AvDI-x zbRGWV5H_O?6F~iM{{_*{7mo+v-UTJxaSA()Jg;b)WQgeQu}gNi-bk@nGx4}s8r3)&uRTrPPFvLrhgKKl+9i#elUGBO zB2I4nwq;-IeI99f(yoD2irZQa^ChdnHL4W`A8#Eo7N|P&n}h)gQ;$W-&7ef1om@#g z;~Nq{okF;+A${hHTKqeavUW`tgMeJbfE;=)PJLfPc!`U8e_=%uUzX5upJ*dki`8`l zsyd|0!(m7<#B;+VimW2^hWb=zl(e(iKzi8>+EFmmXe zy#MX0o}c_cyMaFhH(b0J7$IcQBAAK*E(euQMrdG_uzf+#-q$s(#(xK^tIKFSmtc}) z2E5zIDJqLxU#y%T{g#z^@Rc!%5QB&DzHT!S$rz=L;P-)o27}CtJ_V?^eEg$yl+aPF zd2}tWC|aXzUt46PM+vWd3dyEm%7(anQ*u+fV0?D^ML%Gx*x>oC@lrO5ap-yG{@|~R z{p(iU#%s|mp7@o6H_jA)F2CKO2y0HowEiaU%Z07ziO5Kd=PC2Gn~V*6)e@}`^Ymra zPu)^Wni!hrl}|YF+@hzRn|0ZGFHM~wp?uFIHvntdndI%QrZ53qlAvS8S5{+IiMU*x zP~oB_C^~Ia7InYBq6DZ03+Y_76#LeN@m>X!$*k$x$RmEgrjfoPbXapsddTv;dB+AE zG?N;8?i_phB?)oBK9y)4_#G=T&Z+&LFCmwxsr$eY3z+dnVF)tNo_)Sovl=@VA@{HXhQZc-hnkh>|@tZ_8(*51B?8= zL3Y}tDgxAQJHeqbR;oy;D;@_PRp+x&2G zE`{#uAXUa@H`DAtzltAB!$(6XCJ~Gihr6Qba(q2 z{kr%kFLbBtYt4mn)G_=%Yg6yX>#Kxn+$<{GXIf7l^CX&FGm4s@>7boPIGXntC|b|< zh*{iZz9-_$Q$CRC%!^5At+3B@r(2e1c$aN|?NH=7?GobqyP|vL4w`G3!rAZZJ*GT# zbavI4O4qGH{XjI!T)a5s~S(j?4On4yXcSljN-8VdO zthGuzGR-Dxs{^snBNot*&N1d5?lnm*{%n&R8GYeZwHhC4Ssr%qYQL4EqOA)kr(tpQC;q zJWB$FenFnx>RbN0^gGaZ7Y+efk^`@4sMQ`X?~iU>MlGF~Qf22J(LXgEv{z8p=?}B#PCGe;gy2 z2BDIZer=iN7#mDq=+h>h{k`HZsQo$Uk901H=oXT$c@(1}lTTNJR{ha%I;9rJh1Q&mB-6?a8)_D8ll>_)kcu8)v+Mp06_+AUdJVG4D+v~`M^f#df{I!{4Lgljw)Z^-*x zh@#5gmdY3`TM{D3%oc4~Wayc#Ri3ex9rHq_9&+7P?aQuLsa+7QSBJ#UMF#{?@b6&; zcXl(avk*s~=@mW3B+Jz;%zS8a;8~D_0U$PX_?JFqGKix5k8~A26#)WCh>*)ammvao~-YE---fHXxxPu>us5apl`;K6{r%GEY?EQSIb=g_dXAd?TKQ8m4r- zI+q$%)SC;3isv*iMNRo-=;J;oo{PLLc%-=7`a|9gLASP3X~V#{Q76dKd63Q|G=J~b zv!AvsH!rz7|3p{cU&t73&{~;Eb4oI0Aol^5^pS&*jmdi=#j12l(@y-xo)}FAn~f#^`@T*S3D0 zY+Rje{5o2@_;Gmt-v>tbSO2DKv;R$F^lanv{^r#GiLRY3wEj)kzHF`hdt>xpZf$94 zdSme)xAwo(Md$uEw>Gvu-LW*)xim>QI{uXwC7`wS@#g;nTC4jPT088^+-t@DT^Ice ztr2pfQ$vma6h;3+Yoq_5wU2+JwN?UJBNRnDKQ?u=)_-hk{CBbTzNUWgKZ>>b8Uj}< z{1;cNZu*y4D=jIEecSM|jKI~*|Ke)@)2glf9THtgyg3)IT=ORFf3a#gSy`_$GSUeN z(WIoLgv7*vf|`Gn8iB6)=T}50X87d2b$?w($cd)D`nx3>75y)$HuC)XoIh#XJ#jQ) zu~IlD_~lFg@aTVvqE7;z`#t%)DEgOGdrYuu9$vop-5=ggE;5PD)x%`o3{AWKJVDGK z_n*1i-TMz5o!$S*iQ3$DwzPFJuy-xj{dckUPf^sw;GhPshVwQGa?DKJAwfV9{ZeTfR{VDN3HAb=T zy>=EA;-}RfDu?|Cx+bKRD@LM_rS}hA8=)6~TFQhyuZuzp9xzqe%#*5d5a`-pjnU3Z z)1y?o#tf>Z(#QK%%YQdUU-)vUJ>*_~nz(s{74;>q7t(7KwyX4?;lJ}6SY`3S#g}xz zvA2p*A%`YYcTWztp;}6&PVW24rIk<=236@bG9o-99m!J!`X29n z4|^gz$&M@$3crmEr1rBH?I=xJR{h;0uo_NpVPzT!%+kc^E)dRo;zST<+CbLZXZl#6 zre%%_7`yL!iiqNa$#5Z;SBPVc8x5|b{1_SCHsZBcOKwMjY6NjOQggES zXJm4PG#tcDf>4am@Vku^ccdSehDnq;oL#4=^lOHesFgl9=w<1whQ;nQ1O%r6@m1vpclbv@$EIHd5xo zYWRM#u^e!q8!D{Kif|#XmxED+Ce=6U;$kSuWOk6zUc!6T-HbA8syAJDcU2eJ3n-9Z zs81bC%^_y%y50euL-oKL?xXLPP9iEa22Z~3>1BD*?<0RQ>>hle*ODK6N5=P)ww1Wj zcCb$BcXJZEn=Fu;fmk6D+9rgkc&L3K!b_`0xl4A~O;5QiUcl_OeOO9%Lm8D$y)TQ) z_IAS{-io-{;i?2Uth|s+bo38;WMVWd6BcpV`E2eQEobVogtX4h;e!(g|oP(rL?SzC`?YHR#m^a+f%e6+l+q{QmI5U z74VJv&ZD*=d`!Z1zM>RZUyJu};&qqHTCPsw5Cc>$P%_(O@e430!Mffq>xo)pg<-)` zZp6X#m_+>oYL4XTFI1Uz2Y776s+n*X#8P84wwM2{O34;ODRZhd1I|ayf?!;*s`|#n zDx;4y1;hSSXAo1`eMM7G4R8MN56Jt6gufVzLdn7Wy#hXEz2A@TK3D69M2+z;Es7d- zD^-pU4Z@nN{X{+A)v?(SJJJLQc1CVj>#(;3gE`cAZyYHcg+MFj=DGi&Yg8fZ$mWQ@ z=^BJ;^vQ*v5cDs)R=}J?QTvhpFS=$nL2>u5#^|V8W;JE@G%VH}x`+AyL1XkJF_)@P zP+NDvB;zEh#Gp{vvVXvWQ;M2M_>OVyOuR1W2vPHh&v?3na*F}P+7#Y*Cc&*B)9b~M zVbxO;t~Qt)V%G$FT>0ZXygLODJ0rf+dCg&4@8Gp3 zK!wwqmQdw)Y)lhm3M#PcANT}{;<&F@S%Oh8O0V-{RMdBjA93(l~_|y!3IJ8*9?t#l>xg6yU?N_B}MV|8F8GdI2 z{jN$krrM^?fk)g6?tMzMXukEQU5{z{_mCC(+WoS7FW1u}G|6ZUDugV#Q#im;G52v? zdAg8=yIId(Q&N{a=0m*6@=~KEoaAT=TCMfnL}?3YyjBLAAR!ZVtbI7e|3TS(MK$%W z3%?H}q>#c4O}e2YH58?)3B4CVr6>lZ3MeQ_RY_=}8k*9Sj#LR%nivoSq!zTBgiBJC|1O4vAP!n;YTv1M1`JY3@mcuq?SX*WQ&b@uo|o72_5)V9R=%Z}|V z1s{ad_b|TalE{e?UlbM=ySj)Py+{dH7mwR_QP7a0k>{0#@!LxpLP4$lhEWF^f7zw{ z4_au~g3saBRN?OBzFcfYehTv!sag*V9(*(O6Ww*Mr%uXLTKqP;c{tQ#V6FNl2=ZQY zZD`f9T1PPk{*9|5_`~UI6=MP0Es|f2d!@CoUgSVmE~$}x4Z8w_gG>mn$IZ%#pX*8F zo-TH)+CZbPVg(J=PCPT=tl;bUId*JCz&p4%0U-wSY}Y&bWmX`Okzzk|qBx(GB|yQ; zCG$G<*O+vQp7tgA0@%`>$j{p_shc zsEhWYn=z4xIRs!*BW$@9@AP|~?{)J__2I4Lu-^+fj+TF=Yrhv|4y^v2uKixZ-)kB4 zd{U}8NdBL6?e`}FM=LYda<@?M&x)~C>*#~w-BNAgs2F_ro5z;lDxCg&KBlIt(2)F% zAWKACg=-((BLM2*0Q6#S(ZmrVI|&}i$0Ztrk8p`M$UM336Bu)7j0SbYS|S=r5d7>$ zsw?Ql#^dEsx#s~%FSY+}u@(ppfvn<5+>z2TH9eT!m|N|h?w-(;_BPP9co%~H1_Re4 zc4ZFAP+i>cg~co#QAr%Pt=@@Ph1fAtJjvm#0$Y19L3aG1csMV(4>CGj+mw23#kIA5 zQ?lFeQi5$}hv*9sRQ$?ZXvQWPTW@51uwD`q#z=f@n}4zQ_#M&TOGr14&wD-U>92pM zX?)z#V~NJo@5VdQ{z!d1f|`GNo5%J}6pQmAUkO-)ZZPi*K8{d?>yI4 zI-KDjf)qvFe0SS`1qEk8;rNbPZ9=$QA{rxfz&0>2r#q7%6x}Gy-NZS17CF!xfsp|= zq{*6IfB_)hyoq^O0AtQ#wwZ_R4B!vqo~6NfWk~vxz(X-_!!w~MQB*OBN6ZW8^bhJO zq%06&4Wi=9Z*5)3$l!e2`s)B%7gH_8rMYkitr0%>E|Lo#)yTlKkYHvjUcuI|dM1bZ zdF0`g^%Na;2uf~jhT{)TU^?c|L!;=rB@uqUI|w4`&w0xEk!VQ3?e0PfznJsiw`k!r zF{zxfN1K3?27oah2s4b;rbc#uirhF45cg2rhs~EYl8MLF;W(slK;R)E3cnn-CHzqA z%GZLsC@d-w6myLj0U-u=6;e`4v{tXn|IC+LDVAe-3M}@V{OS(WdBy59hc`7RGy+jo zJK#1t<_}2fH(2tkf8v|7wp`cQ-^$!6CGaIM$Y4=gmTSb&EGEa=KZN4iS;DP%Bl&4& z0cjKXR{;ewWP~ zD3JsP4`{e)dtjx(6N61giiUzyB5wvK=xC%g+au#LAP1Yc5o_TQ(mhfBvtI5ZJq3^i zLK?gvj%PHLEPdO!kfK<4Pdp7*+UzRx0-YhlWn-A2MNNi~(;?WXxM*l24aT|!{%I}T zsgc-dooE|EhIhgt4!{c#yZ7k5?#;X2t`X6k@M%)CMi$Q73+5XPc+Ddn?{hvQ9=W88 z5mtdw^4Sk&5flcLb&G{^xK*5nsXPV_&9oQH$9z0ww(yu`YhhIaM_e=YhsMQJO+H5l z;6mK7F&W?yAD^JQS82JBxx8$Z+$&=7{GtTPDksIC zcb|zSc=JTZ<&GLFvzm%R;<>^Iu!Rv{ST;VPF3VE6fQwz}k2(!2E6T%;9iGMfq!*|c zAOuW#n$&5%4ysp~sj31;rC$~17eN$SGV@gnSw$nbD~c>?*$qRBjjt5Dk~1Nl#WQ-S z-1j1y6@a=X*CPUFg*~$7y#|{yat_C_J&Wck=WOrtxBmqFqk*!?RyW0^Nlo%DbRupt zeO+9RB)>qIQIQ7`a5qyx`&>W>OQ=O>CM&jRCM_3K!J|zN;XF_-F(_b1{XCA~OPQMW zD6d)RJHuuJJdTya<+?7 z>jNE;mnT?L1hbh({b{(vY_i%;QsfGEp#bqJj@Hd6>lck*%!dck${QPny%`vpI-z=N z*z37#{GAnSL=ScwseyMOtUqg?W*>RrQfaeb*`9aCBAEM$TuAEbjC5p8y8YGB* z1ehCi_%L3GkQ*jdn9s!>1QQ({P(HGJ$y$JJ7BFvWE_1@2jrfGk8n%$dkwr>JPuyo4 zL8ooYcUN%XNr-YhdYoCuN<_b*v4@dZSw9%<9{|Fy&tS@S%0(oKS#1g<3n=?5<>1;V zFN11Da_t>QfQ`WFi=+PZM|^R-B=SaByG4%GMsk*y3l4(TGV8{0z_>Nw;)E=ZI8-O= zL%GF#LbyqL`Mi+gzv>lG8^tpPqP?x0%?wGN1OS&7Ibej`VkYQ>0GE_&qvZf)u5$S; zHhDAj7hx5AK<}{ zTLC#);QR+#ShH1U9Op>_QbDkVgNPm@At0m{s$01VOT|&QvR-0ENSzG%a>cWE*s{Y5 zX)Fuc#+S_>xkY*w_d!nfY@Of1ijcA>oVM1+rHmFQwBL|G4l;u{3up?p^zrk0>ib6q z&14%l5fu2@A#2QPs!XB_?6x-c4br`(j({4;hLEAJan)fF$UlJl$}V!s5%@{0c~)_u zsaSe}hE~Et2L(I_D4tJr3+gn zwQAd-hCk~*Lh@n5^nx}a=jFTjS?a-z9$$#yW+mXsav$n~kRc{TTI)5Gv@3tnZ(+6_ ztA(*@(*pzRxDMR8-hHZ93w%kg($DE-f425gfQZK9dcDU4<>1_2{^*`kqbS)U-sXC- z)=0m0&aqAQSd`HN{88^s8RH9pXQ#Ik%L`pdzg_^Ppi;lix?kR=g(`0m^`MNnOTX+A zLB=!em669;(a>{176`pgiwd*8E9Z|~wdR;*4C*PfmnHTnxFD*(7!H#LOju%y!Vlkj z>L>alpa351kFLnZGz0LP{=6+%^cP%p{U!&rm0QN1eaWX^n22W49;|MlZ}{q2elGng zBuT-#%g^3t=I0#b!!?7^9#^>AeV8&V&}?7BK~SZs=yQEYabG2mZMHq~@)7Yufwfr# z+ku!S{Dpw?o5#pFAVLnwv2z$3!!_Tdge|y33CQ^`oQqXVA8vRI7VZy>+dSk>j2k?$ z7HY!-Du)0~m#=CWp@ zYyW{=^Piy=KLBrL-}wZ>${tRZ4{$A2D%PWjP3gm=dXoMEN%|9a<{~JiIw%4%; z_rh_sGQ!cD$b|^_4F>xjzSN?CHEIf&$Va`x0UrS58~$~b+}nJ9>WeIpqf;qojLbl7VPy9FmiIb(R#WTm}NaR`_2M* zF)&spQ5>11Prl7FXYqmhEH6SAc$=Vg4kz*G|LbNn=B?+ zFeHWjR}#>$IseCE8hmO&O=Q-M29~579xFd8Z*H6{^nw43NX$C0i9BgWRg!wfsecY6 z9+9F7YHqZK?>vlb*?em}hfsKOn37JbI4?M3kZCvsjS2VgU$`07d}pz~knmpaa%Urr z;9_yKB;c)SB#bpmNiMV?p4s%^3T!tKVA43^Hla~}p{zvKPX`1H)f!eu=lE33DeDZx zO9L|Y$lM`dl(BShauOUc{lY_0b!%&^e@AKPIO1VV?i7 zU?%?*L1^y`tSftwdqfy~xs8?l=)vs?Rx+f6j+q)nL=AAIJp#(7fUJ#=h3HW*OMQ($ zGzEtM6A_Kph;+uf`(M`S+qdME*9ySH#(wJ%<@K?lRU~m3pn=`2p-I-rR05)CW1Tes z>P`daLi((`Gm$ggB`E9)Mk{P<Tv|`nM#FKvk_R-f$1MD(A|Ut??ncwl#!p`}dTogvc>?t2uab^_omvOX@9qfRg@QgBfBd7ry;gi2d()+u^+7Ul z^Xo@BD*)fdB0deMSplgygx2YA*4*$N7TKVP-grnnJ;@kV1N1SL`k8wW(b1HzfGFv^ zb>4S(+JZ%c3_;aTix|PCWN_-9VZc4?Nj$sJJ)q?DbYH|iYs&7i6focGudLW#X2lw( zBBkOZ=vpJumB|L8myESRzc&vor$5lq1B|7fYwI=sv+`T4?l{1z=6mLAeJ{$eIx)?u z%)nvYm;(G}6P0_9&3wcG*1pxL;|wO0{F7qYhdY?6~&cGHUFKgBWg8iWt)cZ`C{+lcSm@)NxS(3UU6{Ab5G?T(G_ ze~^JWbw#U=mX}m>bykZb<&=dSt`FL#DO?)%f~XR?%4ZLkLpGedm}gk-FqyCBdnqz? zu>HMInEZjT-#+}hUi&SY@60nE&R?OQk`Ikhu57wm5^1HSsFJ_>#84{inYUSH2)vp1 z?83CWh;n=1uf6`OgQ-S&9VJl8V|}x<4$pqjxbKbJ6z+^v(zib+&$uLTQ)0Gi2vz3F z_|AK3;;)}ATb2*2s0fV?CvtMzStmyd*&_KU!(Dj&tO#*07}iRSNu-#Uzph)uh=C2h zsj10egWhs_81M(l_qTI|94FGL@q%qQ00@0sc5Qq3g2s(+0!aFVbXG}VaA zFFR=7QB~1Yj+7tKXA4w2Qw72%0Yvp3WT7f4t-+QOzPoDy_;{gacdiXJQZa;!ZP|0T1fG~of@6p7kuE!> z<@8dYUx_)KU-$Z>1&XTyM zST33E1>awKmF^jHY&t7Q*ibF?hp7^b-KTS7IZ3Cs2ls*DUTIhGz+;l0n`2w(Hgj;n z-FBw*_~_zrgGNWFPEOnRbiR>@*_P9~h{DB0WTz$7ut^o#`0*)Me5Xlmj<^$1b-Ob9 zc?(iNQODyzQIT{8@!IwaB~Ye~kzZ2rW8LdiT;hcr*dKnE27B#tae#mlO}0bavn|(Z zR0gGgUHyTd!&@J+%b;s^Wi*(HOsq{UGroJVDk1DaQnv^BLBMwkzWEuWGq5H)Xg)9Y zkvZj=TB)WRtFd!PnQTDRhZUBZ=!ai>$8y(K9}2lrKO)M=!6{Mcveak$}-XQ8RIi5@Ers)uiTrknbxxWMa zsA(?4vEh4qRM0xrDiLk|3f9vnQOnD)pXWecSD~@#dPs~2@QmB?#ywQBlC5Bis*5eu zUElDS!%?-nY$T7xVU3UfGT#4U%%xW6l_VWX77u(!#ZnS2V=s(}@Wg4VVkNj8^zY@! zY&9F4+m`D(9BLVcnCz-0;;66OWDJfK8op(h7}V7JFpbE3A7 zrmR=0eMy7NeTzV}rMPwx%7X`V_2! z8^@Ki-<;}AE_c3=^j1WsjUSbKAJ^w)3DVY#WD&-1EUACb_9jl+rdz>u z<`viTKh?4xZT!I2szqjFhNwofqe=#m(imJ_-=~}~=U7@1yTm|dnMtt^HMUxrzcZeQ zXPx}EX+QOIB8bQPjq>>V1udDcw|WCb?^AA_pEad~itn6##Y(d-$od({6rCn6|P-u-fQ8d9QE*NL;jIcGYqRUFh-pBSmLlqlpvC@8)wG@t9hV4NN}~8XyowUV+TRU5<6@eCvPj%`Fh1Ctrn_^2;=7vd0OuB8J(n)c z_O=E1W@8e^EAS4amcNwC3*&!r3#8F4S{hHkCBkn7P4s^xV?^_?YaNXgL4wjj-0mPG z$j>XX$e`bgvP&GhcKxctoy64@1PH_uJc*}2eqigAI@TDx((-xf;HPosI@9yFxsBKpFL?Xa<7}Lc1f83Hyc#1{I{Grc zGLn=Y$tMXvy^bd`suk5u#D-Qj9)ei$=vz<21X!BAQx3?pN*dZ><~Gr?9o1qW8M|Tu z^yBiDz*(g)c7;#bUq6)$zfODj&(FW`O!qoZrPO3R*Uzrtv*yhKl)&F=>cRYp z+G_qsyzeXb!hpQp_JyO;sN(~a4hNX`RzYXE1Q@c{Q)^@*nWX#vU5_L$n3vyOC_l+ZI`7XEWg_|V@9Wh z+?vSp%ZR<5Q;r)Fedd;~$Qk9Z{Ev3vhPC|eW`lztir&v~gMDqfjD-`9`4>d*TfZ>E zTnV|}O2^>`-}8$M?ww+DtvkYhhZz4gl?2h_d&j0CeEo*)Ubf^$Nc?#7pJKRYpxd`W zb^o6knaVRqeYP9zjh5zWE*VbnQ6w%sKRR4tmZs4|f{4FH5vmY4oTR@feTchl6{ULZ{<@0VWf7Qrx*(8sO{uhWMYSG{s% z^d{n7IZ~T6%c;39;Qk10e{8jM?tmlRSV{se9VJqnn3!P)?}m$C+cR4-gO`s{U#d}G z>6uf42O1iv9$x0R>=N|L*wjds40-rSIv@7;qc7srbydvkFJ=_$zSMktL@e z-O_|#u%-s!JCZa84hBFbm93`Ha7(hu^EXv&^J_zW_QR1Ri^yP$RO%2Vb0~>!F{K8d zHiyqtu}!-f#+MBS>=+Gzm#*o6myM<@n>Vs>{N9i+-D8Li1 z*{H%*cwzhFqCxltK(VYUn${d+ksp1_zn|ju{1Uv%*AD3b&t*5LoHM7+H?;l`I%*lr zfTt&2Ha9#_ltgHf%%a{$Z3&q+*wtRo98SQEQZ^wx3(x>js+CvYH5pV;@W2x>3r0Kt zoA6%!b@+(99hs#d&2G&2B$Ysd`jMdc48Gd*F^hHKn~P&sJwjG&<2JViFUT66F*q9* zLbtUTKR15-eDruaf?;2BmYhXA^-Ja0&sKWoXvSu|<4xXkLv(NtySV{EnC=17FF9F$xJQ#QUU=4Vm)=!!)A0ZwX(IE!r8ZJ4 zd=i}~o$)6}xP4MU$nmC0)f0uzP?JgP0*fFN?D9z}FV_cjyF(Z;@lC&JBE7O{n(;Q< z(aHPGmE+WK3%D|J(&R#GdZUrb$jFKW70)`BfHP@}etz!vq;N|cVbduRWFL)J>{Vcl zLfGk`8%`g$xDaVS#k{Qxj-OIi9=YUoy3TewzRUr$ICZfgdM-cGi)M3h zN#mpz6K3^Z`*8S@SDxD>Vod)h+m-_?=p=AonMxm8?D<- zjb}D^K4$vkO}#FL%{e~ixo~bkc$Ou4>#Rly;$x|c)857U>9vQgjUSH>2pj7QF{UpG zrJWj`&V7j{3FUO|e0wl>l5|WQjJQ4my+3=%W+AR-PmZ@#RP!;3R3nh=IPtDD*>oKx96W!JQd;POW=_m;+db@pAq{jm~ebn_HVgd)6oN{ z)Ixce6W($G>?~p;bAe7=IMHz|_{_VTHf+~2VL>=%hVcW#;)R4zA$gIsKY?)(B9`l5A5+0sZ| z*4A)>3=BBg;Ybh#-I`KtlC78ha5JSpfduU~pc?XD9`9Mo*_M0DAB$?FYMxtiqoAq& zF5V+UvoBKLII)dTz%|ydJq+b~(%5Z%vteK09>X)P9cAlDmj@?~5SEv1WLY#WU!E_R zzjeRltr(R{B+n$~63S2xL@ncZC8Wo4%GrNuOIoomo}Jv3?KeG>80mU4YlSQ@8^%o{XnaCYm0c^>^-P z_>_P5A_Ei|(1t0iugcpm(@$2;n|(G9^_|{0nvqN?EYI zb{eRUMfLDBr;l8rhe)wymGqAk3Id;saIx+{96i{gGe65q1cb4`?rXxO&LUpeO(o;7 zx1{bJA+Xu!Uzasv!+ggY;@L=>9WD{RoZOr8yQ3L|p#w*2i)i{91vGtK6n^XrhhW4F zeA%|<Mx@y6YO~N|))ydonw!R#dge)QAlZ7VAK8=5?)_ZF_rYstnW> z7vsVQbpc{FkWkWWpylaktAjw22AeJJ+ZpwnIl=yR90?b1cXd9>nv&_GKO7@J}MScW42k{#{C7wa=?o}o;IABVqJfb%}478r6kf`N^P_#)Q|~!x9AR9y;;y5A7d~ZailCL{OV63 z$LIp-{Q^(Hd=T^{7JlsUjvU8+{hJ#T_77cGA|2i!kHiM>dxlsme9rl~cY_GldcUkT zRXfiV0y=L!10o)ClwkZ|R8OQz{Qig{yv5`f*z?zOhdTKYntaw;7XNa4kYs~$G`Yhbb*{H6Ty-49w|{H6nS)90mU#qP|`qk|uy8ntGJ z&m))fDgtfhYGg8A9=Q`)Civ-Y&dd+A1k}I5_{hLxXVK2Td82=4a7Ep{>|UaOK0k(w zYy1(Cz5D%=z}D;Hy-(=PYo+VKtc zTVgL01=O#938uX#7>XGEce+;RYcc{if1u(yTIFpk)#rHiDlfM~CEx3R8Kb*0qs68V zRHj#MlqHv*`L{88n67R7KDIkXaB=EQRq*+KXpDN_t*(@O!li#!g#7kQ*P9K-lPmu+ zMrRqQ;|Jrdwq`cf7RaUhYCNgZbaD!t?GxXhD$9c>0t}q``X%znFRp$b_x;Bht+4sE z-$(=h(d~aG!?y}DQ4&=>PDi3$fz~a)UH#OJpDg{ufCIWd5f@8N?*fnru{g#CR z;`PKE`U-)Jo0-~@Hx164ZSw?+#_(Tx&nYyGk{Fhj8abP7+KGb9#vH3?7E3VHe90N7 z@Jd5G>G)Od%W>dmUgGyo?(Z#lDRll2PcabaFN~A5fX<{?X#HFaA0TQm=HTQ zeIn~1<6`JfNq5aG3HOVn>=3E!%SoA+v;A6sN}V|s5W<=4e`t(8a`*Y7|s#Rzd)Z2NwP@r-6iRqiyE)3{^ zCHJNwCd@gGHtM#RJ;FR`yuTxmN{T_neNS(xfv)CqVh z;eMbJz#TXXK59rqxGslXtwacU%q6qF(vSEBc9{kR^Z#L!6!?gY-}9YE?{?Dd{#5p8 zeK9KXfk(%lm>_YOEa_(J7)yQpbg9;vzd`y(hP8@7?(=jsu50zOLpLN6~T9A7$vK z+0#Ys^d%(Lj`W+HFrXrTk`y|gCQF^5QX5I)`rGvc)6{L;eI4p|RxAcOdB{GKe+_-R zLd2M>xbf`FLb%P!2OM)paY+z&V#5~kyIQKK%9Nx^m?j@3a3M3-ymwMe%+M|MOctl6 zsNodW;)>;HHdn}^zK2bMnSXtbfcLUtw}Yi|sH)g=7x5QDqlsQk*B_?%dK&Zv=*5Op z?tG*^J_&A3eTHbr2Sg?GP>6>Spnro(dH1K@o8$~pXZ4$pQgSoGS?UXbCt3>J91d1EUqriEX~i)fB4^F%G>`1 zDlJV7%ul`fx2ZHaGV}iR^!wNUA5&@k-C>*3_1|sE|2CE8M%(^Fo5F10di8L2sA*!j z^{`4=dE)ner2AjE(!bi2e}yTdgRQ+Ium4L^V)XYsd)fWG=U-t;M@#oJ`txT`8Hbco zdsENTCr^i%hmKN3cYk?DXKs7aRaRN? zxZ+S#s(E@?sNAbh_11f z-34w4NBDnLDQcnxrPf8J|5Pbw?=M0& zvOP9e$7|5_8~bkPs)_o4K&70wm=6uLaEc1m^GM^<;GKU!C8cg>$U8~Y>c)qj*riiF zaygsh8szbcC!9axE-Gt+KiU0t8-D!46}+JN`-J}@p$2;Vnt8i@!DaHyGJ8+G1O4NN z<{N9v8u6}W(eWaWRPB8MJA-s2^y@`>E;jZ8tipSxWp*w)QxqEHH9V^}rd`8zu-MSn z{&Q#f5|;ZUt-*9NkMro@{x|hkP841dUA~a~vInyzggl$i66r@n;ZkL|OP6`Z%mTsg zu~>PSLE2l*2yFW68>oH{TDVZHDlJ;B+!Kh?BOe|kBb!#{6VAk`0|~5%)Yk-Ak@P9) zUucMx?z_&%V@a$bGPE#gR>O!+T`_|e#mckSAIQJ{zKC#IrFhZmQI8GtK0fBya;8@8 zkN&%03<@OyBjYT z(F_IBouFAEG#&$4x8gH7Vs3eapcA{V3Sn_D4`K~^aYg^WK-8+V;qrkDkd0CPG)guy ztyp`~enMhRT1KVeBJmz}afnz6*iB38ij9BqkPbokk&>R3SDed3^?B&`U;?X%{g|;? z!sAo=tA;9vplHpPCc)*1r&TKQ#Lgye#XPo?PPB9|@x>A0L}l)wN_8l^qS=o-b-pcf z(NWf|a;5m5py<#atQb*-H@)?YoM^R^<)nYNWz^$Q3uB^S2{ z$9xlPPH}EmzOf$x`7tBd%TFG%!YQHBFStVn>j{Ai+DskD(t+@|j}b)~$D8n;+((GT zKP#EdtURiFdY3qQG`ufY|1v3KHF#p(CF^48_>9vffT=jLm!)9vg6+xv=QhVvvXCl{hZ5K3c>2u+nx2j<%qE z&~}&$Rla(v0}yu@e*F9A%FZ{NVRw@nn{%7Nsye!nzB$r{1>rB$HGwsWKDi#!gmmag zV~pB0FXI~~6@037f0gyQWm|2|{k{cYSLJW>4dz4t52z#r|DpR2s6>l=v)N;xee1tK zrK&d~D9^(xWrIEF#9#p?h${Gt=`B1O+*5fFY}_p-uthaCFXVjC*Da;B6=$7T$o<&3 zN7ivG-hQx<_i0~`V(3-^301_`Yy46rdn?h)yhz|(-^&xNTS@+jMM9s9d$lIFl7k0} zM1J)3p4#8K7lA6q!A$ye1-5Ba^J1|h{e6a7+bOifVhL%JepAQo)Xc$RDfRw-%h3N= zrL=Bm&~xp-x*p@Y)#opLMa!fRs-og(*yEL#Sz<}}1pIJuis|_&@4`(s%+^*0@GD4T#GlW;*zoO!gK7@?d9+v&6jeqK20i$7tK1 zse}`MzX+;9(vqEYcDM{Tqy1(L;V;d1NRYVU_Lx0@L6_I!URp5g|Az1uMqcd|haWer zt;!|naX+(%tz%S%Be@5-m-=GAy|n{IK?+BwJB5@qvBPA2m_;QgOnWS?HR+UoW|QFO zIy<$~*Sht1^X;S6mKzmrY$}N6a#1_olsSrSN^{?sW0!_%1N%{~_q`nNJNK)+XMM6o z_}JVdYH3RIoH<*me6mjyL7AYaWr%)LgXg>@ijH7iqlj%&dUVfok0m6?@cuQ!c~=PS zz|SZse)^*Ryn~TLNFg2CIjF`S1mt^<)dO40AGq(IC4&^6qC%#g-I{cy(!|S#E#Q7l z5Un(!uN2N>B26exNBs_6HP|cb3iGYF5W){!LrOIPJvtss?>D=F>$Q(@SNU+UxC52~ z4TcpmKbz_UxAKqaR-LO!S$ZM3?MGEgeq6fn`IhJ{=A-d_>P7g)Wv&n(&nV6PxR0_( z@ei^_ZsspPTJ0S<9KfRM2K$gWAD~1rW{_KC1DZc#zL)T_k|_Hdxc0;}a31Ipy*1VA z=kodVm26}f&!{C?2id1+>-!T`c!BJjP&ILKi&&ZntU6b|^jw-In!6tF4gGY$)u}91 zCnPpw#W!&lOmqla>T^qpFvcx0rwEfR6Xd}AI6Bx*ceYd_KOoVR_2-%P zCFfc4r=snv7}15`Qm2_5ry2IvfB^Y(GP;6+^1G4m#61B4%*HQA+)^=!a*Ha-ttJzh@!N zRN3zAaV4&(@+0OFSa^bQJC}_!PGgbS3{}w^Ad6G_#Xe+UmusG;s+-_Li{*9Wi92_n zbba!Rr@GtB+0w|zjk?Kg0{xiLJsXG13A8Lz2_I*NSox_7w6JT3@xwtt(~I*@^fKyy zFIDJq-SlDK$<9;4jIb>0U$}Y*D*fjw<saEat zX|dmXw4KGT1%nM}n}}DZ|I&ygRxYvEuv5EpTzBAq1S$Do&MsWk@n#)I3M2Nkju_8N zjTn_|EY?F}f$t@$M|{sZ^uAsM${_gG^P-oK(}Y8ZDgU-vx=Z5p50RnH$L_~Vt^RyQ zx{Y$FvU2^U#b1_Rka!i_cc7B}96bK;QB?W8k{J%lA7^D2po(C)cVrahjuZcJ4+J@y zNe2t-JjZDPkklUt8iT!h_BN7?x(7h+-nbLCB|Z;aV--E`6rv%a(tP%t(}FFxRzB_)AuHdV-cKeHu;g=0Ys@A zip2y#>Yzy>PZGE=A}dUcNvs2QUdH5aa!3#^t=!kl!@)mnqeBS5sLCPLhq&%_PRbQ_ z+7(0lE~Y&T+cLTvwgMw%a^K~n_A+3c;xU~mNBdLFq%LD>2**nL>rTuw8my%GN(c$2scbewfVVWnui9Zm=Fzc)3oACULCwG` zCVLEldX|OCMn-Lj#jw>PKf0>Sr-*)}5%LVs-y{z2pvv+|$!2CIU8i#lsRFNw=AKls z)xzXex8qk+;NTd+k|6f&$G~7dr6ZG93xpUvQ=kN)}N_ilbpZJuN1C123 z_rNgxGK2{0r(EBGLI`R}kS(Ddu=$%!IRO(3sS&fK0`MIs`zt!o&tShxOYq%-2g?8h zKv1h#Ouoy}bdV!A$wz(H!oz*f2OE?A$fe5$&5CMIac4 z9VR#%huBB3slelDeDXJvugqiWCQPSmX+A9Q-@(8u2KybtBm8yt9Z!_ZD_(s9glZ35 zQ05Hc%%iJtj?MD!Z;LN&Ug5HF@4y``c1dpwyvEiPuq;tC^%+suJbAE)gT&GCh-1*p6u8u41drB>WMfeMo?cDg`i9ed^Z0CqN)$|^8??lJ0K zoJjRP0Vm5Pt{mXw#WqUd_<}?7;sIV9@{2XcNBmh~Wy@MZjt3jZdq?u6E$DI`W@*$3gQ{2I^hu}~@=ulZ@OOuz^Gw1H#u(@R}`gmv) z&gX`Lq*Qoxf^~o*i!F9NJ`RGH=j9U|#~3jW^Ep&E5rlk>?<1f&!bw4_g@@zikN6b- zer|1gDl0KdAgUZpMk#~}x~?D>{Bds&jvalKVb-GW=-YzD3;@it=(S##sGtf#)dBvI z1|*f1w+Ir|dLvjzf;|_d09*BJF6H$%u)cdzM*{v)nSAX*^!x@rs2}?ac;F`Y#-{np zIb{D{94i(b%fitUK`QXCQ&DEo!?8Ky*zkv7lC|+7;pEL*-0%VRqs8FLeZ;_KwTfU4 z`^X&#OOy;a0H&N2>XZgoE)Y1wuCM)Yfq~46U^}3}qqWfoAXuDF%vm1m&&rm+5L|+E zSW^Ugf{uoypquE3%Ljy3ays0;$1gX9qhF1CaUW6hiwKni2AP%hW0d`t`I2$^QuilOwS2Guz{|!~JhyPsF92J9jD}rQ?_~q>27)auYG-1n{?` z-_v1YAW(_ZjcfVg13F$42vA`3y3;F!w#l7E6izB3Ulje^a%tKLpFdtfdET91eI{C=Fz~dUx=k0 z?$jKq2VB-LT^KXiOn46Tyb3#+kM6GOxfR9lTZFkG&mFsuDBjn-1Kb%JJn~ux0C3`O zRZg3fz2Kkkl!Q9rPsTh|^4fc^>!2+;UZj(|sO!gNdC-=y*mg;>XVpaou>xd45Qbnvd3f zhMkB&V+hR9sORunq?RXOUX4xo*`e7DoBIR{t9_@n2!2oMk*!5sI%!n9h0xSRFH0$= zzT&i(nJ{eV3MEdQ*abONb54NzZ*?Q2SfzQ-9X~NLX!}eLDg4~bh3cKFe}mblP%sg7 z(I}Dz*FbTnwhU@FbPVF!yhLN77*Eg6Rl!S0;1THhTaF&wK;8j~wH@Fbi>R@fV?Xoz zopcJC+j{EiqC`h2_r3luE$)#4Mh;1N#Jd)GIu$lfdtXSxboyha6$Y39XCa)UeB#6O z>^mjm*jW1DMTf(G5fw7wJbOdDmZ@*pSYpTUv#fLN7k60JH=Xr6XBFq3

n7Qw{G!#dWz42ePA?AKkXHo;_=>JQR>Gitk@h8mzH9jY7PGq zwO@e%)gX5Yw?(tB-uay$?pom?rxWj33Y$q3xnDcKeJ^o?_QU|Hmpa+M{#pGhD{j48 z5=kXo2ynrqwok-mFDYJ93di-QLdQucT3%9dqujq3YYj}En6j==OmT8x#sV6+)B;Bs z%#5Vd%&(A{f0fp=jg+2gU!L^p;S^%Cu(ZGLMbT~>YEh|j;qY-QONz^B*0avnFM4ez&%6nS-lf|g@OxD1)Eci=K74e(muKjdy>C0Eq_Mwo zk@ldlWS3HqvBfLGqo`GdP1H-pLqO7NzWeNJEy+mjQ6+A2B-=akKSwD z$=)}|G`@T~Z1Es!Y@BQGA|Qj-vbBmDf^s+h^HmMl={^tPB2dDqv)G(qn(i11}<{-NA+@=v@d4WO9H%Hi@Wm46tp#}iHptZ zVwPc4MQQ|o$-?1hdN6!Jsg?@; zgdnnsgxOcCpD9vYMN=q?BXeD2S={u=Q+@Ki^q@GIHg`dpo5oFIZ)mCV-lV*)zDe^g zkitjZJ5>d4D$@dw(Z=RWP20jb<#jYPpb_juZ@Puj{IFi&!i@U%o}GZ;K?by`ax)|N zD(hw*R_byP(|LiFfmXr1yuCBEJ9&bof06Pa68s&#DezL$F?_WN;?tE z_1n7gJjXD5U^8a75G%sQIo3Cv64wJ@<*#%io$Qjdn8rJiHB;R|yoGef++fK-umPG; zEgzoTBTe;$E?)l>yRQ#c6u$-}G`YJ_Fq3Mk-T~+wZZeHdI&rfXm<=%1;QFy(H8%3G zFl9_$?1_NMN?p%mL1|9@C07lKta0w1ydWX+S7y=$u=~u_*+Q@9?fvgZn>zSatp`_h=UObk4j#n=Uw0 zd7169=fbnl)NeRb^|WN~mb5~{5a-UzY!VUsYb-Vsu3j}S1GQ5WU(AnGq)V3fEIai? z*v!iq)YbNQje2L>E_Zs?J2c(78~O9e3Z)g|d=Kg;|HAIQm~0(!W|{BH=JIvJ4^3Q5 zPKm`2mYVv*5z8OFed<`28_zmva>ICcOZ_0<9+k9~aNpJFWw}u`b=vS2%9ps6ZCf>> zA%7@>Wp7WWLIWF!J^<{1pq@mV8*`J3_Wc4svG{rGGyOaMMfF}joQP;oC|~HxBab-4 zKuglATZe;JVb06D@(tm=j&D)Q@cP5+8#Ik$(UBqrs2icqMWk<5GO3XF*~j^>I4^^P*K@l}6O@ldCrIR*>eC(xFmnH*4{!*X zl70!s&_{eU{eG{#vMsRu{?hIZvInz0%J-`9u~Rp#2lI~$UMD#eKBq?=X+uNf>PwW6 z9U?c2P^RBwin6#v>mRIYnZCn;9tlK!NaG?&s=b5kpNdBGUZvPy<)*@X!8~tPr#-rb z5l-47L|v?F+(-^s<~$)p9dZ1~T%-C*2!CUIbtNeutDCxU0!i*^wH&{U$==>a?34c5 zK03KBd4R^BbAVIAGS@VOoe}*E+C1h97n@v|LLw7oRc`Tz(rzk0Dwd{cF)ELapRQbd z(t7-3`rV^%^(()=L_faxsPg#7hd*Pd1BBu&7c{kHk#{hJpWhLf$7&+liMSzR9W_{Y z%(g1h)9)2YW<$7pakM+}aBw?xQ6joXR-hW0Gtmyvf^E6LR@6-xcVd2;4rnPvy+Mhb zNI8@fs~MI@cgj^pfxFgB!e~cLWEU%>Lymxwb6h|;g*z|$%d38nbOMo(ge2K=xH87+pqWTx)IM>8k6z&gfPDK@iY zYSiMzkiVO|l+;m`t6eG>Fp(57l3N`kh9nT~hRlb918A@4cWcpti2{(?7ivV^?O$Jn zixKnpG}98{?`WUqidc6VwnQ!w^e9NRGb?H+1aw=Js-tJ2R*Py^E>yplz%)}eVzi0T zj%wdGy6xhz_N8i$#JM-7QXh<~In#Csnf5|Gt5Gc~cAlCMK7e}8AL~u0+1;L@?RuNN z1Q*?RS&?S6eFQZ)KlQ!~-|)(@BGkEB#u z!wO=sR360r*>7O1`qZfkV780C-(Ag6sYZ-g^rb{~o04&%PXL7L6q2|HNs5QypaT($ zFi|P|Aan=6{tH`U)DvQb6h*AMKX_eE>uDj=?NGS8vo>0+%c5UQu4dqSiage_FAtN6 zv3nXKHF&wIfo8cdW|BOLeLy$@=xT`n1Y$N_%GMe*{c-hkkXf@<;=L}r^XeU)btSO}Yt9rvd2 zef3EqCIZJ;NNzB%*?C$*$)a2A4ojFqhC&sLj7hRxD6(pXCZr6C#v`W84W@@+=!(8c z_0%`OKpb3uHnddUj-t0_SfpbBex2kp4@xn(XrRTUK|`QlGCQ=UFPtHjIb=L?O<;rq z6}6LNh|=r&#Mv3Y(E0Ero$KtU{6j1HEV1q?d6U|AYUI*~GB z%EQ>S8(kCnLR z>K>&jZDJ=DY08hUq*|DUOK@<%0U<`CE?TOz!_vm|3Y95LLr#(@qaJzR}w zR0rdU99ql-@8f9DddZ9pwqjkj$gU**!3hvCT|ks62;-0nCb?xy_HYdR%!+PKCz)|f zuG`=kgt>fZ5_i}Qj%XbvTN;g2O1=vWcdbq}Ifh>iCpE2@O#)25-Zc8YX-y|UMnVfc zaUX1QeC`IGOHZT2zwI}Hs4ZBbybV^n4+khFc}i> z>x#x}1L9c5VEkUTp&j}iVA?X_I76r2BQD!_KlE@gsPy>!J05UlD{Wj0$zWhy->o>A zYm28RL(QGh+ccF1x`Y>OPwlpIHp@QL0rstBv1P$aKbnh?JPJeDrM&H|?AmvE$#!+y zOS_%W61vfY;rtmy-%D%~<9Syd=Sm8~A#4I9l{}y4n6n^a(4uGe^2gG15Y^E~web9B zj6pXrjw#;)iwSQF=P}|$c?J>&Rt5;4jKgAo$Y~SJlzwkm&h;TJNLzXtM~R+Yp_Jin zKfL}NpaSTedIl5+a-Jtw;I?_n)AZNI*D!YNur@hc^sGG2aUm~bj!7oRzNqDfG~~o0 zmYTyFk)GoO8bO1jDSNo{%440qVq*7b!sr*M9yOJx!j zjBz1#FBS=-6{-V&_JZKQ%Umnp5YMGx3&qO&4L=9Fto3ZXTXV*&QYf{7<&+_pu$wJ9 z1NbekHf%l49VR2{96++Eq5RB4&?TV)2c?8)^ls{Xc6!2}tVelEg)kn8=jzJ0)H#~wo{f8)MP zp($r9Zgt~E{-+5+;MVddxz0p^SJ=RrPmdj53l7}EY`aB}7L^lhMOWZ10oQHSAM4nR zPcfo}<+oiU&Ky;`w*!w8ZnJ}rKp&I5In}GSY|n^NW(1EK+#}kd$*wzGO#~E;bEnf= znKE4Nv>Vae?vv9yR^+rtFAMW}vmca6qi4r*x3f%g%MxVnWaQhcxitIrf5@%45#c`J zl=vCf*wkVkJ4blujB%$tJ$pf61KnVz*6a4Rh2WhN=_l#k+;NGI?)9T=*k)<0GEa;l zn$!$2*?m1qsDVU52GS)8>1K!YIP5jvlZzPhV8TFP?xmP}dl_pfHS}18uQ88Bz^?9} z-XAcvXo86h$d$v0wHZCey_q%7D#)wsA{VOt+;7foajJu(Z;(e{_KQ~Bh`qT$daz1= zu*Q3^E_1M)yeqsDo|xcByZW&j*m*M9AKV_s-VA!MB4iq+c}dl|N^^ z`<(wvuH2Ul?Ym#o_YVI#cFNlxofd;WyOR>86%38VG`Hr0rRnRwB#n&~p5cCpLLTnL z@Vp?`7^5LniGhS3FtpYc8vAf3`=k_^Z-1M9-tRMw{G6dpdOqiqUbMg6HbuHZIr#`; zb?u0_y9N|}K-U)oT#bndO=OgX)L9--eTT4KiSdnucuyu$T6y1P1M}a5a9mX^8IwJ( zixo;efVyvBsCkpRQ8oEy628N#a94W~%@RFVOIr#<7Nw!Al4P|5fPmWMYbi67XP8lTAlGwQt zC1!>zA!it5*mbS9^r*YFle-9gEo|^H0Urt{QazQV2sXJ+wD_~^&PCwSF5LK z*3Z8t7n$0v(AleC?}`Q9_|E7kTSwK1F?oP>u_gg`P+aA^XCQtrnxCxo0oZ(2k~`^M z*Z7{-U1p`n$$#H)totj+`jwFOzi&8Re*gUI?C{swzi8gie`($ye}dkB%CT<$m1F&J z^yyz_9RG#&e*2U4{$s}R^U{Biy~iJ?{%gkZPucrrZTugycd_@+9P9Gx+QRngI9~St zdy#c<`NRLVwtaoX&Wp1SDQ`__ZSJpfJ2kY&7 z-}J7f;6Jh6%70?L6?oQ*t8S?;&Hww1<65R>e}>=7!aqRoix+wMdAYfNv{*AUGc*3K zc@wg8|I)lS|6TK@y?lyA|3}RmR^?>y&zjdSFv!RMzPE4SU!d2++u!})D6d&!o(?t# z6_FwLC`~*#SupTFQC>Z37eh1Kf7ZNCI>vg&);fk(n)>EyI)8#*En|F<_5Tmh>-C>N zZ|HUcqT$~*9N#|`a~Y&P_xkS}j^s+#{zc<2{>-tO?=-wJmQ18^t#F_E1N8o};b>Kq z-4@HHS64b$4G)&CnfKi^D_ZlclWx%FtE+H7`MmVrs)R4HgWB)2hmYxEc#7vQo}mhF zBmH`Ow;ky=2L*UCH0dd^PPIdgD3beneV4pQ$4xrhXX>=GDfzQ#ieF)PCi(xf(%h z>F%Tpzvh=5Yz=3m3n0!UTaV;UcP}tykD|SS`Xz3@bdzA-8KFD;(*6Bo4s;zZfn+#n zJqamVn}L)|l;%j5ylp*!)!%V9zKgUA4PasIZ$=j*y;RghZ;e8%O`GX3~e5Z`&ab?+K1 z=Km0Pmr-&3iJI?`0tzp|z3||LI~4Bj7FFznF@0@$*&YD?kuXe)9fu&gG=@ z$8Ochhr6r8lP(l2j?-=c>66nQAj?C;5l`so^iRX_te?p6Ps7on`fQNu`JaYk6vz3W zhU57#YkBpbhU3xs2+zm=y5YE;?W&fYq~|g%^Ce5ajG+Z6Fq^2~5Hl-;tvftpmQCcn z=$On}so~&xqt}YQDLC=iHo?SkiK~!picwzTK3A)b>21w~V#@8F)-s(R6mKINTTeOe z{ebg`Rm679#N%r)mr-q=y71$;R6aTV;1hfzJeCd#f*aGUKxoDe`oIt2UcSgY$QHiA z*F*(N2HTD=g}EgyoG&}~!Hq-V&%&|Ca4r4*gM!^-hsDWxFxrUT;b~qC}JaIC)*? zs}Bg1W}NQMMM>DQ96sf%=z^C>qx4}OdGyGQJtmVz?tM9ZoSz$=+w@R$gLhZg@wg;t zcpZz|CY408B!Hk$4~KA2RD**%6nvw3cW)`21f>8#_YN^I9LOM=mgsVM(t6f;5E25x z36k}Kd`<{M^9Au&?#&I|=Xis-qj=AF`uMhj3Fxz^8xmuboi7E61waQt1xf)BSV3mp{K*i26p$X$Y$VT{21~T( zU?8umlV`j`KAfSF4T;EDv;c|s8a`R!ah&()@0Kw;78Mp6-1 zu*CGUQM7}~iac3DqxTRq&h&18Diw3@XzKKH`X1viRhFwm1V1u$BY5;d#^15&7F0mC zTC>K2{KF7pkI-nh-as@kv3h1?`ZHmm|BD!a7HLDA4jmd>m_RhIj7i~($dgiDf1op8 z!&0I&Uog~f#`dBT8FJ674;!odYSoA~UO>>FZ*9WCPx=%3tm%p_dMZ1?euN)uS03vQ zP^;yNYSbVXT8(a{ph*ZYCLL$2ZGO}3$P3YpoB=fN7}0trHw)sujHsLvPFZ!^ErrqrH0Xf{_x9^!N>EMW%_XP(mITn-_fE!&<}ND_8jRep|8aOd^2bJYaJU! zCT1Kn$U6o!Oi9ijpHRq=d1v-V@S#~{h9=Ol3zmi8PH9QcT!>fg*BQlXg)@KMWpU}n zd;*2ogg40#U{nn2o-XktL`d0RD%AySw{2_#tOn2HrjSnAi4bo2KJ-WO(X-p8ri`*5 z%?#4Qqde@wEEn%(#>n_$K4se{HW{%xjMav!60M7djrIg$Ch7k=a^NYCYGw1QNbh5p z458y^@H{T1Ejip^6+yK7HIo!kJ3zrjHC4}dhco!_nR_85Y+})@O0Ox2&IAGPX-t~r z_wmG^5mi84J`58CyjYjFGa+}h$4jw5SC4K@WGOg!YD>(3?344Sa~=N9@l)lil+|AL_XCnz0WwbuPhXJoet!0JrodI(zIP|#8T=718cfE;wE6|z^kIL! zq6}sPyBsC@ePTGa@NOnz%eG|{*j#=tk-2%G6dsIg(E5=Rd5|K;Y!W_<^Ar`FvMd83 zaL6RqEJBy1bm>sqL?z@fLt1i})8z?%vNWSkgjvO~HY?UrK2OTDIbBLfZ;hAFKjKn}~wkxA3#Fa)DbycmzQog}{nBzLc9G7Kxbbs3?TnWX4hO z@-ou5jUZ2$OAd*X_%&#viE`_EupkVZee$8IZ4lzaIm1lSXJd@M8A=S(_{D_ z4#juJck{(x1%c(19Bm69LPH^jg+g%oM@AVSWndW2q=}2Ll&f$U#2p_D4pC_|r?_wB zB;O|{y@qZ#TTjgB8@?fG362IAMuXh3MUa}Re2zJWT#w0!1AG}ctihg&pr9WhnFZo( zC2-ykP@3DTv^q=|B>IIRKlNO|c4*+^Ns8}LWI%WX8Y~*D9aNJMr?82Ez8MM9enkMs zZS{?BYkgJpgU{IkmzRaBx0Sf0&^Iy}gsTOOahFO3an<{R>js2NHlsv0F{HFWEOe;p zmR>Pr;Dv>R7GLZRGE|9V-A%_>boZc#m0&<9o5UNC);>h>T!-Tgn1BxC+zpBojt8Hi z@F3CK_Y)R?$WCAG46P()za*9z=urz7V#74y4bK}n5OF4`U-1=TA^z08BQ8xFCSA;{ zj_5d_R%nNQEPj}Z^+ynXK|=127+fnfn#JTcAi4q>U(362#3Sg9FnDGNB(Mn57*77h znu@}c#tqf$HsZp(3WQCksvdw^cv3<2D4H>^P?0DKJZPxWX@)mY-{_ELQeKf^kZA>o zoE*$k@CxM=)nNnEVgn7EC(X@?SKco8Xv~0uO3ot2A zG8093{e}71=Q#yhL18f7UO5pW(uz3C1{7%{F!goh zL+g(`Buje()6o*0d?NeHIg%Tk^HoQ0>@;4|N{h6Obv+ZDb3YtYH~jFYQCYOJ8QcI* zH!vlTSzG6n$3qZjedKY2`PB{dt~`^-8erg-_}CJ_h49(Qe3&i)u@^v)k5KvD&`uw5 zpBq(O z5#mhF-I1EVXRRe-g%+X=!eYZlFMuOj(m#SxTqYhOj}I@P3n^`KX~N7`$RQzh0YQ*r z$wbT$<@j`DfwX%HiEPoSM==`|&4~`XdZQRc8FQMHXu^?`mp_rgJyt*1ZiHQRP;XGsSK@6p-p|gE*<0>aGTxtG z;n_STELK&3WL=>JI66B?{xCNQ4$s$5aQtQB*I&7>D!HG?XTGE_c%fbI#87iPWwq)I zr&AT6|5+IaNv0jCJ@>2y${LWX!dVW9A@`>k9Lp@MPDvu*`ui=veG0gMOJlPeCZTEx zMPVHsUz6M+2dpxSp|43Pn;LrkmT;>+39OH%M5ai|zxk2q@e8Q@yLXu2<^^zVK;gTT z5EXM5&NB+QZ8qFlmHft^{>v?ceKwJw7?hg1=7kFte6~3d_RbCt&}D}}J7^%t#$-gR zEv%IhLh$SbA40$3(5mUpW~&`)8}WHlIyxVsgXY^OvMf~+?-%sRmHxc42EADzaeJy9 z)pjmb@_JKPp?^os65j<5y!1uuJgo7PXh%gz^M^yw@|VWFGYkXf_tY0v{M(v**;My2 zRGp^phd2F(T&VkBP|V`Of5q~N+!J?xtnZ8;c@Jx>kqhg@;%(1V1-XyFpR4ju;DRd* zcszf?A5IltU(hhPwO6=zF<*2F@pbJ_md&Ad)AwOxX7lB>bo5nG1D|v9XIt6)LHZ>1NNuFCjO_U(Fai7E!UZ)H`gBLvVM}6=32j<}Yz=m$|#{Re2 zq+Dv9f@ZwOsO5ruj<~OQ4Acg&dVAG4Kqpm$K*$He-s)9szI8@#tgb{ zDOm%4agtB3=)BB69wa)b-ru!iTL(Y8gO9%&ve+C-Qln2$<4L)r+o>89$sx|pq0W55 z+f~6I=2L06*|i7$L{m(jCygCvI9yTq3CN3PluhjkbCubC7^LHFz#Abf8uE9qKb#!F z3LW^6!_)tsCO?OwI8Mlcif1@rlyIu&4l*|No<>B!$4GmK*m`UpkEb_|ZtV#?^%MVR zys-c?SjFuaI^XzFH8qtf&$l?56}%AZ^!~J}-fFH=j`DZj>l` z4&UUA)1r%P6b#5GTYC6nr+25_(@#JcD8VLzEtZqos1t;tlS|qYz+UQB4n7(Q(4!in z$JI3Sf#F1nWMk8#V)xUfx=BG9Kh%$MMG#B3ce2S8Ag6 zy%`NoqPqZk%hi5H-r0kY8HtN&w9R>0)G1<*`KM3#Sj_nZ1Bsna=N1tQ&C)p1MIZMQ z$qeGBu-$#`w-%6r^d>dbJ68O*8msxa1x;cqL1L^w%SBjb*f|)Ag>hzg6D>ATUEXXP; z@7zov_rfo}^7|B(Dn0Ji&eg*y^cMBC{bP=ioVBCXH9UsJZ`AAO66==|D=t4Z8`&goRu6R+Tx`5J7En({PGFPNCkoiaCDGVaFCN43ShMz6fG5g) zK_@8Q6C+RT2&$iaLnqN2}agC z;kxfC-tTNlhwNj&hNg59vA$-tLhNZyVjB=_lNQS1ow2DEJyGId4x(Alk0<(71AeZv ziKe~9nP?O!$!D^*AA3n}T1zcXaL7lr)%-!pDev(8+Tn-ahuyCqZf!^X7Dt0LJdGcq zkk?DMfk%XiE914&->Ht(P-)ODKqF6aGmu6h8po)*(p=?VdpsAywCAwufsq<(OJi^A zq4a>lheH(hDHn)}_vHNBH^cA~ApAtJ{N(HPY=PN@(u&SOl6YW4=(>H|E zT(j2stGg?XC`mJV&^D;Zj#gE&E1hZmEFg%FNpmbFpD%3v$HP|M;4c;?+H+(V1!Mz* zi<>EdTa_}XH8<#nHeaLJ_L__DI8Nu>h4XgM>Ne#Wt{kCC#EApb`ek(xwa_|CVbIUT z`tiJmpYQXj8}sSdHLnY1jIz0V*t@Qa!f&0cfjw_&#tGS?2~`w$?#u>%Owy7Y-GBIn z216bG48Ie)>9oGdzq}y{`(?QPYwa^{WYup0fs0y3)P35Ns`cL-(4RlLc=tF|KXl!r zSp9dCV#=s6mVVZ&(z)f^bD4I450Ya zaAfKvl79fb(%7oG4QAiPr4UQf_@5oC?^xPlNyZV7s75Ys} z4LrMY6k_;n?7iU6aeNW9Q_J26u{rAK(NpU|vsr#uDr1jjOS}`DJM4?MqhoNft~)$` z4|(i##e9Wd2Bn-S73N)$)Y)(D%@*m{DTxeBufJs__}xd|iLo@M^v2U_F7OL`%rs># zt6lwVj$_ha zd1u_x!@SUkhGWn2*X~#Y7j*zJG^??XeZBjSItJ1rTay~4eWAVEop(&*U5cE6@Weu-Qlbs?6y^o9_`Zw#^zsXFm78{SNw8y`-35l`sU%8r29El$&5U_KQxkf-!OtgLyazM`PL=X78IfMCFPkDxj~6l z+OZ~`wn$@tGrR4` zb_M~Iqlp<3rVmKEDyFSxoYDrcr2;$Tqk*(blu7RBSv)qMxzM51_fHe5wYCrNX0^~i zL$_UlhfxFquav`oT*#`%bQ3?P^B8+aHM(*6&CMv!wXLRjP7g~Jsq6~VK+=iEQW={L z*$G}H@pB`0i5_9*(&c<~dS2As2eHizeR<95VVIh#@0awAKnrciah-s&w(53??VCE< zysnl!aTjC6ndfiuno@{xM_rcF<6mC|J9O>ve9b4wAgrC@LBTMxflh;?4;C3RFd|KI=4vl@w*1|Cd0Cx+K#x}z)Zk5+bJ@r=t7jhO1 z$ifccAVmP@ifB@pnt5Svng>f_upT>#MFm5F=6z6R5YO)~V zTle8ojVZf+^tK}ralFZkjL`|b(NIn{XwKHnG~#qFvpAqI0TX*!1ixssceeladE95h zNaT3vDKwu_nMv#0jb{C!4ATs>;^m9##i1qQZJpULd4-weAjlZy#U zaz})36Dh4#lDuq#{=2#FLMNeQN(v<^Nd>dDL0=%|sA3DhEr}VCj8ClRlcmFx!r$D- zMjSm42scWI<8Mf({=7}o0rp%XYRvB>2$HSZizY#u7I9-1ss zls8fOnLTmoFkQ_^uA)3+e-?3=wP?{_*C${5WJeTCt1i&?IdwF;sWovOg)ba0Z5@NqC!q@Rc}-R%&S~ zebB2+pwmg?`Oh3c1N-!a?4|9lli5&mO<}Y?@kws z>!tZFOrN?4i6_>i%L^YBd>T^6mLJQ%<&>zvW{EwDm!8`x8L7?XY#QK9*E5wAZ@*HB zjdR@=7L#;%s@$rM=IS98_3UU9t}!!~#L)6nsOZI%@}5MJ{083o)!JBBMqAUfv;xYF zT0bFz#lX|~jAaQauF)cLF7oAJN-03TZ&1M=b6nU?6z`btki4WvQu@jci=y8r{SO{# zEh}HRqx?qgBt5g{S9afFlc+<{&a(-HsIuNzbUwqZjv{jklAwL^&W{T;=|_1m^yN)= zKEYZs3t&rE@#!pKnD>CQ`ByXA+BsaEnDDUN7VC0gllRlBI}K4mR8$n$4FDAr#pSR1 z*!BM+R=BFQ|rr);eSmkwEh(!`%5Zx|4#yB4^pA_AN8@6ztzVY zt4pfO^D8UL9-?DqB}FTlhHnaTADBXMQ9)s0e%`~>WKPzDR7g)t`v+F=E2{Y$R;Y2z zuC&dpOiB4uA4^J1Oh`aJ%uYT8$ShOKI>OBUNfyE*gF?argF+srCZ~O2595>FR-Aq> zUOx8^^!M@c^zn1|{AYda$x~0KC+>d@PCmAAGPiOtdu;zd#|lQ~HvifkQ~MiMD3j#< zM|#XsS^NJdR(QlC&hr1RJ~j`eQmQNH2?Ije%!cX;`=US$DmhB-@zt?pe9kLFlbh8c z7XXsO|5P8#d4wc+7@UN?935^f|C}!!hC{8=^am>t&J`I~9ZZ#I6|3Yv)W`Hw)xDKF zJ`or5n4`)1{Dl=9r*Wvt(yGhCESEp!scVr#WN3z-7uu906O<`r^l#2Z$5H2f5;n1Pig@d3 z!EaR2c(UFdhPy7zeTlFlNQB0%y1nbsh(ZwLYjn1IH@IVwOjAy#dmQ8XQQsGf9=$+( z1DG0W?7#BpH3N~^j;<^AYWuR>+R&bkUfXKiBEI>>Rr@JM30coN~zSUVZLW{GEJ)49FgV7 zt30gj#h#{DXL9x>G5Tn!Jn8)SDR8zL0{e8>IFa}Lkm7NoNfK8eTS}SFv<`p5^ZE~R z%bzB}zFeRg*?#Pas;{GmQ}cQK*J{p+DV7Su5>;w0{%z-LN3J0>;8uG^8;HG8hU zWSCM>wC$> zIz_=ZT4Mc51I$m~v8lh2kqX@`#KjGz>h-m@6I|*yZAOzvk7Xk(uPc%#kRfBWcuK-x zir!a;)f3XB5DI*>C2Qh{2mxxr&X%neD2&;CL>OQ4su9Xs>sDbf+eT-yPl)p(kg64v z!7kEYWQcAAR;p2XtUO*ncK)ser`}Pc%u-}xA_wbpm4ua=#jt?4RL2vanH(lj6cQzc z+doYR-JP^Xq+pP6V5r5CiUa-igpo?;9t@!nVBf?*eUuwiR#^|Y;FTttqK(PXBfTTz zHU!e)ii!s$G9$>0?~yLNB@z3mUxdUOYQ+RbRU+YzvTlwXxgj;CIl@{Zsx7enl3h;4 z044a(2F$K%wYVwGi7&@fNCRX)KClg))8y!Z8Oa^>hk*{T(Fv@Q#$e4Mj+I zoCK?#lWMRs*q;WV?dG*8x3k!4@+1^GowUjGq7~CdTAyx>e~8&0T$OA;O^5iY?OLK8 zqpal4-Z^3O%7ASqZaCC%9D5sq8$pxGzu%NUXdpfz(BLCR=n6RIW9^Q zV<1_hC}5LxNyDZzTAOAbO?a5^_YG<31%uQ$b}rcDB*kShU$JNuvKc-EO3r$ZCBs;k z8}B-2$-caFpT|a=BmJ7dF?yb?cCNtw;LE%C6{j+eCb=SGnry zSCi}Zg|S+nmXXzO{?{EF-;F4y>ITjtuix*hzxAIVS-Wb#?mUfu8?dLke!F!2;m6q9 zm)9ffzi+R*PzdURv8q>@@cPkc8l|!3+%V8SGXc>L!osm2(E^t}K!Wi)+0cn7X=xdv znjxiV*ksgexW;HDfg<`qf3^dodF@-D2o=dS)wG`TV|4ORd-p8br4aT z<-@3nyhNgB24|unKI@X|g6gXWXV#`CLpI)LG7I$+Mecv9@)O{a_jW;y-|%IyO#$M< z=~8i>#<1}{@K|Os7t3EOL!$^NnNF=2bB zVa(4(CXnq@CA!-j5(iSbSuGj0_(G? zk@94NPzQ(jIR=j>7S2DpN_?l9rXk^VnkCCyM>kG6<35Ra;onTZrO1BZLguqT7E_+( znaxjiHeFhs!UW$3rAQ(bmaBxsG@mPwgwPaMmJ-{YP+Mxi6HF>!GVEtL>&SJz3Gchr z!?^u<3{L{6gZefUL~f;hrS5hWN3O@aRu>|kKg-ekRmFbzUL_Q<{Cm*CQj<0M{-BgG zAY~L&v@Zi|I=Kl``GBS)%wAl_`t98dPXANA#U6qTwB$Tez&YL-%XTCvLeTuJPN34H z!{|r$?LFGPCLnz`=}jX=ygvAM3lsJvZAFil)GU_?fQ_n=twCCkz#vGxF=)C_ree~y z&5dr5KD0120JLdRG)sxG0JiF7Sb_6mdw`Ww>0XBL=4pj6g3+`KFr7~^WHv-e`}AZ& zf@EaC-yDHG8R4Q8Vwpi_76rQA4QJHGtlfB+3dCOb5k%b*w1)Iyj-W1uICeNnVgWw!CJsDUtPK&$0d`gK^zv#YkM^dpoP>3G z*tLEHLFzD3S`E<)1JU8ZXb8#rdOAFY$o6OmF*14?34W?1+P7h?gNW%2GkRu4CN@cz zP=Y-;5nU7wY6MdpklGK@leL^NZ2EGk)MHXXISMz!9$tC~C1bNWvNPACR`38+8HGHsLb$OK#M06DC^>L>j_0V4$K+fIqeu;M_L};>FpkzqY}XOA69Hj060kFj z@0m_ytPd{@^TwG0B}s#Y?MXC^Nwk&0a(+-OFiA@S5H zp+6nG8AWR7NZe6q$1D%Rb;CKZBwUcjQtZLvNW=$riAvUDLLZa=Dd97>8~_jQo)%Gi45YO} z!oBaL}D5Tjl{5yN;n+T8}p-VyDt5ZU0X`;^+pm|X7{KNy7dC0m@ z7K@Oe?|DV=($SiLaGPV^GwBl4(^Ui)v3)9%1LuQa_^qcUT3PryY^9iIdDF$tWy*ra zD#SiUpr_2B?FLRMXVBwM&(RYRnC+M%QQkP83J7otRZYMeIHg`D<=W2J0&c}m`|Pd< zi!tDIikI>Gz458(p!gYzoeE=2_q?a~1$hkoZr`jzCQjmi{*rFxkp9zEK=}OZ~Djxb`-R%`3 z!ItS^8F19fzA(l+8|1G{5X%&oI|3UC1Xp4k0480ZfGO(y2y+Us-YG-l9jnl+EW56X z9*_|(yi|*#`Y5YH1O?@^vfOzy-P{U|&m))Y4M?B@^eeIw0?q_jArzZX-V_jABQpWg zP#Y&pEUOG~NbSSsEG`PVNO1VEGq!6mfNcWhl;Ukz7&aYc13i0#B+TyeR?x4xG}9^> z%A1C7RZN6hPjHq)T!oo+FAA`kz%)U5iw{DfW`AptSlrvwfGT4#umB>VXe6x1hgO0} zP|zQ$G?YAO+G3cGgVE{fP-t+)$-W9s8&biTKLP5Ij?%U9>cw$#*`U4KMish6Qc1bWj4-<^!B| z?!rzthLTzv9HM(>;doVOBHjCiY|!FF&bnMn;t14Px&s68-lZU}w!4!b^}Wk9ZQsPh zjO@$c>2@#ARFQf#8+OonHhusIr3}jP_J?T5ywI>1(TQmXU=!!-@`r{m4YF_)=hGtI zj%XG)qN|@GM;$^aE27K=n2B|`0ByY5ZY(7_;_VTEHNbQDW}81nj~>E*!^LzQS6Bv9 z$SJr>r>C!JyR+J}*VM)m&8#0V*=Gaqm78{-fe#|wvr7Xv7s_mskTxNAa;2#n#F_LruESqPdv;;%$*}uzc0IG+l?te^o1D-OBw$e zv!8@jzSTVyaaaIJgc(1BZqbK}zS8L-`@+6N&w<$K!9tti(rJn5_8};u-)VEW*b^rh zm3*{AEJTfm#*(xwKs1|fm2_wLj^;Dq z*G55O#YYtjM`4%U1Z6$Gurc(K;R$h~g*XzYI#g=D2G~z%=ZbKR8Cym*`RdV_X)>o@ z%UEXpc;m%*HKo`&hu9@v(-0NaHI>-qld-a5ug@H!zXC{5I{7bGQb6!HhqFP0%?U}w z@UxuMWZenO8i9Mf&)!y(waK3w`i8kZCO-5`rt(!1Y)($HOywe`YHg}(`CigVzz#+~ zYu*P?msC%(p=J=9PuFY@NSY4{n^SX8&+G}z$gPrB8jNS#%p~!Bd|1y`l;}k1ok`sO zI9xoFDLebxb4c1_hNx)vHFS6`Y&IQz&VmzmDKa%E>E*6l~OjC|lg|dsO zfseDyVex@;OVuK|or~Hs!#RnVeAINsfuea6OEnUpCOip;QQ-(qG5Pd9EuG~Od?s&K zk@jEoss&SWoOZ%yzRv2PPJGewx|NX{oczt~4hhmOe1?2#hTrYtaP{RO>eVZO)s_2S z^p$C=k=v_fy4bscYpHdg*3C(Geu?707bg%}j+$O8yI@!@#=fW z%UoicW!(%m%G0|^gtloB-QP09HO`RQd#8{BR~L0sD|ENLcV{*vSjKKC41MpdEcPvUS>OXE-&dS;Wc%x|y{bmwZb(1+eG0zP z;zYU3ekuK4ZXz{-#@;9cAh~is?CH*jWQvlVjSuKur>4YqTuiU?L~Z54ZS3NqFF{qW zg-c(Gy71yLcY=COm7K)ECc~l_X5FuFh2Q3hE}pGjmw<32z+ZETxVVUiX^6Qx4wI61 zxy~_)C8>LYcXS$$nmjvzg~w*~yK!j8g|gU%*hRhH#A+-+dm6+~e;@ZT?0iK3YPWeD z$Gh8+O!0i{pws4Hpkp5?d-5vuxTX5!VP`UV`{aovOuIWW|$EB>s-vZ3mE%ckPD}F<~XB55lw#JCB&c1)|`*?+db_$R^kgca16(i&grxmXnhAN1H^Hg0{Y=(gJ6pO4MneBY^G4I2q}%l!N1i#p@3J! z9KLve#|o`lmVd90{f}5dJx}fcZm5!mVaI94?`ANN3QQKRZYqN+JqG#_UtS`OdNKf> z9?m!QhB{^Hxsu1iO`AM#{$Pcy+3ga6jJdlR|4GtvbpfoW^sJmVEVY1V5HopXn&P`o zVSEfRo|CLn7q0==At&bEFg*$NnOl#7t-6Q7$!4RJLi(Xp&c}l}c=|1y@ZnEyAd@Mm!H@$Z1!hr!8@`H$~k{{AyK`4H>CdKjEM z2X(}Z3m8JvuBWdJm0o%Xz{t>cl!@3X-x!FhY@CJR<%)D|Cps38>S;mA}K;_QL# z`J+i-_B0V5Np*76&vz!<)i6~O3vtp_@L_;g#w9hcL`{naEJ=73SV&)#Bz1FFj%q+c zn^qbMlz_22BV1Sz&v+i(EssKeEECT{Ug#swc){)dBs#pq>Jtsz(mrT6|BoX+Ed&-* zla}l~q5R*m!f2Wszm76XX_JmBH#JgBP3TLLuBH@*fZoz2(K|g|O?d%*eM389VQGP* z;#umqDeny8DMI=m>SIhzU<>(x@AJB;)o;K$;bU4jwk~{D9~kqz9pzt9IN2GyJg25N zx{HiSDgfc0e_z6s4c0SL%?CU(^PHETMZb-i_@Ov+#v=+@+-@>MY zG48xkjwhMX2|9OuXAwyo>D%syMX^iwi~&b@>sMNVz6~Oiku`(BJliLpPFz9c%Oa5( z!%)P=fRSCML)rMek<*~a-g*GOoI`%l2Tq%UsFytPFt1Ai!=iMb(^vMYL|IPX?<13! zv>zwb_)Dla+Rw~8w^_WksUwW{f718`O8K>M-hR2bVL9@rxT|7-*wc>fhew=;pJqEg zz5iKOyI798ekQ^IR1|j~AjP`1AFL6(b%(r2d+#yA-Sy=39m88)r_sXVThE8V$yL#6 zRYmIcx4PV1UUQG5BzztQCp&$XIaPjM<#b6KJztlay?ee9YbMLKIWY3;$Jz{q5-ch& zBCTjPwfuws;oG;LtYcHIs9qd}5!RVTx)J4D%y%lTcR%BEPPVM}e}?nBWG6ppyKOqi zH84CHF<;0({&C%9p}PfTmym&u-4d;5FF!__+m;$l2QA)H3VW)I1mJFg5h5#npTemX zMhk$+l#$9n(zFcF`C%UI=`th)(H`Y4n|u3;tRDw>LG6w8c?xnG%+CvU`vNFOe8qUqoYq%GLGU%3-o~}ie79q z+jMjwad>2u8Y@*y@=#P{5 z6IGhalRTKps5e~%*v%29t7zZ{mTDihBY5JDYtK7PB7$Pd`F0Q2+2DRUYi4Iig9eQ+ zUh7xil6-^efbv8e?sI5m6bVYiu6~Z2c@{gz;o%fsVL4Rh3SD^auB?2*PS4I*c;zaP?aKHKM`4s zf{JeYtB9H8Qot?c?&WYkG!qcwa!M+awIB*BWX!aU6Nwcm@xC+RMv`+2DeVncKvu7{x^Ln2AR%FG!F5CQk zM$l)qipy{I=j``EhmPZj6Xj^*B3_bf-jg_PgF80SrdAGl>rw8&(W<_J^kzNQls)O~mYI>7P{AZ7j#nfl|2e0%a z&=Zo^)cZ6@M{Qz@jJH}5=_b#6EsbTx#gYtUF&b(OXoitfTcH6d^v`Q!w+G`~7Ok>i zD03ACj^YPMxi-de8tkTG^&`BStmGL7BCl-IV5mCV@fU7X@J z`7c&aBxBk)C7$^wpH4Cvdv<0=+a(0VFWxq9)!j=a?U|rc#oi49=agLC&T(=!)l;tf z8aqzo<;=F6Klly`5IBTCTiK@7H2(;bu||eXZV|RUA68ZNNEJ$ahq12o$#lFI=S4O> zM}8ae1@%Qv5O_i2b8Q*tmRrI0sS6QH^w_J{ed756_?||hM5zSe5=Ds!4U)#$o>tGu zI+8t;hx(YQx2e?=oiux*pL?vZr{T74_`jg;OSFd5(PV;;gnzg1m2q8vaB89(YL0$) zqtQFFllaO(`D#@jF2hxgSfcj}Xbcj)=^@=aRS%8cP(JrmHl*?NdW^n7$?&lF`|TXR zUQF-y6sRPQ_O&#fD)_hqv!##vO5}1=Mu-2N&~tt5x(n;&X@pe37U}wrkBTqPQ@a9o zh1PFAN4>lRTiZ|mQof!4`10yqSKznj>p$1Af_@DAOMQ$G;%ZWATHt_vCb~q_rJ^h zU+g%XffwZRnp8mLQ6RmVyo<3so=SB{K{$bJ^uyK}@hf?KFQAUCJX3fy{!X)nS+*Qr z=gmJR@|;mPvQUUouF#@9uUTlx0qckyU%<^0Rszw(r?n^XVfDJ!4;OP;c^I{mLUWqWaGeQ|7c;q%hs z^!Up1=+e@^&1w8U@s$5Er?LF`{p!%W|1(0Rruk1u<1e97UtRXVQ-*S1mX{TkmK6Q9 ziT8J&@@Et;Gd(@+FN5+Aq2g0i`!v7CIk(0!r`kTNA_4h#m=Y5c`=C~Q%lSO0$N5ghM;2tb5*U{#jap2zqzJZt z`B65L(3?od%aM9P#YJp);_VoA_~G_Y^7i{`p2y~iqY0vXlmYfT%T}g z(%y&TzbsW3m==PKs$H;aerx+QlCLS{;9Y;s@Iik;zev~p zS7|YCwqJ|$rmVllqUm2&mdcvjPE=xcLi%Due3D~K6QiI3Dh5tWy3?E~F!it4;ahUX z-{kO8$TEcsD0I>Wa>Wgs514gKi)LsMP4bL*!Os-*9F+UR9~6%tCYz(*OKZKI0(|P& z{h~OF*&T(_M>BSag(a#ZcO%n6g3WY`0EM0DjOyg*pL5K)OfdG|4`I`|59Ra*@*nV zU(^V!eu2JP*`$@VTT(gt(+_8EMsqJk1u3qsGaSX;1vDr@$M12Olf)<2jW4*uyOMFh zkrPyKWzoaS%O2Y1M_3Epd(kXACh%{(+RGIH%^4Bu+1TW~EGb2(z4CY4+7=;-XO5@} zA%$nn|Z z-bG5Zr2D2^!yHk)O~&{Y;J~F-I>6HJg}6a!p;grtdO3O3(7UE(JKw=yF1=O-lTa9A zeja%R2Pxu%>|FTC60larDSlvP?$6GG0%_rHW(FWWVWjIV$j!d45IXu}pgL2Z@X~a4yHe*nYIZ&;hj6+f*a{^EM zCY)@{+2kT?VYE!JW%yzL_#%4)uUz<}^0-IVMb5rjx#;}xxKH~0WGn$LwsZGBCMHt| zp^+ZDy3r6}bxcSC7ZXvH@SyzbdK_(OUNl+CNHqr)-7E_yV)mX2?!ny}_t3aQ;~Ffu1a}A! zNPv)Vc;DHXo!y=NcINC?r%u)LKRi{x>%Q(AKw!PrTVnUEThpG2z(ygc5J5Sp#R!Vf zf#@@8vKkhG3nkO`fOeH(=`jEBOhgP*Iq{^uYLyS5?ziJxGfq0WAR|DH`Bu4_G(Lyk zFu*2pqeN(lL*X=iF1AFUalmE&$-HW;evpR}CM{luI06wY{*Aq_+L3E14Aqr}l+<`W z2+fn2%A@s!M3GI>?Aw4@xPq{V7eMse%CQG`z=mpo$}#LWb<%Vhs#4kNQ!*E`TuXz( z{rZg+48yAlZgJiqN9y?E`!HaI-ifkfDAW;KCs()4rXB}nBd7W>){Y3T1-7(gp*(5O zhcn8DIAfmnNdwq~*tBA+Y&{Oxx{tx5w@YvG7|EfV1{#V9;C}yPf3Zh@%ob|D!;9x1 z>Sw@fGS98wXi}>lW3AKaIn$H zs2e2i7S!*gO+1}x3p?@xNpU{7@3RP}w|A;l71iKr6Tyo~`i4oI9pxLAJI<+N%@x)xQy&o2In3=?}yVU!f_G42Q}l3!u} zT|wzf!p=g}IpmDCvd7QcQ0{4<7uk7FAixL`fc*k~MU*H+7%>rG=?0T&jZ?1WVBX5g zE+Fmhekx#)m&-<#9jgY=rRZl$iybI{S{=YkIHs`>YgJ?c_(VQm1<0=_K8VAfB}6e2 z+fxP-i;L!}{bU*DdYKqa+)l-ID8cHH#4S(o8fE*e5Gy{mSA;~6P^G{UjUpq)lbjCx zSYMELB2DXX-6!vmoKwLW2!40bQmu(azEJPJ%D|_ z8$Q@X>6n)2xlEJ^b^rC17GJ6d=K-*haEk~)K{)YPFfiflC*=O~(i46J8WlTwPlN8O zTodtXrrZYeP;_XIBAK#pTA`<5VCY08?^}>Y79%f7dd#{Ad^yMFim2!M$tWN1OJ+ww z3{4Wz%n#LNkqKWPpAK@Q<*fCGfqMUzJS{HS#8*BN^W{(>#g940` zChIzaG2tG%P*ogPt{MbIriC}3<)gSFf9Ma=!#AKRig)_1`kxKRJU_GC8a#6|08PRi z0C3kwi1)1b)k5y@867V@gi?|%_;=E4Ol^rfMKEa-V8$hIrkWTC#Q{_Djs-khO#+?{ z0Qs)~f?;5hRIb|UAayTd&AlKTAY9szXRMo3NE~F=53oCfQ!xg}#Q9~h6IzLf*ocQ{ zaNvvO;-G5@D;Ea57?2_c1`(mZ#?p4;K>6b#Uq7V)TU-HpwL<*y!m49m##f`ExrCwJ z_twTa*B66_?sgqn5TVpi=5vAfIIvKBc(~LgHs)j~i8k?*!5}rtFe~w}{SYi6Eevu1 zT3BirHnT68yZ&!6vfy>;-C||BFdED_A4*q9k)q=^Zm1+G922h1a*D<>2$-n`Jnv=yw3De*K=NrLnB{;TPQFw7tqIkf=9SkuS zOf(BLnl21}moTj^obN&WNfRG_UwybU)FRoV`za3C4FgCi14pg^r1KGIvFJRxVS4K! z@1e27mQVTy0P4RE|mMPAB$lnS6*02GP=DGPD1IpZ!B z1$FM`0sPGX6}yD}t?=VLz(W<_cb0fgYu|k)e=?y&0%QWdD>2?$f_0oTdm5Nciwo)v zl-`dgiHjw{gcSdPg7LvdM!cM8iFoUYxRdd+LdiNtAa!qmgAt&10*x1%aL^sei!xaf z=kqNkCC}w`dI)e|2&ZZWv3aFZ^%&Hq@^OUmQReE2K~o*HQXTx0U+rt!-$&WBQ)}0> zgfIq%T_04c>^*_1r99V3!fRHLQ@_gaqadKE~dfcC|~_OU^9 z`z{d+q_4A3|BGT`FV&JzXy5MqtH#foObw&Su^RvKgu<=MUGy67`v+clrrx z>shhA1`7}QH}H9uhrl}z$p#j<8}D;|4|((O$-b6Ct%OwC(?CBs$*vc2hO~3~BwvlX)ZN$IOk?EaYQb`q85n*v=<`k(+qmo%ny=)QVc@{nm~Kk{H)B*xmCQ0!vW7_wn_*p;%6~4Zn+^edZt#c|#TI z!&?&yrB2QzA}!5?qkr!$nB2&Bu)xB1&m)xpL=97Q+OzWd0F#EH9}eiU2`JMSOCZ+h z4rNsDsL2!3Sq27#0*x8$s>?It%B_Iq`BnwNg~dI_C1u)0bq)ZrmUk7F6@jn{3s~j2 zDs(oza<8s(*+FyFM*wh;@TrV?{ibr$qY5Jdfddj&rWQD8A=^%88H}hhhL+RTmI-~U zx(oP7DU>hb@X>1hV+Hi1)Kva2qpSf~HMMR5Mr#Eoy8nYiy4!SqB1t4JbK0salCqq- zlR$uW35gz9SqiKvx2zt&DZ8|)sX!o?xiScPYM2hG3R{W-km5<#~%C&;D7 zZz{>aHv-ultkXiT1(i1pXd^GX8(#j@bSsA@x-@#J;pYwuSs(JfmK5YNFf?wh$6BwW z!i-dLuluFbK(J9ifKDuANAL_)C>B_1x!!bsf4+;a>FL3HwfU(GP_}Xau@`3b;Kc z>YivDb8Iz=YnzayG{SB?WNM!#L|VdIFVJfj2#qoCHru5Ho6_SNC}=$qIwycqhjnagqrkdt_~LfKQ2ncNEMEkkHVQB`7u@H;6o=e7ZIq5Gx=f_SZgn2NAy)1lPNp|662 z>B~dew?nzK!+BD}1*XF}jNLr>)kUd>8^qXMYbe78XX7=`~1ZF2#Z4>BH8o6gS^ zP^$oNm21XA4-iI-;^_}|1#}B)ivwt>BV8%G(WKwy<0pWKAwj@$Yl_!_EfnaC1Jk6B zxdmp+wN|5Cu(f4qqCU}z0f#qx?`?;vBT_gw829K=5-U(w?_u#Qz?F22OoQBNlzJx$ zKn_+-dp8uRGga<7MPmjK(|g>1HwtEwo^loi&+~Ay!X7Osso5z#F8kJlJJ}*;*)6_8 z_bOq6K$|Mfatv?sG5GAWJc>u9oz%AiT+0f>oOECA1Ek~wBR?x|Iav`g5~o3=YtCvV zT&cu-XPD7v1fW>UXR{Bq>25?n$+eT21blY+HRmrqd_+4BvqrC1pAYjDZpxgGTAAP3 zyN{-^^|!2#cu#rBoul@+Nw=zO$q!@@8gTG9${{-T83Dq7OA-Y{P0(MpypYFk?Zdkim` z@Jl9Yb=&eY1`4nCP(#^bHR|cdD3^(=cCy(q$kJ<^1K%}}{G?(HAYo#Sgan!zR6%6E z4oZNyEPufa#;T7t*+r*GL1kdV)~R0#a-2NDSk2-7{bcVrfj@hLNoey|5IS@fdSk{a zs<{cbL^p$cQJLD5S%oT8J;CS8-SYi%3f>@7UA^Pgd>8}O%x2$mUfT*926^Atl9Nlm zWHnvgHbHF5$7oF+LwT!MEUTVWvu>I20lL_C++=nS6L&oPc2%6wU&=r|V|Gd8cl_x0 zFs64=xLvncd#JlN{Q*@1h8=q`B&1<60vl#q3BUKiwY%8CZVqdUd6!!HB+#I2+Q;l5 z?U(yk=c`4U{L`rY(hhK{41?kTeZBT{juN0`^@HxvmmiEDZ5SA@qUu~u=;?onj z_YS#8RntrGM-qA}r#Ud$5s>siqWcT@IXe1@z*v>@hzwNyrB?S#9eqyifz{(38Olb# zliwSMUoW%4lRSTZOh{I-g*AP<%3m7| z+Rr}y(S34#(f0#mb;ynZgkQX}k6nsI)tJFU+oDigoYl#$2NQ>P?JXQbF? zcfIFqAJ;|hE~lXkWC9xFd!TFB48aK^&@3KitO&HqAk>ap2f{))PLCdCi~Oj6}^A6o4pT zC7rH9>#G%vt~A`-!}4g*2V*`$i24 zChs+!9rbjPnN;L`qlRWix+nD}6_}|;OCyN9K9sn?fYkH99x zuy(+vnR#JYV;IMZl_ZjnMve1QIp8g`tWnGB5IVMoMufE**Qnj8%SRNjOVy5Al zRlh?^8GOO8rY#`xflyqg(Kp*qS<>ab*AHE}rV3ReNu($*9cC-dUPM#S{~^X|x?s-qfpp>d)^ zHNnY5plW55;|Gn0-^z3b9|~c`Rxq4weXHUkyb)x?0N&J&pWJ;H7M?^S)W2`kU9?yO89aq?)XfHwc;$9 zr-k~6IMt3TN;=oi*_v=HHSp~nH|!>BrIbd2@GM$>d>UT~j#!s;`EXz9<2 z0pkUpvMJyZyup+&6R+mt{j7px7RLG@or8J+u|{G^L5%aXFGL500GK2;nOX#!DLsTd zt$E#B%7SF21SwZ0da-a5l!RkkTVmgj=LsfHM!it5rk-h16m6J{eidX*yDhFHF?+_u zRcB3a4^oi+KKY@!Ctoh_N&&8%50Q_>BWJ!+I>gptlFkg1dWR8i3W<-Kc4yHDLmyJp z;ZJzLSU|0V4wUhnN+3p8hy8xh8U)s6$`^iqAyXQnN1za_mx%`>2aoKI)g(uP@z~V@ z)XeF}Q}BjZb|{%ftt7stmMPf6@~&b5VJ<&|1kKEw&xEwKkxs!IB>N7`EQi; ze0k(wprp&wYkx}oe-BFkbxMj_p6Xbd>iq8{{*}Ro{}Un|?j9TL8Xo8x>TB=s?db1r z>+5doMYVQ!G@;sR|K{eXjw(;YhcSFjls8YCXwQo-c3;VsnYnCZu)s z3jHB?IXRd8zR>xejHX$LnOUIM7VMLH?0>o^qoQdWkoBZW{Ei~(X5#(0+Q3zERqy(H zegC1kU$aU5GQ1t1o+5R>Xf6YZ&Gz74-@iPBy6f^(xixJB`Wf-v4QO`UzE-6z&KS@1 zYXAAe+g--EM)%jvj>xf+a0OEO_6`k)0|JYz*UosdiY>D0Pb501=jF`e1$rZ@ay7-A zZ}iweezG2s69@?zGziTwx-VewC1a(0&(yGIrAz2}VPuP|_&VBNdi`o6M(X<>vl7p5 zj;&Z_qro_ncQ8tz4_@4SNP^xyL`c-@zF>3?Gkad3iA_+DC2#VSb0^g%*?uR@uBdb; z-Kk;UR$+?8V>`oR)_yn3Yo~NK``!2b-5h@$uD#qKa)&)c7+cvr85KR)%a2v$+Am0a z>abs!YFoBnl<9fDHIN&^bx=}pukV+Z6qOy6RWuwNlvnrPaUE9F%{m-bHtpQ&`}bP| z|B;NAAJvSC{;@UiAIa#l=i%{xAfq&VzNFG(S}6zpCUn89$a@dy^t{f{N~Z{mwJZ<+ zIlsaQ0r<2X<{Vb7O7L?awi}o6;ba%pdgEj!p)S@LERn84tCI*yrIT3`U^*$BbAe-! zO02C8ROaC8{lc2!)jEFjuUEKaTF=`~LP&;0lf!SdP?fHI3U4&?rv9^;;4BezGL zvdf2G*9W1l^twA0Lgb!u#i6Y=3ciw9Z{@~VWqgk4j#v6qh+eBm!8nphPTUh4>)z6I ztKmwiwkUjz8)Tl5(LznX`TFa}n$XX;S6jGO9@l%tAAjE*HGcj5^K^j!?)GBt)!nbF z-H&&_Z-0EfFOVS0MZ;C@!br9!c9f;SARg?(kvN3|qH?j=l~Dx7rva3sx%aXqip1wM z5JH5&Q&R2*rMsvKi6aO^9MZ z`osn#)vLGVmw*nRcVQ~F!z9WF#OanWg{MrJPXx&Kg&&=oEOUpEBfY@PqFWI*ESsDx zlOb&1w;~}ef%k$N=?qjMGSA+e+CVOhLv#!5!lDW(FBpJNXtQq$4T2t~w7x|U^S|`K zqh`J?otBP=Sn5Tbi~a!A=URLqgKm}`g~fhhbz`myRE`G34=-juar`hs$T-mi&?C~} zX~c?ctsWr7r`<}-bQ)X>d#bDjQb_!O*z)P$<+GsXVGBJ9JIwyBYONTQTynD|pY5(v z9u)45+ZrZn@Ity0;;w(+^$CkGN^mvqWhu2;0dW?Nq6b40WQI~&PxtQtrG=y~kfQ{m z>phCNylmOCQh1W}f?Cf-1QGT>iwktnwZ$0g@|bT83I!*$qFTzbi%MS9W|qd=O?^uF zdR~&%A|4yCF(e6h3^Wk6*GXzA&9~Vomeoo}IVum5mfwOwm7AYZ_Vj!J;rlQ{52Q=K=4nWs1)^^j5&qX6m?dpd)!SO}?#|!n+9S|2>pifk#C2W?MY_tKI9vvqv~TeS6BL{ZX*D4JYpLOEHyrI~fnghCxN;#d5CjEEag8#7QZ{ z5wzyHg)>#AP=EsiU<*ZdF(UiW@`5eq6dz*+@P-GPT$*PM&i1fSA(fSLxqdVC3j1Tu zgvV{8qvt5}l^r;0G(@uXPQBIug}szNT_U9oW$ESkuAf5rt~QTYp;Q8Pt|DMsb>tJ< zjDtFV0;vEohpG-r$8k4$et#BsMU>;t<*r&{8h^=VbjKxCMesB$^9x+zl95m5t3us7 zFn?qL`d$Dwf+vcKO;=$6TZK=5c^Tj+zDT_srVLs=DmtaSVR`2nmRHR5JbZp*I;TIR zM9CQ-8tB+RbAF`VB^9eqQ8*1O4X${hacH!JL9;l4Lxa}ks9HWGnc^8%ZscuOPlYu` zZ24Nv7R@p2^UXqSf4%5$0W@<=S-rk`e8e}brH@V$j3_>C`H&UBEeTgJ7wcL&B!Yir(TiZOFvxf2`){^pir3%4< z27r2^cbov(FQ;hs%DLBnj#nzI)3*|=C-gkr=5CeEs=M+<4B#OvohDvCY2I0=1?HD_ zMdeZC^K-Y-1*qh+uu>XgpkhKM*ID1lI8}mdvSYyxN!m56*X1H7)pae}$j2q>1W+Ot zG(u)1ub)MBTK2|fkMK;wUueUlw%8HvMDwTo1YaChh~?414RT54JT$ySn$h)(r0$lF zX8vGTgKiB>v5D_Th`RBqu8M>X_+xPw!`4^aI3FcN5^uN36-X*S-lq2JjNo#XPeBLQ zS_1w*B<(wh5wFA|bwA^LIwUv@%PTyvF1(&^M5l57@pM7*OWY$va|n{*SE;J{J7lly z_245sQJDu-PGStq@HusL%8Eub}UN4p(2q@CjH5 zkwYCKoO+@9>kQAg+em}*&IWk#J-jqw253zZO%(o|mi~I{CUOBT-SPfja{gK53}7)NKQ-XyDd8>(1(nPNFararrr(Qt zfyC{&DFt~Y_PC`fxmUCxGj)N_p+N=+_@f%AkTMTHCAVr=(3McIJ|ZBc=4}!vNM_3C znPss4x<7i!n?{U~ZJj{9L7=S{pJ@q{Q8=keylYfGf&MFK$l@N>8-sZBwBc;*s%| zVZEX7Ez2lxWMtL6^yqxl2d40tv#5zM@Uw!@Jh^BCMARWXU`8CgconSzk4|6rvjWB- z&Vx3*z*#py9dQyP&)mr&DQ$Ju})OI-a~7GyZm;-8(t zi)-RL*W+w)6RPAA$}QuS?i$~hSS9e3l2PMxNriI{&n74sB`R`0PDe#kCgQ6vB&OxY zD5^SX1mR@DjH!Vt02A+Y?X&dM?$jE5+WdV= zc`81>X3jeN41>7ztf`ESQjzY5nN&Tg=u9Co=exel1JyENLD+y8*;L?9G>t>l=%a)94mS;F>aT zl|`_gQ@a4+)QgN-XShiNhFx>}g}CCkuwOOP|Mtw7Ib+QAq9j%YQ%HcJxW3=L!5a%y z4_fHK6cC1hRPr@$!bMpuRX4N<0B=i{7AxN+K3Bax-F&#!KBw=|5T}SS9n~dUCJnaO8&WerqW7pTd)nt)5HT2ru2sJX=%Eo{RavSUfihw> zz>x&-fk-tbG)G{)if{=@Z$ejS%-c$kQA*AG<)#pHgX}*?a4psF{j3onB;};36*j3w z-N|L6tZOsefaVBoiB_rB$3R>M$RjllnO5MgH|s6(BfntnC&Acu9R%4Tj;;wJ(O+6e z5@2wj_!+6ko~+;6uE(6Lw@_naKlEfCv9vd-b6UD*q75s!jc(;!Jd!*wxQpIMHu|(S zzWZ6^xYWpih5sP2QJ=l(!9^oIHhwcflNF2n$lPPcv!G zV3NwO#mPEsE)kSS5@;!CeOzDoU1Q-6I|!AWCZwTdLz*vA13^s=2k9 z$aWI8DVMg^g4+5e$-*M(1~b~U;OLfGjiZNc14}rOYVF}nO#z~?`bZv4Nyyk;WV_mA zyELd{Ly~LfZHE%FZ7Z$=ORuJCyW>C&T+IzRr;#mR@cwb%)jT5iYl-VplKYgK>GY}- z=LkRvX)gwK;VyTP99a_Gc7dc&U{e%%rXfWp3bfutUBR&>$qkI6evK&(T0$k(WUys+ zH+Q2>;_xR)-RH`?W!&m8v>WJpJD7ud?nt}oJ*oj0?Kyc}Y3SDPnO~B*=3!{3h0<_K zwb8GX!IT%dczAj!>)Q29IXT|JGIh zwQpwG6Awd7Zu?&bpqszr;1zC5N7b=0_IqZwFx+xHryUG2g~_S6zr3TBb3cN;uHb8@ z9Qx`ps0{7%#28G>97=B+$~*$YJ`eRy4bI(LGdO7I)tLUl_>us$dJw`T60=~`QBsz$ zUXf6eda(LtfS3ubnrEbL0%zQIq#iWj&4lS~%2vL_gw{1uK#SJN13--qhtPh+bS}CVAaKWz8}mddKJ5igPJBA%A;La$I(4G|$;}&1#Kd6L zf{&iswf^aN)NXthQLa5cUNa~cKTf1QsN$M;`%a_mbmBo4K`9zxi9dm&fg^^mh8W{8 zBwmhy7~zrxP~`!PERQsrIyS1?J6a5NBCu-K$fhBLWEp_ZckkF(S4PK)M(cUT62A}X zb@y8`nqaE~M~_A%G#tC%c`zJ9U<9;{1*u$&V>2ymfpmSLmq-MT;Xvb9=7V%zO|kxL(O?*$vk3ZdiHBh zK+?_e^uD&D;D;%%yv97`Z4U=}wmx10L)yMPi&q^1^zB#(?;(qzCk%9lr{V zW2WOO5PIjyzi$mNoPi#lfuHbteLEq`Ig3Hk`fTx?C1PNHJaa?=F7;hdEax1LAneuW z$=T;zuCsid;A)Os$Nd z_0G*r{PT*@e`>(}ACBiksQ=+|-ZyxEHt%e2>}YGqYe&_zwxqZAq_?2bTDn`C>zW&o zjrISb0rxML^SX+^Ue1f|FXs{e_03c+q9DZsu;!ponrL&TG4_R-d}X1 zE^DC}C;R_;MgNC$y+&sLgJty8#PV;7(ft)&L&vy4O875VbQ2YAB@KNA)xTfqRe$(M zRa{0zOh#E$N=aB!QApx3R7{>^0_mzSZ3^yrBt+{4< zge?@w^FqsYx|8IGgef8L3>JyG-woD?z0mlK&1;#h(c0kL&t)_)vl#nBcAE4j{e@F& z)BR8{(yg*}qF(+Bv8y~UjxS_)TiW;IlA#%Ug^lbR(4AOjTif+FY4!&}8d`5q*7z`a zo3CVIo-r3`gl$iBWc1heusPQJl{l?+EU`*M_1^HS;HqijJ)BQ)hcaH#z$tA@7*)Ds zd!NCGKw&9z1bG*XuuWDL8ntv*mh}*UevW+EwTF5t^0B;FxduydHtHW(s8Y3Ko@~#p zMk%uyt;S%@T!9jx^(D))n&e;|buCR{Tt9;5;;j^mboS?}jEWxH^7h1fc?R4ac+;se zD5Ka6%Ri3i_?69|EbFX2P%!P}=h$G3=i$4EuM&(s3rfQs4ubE*(4OkVbz4VU9^=3l>GzhjyE=-f8|(dU($6y)a&Bk!1u>cZ_1p@A49!J(_VjT#wLpY z%}}q{@x`>367S`G_pS5gjNu>Mx2A87FXt@&=)Sc{asIww_s@6Vz7%=29J0OK62Wb> zy>i;$=eng-Y2vNXI~cN9lqy!w6M=ZdYPZh;G@972u5+A#1SCspS?0fD;V!sgt-GH9 z)Qr4Qt|nx83j@%5JmeYn|1@Eo#3OQMhjATK2Onm*m^^!GoRr{$`+`Nf>3;vKkgm-L z<65?$&}(O>^9feW_v(^2M6MmM5aWUxd`@YYhdt|(rXo{lVue-5Hz1ZC29PN6sZB?| zeZCjo+Q|~kxJQ|Ot@Ax3n@)d4#W@^-iq)SU{Y@=5G{s}XAE;n%hht~1Afdht?I*u_;gPv1KfY%Cg7eHBYF2{c$Xb`e|@Fho+k@uaQ`n_se`FO3xuY&zXE z12C3mXukJ<}PFb_hu8I+>oqH;=g)qbL}1Pc|fgEd#0-Qq|S*~4d#<4MQ@J_J>Z zau!6#%9gpxx5{9V=^ye%C=1~Sna=TifrPs1rV;g*6xUb|9l5%+a$8pvw(PK~a#O{d zO}U6=B$eZsEyyhebs6#Dhsaoveri8%!#bkF?+=O$BOEQ6 z0l8kmQot5KbI#TC8r9^?S`0NRC%=^>?5KC!m6HaL0t;kuEDwO&M4d)ictT>YmZ{tg z>ki2%;+|I%#X{A{k}^vfNY17vAU91-|^TW37v z(J8^U%F(h@fRqVScs3g>pb}&*ZbOr@hBh}ikmgom>=2+CbH4WaBtcztmI|e0^fW6y zz@N|Th+c)*lQGUY@rSb-vQD+ljNfX>mXblWp@2$mACDe;7L5A-*h@RG0l##7>5fOS zM8#?^c`z>mjAVH%zIGC&CFzLVbJadK6EoV|F>BHc4|7-P3YhnSyju->%oGI*nIooc zHvax(@OIn3G*z^u`G*|kx3AmI(ql&vW9Cflqd}C`vAKr@iUQSQgaz zl~rA9KJ)mQ62XpIO*Fc4^f?T9E6WSNF+I3tgB#q68kM^y&-=3G8yG`VNx+et&YbEx zTFthuD@puY@A{Ne7Kx`^7hQVxCG~v!gg=nE0p3A$xPVS|@Z1lBhN3Q>VRyUuQ>Guc zR$1__=q|s0kM@wXL5@|Beqr5+4%Z=L=wlwn!N&kX1fL=aLp!D*U^39jHocoa6C^uKpW2UGY2=iVv6;Q$nz zZx7C}=lR6iHwP@*F-O)i`MSDGMux?m7xq^E%n<_>@Ycg0+bc)_FQD4rn*tEmQmrPzp%M}FiKwq^ zQFwikguuur-=1MHY6w_bF58i=l>k=7MXX9duLS_b%0kQ>qKAXT7>H;+(x@P7Jf9yz z`*?(>o-trnXKeTfn0ADoZZw7w=~+`OcqVqCAeLkS1Sl0*Kc(1miKA$y*isf%O^Ptr zjdQt(gglG`hih8S2xYLw88gST+0&AQi5PhjJSPq1gMQ$@^ClH46(vngutFxhVD{#9 zjh1N!$%c#G%!@$NMEFWYrVSHQCld{ItsS%lmWn{E_(|-HNrt*|atk1}(j+ESQVD6Y zl?uqlI~gr0S^rz&o1SD1%oH6=Hz+L8!3gBWDI&cuYQ!nx?VaKTb+G)FVh)VL*hj>{DD-0K&~0;-zUUaq$??^rDAa zCC%xkn`w2E>D%ZTZvx)zDrY1!W>~u?VYvEo?54{hGHmnX8aTxo?L@lqGY2M9R1-3X z_n&;a&b$R@Sy(4bd6Rus5q;Y%I@&C}KqdOjJ4@&8EXyh(ak*4vYd>*=ilVYK{h55y zj73uDbe8gTw)JLGMOf^vWzL}yO~&IKxt^R~X;1ba<}!JSU_0cVB;KzvyeAocPjEm+ zM2&dinyDd#03VPi*b7mnBX&L`boUWv=y`^ue*Qi2F!?;DVGXX9yt7MTUR4py5Q%_= zOlNtL*#B zMyODGQRe=BUNT*%7HDmr4z?&0rW7r*i6}bKD{@!_bEFG7r3(+8>ONH!Ut<7 z2xqzy`5hEL4N5P>7k;}~6r@`cA^}!zKycr=7nn@Pg*%YOw1|k8X}mfRI-x3kv2GC9 zQuu%XkxpGkn^bCJot?)8D!36j%nJ;{G+1@P$4L_^9TtftQ0nCnt|btC>FpTO6L9Dy z)EprKt|39?~FVxf5U&)es^T39%T;av{=6Wx>iJ zS5FXvH!vaQ4zD6SFK2g>$l~*|)0s2uU`e|5nkPCp``Vp~N zjzvS)XAHnx0&8$o;nE1Vxi~*4*CmlemM?rHr+G-3fef!j(!Ld^|A`DHtznWBXECXP zyVr316yqvqJZh=An5q$I6%&-K^}f@s6@4ovo>42cR4endR+grYg1ZjFtS95BT4rtyyXNU-+fu*-kfaIC<4|XITTdI zPAnVa@;@rC`{AR?bU*WAq4UWMzI=Kp+Q{4-j`>l^GK1{~kSzH)Hmy<~OitRMO;*ld zU;-|9-9i%A^0KbQIH=`ux3K@`mP`yZK=e=G{fAK5&)vg%TdFvCc+)g0?QA`{Vg-7l0N8X6>Sxti#nV2W1L( zUIWNeQFPWomtB-Yk6HthRX2KRFEW&gR%ixk*x}BVzpa7;WusZn;inNxICUY2>tRLo zFeG$w)Aq_q^(vV5D!%Jgb`q1#M5<->YTov0(e_aVRO(2He5lsa7>zbC?X#)vGgTM1 z`O%1ThG%%wC%DN@AjfSU)mPInH*GxYRm$eU=`WO^u1 zii{$6uupEda9P+Os=ho^$iTG!SJ3co$?(Tza9!qbqmxKO+lbQi{efBd-Yil;4tWWV z_R3>bOXmew~Z|ynJw}>uUQ`3kovS``Uzo;*vb6# zn9P-JeH1NeMDN?!psU*fk!X_PIDbOhm8p=Y#n{hL!K9heJ5#|vh|-Cv)_JD3isS@Y zkHQBhz}8jd-sl8r+=Plw58X^PhW7;c7j%7jlJ#2z?ej^9*%X`aRNP<*NBh)r!MJQ( zF^@F!1*{W#XU4yTPfBYxO^9iLCZWyZYn4)${it$Ufmr+0^s{o-=k2r7>j5xV<>%Y( zX+@FGskIJIS0u=ZW=H~2#w#=C&i!95W=Ov2S`yzMEobMMW@a(aoW^F+V==3J@E-!u z&ZGvM$7Ub;6E?>Z`i#xhHcbT{4r95^p~cQMp%K1qpKJ0be9t?KAS7AK?Ic_u_$@b& zUOkT)H~%i0(1Um?-)gW$C!e!k2YXTn-enRHyBOetmuLY<&myce8(x=f2QaqbAp&1$ zkUh~SV8{Y|K3(b@BW%$Eq*oH|Q$q%qb82bWp3N+Q(3ert%UIgW1JU$D&SA%5?D1wC z!pGzkcL3c_m4H%#)h%BOVS9o-XM#elu#aXdguqow^!r4~%q}_up9ZkO7qH|@?(1zq z9%4Yc0ti}}$2eQWA{nlkpqQ&O=)G5VWMW7RkvOtCiP{I7u#EACplViTbCZ6 zJxB>XEOF1@PT6+wlY!fn;x>iKx3lDyq+N^UV?;v%JB*mqa+X`~s<{3AQatGQ)V23Q z?)*5yNPv;qds>rwG1&+kKcKV*l45cvlyohwV?VQ_CeRP)wYskalaW5#f3R*)#CO0H zNABqd{BcB@P<6nL>eP-qsPO~!0GO6wC>+FoV+>;%YVF>S?j&KuSOFo-j}(wQV5mbw z)zRHLppxX6X6iAY!tssH=6nbL$86Ae$FbqrF`jGb+DrBg^Ajw&qrHw3ul$oE8L}i9 z;O_4e&Go~JY>pGZuQwfEZ%KyFvH^FiUopOjzLhz}$w_6>KE-`cd);wb5B*B=jE0!u ztTrwM{mGdXx&i5jGt3$z!1$S#5Tq=p?pjnZ_tj&qDVr1`K5 zD+bFqvVkR(Cj1j&a{+|oV{?F{d)$Vj(lX;<7rQ^>7VUn zPEVhK+BGW@C&*w8Dn`V@Ph+cOGf0k^f-^kI|7<4{-5)A2&r2j>`-Df%v>M>xEm~wh z2`NJTnZc*BvW)#e!zX%W|8jTwK7*gV=qNa3uJ(&wfjjr`n~i>wu5e|V$G)R!sM{6=`8i*G&w`~){LxN!Bb=__Mx40f(4hj(RRt3Csy#^( z*;@}yo9P}79E!76aXT z%1eyu8Wg_K-kYs<0>om7(|d|PlL#_X0{U1%A5L0{Cl@?_!f$+^!Iv^KoboWFuVaJ_ zl!V(VIIn(IOLgBVeGw(2dRb)Xd&0SwtHaq0O2KBN24<^!b6UWxTUglTrBwCk5UIAt zI%(1^Ha4LWtOgSW_*4=T30$S~IPZzQyY1wE+y9xtC-F?pumAT9zM?*{@o!h^Bjh04 z-(~Q5HQ}1~7~#)$vj397FF$EHYB)S;J?-cI+IEi-?kDti{v9LmoOWSRIGv*IF~Vs# zk=P#?L5b(=4~%fuNBN@Ste^H@!3a9~K5>p^7|s{ZZnVMnigFCj$=nj>iI5UrUJbWt z+V%tCCx+JI4kLQZq1top9vTzDg=En{bDr7eOT|2T@FG7o5|6x!B*{$6nn&~QHc_c& z;R3%DJ1r|NC50Mmm{pq;E4keHbLrj^2|{V@i}Rpo6to=cASqmezC`Pb^B$h+Jm$g= z@Mbi{HM3dC;owy(DHHV}tb{z#LoUQR=neeAvF5d+)Q+Eydt#KmlS0tf$o#XU|A)P| z42pwKv%U%L>85cD?(UWZmqvmGhXe^0Ah<(tm&Tpo?(V_eA;DdO2MreBX>!kf&+N?X z?9Q{hv+q;&R`IEeFH}+0=YOtq&aZA+@jG~n z=risVI2z$db3W|LN~gV;`s@`)7i# zG`2u4mqC4CP_5}St|Ba#$wX#IYyLF8VK|q?X<$h2<}{%lJ&zefA6cL9EU{lMk0W7V z*jV5!X*?{CD_`c{tdkjRqAa7+ih@rk_-Bnj=u}~lKPSYj2aN@sPt(!sLUdet zsWV;1s4R7)Q3zq5Q7t2oTMz91U};Lrpy?^XfW>hqR3QOizH@i55VOx=P!6)^;{F*M z70rP2!bcgE!iqbHiBz;p4W8v4h?ZD(QC!o%IjIo0Z}+dtxmdU#paPdj3Vs_I)&3ElV|m8Iw4JxBBin`pcg2 z{nsU0i$UIBY6-kw>Euu99_7@E)B%{C`FR#EPWK9qa*eIMZI!uddD~EYnWILVNxn?h zkga%Nc#d^XzKuhy%_XX6*w)lz%rq~9(`Vs|+k7L%<0xmnHY6^=F~xD6ryNXz?7Hqm z|1hoE0eAcC&2ns_yjBjINvyO9XfhR_2>xZ;@uVG-kH9nUbqHmlch7ontmA!+8p3FZ z0|-_>-X1_v@#IvM=}D+1z7bJ#g?W|>YtiO5zvdw zTQXdsNtQ_K*;?Ig%aAa>+TV*kpsWAWFy#x55m$wAe{O>+J}IMk5A}e9r4hayrLoMc2%R1SH{tj?T}-$0)U5FF7mts@fqVlQqx83E76m%DTYazhv50i zI_2a65@$L%MQ5hF8}?Yv+^@-2zIoYcAdeWGby&`Teka>a6O>yzL<}>>5K0Ec2Ek5B zGhKE?hqipXcdIn@V8O`I*o3a9UhLwR5(RboW#a_YM7+s;i~*;nGbwIp9m=Ih$|USa z@9?sXrRQ6LQN%{ND$crup`MliUrG+8r-g#blVz7aJL@Nq?~j`(13Ng%H&f7M=U6=H z&#zy_NwFeqzz1V4+kSdUU~F{8JLe&a|2f<;mGlaU|28}5SzH!cE|(q@At7p%yy~ap zbBrZ3u43PnU5agNyN)!dJogi@D=3bzh!>l0V-9d?Zf37JcEt1+2tdM~pK-?4|0vYu z%4_K0lI4Zkfgzmmad_RUqw*sL(0$4Yh;+sI9*;Rn!p>0N`ly{8Z;bY+^GP`}nTIOYWyThuL=WR*m z-y9#HFAesD@rU#Fu|z~8&R|P+2>hsT8jIvj{f&+Ct0|+6?`Eeu`hx}=92<%nkNM<` zF_vkd5YYDq%Nn24Z`;5p?9$jSAXrEw#3zVD_8rQxBYMRul5ByfNCOK6KD&}IKLtoBFLaYYbr_%lR>AMXH83)t=Yu&Vi3 z8xvV)6WQMvu-{z)AuuTWSP&dLf-f+*J5G_(nGjg`C=K!`yeX7h=_ncfC?K2%iwfjP zSCnB?*xIZ@7&05hHQSf=cZ~XxgoOZlei4@IXarykS1_38!6hayHby`Od>zEm|22l? zBt|qi=13zpnLXx2G?u691GYEh{xtHe6FT$&k=_Lfxx}T%#-SS8Xc0u!?Qr1yh@+up?#IefX0Ym68CyQHj@}Z^`u_UhEN=uaoR9I&Wt8k2r-gXyqq=~!pPUyf1Yj!|B* zyP<%A2wIu+cA5ABR8;iO2%9p6fN49YnRi(}t>V>;U8@4k=T>bLo8CjX2GR8=yl78%eY-{*zCXXFiDfg`1}Zm~fwZ zv(n+8#DNTbSn#n$1)e1na!~Pcm@@#1QCafm+4Lj|ac+u;?6R5d3J{_Sc0`K_y72sq zINZT5o_jgrs5tzP_ck~AURotem1vqjSXu^4XhEfuS{&0_rTlBbN4BN2gdB_WrO(bv zSLfN+1W0F^e8 z-U3kRNf?SqH75H@%LS6cB9L_`z;*#(FQ{!?S-0pz`}CUgZ3>nx@GYI-^LK6{^ydJx zP;9l^iaJ7UT=rUY_Bxaa{Di0myl?I(-n0poVT?v;D-;c&?rNFJ%0~a{%PH=t_W(6N z31wTJ(o>3_W0ZI1SR}9w4vg55nbL{HK-Oj+b~I^X?=ngtS@}Zq@IuR86^`$I%cNlI zv@CAFcI#|P>wI(T;zH|kC`btHi**=s#4|DL$dUZ?L{be7{H*CpJmo&}`Lv_Wc4$_Js&{eZvTrM5RQ_%6zn7 zZ43rx9G-a`E*uTfqr1Qjz&^}`P67jU=V6~rz_w1@y7z*aD38Jb{))(fkjcPyO42km z(Z#yhR3MH46rrXx>8+1?VgZ=0m=ct?W==zcuh*LoqXEHo*Yb8Gb-d!g0|+fmA)HK! z==MlhYMxe3TOOlognuch_@aG>n*SE{Ey>rny3jQw)cED)7BWjLm63A^X(p zLx7qG0KK$?`T4|=_~>b6GjXL0B?&(22!Nn5M*8 z&qondo)Ij_-NZBbxrO&5u2tc}Q4^P`c{lDI@po7bBauIuQc7E~%K!^iBnxg;^W|x= z^=S*{7nF7!L*>Iw-a^w&&ljmI7Til1qMp=tGe64~0%f%>DtBR9dYHTGg458KX495* ziXPX=mLKkxL=6^KpD%CfE?WvNt?KFz`~)RgF2hAdpmd7uhXdNuu+~c#hW3}|$rndT zR;ZNlM@ZuDm#}T#y#lrXW-PIG!j~p87vUlZ6wfD-*=L`UV(Cz<;b7vQrLB=FuMk^N zlisgUq_gbTtWtWe&z&k=hOaX%uLG*rSx7fHUTkpbZB(SL@}zJ0PA;Q(ZwRn}sP8vK z@0r(!zvd>RlZ;4L0lyEel4HAW@x}|OuFq(`YdDVo0P~muNOOhdOHE0 zJ3$-iJ0Wd5Vaq!a_d5lC)AZ!KbRxSn`nw63yUEZq!t!qV{cZ;7-eU$oBAaUjJKzAz zhZJi~yEC*E3)2&)Qg4p{bMQQ>9(%$?gLw5Sdj4#1|7>D5++zPcYDJZOe~)2=OBqA+ z9@xnO{D@gmzKoSmD#n&o=R48OQr1$le7JmnxJr7o{^Dp;?`S*y;Fa6a-ZEAT`7oS5 zY&+)B*?yI2_vk(*uv=l@^$9A?`1hn?K)>FevXNb~&`|`(J}z)-`G_v#=Rsryqo+uu zb?Xt2pVXc2{^e*r!RHf|%5Tzt_}t0!b>?p-Xa4U@@1?2s z--c%vC))lmw`cyH`23%J@4lgi_SVeLz0ml4c1uU?e~a%8C3O7z+cUPA<(8kytkO## z4e<2RcYl+kH-e;x{M!YZ5i^XB9$w{!ny&62on1YkkPbUX7pU)TW#eFFZEp$v`C#|n z%GTKYgQ1DV8$&alx5gSehD!gC(D8`pP=BMWt|zT+srXtKisz73(#qiFg!rRchYJmMPs2($95u(0#(2&bZH|Rs!O8FIjkYwNmFu98o^dabv#r62 z(M*3u)0{S#m0EdV))3z)4=6`6c*8V)+r3YQ=lFe2mVfu#)!F_B0#CKW2^6!wdG+?g zyvdJ*ICaXdx7<6czA5AhiVhT&2|6lw9o^cZ89Q4s+Ps>kcz#szrt4x|6{@RD-5s?C z;@Y{@fTzX(e2HG_d@P(;zD3Yb~Iz;@4_N^P0%R7jVb?|JI0YP}5tjN*393v6A z(au$QWZX^dsJ8)yNy^pO@q}?q@8*=^Ku`FmH9iUKCp8lI8_qtZ5OjaAiLB;UIAO&l;B6uRqbtHfM{Zue~SPr{< z3AFoRh^>$5Y?y1t;%tN&O=^U-#UkWvOc+T%XAG``{(M53wv=e1x}x}3d|sW_ zM02Nd`o9>TFS}X~<2}0CfJm`iZ^o)yU2i3tlwEJ9Ivrhq%Lrt-*~v+;y4fwrFT2?* zsXw~eujpgBJ*b(nx;A?o{!(&KNk-wBw&p% z7axpS5s7B6)I1I)^TU@uhsF}GYF|;`g8JLDoLYC@y^_zFSG_*!?XZlRz=!_hJjf-I7}jKgXu2ZQ zSte2Wsk6mcu!E92;ZTLbeev5HwY-I@#UOK$R)gz!Q^=hym${O{?67Y|+nkGoE6T~t z+(`kN%Dv(JN@U_HXjoWRfS(hQpJDG(aacK)u6#TpynY8pf3bZUC1_nRTk2+DL1kvcPB}{M;QhP|4 z8v(Bv{35G^(o0wE!Qn6mk@O5f6Kt9dx-`CwUHF@#A;Ca(1!=ZV&l>%*vZ2z=sVYCpY462u;> zI|cyKsi3j#_09oOz-Z6HEYU&yNU0L;&S_viq3K)t8K&%X@- zup>+okSk5mOge^rAP{!+>cSiJs$`NXhHSzuWV(ZIXo~g*zG-jc`T4P5_%sy0rKCod zT8SU>@sf;y#7-Cp+spcynvnRz?#ahdyPRTj8ao6+4;%jA2kK?rRM5G^Iw~O)K-L-TA0XcPd^ZJ0%}J}t(=AymT!L4w_}u9 z2g)w46J9p-%a_?E3@vU8TsDq>(ISIo4-yu?Y(gUFW|AXE3-71EnZ?;;@0DFXjaJv2 zKRg0Y6X`X*-e^4zFRxJML{_1rq`kEK@VVueqw|*8pMIUS< zd+?6^r}J|P@3to#rK^cyZo>8%GCCrPYe^ET4gWaamRjW+HALEqdcCk7-7 zJ2=iL)?B4)g{Mb!u?V6C5$5BItP@3}BbzW=sSAUzr}ES5?I_ds#_wD_M=fHk&g@67 zBnL_=j+!hM;Q51OL`91_q!3TCcB`4IQc-9((pmcs=uc{ejs2YbYmkXlo|p1)Yz4<_ zJJN5xomoU#-;CHNM3^b#_QgOpsOx!en9y-M=->Rm<}m_C-`@Y1yS zOn$kd!@m4F!ujdwQ6kX8gBEMB%k$})D`C{rujk+*-j9SzaMzcB*%<*j3J3dahlgkY zoGDfbFQ5kCg2e7}G~)`dL`nkt5pePri`^Rp^e*5e^2Sr>Z6~snVC1NEMX&Tmd*Y0# zPtMiNY74J|1axF>05WOt*StmFevQqA=#`UA_R9UwJka>|_93 zW-$FpKqwtnJOnEPUqD9$xyXpGpr5}~Ly!(1TR}sMiU)1ZHxPa;G({;CYHM=Gg?!>d z^P#ivUz0KAMbo+hCGu%;Nouzuc`W;S!DjmMJaK2L42dvA7w-r4&TxbC2~09c<|hn8 zO#l*oSo`t7{X~KZXTCfQ{)4zsQ5*D!UWw}QXSJCa2NU!s{UUJWMp%`hm~qB56k+qe zk%b^I6E_4%YxE@nV7X<3AR@M-j(w&9Sg^(*bHTuhf{PGCrg4d;MbXX*pu-x#!n+0# zUSpHU0HlJ@8?0j%9@;Sk3N@;C1c(ZyvuC1ZMX`|S0TmgLHyscpr5Ik97=Zzdke*;2 z6=cH>2e``Ufr;pWQ~#X6zj8Yx$%YMKk`<0F^AtIDrYYH&v#n>`otW zBS@6O_mMmyCN|7Z5aC4PN$H6e*b+@qfQ!id^$q+;YN+y+l-s`ks6gl+K(v+c^kDrX zpo7KI8F%Q4?rtZHe=PxtJ?5hffWl1E>YDp`5@^~dw%VF%xl78qU&!$qP&yHc_9RRh zI?l5TSb%}KuSssCjAiUf0f;2`UU7F9a`ZN0Wd#coPDgASA+ir*WL5u4`g1T?elOf7~r3+Ry;iQ*#B%06ERlQAMI-IZ1oyG%x13 zy@EfbZa73=rH_zjAOh2UW0=Jgv5mL0zZA2GU-I&$7KNE zn`d-VAjdcGbmC`G3h=E-0(vrnSSr)4C^P*HgOI`L;l3CNCf?~P5rJO(8FU$pO?%=8#l0NHwOmL~rZXrn zR4gyCnzHQ#4^c*-mo}R)D#s-|FVQfd!zjR5L-i$jz5yY~F_~YBP>{|zFToe}qZXBE z6JOASfPmL}KrjP#xVgX=g2EK`!n7{4hQxRA^PoflfsBk4_KsXnP+APAAZhATomf$V zZ&3n>U;u`qry`zpEkA7#tIU-@*|GRGsyKNH1%IHpVXZi}D}nVS)3vJzB32TcomppC z6x~%49fL0T4GWW@M1Z_BIy-?c>dhb_U!5!8d`M|EcbSn$riX8d1E?(6uq=BDsed(j zQ%k#+zg+30@CTS86qWBPxtwMl5;#>Zk}IT|#0QhY2fJT>Ls*K6rgJo3QFu`iE>?^> zL9UBZDMnt2udPMc%;$Pj>DwfDu*XZ%T$%N{ipK3dTxMB{cNxH^D)g*?K81j7pD*qK zT)?=%$F0qmEKuF$Dv${lqU)`C!H89)RbwAjQSQoE1+J{;tO+9&Xl_bV*P;M7^S95x zpyR1>wyTv6)e^j|wH2vx2GtqJY8v12(lyr6yVO}n)mahY-Jju6GQ@MbggC zfJ61%udjaV;?k_u4RP-=Ebv9sa!zSL0G5O`YnCcn33Js)76UdE%j0fAdMS;`wT-Dm z1Uj<3>9>vbB8?(zRdF0mDP7q)#cJUq7M1!XZD*yWg2F^|s8&j)E!Fk43(a{Fj6oNI zc_|GUC*p{kxEYmbYyr4%{r~SdY~jQiUS`43tl6g9)nD@ z7eYMmhkLt0eYQG%6+E9DQ~RK)`9FN`I^S*|o&Es#{-D(UkOyKN`lq%4^ijvljqwpR?!O@zw$dl?m_!h2HPDvpU)`<{aDVEob=tKnm zI*{NATDW%)wGx?e$>7tq9#*BCSKF+g$5DdF$upwp=(<^_VNhEZB?bKO5mZ`C@qx?w z%2Js=jQS1jOu%`zu9QsTx4Qrv)k=c3l5);LbBP{t@&o|!h%^Q8R+Xzt1o$OpaOEeq z+yOSO5G|s}Fr1Mr9C;&JbqikYn8U;vcgHwWm2JbK5@vEX6# zO%mQ5741*}=vdfr056yTCAK(-4I;?QplQg&2N0O(VM$1x7?&iCbX$yEZ5M#=pon@R z`8*u7b-?rNPNS0v)VGKtHGz*{i*xGAI$!5s%~mT(19;&u1nbR!D2|aV(J8Yq>o@yvoyNOEaE_{5>!qK0crI)13|Q zm<>vs4QZVX3l~^t0xSvuJ5OfA!#Ur1gz;Bm#_G;-+5z3e74|zhV20;_YwVp-)S5t4mTco$2`UMHPJ=18l9|5=5Qbtt6 zw)VM=!-WM@_~Ibpbg%yfwr$%%f`Q)R!NC^RoBp@flPr8~R-7;uhYO@I{BKcK)8U?2 zA2M_uE~LZNS)=Wh9o3Qb4q{XtTOE>bkeeGG!FU~2R~+pxAGvMpHc<<29&-O6g{fl$ z+>9P=w5_j|0QO4pMwS_-xOIIqbU|-Ua9#ldAtwYMQ4np8iJxvzJO{++QNXFa9aI2J zK~Cve8?Vd0GmWh`x$MC`*qn-s#Ccm`F?>2TcRv1bFeAA!jsZLqvpqvz>y{itmHu>I zQh{2WVNh^@VkT(qg$0GXl0aw%tVDcRR_vRSZ=D7YX8p`)|-p*B;Q|Qd; z2KCwxgb!Cg?-zv>fPqv8@W89SWSr=a$8p~m=g7{G#CC+)k5@>Kf*%%>KY^Y|o~MJ4 zs-AIGDBjk+xn+dAZ86&Lb+fW~d0X0fjXDJVgnnQ6#@*oNGbSPP>2~`HLx}<_m44*~|Ns-xnXXaEMu3qO3Nb@31!X1(r2r47jllINcA z1j?Jzk5mq>e$=flVMg6HKLV9UDhGj25_j*mLi%%$dw4?C9mOn(a8ik6)m`O0`Lq}Q zzo;CqOFfD0U+=4x>9%?z5UH&(RK6QYmq<}N>@k27d2UgwcBJ!2vinlCz4smhwX2A(q0CVF6GpDm*(Qer|aH2e(`Pm zi1bWPXrObs?~~LgQVX?S1PR2A(ZS{!U52zc20 zFA<;lSqnd*%&8DXW9^1gIcROI#h$)|XBP)bVL$DNl%ryoz)?4f34Aq_$|24v&pl&QEzi5s5=Og~;WE58*H$o%~OcZ>8KhNCk3^N@Set60Z zY05{JsF{G>pcu()b5stNlVV+B#SNl~8<-SeM|eF%f#AcTssbWDSAFdtcAoJZVbAWh zrvK)2#&B{9x4N#=R;~J*j|e;(`hnDS8itV)Jeuzkpi~Z%PyRewX8E~LDo1$_kG5s~ zR-N{T&j`FaHht9fI(B0cyt)oE@9K4(R{VMOT)ySj>$z2jt12bj2pd-?mT=P0C|tx9 zCb$iqQ`0OO`N(Ccn@p;f3O&_RB+?U>i(6+6M8Ov`63;YCv;8^E*J&~7devw#NKeoi zGse-7=dVo@zfsMy9Gsju6Ow3rUo-cPIn}Pt%s5Hw!lm8M#Ff!72A#&pAfd-}?mcey zNKw;T4v5-nSF=E-82=;ZLen2qj%LgHl>kAj#&3DeR?Xjgn;T+9C}_Vo`Ti(0`HV!{ zVjc8@hHrZd5!Nly+o^ZZz`OWNBmqPSh(CG|e0s<`3{BjA__%+fb6RG6>7G$cE8uxm3N4v`ndb)UUB@RmC6ZMI zx)j)Xb0pkb?3u`1f3a~iM&3LcW9>IPpTR5mFa`_z=SE8g3@*$%Ebw1GjP?It_WnRh z{N2l5W=m&XbHjf_qXl}|OHTT`NQwWK~~RXM0OS(-4S3hx2n$L7$lMoVM$x3LVdP*V9Od$XZDmEsq&1Pc0{Gr2G zYXQWL&_)Yc0Nr}f<7F?HF0WucgsE<4Jrp{OwGqbk)pR4AZ@XaQkt(qfDg4-I5yv&# zjFP4)+>Dmv+1-p$l%(H^RaG2ASgU-=ciE`0*%gwBHuuoga zvk-_%j)hTJe`~a`=ie#(-e|FV?XKQM3_`Q*rwTNk>)+ecKJ|$&Or3noQhs2~GLN4l z&%!YkWGl|cJ8d@#*IP0@_Vf!e%(&K9IpBn})WEqo_!S*j{-^euv++FFl9MTUu|Wq( zC6z{t8IXs(BSinx$oqNo2V~d<%Y9U*#j{37ZfWDGaAQnYxQ7&{6^Esf#YL~ND<=^@ zyraa`WD*6%`TE7q5uOmDq=pd$2`K-G)l43HBS|;Hc{^HV^coWJG`5as-oo%^*EMQ4 zZs}z%3uLE4ELc#q`J1QVcf`3PxA69-pRx~oh&~#f!lIP71R)=c{ygJSSO=Vqs<2{H zLEL%0Hm2Uc%-&fG{cdY-q)Ht7(aB|^s`q!|HXZw0rVyf= zNOuvk6uR*YXJR__cah#esS@Z}fQLZoZVJMaAZfWQtc3n<>WGS9#jq^weCZwrt&S71b+SbG?+GPfH7@ zQw?S_1J|;`U(Zqrtu45+xTtVn7pY3U?dBq!1VKR;&P&|~yAIbjZC@BuWKK+Hoy@(Yvf@S?Zu%`;tA zj+Nom2YTeqnm))p4Ure6c<3~rIzRaejQw0yy`VJ>s5A6h!PIW=0wD0l9Y z)l0pit~7jS;xaR|{G;je@v`UsO?KsG{<7_As0IH}?N#^6S4-AO6>pUw@eGURK8l%=zuk}C{gd*e~hf`nBrdS+|Gj0D#AJ*(XHlFoHnl6^Rp7S@S z%WIc?X9SA55QSd-P>DPr?JW2%Hr$_&V!Z z)?jR2Ufo_%U~bbxf01Mn?(6;HhHb*NlBVCNW6tj@x^dtCRpa@vW?JpP+IW6O%vjk% zGi=#~`5w)tdsaaXr^n2|+(xUFpQdKYRwxh499sIH#NS@J54ggdcw8=j>P@;B^?nKYv6#S0a+6ocs<^iRVU5B#Zhji?IxuC_`aQ`E?#I{s zms4D26xX+5KbO^nd6+B6;4H`@G4Y?HOw#*2r9z%(3d%!ArSd_RAwx3BdGRztQJxfj z4JDsK^y|1VcXk$Pw7_yoJ>=2uV=|ow~r~&Hp%TCJPRnVx3c`jjiL{yX}hU7 zcI|lWvl4gm0S)9f)atPY{x@~qJVsHfT5?e%0(iga!_AiV?{z@MXXOmv`OQk_7 zBfX&d5K2;d)Q3TGITUyU{gMKwQIN14Dq5KVu-0jG;&2WP@4z38XPMI;r9U;Eo6q}R z|D(q9ANugmjptq_s^1&WMqSeMl~8@?dX}<^POF&{9LE!Kmbx%reT8rn27+^hx!^75NV+qh_Jyp(cuc2oTw)0;1R>j8yjZlY~sDvm(*85_M zts_R1k(VP=CNdR%BsYVJ%v%_;weM0z&BNc1E;r4zW7bs!${!dI-Olza)Kw*n92g7U&W%UZ)#S?`nrk=b zevXL9LTEh{b|M;Ii9fUKJT$R=Lo_z`wWRT55 zzuYq|)qOd0l@&hr{C>NN{3*8`RHos}nOcUaE+Y){XW5$p9r{`SUl{uNXL$kt_n6)P zXJv2AufoGWh6U99zVg%bDe~{E{QQ^O4u7k8D^0ZjlbToG$o$vJk1=%RM?>4-pYJ?q ze&TslzWP!M{~BJvzax9Ie(?fS8%kFz!~bUJCyW|8^z-lAqF)Lu{u;LXOZH+2ic%pt zrm_3(%|ra1d9r5X-*^0Gi-v8X*VPgx=&KZZAl$dgKH8$>E6M0#kG3d;a_o+;VZF~U zBzwD*0JPQ=l@NY})2~qlmAy~Xoi(&pO@oVTLk@)!9QUBMs8eZ+Qrh7{62E{No_0Ny z7ZAgE_x#jhe04BewvW)YseO#1GEnYEL+u6B78QFaVIeKKJcZh#AJCWVZ!e&>=sT8A zFTl$z!9!46)XFA&ksxqIlG=1;#T$A12dN}UR3F4nt<@o25pBCh(+A(!dD?GEx8Tth zMaJ>dxTA#xQ?hSo1Tob$sA};c6e#&~MI}ynNfB&hhW-b(CCwuF5w^OWp z>A$7^3t+o5ahA|bTH`H5<}tC4L^WMi zfq`ZbDTL=G_Fnd|Z9kgY^Mju0umxww%rlsrn#VQFiUku~c$$4pi6 zvSB7tZbu$6dRv5wXa8Lh$uJhZl0dyBt{Z~cYyFDk%{jXWdFVk^-}AIE#cHC@Pr&B1xFt7%j=&X%CuiK&d#`P?c+%4nc$SH(o&F z3;BPF7x1g_Fq%gm!1o^)9-8fkp@j!hxBZ$KOo0Jm3ZKmxp?8+el`YRCF21)Tz7kr# zp($nm%tNqpF8)M->GZ3j-Rw;7^h^!rkviw5d*!55UULebmG8!7A1{~tLgrcw;O3=& zdUpBR1Mlprv4rSVIq}- zjt=$HJK)GN3>w8dhNd#x`3&hYC_sWKa#&;5`}Il76MNyOO{ipsUw`398b41tQFg&L zlB||UAP7HG+r=`+%}tnrA7j6-$1rdKQQ-NmtCSEZa3g$AwR`eSv}IzHq2rAGlnMDc zO6NnkD-S)}WsQNz^mUvEX3nSkFlFIpdK_O=_)JJu`s}zg#NXT~S;fYbqv;9Ikw#T) zn+iDsY?hk18AFD7M;8>IJK(L_mxZZs%uODx94CsB*IT$NreHn=zlP07Ll&$+vObaS zxs&g|W=0fXuG+%xKn}Jn>Q86*QhD7$u1aF~IvlQ%A&sjT8E#9B5%#MOwnNEt#(m+e zBHAh=K&b%#zA|~I8f?dFRg>56b-!zsRvmFGj%_l6jSJN}L@^TS{2AKp%{2UBq6_1k z_vL)%XB9M6%HniUsX2cY9vGwFDZQb)nfs&gKt!KY6|d^;@mP3(%3dEuHhA(G*Ns)l-7=3j+}qf>llhd*TR?8q-$6nn4kQTDF6GeTwWWy=mis_oQJ z{%qBwEy`Not(^3I@X;16_q-fhxxc})+q^6HLX!JSTXb)}{tsKUnU3vgT}4Vn@h@9c zx--g6#67RxI;NX$8|9q})D{h8X6+5K3DbqzqC}w$JfkNH93{WmqMo1#U%Aa9=WMJ* zW{%W*fjXT0Z{1*;Nyx`9vNV_WzKRjHQC|faT(mTYlul3IHxTkQE~*&C!#lZ7|3BPn<@0g0%|`6YX`>V$A* z>{&<51V@r+s4RWi>LvEl-32D#h`A-Kd-bDuZl*aiGq*T&#gZhAe2b21Y}9xFn)#YD zlWP~jUU%f$Vt%@fl3XS4DE32Yl4tYv z7U{Bu%yPCg{ZlZ-^K!&#^ep{0wMpT=aXe7rJd5aVNBULMWE6Hx2J79fVr0`a+~Ikl z_T8SwSku?~(Tg&-G>(_BAvex?nV|B8Ju9NP_MSdXmkv&Ye!hv;Rb z3|x4WHfD2ZJ7H>PQ(wUEJof{NFWu*x?hh#3&|lJDq`2<*?Ek=4Rqk=50*ANqEa>!u zzRBrJBkbeA2l}`b&!hCMWBa|k~ae?(> zHTdhy`s-c!zr_zQ;0rL)2rzaIFii|FPo(0Q^nNex3K!$|fiDnxG({y3 zw0HKgObm3N4fMPU^uiDF;S2K92nuix3Q7zLX$T6N4T`Y23WDGVNAm^0T=yfXFH?hnrsxwr2M?rgt~z_SUEV?JI0}eP?rhV`+VDerI)JeRcNR%J}BW zm#-_!-_6*~@tv{OQnxDA;rLV9hWMb)xj1FI95Q9#CMP^qZ zfD)W4UHRK9Oq|c+Z^9`YhJEpDhORj@|0bMbRrG`e{O52A{VOVkY;YR5w&+W-MqHaJ zJ=bs4Hj*K0##w!1JkjtZTtn@u$J+VAIrE>wDfQoVnms|2=#Sx))(*@+g;OAuvgy#{ zLmyQ}_!q9=J-Q1JI~ira^oa5_}A&xILV+Jcd&+2D1NGj}PYg>2itkTpF<&+iLIP%j9?0v|d=EOniX# z9@t8Xj3S6iG-WZSkRJ0+?I z+hp+#_h<7G75Wzednf$?(Zrx$)Xd?n;uc3a#<&iIkq zR+2UHW5GH*)M3#+(AiAU0Z-6zdHCpIX?)4OnJ<4D?V99Dl0gi`PT9(>J6t64*{IyS*&~(pEP^(`>QnDV7wJq{u8N)Wq%zI@iqB5=QcgpjhwFuo z_mHFQQ$0bw#TJ&`rY>4m=0iT%@)p(M6w}=^28oXw|A)P|aEr20_qK=5fqRAyr5mIh zrMo*+Boz=5R0KqjZgl9B9J)gqq#L9gqy*_kKycncpXXU?JuBY5zW3ex*x&c<N`P&>5w)Qv$GE7HL=diw?SHkPR)+-GLK3zKR^Db$6HbvG67CN?M7(Uy} z2~iV1ciHrm`MyQtKJ+rz9R7&~A*%$!h>t$J&FcNkPWzI2wKamvM|E`OXUy z!x{_2x`En4C}Zo#j82NH>l$4fW8=>`MuKk{lm#WQ3J~xkA$X2W99j!7ZRUR>K;ZdE z-h^&o2vKK1)U(=|H1dO=l zJrLi?v2gfTLF=vtin6+U1ocgtLd4+68!(0?92K<^V>!hh*j zpD`?m|0CV10koUc=?~rNUxyEtCtcQJx?uw^GDcJWqFaq3?tL=I;{#Qd+}luG)I%RH?cm3`^U0qOqyn-;MAF+Zcq zynCfA0O1;3dkwd@pF+U*-RNZAMc5G&Udt4)$gMG z6+R3Un11UuB+o*go!@x7kLpe->>r+;SG{pb*k}9o6{h}M`0!V7 z3fb-a#-Cqd0-}W$VnO<#m6pkqSFl2i^03^BQl#^M$3fbH;ImA}=KGQRM~)tr&uSJ+`~8d(!IbgdH7PzeHunPHUt9zMiK5M2!Yqpz^*@Ik=0`*Lab zA-pcplqW~_I((REO}X1BCH%iZYM-6#d^_1ia-C;~>)#I6zU_ZGI@tKOw|a8@tnBV>obIk1 z?=BzjEFJAE9d0lF>v{O_%fGH4_|Kh(S0=hXPqZzJw=Rq!pO)E)f$8!7>9PK~v9|yE zk@#1a@xLC4%L{W0b5is3vU78gMaDt@!6M^-YaX6?^`AKp|E^(D{)>j`zj_#6`d7p7 zn9-BJ8-~lXI#j_$EiaIfL|1~)^Ub;6Dva|B8IKt>d=x`X81tj)v;WdPAmL=v_KU

nsGPw}YxnK7aH=!+Yr(w?5i}BymjbVQkltgldZYIPaH& zSKL2`;YW#qVA3CIbx0D&lPeQR;(XZZ%V+EK{4=SoI6vbiG(Fsk9EN|030x1u{ED|4 z>rS@bgrnh5vS>b_|sc8N?M;H1JDYt1Zr&iRq@^T0HlYcBVxA;GS%ab}o2U z61Mdz^P`#D(PN3choX@8rV(s91>D6d`pG4&7i2|zhcjO^Yd1||W14hG z3QN0xyewqyV6NAxsKSl5sX)`lGb>A$S=}ld9PB7coDbmGtyztIyjy$UI`rS{9=KqN z#Qs;^1DxjgcXPK7uN_R!74BB5WeJL`7asLXeA_T<}4U?*4H={)hY* zCYs#f3}YEXlAcveQ(j+oA;M=;z|7EcfIjPf>^F22{dKbl?#V2U#el^^)6rP248&pf{*g{d@Q4- zAI+TX^y=6&f37s?~lFro6I&|)_)L}=fQqQ zdw_{kd|8)CGd{dp({>;Z>#r8q-Nln9+-ND5Bs4yhGm(iHz)_bVxiBk3#C%__e&KOx zgdxdxb??UKm6fx}tT%|#3mVX4!DiHQIWJ6Nt%UNpX3F7^H@?zlX#8-2U2P01^7c;j z6Mjh_qkVSDIa1Kb=aM} z$_I2-erS+BBQj2O)^L{ACD6Q5lpqxSZJH&6);233vB_)fxeWk#N{T7Tyma1|46)mR zN{{k1Bf_b%Y3Oj6ugonYqmd+zF^gOp$+O?O2UJ`<%A<2GmS5@x_Zs}@MRpH-d7|`{ zk=O2!$2U4FYBjgdwES&M6Mptz55u42`>e0K2P)&wf1vi~>qW6o!mao-kt9xCyZ_H& z`1cB976XmE!IxD5al1%TJ4^7>sFf~%O<@jfF%R*{^Wqn&&G7t_H{}ZjjN5;Z+Q9WN z{ENi781_>T&d2ezxF&II9iOrNB(<}>ag?=xk=j4<1JtZ>|CZFQjNe8M!^+FUEVevE z2}bu>#S==>2u_eE7dLg&L#P}Vl=E;}Hff4f^a1rF&HFcC7#4DJYB!zo`9?OS$1aF+ z0#1t9q&e=bC#L&RYUC+rT@S;PVN>NlNt~ADi5AM!(javtiPQJzVVLNd9-P{LdXO?N zS1MvlSN?IfVo@bs?|z}JMgdE(D^6v846bbp-`ym{giuvPEtf-2Cv-mhaW$Lwj$%z6 z(L}&#^{w=`PTb}97D;n!2meCi{1!woK95Jo^l0QQZAWZvUe5Vxo~*(SCND!<08g2sa=fY#h|tnmtOso)MitDkN4D- z-K&>dmAL@|ecawoF6|T|pS?_oB(>*{dHzCbJ4xIvv2pV~cEe&wGsq%VX4>kSbYtW0a*X16gnJhg_$K&_`6c#EZA&tHG_C zPV282^X_05+<#9amYK(}bRSk|+i0i#`C^<{MX>S7z;0ZtiSPyHhsN(7yOG^9BMHp{ z-gD|%Pe>(_$2@;V5;F1)KZoJZV_z)!Uau6Ni@XQ|A4YyYUS?iZtnD#efW}l@elZUa z)swq*lsJ32Cc;hG^ZYuJxX0715!^?}_rjO>J*}eR#V78%=dr>bKO>18jg$PpjwG(O z%n0kJx-?G9ldiUHH0x(39n#;dpKsW|s~_`y8wn?D-$iW^Usx)2sr@68IBTW)u^*(_ zuuS&ptW*5QACbh}ABXXu8Z2@)9S39=cHUt%u79T7i;4SDnnBZ;uJ`F;qW;H8>AS}5 zN1ESfW>chc9=H{Vz4^Xi82gQTPhxHl|8?woFl*bV4{f?{BE5cRk>;)ke-h;2PyBy8 z_@AHdogtr}v;Xw%{|CRCo|9l<(d13t5I(+%(I(&J$Yhh-1Vd~TT)Tg1DspZLz zrOD2v$&SVAr+spA=s$Pl?`<9EZtm@B?&)akY;WppZTR0FYW_#2{@;nD?7CmQV_6x0 zGx(<<{i})b@o~QnHNEmGo#Exq@UpitaZc&QcF6?~VzS=7gN28`4G9ek4h}(fjah~# z{;~i5W8N?STMFsL%U4b>TpXXhL~2)&&Q*Jd=eG7v*Ii?e?0;W@Kf3$C+UUNep^1f_ zk(p}nduiWz5szpdw+N1xF!q-)=I7z`j$yPe6{u;$ya~hf``S2r&a$w zi*$XW89nvnZ{@3}g>1iX!R_?sq^#63O^M0+X|<7VtLqcZ$9m?bZIpVbftc&q<2j220v|4nWLn- zw+!UVw_tpJn0#;e`6sndB!XWw^;D*r>Agz$>ry+}SrXnACMEYQ`-$r<_{~H1d;ay2 z%I))|nY>x8@kFcE$yAR*8#z_T&XSj3`U}4Mf+*BzKyJZ#!S5==rgWtzSCvh}Q?+8` zPQPBCXnr=^^UY3xn`)uety0QjJ@ZXeb33n8eSI>(DrAA7JP!ts{kSCA)~!6Q%Sa%C8# z?<6v=D$HwFX6P9T=A}u|K#m!e?%FXXBIT=WYtp(t0vQ32B^PoVjQ8E@p={ws4}%#| zY_$^h!t>Ts%(J?|@7YM=N4&ktE8$AVWpHYhY4u8mRG5OD0nfW~_?oUc#dB8SQXD@k znIsGL@hl<_wvD`8dVRKg`Y32Q3WLgsF;e-s3<_N#{b{kGEc=CC^=K-63{K(Ho6$D; z-OTl)WmGEqoSI09!*CEzf}K`n@56#3byre7Rt2!k>LY^{`Y{gSz?b!-`Q*WtJJR9Ng zjo|P6l&_wQ=@~vb8UHVnuMP=3C)tfDP;@RgQhcxZNzbh#OY7q_T{zSa-x*D?s#Ll|a#cduMHIhLVg9b7AWEdRD&h9VaJW z*~_B`(t6%>(Rs_{a8U@KRGEY?_6C=}=x~{jH(jp4kV|>Gy70{-E{B>t?*|o=QYMNp zU&yNWt>Mp+2&jImj&-&V5hRR|Mn}#QN6s)gFW8~I3%G=EIw)O0`Cf>?dK#EqDa~U~ z2xKy+ao|CyZYi+i!1h41zECjR19_d*90#ofI+oVdsfCkVKW(@tRQcv}%FHHE&zjcx zGCpN(ivsXr*auoRa;ioi!NJUE5x06bbFPwA4O5xXm-wcP+9<7@Lx3)>traDWEs+@t zl&*w2h=s7V_~{UH>_a>)@WEGDZF~f+1@X8w=3$?It`jY)RhDY>^Rf$C_*)mbY?;HD zs!;C$9~=~VSyu(%EIcx-*$-bXxjWp7ouBdRksc458z3nbLc7wsHhE_?SkowyYQYa1 zG+>JW?4J30<)P68kk{DWoT*cXJNNgJ?9L3GX0l>iC%b8h^9f8TOWgdk^1E(-c%2LIgFpG^ACK=HW@^hxb z0B-tBx-Uo()W#z(Fvz=tr?n~+F^ZXnGuIMc_do4b4WHy`iTAf$97%7(ggDxTVrW^^V&lJ>?Y*Odqqqc;lyCWnFwA`C<@I~wLCQ$$ zeaqDP`SDAcQhTp5=@PteQhqy>ri(euE(Zr^B8*|mfm!|Nd4gdVSC4q!=gxjdtVJ4) zafL5ax+x9ODt*+wRbE|6#l}B*5)T>-=N^@?W|a(ypex+vnO>TcT)#^^n7nn{)@xl< zvu;k!9>~wkuODPB@$?#iTA*RmIjC$Zd7(`74JJ}>D(Dk)zF&@z4+ykEvFt)$cFv1} z@AS}%v@oqX1aL-9y9_7#u+@}Sch$9>+ zrQZ;nl`+!fNQ+F2c)P20|_jPJWRq#1fW1A}#m^IefG=BpOPRzHk84O+4g)ZF$;?n#^=({mB5d2p1ug@LJEjCbc8dqFyp~3D zOe7~Zl;a7G^y9REnla-0#nZ%fOVkGOS9SU+X_FPRkPEbf1&-XrtYy#S7$-#x5!SDy z7+xta`8_9xRLF(mIw_iBlW&j_ZMXun`!GP+0Di_lOb)ZtxwWqYEZab_jRD+X;u#QR z)(p(3964A+^HS=5zAN!#S5~|YfZG;;=1?+-0uww29tcdB{K~t9TxP#2rn{%Um~JXx zT;D#@jzV>c@{W4rv*I22?U^<&tj)@k&O4;gJ9;iHnh?dep#w}IB`j+zT)!5r2%(6N zkdT`S>&yUpy>TJ}aj1G!ceBI%*JzHXi0=1*!M1==UJT_yOlDNDMq8AOHXS-qFjkoa zaWq+mE2KU?9&I?3Ga?S7>>c)S918^=1_jbtBL9=%{_=d?ijH{qHDV8RwCLWn}W5=8oY1em&#yoiuRTkk38Ow=lF zI586;Fp~5vQ+c&hEa(%_T2eWAQ?}WFUF8&IOE2ExN26?lySc(e6lrKGVxuC0bXD&? z+foQagl;k62joK40HG!vVZNatlo?@iTcQUU$=VfZQfR5Smx9rklF2CF=kca{^Lsao zrnpAEXO~XYIZAhy^~ev-bYXZpCk5wTiuMx~#G&M`OCScBxz2&IH1$(WiEM}yg*C+h zolU*V4{#ITRN7IvYD5-lS=Q?#&)5U7ogKxw9~2TIXxb}mMVaM~#%XN`eS|GUcbff@ zKj-0v9&5g!(@f5T>=ZtBx+>D#7ib`V1f_w5iXc-LzE-Vpm>3YytD^iWS4cY#)hSPn zE}OyUC9LcM+^jb5%ZFDt75ZE6gtdOyOom1 z>8Y2L{G4^Hcj+E^YZKcBDWbpJ{yQ)=Vz7I5UEz_bLv z$oF0$<|MJ95Wt*GsA@)ti$kOl(JRWNSYoML!PY0jdbfN~g<7(JWx*^aL)J{}?oHVO zaxjOe%RXsZb9C~Dg8bo1cQnSu((G_sQB)3KJs8035;T~t2o~b9c`P~xfB#|k*YPGGhfaewON2}ks3rXOKbo7F| zO!WN3sl(kxxbehnRVxA>i%g2uM%UM-JZAJh{qR7yHvO@Yt9#ug!~#Amm{(Bec2ZXw zdXv(t5`(Iyf{J;By{aauURLKBzdNa3=*@C>;nT16_p}>a&|K4H@3*j%;&IURhBmZA zp3pxQ9POiQ+oJbP60@=e%n|j1(;UM2`{eu-Vu%xbH%g&w)kcr;rd@G5kHfS`*T-1L|aIDQGvQXv_JbC=lMX=fJh>7>H7}K`~L;favU;O$^T&siPM9W62m1gwU z2ILJw1<#tYMjw4KKncAoNR=$K%PW(RPEAfrywK)u(gP~P~GBfc1~%O2m*q)@1=TC91iPXAIk z9_ip5YHW}-pMc@V(ZWR#mtC*hsDtiG^O^{_B@0(dx4ASxqo{>$87b#Ry^WZIKD(q( z*cKFhScwxsd-ke_i?_G1tg>a;iKL|=wjwSSU!X9VviOpIZT%yTd2dB6@Zplbx{xxx zpRzwY6DY&)EiCfjPYDSVXlo#^RbwnK>}7)tIQjNwuk?WJyP}`xOuU9Z?iWck?}@=lyfv^VA+VjyuzT;5x&Oe$Yq86@PgzHwK)1zE-;?u73`y$_ zVPA>jHV(ZX9U^EH1#S!{@DCGvh?05?$3zWN-WENd8%BO6(%zS*zdbUfJHk95&ia0& ztYU<-NQ`>NpuB~w8=+>*yJL{L@5^@}6Te6-(bz^e(9M0NBOS3Kas=LqCTbZO+7h1e5>Bl7AS&nByVVvMZ@xu98daLA(py#nRSJDr(nyC=K3_{h zX97kwi5dj(jmRXof%4DwW~hmS+!W`fd{pJS736?-_zDg9qITsUR&)n$qo|{6k77n> zbTW>gXR5(lr}7x4dA#E>mZoCWfsZU|*y*>lFF6%vpgQhG-x|1*@5fU@xHISZW4MAH z;9@=bVrc_V zu|#`wnKyG9oqjp4Vuo2mSSfiqwW6o$fRVg)(G7x+b4lIQKhF79@W~8maOXHVAJfwV z>e2Tr`YYlsL=v}DaBhXXLycHf)yNMj0yLVc(aTnkeU{`>zL+$9xwr6zN4MYf=9-0u zkx|o<^_?}Flr_7iHT#7%9hWtSo9mpJRL&j%$74gY1+$d*z3j~E+|PzCoj56beF>b} z?6c4v5xXXvI*Q=oI?r997_;Zt(hTs^f_F{A(SraBv^}m#=%D56`&-PxH>sKUXhoU~ z-4@KSDrVE0gg4Xa>JH{`Tl(DuH;X*Ckn+{Kw-B$Utsu*-rj!Jio7?_G4ehr?0z9`} zSHAWx2*)mLd$w&1-Pw_f*z`r)9!uGo8KkLf+F39qR`%NYd}o*N*6y>Tm`07=&8FS& zyxVWAcV9l*-o7c^b7${S+xF?85LwdR)3)}@o5J6J?5RBWW@vffz`4(Zve&BZOJxT; ze7kSk)(l77xeC$AUtdc6o^!eC+v`8zJ zQ*3~U4`H-%Q;3a*PgL^6Wb_f%QzLrrOtnu&5(uUHGRrCMr;-ZvGE2Lrp9E<&jqZLF za4w5J@rAQPbG-0l#sH!1Gk2 zsCUM%KcAWFEbyV6CGP7|?2yEhFcWAh5o;W}97J3WeC9?yV1H3uK7@aXI)qt43v?ph zT=slklQ^PU;Q4_=@EOe?5|_%`O!ytM^a^eGs*(q>EklRt!PYCn=RnR-BZLi{;NlyQ);%dRRejz1QRv*E?s)IOhR{K^V0`>C?BGE5xfs< z8y^jP&~+_e-Bzt(Bg#>;stU-U6cSWw%5>TVcG7S+c@p-RIRzGv3QwM)$28O~yAv)Vh-&t18eseU{z%HE(}gtgr1UZPb#1}otY_Pm>4bNz(Trj)|BB&YWeOn{@Kclm^nkM zDB(?k)u<(KRq->!fLg|wtwhm>C@5d>9woVS<~>YtXR6`6Q29}71G^<8Hl9{7B5Io> z4CTXtBRCQ-Y`Lin9%~d-H*Gv{U_VXV5*Ex>eO&fQLHtQTq5)FAYWP7`qnw%X;z|8p z)6QF?j)N!k`U-sf7I_cDsGhbFesrMIqPUoa>sCOY+qSdhyymu|-Tcm2o`nm4_DOP& zgZ!BGFq;uQnVhsY zoAc2#0$1^hnfG(`$2SP^!+G`i(J}gtTZc8V(m3)Hd^*ohwpM8z&T#pl+*T3piN#zj(+QK9YV`I9GseDzLz2*Kja25sKYHtcdDc!?6pE45GRrF`^fXe z9@s~q1(OZbC}a*Og+UW&sJ?s^5U}%ec;245gBz!KhxCa|zhk_7G;zlr(q|T`h1m4q zTBRtqa=N!xR*Wn{l~OWrV+`|72ve=HQb!1xelY6b**XkIIxH&Zh3*mcv#=2^?3j|* zi7vUVQaY_8v5&+e9t7F2`!?*yev}ycY|$0|fETV0)&8PnL<}B+%RK7aN9D=N%eJ6I ztj6mPd#!3|_t?H1z27pECESs~WISU1Zbgp8$HFk)5X;|_$G9-0c0YYQxg#I>iOk&z024fjy9X1Mrb=q%Vj%Ctd z*ec13=|skk!CB;ORrKq0VynioxSee+o>7ok-jgS3P7h&e(uO6NFg@oHoMS0C#4fl; z;4V0>v*CFWZGftOpI?x0rh&gWOAI4N!+BD?_GMVE0SUWFM}B2-H4|LN`kqlwvf*=` zV5bv-!ePp-*kv)s4^1Rb%qbjXii>Ci6zo-sZzT|^{ zM{F?Md8+GSRv9zJ{X*J$DQY~q?8sG`9F~(rMl~< z5K|@f;fb_qANX)ThHlwOUzEFicJ`3Jdd_u6qZWn0P`|whI9FkMNjJB=dsNdd*!@+? zXMXeasBUm)SK%WbgoiGU>iL%dv$npWgFEnsxi8(-6I7p0GlJ;$-9Anb^17Srb*_j|p&}USF|E@{)|2fF||EDB7>mR!{ z{$-N=_`gw-?f>60$+nPDCEzvrC6faLeW;bo;XP5Ty7~8d%Cq`@mkq1?B{=+nu;Tvp zJy)J?Bz@}d_gp`d?CX23Kn3uYAj@wEYwXTc)z2EyKV-v`S<_8Og!QJH>&9&BHNyH+ zHvHQ?*O$MQ4STp=%j6gk>emSCWT|Ce%AXNdq-?mM=BHKTFZW#k#j;_wn6+U$o{8Lq zFrl>|s<&d19hUDTug)@M1W-4oVPy2StC2ZuJy!Y}cZ{{8$&{x_V+@M@tYd9RL`P!p z1yE4LBO=(=5^S>bvNaRpYagmOyqbn3p$$`{y??rfOtN2}Zmg$zVX}Ws^CPwUnjXZQ z|1~4*S~d(*VBdg88`y1R#XtOAHk=l~{=b(E`-sSvG-KA2u($q{$u%k2m*?E-vo9LF z!|}wym0o|Ra?9MU$Y9ojLyLXgd5bG!nNrUo>sdC*6Pc}t;>CIEO;iT;M;#nb(@r&F z_VSMv>h=OR7C82s(eWmpwqUc^ue9I_|B?-t`BGlZMsyG*1v+(7Q#l9A(734CcGK^* zJNB^ZekfC8)Mb?I-NLvmtzapseI_T|)?le6y2W|WcL&QOb4ZSA_L)B)+0OW|N3?N!Sl$J zHw0E+Gvb2IW#B|`*A4pY!Hb}R`X6FyCOJ7Z+Z7c-?z^-prbD|86?*lro3Wl|tQJtw zEO)uHlw2MS)rYtqj~PC_I+=P@a&dtSnVa(mqU$SBHR0h6-KV-wC zenwB~{f-Kevf(?}L8c9=;I{50-pGU75h9jD#MSZ{-rC`g+oMz~NZBwmJpAQPnOxVM zi-Vssx!>=({!S*x&GzhV7rQBwQ;>4ji$mYkIYt8+HkD>rd9(>{=7Vlmm6%E>5@F5a zeDo*TaCv0@;BdnwR6B0RMlRbYY z8@@CXJL>rh!unG-{DQVc;vXTb#4F(Zby5ihK zPs<{JfYeZ$eT|2fb0ptm5C#N|Osz`gaPQ00L7KHK#qfN1Vn{1$*fa<; zf|Ob5A;Hal(#7l(2TYZcV@i)r{I&54_&$)fP9bU5M1#AP&a{R_{#+NqAx)<-RPxSB zY+Bm5Ixve8j9PXJMd*}^3Q3-ZGlv!fvOkLcOPOAbz1D|1sa(>Ia+w4>or2!*0$lxK z9O+FPbyedrN~;_Yj7|N?=FH5DHAD^vwKnZ zrM=jhFk^nlr=tEh*>HqUbpzgQ?q4#w-|x8|T;x?Ftr~kSC*s5355Ii`Rb@QFSpE!( zs(6VZv@c5Z`uUZHj zm>-ynR;NoNdrZ7Z)Y>EBPzwrM% z*zo`S3;*BvFP#4c?|=LEM4}fzUx&zd;l=UhpWcP%$D5}oJ7-6me@*V6{y#n3-Cvv7 zLAq>KMz>cdHowelu1x+jm(9vQaoPOZcdX9#{zG#AKZxzmj&;qAe4HC@n!SD+XOO=` z4YNb_GeZqCpBm=7tEPtArUq)K25QEKdq)O4hx$8)`rAkP>$-;q2YXujds=$CK6ZCD zceOYELF>0QRW~=*wAPi>3=Wm`^cQ#aeQc~LZtG0{*xA%jg_PGc)qO~*Z$EG#%A^cT5r{x&Hp;EkVufVYpI=NliSHgweG2GU>i z%H6Zb;;zdp4`&zmU*!JN-^u+aPoF<_cy9C9@fzNLcn$AAu&}vjb`9?%Eusb{=6XgC z{u7C2Pk3MYk9Q&K zzxyskfa?DtynjH+8A5*T&yUC`bl9$I*;*?y5>~wNr^qTFV1WrbUOvs0O?0m+mB?YegwtB|Stc^dn` zd^yEDf9d|>b-$8>F`7}U2HuUBo7m&Dq7~6*L~uVxXW24{EKP%mBY~ZdGd-@bQA661 zcaOq%1l)9gWEa`5v~J+f`$4W8{UZ_l9_h_}-xlgM7V?<@8HGMD9A7#Gf0e?Ptwk8{ zFeb@ZK=vzrjWa<{K%bYIW+EQ(L`#5c-Ma6jG~~p2prZ`NJQs#>VF%|T{Ve%5}ezsl4f1>>eA~vv3i)6j#^u_ThIp)-?b-6v7q}DXlySzJZ}Vy@K@TPwRT4 z@hSp*U=rh5>70`++Hlm`NvIZ@hY!pxN!cn}s){5!TZz@jB|66RdgZ}$bvSgNy7nts z625ZPkOkVj8{kny7eo|~sn0i_&2_E-^Yy!4c@W?rZ8#WgEHHaaX;C0;o)s}g9LYV5 z((8@!WjZ{B|7B)@lpU`~M1I+g)qE*VD4aK3T;TQSsEE4?y4IFwI8fGoVx)suL4L8}JSVSP9WD>&_|1dfw|w>lTy`9Cz)2`Cxk&yYU(NzhppSeLhPau&RI#dyWPoy%AOP|rK}92 z)0IyZfVHg#YNXY4mvo}sDhoP>dSra+@j?lSdbUNoRvVxcmCI{vrK5p4otBE-%0c1w zjBZ$>FH!MG@3^zJy7kj=>@mt&a5ZkbWaTvc z0bWL5a1cW&76pf;YN&iQ!j6-1aZ5pTE~>(hhd<5ieozLcc(#L87r~NNC>Nczp+6(B zWBPcvyhjp{RvbdxTx4B%D;s7^*?TKI`aQ`F#>PHIG`Wwg3NQT~hA;WCoh0uj z@UZ#SChv4UMnQZe{LVG zd*dw`6d$ytlu70hX$N3l(Cv&~IHDXn4h3i04i42FC)6V&g5e1S2qXgG1Z*MFmyc zR)G6s+R#>5Tf6&0&<&%QP@@$eK87O-Q7GqQKQBu9P%T5TXyeb~BZ8AZ{rTZUdam@6 zpR%f|5Q0xxL}mO5NACu*$m!K6(nUJ@v)G#D{cP3Os-$~SW3=o=8?MYUJSCAmhNc^K z#J5$IB%}8_+tDbU8o!t$B6Yo*==``<*6VpMwR=2EYi51t5<|7U?*$w`_afkFy-j31 zv_RKw=D{STCty`-X~l%5h{(ps_^#r!T!3q7i-)HD+M{OylI93RvpXkmL^6@NPi-7^ ztWhY2$yN!Zi{V48F_-w?mtwhtScO1@(`nc-S_DzLp6k(I^js>xZ*KS~&Mnm>JBsY( ziVwTwZo*yYj#z-u9DGYbPYT}q*y;NCygJY&wxVWDXpItktcg^mx9_31qXo|ZJ)?Qm z8?*!7JP_o?iE8_ivS15dT%{4Fwr_|YV_dT)-?97fp|@?PiNz946c4~k?e$qxg85*Q@s-ecxY7#a8#;$)}<@vPDBzzhJ{_)$ktj!gonO2EE_W$A$m z9!hX7@#BM2=8bQ0Z^G%ALj##wK(x_|Ry=f6?poMnOF}D-bT5an<;l&6 zP`EdJpkF{#KZd;s$-Sei-F;tBTThY2DzV=%18$tr(qP{})}1FA0XIpiS@gZQkWUTwAW+f;czqvOj`gZ zCQX_KA}q3oO?In3Z)UCmj2)L?RF?h_`UpT9|9JT={244%0AJ75fiYNuy~mw8(^vd3 zvWqCn69LB+tBsP#i@GlzHNPKjZ54%stl&6_Za<1rHD$43Z|E1JL zj`$^TPUh$aJi{SE=fOgx@!TCEd|Mi;<%U0mhQG8QEt^IdzaPy(OPJOiA9D_ZngLO^ zz*|uu4+d^9PSA{xh#`KMHRV9V>bXhJ_C-q=?m`jc#q+ibf}V!ER|-N~0@pVuQ6n4) z<1?@kY3S&VI9D)KEjIif$K)O@{1{q-i+xO?QoL0u!j&Oh>LIYE8)^fHa2te|Diy1h z2d-BJk?0d{d*Q1troIvd;?5N-mm^f@q8-sgR~#t>&G5p_utryJKcmHB)uAmd#d;4S z4C;iS1NcEAz{fOj!!!nh2ODh(T~GyNqMT4zO0Zu`u(*iru7zd~!V5LSiiZ)@gVI|; zgvnai9WVj}C`M?A@V*o%+KVvF5i10QXI~oMBAV{ONRX|A&-;=jT~wjeCJ1fVrE)S7 znjY8fh_5Y*w+tlzP{u+m8r<3^jFJM?0+yQRINw02-+0jN&Z7YyoHGP1>iiJKl_QSk zIcSw9%hnC&%YJl4+AVF0n4a@jT;@2{UO=@Oj+q~{3x%mG-9*6;#U=Nq(Ucur8F)GY zPT2qmK`3<>AatG_=T|v)c{#5)bG+Dd(WP?t&ofZVKq&yh@jl_utE`xP!tL|uGP68B zK|Ia8lrk->k2vWm?CHIE(99ViYcuzr)s3VIQI$1^Ps#wu2hX1tOW&Lst|-|R3*>={ z5HMUWyJT~UO#Z|~;l#|+Gy;ju%$D=$17+IpL%8nym`P@7XE>9^GXo-o%rHu9Xz20%8LZ z;)ntG9E=M9epE0%Lh6HnSWUEDUKK6=B5v^lAP~lujZKHjN~K8F;;fGz>4Q>@=8gLb z!0U2iS*0~C)x!Re{~p~De|-qsWdrP{49ZO-{HhFkZHwmuiuXB>_A|zDhv5g~WP`D}$w~ zGGRsx6ui%hcU>~@8Js9gmVJm1qLt4H)Hb5gOG~~YEz@R%D^e_)Jt!tUF{U`h=Cuu| z(x~-|1iLW2;QboS1k@&4!fgN#Lj`0%L?{S~iE%^@D1?j6I0V$i$&Z0lJjMKPFG(+u zx1Lb$S%pkx*0i+3=-?cC<0j}q>kV%-11t5|D!_UI9G6zkd4Nsi7hE0D7Czd_N7t_F z=cknXe*eQGoqiELP9il<`SOk+a76pPImrk1Rn9MP1T3ib7rC%d=-HVa?l*`$;3TqB zL;CxwWh1g5GP?8klQ0&vFKZDlz_4#q#|R;Y;JayfETyr!#xX`=5WVECTjm{VdiZ5{ z3c~ng*?44To7h)rxNcr}XS7&m>?oi2!6A#-U$yYvr{msG#1~<;6L|MHqUR_M_c$E) zfW6(754_w}LCc_9)1W?gah$7C49!|B_ulF}+Zw&quIOHB;$f&1oBMWc83 z&7ka&1Zid-KnnqD52UrBRCS+lc^K!k`9qK@s9_PTRSVi#ELky5Sx+BZ0vVLMbOs5SpR)O@Emxs zzyGKZ+ziA_myQV7Wukg#@(e(@5cWMMokOEOR>qJ{4urLfChNnPIO$~W89bvxV!VIsvmgp1elTn2Ze(jre#yZ#8Le5 zKAYo7dN5(cLeQHlZYSYx4prRVN@ch|!qQlZo;Jd{GlEVvD#$*?{2e;R0~9q*4a?Ly zcu#=KCeT|{NDK@K4^&^(4hGE*;pyJ7d5 zu^OPzuOLG6Q9S7tN^f^z4L}rYmPoG)Y`&Vo=SJm)iY2|q=DkKpx8jg;b8e2=7nF=oqD89*_XaL_9z|~qC z61)d2h-mzp)|HkfUJGWt>{h&6X=~$RMDnks6#tV)uJyaV$fTD+?N}n2+5W5mQMa^`&eUOj(<`mOuf18;n zdZ_%#@u?#>>&*g+6%c_ZAwf9ADxK*BF1z-u#32bCH`A49ylINS@yw0pJW^B6bq~t+ zKuA&Z=?@5A)zJBS$#Yqh^FyJJ)!>Uq@0egMr`g<5Mk~iol?Po>=cm~`D$kh(#1`&|%2I=ljrKP32JEc3MQ;?QY?n3?b-e>Q9o^$U$=RA(#KfoA%_)g|~&iSGs zzkUB{+nn+2|0~?oJ74(HdA{0$lSQGwBc)!<5vaw|qTWJ#r`V&Hz zIYnt}Ff>e`XMZMmOD2`Wa-};(nMxFw&+{uJuFCFMAZrMrSgJ}6U7jq*iVd!6Q8%J; zX+FEzn7A0CdW#nnp4vx^N!}sTA`2Q=1NbR`aA7pta;QWsfq*L z&HyB3QFo0K!(POD&OrQUtX)NM3=$mH<-RJGu6(jr-kftO^2aXK_A)18fRHP*BDX;eFgQ zh4jsCITSIXfNCixQVet%DRW4QNg2iKEv3%n{p}QFap|eal%*0Yd<_|fVSt)m0EgN$ zle~*E0tu0KGx1U*hp2k5E-qMff)Xy8jsi(IrKIDY*dU|8C~ZA+u`sCBRKwXq!cl=2 zrbw|;knGd6?W1rW03Q-_CO4RTQMX*(oR^Dd4VBuXx6!7{f|jF|6EXNScZ7MGo)>9Z#WW4rNkJnDNQdJeo47Wc6g-Kfps z5jULTz9iHuC8~{E=DfBk@fq6GAE6He`EmM@E67BKHtMLP17mz@mE1|*?TAxI@(j1UK<`w=DGtDKV^RkN#6Yflx!}w37GYHmaqkLiy8z8k+m5C6Hy$M8)@|^1OSClk1wO120&W^Y zN0b>o;B_sTAM=vn4?bRQ3*2e=So7Z=b`?pvp3E{GC2B>QJoRcz@()QNx{v^7ac`!m$qtR*B5=ybZp?Kx3>yo zyCYQN&rD7_tPc;B0Ex~!@`%>o0PzL42<}X@iPjqaGn;}$g8aN7PHl8R0JkV9CW>$c zY>;3(3IZADIOjbIkg74J-UKcWx*Zi}%L|GMF|;(SYjAB@O%>IPry|4xEf^}Ql3|`e z)be;WRVcMD5`!gI;nAKbDw|TDtwk|${P9Q~BvrJSpb>^DB0Tr1!5iV!6NS|<_>X`} zQaeO)ZAfq!CSD(Uni;`RO>!XW6L9K8*J542_~1I1HMo%g*3eU2AnK#*Xg4^21KyYZ z%Z=lq4hGMOTM>!(A?;dnGf#=#*rf=dIxB;!ClYaD258ZR)2y!U;bM{C0L0L!nSLB) z(7ku!IJZGOCZuAq@GMf8kA&N!7lQqUsCjQz?bnHKi z?hQ|_3lld$z=AsJVm@-}L83vto71`7@WWnT7|;B+o}g zQ05jv*-~n)Xaa1%ZYB=n7J*&Q$Meca#VwaZ@c~l0Q#nQB@8cCVSPia6Lx;l>kUIis zn^}ge(3Nm9GRcL?czZIBATbv{1_}tJM#p?*sssvUqpE5FYAee~T!(>3MktJS-3}yX zhtSlW2@&~FNmarIeR{=EW4^o-4Pn>DLY>#zcb+9pu^d4#EindyyyMfv z+2$Q6d4zGiH_&CXEuS2N_g4Azh*3=((Z=^hXlY{aChD5GT7a)`Dq+p+MBBeQ9u>uB z#XS0u+X2h@oYm+wnfpdf7wR>s5GJBTFtZ^xLnGwJ{@Ele(aR2ilMy~l<%e#L3F09is+~Ns`rRQv?v4=TmuY`Qo6MoSwbWc z{U0Zd`3Yv1Y|%c>jes2QN}{3K^0R2b^VqfH>Xg~0sk&wb_DV`B@|&D>ro4CVwSRrl zY$EV^e)JfM>BH1#laGk0V?p8$*%&RR;#|B>otzwUQ4CEb)fXn%PH?#e++Ip@ITJ6g z=ZPG3zm!J6>5+`KpCWcivulo@VvK)JN=*_ZoS5@&c@8fc{LD;jF;nanesI}iQe)jS zo+){T%U?({(xbUkGgatCLn?oYk9A1aKYDEQ}GH z&nrm;PL__N)h-sWiD!i**_7mT;C-T!IT{bm>odvroA8-~P4X_k~f87c3@+6+q z&Cl6gJq#cY+VwPUs@X>-Dx_+nl_zrFv;;beQt6(K>NJ-aft?OHubjocz1tCcdc(7v zdOj79{U-Iae9{C-;rZPtl?tyL>0~s%{g+YFM6dgsjJIP(%ih^a!XHfgL4TGe?QIBV z?!Fu~$!tp6hugsuk>Q(@ofATFKj`V5SuktEljT~aYI*8)MfkznUGUY-r2JQ3;8W25 z5{GRVYM7hJr!`#0Z74gT@gH~Y&D$=Yk~KDgX=fTT3qA^`wj>k8R!W9CD1q|ex?)2I z%M=8I^|mU&m0tBhP(h8KbepUWQP^ve?tM@hzlpY z(jUlL()vkRcC^--vjO zk8)j%47L=^R}!g-FTku4hR+X6crL^=FA5e4^#TC%qMt7ethmXI)AnU2)shf;yzto| z;?NK>V>PT7MDx=^q!-N*_~*UU9=)uRzNXDYZFnKLkahGjn9eF)XevUCzR`%8M0Svm zPu$ZeyW5NA+xb~U+bjHRfx>zHF`7nP_r&DUwieN1n&g=2S*pkVQRn>y`hDe@z)1Sw z6d}nwoB@)emgC)!K=y%Tepnqg;I)QiN_dREDI}jMWM`LTICY_1I$}IP{0b1Hi3^*1 zCz;YLc`E!ki$46*6+{7h)R)PMchr&@{e!1BzKM5;$?1>h4RAD~k$93z^U@#V1S7lQ z$IO5;t_n+^Q4c;MArdcu^bD6ip>D+v;VGXRjCmvtutSw4k&y*QU}Ss|(Lf{CF)Y6Ys z&ke<5$3~{0O*DtLZ36p@U~vJm_r2pIlXQbPwy?u8DI>!}f zDHI7PXIA%rpIHHAxgVZ-SM9_6q@q4VD*Otq20`^?L<-T3Qu;xSW@EQ- ztv1KFL23$uc(K7e%sw6jId*-?eco-~?sD1P#Gxc<=;Gj}k>GXtCf8 z>efW`yv(M{1QW$1D~EDC&cHq0lSv|+5`EK{V{K(00}jAT&OIri)6+Uz)4CVadQda^7&8VG zGlm>9&&6hpzQ7&lz@l}+nY6%}mcqTvP(uw>d(ksvF+F3sHFJDJl6Ezd3ag%qt)57& zZZFnjr8?{QV%EuV);VC-#S$C01g_?KDq5j2U4dMD0uC&0HY6CBU;~$2uO1o9o8C|1 z!(E$Z3b{=O7vwn2AUb#d6&MtGqt55?x?MBGw1>8G~&FG7TTE;cAL_<8GK9^S~5AcI-lwE$esWh2X<@2I2NnK7OPbkYhEnYIxf}) zEY@FCeTmh=-V=x=W)8$&XgrL%++5^mkuZym2!W?VI)DbzXKHAt+NK}dpCgGMNARJR z<94Epv#jrp-NbjNtQbVg|&TnEwZ9NGF z$ANhz3mYg*yMLi8nX~vQAZ|qmcEvIB*GXJZs!rrz&$j+d)%{G>{Vz<_nS)Yw-xKDE zzb4F0r&GCO{*W*?<@nfJfmsR`q?F$bN|^UaPaF0&Kjg^`SWRZ=U8UpY->_?)-nl4J zOAr!?MAExf;wi>((r9*TFq2MZt00l8^egBK{>YYt-XHMi`};>@)IU?L|G!AJ{(Ih^ z?9cc2^Zoryl~b_6{(IivYcK+^QwW5AWys>E{`^&cE{-83OqJf39qmC&SC?B ziN6n7$i&m_jAn|25z0QW*a|>MhX1}p7TKcVEz}#~Z9Tw^2=0a8=kmO6wK>wfUtLn7 zgfU-k#sJ|ljACWVYK`I)PA`q(Rn%U-ND$R^oru>I?|Tui=M$i)Fvuck9 z_i0+8L0PEpLl%_9S%wC*boy2A7sNgaw}>wiSI-z9Oja*A9WbOXd3|HCX<5{7=NBI( z?3NuIH673RTQm;TgpwOwp&b9sbd()RWJjMW2}7_B{-w8XOJQE@@J;A1>`+c3^l z(4I3kohfL@!ujJ#9|*~C+HWf^W2c4m2H#|mw(dKN?QEDeP3CNbTluq@BHs?b{-}U6 zoWocLvMdP6Flp>Cp~g7!fMgiSm`qn>_=aTQP*TG(Ih)a+?6#XTaF)HCH+`E?Ja1Na z=+vOs#_-wIV$|~UvdfOnGK;PHJ$vnnHw@#|s{aobn~Uo!CS8M#xS2!l;aK@2{Vh4o zvg_@1iG~xO=*1A%9hgYn#hu)@geiMPF#T=^tZm4*AFF4rZVxktB5#kLUyR&-YKLL+ zP-uK?eRt9i+ORks=K2I0var|nco?$q6v?{h`Es%3{OQZ*)rTRA&7?N>%k8&Jo@K4Y zpjL;L_2Z}UhkC(Zhc8Co-G9BCd}jGDWB~>PY=?lReTCil1{~|5)p6|O%i?#(%-(UV zT26_TD+xUs*eGHN@O@}?d_L}caXSDHfmCTw-0eeNPug$7ho5Kc10>wAsjQMvYw044MkL|I|QQ**vp!F5?<6v zihG#d%h7leVH2K%zXKYwSU8DvX`aJA113E=J&9tSUyC4y`VJ=kWyk`R&(b58oN7K6 zSS#fNVzDXGzr=WIb{e;`M@%h2L!=mc8ebsu4NOdKSDA3;o>#~WH>A06npnRSM{oZ- zF!5fC4r-inHGe*9(!j9s1B)#_hbjjICYI|H=Z($ekT;f*e95M=yp+$qfhzYz);@h# z=IzZOh{e{Z{PGis#kM0k>ZTc%arse=_3Y)nxX0;t7TZM)h{blE3F|3?jW$RH#yyn< zzS==SIr!)ivkJvyN9xCB24Rs-)tE0ebcHJ76u~T1hzT#KA2Vvk#zJReLP{1gn4y3T zWw7xD_rH{5F#x2TIyir*mgflMRnb0Y&+AH#dnzq9l}$LEBM!B%RB9Jmq*jARmH|{l zU=1yE;wWN~rP0t~o8C@v$b*WZ0YU54>}oHbYL$jb8}I^BCe9;lJ%^s{(JE_|sLEQ) zPU{}xDlI|IxG*MAi!s1!B=T}H1bLQ(oYKw@QqonPb(g&08k&Fa=42BumT1h!s!7UQ zRQ+ZI&P;h|!Kv&rIIR)ne#uVaE(Y|N1r-&t(Qyfm#9kt4t!{0|d-U>5|@ zt~^Fw(1rbr{C18B^g5IhvjfY5cIprizu6tHLAzzA|JrWZPr3K2-23lQ;{6S}3o7xp zqzC;8zx5yVc>e>r_g~cG{of$>x}>le9^_t5UoiI5(7)`K)gnHN&L94h+;hkt$p*&J z>I_zYlY46Xv^7OPO1$6YUMPVyCdqWA=`V86V)V2c^4o5ivfSX%w-WE!5t2-O`Pu`4 z%UJSr=2FkYZW+HT^LM$oG*&4#n*JBL=P2atiP%(o_)y|q8EN7YT4)6kxc=?CWz4-G zxyL?Z3X*%<4<+8q-Hj+gXgDkzklZ7P5qFx_ke8;EM2(g6f_f1zkHSNdkUT&+p1^5G z6O#!4Y=S&dCW0p>1u-OqQZypuIy(u)N77ivri}b;lu2o!LdN4|9uqka-n^Y~AE!$y zg8(aTQ&lfQUZW&j26*M1Nb!V%up~;cmwD;ywR_eXqzNzIKs;mJFF49FQ_Oq=T30PD z`zH6QXUx9Iy@Rsm%l!k;ZW-Oj^6qcDWt7DqD~CA`K30u^O1#xmYUYQYCg~(bwX;qK zhjpvJqIY*ea)|)nM(gX5Lab~djQVIXK*@%HKgd5YU^mER#Xm8`{6OG( zK<~Z>p?B?7Skpw$MmeA#Xy-%DK+lU7-6+n>4`!nv zxmUd7dDU1X1lle8OzC-JlkzF`R)crcOYFcNcyk9e9o5!;{IFZ*Gfo6{%O;QyYvV02 zxCD*@l6$Cm-i?iK9#H{1;5El|0L_`uT%Z!~0?>;PB=_2~n;+z!E;tFidVeQo<1t9? ztu?b!cfn1R2hul^AUlJ0%WeRqymusO_r9j--Eb@nqVY0t7_r@CyteGJ9_xYG)IHFb z??N?(voY&HyJbaNp}L4<`YP1Dtc^Ay#xfg*?fs0bMSqlg!y6F=1>bhd^f$g{ab36Tk-W^m*eUN)wKA1FQGW5|Ni7I*Y zlAJ@DmxqWJ=!##?>jutoDhx!1lbD<4hF}g+X&dg;=`9CjoEWN7kZCB{-{Qom|FT;a z(q?3LmbQv$65LGl-p(#YOGx-F4}s`=$Hudap^S;t@6o#vm*~uGcQ3g7Z-yjYC<`93&?n~qMfNs#b7W>n3WtIRLjq;DYXeu`$Tv;Q!lk8C0|2l zv|j`wa5<`*e<{|7k=7tQsVQGKqWJ~AJIF(CL?t~xsCilWK;Ysio*Qwytja_xHIE|4uX>+&0#4y1Uu7hBS(c~JKLzVWiQHRikAqa3IO<@jwL<^H-`_DXGO3nce$ z%@`ftf_BR^KmQ{4o`SD7fx!xLX@|fO2G=z)gEN7-D1=$ft+&(`Ks_$U);KCiYJv25 z=kY@0!&w0r*x|@KuhFoTc>MMDpnf_JOYlYJ2~MHuU>gn_+i0lAIqK~c$htV>YjEn= zt>|9s354O9ipehMB#iyO$`*Kgfv2rRUY|VdcMgrxkvwMWs#jJBX zB3}b@$UFg}8}k$K@2m5y=mH! zCjP75RmTlmP|EEqWQbA(5of>In;^aWojA)WTJ)Q}c_dgY2&z?^D_p=;_1)f_`?k}oTr6j5!7Mgg4BF`(;bJ{ZuNB&E9cilj z^x=UxE4M^$QPCGhr}x#B^=xM>NBWH}E6>HjT$TBU_bpAIKdp9!-4n^Tf{3%blf`$jDGOG85jl5PL8CR)YyRkJrfUJ% z#szDE_)fcPLBxU7>%ruSrt2Zp`338t^tB-3?BCYAG@Bse?1Q~YS-2T1!@0K^ryx$V z^oKXh! z*0rW+QasO&a$p5qOeQi^Xo2W+=+vAyXhOUN(y_HF3vn4ZsS0@jTi%y4sg=;G1$=I_ zb8oemU1JL=W2G>P3vlmyOmYP)_xGjCdmB~CxK2~!-!-o1nw8sT)1Z`hSNhY7aOptM zsSV9wF_dCZaG6)iA~j*wF8yP@3$i!=mfk(?MEtSS3nI>{TY&6MlaiC)*_-4^7N-N$ z55!se2YXY(&dpqdtqXrW4`SLw{RQvhQjsyzbYbZzP0<3Im;@TZ0XY-}(%IM*Zz+4b zlKkPj#7XD?`$;u-t&2B0K@693MoE?r_GW3VvfgC1Q@jFO_3q+%uWVf$ZcW6*65QUs zXI+5Xi-^S4SH-5zLNf00SArgoUxWxpVF?hdp%BQ8trIUV)NjQ4!QgFWNH<@LkX}b9 zZ7S>DmT%!j5H^MuNq64}tU?&NKL4C_p8@}p+#n7duD|ro(a(hzhZv-Hg-|8S|FF~RF$5(76s{C3 z_eaAaiMR?9_9+0_n|IR3hCmVTmhwOqklu}Be?o8svNyZ25$^qf-K0)00)N<>52H1R zEPGJ2% z8X&b)46!bKE-8mgpBQgtXvl-TDLEje3DUd6xs+Ug)w{Wf1j+-0YK^Dgc6xI*a5>+D z?9JgkMtSshozA|*R>XYfpx^EE?tu!>Xwr$tYj=VD!)CbQsWYIRUb1??%XOOs2%m1w zLT4dsC8pR78I#uX2YWM)Y}@0zy}57((z|a3KL2^A7i4eB76@H|K8!k%|<8q^7cQFA9KLG_rBcFsT$DlI$o?xQJExs1mz9B&KG?>xcY!Q0ha&t#dfc|0bnTs1bN7|+< zt+x<&co(lhdbjHJ=iwcJ+v`zpULO)!o6&9QO za8EEk2pjN!VVC%)jr-rs#{Id)_-s2Y+Q81@%-;sd$ZxUYQN$qx_*_lzrWglrknA1KG=VdwIABNA03R){jhOC_zAML z-ap_cWG-2LT8Z zzOy}9ED`M0a@%|O;X&4V9b8?W6<3$FwV8fpU)%ZcCt0fiA@Cq;y|4_v%UX1u{=djt ze%Jm7SqqyK#yXRX7Qy-5#^uKH7GK-lh$e@V+>9Z>H6s7Btkp0s+yZSeUXw=a2GVRN z8~x#G@1x(!W0Y?9`>Q=wn!{I`|15sO!l(7&YX1itmrkMLEA4MKu0?1E<2M^O%)Dv> zWaHM%85bYcx(K`&h+X<&4t)Q$=ZzjZ0N}J|V+(_;9snxR_E=w{)}=*DJl4(RMz(nAQJH)|#X_E?CqZUM|}7 zF??QfnEiIOFa5mY@%jGn^M^lP?Iq2bj;=PMB^a+aEjZ+^w~|fD8sfklR$RgOJZ(N;8yH$ss(B(fq25{MNawQLwZLnQs$f>?;og&kR z`Tl;szkl2ND+U!1H~;4r5J%Q`H`h0o{~u$eK8!W|>wg2b{vEPZ*?%Efsx2e6c&9?q?^N#5f*Vj-}shD|FwWP+)%Ys zuJiPNL;>;Pl+i!=oOQqU6g|(s_ zD50Z4>uQu3X*;i*Am+QbC9f6vYXK2DU;Q5!5Fbd|3;G1sy#Kg>Si8UfP(W-%rNtSi zHP5Ndk3T5=Ahxhn)@->kb&v{@GGmM*OQ4I&`+UZT{78}+s+wjHL zUDHtJ*Fr@~A2n2@9$?nfYleYN8J)XU%~uuDpWG)`77JT$ewRpZR*F2s^;jyqtIRL! z1W0($;qVX7AN#-&4J-88>-ZuF*K3oqC}Nq5ll8G?c}(;n1@KqC<}b%rBw|{mu@hr8 zzben=lTWZ8nY*w6bUJ-OWX}?}FR&95CTdZfkeT>+uB0H3R4}EcWEU{#@E9sl{-TOtm?7&g}Cu4zFn8BI3Erj#8=>_o91`T50<_f;tZ`7>ujc`7aSy z>rV_uxL;YY<$Zn?`bfJ$Dk#k5dV@grz3bbQSFQOw9H&S&yV>%gZu=#5uhTZjOOF~u zDn&LgKibBYeb}ydhP<7GI@OIW&1X_?c5ReU;q&Z#>;msIz*o(G*7E7RNpw>AgY4$C za{QN^r%o<+h^Rh;Aiwu5SGR9K1w_F) z{0*`Zx=e^3)OM&}NZO!8I&_f_<}V~|1-`r6OjrpQO2pV>e->OKADQ4EiS$2WrLNK+ z!IS&&|58BwcFG{_-R~8pr2Q2ug;!brYa(508`p!|CQ@hX>Vf`!+q zIfw9bf1f~6L5LS(?zcpGBxE?p5LqZ=jDUz44A!wdxf7`*KuRi>SC#Gq1(#$|J4b9> zFI+mM&;Z`DXKZ`{zAB|M4}mm%cS4D_+%P=EfQBXv7GqT&qx0_yhz|)JWmzY-Z1|MQ z;XHO_no)ibNgGr^)cirxPT{r!k+dyTHYK~^-rJqNmD#>S=9wIL|0qkD>cHafCv;Lf zTu|AWp`VzFm0$Ap={$BC*Y0P{n;G*JRmu86(vEaH|COYjdY%gePiF47J`t21LCwb<3piqqH`l6Kc3ij=j1k@UcaSdu!7c}r`U)5XM%xWC#(bkT3KIuCtIq|3X_b2Rbz^av#OpEVDw@wPq75izz& z`}CKDj#PNnC$sF`2=;~X;K=G+D%m|Lt(%EtP$Jz=WQoq%ZSvVy_NQVE9=vj{Xyp zbm+epbNUxOTJs-}PDdUvr|knhExp~XzhX{1TkAVoYK9v!|G$gT+S0tz;)0^W{Gx)q z+N{L4`8j#H*?%fYrlqC+nRNOWJsKJo{sVIwkrp1{|10AZw1ZLjQs33h6C^{OT|K@t zPVF3BZ0wz_Y#ps^94tZqevdgdu`qmLuJ`<5Xkf&@=igd zQw0@mStU(r1&ucx9O+CoR?$8@M02an$Y_W;r2CY#Is`F$G3t1AFKRIB~_~?kK=sbhSJ4 zv|urBUy;r*Xci+WL+OTrc2ECBgaTg~>F%YzZc>V+F1yQK1!xvy6jvOUi=(HXg9*=n zIpW>HLr?O(RDyp07{pT%#1w!POR0tAHfcHlvwMRe1VLM84108-=^;06&(>`~)?#vR z8KHD1cv>1@oz&F=%8fI>bWT$NxQKU{7REs?MYpw2xTWM0dVq4{`c`@@qPk``ETXge z%jC1;zOV*V(H@Y`eB)lhIPH>ntfClYh*Z+}CkK6;zXZ@CMQ2O`r<`gu0?QT zYOD(~l0p$Yb7(J6h*}2QO^x7r$c=-u<|PZ#8s`~sp|f(K1@hbWZzgJU2ELHEn(kf^ z{OWl<5s3~5H|c#*5igx&)4R74CxpU-lE#VQw=J6Vj5^wrhQo9s8P$<;Co8xpFAvzu zKu#vq353PeZo%j#RY3AO-vHKFz{k7^d4Qc3JaJP<&do2{FQQ2aK`&SyyHB2a%^#4A z;#sm?M5htGquie>q?0yf`fG5#2^iC`_G5;AuRa*~o&r>$M_ zua&fXHxfsye3ZLp8Yp~!xF=_yhMu=9@=TIj@(|akL}Z#5{Yof`%xJj54DI~$+LLS7 z2Ek4z8<^_qZvxB*QaA)@i3H(80BvH+C^g|M-_ zSk7-5ughSk|=7sx5 zr^oht-jpfrpvDlQ+(Bfd*)2gC?5OGXT_q$e8MXwbM@c>28_xsIwuW#sc>!=%g?6VR zMlR$j_YMLBkDXbOL**%8_+h`6bP;y+_j@sD27e{iXbJ{MTH+YNet|^o3|SQdqC2FN z=cA_@tkO`CX@3yE-|rPp*N7(N@IZR+hMq!Bnd^a*Wcg zBCa} zgTF&V^4O5npQ@{0+gH-n2EJS+WgyY)41x1OrX-`J;d08c_dv-J-?izRSF9j56&^;x zcos)Y0vQg~A%c%bDis2ZN_fbPJEus`@kb}M8%^W-{Vq5DV-_R)kE(QFo6%l8Xo@O!ySa$s!?aTNO_|+7hF?g3Ewjl3p>$3Rpp$^d*&LArwz7_+x4H z`15%5A@Q{PO{l^zrq0Cr(9#kRtG?HcN`X2EZHgqk><4CydXA^yUPYNPZ01z`;UahN3Q`-2{5Jib;u5RIC`uB!MkC91r4Nar4t5PZ50i3J1&AOm zm8Z9VAQaev|72g7IP5IjMeJi`F?<*^Yf;zh^)VcIZLG(Pk+4C~OG+W+yQGWLdNeOJ zj5E^L?h%*gz(=o~7mPKp3t&n1q{9siFZ~(2;pY|gvMA=0RfI8NW5g&{WwyMQaT1VD zHk`ydO#-iQCIDGuNi)USG(9d9CV~zkwOKG}0myX-l)+SmzEe-YQ%QvP6Nr-b@qF9! zd!byFk|ir2DN5u{0nH0x> zP{%Y-up0xToD>1Km_{S}Lt{e79?`-{n+wgLIOoW(asD&?P6Eh-SgeueFN)6&}QMxX|Je-1nfkXa;0 zy`P2c(a8t>M0ob(M`Lx0v3BoNrAQL`9}VBu*u_lozo23Yj(&z?9|ErRA{d9$;QGQo zN2hZ`4QhTIFQY8m9%>zBX<#Zv91-)w=auWdz;K0SBrT|BJcUnEqlJu&;SyV$a|QMx zt?PkXdvg?a#*#J4n24H-I3HIWfx+=sfOf*nohX&&i53~#^hti3T8tZ-_O6^T z&%}IJNt2q;=E5PM5BK;yq(c#Vp2VPscM+4khCAJN-dH~0vTI7xK|K$z z|4Lk*^yQ6hB~nre!RKW=J}iSmHy?$s6xmF$;mwhW8)QUUR@Qg>vae%$h(vFnxq94# zeo@+LnCFU4F~ONi>+%X})*bC(!rs1^P)G@GdofD2tx8r!W*3CPcs|bP1tu0X;r@6{ zBcX%z`7FSg%4r$w8NK2wm~jWCxK|zBdWSW}p;?rb>(0;Wo{;)DGFCYARw&FS(W)iU zqV57_Bv8?*0b(}3#j(D$yJ+Opek;O$S*U(!C%)X+%)Hc$409*~^#Ig*->2AeBFX*} z4zEP}{Z~}{(PEq#;@}5jyatUP&144%+4|9T5k0rFSGdBK3r11uN1=3K{z&5cydRYx z)-P|zo|y~}b1v}ZT7a!ieR?F2IDEm6nx~$t1`aB^dG~h}p;g#*WnEz9J|v zI8Z1n7}_V8TEs0z12by|;F27&?*JX721v++Q87giFJOGluJ?LZ_7XCLc1^RmU+Ph% zWJSH~s(RR^UFf<}aQ$3Z>s8q4M37B(*c3ZLFE_$R=maGV5oEX#)mTk_MiS9^fTh}U+ z82tGd!s{4foLEv;P;goo(hWJI$e86?Q0#1Tb12!8^!peHQS_7(-cfzyz1l{Wd z9|=e8dDiDC1cb1OrYVVLa2&T+gh|JVHm-024T-uUE)FytSvf=_&PmEuaUR!6MkEo! zg%a1QiKmblQ5#X-lC&^;gu4~V(KxYzI4QUR2!!G(s>+C+s}7@dyNdZXEdG1=>-#N z8N1wkY_CmIUTasqenj$yMiS1k7T`3HA(WG0D3W0+8KyXy4ndNsQ;1aO%F&_*XfJ%D zK!(sfkO{!eLgmdu*UZ99Wr%Ri!fnjLU&z8pO(n$5=2ns;r3LW5#h^;Xpb5pG)6D(= znazls!^)e(u9?H>mcyNz!@G~|kBVbhz%@+txW++I z)dX~5q0ETnS~jBEhYAtIgd-ZLB;lYiuO~q$N=Y=Lf@x+Q-w&XNrBb4^6hMGuH^RBN z)1pPdqg!4SV4xHl&LBN?18C!-*+my%ZRj;jy=5hdJaY1GuS8WqDGCY&B*3Fp?z8N% z6=|O3E0R2^=LC4W0kRZvS0xCFxOHKLNPmul(q|m~P`8n6wuJ9^-Z@EA(w@U{T!Zpa6ynIn_k;LU}HnJA>u|l9v#XI<0_} zExs9iBoZBKFf&E4jUNIHAjTV(9uMwO3`|0~4#RCF;2g8#^t=Qn$KCeiRc1wQkak?G@#(hM4sD>I2>D z+Y4%gZyBB+q=q)tN8>fb@-@V3H6-3LMlB|!xHqIPHoU%V$VA|Xz-xS!R+C!{$VsEi z=aWx!Z@dYuC_7*%Z;~s;YtmL~s!eNZY-(yA^6#8!+KjcVfp2yXZ9;zD+;o!LO-GCA z07uf)+{ju6rT8|xzVVBHEksR5KYYuQxlB$4F3LS#V}BDtk9Ya9d+TnP^hR3i$Hms8 z+ty>eHn1MTqW!SK1DPBa%FncI(8By{i(zxpviC!6k1ARfS=u2z$gWW8PR!dSJ3Qb@ zXc6%{R1VrTHej&RJ8)z=@IP{BUv|t+cNC(&h4g46ZDwC^?}YYMj4kTqV&!4{m;lDy z1qJ})%Y@;kht>deNeXv?MLSmjy174wH7In8dvuG1qe$(0^=x$IQFq6KzQT>t0{CFi zCXU2MGqU}sdde-9$9|_eVR8&3! z4^!Rfwe|qmmJm?lKdtCRai9k{$#7>y_h;RM^(ig|dR6pZrAW(t?2AZ`(!(z^@ZeVU z=y|miQ$SX)$2RZ?yoV6AeQ7Q_AdDj$zgt6l;A#K!J(V7=^e#RRGOb}Y*O)>6<{`cu z_}06j*5RRU_aOs=!OmumCr-mMcA2Tg!|zMpAqjUzOAjxA6Vq41TcN-}Tn`_045#Du zuNca^H72gov#-dcP7RM}84T|aGw-F7@6cy`T4FvasR8!CKT{f2G55VHVY*p*zpwos z?2yFT1yaiuQi6EwQOg+Omxk@du|`{cT-FXiDW<&QIQAi%t>8FL1fI*%xPHY5@iNH< z|Ac{oJmk3~Wec9&Y8~B|31)&x)+dwf_d1iDo|D`ele{gH{L7O9UnT_!ri7nNiRw&= zdrko}rleY?WWKb*beG5;q5@0^90bc18PH)prWs@EGzriHStxC9$90~}7%{Ls)0xo^ zaDwomRf(8U1fRAdn6-N{>!361k-G3(Yc>#;n$Vc5a|K1WY7M=LZJa5x*BF&El0 z7rs0f`DHGeU_N$PUiuF8iw0Vo78;{xqcT1kDTvk@Hkrgf&jLO`2vLeN-l?F~Z_3h4 zI8iGnmQ!MhInjigC)JVvrJYxC(Wqk@op+%KVip&C5WizQCu9LPE9Nl+#+DoIW4^3i zsfCFr%TqebGoH(H8OsX{X=N?TQ&#X+D+DX}6*LSZu~g&BR;9@Vc#DVz*mqp>Uo{d^ zd6pLwkwQdUU|E`6EQKfxg{A^NgpPbjWCIi{$UzgLV8!%$GORuVCzy|3>?W8+WCSF2 z1$GgScsyA{!^8gyB!s43AtqcG6v{@hU4=sZ#e!V~qt66cu*VQ+|BaW4|65tGzt00K z4K(~`{nt1D(0@&B>_}>2t*EJbS5;YBRbEn3Tk-Z?T|!NBSVdE1$*&`I zxu872yUgUAoXni;%&e?8uV1JC)qIUeOt#G`Gygkl#QG8Ge_A6Rv}Fpkv;Q>)@c-C+ zmHlSEic71ANGb^f6@?`f1;ynBMCJH}W%-1pd7esg3rKPa06F<3IQaf+I*xU4_`vea z4nJ5lTJ8SwtgavcnN<32ImRy?N4&l$;(xB=_``w?3q<3lD^w1bP7}zG`twwssw52w zt<9q$+zU?3tOdWftu-0a4^wpxR22-|aBsz$Vec_ZARju867nb7p&EuCQp542U&}O{ ziWDZkX#G;i{V?6}34W#?Ykhb0tyUuPw`JmZz76v4Q*}Z^R>AvZ3zlh)(4(@=^|o;_ z$b(M=Z0kDu(UL^EE!a5D4(1AlKP2LB3$DsLGUo$flC(T(edPt-RvWcT_gb6~^7^z1g{hjF!4dZ89 zE{_xowvzP!+Hw5nf&u%xInm<(bTHu09mn6M>PpP{2#e`8T3j3G-3prD&Qm-QFlR8G z&}~wzVPT+H6CQZ&KNGcZnQQ1!WakoVZWvG>DO)9Sx-6o>OLi+`12XQk@a&CYZ3O>Z8kf9yW@DZ z9?tbk$1z^r>RZPVv`p-LbiI=q#CWrtn`CvfSMav%1{4f9x;ZHCWBjp9T)$Ixd(`~- z2((OmFDfP81w-U^LPcVIcUnyUq2UyOK?*nzs%7A*b3v2%0vxeVZ8=*F`ZRGV>SztP zt}8u^zLB@RO}?19O+8E5{lH0li?9}z{B@nls8u*O`nB?Y5FYee#4E_`{*jwHI!L>2 zA1Ls&t?IyrTO4Bv_xblrb}wpr@2r*f)AY2~``Q(SZ0Oyub>UPUg`+hfP03Dx&Nq{t z7@C3Jr#@Mdm{&1h6%IAfo8hnTA%I213jh{we$o>1f`^V{hywi#O+K)PRt_a}11=Jt zL#d1UYpAKLt(>yUZVxIAQwR`uet6K7uGRs`G%5vhfxA<*PB1r6%V;AjlsrMQn>vc_ zdd2K(rFbYsyaSOZiQEu_TttqC_Kbo~N3=6>s=^SDCYD|+TROBK!U_UimC28_ zQc9{jo`xr1oO^&;)5IK?@OT?N?GBB^fW z>_pey3PK#76K$i{T;tT@Z_yRA$t75L&wJ|{d6N7hRRk!e2bdkVqlugXvi*zR?qZvb zRs_eBSGdr~bMGfi_M@i4rR*u%6me%e?P~>W7D`^tzHXFE$Y+x*P>`fW%j4`Waxf2* zu7iJlK^`HbE<2$y5So!(>;Fo(bXa~~>Wy$26D3<|nrsuRdL!#wE0n_S@m$|2zw%GH zi@-hnXJ%-nHwjYUmcdiaS(84iqdDl{FJ+T8i=&!Z~UVz`~E6E^6})1_u6 zvz_enz66`=;WfQbBf)TmCis#ncwWqrEU zu$C}zW1S~R)B4u9&b6+0?V3W*SJSt$1d=&?-CcFJ!LR1EqK~}|W(T-5awbT!l|7}= zM7vk)JxI1CJZ**yTOq){Q+eS_?KKVi+YSzQx#QIBQZd`vH@54#^{iZY&pS@CkOjK$ z&F_Bu``-W$xWETa@PZrs;0RB+!WYi)hCBS>5RbUTCr)vRGe*l5Pg1){60dkIrQ_<( zcw1~O@(qQ2A$$J~iF8UT!kS>beHWJl?B@tEr2fs|2C? z<0nt~%3J>On9scCH_!Q~b^i04Q#|O?MEB8SNa&{jiX;ZI`hhUD_1yUnPGKJj*&~Fr zNWKpuV80E{@;>#z55Dk+PyFH=|M5#Ru2z z&&RGU+_(St$4`DIioX1wd5qrC&;Iti|NZcfzx*|a{rTJf{`k+o{`b%S{`>#`02qJ* zIDiCLfD>1L2AF^fxPT1UfDZV8l7WB_IDr&ME2UR~PH|O4=Xw}86@=G;AZR6jfqEfW zf+lz^5_p0txPmO0Iw{zKFc^a}C@beTgEm2eHh3K`7=x0RgFcuZX!V0aID|ylL_4^G zHCTi%frCoegy!*qP8fw!m?}q@DFASV0k8vRkY7`16ITcTI}i)8kOy2SVA6LjUl@jB zNQMo?C6Un$a40!n7yx3phGj@wP?#%(u!oXRhhun$CFBj^atZ7AB2~y7)R2g>;D>Cu zV&VU15RMiWhbSM3NDYfvhmB}r#Woi^ND7|#iDzUUpD>E7z=(hdaA-7%*pY^&_)=iU z6nis=t>|EOm4vOrigw6i>ZdKZn2B9D6mzJBr&vO7b`z@ji^zyGsIZL8xPj+!jL8^{ z(m0LOXdllyM zN00V+kNB96dvcBXI1%Wm6U8%+?3aiAs1epzkU$}j=_q~(xeeslkP-2Z5a}Kh*%JI% zkr>Gw3Yn1{IT9P$k^1P39|@8qS&|nqk|vpw^{A38*^(~#k{W`NFgcSlIg>USkT%wt zla4e!I@yy%QIkFyltMX_?6@xnNt8%A5O$Z8d$$l1!;ly;JV3dC7a5gId6gZ>jV3uB zM~RhQ`ITT9mSQ=UWLcJGd6sCImTI|{Y}uA>`Ic}QmvT9mbXk|o(S!Q;kd)Dt8^M=> zMv$Sgly*6oII)SG2bc_@mpdVt#fO*<;g}@{nJ%K3rN)@pF^+_pnVPwooY|S4`I(>@ znxYA4k~x~D>4SSQeGnlV#dw<2=!`JgnhOD&2$ literal 0 HcmV?d00001 diff --git a/docs/assets/python_portfolio/unicycle_obstacle_avoidance.gif b/docs/assets/python_portfolio/unicycle_obstacle_avoidance.gif new file mode 100644 index 0000000000000000000000000000000000000000..053c5483f31d178464d60619ea6eff4c02ad6054 GIT binary patch literal 604772 zcmWifcQhMb8^;qPAtFiDt`U1w&Du(0&)Ty_jH0O8Rik37wi-%lDKUx`ZR}ZM?@dvo zR&9#fRNmiv&gY){ocsK9&w1|i&-eRWEgelcdB?xxN@Vc>0O{iJ`uyPfe4li>b$zz~ z@9fXNv%Txnoqxw0m#2FdM_X5a*DenKWA*A_`Rs80bpQ9s{_lf>t@A(2$A4Cj|E%o& z**M>wKiXUVySsF_vv{%f<8b@e;pWf7&6$Jk#XnmM`l1q$^Ly)ad+R^<)@SzC zX0BEn&Q=G`R(da2>MvL7PJVS?ELI=Qww=zD?rbjZtj+HHo?6>j+F6;{T$x#1ncG?# z+x$PHt4q_Hi=!L=XJq5o@Y>?!>aWSQx&D=fiRHQRm7hK9Q^bv_x}~YkrKyg^+3|&+ zqYKl+^V1{q)5D8Xo#V4V_9kn8{b*m9Xj_jL=${)S&W$$D{-5tZhZ|>xo2G{vrU&b%2kRzBd&h^nhlhJd2fL;R zYDNY+M+Q2kd%g|zwGZ^R_H`3`I$L_$8#`JX2bw;OeTZ!BY9oHHt?3`gZ)<63tZ8nl zAvSz1Z>(yltE{UjudV)8UHPr5;%h-wMFpXh@U^6@w7BF;(U;;+p9}GYpYjXxbMy1@ zA)kwL@!45fAF|%3XJn+OrKP33eT&24UcY{wnE3L=i^PQgNJtFE7sb6uw0QeLJ27c4 zigo50WacS&<|*i7Okh-W3^p<*{CQ+(c*L{N=TAezpFRuodm0+y=l{ev@Uc&T*Au@- zUcRm#-Y#yBogR8RI6ty;bhE{{J+rp6vUSdpkm;?BW;mz__Fi$rr@!^~6-ZKNS7Dozdr003O)6adhFyU2eF@c%Xe zP>}$)so1m$_||Buo5Hp|gxvOc1dnc(c6nasOJ*sLxt{X;?l(xaL^hp@g5I}+reAD( zD?at7i#zva=~NaDX3F_*&Gl9m4dew8RhGK)UEz9Sz=Y` zG2d5RGW8A9p2)6OQ#w=WKK{k7zou-q)@P;fqh9UT`NrVCTl4+3-+r}V$!R$B>j+Ej z2{&)s57d>fbmMsRvi0jLe)nfcc`gjpSFR7^)n0NKG*oSl7n_#Y4>nY9PZ6B^vke++ zc4zDSw-*K*YybQrM$>TKZ>l?3>3Mtm>G`+wmPaxg@+5(+!jjG8toxbS(qjRZuv$e@ zL}gRcId1ABTuN|W{^;fSuW_$mO&8jT?3fq+>F@0rL%{e96P?i3T{(88FD@8FJjm~;D}W=<%u(k{ zu^?^CuUOgnSXPjbiyGSxIYh#tc}IUrQ(8?>8b|$xg^Qt-Le!cTrkRic1s7f#TSde@`;_z;;{=4bN)NZ;CiR#*Eq=G}! zSX9GiF;1gvbHOYiN?j*<5GsL#cHTW(MA-y&JoMN6VCJq}kAw{6sVHxG;F6z{1dIO5 zjJ;Ak%lO+*2O88xa5Y+u!<4Vt)gTB4q~yF9$Xaq1o9EJ&fE?`EQ2*pm^aC`gWe3 z1(KZqn+VVS>XRx{1JMZHm`J{hf3q+-q8HsaR1u6sMeq9cX400dQ#oA>FPhCM z>Tkd^XhmnS73>5&;@Dy1 zOOl-)ny2V&L*}j4B@yB?kXLY(dbT62)dVt@LvZ7c=_loK48oXuoMojqpcNkQ+5ZbY zMU3*0v>J~84-#UyMZxv&%@|p^U!(tlkz_S0>TH3Fit@!jxWbF7d~QimMzcPp1YHwK zRoRBIf4kTS>bc~wPOg9Ey{wc642Z5J#Y>!%LN>Ao+&0DLVf31{`LFE@sy6B&E+{+N zU0bNo6n?>8z&7zV-M=HUILKWWxmIGbCrr#0KDhs!)Wd-$!O-wuEN>Ladr^|B>n{@k z&I(xspmLTeEXoDLK4i^+7Tw5#LU`#>SM;#Zy9m)Q?i?qTBdBEo70kr2{E?tjnyxXz z?o3pN?}#08qerVn5cdE&aYNi)j$KW}+l1VDIbhoOl>?F|>?9ej)S!jimezXJ|LiS1zm0 z3gMnTppVXQ5%xXK7f9_dS^092ciZI;F_x68KBPAq5H;q{UNB`d8BJ8ME}#5%Ep_k}!i}6@KGH#gjWo4Mxk1BEzQrm>pAw1@)fwVXvLj!e2eI zzqX2O?H!TNVMRA&MJKAsXepQYCyClxMZ#m+=*a6$hvvj_7T4_@n*MF{A5Ebm)V$;$ z0G(uNLWm;J=rac9Rz;dtgp2;VA(gR*f3xp+#2NWba_e0Gec$#_8E_eSc`JVa8fP51 zf%JCo=%z~1Suc>%@;}Z)4b)Vs_5wJDo`H9TQB*jOa<1?GFi8rht_X2YWMl^HHb|1< zx3pF|nS`r!sW3T$zm#mv^rsMG?*xIQnU6-1k?{#yBFyxQif(-zQt zZ<$lM2L>v90hCx3sad?YNf*6aEp%tbrfYM*t%!>*fnDe`Lb>!w6+;h}oaFeb?u#b@ zyvYdqp_mkf8kR4|B-mxDy^85@Qczr7vZnE)g+e+?2VcaQ-&~$Du|7Z)U}8nz#VoEh zIUy;7lKgL)6zidCk@kFoYVJSS#6XdugTCOf774Xeg`yi|tysn4%MylTu^RGcMM6}E z;5pV91l~$R^qtGVHE2ryK5NhYOw)Oe;c8>b_uu@t^l+Cl0xeU6lC~AMw6p0t+K13( zC|7f?Lm`)zH6MGPLjM<$P-l`tqKS6xB0zmzJ-?Lv{&qm!ZA=#9DuYBRR;W-7?g>?6 z$Uu3cS;G*}EY*PK%Tkd3bk;4uvrJOiUzMsp1PiW0{vlgnAkHS#tI9NuuUFWk$hYQ&LR%&y3biuidNw9QyhH%z*dl&8v zt#td8=ctS?$h^!oRRM`YonENqz8m@N28*-3;ygln zpr6lYZOMoKV*GQ8(k4J^WVJcCWzN3+SXYGKQL2EE_&cOuFT^%gvbu3g{A98PYFzU? z)q9epskM-m!o<5asPnAMTKQu-4aMJiHZs}B4BpG+*T^S9Ns(dKaJ+!aPV?=?Q8z=z z`}*+< zTYns4C_O@7GQ6rb%5DiX9tof1MKD!AifQ+!?Ro4Rr_CU4UonAD7dIy%jMUei2DxDS zd_u=JoTcI-wcIsm%U$-n9_UngkN{$jCj%G&J|qAZ1SI=?3Qzw{G4AL>v1C3|^IWbt zRyE+!kOboWBwJW4;&D47+0u>A3Wx+)7pOj(iwClGxKOle4g%q_HGY58waAxTB)dcC zEP;5^V&sr-NMBJ1S#AOe3pdh4NP;{KGSo%RUf4@Sw~Jf3J%y_qMW@OkTEO;y%%rWMocZOr7=4%hnuduK|5!3G~52R&X!C<&Q}Os8ENLqAdGd zH`kL%JO98$1{CCr__LQ94&Z7x&?wFAbSgh}Ve;0Hvk__vNAl7Ut6#i2L&@+N3n1$V z6%h|LJo6^u;lqN6=qaR;x%_y!jgl#sbj34mrWlu~_)GIh29*DrAR-(P`HATT(mnbY zD6ZQ4#Vwgvox!hqsS>$AGcZlF{l*#CoWa+%^qRFEn-)bg;Gwh?u-5_5JW~M%62X;L zk{`50^C18_LZOCFjUfYq^QYJjaZsYs{WYXNG}mI#7~Z>2(=D#^?1zPSHM9juOKZaO zJ`UE8GVUV83<6Eb4&o`#X!KP1k<0K=yg@2sGKBn*RH{Kg0Hrk%w?2&|85>XFjK~5I z&ne*_tzHgBCXfL`cOD|HRt*8iQQS4psH6>OCR3Fe1HV#0`vEa3d|r$%LS)=S#fsC~ z5b}qPspAEy`kSddGat-ygA=%6oy@|rRAJ&Q6hTGYa@Igcr^n!2Q?4p=^+%CmmP#-Q zz96~Gadaf@GHluk_GikV=BedZ0|;J zgQKuXKE!Cf(rYVV7$%K2CG0i8WUV%_B`-%fC7oIofy60MnZmi#5it{N9~NcqtXsT} zildf`2bEL1*K_}s%VAgyA9sXj?JF~kfCDz!`bHwf&m-~Fcrste?`b5NdR~H49>k`| zc!{DELA#BCpFE>&!i7C)D@1*W{#Y;8=tFyT1HOV05g_$RAVe)`p!iFGXgROfS;mZ4I^*J4uG$T zkUnu(u1C%!f@V%ol8Az7ox`!hU?L87J^~x`5sg+rFk`9P#9;?`_^ok?Xa-5LCD2!K z+DWIJ9{{Lv2O<{bZW1gttctjgNcT-ZNMay;c-RT@t~z;1#xrHm4eH)~*eMo9#E3iD z0M!XJt3>GuB!qd<^4~KRl28<7Ie9SwYNIAPPJ~G5N@qj9u|T~Qxxk{AJo4KtUHCvy3S&zTfkf+#C@SveEw4pe&;Y(vf>1@N-%Leu( zb|Y|O6-^?;5u)P34ZTIktp|mkl|qt%Jj6V@$neJV#*tgR?LP2B z1-c={8_BHSe>UD4-*!FS2lbMW@DVgsn-T1EAJ#=kuD^{4^MTetU^A}d4Mwmt)LT8A z+RZVl38ViW0@OkP6NQ5AV_@ki_ZjfiB=L{4jl^%G-^nDP=O|dG5d@wB`9Xvf;Ajqw zU>4QQ5%}US7)WjBBS`@45()i8fJ}~1sf#}*BATAwq`pAGJ`*6j*r#9~SicdZ7zf-U zSd%-xwFs&Eih_eAc>Y?^-A6*#eBe6>+7@Oy85BEojtOQ9e6kjzWcu)Ku^(s*x-E$q z#KVUC*=N?2rW6s2`>^32@Hy6E3fMuGOmm8Nm%+eoUe#&L#l9FR=5Zw7M#6Ft)OaM6 z|2CcJRg*bMpULvdmFqS+8bNU|5?D_|aZQ9Iv-LJV6kisPQB&_EE2k*aLUg0xkNw&2 zJOJK{OJJI4jBD(^z4Yv;K6z7v?nP5i=xEOsz(ElJ4GFe!PGwJg=EZ=4?>XiYqLJCS>NXFls(!`6MY$mtNGS#ktyKn)bL79`unQR=8i?{IBTziR zV$9c(3{Cq@opusn5druiJXO(!dG=!wJs&^iX2KPHxqj0(_Ga_8SFx?L!44*FH)|NCKpu@~|tu%~nVD3FqnA|7N?7r+6TT zpwU{SY-R*=^zF^IgkfP#c0O%H*f{~#kGE1J(rn@2TSm}XKk6l)`#0&RCou4Tiq=yH zQ>;fY+|N3(q~|~Gt$4UVmwc$AlsDuq;P)N?$4IDvvD^~KsN&YfLLuWX$whd%_(s%y zj`~H|JJAg!V3F+ptod{1^c254xxiPeb)g(9FLu{g(U89w6a((-r!~+yeuG5ZC~j$R2q zqg^$EBonC15lTorYza%<>+;IcJG2XRm&p zC6UfvM1TV@^a1emcM<0qIp-f*&a-}Onq^n<~YZVfJ3;CbJKuOD?o?*148V63+|BNtRR!?NOW8aZsywV{QNF_tT zVp2eS!)=g#SDWs)?ptB&W|s}RwSj2KN6le%#_RX9?}cAeu$pZcWkF- zs2s~$oon#fyv$xhhrzQwOY{5nj+LM1K%sNdJLyIvPn$xgnIGzxjHsz^fx8QxnU;Sn z3;cQ;j&E6s_f$vIa)OMkMCZSUv~yTw$yChrI^TZs-8RkFdFbQ42++rJvE>e5ot%?Q zmgBABFXi4ayQ6ZFZ!uJ>%iXODMt3UgSRmAbZ~mMWWCBqM$-JUNX|eWDBm z^BVE2Ah(C_Q9jW1L4$|ML)7cj%4Vz36WbOZQ@)e#<*h6EjrVo`d7g_Tkj5L^c0-FJ*PmX|F;au^-ow_yVdZMz zU8Bb}TvbMB68Z7?@PCKnL;4%3<2MAo2}s~vS4^LNwYa(NpqL8fWRbYo>XH7$UFqs> zliHY#O3hTqbxwWJWtXhbj?XSUGG)TpI5|!hK0~jngF-9kHySe557QskSi5~61>L&m z$U#^#!*j(YG_;{h@BG)N#NFM&wLD$@+SFQ^QXAJW$1uV0nd zfw8P6$qrdXQBVcL=hGJXYS(oC`0ieb6Pf+|H@VJ**B_gFks$*;wi@F|{v(Y&=Rn{Y}DQQ7f!%#?ps-SjyFnB1Tu8DcD*@tj{$Y-mfP%tt+%E(4iES<<<=5@O1l9JJ*^f) zkvaUP2wH3xT5pLU3Atrfv7HF&7z+dcs^KrQF%1*ah(G}d0Cs|lxv7r_GId};(slpo zpFtzhoD_~!8gi<1??z&fSy*r)A)Y&RH@Nd}(!g>%aY*C|_xVPQx^6k_W!*BT%2f<+ zFpiv?aWp|oo%=?_K9w~>&-y3EjGvh+o`WqJY{KkBS6!ze8YBU>9LQtp%!uYYi@f2M zrOq$OCE`_V;P>)o>dMvKm)0VENl!a?*ngkNq3RDJhJJ$9iup8D&M>c>O37*2>$H78 z3X+8)+5o)rI=U8PDd`<9{L=M0_k+gX=1@EoRI`r07lV4x9=%j=B$T#F-5E#MnhSeo zmAq;GCxrTFfmU;=!`WAjG2e%Rc4A8TtQVf%t&fpNuGinI-+Y2Ko$1?m1ya|MyfOyV z@se*INxbrfx+JsCeLOi5xTZWz_iKzKBh;fbYbsp@`dT>{k-8y2#&GN8iT0a*28D1sSwa z>wH?8pt@9Wt)6UHUTIp)N-a)FAb!JEx45CpZTSD)FtSwm!ScQYc~$zzX0pMe#y%x= zrVnArL_ZQ$kSZW4sLplmo2V+7OV-h&p-z|k#_Xt-;fi}!hb>XWT8`{1sXtd(L&9US zH;xxz{n0c#xL!oil?(zwWn1+s{5;I+fh89dh_@wM*rlqaWS_-De|i`qnVmWI0U)rb zP7LSC3Fm3X>aA4cH^EeDHImYuD&prBy?vAS0`9Q8b1%(C)a8+lGsmgRpe^M?RxA&1cK$Ir7%$w1A78mPw=b`1;iL6+m#xAdUzs(d3 z@a=C_nIH=y$;Zg)=B9QR9~aIN(!au-vIcgm zUmCx*BVS1w)s7SBDu<(|0nEP%V0rr+UQilmj=i2vA$2dEwJoz@uV()b5Cf!4D|5jD z5fmbJyenO@-6gF{L(6ev!|BGw$f@gRYoLz}ZwonF7M?+Zgvnit(EjgJ{s$2V9Oz%+Yf)kEjIzQjhCu_$k z)Y$cUpR&w7T>h)G;I+EXu?q74(Z!={>)dxyzx%|H2DqX3!gpnMFKkq{#dI4kuPxah z&rGDdx{;{U6~&&Ny-H?M4%1Ox=6r!$1+TUqOov=?DsiIje&F)*3;uAExM0nEWjk|lH4h3|SaL1%55odLIsxRM|xIj{3jrP~4ojv_=`MY(Vb>o*dsGX@x$y@U24f&);>#DdZ7 zGJEHHQ_=VIg+W2V(y}99M?e&xdtA6UQ8zKpvzXTu0S?_LYmP2M6o3DnS+F*%yg{zG zce8Q-!P|=H^23mrA`=F-($+uirja`p7pUJEUYcOeh7}0w1p1Ig;A8X>E2 zzQs!2(M>>HlS3+lqzJ)jLy4r5(lzpymmA*+P9+*Rb?GEZ^1IhP>L_@)-=@!6Dx|2O zn#$`#Y;xV#lt-XeO`GpNPz+V?9yjXV^o%h+W433dL_#&VV`TGEQ}oOdOjorI{%T=U zRds&G2BYM(1u0z+GQs;4y4s-MilQ&KWB!wSyrD!48`eaz-WeN{RtYvIR11_8P?Cdn zM<@a?I+$s&ZVE6Q6RX>XwZ+G18pTGp^Sb00*b>1e?i7wj&6;djXIy+qzk=W0?v|e3 z$?0B$2@01{kd|CuNP&Jno5lzm%_m#kM$bNrn6{!+UK1*CSa7@tp$bRSr#MBpU~ElO!Osuz!990I^9wY>qIJJu9|p&V0>HHs zT{?XL3>F-GMyb26DaZy236A%At1tbxrca51K{3+p4468mb&wG?Kp|-)qET=)5Gta3 zt<*L~VMM^F^0ybAsZo$=7-f7IFgVaZDd;W<9zLVMoo6LoC^35Vd>%P6q&;q?WjBD( z8u1-LFNhAL*sugMy<#} z#GQ&8funldae+PHr-(Q)#W8{70?J)uWZEdwE&)uWbn^je_{3=dus3^5+=!G^f>b|-H-=%creRseWn5zl46lK)V@i|bVJTx@a>s;^#~H0D-04`Mv3j$DHn$=PEvVq%J8Hc@XkezFLX-PJdlGd4`q;-WNGlr~VBA2-#Q6pS@q zCpQ}j1Gq8AL@i=PC!^iO`2gZkZpFYDBY>NDlvu3ct}U;m(>jSO~=dst_orw~I5 z-;Y(tP(~p20&yT`W#Lh^wTNq4&cDBv3+56<@t)nKVa*n^i%BH-7m#Qaznhh|+L#CVZQ(v{l02v>m9fx3!dWZ-6${Bqvu_0wO{luCl zpzlnm8JO8xO=wD6+Y*6N;WN6w6YFB7E}NR2?H<%Vey}A?lan^9aj2z61V0*y(bSGz ziMBAEj<G06bOumOsq6+Y)Hv_Fh@#>eO~V+~NT+S+wtKK&v*@#fkT_Ge&i9Pb}W zhXZz$OK|*uoou%cCaWosc4^O8;T;>~{Z!5SK4uY!i2?@AC*4yBB*f|Nt2x(!KuMtB z5tX&=`F~e-iw0C8lP03aCgPK05_hP$Mog?8FJPn}yx-LkB+P7eE@V#5Y=_hA&M$xt zyFC!`mi;{m6WC`xU6Z9?y5fSxTgo~Y@kNx)4&n_W{joa2;4l78BtZ`BS^ho8$~Zk% zd6$lY_iy9OjlS!)E$T|fLD-N28}a#T~cA`)-v_*~*k13t0pY7)&RWRw(1@`Of0!&C!fkxy@2@64?ca zX-fa;c+L=TOK6jhN!&xK-^MismcjAw$tlB8D|2%_;11s3`6zsTfns5S(t@+j){4rH z-=C$?9vKBjXYqVEUJz1#!QAEc!_`O)OO0aSS~xa)*JZ>Tw#GCY}V({^vu!h`zH_vQd5(ZC{FXg4q#^^6cgPY-AavKaZfw`{xohNqWFy8DQnH>dUN>m=3?A|fI@tsqYk5$C@4|)< z#qpJeyy;oI87?00lA3%t0JOpJu^iZ`vaQ@(0HWrK@V2%AS(Hlgey9U|zRlw0==W~>3o#P?Y1d8~%6Bc+IJ8OnuIaQ8x9Ru#Ycs#3d0m{R8c10j zVZ?z|>xp+CiBU&U9=`4Y%29?UP-?qVm{@`4r1U$?1|nU(6z+oc2^5}!;NHR=Afn^9 z_uhKa-WPkYsWyc!D)uZ^h^B^Dn@9mXq0q-ZG@p(?f3O$6L8)#<88I!{(jJqnMyW5i zIq+cD^YLTduw9`}7cd`IBRGzB$_EzDV*F8ge&Nxtp=KHZj+)6=L5zFIM<8RW7*#8f zKQdBLgX;UsHP>SBvtm$>>9heMj*SFT;K1%(4ee7r(WPq*LB*R|Q6BA0A9DcIh`#Jk zv_VF(I{xvl3AXRs{^&ZbK_)sQjJ9|;M6MXX@9+|OE=@tGhW`3X)0aES3Gr5IL%fm%mH7xB+;87?Gu% zCKr-(9VxmFv*Dr@3?DCg!HW8Kk2%J^J7C}WS$cXx#&Ci&5>ya%QvWV!7T|6BG{s!y z`62T?J`CM5 zVVD%ZZ#fDv-Ab5vRL#@##j@6Qe(S$s(-KVk7MorW-*B87aHnfP)?B9oN&POwA@LVhs2%G8iOFJf>^O9*Gm6Qo=;V-Un3(YSG(88Yi-C!I5dVBAC~^{Jr7X* z7zIKmJyu8Cb!%MPNs<3)!g?XOFm+0iD!5{v>ubw~iapD>8D_47YH(kH6XX{Vg^NI^I z>x>zSvX5u1E$~OQ3f8%;2QvcsuNAf!v+nUH3Ve!Luo5b?vTtxRd{goJcVc`4uZLbi zh0B(1aduU4QCY)J_X3CeAB4(!25oMCWk=)HXjQ!wxJt^RY}U%y7#lOc1ae%iRHRW} z3RjH^vv?K{uGx52Oyya%IcQvM{i=KeQ*^AUd9LVC&;KcNy}mj2_MN5!U9CIiyB;OG z4W}HIYPBaEr=q11x?A7MDR?{|CsSFz6Vn3pUy64GjOu-DyIANYbT_CFB`jXFeyeoq3!wXBky*&wOlQHy|Hk8Q$*vZ-Jy+PjQ8aYE z_0_Yu@xb!oJ`=1bU0v~Q4X1A&mrs_c4^=U|$}Jp6P2app zjWfAhvUqZJnschtkL53Mm|)G|zG0#r4S$7%9dY-WymITQ1eGEs5Ha4Bjw@m5 zZR~A{5ppq(w2^X^V0r*RY_5koa21{T4;O4ep96a)*!k_;CsH-*J?L9cGFbdi0;`VG zi+6GbA|9&=uDtm-40>9HDty&%E8!VGt#;n_TNIPZ;9=I`?aI5C9A#0!`SYisHlKw= zg73}>ms(Gb|7{N_ZMk#mT+I+=KR$RDW`X;TB`*TiNh}LwsD!Oj;p1 zcey#PNXU4$xvK8NhjgiNRlEd_nO?hv-*5HV_(UV+bL4lHU_jJE<1REL$2OlegAga- zVy%N(NcqrO_OO>wJZ{ zJ_JO!B^X8s#;Xjpf^+Vwp#vo-74{rot3hLLuGGcL3E#+lWK)#~C=;TWeLr6AXO`ry zze-|@6pT?~ep_tQC+PWHHGym5)6Fx4hKI$?RP`MmhKK}8(gbs<)7zWyM*802$y zp0yIOkx6<~{n#bhEYW2|jiVc&Vf%+HDqL_vpdF=YH0GO_(?P}-{jpd!ciXT-c)hS< z-d*LlZ|f-Mjra3Oelq2#+tFPGb%_5D_B73u8*F5)li2jq*@5;U3&=t@d! zY}5}(WEe1S7AE^$IMWUFNa(YHhjpE0MBlfKwmEmFn$H5Go^$Rv!u^9s*}bdsrJ$SI zmce7GNrX>gb{Is7b%z(s)Wvsu4Wf#54sty(%JPBO9pz1yt?k$*rKEnM=w$8{zvFR` z_j9V^-PG4KAuq){vxe}pMv=QgR<8T$bXgbpH&rFdKOB=DW#+R5-ZQYbUSTEW@Tzit z-iW?Uc41*DYh}V6(P;5`(M&maV-98J(NiXk;+|-_wx803PBtbG^P%n;NSWB7NT7~*iC5d;aTbv zVz}}+0y9LFO3lTdTDJcFo1-VOk-%DwSkiBP)~{6iCO}R4s`X9vU$tE`rt|tG`@<4v z%}iUvtSO*XK;EBwe3bkBY!*!idHOu;g?M!yx}3Axw{u&5Ps3K!oKG9Sk?#DN+*a(6 zctb~Jbp?)c2r=6!f06mOY48*Hc*x-XGkcrskPl23+j^=1D71R#>2nu3Idq60=jDOb zlgA%wnlGqoltas>E)T?1g7b{X*lKSu^{jB5FBtx6oT0zoKeoJrMzJS2#V-xSawk3A z;bC8rBb~G49B<8zold}?pJ+9W9}B3&9skkp(sF--hpI7OlUhihIrnMt-$prs7M53= z<0nFTr;!fD{|s-8SYHdxKOHpM8vS_8f&mV7ukvAlgTH_azt&$M<#&M$8@~?k4Tz*! z4SnSJRi6`&$pMoMlZ7NvNiNcQs8fl5_WzQn?1L;2PPX`$P2<+Ft z7ef>NYh_}TgPxv#IpKz1FXRKqpNAMKlcnSOC1fkt%@9ZG-lY|aNe&}`PK-m-5!V*b zag92c)s>5jjGf7ei`!%F9|N}2agOJM9ngSl)h_oaHxKFL#2+-zU+5&j_~T$Ecm4J9 zZW=f1*QJ0@T(>;zZhPc8cRFz|EK*x#@%&uA4#Wvv+cWt&Nwsln{#&MJ;g*Et@BYRB z-2p82&Jd3w$z}&+wv(LXe(|}Hv}Rs+{|#Q z%9tWUcY!=#fl$$m;I)mIGJ!Xc>7;9S+~Ef91F0x9sCXIbmQXR2vaEY!-p%BP2I2^q zW+9aJ9OZva5uod4Owp#&Vd8OzPj{`r^kU8X6@SWoy)ejXm@v2ENqz#6-_9HmIp%H@ z+@`$oAmifGVJyGZq3b-g>xYWfcniMpIQFc#9%oHgzB)CLGYalk?Q~`+ZoDd2PozLy zw75@UP6a+=i#Jnp4$qyG!tsT?Ve|VHidyOOfyUZm+KEh&q%Wn6b+!71%Ny0s)kJK59KHCiRGoW*1*3_PRygwv4 ztqFvO->xLDSk}bTFnjw+;r4rulA3q?k3W+5eYwGDyb6Y%W1GLzuwFMxi)&2 zRHQu0bmD+dk2)-rNPZ}3u=gzf@Oia-yXD7y;-0I>^V=VJv7Ph4F!d5ozu(Ov9?d_u z3Cpw{nj&ZVrGy_209!1i4#i-GX7oZc4U{qth%kAf8O?yuCKTi@Q6_GJ`vB$8AY7%r zOq1k=0Nrl+k>C3qliQU|UIiEkYGpEe%>1gAIRnVzRmSLbhb5zxIRQOsafb;5gccLY zj?91~1{@=|x<4!#2$!}yZO_TpB^Ai>3e9Zxm{Glz@@j|cHEDulV!1WQYc5VCHAvW9xXfy~Y#+ZfrfCZ(Kr#5V zGTH7fihgCqM>2V}GGba8HbkIx#2ZBHAB$E7Oyq82nc>hp&)a(H=&2GWE#qI3Nq+D{BFI*B%HZ03fAemtX%t*jgb~Pc9n( zP%1GNW>MDENEUr>#wINAm5Izd-unC7M>YKTpLgaL%1*u@Pi>ww9p9NuYGo1GV+m+w zsKZ{l5-!`mf!uulg`k(##14bd405Q^J8q*}u6-xlkm#)nvUM^oC-R$~9d-c5roFSF zJw~(0iy#81<;m5B52%quWC#XQ{t=@t+U?8TFJXQ>X8#RfDMowg1nu7+4@xIDYu$c_ zUP=KnVhD(*;)r-(a66GPt92&@%^U!PB2hFqP;jMhmTiyg8GQ^?57;XAlT*DI^hThZ zyM|mShJeU3#;;6fXvEtCxIcm0Q=G=O^=5)3IvX) ze+1u_3gsL&dZ!~JA}LCMEVgLwVLwp6q_mqj4F=6JUBMiHrni;ccK05*C&7MmU;OPM zuw}mu>V~*qODTc<*>n8SjRfLX zf2eZ6O|1a>=yBkjILn9>pq1CT71(0{zlt5nt3($O<|IYb+5`2z zZJU`&3k!^aN+nsJ0GXq!uTH8Q^071tk*uj`X0J$U!`EbIv0Zdhx|#l_dI1uOC#HIV zb~i~|k~F4}fL3Nansqe*V=2WGFLPNzWc=@Un-AJ)>J{0>0F>EZps||0d&w)_MM3fC zp>q%^;C7-{kXueG1Fpt>JHY)LfRXtdvrnYxiax*vQ1bQ2gvQ@x_~@~zh~A~A_vwh8 zL-G?vZ%dk|mt-|Q4#0Z?ryg(UZZ`G_n4Y>+9tYNno4M9D?#YM;K4l4$4gP!NzJ7XP z5B#s`o^9(HD+UTlRnx20s`gh0cGrgebu@o@$Ylp`TNiu&R~C{W8~paE_LIn44thXd zG!?YYywXY6@H9d8C`v$1QMOLxUhum84Kkld=HS{`((&`Dy0~~WBi6rA#3X|E?h7^2 zN#xBsz3xD>B3{nQGu!_Gm_TR0=hxd)wI2IK47gRy6EH+Z7c#sE3 zFMtC+d_z$HK{3cfJP5;Pj+==?cqqSkdn2=w&v$KCiWYBka8Egv6Ssw*_9VXmu9VV` z133pKIZ^b2DG&phpAbwvi*SWe@ww z7XSPC1i+I^a$hrhvyZxk!+_&vIi@U95r{Z@KX!<4`%tXHH~@t^EK^X}XrldSffXrx zGJJYEym>&+0Oqwh6cURR~gY4{gQF$#jks2!_cvtff|7N z$Ln{Y#p8>w#Nde#h6}Y;}e>sShJy6uTA@~F(=>Ph- zPrAOgIh_CcR%EZ<{{)l6kP2|T8hHHF&->}K@5pz-dCv)tH-4d)2p<#zFo;7TKu85d z>ZDe{GBo<5NBZRlyQO=*m!r6_fBxQQJnIm^7K}mEr#{s~KMJrww1CqKORy375mH%qd6<*MU z!Qzvvzyfpj;0Vz5p-!?mJI++Qw!)M;6whij8`t7ox;Yu%y=YgjL%w|rre!;raACuT z5hp%b6Y$==jUnH3@#V}J7gaH5b_!K<=c-lIl=-qDazq|`_7oWl`EO~0f)&SZ`_?tW z)~;`t&K-F->&LYP!j?UpcyZ&$Q8ET@`}cC^0to~i>Y2LKr%|hCPwFL&n61wVQb2u2 zf$rwug(GL{7Vh)jjo$-~-*>*=`e)Ot*T0{C|CP$Y8|c0O$x?wb%d|_-sOuC|5Qfmc zaDc$CP%{Cy^PbDkKbP1eaKN}eJS#-9M(nCYo;2K0#T8kM4L}buB>yn7EX0_u!2}t+ zQ9CiRf`PyuP(xxh-eO!X#TFN%Ex;3fVzMVEd4h5$DK$D0$t$tUGNl)nEK= z{gSRK!a&1|G_ymKQq5eb?28tjOMnj4N&pVfjSM}s!!8LGwNc+vt!>o0R@JN2L}{%R zxkcTJ)lsep=zdq1eudU3aPnMMJ+nmtl@s z=9yW3qK=hm&ROT3ZN_=$pMh?<=b(xHdFY~%p84pcnMUG{I~0x@QGcke+UlzLF+^fV zD|R#hF3bS7W6U@nTd8BkxWZg*P4+fiI|i9!in-~o+wQyZ&Rg%f=a5A1y#Wtg@V@^R z-0;KcCLHm_4Og7;$Mtp`^2w*TgAS=N&(a@6PWr$ft=Ag&UV_)wD9kd@xXkRS%3l2_ z(8%b50M|Gmx!<;uit(aMK8JfyRr}pi|(7! zIsk4V4Po#RWD)?DJ8O_)qG@h}HY)m76)<{G- z+OHAsxSBusp~Q*FsB1E60cFH6#idlybu2)GX#XVC7YO75H5lL{4e{f)IZl$2m9*p~ zha-+?1mXjVS>m;tNS2FbOpr(+r0c{0G8ObCfvCa3^uX8{F=CRIwY23eJ2($Y$mWx5 z3uRaOC$>_Wl6%863IPqMmlwtmmgvLfGocwxX(F!~rr_lsvGvQYaN$>FGUkGc`AsY! zOKo>quv;@QF`7sxy|_Oh^fTrMhpT;FPOlp|bQ6 zfjLxQSABFyJLMTsiB6QFA+fC1YIL8?^e0acAf_}(ai9e?+ZDM0nAtUSon3+G zaZG`ZdsyQTB;mw3?jep!C?=*et*J;v@&6B@{^K5rX@oM^@efRt*yO7162$rRGm6as5)Cqiu;t#-pM-W7kh<&8u53#^U^A4j}#yS?VArS>U zln`1XB*qf4*o0C^B3a5>7PCWjtx!b)lhU4csvn7jYsbNgCXDtZqVU8^njwln6k-|X zAi+pfTiMGVCb+{b?s0(%TG6hRx+$p#C|(j()Fua;4ZQ13&~=7D@|B?BG$somB(JUn zKnOor>DnB6FvMo*8ou~Q2G)@Zk^dM&86dHSeGgOL`{oy@?=a4G_uJo({P!b?aBw32 z(TfL1OeP4fz->hli+L2|AF4>nG?p=wA^al|BjK-q0i2i-m$<;yb#Y3_QCpVG*1|OD zZneIPlNVrbQsgzM*~$R23y@_7&8l8}5%N;vfM6fB9R@N)l8#e=Bo^Q}43nJ@l5#ek3Niq%pa+8Z1TKk zpmN#Eb$;=oJz5zO7B@br_|KQw5 zbWshF?E~cFdy! z=k3T6wXXQcC9YwQcK|~MC&7R+ra=;4 zf8^DQd3U^#d+S__`_PA0hC1Xyjbsdb;45jgNFMz!!$x{ClqPR^{W{Q0lg1|xxC3fV zu)k0nWYn^eHAre5l6hC4-iG-&s#RT*50HZuyp}OYMqcuep!p-iu0XMmU4ehF0~wdl zM6=V;3`~e39>&nQjNR9d@8{pg2xYD0iW7~ z5DKt*+0VZ3hfh51aWD8M%=b!I2Fa77JY_$dxiG%}2=GmE3}U#PBz>;HpMzcV5EI+j z$QB0%K!Of+fZ!vp$VUdKjff8fAr=1Ugz`h8fl}{s+|#cB2GCIqkW|7SfhdVD)B%T* zI3N0l!N2}f0{z}@0Ab?bTw$m_K@xIc0U59X9q<7mFajme0eL_QcwhoCFatGk137R4 zk3b7R@CZb31pi5}1WoV+Q7{EnPz3K_1zqq3VekY&Pz#Kp10k>n>;N_Bpa*QQ2YrwM zEARq;a0nr=4tVcMuAvw1OC8b-B#a>$Pz*7Wa0#1mBs5?gbb#-_;7;>S(^dS}cz!jD&vvP44AOmh&*cuoC{k7bt-h$bmM$ve|C)A97P9cC!LLpd75B z0@hJJSD`-Bj2Gkq6Aoe5I6)tP0TUuY6pmpK+p|Lb10BpELp5|mHPrq>2Q$A&GygT> ziGnOVFRhdS3nvImCQZ^O*waD><114k9q8d0D8W9>F+cY+B>J-gdh^&+K^^L$8S*U6 zmS7p;;UBP*5~hJ3=s_HI0VH8`N;yb72ZlSp>j1<=4M<8QPgIaV!wk0ICLUl4V)Cxk zGdNh2O4+nc-PAv7X{E_4eQnAOKD06h+qbO$oJ74fQbMlrGY= zG`1jYs=&v-bc)6)Z8RbQr~oyRpa1|BOC#w}J@r#TbubbYL;|&mu)u#H6;Fq03((*T zqTnJ5APG=|3KHPE7WG9#HCJ`DLPu3ZN_B*;$KgIRQc)<=!lxouQ3t&!J^z38CUA9E zp*30uuvbZ>S*s_!z;jqtRglOtUMfNWSkVs7)K;yvN(NP0(KTIZsT8CXQ9*QcIQ6a; zK%@l9n8dSKU?-&_g1yG$Pb2MC&sALoc3_9d9_oP@8o`s^RewbEBDhHn9`#Q7YMjR4 zJ0Kzg7%2}ZKtutSU_JI@Dai&*;T!yc99Cg3Ka`&uRwGW;M!a-erwA)t)gmc~#9b#e4W`bHxBxl#A0k*VWOX*%OWlh>-MFk=NG{9|h%xbf?ZvX8zQ82&~j^Q5K zAr}(i72rY3)Iw~zVo_aV3xpzAUUs06sR|q-0GOo)lPE>(nXM# ziQ;!(rQ?6>l~`SefGG7K2!Ivyz^HesOMjL2N&m-*j88=gg^MM5Ws{YHfC z5AxvlXwmUzv636_k}-MlG+3JnU#5&iLjZS`3IpnntO1X zsaXS!@RU*cfI(@O{|RwjHkSE#Y*v5_vcho@LIIZbf>)X25_v7mSood~jqeVUC7F^* zS(FhkpFeq@`B|Uw`JXG%p9R|R2)dw6S)1`Bm2tvwfx|#t8I}R4h82XCyC9JS0t420 zm&tfIikJ&4fWeZamm9jB1;nIzIfv!kr<{KcBPY6r32WgU79!;x=)B2JiK#Eu6Uwl zd0oaSb{61mYoOC=K&Vfeq<5mF`I9XF@_qyJD*s2Cs+$<9ry8%r$f~dUnp9S;6M{x0 zWt`mwr>nySaQA=+zc$IV1G+#cyr4@v=EtQ1vC&`*wBQa}+scP}!_75nSlr1W9Ln3gvom|jHzdPh z1g)J;9r8$${XJ%DBU0sU<+&=*E4z^)JklJ13sOnjb=}9e zU=4mfH5S~;iG5$rz0s8&;h!Ac@8Sj6z!q*H;^lqb5q;WA^4{@X-)}wFg~iLA;#kh$ z*MoiBB?7o1y|)iu-Sr#Q*`49Z;sC0k4I+N#+h7o&o#IuZ-bGl}*CyX>eJHryGd#X1 zT%Zd=BfY6W+)2LB3FPDvHRUhf<5+USJL2edcX}4M-dSz8>dw z-h?q;L>C|nzTj8Lpt#pw(>0?Cv;YtWp$n>jeaXJ$7at-HpD^xT@28&hk=^uf0s*i< z=Cz&{#2|-P6YOtA?60)*4Z;8{-3-#;3^;!BgT5+QAPWNi2;6hcU*#QL`4gV` zccKNzAnUch4YHuD-C6dJBk}!$=l3T7CSwfHU?|kSQYatDFCR4k!3c`q_)Y%ijU)N_ ze&tW!`S(5{93Tr=U+~!g2HZCE=Uw{&0)W7Q0|n#|Kro@gg$x@ydNB>rcJc$woi!6ioxE$nRqRg2zYuZd`5aG?836V^x05qu3p+t)s zJ&H7`&?$9v^4yv8DbJ`)IVU1<6*Z2lx8@YjXjXFJsWC=>j9AVvi(EE?!(k3m}((tQ-K0IWxqrnj5OU3mPs{ zr=1ycE=}+>YJsX(w?_SXVSpEAXptRji%k^+5XLqrE`&OGRXl0r| z4`6@-4oDzU$N#mr9%%?JD3M@n#Qu@UgX7j5Ks3oT~65I{{Po(N=+LJqmsfeXGUVt4_lu*HKBZjso9 z99bx3hFq9Y#u#5@AwrT~CKqFSKN9IyiZX^79+Fk5DHWSfsdfMiwc%Kc8dZR3)0kxL z$!DMF>BXR%U!q1M7fzOizpkpRSp!;h(S}$!(o#kh2>j(Q$wChu;J{}V{PCb0 zRB@~r45y(+8p~nLL3Gb4@Ms{vfG z#m@o-@C8}9jlo76wzzzYEp3#MMGL%jrnW-?EPb!e`3cU&3-FdWGSQY_KA_Q|(v0?k z2>-l*#j#;vc?Q%`mmx+MTVQcT>sGYR^%h=;fzj7tXBmbT*Y5E{0-bA{xPO&j?snXq z%XfT4S&YTTY3wXMi{7x5C&j$88pHaoClES$OatO1p?%ad3M7|4i2D#EUW=v*<%+Ms*r-iy{Ur{`P>!0P(HwwWer*A z4{|Q}z90&*DDgWP4JRm`1*iZ9SjgW3^*4qnY9Wea2*VQ>$b~CJp#>!@0SC^8ME^_$ zZz4eSR0cV?!Fe4qApu~+y2#Q7TrET^7hqZrb$AQyv0+OvNWu3eA}9o?Kw4%f-`{ko zJu_5c18dw#8HWhTAQtg$Vf)1}f}@`hc-)F z)>1QqN&$Y#Z~^SC;g2TV=i)MShMeJ%o3t?IG1;JoHJo7$W=P-|uvCUMsQ-ZteY+kl z4!O|$(1HzPzydf;Q_r>C)0`}YX$1p@hT|VX10mkyEqM z$f)Kq3IlO~4;><^1}yQK*=)o0Kq^)p+QOm8RAwJbNE2}`q_1vmt)JkEM!nLHDj3+E z6f$sC*?LK}4`D4_uHg%yWMCbsFzh?pl23jV z-0^Rg@DD@;MHkf=N+Li}h(;(Q9!nsKE0FpLN$?;CWG=Ir&y40Yt9i|2=7AK(%;q@D zdCqQz^PJCYh39JF&S|bQpa1-4KLdKuaTYY84_)RuIJw7+-v3j4^{HfSLBOtiz(Ay3 zxm+JD8Z=OrGEk^|ln;=D6-03`ge8pQR9o1_s>U&^SxnWj)MCZ1{&1^R{pwr8IM=!s zv5p%JY;ZkVxk0|PX6m{-AsCy2#a=6c0z6=#6c{PTAcldMN-!YP#0Af#EMJ=4rcBF( z$pZ0hu+JTwVZ%q<%ce;HDnMzM(4h!2Z1&3=KY& z@I^sqv~a<}wVmzo=o{S>N70WXZg2Gvd3SRNfdSZ^@o)2W)1c|ZJwhQ^!d8G7xc~|) zC?N+!7{eZYC^*EACX98Y1uaGv+P?D7+j(1{Lrwium0Q;+&U3Xs=< z2tf+^}E4@nul~j8Z@D(PLKj`L6opZ~vCLtC#leR=^J)=#mr69`>P+ zJ@JJ{_~SvMD|#`FG{%HPcN2U2?6<6ifUt-ie}5br(Y;RiWw2=j}7egI@& zK&LmPoVH+%7=g8uZ^I z36TZzcUkp^e{m&o3%Gw7h!_3Wb_lo=C2%ctZ~~pTeAnlJem8Q-SAns`5Ly676G(v% zNJ$r{fi)->+y_4PH(v^1fCXR&NzivAVuB}_e(P5>4cLJRNDy1_g6=1SFy(d_XoDGu zgRggj5fK0sAOw3*1O%Y~NoIXIc!iF)AVvrv?MHWFNPP+s0MDaK(&L0mXhdp=eNs4u z`d5W9IEHf+0s?p~2KZETc!fo1hh&0=yC;aEryzI(M`(qJD=1$yc!!htD;zk7d#Dfz zFavb3J9IDutTZZ#=z)Z&f=_6H0zm*~(Eo^#W{NE6Erm#ll9z{4CyJdD0Kd08K!|YZ zcX_1PK8M(SH%9>!`uNaHVNEEZUc9^JlE};iPkax5QjjpJGr6`9pcmQeu zJ*b6x$asvB$c*Laj1PB(2{3{KK>-8^h}L+G$(W75h=iAzZ3o~+%tKId=z!apf8}V7 zmNm{4;YS5v zD3J^qj%5goLlTiz7%vWhFJ%Bt*qDU<7<4Jgk>}=-KL>c~I0pl$1MirICV7$$X_G;+ zl6n{_Mu0D4K$1gAlQa24MR}8rmj9EXczF?U2fITBCZLe=D3m2hl-l@|%&`IZVpULS zkN(&h4>^@BRh5Bwc|Pb8MSuZK8I)i7h$tzRXo(zUNfuk6mNJ=^HQAPw_?FU@aRp!k zJU|dL-~&J@n0Wb&VM&j**nHw4S+epWHUZP~YQ-B(%ku<16sQ;!np#VI9njfkGXqu+136}GC6pfGykq{KFa0!_@mV0pkYp{xn zc%=&osz5`kr8-2XT7s#X6?TwpM@nCXYIl!X0jod=@YSH!`4<%VjnO2d!#b;wXgaiht0R9<9jhb}SS^+^23dbN1^pFgs&}C+ntsA-(7x0oXDXe^&qrLi%1siwe znpPi!O82z~jHy!)8*&mG6dyndyg&~8@C~j&R07knKFSk*ITmM$Rp82!0lOCji?Sr6 zvIjUU1yBM#dH*d)0IO&tvl&OTMDYiyKn?o94nF&>dm&l30GLi|vL5TF1ADAXdz=T` znMqOrCxEDPS(kEkwf2^^MzI5xIu}4CR6RQsoG=deAP$v4b|f1SDTW)Hxw42$tY2UkqG;c3V#p__`qPF z^0Nrb6H)M7(PgfV8?I@4vXV=2lv}iz5&&i@1l>7bciV2%>JR+jyw3~0{6H7LC0xWc z6vm(oL17KSMY~}u70)+osA{xGDXN*Fw7`q6ZX2oyQUFdT5E^j2N~XNaMy;A)zn-8D z({Ku%aQ_O_pbmT+7tlsv1|}5ga0)>Y3*b;{59S0BW@5dzYqoZ4SCDor#%mBPVi%0T z9Hzk=tYIDO!8x|J=qohByM_!Bx6W#5%j>x_3%W-E48kxJ!XU$P(P>jwWkQh;oe&hI zunt}ZW@3hDLu_V-HpFh2BUTV-Z$`vTY{X4WXip5qfF{LLEN6;F!ojP)PAMJ%Py%!N z1bExRSo^|8ArIs!6qFDTb8*9;mcv1@!#(`NLt$zSjA|i#VjwJH1%Sl!7r_sV#~dud zfm~yQOvoFi$07V{S&WlgEU>E)030B-E+GW$s$27GY*`BrsxTC)01tB^z|uy*L1DlM ztpC8>JH7xw0Arx1`pLUT3%TYy!i@YcChV>1fdOVZm&hx|?)tfG+FrbH53EoKOHc@| za1XpNz5P}J8Srn{n+)2^y(Lq-Zz~Z7K#aQNh~oRoOr;ec%eRYjdy6t;}PLz1hvl8OxLt&cHU# zBO4w+um?#{0pK~ty_|wcu>+0J35~D=cX4%Dw{=}7r{sVS;*g>NjkE)?02Rpw`^e2H z{kY|;&YUCOZT}SGun83a z4!-~tt3anOcbrO?ORNDj1PF3U{b zxoT|<09qPWG*bGkU?_=s4R0V)T3zH#!Gho>F zZQ1CJ*+el6G)(Q(uIt!1jKwJGzy9fi?%cyJM8!@JLx2o1Fc2;XI4vOstuC3bzF&D; z%Y2@r-Po<$9_-!@?B5RV#17+nI0WbL58z<#0Du6yBx@6J0{Hzq?w-7N&b0ELmjlg9 zE)D4T-tFAZ;!nNr?APz``0q&-@B_a9H&P3Q#5~XL&?s+}u6djgAB+;e21$MK_m1&l zF6&|%?@q1+0MGMTul3MS z^4FpWw!sD}f75`k)GSXtF7F~rNfty4^-~Y`YrW)h-?m~J2j%b&caQhpkPJe9Ek7^; zWxxh7XxT_FTkyW;mI<N~V!Xec|P!79b`&n-cx1c+FAPM6j@V+1T+`p{)UHGC{ z)@953j_>xZ@6^q2^$7Cs`w$D;aQWU){W&rSnxG9^KmYK)FZy~#`kF2tWepHn01PBp z(BMIY2^9_$kVC*ih!G_MX!vmAMT`_3X5<*LVn>h$kxZ#j(&R~$DOIjy+0x}pm@#F} zq*>GEO`I#IAPL#C;E;3w`oY@f&8RnHx0KeJRn(iif8b*Hq*~SLRe~R}Zspqbs#dQT zN9H73w!)M;7Q-go&_?MkE^5~<1Upw@UAqYJ<~6vN?^v^e1rH`%*zn<&JNYIADs&ss zqr}YAx>c*&QKRpoN?6?4v)+xLMUTel_cLI`sn4eU+*YZrETKu8UQC;>?Yy|dqE_A8 z_iy0AT`C^kxSzMjPKjyR!-dvm%-!z&(-na9b^p7%v2U*}`#NvoX3@&cyMfkgEZWzq z56j-G`>yb>f)8Kc{(by0iGMb3G`Y866xm~sL1w|s8|kRCjyndilCMDst9p#RTjhze$q0TnSYy6LKmaL1lZvu8787HQFA>hW#g-}<64EmteTuTjCp(*xBO;5`a?2u3LFXQ84oQqB&tQyk#u~FZ zFhL!GbaSFB-;^`Xkh0|RBn&UrNegom46%lP^q-ngx&n7xDBcHWxH?+779;R-#)o+LcRI!*aD2SYy2|TR3xF z&)oLV-D+E3+jUna5ca{uq+yUj$p$C##bXKq`t|o;fCCnIV1Jb;XP)_7x%JNEcvj}7R-0FX;I`DBz+PFZAUR2l9_Z5}DmqA1=VJF=sG~+{iGL6=NtbF+a)swlB+21xu)`L6 zY_iM#Iu2HLi3Jw6+in|?NJep+?f+bM;e-dX^VWNBzWet3Z@>ZPK?=MBH~etK6IVR( z!3$qp@j7DmO#^Y7Da4X@UddS%B|4Yk=ccLpHr%X|-fC%xP(M{x)2n(~YS`bU+Uk<9 zzBgYd_H|ifgAtB6Vpz0^c;bpL-u-ywlUJE#<(qf@d6Suko@1DSvt%D4N-8Cu4^l$s z6q&l+%C#j)FFo|^S`QKZxm3SPeV<;BeSTi!owuZVjkPP;1OJ0IM`>MaTJ95|q1a~^ z`Q79d;4lds{y_-uvEv=!NJaOIbU==fk4f*t;CtXFp$}4pfS~ChRuV`*6msbry%3f< zilvidd4+%dgN#w4RX}Tv5dVkgDxt0<*Bf9g!z42J2PIO1ibxP*d%92wzVwxcmL*Sv zSHPI`rdP$0T`^-;)S|$+*hPSS5scMKVHsoBiF<@1Qj^kOSY}8=r`&Ld0}SCDxuZjb zoNy&u<5?e_5X2!Cu_dI)hXqf<$A5IqagY0&5!|vQF6gasj6~cdDQP%MUQ%#`(`4W> z*-5=c&Wxj!+9}Y1k898lhHebXaSrrK_d7iMfMf@-FbmTVz3FVgzHqs9DWxf-#$2+$QwMNJ?;y(o$D><13Rh%Ug!Z zmgxjx54*Cp%x>m zeaja>`%ksTc0`apD|I0PRoiB_Fu2XFU16D^T<`#cqmTthvhfJwf@HMm<)CS$rre1T zKn-s(!*iiK8|xa)xNgnweN%;8?FKkJ-0kjW|3{qypo_d1NdN%O%U)Xb7sCAAFG#Rk zANWRu0B3kh83;gO>3&GUtBbB^E-YXa--N&gzH78-4iwvRlo>({;UPu7U@Rl`v7{n#UZ-reO;=cem#al+qidl>x0H*aI zF~~+HX#W6(Oh^D0vWP(p8k`9z(7+K7&T%$Iaf2IJpv-MPvVZ%G<;k8FXc!5=7v91K z1L$t_J?&QLu z4*=UnPuI$kjrC%bJZW5~q|yaWDy9okfEdH#5uEY#Kwxa+Yz(B>4n{Ak8SU&UyEke~ zM#vTpjey3^y1Lpna@R6F(CdGWWnaZPTk!~nFqNx*rF4P=7ABH2DJNSXDG z@Bf2;9Mb&Gqn1|%aEM@G;100q!UdJ^+>jgq4R^StA@0FJp*hZv$Of9Tk>>==*%3DY z^2V1f3t7;>0wNa|(_g+Fn)im<1gU~8l+p&4x7^!XcXY^8C-bP+JjFLh+MsSA3mMM> zy%s=wHgK$CSYVvv1cAbkoxWaEC)wn8nmPcgK$%;#;Q|D8xx%?FYlDhi@i`&8(qw*b zy#HD6tCk2108fhz2o&b&^ZKc~p7_Ow{z8~Nywd|~dc%Kb@7zN9L0oWo5uEPvP5*r1 zW8V3LgkAKuZM^JpfA`r#d-CsXeL-Gu`4l+*_axkW`+^_o-A8{+42t}bt8e|_5C25> zT`vAWTA(Caw4m(GKYi%|wS0nXU;1(Fz2;HR`S;&m+E9b93c&vYoRhz}`p>_KSHFI- zYd^w^zx^Y?@>4y^Lx>a*8W$))^CJ}W+qVcT2`*_$K&?Hg zj3_uj#Irs4LqQ+9Ko%6h63M>2gTWY_K#}-AEh(&TfdS{ELE1aP2Yk9fV?hgaL9OdR z_cKD@o4B*; z%fKkq!fa#10p!AI1DYv1jG+KLl()CIsc?XJS0O0 zl)}yc!97f&K7_SER5Uwuw&9yLMfidj&>$>;z&upGPt3v~d_>WUL`s}QNkqjd8^qJn zf~7!@L=;0OWW+iIJyHxkQ&cY*?6d1DvP+~tSA2_G=)_p0#bR8;TJ*nLEJZa;MpcZk zN<_6^T*6>f3Rm2^p_97v5spqP}&grZ4W!%360%BzG! z-{=KXAcmh@iDdu>L`Vd3AcomMrD-BaHGn6#7dB}%dCvZsH_QB z_{x;{gMSc{3aA8r$ev0GMq8i-6?jRv^8jY!ONUR-{{MgAcc1@ zi4Tw$Wx^di2*x&0fol4fZn~n?oSxQ%p4WVy*i4>pn#?q$zFow=Xq>@w>YGn$PD$b<=;WK{oX)bTPU{>S?ElQp91tbjoV3a$$IHY_ zywpsxK%_qU2PZIz-%N?%9M0mrohOQ-)by9xY@Yj6p8QOn{Y0Mrd>P67PDr%JmbA-W zoG|muiCzMxUoxcjLLPcMLp0y;3aAQZ3!mD}91GcmggBQ!yP=GA&axJySGIQ!fS6G;LEi zeN#A%Q!`ytIgL{(4UTC@PpiVJk_gIqkcXmli965(Hvg?tHT_aUZBsf;R5V>wMx9ec zeN;#-R7vI1JB3mdqk}t`0#5BzPyJL-4OLMc)lZ!RNtgptO;uH0RaR|PSAA7jja5@c z)mW`nTfJ3W%~e;ORb9>1JD>yDv4cUN)n1j=Q!Un7{ zOug2Va02zjR&8BRZrxTE?AH7cSNtH?`!HAgK-c*ur4gfkoJLh1l?LSb?oro1oZ7#Mq3L zSn1PPv+&rm09mpS*_mwU3>x zkDgUopbc7~9a^F-TBAK$q)l3-U0SAXTBm(lsEt~wom#4`TC2TUtj$`j-CC~gTCe?D zunk+W9oyLP5-<@=4s8TwV26LW9}ZQ8YnTUjKn6aDKC=xImEeSNxCe2l1jM*ov^5D) z=%af$47Fujw?zrPO+HH_wUUE@XG&i`57!GK-arCr-a3EuTx;1yoN;NID-UC_l| zYh;KP_;(2ZdBwN3k>7kj}}2j);d_=i3Sy${Bp5H^W)0H2bG z1qLFF6s~~$ISEnFhjdVfWFTL}7~vK+2^enR=Y3!t)?pq#j1oR!l=$Hnj$tG=VbCq& z9qwScoSm!58WA310mT4imnD zCSx;3V>(s|H-=+nkYmK)VlPe!JO9=mJT?qK*5fyh<2k0{gj8cThSCxK&R;NxMOHjV z7UPl_5^atN{|CXFa~>2V#2`aLeOZAKIxP` zDVBC=nC|I}-sp~|=?buEoYrZc7L1P$>CX9Hre5ime(56)jHwpsl3;45&gq?&=!7&S zR8l1Yy{bNP1rANme-MS;GwW0;iD?)Hli&n$zz1=#1jLYQ+NtZ3;Du9ahh-2_!%%CU zVQauH3B1;8zCP^qRBXGh0Kvuw!ZvKeaBH}(fW@wW#@_2`PS4F=?8?4uvOaCpPHoj* zZPspW*M4o-j&0eVZQ8DF+rDkw&TZY^ZQkx}-~Mgj4sPKdZsIO(<34WWPHyF1Zsu-o z=YDSJ-aVc92T-61Yya4pa*pmjbZedwg=r9?!jN2YXo)`H8Qs-x^lle)IEF+xZ_dXxQ0`p1ZjW=qb!LSm-6+C@$W8)mktL}umo{1hho?TO7MmH zRcU-c22AJ#a{sV~3fEm$n1@nm1Wo{k<%M!KZ*;=o1$ih0b|{9G*mAn2ht%DLe<+2L z5QKlwgp*ivM;ARepYeZqY)tqEV<-s?Xa`;>32LYY3@C{|@Q25?;UlkrWl&}#r|?n# zb($c7y;X-DsPurI1~D#$fB0Mw(CAQ~Z(tX@QipSX2&)Px;rOfoYdD4qkb!+bg%1e# z4?u@i#&z9&1$%IXL&yN*&Gl%16rE*MlkXpgH`Xw=fpm_L`bmnE#ArmNMMNc}OGZeE zu)$~~1O*Z4k_JH$PzQp9D4-w>BP9ezxBK%y=lkM0d$Du&?1}sS-kewg@dU z3||{lr4Sbq?iV*Q6&kZ2pWATmV0s2WB$j#z(4GOqW23Z#jxzeoNyZ5El!MiOhpGL+ z=>Q_W42n4i;>r}IEeBDn0eUrrl#$>tX_sWhBYIqLgmj!c<!)df|LKzm1ZHs`S1#gt$1-?Y1 z__Y$nd;~k=*`y!zmH7yDCGlxQAjN%!d!C6H7uS}N<5MnK5vyi_+I|#zme)oAUc4+5f}gk005U9 z0jz-kKx}j|wBzl6M_d1nsI>q8b=0%N&9lRee+Pfhc9&1~H_mCJ$2-fX+Y86rOUK&_ zr(1J}+kXzWmJXs~*`vP`JL|LCe`mMWDAd*Iqdz~l zSH`zj#;D7arwh%83w?+4y(jY@PUf5TXS$9ljk^U!Lh-r2Jl(8U8cVKTjE7n*26D zJ+v_1GdIz{Hqx^^(lk5LIXlupnfN(9J~%zvKQ%fqHQG-Z`TA?(_r~!1ncrWghuWuy z+I9v?R(~|?e$UwIe!kI}_J^FlNhWTzhOah-tu^?szsIlE<5$kB?)<=OrPgz$#(Aak z!Jlfkm2#VvH`dE#cb3a;|0%n@kZUxPBs2c|``B>b*wA_PO#UQK4t|>We|;S9ZyD=v z9sAKd@%{bi_Yb4rn}!E_e)V?^^!E&Y|2o#!IMCNQ(AP22Q~#s)%eU^f?#|EMUs^ia zTD~`z{z`Lg>-bFm`2Kz0_u?;Pa_jp~t?$Uq)pacm=OE9fcXjU@Ya8mT3mfX|Yb$H3 zE2=8rRF;>Pmlc~kx#;jkDr7GKMo5D zc@h}%Bp~Qhj@Rl^YZrdeCX%q>ErD7(9y-y*~!i3f$M#HmwR?D zcWs>t)zz}4rLFEcs6{5r1*cr}j}pWuSlqEQyKN)*Fvi&8-c2*>8>V-zn^+m#wA3{; z*D^5G)H6}nF;dmKp{!wet^-j}H&9U3zj9UYvWl*pvW|?RwzPtlq&)7@Weo{Ab#WOr zQK_pUk}4N3DGU9lBq*UMD6S|VrhpZ@!XI*v-#dZdJD$(Tkze!*pNKr~#mn$>H8PyX zpf;~95`IDAUUzN&ml%wYA!&3qw==vG8Qpw{p6H0+Q48bg!OwS^2=j(43t!^7`go&5 zfLj-2-tx*|XDPn4TNbt9Xcg<_o%-y-4(NAbQbhJxP1FGbvhyAt;kpU4KEGR$P@qR zTXEuDoq3TA{6?)!TRktXWT_dM$=|xKvv}pC_%E-i6XcHmle4|Qo)u9>G@5qjJ-Y{# z#a|V+{hvNk7wj`y^uPJYTNvsTGjbY$I86)h`wVfJOxiC@8C%W@PAjgwR-B2%=!wme zSXPQBb+g>M;^hAhnI}nK=Md)Cj9PC0uCmv3!AP#~5DygOIeL(Ck*CVcgs0Z75T!;< z{BlEFAlfolQ!=q2QF*J+0VS8EQ^cr0OE$s4;-3G~Bq-e{_gwkgCxnuc;&OybPd7Oj zt1kMR-w+RjTa38b4dM}(`U!96Ro7h87_bN@yEqw2=7%4OpIv>6gW=P$2?}fE-KSDd zZln{H**kZT`k|5Npj{I%&}@IgEJ%LYHpQ3@3-T1Ba2Qe(nV z3okr2La9vYW9~fnx5f3>8m>F2N;QvK8t0q@B`l}ND3Mk zn@!=@@$$ta^6V{%=%~R>g#|zcEWeAKVjW)O^_>lyjB2rQAZZGBkAXYWi|W8&-(smk5JgJV{oL ztK4}Z=f|pJs5<8sKx{`|4c(Z)cRkIH+OqH7(0!2mj?o|hORifDM1^Dtl#a&2`QvPd{q%`RGJbU%KlV~YbTGdKuQZ^fd}&o zI!3E0$yG=5YzXe8JiDy)3?31>DY(rXD=$Td7Qc@}?KaKGknA-RhJ?(D9_QeE0k{M* zh_fv-N0$)U80;Cz*}mKhF#XX`Pp$XzE0`Mu_cU>}B1xU%-uOBY4`d#|k|? zMus|1v-LVwMT3jG)2Sx=Z<7qK6xT-LAt> zxvjW8H4|)egMq}u03uuK8vpj)*soF%yrfaNDC}<6MX2wGgdqoihXw;VdM(h+g$OJp z{wZ#HAXb}cfx!Mo(604mt8%-Rg>)qGs?<+fQquiAOk#t<7FWGWg2he{Tia_K*tC#{ zw0CA>`if94U>qi6WgiC*Ydmm@Kbft6IfA9fhvMSGSQl7$u3Z#VewLKX^&pkfT-IcEgl9YsXs6o7KMG z6^9DqksrZJl1hiIjo0IYUHw*$mCX$DhtL7nI2Ww_i&neUBn^BcMoFVM|x z=LCMhq2xYTXevJPS?GG$*!@Tv(6C{W5hmZ*jpf+xPB3XF1o{2B{9b&ztMOUztNR8H zlI@zLAnKdVk8+v~$H{i-^|V^=HrQo(RSb;{oO9>$EF_wo8X&Xa)Z=Iq#NPgvq57pz zH?|vXCo#$(1}xy_?apYi$2`Q#Ce?Boa7p{#CVGD9q|+4NN%`9t#InFa$K0(dS-=n# zs_bFUR$u8d#fMDzh24Ad9~@RR_^n&CmzKG$r8Mv$0V@RZvRK8vYsHX0hBz+T!C%b- zzeRM63aVe<);J$QB{T(Fls74uQnswFqKhzQ+?-a2ef=7u5(9T$NoeQ1c{-)D&%d?Y zaQ2U>{@&e%6zMs5F~ftE1ph5MQMT?9$)76>q2uCooLbB;OF3&K6RT>nAvSrvY_dAG4Vo!@H0=(EKwVs}ND50v6Si}@5J&ID^vHD%rnvSc_L5CXVvA}Q zZB$k(G;IF|^5a5gzpCRjIW>eDh<({;ARD-@D$1avF2PRGN~eAcZ;<72781NI?U>p~ zQ0RDzw$Tn?K&7D^K|KFrp5w}F+Iz1E@Rc2FKvzlQT*3p_f2;IJ0se%;ZwkaNb}KV! zNk$*Gv_AVxpuzT!SV5Q1_Sv`o3>zk_7%(inoZ^o47WlOF8r^Xr;d6KAqw1|AS|J}< z7qc7~_~GDjRv-bc#6j9+-RN-Ml?fP^#e95c;kf1gfnvlnfMC0@La76 z(kxD<92bcBmP;B&_aA1_7lxA`zpp zNi-`~k_*#n_Y0P`KkvXY|FTPw3KfSJ@~d2f&TNWk?_7`n;ID2vA+ zCfEfR{XQx~8yUHX3rDuuoO|FKt$0ULd39#d{pX*TUI7W%E>Vy~5;EV3DN7g=>%cTl zWymISyUn6EgczaDA@W!|c2k|tRHW;?T%0fP=K*@IHohy55m>AMGsSM05DwVFEB(3R z&f|{$8tr7g*9TUJu1i2CrcHwWhf!;|KFcJP;m1Hog)k;D#)l9D6deifr!chVNjnN8 zXjmk?4@xoIjXi%ls|*rLnNV>Y#PvTO1-qcReYQd|4AsE~W^X986Msg#9JC_BCl`b% z28N0EFcI}x{u1nr0;RcwfFf>8U34JJ=ln7;aLm`VdcP!|THQOKWT?QCcTSjWoGApT zbS)6`E$zw;_7rw%6Jmhvbz!nNMavE#sptITVF63VvdI^K{dT=GFgkjzUy`IOI zp8|yZjOpEunF=PAQjl#0!jlDIE!%laD*3Fmko={ivJ`p&(-+C9)^A>fyvfXZqnc_p zS@I_5_)Q*H`O*i5k7Q&OJE~8(yu7)*a=ctCfU9k#yk4cE!Mb8`o2}QmqPe-Eb-W_o zRD7Hg@JXez!@BZoNM(0cWp8t3-+1MZYkECdaF$kEjkgY3*W65 zd0a2{s$Qa{{?bIf)JeSz_glHEZ{_d4RiHh7tMuxvN=x}QS?tx5wJ!Q}7`FSj!+3~A z7Uj{855Ns;>Ak)-Ofw@6WKd=2yAN;=*)O1e;OI+hfy*YLJ^1VwYaCT}?q_@G`?0J> z*z*S#dKJ%DeV5gstnqsVCX@CUIJ4+eXm*cAX%6_0(NqrelYmk*XSyD6`2j=7IzIA= z9eUV;sWXOQmuxF9gI+lK=(5!codw1Xyu6(XS^=Q)Fo+y1GTo4M>OV4u>C;S9KAk2= zg9_Tr^VC@b{Ug(Jx3-B5i%>8gVA;<}zkR^@$Ss^C>)@M8*6_&429|7Auqp?mq7upA zDk3{gu@%EMiN5z7)P@UV(p6Cg`qC(Ob_lns)6$e3lKYR)D03$B>zFBAAUmE>jHg2h z`EgnJBW8u6*bYS{BjGPVpYu?A6voK_1P>j0D$k!g75)>8roV_O8$eq(tHN2NZS5=DpR zZ^wLF&Qq?kL;Eq&AEb!0lNn8J+~UPD9yKw&{i_DKjQ&YQ^ffSbM=?4@GmevQ5Xe6e zv>vY>8T=%<^VX&Q2G5>b%VEm~asiJSH?b0r17x=z12KhWN9`zkLD*i(XZor3IVz(8 zbnuq_w+oD^>BrAek;v%*;Dae(E!Nivk6fY3ZZtB*J;q4G6W=v5sXNi{lYue>bg9g5 zUOSX|6vK|v??OD9hYUO*56!myO8@%{EYRJAqwm6_aw zhuTj;^_v(g*D@^Ip_d6rO=Da_E7?(lEtQoV;j>~*Ofg~p0N)9&O{K{^JYPzY` zLuHIfq0ol`Q9_ZitSFk8K~i516H4XHn0~*(o|Xoj>c%ot5PyX@oLT z@h^`@Q&K-LhwOTZTL!PW7EK1}e||vR`-Jeu&Vy_y#=yRL9DQmYqAEp>kARxNBV;U5 z>Zpa#Q^qoKPo)fc8Yel{`n|!)J`RWO$wQz*k%4W9KaITXx>l<)NF^^&qMtnJH-qzzS~Bm2@Cs%0SN;P6aab) zgQ_Ll1|~8_X1D*KqTX#Y_%8!1@TGt8jG_kge`L_303nkfD`$IOe@$|9642A+g@G`2 zrkwLkcJ;*cIwh=nhHqoRW@9OAV>xGI_0z`R>5Ywl8&tl{ZS~Dvo6Y^O&BL6{Wo=lX z4CLRxO#nZYPJ;@zr9#gI>bX?<^HJ0c6-A?B_|JuLTP(I)Y~fo>;V^$H_B3gWkG6&7 z-xk!^7Pj36g~RUpzyb;2OEcS2v~3yw9XXoDjx-JYhzgd^-BJ0xqdK#rPTRrp?(9HEGkZ1~dv?YBBhNqbK1W)C9F^oAmw!I? zO+K!q9oHrwW$~YQ^&cjoj~Zt7-{zhGYEM3Fo;09O>!eRBG>)B<_giaDs&h~KW=?z2 z$3OVbei)zDd7tcT9S+b=zSW$K(fCg%HqWLsPG|a$zvi+QOP>u%pRImAUitiQga3Hl z_}|m;v!nzuBE4ZdznsWz!i_=WbbjKZb2jLRQ40-YIwW9@lRHt46?R`4eu1>X8pt zud^=x*I3oj{P^tOqZU@G9r;O1Qs*lxSIR?lT&HY#A+?Zp%P~zgy+p zbuBEY5&WIa^8Wq$m*J>%ZgoIYC> z7sQj|-L$4u?#ZdFef);z`#_j+XzkY8BIoA9Yk)SRSQ3v~2$HJC=}$%$K#|OuRf;{AijdkZecECzi=P;zbrQ-hq+Vsd zC7Aq$fy+(rb-2_u*9$(&z|v<~>EFr$oa2v+K3SFI>+uW32-h13CF{styO=Q)ljZjJ z6obXoI1#iYN3&Jlbfm^R2=@6Ic??*}gK{pQGt&A)9QbMc*(L$a>I*gf6R zJk#6;`OD)m11#5WvPuW-E~f;g8cgd!NEsn8j%M=R1G4#vsEsQJ{zj}h|@E$m&?%vOK7y_T^-(5 zMPi{Uhu9B}X~ufWPS0;Ue{jmMjaGJk>5`<37RY8bwtg*IpdjpVtM7N7-wlB>R&Pu} z8=`ot`wIY=6RqO@hF1DQ1?XFP=Vz9vcmOGtOH7R5Ue_hk;t2}CH+z;bFf#Rlo0w ze z2JS2!BqpT*>V25FKTJJjrL^=P^iO_``U!XZVI!>cP|`e@ z$;doAMT*ph?ra({-v^I4EugUt{WiSNuFQ5dN4ii*uKTQdZLMS^hgqmMyWP}8muu2x zi!}k4iU=spdm#BHJ%x9JPrXS(JjLgW)ms0N1i9?>4Xtu6pd4LwuUh-IL!JSY1ljZo zqQ!VLiP=#I66@T}yF*|2^ySNJ=jZ1>yjzOpN~soil6TN4N+Bt|_?cd+<0QfF3Q`x# zOAQ>l!>3%|wYIxO*JB6Oe77a3IX;L_O3_VaMnH^TY^2&MirkH8CR$#u6Hk--NybDU#)u>HNenz7cF?sB zHIvyG%hB_9uYat7$1?msC-G;8inbGsZJUxa70ohp>S3Q*1x_`?- z8uB}@=Ko+TPa4h-JTwNNe0%J0#h*>oB*cp7RgR^NKNOX?j7DDzQ`O@0BoUdz#V9Qyw~s3fD{LVSP8v?y^x$W%U;`NxTi zi7uVbEU4}!vOogelRSX9DdrlRotlKl6vIo=3WfjVmQA;o?|z*ON#~sz1z-GRk6K;T z;ydR+OZ=6khlpsgrsH(P4O+<$%L*?%AAqXty3YbT8hDyrNfQ6s{s0ew{JpUqVqayG z*%UEA2Ed~-%_#~Zr-?X;gMu1USK$hIyzNwfP&yvz7epbBoQI&~2jN`1K=v0nu-E`o zBBa`%C6&DLj8|;vyB4RaSyFdkMdB^s5H=Ha;aOPoaco32d%nXbOjDH>K;5+96H{A_ z{uvVtB6WZPSw(2z>Tp(NkwXmk01`j*$;BdCL_R`S0qy4aa(HbBU?e4)E>#v~<~_&% zdSA@ksr)u9K8q&@e&tQqAOloxo|CzjgT!e&27t+Kf+v{G{+_ahx~1 z2O~^G=lHcb2w)3Y)Z=b{5XhwSDn}-gXnV+?YlW3=&&T;LJRouhDcyk81%BH6h{mKh z-MHJjl@zWT(Onw|dM*=t-R=vI-FqKJE~|KapLU6F8C654mVA$rO;ic=?e7A6C7N+A z2fd8ob@cfxU|*0qy&wE{;$;0D?*0|C+mwee3Ju7G#5f413exL zh_H>=2`Pq2aCEQ0!mNilW9(*r<J~&}P|N9+#e#f9{)5Wn0jIY-=O|$NpS# zg)i&DGNAuNj<@ak?m(6#+(kd_$oV{W0= zkO%np1?HMwEvZT&>ArYL9`Y*Sd{O-ia6oOkLiT;)CZ=_66F15OJ2xqR+lFdu z%j>@Svh-LTQZIkwS3|G?1l+U0RH#oThm-s+CJjw2aSqXTiu z04g`hs4+gy_x)?d>k1GEhl-{!9qA<>`dt3Ty>@qTDwW(1<{4)V|zzjM=0Abf7VXbZ@r0m4hFEtb}{yOz>$XU z49z!kdTxCGs})Zm(C!kTt|nktD=;7yNFhbvO##Hn&@Hq=TK@L6oc0aFzk|ee1yUhD zFMWq)f2>2kA9wgZ!P38#SU9vIb;26{WF;i@K~r89*&BQ z)*Xm+#Q>KQq1>@>NNlvYj8VmI-wLuuuSpEzqyoOFyOD_F8ZM+3<)vj0^zIT05@Q_8 zZo*X{zGV`X9*S|Vt}2zA#4dL*G!Dec&@nxM&++_-ffE=Z1QgE5H5RICW!f@n-0DAw z;*^v#|4w_`KKS~&d7kS)C;20MZjjHZ&qXQbMj6SQ3PpS5nK!|1xsvYVv<1yCX}glb zINB85f4a$xFb^wO{yWe6k`3!Fv%Vv{s?_b?A@9W;qj6CWBxWSJ{A z15}>od5mfYaeV*=fx=y@q3(bnauno2w0BV6vv_^oPN_QoA+c9T#zhmrC;`oAdhNB@ zg+&X%08x6~V&&Arq|sFVV8K+VkyYNJJINt7##adfrMvBO@iycc!BQ+H1Rk@jb@BG2yjvzM zG{`p8$^(0TCmUE{k0Vu~Ay6MeUa}#{J2S?^gpLUZ4dQ?apS9Y3@4CYK8~i+W&$C}Q zsQ*uT|J}@?yG{LfQ!LLs>E)_^?-0f^E)KuBG~RY&T;FNH{8pZJS&T6fnjbVH z!|u6)&0=8+JOEpeg1wLe zdw!2syp^al48>>OaGWFrxkf#G9>eCE_u{c~{lzcKdk`;!pZAJeY)$g!Z`#x(3P#c861~(PUVL=bg|S z_lMV!m{fq|o>czS{jKdO%G7VV`{Q3c#~A{T7yKAnH8)J7FIqyr&3pk4~OAZx_A~z+5qIido<#@GNV8ip+b(pqlV#1`;s? zV~!4p1v4#!gUPngacB?2o$|}o;bpTx1K7E;1>|fEwowr>A#u3&(;#FdjL#ZwV>0`C zu<**|M(lJ4S&g3{1yi{elh(8x^7-)9=b}VWs2MZ>3z=hx4&fy%9^Z0micW5whaN|f zcYy6zCQTyq)G1fJ4Ds;3j+^vUa-RDiXzi%~C~wx5}xGoq<|3Jq!6VRh+$M1hneNZ zND&Xf>WA_Wqk}cn26}7W-DzGiVBUIT@k6>pDKEeiXG81sa7L%VyuvyRz>elt*y+NC z^Gxo;B^NzQY^>4r{INEIc~0Qpu;r6ml9qXwD~I7)05`k~gg%CpfSp=f3QJo22XbX# zb8W08>SB%N`kX#fjH^^#ql{eXZI&A(oMV)nBTOLPN^(xiAk}M25Eby_lyMy;NQKuD zP$nvv5M|&>GQ~qP?{)=*b|pGvABx3XuO)e5VJS8XdVGZHf2*~Y*igwRojj5`W!l_u z^860<>jo=Nm_rO9p@i0(hhUvil7~!8Xmx{OI`;LFOZW>X1;*8CEI~Im`se=G&v$o< zq?V2EyO%z6uL)gW_gwBsi8jHIwD8fs1R`x=bQK~8c1wW;4M4+Rnct*9gM(n+Rx`j+ zLV>DblTF@5z(c=t!2x*-_HgE;bxmcZQ;ucH{q}l zJD7c@BeWe7QrnpQaPh~+igeE603ZENsdZN+uOZ9z`%6=00YCL_;=wK!&>0RG8VSx_ zjpU${Tv|su4|v8+Bs}V6K}>jv`=}Wen!H7_ zpdu7w)#0-YXl?i~mH+)sR5BjjMGrtzfuhv$yI#W-QV1M^6YJ%-^9eMGkSGXbr`-RMLAF@;;-sZqXGbmOVwlUuK^E|*;S*@AEB@2S9dJ27?~oU!NILD)XW_~BsA zO&8b%{Yqv9G!6um^!F9@Upb)#odWko-S=H%1YAo4$_0cvmm&VKktElAIgOpNbLRi@ zuCL2=OEZA8#=eKkL4bFlD$PtC4pt8gtONR+2-@plWA6<>BMnH#GDFTmF@}n<;~!p6 z=0CdiIfrDt7v*wDGY>qBk=~2VI5a6ej4$N_8YZ4^p78Hp<*uvYpnza92hZ3=C4wTj zE^fb(*}g4GVv;tx*cI3_br5D8i{gM;VguN%4?;4yJPv}(fX8|4gnV>J;X!bb%Ymn2 z0=ozJzZtKo+8PK2Bo26x))k^O2UHINKDRw80&M*ZIAYRp7jJ#k+5ISjviH&?+JU^S zKeByEzgg0_uOp?&gyIuR1*lWX*x^77;FQdM+9rD1u6X)I|Fq-wX{XES*TB;*{ZmXW zP=W%&VomJNLJ9%YIy5yiBiLjWY9r?FkAp-}06yJO@A;SEUoD$*A5%N*;zj|2-JqK(>_@IU{av&^64#cACoz72mm4$2orx_O0U^R|ARuIDJNmTU+q69w+Rl4`KrLZEgLYI(JAO|)>7tz))8NYr zHSA%905~`CP%PqIHC@F0=z*(x5>lPl&WH?uWj6p)6y%UXp7F@p9hyKlaV8@w=E6mO9D zU1|MZ#G-faztP&u7sLR*w>&%IOh)RxPKFlmH0VC=jaqKpm~0Aa`8oBCx-nhy5Jt02 zUmbZk^Ch0WAKZ5+>ll^9T5-|yNKU^gMRap9am4TbfUj;OYvPBh*>1~QZ^LdhU-7K2 z8MIXQI;nRaiDT`DPMoZHkF{)NeL4#$U!~M#T)6e)^vLMXT@UV>PYQ|-D^`uS7mbEb z%&0f2_+2FVRE|G?`Sq5@34}2UgrLnuy){<9eP6q}Nt@Kz4KIXPjX!xQz&;kdo}ZBy z(f5H2A&VC3?s&{%sT4g zc#MFz_;HC4UX^~NfPiCmb+Cu6iY_Eb#b+)&P{WDwKV@MGwhwC-;Qake-f1k8mVDO> z!4#*E6C|AGwB#g`1;7CF@0c20TYP@?>)3p@#xu9Y2lg+NL~`7+j*4^bueIs(T^%~Q z_0)ShdfuL(w;=W)#vQVvoi0`MCrWRh)AiX4-}vXep?!lFZ^uc5a219H_s+c@OU)WC z2iRF-bE^%H-F$22daZyM^?VP@lAQRv&)>bv5~!WI$UR*@FK+!`{ripPm4?5PRL8g1 z5mztSzu6Y`3LH}q-7u*$)T=gnI}P(nqF7FdHE)JB0!fM;C%@iJHZN9%Z^*4ln=Nfa zsHS!0j|)q__DwffR^;vwAa)4g87TD=q?B^G$O6%^QQ}yfbtKxZ7 ztpCfgZor6%w_sS7^P_zCeGQ2KZCILqeYvAKufnK@K1>r>p&R|^_e<7Smm5v~YgLR= zd{z2x0te)4(#GIizYO`0Jhh!L_>~`Zb)aMl|-k(4qC$2{j8)PWzrhCie5@2~Qc~(Q-dw>Mi8}S|-aF9Thq( zYx@}v$1z2B(qYDlbo@e<0r%$UatSb)6ecd%A|+CHXPWHUeT5-pKnXjEMG!eUYB~T~ zf(8N(q&?&bQ7D|9qf^QKP=gki9KXVl2q;zRxHg-D*CJrRDVd^!_F&8cRbTnogvpI( zUcOicrq<*Gf9k2lvkTC_*ziu{zw(Eq+dO=12{9ier!kRP7qs}cF#uV!=tRz=HeGsI za38*aFCU;IGYRZT5T@fV1As5B0^u)Qjg3?;QN(X@;xykSrCg=?U%XA1N8tJKJ#~Im zS6Ia^_u+1VAh!WbLgrbbvlWT^6LyhLyG&Q$-(WH^^cUIzdOiJSS{8%9uy`g@a-i`1 zg;xzvVbsC)cphy|4&@l}OF!wovA);Icb`*G|4jL`~dK z-`Xs_zM+`w)|=}Ny=Ixc4JFv(H#hwx2%?U4@duZz)JNWRGc>P=N1H$tk4;gw3#l?t z-DL<%uStw0xPa5GQ=@(rac!AwV{;~9^+n=$-Lv5el@u-7?QiA38|(Kf-JJfrH}7uQ z(A!vze^haQ$J(-WwXtTuT-*57k$GOTd09Y^7E;dY+dHHHOD`eDsa^R8L;6nkN@cgo zMMG0jEB|7ZVR0jkSHA}0-<1?edfhNi7=KY7&?vCzrk0^Rih^8mX9{}upk{?dG*ghh z^>E$$k=x6M)b@;J_>%6kHe`b5d}e^(pOL?AqGKpTmT}r2Pc=)ca@JI|eo^s5WwV~g zMTI;|k}zelYiJWYv$XV1U0r4$w8ddQYk_B}|Hq-uWixhD;<`hCqQyjxtT*t(t$ZO# zxg^H{f+`;np>^#+>dnMLK1wZ#FTZ7m(WB{$LPC`>h?dyDzJCc2NQvZ)J~pDi*d$2J z18;I<*h+;oeJ;CK{OGCZT==?`==;S;Ol-4NlCU<&m^mjGwq+^g`#;CI1(QDFwaZLEYPW3bSulD@duVC*&Htp4zQzjWD~t{-;srXy3k z`9iF#F*>+GH9P+xMLG0M9!{ZaIUAX_ZVtE9IXj4ajVV6gF?9E^i64H*>3^z=vt$=} znH4Qsc8&ycF%r*m{N1>a=jCeWO=6y*g6baMo~K#OWKJ}Q*ks)m_Zofr%6Ed5O=*;v z>_;e^q8vsSUtV9h`)z!}dS&;U`qRI@4tGW*Q2dQo%o6P}trT!_VEvybZc*P_n!o=( zs6XO$xpx6rN832yc>9Fc;j-#%|2xIXwlh5MbskES9+tn1lJdm;^n=s%kC!f0j?Nc) z#`dI+IrJPoagcqtdOah?W0`^0)a`-t zamskS!f;)le;MzSsA#szS<>7;@WbIHjA4aI`oqZLqOy7(bw&5eiC%<}LnG|c61I!} zlWF5#(sk91&0|6SOD0#!=BE}t*;Qr`+(+>rXs_4i6;2z-Idh#eAGfNPlz!KQ`3E|lvY#wqINV^&39W`scz0b*M002eD~eK;a1wi z;24kB3rhXL`3z)Yopx?#2TgT7HTm&+_{8pGttZ>hjTXsu*@q#De*4dj58wMWZ?A10 zA5K|@jpgz$t+;6X%hvfTGg0Kep&Xk?mW`O}GR3hNnD@a!EmZaUkM|P`3yNM@x$JbuL3wj{k z1`Wm7vnsm-WlGNW)Vb|&CXo27p$MNQHexxd-7Q9MM@;I#qd@5 zh;HT=Crt>n(HpwcC1Ugw(&V83Ku46K9Vy^s4i&&?&6+XmQWzNzH5V5p9sB)f zpZv|2XVJO{c%X}oP`cCx5pEY}(coKnbrp3pi^x9qDs=12*TOz=U(`M6>g^db1Ss>b#Q2o1q%zsBC4Zbm13%?EzMBg%vfsI7&-Byrv7!u)svX`Op`Mc z$W_$Fl_>tQp2$`UeEH1n+^^1=4&;p0Omx;{aV1B)8wCP^uU1OOwnV#>#Q9!`2~|J1 zaqJeCievQ$a`cI1mbYb=w6WuXQ8vV=Y8*XJ8~r_Z)_cH6-!=}JRjxANt7n>tzM8DA zfa6$P*}b{o)i*<1ZaH+WxyLS*^zNa(jsXHV7QAM`3m}(FIag>K+r2jWY%-jsqK>Ts z!9zswtkso}>Ft2*>6(REZJcB`wmbq5YYg-xS8}htvd;K;O+1K>Ln^Z{$6_lx|TeN{;=Vx(e zF-kP8_JJ%k3$lQPFMw9FJh{@(!2w z>dJPT^`=!xb9#X)EAjaF0T`Y*62HP>(KZ(Fw_l|CYq?}=ygOTF`4<)dFTr#wWNj*d z=F+VG=eh4gWO-S7HRDJGv87s*^IqGi+{2Gj)vLeP5OzdP@)}2wCJTAJ#s7B7eW@Y6 zs)~r^A*q%2)rT8Bp2MHMQ9`QDPY0Ww=h_ReRR!<24>h-QfE+p-Ej(`)>AlBv*CD%7 z!%%O+w&a)N^=5!nd$}>760lwIbLlk{6lVnadO-xs(>f7cCn=_eLW--4y7 z@zS)pl0XH~<#&I3cnBRYG`AnL?ex~veU%1td(azrbH%RG4~eIZy6}m)9WDuM&Q*Q; z_b`lY^E^S-u6k)(mCP2a`8SDpVpO}+Tl>)x_~QkT!>$b&+Ka+<$LveO*|C5On#`fP z*K(3f6{;*$q95i@;-ozp0$$S536B( zGVc4xi;?a~Z#hhhJnTx#yTE}M&_!>?vlU%uM1b2YM@!;!eI0AHuJG48(I^QjTk zcq5csuavg+pQxYS2?FTYcA*qFSHB}Uza{TLWQ){ft&F7;vxb@bbN)v!9i**BDbPCv z$dSKXg?|y4V@F8W3;)?M`9u1!k#JOhX?WE0uTA~6++Fj_YiyZP9RDNjKBJnB!v)VL z5NZesNG}qQ-b8vQ^xmXP3mxgbBcX;ay_e97fQW!}>C&5YK|>Wq6ci8z%y93{-ksUq zIXmaU-rKc&fz1gs z!drA8EM;*n5PC9R+w2NFji6s zU^8#)Sb26Xe(jGK!3jSyo5r6xV~7C$I_yx=_a_w+qW2jhuTux+ASv^HUHNnb!h_UO zm1N9Sh!TyS&;~x}4Yahp{2bQq#ia>I3|Q3iwR!Ve^wR}t6OZ<5^uAE}2! z9BeuPYcUJGbG--eLSDqWW08Q}4 z1NuZ+z5xlw#p=2*pXjiw{)@d=Z)9$(5@;J7WIL+jwPH!Vk66l$ou*b)leEy4j8Dmp zx0N)%8^^P-JI9LDd0f&rMO%*qi%!4MEJxJkT|N~df}L(DyibTyj@P?n*N@o^u#NM0 z-|6Z8+u1kx&TUu@eXy6&Ynu6THM7bz>)1Gq?^SbNflofrcO=-gIKZ!J$WK8XxCNkw zbv`ybZ`kir!7P{ewamoeODC^w=0@+xJoC}Nm+G1r1?_a?{+fHwNX$@~6eG`y&{ZDDtl~MWN zTC$?{bou=3)l;N0%H`16G*0gwzU-A~HSV%VJ*@eCkKxEg{`9mJnn%e ziv$7{gmXS&18LgT+_caA-9_0f z+l7k5+l+8wsc(8~UIZIdsgt6B449#u523m0fz(ayk?LxpY8u`C0q$IWJ>ZCv*Vnu( zH#uLW+aHnv0~9-huamSRUL|~^iwk!gwbyy$M&S1?rhsym@vdJ(;HL0~keee>8P4RJC+gP|?+HiHeIt&FH155lpRcW-D>5Vw zks{QfzkrmWzMlC2iI>3yjU5KpeL4lQ;~3e+X>EdqKMXfL)3IST&};g;S0XqLp-d)% zo_l@0**%q=8Sj0)7cm8v>*x(HGLEK`z$!PX)AV}YdnYIw%qw|1om79zLTe@l1Tl?zHjfjgZgvkYx*9cEJw|3 zE^R$UJd~4m{zJR*9I0P5C`LTj!{zR57yVLTSBZtclZs)LdM2kyPtKRe_tbSnbER`} zjY|UV<5p+gx$bK%;=WJyT8_QzmiqjAi<1};t^7?>c9dQsm%ckwx8G;ZLWO*J;lJmfSDN|Wm03$l zAf8J296OZ0_Wo!$TgSpkpi}g)b?3!12C-+6wOk7r;4j77X_D}7>llU7L52)2Y?rpd z>k}%g(=I}^15Bxdy#&@wDxg9#LMA2qLKdIo8)TH?=~PUrSZk}kYR#eLqH0x_0ZuuU z8li(Em%mDk9xWi{B3XNb=tB#?G*z-n1&E>QTHJfRV^`Ps1Vdfk3u9x=$GIz} zx{-nGW==IGt7@BnCd!|YSwA(*L)?nVQ4Jy-$h1sKs4Uj?G)BmT?jPyL$of$EEFx>D zOjbR+PgXy859N}VxP!g`v}~isOxL#?VajO&dCmG8Ar_3vZz-2wQ@mr0Gr-j1Tr+Gx zo=ou@^;*cUwYTujJX$G6rh}Pi7*r~=^(;?1Hq?>`oq|r(y}E0@=YMTfR~{4Ad{sbJlCl zmp6XI>JM+vv!!ve=Y%F_ocDur==J@k1kkOQANZOVthXnWm66jQ6rEIpL+?X6%=kSv`NR9 zIj+p?m9&v}%XSsjkv~#C-N@%7=HuC<094pxHOeGVvIDj5sqGV`MUq{O2UIcKaUxT| z*la4;v!CuTA~|9u3O}!?+t=B$vWg|E5FZi#YpU}~2^vbOWAhDnQf!1|%)O=^3t~E5 zK-?Xe8x2L{gu#;7tLhA=PBj;O0O}E~H216zIgS0? zNpSTu8h10(?7NvM``yfx!FVCo243;)I*wKCcRGioMk!e!w@OOrj9dCB43{{n@v|T$ zaC8sv@KkjVJ47Za_=^RtF{=7<5t?QLpv5MtOK14v6g}8msULK!NE{BO+p^!|pm!w{ zH`rawlwDTRi~maeuxK$&zJdM-g%&TMSZ#GvE9JCv$=&)hS2F5f_FI+|7F#fX8%Kz@ zJY`7!zNjqPOS_W2!Bw+54A{t9|B~3`$U<6(+|(y0lbz%nQrmteGxZ#gL+%T~zY20^ zE4F(Aa%fROisWE+{MV_DwKQWD>tN!ldui(+iE%qYM2Iq@o5~#LU)EHuID6)5)s%-* zuU6v40~+D+FrWAo^A-6o46}hP{*#;Qrc%*8Aq6pj)?(`uul(Nai|@g2+)>PQfW8B< zAEArIHm7Q=WIu$5!gm;L|IFnNTy*@1)b)vZfGYvKy}kGm_1XQUPz0j?qX~f7hdmCD zs$d8*-V!o-j3f#EO`rS-Bn5<-g+Cy$wjK}5Al=MUlgY$E^^gUE54e3(UQH5e=%R_Q<1fyVZvj=hqa06 z4q5EpWnWZ_L6vZ7~OENn4 z!of4ib8yd}skVvbUquqR4kO_eU`$gOn-XwD&QT*D*w~$Y;`y3jgOiUBQhy9O)+^ZF zVfOC5yPr0~$$o-P`_HUxZ+}XBx}6J_Cz9R4D@lU-8=(3q%B+dGwuYz$>A8-8q~{Gk z@ZJroGW>`pRcIfMJ5RY9U2{3hY>J`u6#@w#0`&+M2Vopy@vJvoKf&y5dyGFq990|L zrz_i61UWRh{@Eo(^~oNF+^7hd?m(iD4-U{>Xkp<@Vijyrn};!0!Pqy;wy%of*0N&e zX^U@q_Iqi|AJVviXJ_Dyt$l8sS!jav4t_@fUg=XFcP+M!InBn7JGSrG^5lzYcg$mc z!NEmlIA*o4$mQjhaJkv$ZHR=hAP|M`F-QclDBFZ{y6-(?4(F*od&KO!sOlDo9~hy0#>1u#2` z1!xtiA?KP_15jF5CcGm57gTk&Sqs=ZDu^3ma!joYIk|koy8~s_J0L?Lf^gui0p5jtUH!uFZG;M7?D{rZlxLdcAOjCB`Us}n(EKJra69$hGySEz3Y7+f; zczX0Syl*!=+2_Yx?R%^b1vG=*V25d!m7d#*896arT{w=x<^mXGgPjG{*e!gu426Zr4!++i_am!J$QJva6GpRU6^46 z)fsi>Bl_G|uJ*nvIOj+IT2-_I3}|l;-6tIR$Wx);5p?J?dKr9@{6|b1>5;~$aF+>SKJV#Cm<-B-=QL16_{>fAE z7^yKtO(6VZL5nlDjpKZrY#Hvp<;Lo*CQgjz$~ZdhGUN%);&T<|-Dnfwa=gF4L&vaV zRhz)`I*SWu@5~(Sm;If`WdZ;W*;TlLL;10S`H#(4mjtN&AC*5K(o*~~u1H<|T(;@w zZR?T{)DMCkWB-#?HUNh(wQ-4K$pH&O@BR2FvmcrGi^W#Kf})wf57CPcS+zajTG}Z2kRBo1yfQUB67*UoahE=`m@Rg z+w6z;$%NuL@lg0=i=q$TOQah~E&7Xz3{vJq-(O{=r3BJ!0rRUJq-U$7Z3*oYcllzM z!t7PZ8UeD=D5w`w_BEwK;I6DiJo$HoFw?mrtEdu3fD%u;l0duC4;1@8fOesRrP@wh zlkFbvFk1L{NvPMJKrl(`bx*H(Cl%%J5ggQ0WFMVYsQ)MW% zVmwb_@=nPFa-m5RC}F&!yFS9jAr?L!U=i`l;tHRWkX-#Iwp{!|DC)qd>cxkdBRt$f z{q4_oC(K2Hc`n@AgdZuU=X@dV7N`q@Gi(^%ZN$4{Gs!v!VfO$eak(DJxpZ}66o#s$ z^)n-~`xZ4~PdFN^1KXbT?>=z~)c$Q?>)vX;jQKYzYUO)CBr3D&hmd+adH^SLIZaD4feQn_6b&fj8YXz z0NCe10|pV%;z6I{LLdnN7x|{I-f-0h$D}O91jmF;FFNUq#iVqI;@a3*13SX^;=!ZU z;8bql6H0X(Y(%`7D{~hT-W4kFKGu#lR(Ukxr5XAio2hkvtYt3Rz1?~N4q;pK##@&k z-nXEl!SiwyN?M7hrvoIInrg2-J6;QYTA&@j&KJ=Y7G3b9cU_1A1)e}6ac1^elJbNF zo_DmB+P$S`tMReoj`jseXUP=zkQ7{CYBM!D3KUiT?)eWtv{Fdi`vM!C0y2JDfb8IX zbawi&Ip%u^@@K)bNAxKo7Ae%~8Gp>PEMgMV*27lm#PjILsPZ_x5JQMR@h6g=f)?3M zh1n9J&t*b=f4#|ds!W~lA{)+e)+!V;g+mq)WNiSJF|%mgd~ouM^}v?}c`h4y?u98o zX!D6I@|||^`>-kl09s%{Tz7TaBm(>$q23y*1&~tYvq0L@7j0V<@9BrEXwM-pT8(9^Y6ykR+4)7D!i4-d^-wi zi6JAdC{KiE%@-D~Ng+2aDs+n~_BJYBsF2E9JO>v6+7M(52nc_V{gnl;Xc(jqQ{~G} zm_whV%1}Y_M^?T&HbpwIrW&sY0e;d`anhaYR8;$rq2LV)(hi47#$z}(F}CzH_ZVtu zpVX9Y)@$zL&!K2Mq8pn3)W7-z>>9MG-mD$6u)%c#AfT`u#FNU{%@^pR!1tk?yj?GA ze!s+tmYQH7ZbLLwmd&hxi{3DB-p7EkJ+=7PRh^8qWwH?rpb}FHN!yEFcNb;F7d0zpwc@Y5 z=2`Drr0*6(ft{l}s6Rj&QGkJv*kk%G3;WJRBxC@a-wk?`W>3%uCoAIslVj_^VJ|b) z+O=hx^gq;m_z-RkfGiYsxK}_P7be?%=w~SgwgJf6s>#x?dOsJ5HDVh{hQN(jomb)A zGQs_Cr3ci*hdKI&`|*IS$c~C|nsKZd4jlMald%hes+>na7Eo=y)q~ek;E*C{I-vi} zlm6!k{hz{{G8qQk`$P;dWMzy!+i>tOEoWo6Q%mpA*jm;E9I}c6_g#0IMDUto8-4F` zJb-ZrtL{m>_M!Ok$<6Vxg05e=XcjnFw4~!{1;i8)jkYoz>FUaqaqdNs&7cwuwkAC- z#q>~P*GVv?!3iMabiCE{+xThkt?6y18SmG!M!k@)#T_mc;23|-)e^x6oAY)tz*YcR zR>UNctbEL$!B<64ydlzV7$I@nb0-c2f@+W%3|Osyd1QO2n0dHL4qeV1b}Yw*C&NWNm^HPvIFBG` zy5ZEs~h&`z?PRA`*;>dkS zq^LX++y?*~!=GHrrHH}7oA3`t1CSQ@#M`q2v&bXsVZdVyShSSS#Q|)JJ*52!YQ(gh z^psyAu>Jq$alfof(Tw}Ha&pMOpQWNHt zoHiZ;gO@@pWItD+Smiv+Am%(Cv5|F(2$5#o;%G{?jt7&-+U!hm3WvLRx8nX1$>aRLz&3%0 zpuuI&SODuge2%ty-+LS0NHMF%2%(INFjEkB3o5k4rj3E0r4fJP8y+}xBapk=3OQ;u*ATe?D9e3!sa@9t44r=rJ1=JV$4oE2fk|RXmwb z2`JP_z|h$8*G%BGF{vY?M}0IQqszWpg0^%0kQ!sdPqFE2>|Zf$Mn~isZ|5whgnJuw zL)x`-huJP&@GdI51c$*N;GwI zmfrIQOG;jh`S!2yNF*23>kfQ^`#pKF2MK%+R%Wb@ zP2M<>HEY{1|FL*Pc7SI=YYb*HnJT?Qkjg88bo#r&z?Q+&OM`D8Szz z^HF#IY(NJAU*`cb6XgJC;vk4}0Y!4oLhAY^hVZX^>}(;T!f}8C*Kq zd{lc8Y+J^b0ebC$02Pa{e%8{+{VC@~f~?HxT=VJd<9BuXLBseh$Htx zjk5FlCh2%o-YZX3Vb<75G-#@%e#x!MYvY?_iYcY(Tpz{p$M~i?P(7fZH&+#@^i9)j zQYL16EQcFhh$l`ST)xTxN-z1QKhCsUb9Gft!1}N;(-HB(l@zXb=3`U$S%?_F45@3u zoKZKCxZq@zl2OS9{J2{-9HJUdC?Z0ZCvmPHO3#TvU zI#H7aKVV={9L(EfnoW4&iwC>)GYK z=ado;$4SCaN*<2AgO7ZMGE5BE$P*CbvNt|@fyp@Mauyy_D%T<5ka44`iXGRF7^Rs=Gw{8&sx@TM#W_{0MiGFuFDiYyoGpQ+4b{^eT6O-N# z%QmBU@AsAOqX4f`noPUi#d(@OIo{;2FnWWVE7i(xMZUB+CwfD0;*}(=J&YB8183Aw z8u{*nFIyVaH~d6U3B$Nu9Y)(mH>ni#X4<-Q&P=*rb=5m%&n7<^!xNA=gp}d6xqKoq z^nuJe0{?tH;4lxK*cQ)tT5S9GJ1r6`z!6LF0=18a0R(9b|HfR}5qz4%kUwjEQukrz z>#B*jRecKMX=fc(dB8~I*V8x?rYrz#&5pnjWkzxP%rA~#U~rD?w5F{sL*1z-HmjMNjK-SY<()buRp~A9~&qZW$z*9o4dP9 zsGSPdCY>|b;e-LM=Fux34iUI@Exl(rfAd|Yy-rFjnfQQ6SzX^pL7BPv@RjyTB1!-} zBaer(#j8vqa$R6(ZIO3VB-z?C_W=a}^2x$V^HH;v)%A;c@0(w0fu6%M-xZ0i1^Ai_ zb)ArW=#_`^m+2Sb0P$spt~tG+4v|}Hy>OZh5dC>H5D7fzMYK&F1~sa-yE#ASm@@AV zYLW8;(D&Cs)+m2fHq0Kw{{CJ4KF$DAn(HMwRWF1e^qv0v?qGtLk38AW;1FqQmd7M0tR}pho0L z?B~|bk?TMZHI_h{TZ1el! zkm}KWy}nAr7T;;xftBAhv-m*&_)R05k&W+xbzpr1R$2+{hq9aR7lPLtd;-7TNstRY zt%x73iufybhn{M^wP>b9fF8T9`?6+mtrI=DA(8`e&}GFUU8|@WVKToI^-F3^e;(pj z44l8v55y|mBTh&MR#JH5B4)Y5^6DVyeS=dB*;y;;_uwdMGs_>2Q9VRaHhEEfzjccJ zrG_X>PgJAI)t=?8k>~jUh2YQ%A7G6TIT?4fOEiHGhZ)6H=-W%*RW#eWgjov_Cp`kh zCgdXl2NFMc=5ZNq{Ro=o1I$4|<$Zu@LQr11Sd&)-S-zH^oulK-;uAiHkEyGFSc}}w z4(g$d(-M!n2PB7yk!=scid)I`>Z6dm1mX#{LhA{k==i^v;b!Ynv8JxNkBFMM9@!B) zI&f1|VWHm^prwPbemKM<5siNIR6NhgZ#_|qD~#GTzO)J;jSAF92Akn0@^U6pE)v(n zNFa-(ug{$$xo{{qUx1sz)Ax(fSs_V*_5Q(hbtGN4jLkx%5ac3n7q?I%ly@8*qM4bAp8gk`B{uW7cUnsm$GTLMaK=F?7 zBEf%l!v9-=Q662G{(C<|zz1BSh+6<+aZpTV@Cp;_~l3 zOs@?N?sq{yp?efCEElm5(sZ6gN|Q{n2+U~(?=3(-E|4;h1pf%mNCt)kvWooZjJa9O zLMz7lIH#Q5eIv)>DXdZHpT=L&p$;Z&C)Z#o6zRGT^s7PEOg)Xi1K1Mj`EVoM-BUJ8{6%zDJAoCSSFvWtLX4M=_xyhvmi&)3}D6!S1j8vBX%tR&4c*UP!1TymEZnR z4AxAtYzyh>0=_Ryv+qjFqa_9}9{&`s4Vu4JHrF2FulABFi-kGXaY{o(VBT#@7l41SMS zgL)H2TU5dL7namsmIA^+&dZ670qkLRKQ_t?d&*B6Y8XdrtQinSq?ih-qDd0n`>1Rk zR#2w8GYLZ?c$4~j1}QX?^g9f`qp7{O0XqmS>)*%#DFPe;NvRH18*6#g4>02vO!Rlw z4^gSiRIar}sP(J6a3yIx1{A+Qdfp0t{YRI!6}S^nJhK4%Fj$;tfvX1~0qxE%RzdY# ze;V7e>We4q^oQ=5I zKa}G074z2#m#rShwN3TcJ<0hyp4*+#JG?Ev>Mdgv^qf2mtY?0K(S&O`u8V(jE;oY! z$Js85Ts?I7Tb!lC9YxSZqC5-{xIlbYrFHt_NJ!s7_edsiC-j!#waDSiCH#)PMmho*epMdmS&|z|@e|f**ueq` z6Bf$e0G>p&2ZmD2=ZCLIAEmv=gU^Jne#?0WB6DbYk$nQUjz<>#c*k6LY)!2aC(GcZEU7EmCh3oC_s3 znfTBdOr3J|rl-LjcDHFQ#6=&501@@}dp34Z?%;ssh^!(M*%X5G#AU!g$vW5M)oDtP z>U5v=y)=(-3OWNAb?to*7_p8oCbQ_RV{Z4kLGs>2t6wIAmx|{XTD*4GY9j$;j+m=Ua}$zo+6@5zyLsa zXAloxQ6NweOtVELD&!BmTg%Dq&J*f{_w@l!6VxI`@uzx}w+5H@`ZUM@Fbo;n2ssV| zQ9|RvO-6JTi8o#hb%7g5z!X?4`RyP%7CC`Eg~T5hK3{JHH;pEfP8$9hAe+J4JcXWR zK(6m1i5N1Hh2$J1VjV?dPoKW4W86FVhY_eD*~s8j^UPFo>iFwRX2I-NK*q^V{z?8m zTSeGiSdn}K1O1x;IXi{+!+c!^iJlnnXodS&rxrCdwYGn@UaU>+@R&{iHqJLQ>MRZO zMUms~qP(z~p%TasvLaa8W#InXC#|_DqgzXOtcq`n}|(9Ly1pM zp*Qfky(Z|25Lnk9>;i{b!|3ujTjq2O3SYD;&G=t55mKg1(?`y_=*atiNY6Kb0(BRL zzLACM5HBD|f?kh7Bd5Z_vp@U1Ac-%%UuC$a4quhbYFnjzP)qzb2z}5Doxu`T%n-%- zKz|lsG%c=sym#-@@k})#5K_54egB}JY+{BgO9*mv z3O!i>>3I6f{;j$dL#b=_+i- z)tX#naP?wsso;9)r_N%sT~J_jQ0R91b>BwN#{5z=um%M^7h2!zgTBEKSKg4urLBH~ z4|zZqZ`c>d%s1S8H#ETAwJ$cvC)Z|=IfPpw-KWzJN+Ao#kz_ddK|j>BncN-nA#=7r zn|ZdQl=@A7&aup^lGzW^Cm+}t7=^Z8?b+_-h zRRAX7IN?1{2taQku?0GP3;mU`^!)o=>%hx1{x8`!Ou05a;VoaxW*57e;K@&$Iw-$d zL<84+CJDVD?=!wmrLBHP61UwyUPyO*Y;*i5^0?iohpgqGc(-PK44k1MYvCOE^wX-zFdU@VoiWT9e=1sQ#KnWCW=F`yRB9 zf*xl;RtHZZ3QLerrw6Ifk3#qa-e{oeGB74?$pAOQN!6d9SE9ZSF@ZH- z;?BD=z%>RSMg0pC?+dO*RkN2Dmh%_-R8`jVDuF^jd4_>lI3xi{@(lpydr9hskMBYM zYkgq(k6wL%tTZ)XGCaL7JpLgqomsrewJnW@*E$0Gzs%Pg^nJ<4l(2>r;z%EKlNes)#WE5-oJYKPx{ES zd3JTN?0OVugY-jqd+;TM?jfuE+|8ZUj3o8>x9`>eV(63D&?y-Nh>wF+ll$UGGYyD~ zZ3iN7)htjL9*CUXd;zWq@$%Sc3_QRh@MXwktIZeL#uD#6^x6**a!}8JDx(D z!7sN$ZY&*W7YIl#;uCNe^s+p%xI2G3_*oyL7*Ede)o8LO>gHU)sb{%}+gt_XQA-C4g940d9xeO;-Q})NDtNF*bHh#IhE0T)kw3hzm{Judm#dNzz#C`1* z{aS@(aSf0EMGtGy^!w&jg|jSir@zaa0}W>kx6U88x-C2BYxL_riiHK@nteRIUH**B z2cLeD8T`2_Joi?~pWrqdKRe;xRme|Qou{ozPL>veWlgr_QBgVn@H5zfL{yq=_?l0W zWC#O)LVC+7hw4~r62p0m8`l5eE0N3GoJd2JsTTQR>NlFbghn2dlo1KYq?};V>=*YU zT#uU5JGa6BZ~5DKeMebT$%IE)<@hOO*o}>U#t_MD#Wi~HM-Vjl<_Mi>@uQ`MwFTpu zUT9P0J7(bfRP$6*1|jW8D17s};F(6GNmciP;ws!pnW7v}@0vT~7WBUXn)M965(f%u zK4SD}Q#Sfn!KGE(HbhYF<#_b-@jb{`fYG67so;#toAABD(Dli9d|V#eAEIT?XfoPyPft%*nLN4V0d=@r;eKW zQ1{9y&^jUXunF;uuO-u;Q);)3Q=T>zAeblRkSf*Q-BdNCRm7JW_>trj#iOf3mMFDH z#yRE#MTZnc2Pc2sSyF0gUFu3{e)Hq4Oa4y9#LxLXeS@Z!S-^GIxNmyYtCz5rXal;W z-CHODNcYyXrry)SoqvrxZOrn${CEqJYh-vi@(~}VYm6e+X39S>z32@Tlu{YG9bc!g z_&Lc%V`yv^sciVToG=?NVwfR2!clWOaP-Ulp5HABE=AwQ)t}wG0L)36rA-OoZZ|(i zM)mr~R=w%H%2WFt#!dfoNQIDFr~;d7?wFzIql3v9%8ckD!~`0;)dTT=%n}V4eEspp z^s1Te-M{s{Kn?&>(u|P|BXqp;FuK4JbNG|Ci7@CmN@uEg%aJfX!u%_j`2$i;z*^4| zWG?crKN6&AF7VF@9dhr+6wtjCk9Qx-&(lW=NwHV1#2VnVq5P|$4x)#ZRPex;A)pS) zt9#4cdNiH*CHlm{O7my1WUD1s!<%=*9Nh+dmfUbWdCsx4=vNN*Hvngo5TfALFJS{+Uv==3A0(R_XVSdNiudmxN^vSFqrY_>QY+#P zkh*5gJj_E~&QjddKA+_Kc{RX^hoC9A+Iyf)@)|+vlo4l4HQyE!uObgmO}~LLP|#^= zq`PK~TR!L&ERd&{Wn1X+lviH{1ecdQ0N5MKla=_Tw&!rdy4$r(6Q*;`8t?>Y zb_p%!DDyqqIhLlr$Z9s8Jyva0qym(#kFq&Wr4d*~kQA}S5;_rlY#-y7M{3!o zi`0-q76n<<3@d$&s|<6#=)B-sc+SaNt)L0i)a^0M_4-kvSd%Z^o1;~1Ptc&*Y^O&1 zd9lRpS1516n3A(%OmUlWJs)$UV49X{o$y7T{r2)>eb7q%rgI&4y_=>X!l?2|TkX-Z zn<3ZcbaR$iOV|N#UTdLgBBUAQSsG7@_r$FGyI3vd*nOQe8qIpu3D3WA zAkUh3JLm_Kg-fxQL7x0J%~Bf+l|k)2D#tjd1HVo{{UF%+G=@}uaD$uM;MMceW3!ne zt$gXZ_9T;L*Az>`lAb)pU0y{ejlWye$o4nB+9yxbrYo?U)2|j}zPt7E^}BbPcFQ>M zY0h`Ro)`oBRyYL1Gmlq#TVA()qE5CjbhicE1op|iie;P$|CrUO`zA5+WjHPP)6!IM z&w2k&1U(ZCk&Eiv>ry2+Ai{2*e0{KQTOgRis_&%b_s|maBlJkGts}+mFrbqzi6jCG z2`{j-J@H9mbaQ}QoAhyiOk(>7Mm{M}9Q_!776{&Y%Xkk12{`bt{)TM{97FjZfzVUUqh!!%D)^Wi(;o?jt+bO}W$*VN}XI!!$d5(78 zeXfjW1T{HxOs`L7^;|zbc(f-Q{t$n`$pmB>_bqXj{_0FW2%brWV-H zPbus$7|5>XN&D#iMEd;+vuK{BF0=BR*6BF%4uu0*7d6|1xv8{(FbA0roByO1i#Ww! zNJPp>#$K#S){59N>wf*{s@NaB+V(2td*YZKUQrW9k--1?66YCLvS@V~j{P|K8KHl}^)|O# z|Ge~DO4QxPj0D$=$sgD7G%KzuS9NV^)N}1FB6+25@>5+=`HI~~5@?8HK=j1hxFa?7uxbB)7SEs`HrENRJ8Ts$_pW8S z@6GgU>v$388Q32TNXWiHKR-EsfNQwg(Em5%5cTQDXWFB8Ut?LHQIIPmaCjbm?+MCw zAn_twJ8y&A>VTfOLq}QT;4Xa18(b8C3;|?9;PDRvB4VUN@bIk=cR4Mh2n2B|f}{j- zSGpwWyF1%}fNUX%n-Jt%h=0X!51&3`3+gq9_G6iJ#C z8NVUuXB3$u6z_`;$`rt*yJC5`l^)0{vFj*tSSfL;3`=FiNx3TVlqm5wDe?6w@y{p; zL=1B;D?PkX5+YN6)TboKboYoajS}x}#aB8~64_GXj!=HcuPimAB;BMeoT@B4qb#vC z!bzqi7C^^!MZ`s{qKwnYROBC3wi-RrP*F1$RA;Z(n5orttkGhx)*h|Yi5Nv}sp##i z=--U0lc^dyvOeZ7Gx8`g<}Wr0C^B6xG~*v@Pgb?qdibPi?5s!Cs-4z)UsdU*-UgJ9 zyvehZ&9mQ9{U)X6*gk4&rKV=A=HdZ!waR*GoaJVm>8>*BTs`WUs&-HrZQ4rVO{U^Q z_0HFL#7|cJo2Gh<{W}job<-Gir7U&+O7*}#^@thu$Sw6}-_)aS)KO#_(M%dK{2H;c z8gV)r@m3lM9vbKfjl@)qq!NwfCXJLnjno;9v@MPFZyL{UG&0CEGnq7F`2RDehLFmt zPEm6u47@^D<18n;@A7ns|3PERV>Gf=G;<@8bYVnc0JPRZVX2O00dagE23_)WGCx(b z;A#@XG?i(mRgg+jJqoUgpet(EELkS0r<%&#m@1x`tkRjv-2ad6TJa!BVGdXuMW9uin zWI7RaGsCho=t7?*GnwBKY>-KiyJTy@ zboY_Y)^ZZ-6zd};gXAV+E?n}izDYPcIydD(a=Wiz7dmf1w}2;n=u5czi$z9j#{)9b`sdC@$|#+MX`_ zU9!l~ZwN|DQaM^=fh?g74Qb*@*di$&Fw=9XKIZTwghM8om=`I<4D%6-m*??*$j9id z$8;x4d5KHlRzoI;A+xGc!4b+A8BeHdkY`{dF1OU3VI)0E|A^zgOpPJWN}&R-1}qPm z#2M>fo-gGAjJCf0M_(>UXBkXvK+tcnHN9X^VXU1-;^ZnR*I_^iG3mZqE{QhQOiLmd zTQEv9{vfoH@r}?1qZ{C(r`8Wp&z<~_dK`Q@DaYhVhe@6Wp|fj}XO|utXnNRW(*2($ zHt94Hdofc-=0dALQ`f)(>l2gi0@FOnRn7ww+fuLx^<-gv(pyJk2938-LIldhvzIsV z!LFbQ(OI;t*;tdY6*5Vsi^%vi)>LB_J+u}emk`;HGQq@23V|F8(4>I{fnsq%k!Fzx zW>Ey@(edU%fo6Fk=6M?H@t*5w0@~1;wRcEn0TXoG@@;%!LYV1m7Ck}e%O3_zs4P*_22Sml&tJ&_jZlW}aZ{cEw0BVuSbPuT9t$NAfj{^*%x>qCS%u*uKZ)}up*x+XA%;6F`7`y|HY!)(t3t?hERdlHGv3W>ah z;%G9=0wm)H`v^l(M27_M1ih^{_LM{D<3pY(fVBg?JFY1NRlg05)Ta` zuZcMQ5F)2jLL*F^yAP57=*sR1cIx6&XQ}m;<)%R^$cLNAae+YVl;G3;S{O1x8yn|~ zCH!SQW0FYp*fma`Z zG1DNou8CUvE3__RXMB>9B{ z*y`a=U6;&rl=lK5^pw!MOD>PU9S~pCX(|oXz94 z6G7Ie=)qH$e9lRgBO+1fB%>~L8I?;e;bDUOXSBTAaQxHYfg@YzBxN5$b9%I`!Kj%R ziSb>YJCVryDDG9~SIdKsvjc(tGOnV5&wr>4#sJNPX1r``rZF8zJB2lyK=|Z|8K+fWB(UizdG@M+VwTZ zvoFtQ^ZvuGAI&~^oBd+|^}hkv+x|~*eVNXu^oRci*RQWGZvHRq`u`cOpID#iyd&$^ zCtClDtbaGs_n%~a?aFhD|ADL@`X9*pj{lLYuWWzyUu6A@|03&a{ySM8+R*TyWPNc_ zQQ;j~Uyz@dpObZ`)<4h4_&?P8lqB?>T93ZFB_{cl)kY_#JpON--B(bPf7|H$KoUsj zrXxkEQUnDQDFTMxAs_-XU}lP>_yDl_DLa_ufnBMVg36QL}m8|FfU> zU2D(mS+i#DgG^3xkT&zXKiBmoBr1nS&EgsU6Rywlb?^%a`d7H#=ilM_f2#HFo-bV7 zpTBl-`FF4WsmDLPdTTo;tH%xxt?mD}UcI5IwZ4(XJ;R3=nfi-Hy{4}5KY@A~d=kI6 zJHJOHr%MFa(~y7i@(Mae3Tpof*WXprkyg->!v3pTFD|PpF7vN&{muUl*Z;d(f9;=Y z{f#^SgzLHgD_qZY5w8EIUC)1;mki8%vTc)6!TvcN>yKbl|C~RZ zr79Mt{`Qb@H1AS_+<)5j?QfBpBF~|bPHY-gMbi~_qlISIMlYG%8ti zc3U5|Dz<+u_w0Q5(@?ts^LM5%&WD#D(rK0|v^9KN^{rF#TB`Gn;NiT?SMv0I zpf)A*LXXcaKB#X>;ADd#WaG*9zV%JWy6e zJdo@{u_@%HSJ(a8mp`u}Y06BLDwILnscdpeYr1ME$kZD6&e_j@!Czr^1c#iu^(iW? zhlMG`CL>>xv$^B=s(d$y{s2WF5j!ez1b$@bnup`VeBlMWDJ)fo0(N7v->WuMu4c;p z*gYEXWVR0hg0FTnEk#PKdkyK(<=730^ip$MyrIiXN>gMDC^&Yg^icKfW5z=&$D;jYOnGdKFz*`15;ifrmY9r{Wm9^ZVrhng! zderC#tQ*26D*=LjNq7?$G!+>ODJxjXj@MI1D6C8BKa_WtYJ)52AUr-OA}|39a;Z{^ zS#mC|w+iL5lt@at1&E~%;Dynd*~OM!Rpjx7J-V|lmnWd;P{AlOi~clkb7v$!GfMG;+{awo*w0nhkG8NOh_+9q z86x^m6($6-_sSuRMG5@ywYSt?q(r2F+9ihgLWSv8UMKNUl)IzasF}y2dfjashpzde znxR;}lzQNKgK|XdSBg%-n_9w#9zsg{2J!aFy9QlFg^inWqgkU)lF2 z3|^8m!||iPcRh82?m7s{(bBFS^;rbV#DBi-;Bix)jVhpA^`Qyf(@?N)4X$4PV^QK4 zo>Ph3&w*7WEy5Thnf6;n3Q-TMN${!A@p42Kx0jqH&G?r3BJ+I_`J9vT4;L^-2sgv5 z_GEnK4!yJ9T4Y}Fnfk9>{R%miu>2!M$yCKd`A2tGEwj#;+g>QLI6$Q2E8^(5)kfYu z!yWXYKikSF-OxYZ9y5Fo?2|XVj$NKdMaLp;_|-(?a<0SFG`G`ru2LX_^Gx?YKEPZa2y@7WtiE)WafsPTFsg zBI~>WV>&G?7Uo`Hv+%*9G*gffm=z12^0Jn z=*-AT7t`GK1rSe+?$~Z@YcnC=)`IZ`LdryOo}O?XrEa#im5eBur5xDj@Yv^HK{40|~_}Q41jDFGYX03IY$O zaatF=oiw{BaOwq%|Am!y!XNRk6N06kWABErTT8AIbFgk4E&jr>97*KbHcZR!bQASr zr~1}aYx4V@U;aoXqVgm<)dt+&R&dwb(TERr4?L^=k$w=7C%vII_;TjQyOTcN2L}11 zL7%f9??LE%ET#I8AM;TLOeL?S4%va=99}Y7<`oPqmuPoj(9QE=jiyd8{ zs-iv;`}QcCPpd%PuxBK(_9#aTee~_jQLaRPf%fyB(RXJ@7w!5&T(J7s2j-vo zs#=A5Nj+n^Qa=lDk%jts>f?pRKMRfe3k|A!#*1J6{AhvxXw<1bQU3O4k)75@i=l|>ut+NYc|q0MPkm0 zCg(sc{N|0(3T+R|^UZP!Hqp-Hk9bv~salV)C-Bhx;)$ki_YCMNOpB~yA56abjM^>y zn^!37q062-qubSW48*lNJ?1jYm&)(0t0I3}oc7Nu`|ecrR}A!a4?{*$H3Kdt7I!;* z=4XNWg0|}Sk2rj-GP`j84>9gh2K$9X^7M!^)!uHgn@U zLBZn1vr9@eis6*q43?QMP^EodQm5BCt*A!GdLwGuQNBUa&eUO-IwPB|{!rpm4(z#4 zF3I=GjmbiUd?nIDAw?&u>j$I=Am%4N-;(M2UY-`a0gYuhNL5Whil)oNc9A-5CVDtl zSYtQ7-{hJ0WA?dXWiEAoNyu`qBk`*omqBwU>kn5^dEY{nZ6B3|~*y7{s-+04;jeQ##9&Ri2h!q2U|u z{A{urQ&k$QwPVF{KGmgNRi4zp^Z3sB^iWjQ=RB?5Cno1JQv+31)n@#>9$#mdk8am| z{o}M9X>xVBSgqE+d@toQ%lz7URsDw6{>$0(g_D8m#$WyWKIi9)AgY>XO6>zb7E|sB z3q>B;78gSaRtBItsEsEoGR#Dpg=tWtL&*7is1ECLsY}f@CiBpMo6AHSlDVzsV|GB< zyOqAQl;U==AKC%yy$WZ9_3HkekbRy-6{7o2+jI}%V8eAoEXk|O^>XYbiF9t>r(L7n z668s&zAx`bf4pJXdZ^R9yh+uq-2YVeP$yn`1MYe@K>y)l>t@?3@{MGlbribvq2kWv z!8`3Y{?e84&ad0tIG;u?KYPb@WPSZKK#W1}M@*9GHHYV?y<69B*DucP=sxZKVqJS$ z-YOB#`JIf*ROE-h1(@OSuc#{& z?qXrsZCR1g*e2Qaa;iEpQ{B+R=c6hnoiIT}xlg9R+&9rlAdk`KI0^feXbk4?prHoo zG`qY%fRM2R=PCegmwp1sJtqmsGkl|?YjQ~hqwi`95dnb@$i7^(wb?OQ>;RY@(ni4S zW6|-#G#PmYVaLF25OTH@JzeU5TLqXV_}pJ}D<$|+#Gp%?eU+DdnaKQfme4|+Qs4}- zaV$Cs2TMP=MhChOI`FUq=k5Bd}++zg-O)9D{z3eXT$4sT2ZCu?Hx$1TZcI z$oU4-#vqn6$mX$rV0OU&fNI?rw2Xg5B^Q)I4|fObpR5PZbnT)&)w0LpQctDmZOy!Rcr=VsGa>eXgv2-=tXFQ7N=<=B_ z^#{iUK?)3(8R?8ZNXXg(3n6BDZvKXT0JR#hz=Q$XxG6f1=a=2(o)6Y zfn_D&7aq9RVMxwS03E6)l5XJ*V*8^B+Jk-O`n zrwy6Mk_`!?<1Aox0F~2<>4yV!IwvJK#uH*dDZ)>H^8-;eXzNf%tu_;iVfwqbfqJ}D zol6Xpq@17#n)?gz^nj`w6tcktp9dj+0ARsQ)CfLY&D|23nK(a`SOrZaPa&gMO^oV_ z=zScV(4qq6NCGbfD5MB8bOQ^?*Q{>?Xkn^XYJMAb@QbMYH8&)8Y`A3%V7_G@1qbP1 zLwmg9N&(*le(GJ|nr&7Jxo>bn#baiUG=wi|9P2kf1Se%c!quomg_EPfsWjhXU#=zV z5PX?zZ1yFKJsNlHNO67OabA9Q7i8jnSyGlMs&F^9sIG}JLTK6%-Z>v$|xYX&TX zhzTKw?6LcY4IxQ*c#s-Ujiq|PDMykpxA+3H2u6n!{K<#?XF3jJT zAbS^&O7}~9se0)byD2?&Ou%={?$GrwRHyNwg~z~rp-j{b6WM4>^lkPya(E8rd$s{{&LwP4M{*9*HEA1f@5Vz`#SUEL zgl%Wgj|y|e3v+6n$itMs@pzI4xk@$Bc~Y zabf*Sy8Tj5Jy*;};MTIRL*o-f$WkxHhel7<%zb5n(Wa zUI5JJ37%8-xL4bGPo)5dw|S%LbVpdxf+{-K7WT3a(Pvz@mPD<1t(a(Tm4aPwAU=Fx zDvQOhXz1SpX&q1%OrVD)80SH(14Fch2wj^exg%#KjRHUr^Cz-iI<|v+3fFQfk|h&+ zYzfmpli8#=&*8=M?2_`RW%)ao;waT>RUr)2B zxE2N!ELHrFBJbb_@?EHch?SsFJgU7!%Y?pS4bUi4Idw;EW4SVyZ*`Vld-@7^^@?U~ zit*0q#m5-_E=3~6UN?KDO8@(3^b)pZIsBtrH8iHWnfzL!2X(VCaG8&?QI(4ACj8U| zkt$U}zI3arpvE}iGv)Ws_Wso=NKuX@)T%D*M=3H(qc+gB268{QKD<^ehPI`~)}9m4 zxkgnMi@GwB*<>Ml3KknBaujO-f2joK)jS z{b!L|N#sg3e*}P?Z*{^;49w4{#qM#;@&R}BHJx=ar?d^=VZpr8&}|~h+JU-x8@Y?E zxRS}*)O_Xb0Tsa7f*K>#B60iQa>1@G2X!s5n3{PGM6_-cE2~MUNvl_;5*{DIQeSVQE`KexUB}+SD*Mp1An!;%wJrR3XXz`yoYE&+E0KCBG!i-O(ch85zt{_qak=(hM=?4+YZTWd68-CSXFFYWDwwx zulcdVBU9-$AVBE_ET43^=6tjjX!qnW%XtM%x_ikRz)`rSof?T(f1 zjyLU2N%T%Es!2}kPMhm~_q)64nP-M{Pqt}KuBNf#i=M*zo}#&);@>@`ti9#Zy`NFN z1*W}ej@QXKF{J^$$Ll*Q9@l6^%`_bq4|XAZGgd@p1E-VS&5S<`%c_#y|{;w==^-lI8?EIN4f zb3jF@&xWI(rey%OG+@{_DA3Zu$`7144oSB6;Y6y4j=-~s&L^||s0IsabhYrZ_<;BD z`pBJ}5P|;tsTa2h=0497OECo}H(eMJBDxX~w_>a=mw`Em0<;}&ca zRx%SdW)qKJPXPCs;Re7Q^`PA!gT$pP-#|))vEDaG;o`I9GTBfd_n6q?Y@zjFb2gM0yI-$}x4@+4WZlcR6 zFwTFbj}-IgiIatFChC7?%4KFho6T0G)7-~FACyADnNV=c?EPl)>VAXT2B5J4XqB0> zxDTy21MKiXrxRdn0X!H&vtWfYKg})cLkG+N6H@c6AuuP%KDW|Oe%}RZbTAJUnQtrmp~Z;`vN<7OCz9esi{{J;fL(gPXa^#$7xj!qo?IVfBo+&r`Y_T z26{v7wJU*8o0i$p-IYg6Gsf3%+X}B4w5-v{u2@Iu+7efd%T^s4b)6gOT`q6XK$n~b z7#RP~J#gMYj?caL%fKi*Pukr;-Jc&NIjukTT?re|O&`X*n;%D;Z#WKbF!CUj*U>@L zm@(Fg#9~8)-RAx8TOSs50x_3c(>J*TIf5LGBIa?C0}Q6ldPM`1+3y&u&1t8dhDv;J zc^Hm@1$3FVZsx$`S8c|MDBVUp$6GTXbzw_?e(uX2TjzCMAw;>I%)I*^n?&(?j=7Gk z?CxUJeOvY=DZSm51?{GHd*=7|y2^KV2DC{+dsO86-_5m;_t@io_BR6dFm4og2KIM9 z?@Nx%eH)-L5ITq>KY+yTdpjZi)vmwso$NmG2*W|vq}Sj~v(G@wMn!vtM8mO9!=-bt zU+X|>WUjkW&&<@wXhvtDQSdLxe4?NRK*|`PsA$QG54>CtdPn9kgFhbA9Z|@2leAzhk@!gjx>$9=n_R9CXgQqaIA~%qFy=a^vnDZFF)ku z_^JB`?7V;c?9oxxYb{sLpIp#ZCii}R-(TWXw9cmV%^xwKKff^4Cm67Pa6co#iwIUe`0#;a|+dh^m+w z{+2WA;bD^wuqWi+)qz@52MA-N%;7}n-Nn%29&rGL|u>*z3+aE(Tu)0F-A zsi<^hN~0pEn ztP@!U9AaK za=K{O+jInSX+;Gj>gDvr37ItpT)MZe`PRg4p)KXd+NE@v*MIxAAe$FU38Q>%l*Tf2 z2^~TFVk!DpCHz#h$;W0%h;WsBW>x&h zwLSC3*9q@>Lv}1pnpy7P)~*>5Kc{>td?NPZ+kr*2BmHyho$6Ve{&bl)1NO8>b}`aw z?=K6`d3Hq2pPdLu>?D#pWU(eqQ8K9?q-)CUHy|vB_Tt*5$U_D@O^b=tJ<+oPqw_rX zupuhWr{~r`pY5?LJy+>>2YVf^S%(Q!n_4U8Z;s#7jMlyRDrO)p1$FtbvDxhxYMY^; zD%$NsNy&-wj~;30mb|sxkfyt^Je*f>Kj{cUE}Zq-r+kpzoiz)PHkaoX;e}}^iYU<= z+LU3#Zab=_^`YEir2HekDN8bB`ss3&J%fm5(fS{SLOK7{u1|XDy%qoQ_)Z9WBv!v% z{aOj61mWBGwOr#y6Xd3*$fBrQUtBT3hrBsyQ=uikSfqDLXlV?F^c~8+sU!1iwL<6a z-IYU~f3@pz3M48-{2+&l)G|)xO5m*#I>v<0dKxzxZqaFqdpc-emw<}ttG!^+9;=hx zeXM=Y@KNRXHA=e9`!!>$x8xo?z1Yfj>c&>sBGrfRf_HwE$y1q?l|=f~Ni=hFTo{xA7{-5fuo**0rj9*;0@+6k;? zd2uePG82(u|D4<6R9}o(2i%mf41A{kwIH zJ4+>n>As}M zMEgg%BJ-#AVI=R%v~~rSwSuc3s~Hjuq>z_=9U_bF@L87)Qh3^bhI+a>RWClfHt#%u zCU>ser|`7+Sf}|}x1K~Htta&21G7dYG*-f;opF+OT&&^oMZ2CfXVRU`d(p1XspF{c z?GdAt@wma(InqVJ!6@T7UOnO9Ir&iK(2djIIVXcH)5U> zqg7&$o1C5yybw+!%T%j*RC=dPcb$AXg@#Jsz1-)u`I@muHt6$w;1x;sHRVUUm5kd% z4}af#XOjeY{@hn_0$;arB^|6us>BTL1m7k1>9B^vuWYg#O8n60c-ipdAsLTq(($E$ zH--1cFQo-DlLVWe`du08gCa+Q$cm$UvMl9}Ae=Hl)q&81{0zCNX6%$bL7Gi4gwm|$ z>wA4mG~Lo-Goc#F{IbJW@V7s`S54dd5WtuE_dI;7mHdVW__dUc6@xX+S88XukgXLs zv$_`}gA0GCu_Bjd4IjWugS#ay38p^R>+p{diF_^?5;J22@cB^P2ez$s4#w&hrm3Sd zM6*+G6QH+u%2*tyERbvY@dAz8oa< zM!Y*X&K!HGN58V1g@tb_6sM-{uTO?FU4}C_g%&*Y=K&&OP9jmd#u7zyUDNLa^vb|M;KXNCPwtQC8&c#kg8L&;G`c~yw|IQ|BS zZ&#V2+=BMHcNlW6DEDpQ&~V!`20qR15J|#!u6v<`irugo8cT%yx?=z>G$uB`h+RJT z;+3dv16JM88*R+&hV@76C56~qgcD9c{N%3M~joFp>NF(UM z!(%2?o5%7+sLL1YS-kUPvR+gF{)@r71%}+Dh6M7BS5QOXXU}t;o$?#m+o=!#Y7aVq zc5kHDun^_{BsEk1B|e`SGK7d5y+%HB3HVNF0XM99Mpxw$yPRq%FUMEJN+Gf%%W6gA z5S7Mt-IZ`VZTW6yaywRjJN!Jr^3vpq)2%Aks4rDytly?Ob;2|0-bk;eg_ht`~EX-lzLR#;ZE%WI2i8ECDSTRrB2fk)G= z8ypD4@t#LtlarWx9jw0DlyONq#Ezt{S@|p0MkcyEFus?V1{3GfR-jSzL{~4~HqmJ; zRh9Fj-b=GE~LLS()q+GU_z)F>`g(=)8NZ*^5$Tx0Ohxk=cs- zuSU%&dfd>lVmxxNMT-57YAIY%y1*=dh( zOJorU>a&q7Fu8v9@?aV#gOMDF^G}3UJHg}pDjr_WK5jg=yd>IDdBf@_AD03v#LUiS zI7c@87VhN(2HvsQ)JQlp9fYi$@N&u_Q#wWbl#L?vS4NQ54rF!t$_NgRy)29@(=Z#= z>hP5N`#VpBwhlUYqC$L44FZ9hT`MwP4fg|E?Tr%?f!lXVPO(vMY7|%wPbm2iI{4#m zd88@dnIIOh?_^wMdMhgtn-r%jLDq!8 zYqgN{Z$UInGMdOB#OG#&etg1gCAn~*GoP%pDt2|0;<0du3M|;i1+tJu`-Ao~f-lH< zh!P?gvQig>EQCJr3UtIZKEsjI--?T#72^P5Pws@Ae#tO1g>xO8=^3&`Cvk5n!4HS zR_ZI-MnmQ(3Udiz%7!@#hbV*uN{$7+I0?43Ba^PDkzArotOIB-W&wh%yw{Fp_8$tW=&k#x zA5&ygf?q+Bx%5^?1b8P?zLXAeEbXmZ?Xq@hH5(PrAW%kN3(=?512~OcDaod0-!}ce zHchB$4b)IV#pooUJFV|tbD(n#Bt}7_Z7b-HQE*s6Sj+DSCbyzwslF=j-Z477gHf>e zRCnEH4JTr-w+p2@fVcYAn+XeiaSi6i&P?hrZ6C?LR+SxId~2Zf`~s0RIN}4{$0)$8 zloB9(|HY{5TnI5gXaF_N?SYMt!!<=NoB-lv-6Zz zQ>oHbmfX1=v4~eXjVIcx^%QHVl=niEGj=FUH`|U;p?^%#zM2AY;K;v%_|>$26GH!+ zAxbR^9S9WujV?5l=-&{+aUOs5cLd=t1jKRzachPu=u_V9!lA`NPZcAX4m-4N>Voii zy)H`o3}41T-SurvUmWEden!I%7EHrY;%5&jbg$@<*3Ipp;iAw0EI=0iqoC zK)U&f?R?WAYbGNjjPQE`ZfBCDMC7Q5*eD>W@a$Y$#OWU5#pvrh14%AWL$6SW`~b_R0cKUsd z%KItJ_l@WD4PEY=%fOTa#|)tpmO>LrCsEe(9Xb~Jj}s=;=qKdnC+x-G;G1Ixe*)}y z#*O%3Mz6=s>0z?a$s`Nhm7UQ`76IC?_5Fbfm0g2pyA(z)fo88KBX9{`KU=gKf{cs| z{1f!mJp*5jPx!e^;KxHqzK?`MD~)1cc=}C0(M>;k_L6YubfU2D+{eH+WYY#>IvxtA zB?Pv`Nv-HjC-;Yd?7&GvQoh1cAL1XRnEBRzo&FHsm`*=)9jJRRRC^tmNk;1@iOs|c z`DbfASW%pD&JWC$G0ulR5Z&#`s5H)KHxB;<{v;#~BnSEdbr0;o>3?Rd(6hzfDurm7 z2g1IU2~$;2kV#QSn}h$CoLRh+2`(Ed*kzQxYgD;wVuChlZuh$*V_FLJMIh$(9ZkdM z{gGi8*mDl=l>Wfz0(;IqcS;x792`tAY5>dzdCXkK$(J^e`A;Zm=X(#g=O1Ov3m7FrL`L+4v zc1H7Q^SyCKiQ%Y+VeuP*6*jR{HH$E*;zM+Sl1@6G~`=rt1bUlN2*M(2o&F@%7ra&BeBj% zc>}>GNVq~&s4N3qaUp)s(Nt}ZBFGx4em!Kp7O8QJ)XGI_?;&-H>9%7_Ki{j910;TN|EDTO2K(YSKQVG65 zgeEMQ^Log0CIC7wZt4>e>4F+NpTS6&hf2WZ)@2HtSDiy_PqRZ7Bc|?qHmtcy}Ol`9`pU|}9s_By<*&6#?iiI6? zgkOkV2-rSF7WPqlUhwt0AJNVj;t+el+^B<&EuXUmju^Tj|M9`tXiN&G*Nnm;$s zkN3`wzWw>JcK&1I>~Q_;aP{~1<&(pWUk7U!O!I#;ny0(-M|;aZc9#x!h-cdqhu;Bsjg$Bs&!vQ^S;EJX!ciT0-jNv zt|9*~*$l;M8C`fytg^1GqPDdBf0NA%uPOF_?KLm3rjE^jVa=N`5~$_>M`|+AWo{+a z_^w3x)@GLdOKP?Rs{aqEncJT#;l5o27nmP-kEK#a{v$Qx1k8Fq^AA77*h-{_37hJv z=~q0N@2UJaSzXOfP2(qQG%?}V)6}r=T;3n4}@HL!t zr70nJIxv?qmXB$c_%gyx$4bg8-@^OcCUW~KQ&)+`0u_(^kjPtrI|cho$RinB$#H8@ z;UjB2yPTgXcZR~G<&pZlB7c{mZC;N4x?+~%HN?>ed48YG)i|6UcYh2`w**nH5KcFP{RMqMc+e@$ zIIPkUVxJ@5DB%ZWc$8@kc(`OG=G%M}*wCh}}@?n2=&_if+~Rli(K(ByoTr zHLfxgi*9*gE!P2i3Fk$%z%ftD_2RE6Yzf7$nu0&^522HYwKy)6kTEWrsM(3jf(Hu3 zB!N$>aIf6_vY4ysW7rD<+7XK1ifHYT11jaA_kpsK^^Z@zy8Xb#@)r#(T)-m^#ixoO zKUz+?Xg_z0YzW!&p|5W)dlX@ZzuVz%Z5lv&1V%9NA{wd6x3=GPU5@9j{My4^EZ-b- zkz+#g)E{8cckA~Dr2QYM=TOV!<5Ek?(neURKFtobBYtWOHIZ+56Y2pTZ@SW1aw)<{ z1N_z)ww~kDP>!JGtC$Mq*+h>)$7-#yXj3ZgTM|(bYL=Cd@!i-@%n77=LIwGX8ZI_9 zR@hChcgQ=I`V#!(&>+e()h-t)qP=L36zcJB}D7DEpRDx2CF*^?F_ptq+$FEM!NTE!W~2`a+;`A7~s@ zRlYqU;DV9X8hfp^zS%;Y7J4kpFPFl*A1GdGuwWYnMvz076h-F>?#V410y27~jP!J{ zTG*o)!spdsis_~2%!fz~wSXtA`tM`($mM;1x7weubcw?3yQF4DUb5W^k&rT=0o~5l zH9FPg*laTy`9$c9&Ay2tpqJh{KF*`$=Ij*Yd|K$9=LXox6J&jrc0~XEva{IUFz4Dp~zy7JdOEn z<6jql-o+P-Hs|+V{;DIQOT0QY77pM3s^8Qqc{$m;a9sPV;UMy_?(FYnp=842yhS)-x63m03~amsxTaZ!tB!n zBfHYu;HKZ43X!F0H#S*@1BR{@JS=z71)aqnEBc4=q1Z1i0M!s<@&rM0rzdV;EChP>y4=7nLjjSh((#VKZwDnkERy zYtEkPlGstQUDmN}jKno@>nP11T2-CtH|L3}lQn~hMKKwQHg3sLr!&zs-z%*_I*?N0 zfJA9RlIC^_N2YH(4>w06o7>swuD`p&I_n^-`5B+P$qBpd`~p*z zOgVTL(N;ZvkI_b|P2tvxjdG0a*~<>Fno9UPim0TY!FK<~B{4wFk^U#7cjs{z z&VmEsea)UHR4?)dPC5l=_u*cnewQ&gD%RjOUz`tFyY!XVKDv~dgspq3(X!g#{ixl; z&?Lu<&Am%$v0vMk`>nnd)IX+v!k{Ry7I&%H>~c))qv5L*8=+?ID|y%ZKY zoigu0I>o0oOVS$wO{4j3w>zr-iY{n3Q`?)~)N)cqA3{TT+XSKriUGw&cDc?SfeDh< zj(px)g$gzlAAn#zOTUngfUh&pqG1yue~VsUfrzc*rR2?zW6aDpS(O=Kk^%Qc?AcwE zoH4)aZ$6AeKl%G3gQ{UuMdxfJ_3u%>PQ$k0;Mqjo-=C$?4Li0v=QFc^k8A#snpMhV ztWCeR_x*2p69)+=5|{pJ$CuEqZ?v6ui~H>7>HOI?A)QSPHXc_G{@Hs)Iww*!kxn{w z{vM{1elNB7(p~-zQ>`J<9=r+sZ7oMK>f&TM8SJ=yJov`>ghcw?`Q|hUU5>*a@xCbm zy?Ji|-|O_zV~0xMee82R#L9*5snCj*`VbD_B>?iQlYW+fE@OZ5eh9CJ1Jf`)e47X` z(!jjQ6vWDWSox3(!b}`?c({>YG&__&6LjGTu_55?UwFk6{Lb?L)#Lzm7+lRLK#?y1 ztBUKTpyhLc@Cjo%31s91^9=)9u>;t904a6?EMW0m$^JZ>KAM|&9ax}l4S+QQ%S#04 zHN#Z%gAz0FKZ4&_dr>a{ekX=_aPphqlffF_gYkUGpDKO_op=Y*30}g5O!kEP)`8)R zA+Sl8xnY|QUna=Y6M!3?C4;8NMPfPF-+}#6WFR|!s0e>l znMGVzj<2Ox0=x`eVgc8~#j3k%@?^3=$t@(PAsfR;HUjXQ58%L~*0EGO&8VNxsN+DG zE58!f6C9X)6YWmnCqvS}jew=1^ih!0S_Jo>A0Fm$qK)eeb&KI`z zT{PQ5iwI)9;tK*(LwaH`xy?zPUnMTKBoxAFrVMUVaG>680CSQcFd0<=z`I0*P2s5$ z2xPUwm>(9HdVm}}45}ew4u+7IpTGP1AT2Qkw4ai4QMsDG4?g4ve%fEW3OYF>Q$f^$ zi<3Q;-C>9f^A=A(IGjW{eY`R%_}A(g5f4HM=jf~FpmjAnM&%N@xb$1o^$IQan<1{t znAHq;=n&*)DKfzYmcovSB}blEAR;Z)Th-DGAE%JL07Nb!mHExzUxFW}=#2yb-eeh& z7LY@{l6sHCT@oES*cG*Ek^eWD7tqa7R?i7SV0%D1O$1mZhX^U}B z6u*O_p|c|T%!1)~5m;Ng96KzQfZETHZyLftW8jnQRHo#ZpWi9Lu56W3kA>9%0uJ<| z@FUosP{hm2>t+bCM1jp5edYcin+> zSVC5JrC%x?6C>B!92>0<&`qR+hmlmP>dpG7ZoMmX&x*HdvnhPv-3bE!fMZI8$+qoN zN+~O3IAvp7Kv!aT!d_;8?f^)J0&&9F+`Lp>C&eD528s(koLFfV`YD>jONBovYB7IR&5nDz@kmlKKH9(&GHZ7NlWwdb6>;WvSt|meQ z_$38oy6A|zTrLF(KH%hnzWt){wgMst=b&NR@SrBrCHuqOP_%5N*mp#d1+1?bb8La> zB2wleG*KYr4v4CgQ0OrU`f`9dI6z)wt`ypSUX1^JNsIhbx8}DA&G?usp7Z9b98!xD91N^RfD3Z)02OZ0O2m_M|3+1V z8dXbMtDBqnQ5ezRj6c7$u%_MTKpF9(FpAjLa1cgN6QbJO3KoG$f*{;G{!ETvcT&EZ zR(|z?k`aYr7UfC%+~^unz!L zTZUR7p*xTOC%H6G$8>sEcJ{7!4&nd<%~o#^N7>D^H3}oS{2q>BXY$i(2kB?0TEb?x)f>wE{>mrarsR!$?TwVgwGn}fWeoiq9O$GWST0C#az{AQg^jY6 z@n;NX(;sC|iAg%R$*9Nq;i6U4KYX1V5lI3>p$?_@!t7>4!;73 zt)L$wy~vos=0kolFShe59;6y+b2LO2_=)E*gV|ez z)8~K+?l%6Ko@~Hz!a=0h^my37xS4!OYLi8*EgXm*7JeQv4b#nO_M0FQJ~>|d1W>aK zG*6fEB1{>JqQS#(;t+&<7(`-Mij6c>ycj|`XdTR$Nn~TV zo!9m0vr;5GEOMCt>?-hqR9d2c$W+S3f7@0K;yNmk4h%g(H-J7R(mFwP$$zpVXr-<+ zh2A6{B*UoD1|PD?zf;XO%z1i3c=}pvCFbqFGp96sL9l%4WUiQ#0am|o@^CGv&5N3L zFgm`X*+;Q;D#9+lVzg3}qzv)$8RR}_;18;S#6~;~Cr$@Wgn4src%W$%7^w#wGmoSg zWdXbNbV$q0r%$7>VPT>>I9(6`H+Ngze7A3*_Pc+X2qOBQFMA|_O`KZIQ7dZ09($(n zPzwa~aM*homeGu==wr+rg0*Ip9&moXBfFr6Ubngqh{nQVEfDKM)bwqr4IDfckB+XF zI=~{R=P<#fmUO06n1>0V8&w3BTQhK4b4zF^T5Kf_tSQMcF4M^DMJ!IvvFDa$q>dns zVpdElo}N8kDp=Si4heJKE})B1d%{`{wv=Q8Ay=_fM{}HWFD`)kRAbuMpV!ht=4;Q4 zw;(ZFDaBi=-`yj5h-RKd@bHew-cBFSuIc#B+;t{?a)d9tz8~_H=;v#O1fw&fj;Hr~ zsONWfoN0OCwB`e^JL~|nQ^VSjX!lCk??xDMZvW4Mz*YuIfV=OUexEi5b1DX`zcW%K zP(rbW`k}*7E-R=^W3nhhRm~at<$Rytb3^Ahms54y>&!(%aPIy1@cO0ms>pa6A^tS z&b*LB_N&-Xot<3!y`h|AyZqwLn_=#y>rW>GZXHA(EoJ|B{Rm8d7iKJbdCn4@@+<4f zz6Zi(_<7SW@5Ns}q+j?eCw_A86mOgaMFS7soP;g5lgFHdKRtO#IteR@jk$4}_~z7a z@F=FrTIHb*O6HjsJT7E(Z^;r!V^cwWw?x6lX5 zVz6UW{;2<*jJkD3XgRM;Eqe7Mdy#Kwa|$ODZ1+NH{`m`KHFD|T0&^rQ8H}w+x=biv z?o)I=u<1z~Y-Hsd3^5sHEjN(RP1pG|``@d) zHDXP^M^!vP}BMnQHljqDGJL$8Er~ihU~z+l$5;L zrSeE>@;!O9_-d&F)m?~);;Ix-rbw&vZ>g!o_%I-*cE>8aOqt~)=YcZY^VKqyD{mm8 zsvN=G<*HoKisiSKVr|OR*qlJT3cPvQdhKg|A4N5UG~(SZq-GI8QMi-4LNmQs^rn{B z-B?1k9p_t1Ey)f2P2q(ICRIAAU#p|FnG|pRIUEnf+s_5Ukog0FY&SCeOxQAl`T{ghRPcj#=@!@%(s_Mq$R zG*g+vRmsb9b1=ncmXR%ATf+luH#x%vw`E|+7`e+#NQ}8PlJ$;wP>K{J_kbyra6|Oe zGN7tP{PFwlRS*)7KI05eh>+b3XYzS0rGY}+&PT?Q9?I8d2$xFK*nf&_<3#xv=BnBH zft1-lCsiw_ia`SYALi~es0nw`*LHveLJz%b=paRU6EF$AcL=>m?+79&ND3jLhh78( z1VIHUqM{T5=}o#Iy-5)f1QZm_%YUuC)?WL}S^MlW=gT{jubIgVL&`J1`+Ago{fjy% zw~{#~9{ti~^B3v=QoOR%wf2VO685F8nEY3=xXch!XpekL3$*z@Gfz=FN7cf+cLO)? zZV!B~Z4K`%y|f+nSm3Rs`+GCxGy@dB`00`_#{VkM2!Ml&oHGj zqv4`|#OtUgcxs=t9kfJkja<7|zxkkQ=^C5DgTUS8r(2g)>FTQjcclmS+hf)sv+a#f z92oRzUX0FqpkG_{^b$(Alafx0xP=kUtbg7T;4OKD=>$6%`rCMDD27 zD5LORtcuK2K-luRI_6QbYJ*lhtEvIsi9yL~2x{rAZ(zz0pV1QSX-b$iu>2-+NA0zx zxQ!~LTJdI1-9|cpIJW6{)ib-^bL~>tYaW~2lAThi8Exod#eni{0n=ilyy&NFtC4#H+{Lv=`q<`oru(IY zs9n#Jli>l4O@sHbYeypK78#P!T5?S7p7+Oqj9gZp1M5(hGR8&l)WX1Mp*AxwZT!U< z!XQrtb(UbyaP=K>q{;iBY+ z!y++~+`Yx^RF)!{)nOPzCL%kV#v6piNW>X;g-NymLHn`Q>l>-&)rQ(tlBRmj9u~D- zTa=Gw$K}$s8XZiArM@d_R!zRJxI4qr5|-KP2Q@Q!w!*&&T|CZ_w_&0*Zc{15(SW z;VKDqA=X+269szrYAzrA^QRbia)OMVW=a|5QM`nAtw9*C!q@e10GaOx5>YMxOR#TtYd6D|6RwQyK`_wYuJfN{o2L|%Dz0NS;lvRu8>w=W+HfG-l^`?R-$yIE}uuk z4NFuVpe`Fy5ojZFWqp9M>+0LNko)WZ&>6ITDVJ*`pTKMeREgaF=G(r&+8j#5+uT4~ zHu@_UZ5|12p0g=U+sgpIuav&Mx}v9lm#BFYA^jGlCwGO(b40U(gDX-B9-6x661VX& zO89EMF#leGIXURjZhXGRP3V;GrU(Tr$-+RrHGY`SB)yw?n)~}Y_aCBlVtB+W zt7@^kFU=*=!%q@~TKCVz-{Wf>c_T^AS|#nokFoC}-`VM_OHolt&z_e>{(Q7UH^89F zlYSW)*u#astS_wDeVdElZ$=irWnvkUHGP+bw+e6YIVdv>E7q)qd%FQk(j*aCZi4s4 zwmyH_dT6?2t;z5C7IKSg{_`}=WzC9ZlRidF3`@|$*#W#`tekaFH2@W=a| zSix7aZ<^p^`)ad!;2%%nA33^RAZ0CLzjG`NPM>1?7Aq{sT&`!ZI$WRfyZ*-hA*LSy zkYuu$ync=xx0F~M?Q)}nDx+qRHb&TNNyKNMiaw!M{>4pmt5GhHr zykJo$?KCt6mO!CQ$2@mNJ5tbPyumex-kT-l)1V{Gf?-QYeZG z?z1K=M;ua?Wek=aD+u8QXQsTnxzVlct23^WpBHbS3^Q~>qvtZX)BDLs4#~~BvAIqJ zdlW_bK<_XT5QV0=W33z7fjMi*DV?h(+V>R65*j7JQWag2oDbqv^g>Zs72*)46lA@p z!&bx5txf1TCV#BJ4n(1)2(PaKxH1OFrB;lysq--^Z?DD|nj8yZP!w9_1?AS@7b!Y# zRXDD?jl{!r3c7RBq6zxe1bl`jR9%b2AfsQGcuA$+2s4XO9y1J2p?KPjDaoc88pg=v zn|zGHN;UU~s^&}i>MRO@ul8f!iI3_im`rJpyfg;WK?-+-hE-;@lfq1k#CWO{jQgz# zJrzTro$^6QF3x<+tvQU;7>2}KAl}SDCw8BjS8r^5@UVvP%;J5Mr&%bJQxZj%I}Bz+ zp>G}Lzf&0e=`<>hLLW$$T;|lrb_0@PuxZEwd?J?N7T6&lr{ZR>Y5+GLF@^;MN#s zH!;SCnv^h&FYxCGR=+i_=~e0H;LHa(tn?+Vpu}e}GND*@MVc2e*zz*tU0E&p0!c?B z!mLBOe+4L^%PhTrlzwxJbm;|{)5}bmXkJY{v440?6a5mvG&P3+0=t#Uc$|rX`DRTnZVCyjk zQaKLtFXaT3kHNOKBNI+0oSwIGqO}MZEk?&8oUgF$lAx{R*i5hv*x1-Q)XOHU@@)#4 zag%~wsPDAX7iOrKWzzz=V+!`ixwZKanNE@6U7ab9zydV#gLdURmD3NJ)~INm3)6uI zD{O0$!F+E-o79>}vFC4qWBageFp749syHFz-OLHRBk5jX6`A*bQ>>X@1Rlj#Nk8YOjppSAC*t&lW@qm^BNwtns-N~dM&47M_N5?3 zF524fwWY$P%vE2XReuPt?4nb_pi&{rPWkuMt{CIe6Dkq@UWHG`B*umqN5W>I$4H6o zkAC)LUPG_XtC4)e3t@gh=XJ*1-}XWZPK~jIA{~>wMfEE*i-E6|`kd22WAvx{$KH1WC0Ljolw{udA7j}&cE zkDcgix37?oC(}>Xza$STs?$;|j~2|Q9N1vpI>uBM8;$Y>^%r;N6q3zn;wbP=MoNQj zi)b19$JbD7`tOAo=b98RU-FGN_Kp8B0S>^WwDZx;3xk!Vo&dopOg{NW1;`P4L#_lz zDz-tj+AQWYucr880%q%|IM?Mw*29I~EwVv>PT$zj_?XfKyqM`nM`6$~lzr(9M*@YJ z#zUTZm9Ly+Nv(sJLcnbWC*igij*3YjeO%@nlNDZmQ254 z!%nI0Y$t>?Z#d0vP{4+j545F`WTq3#?(%7Ml{g>k3IG6i_Y{BYlrrQXA*31~M+7p= zYOC=ARbW`tLJ9q{*BdIX4*IUw$N>;oLfi`ep1!x&_k?=~_<-tO6W(}bqdt|)aTAOV9w24YNU?S^zDSs$EJ2uhHxM;U{ zG!!Kc*-=a&B=D^|lLK_!@Np=72o#KN2dP=d2da2;MF|H&ceYDsODKgdF2PCG-NhVG zdPia7c;l^B62kvbd5fX!y4F@poswfK`Ku{Io2l}Z2q8#+j5*L=W-A1Rj|1mAH>QWG zq$%|Z8*+kg&+b<2Cpd=oTXKFz{h_=!O9ead%U4;$V*oCk;G0U|5G3WD4RW`RZLfW* zu=etSKj5`^F*QKo9b&*Uh6D#rutPHlmAeylN_9&HIJr+C2~bi=>sA9+fETWGq{?2! zJ@}=OIbbhC3WRXvEn0I8OpGkz>Df5WQEeucRXmtfBX+V27|(D%mv29a{7d*fXVH=gH^!xl=$d=;F0%1GI(iHTTEM@%1Ona_QO7EX@6uN z@7+tO20l#T45QYm2AYH7X7RS6A@MRk6juo$uux}+*QDu^#NBG@)0}&!Kzcjy{!-{| z0RDDE+XZkVv+Vo|uWOJGqu zFh3PloH-5%J4)7Hs@JJjTHXM_D4mD_P&05FB~@hqj>ap3=KF8*JeX%Y>hQsKTK@K&d&4dlU%2L#Q&6F^RUrVvmDSWx z-%7V1O{;F0v8h5R&PoMmS9*k0!I5k`KuB|tQwPrE;+|_{w{9eXrX~?B8kIT5kI9!S zBK+{t+x7X75VK5myE*hU0JlS7XJ)gW_9=J1m=Gp( z3D{*Ym1tN`gGcr3tw&oY_E&pLL%`q3-IJ>i^_1Cam6HwfK$b+DSqJ(7zQ4eXU_Wp- ztyI4qFG4m(M#lLIJ;mn21y-S1b1T5QKTbSm=`Kf5k8Sp{v4>g6-{=yr^brtbbq0+}U=k-={41NAq zp)UBh+V{PWufj#aE7w$dU&KuyCV#8{Jl_5AJS6V$*AJPrzPif&Kbn8efBra9rX&3d z0>XV9<3QX|Pz?1I@OT_xLSQAZ3HB0-V{?e&Pxzon$b|=t%MH*Kcg}?KYu&j@avc+*MGF0%%uVGtWnZA0VS}oo#q2K%dUBm+UW-16 zotgW@9{p2QtPE#MU0s%V<&AF!LGGtmMTWzykd&kT9q~s6YkfV*_P#&GtIIt49^Wr7 zymRGAZJ34sliD{wpEx;n10-r+eB2#VT-kU+l%@DB_pY{+=9=U)T6e6zzy_p6^7+vI z9djtifIN+9#Nlr3)A!uKBrRpP`!1}@NxuqTQeN2iVzfc!{mozAIQqN>6+4>0p^W|& z9J#vIa@GBipp^zg@U=1ib=LS1{(?GX`L(CsM5{+fP3Zw6d-ciZTXy%Xf5jZ-LDakv7>jkWykl4dorWk*Yd*crW^O)vi?+k z?7GemTqSQOnQ)nNl3+)dJylIlu@B?m%$?Ms3Z~-cH2QsS-L`+XaAu-S(xenkVk^HDM?6BWs+MlO7vXx-_7?(}{^ z0*`Q~9#1g^@65q6W7|}}p1--hN`a6N^@M)CXIG~2oTrrNUmN*!z!QL>1}h6`b#&hZ2h$pMPcn0@y-Cq|_XI7a#rmX$2K7natbjzb>!Zvl;D zI^kV7ClAyBph#$?pzp4?C@+9Qua3s2WlCJ@K}n3hpv-D=G;_9iSa$!pwk!mWdKk`T z@?M9r3#NFlNm`hQRO?k`O3j_ppaSVBqc=@W3hOJe?u*PphWy6r8yxgZaJVg#PVv4_ zv5@e^d9y#n%|2Y9W=PaBoH-4Re0Rsf#NVXwj!hxppxSXU-4aK|;2FX2gx0TGp{d&D5~^{-#I{~s!vf&W_3bpH59Me}9z!{-0E zqWK>uG(CSyXkPxigl79c6Pk$sQ$pkNH}xF3U2V5jZTIPs(?+TJYL5C+lGy)6MKd;d zQPKPjKJWS8+UI|TH06o^8qz%MY=8CU#p_ppg)}dl>i*u+l>SRg^Q5}G`q9IGwlsGi zS3E2$e(<2UsHpJo@OfTd?)^;SziVl{3m@VV2&QS7f3-AmZ2yGM^HITnspoP3P|u@d zA|mgEMcfV!yVdC9`5zTcaJX+^n73cBr%#}V*I(+ni-+&u;d6UuPdf*X^8W~FT>ni- zlLozW5z?dz+{E*TB>l}kPt-EBz6fa$dVksH8d@gT;Kr)g4gSub|MxA8i1f983!h(v zG**6>L=^di{|ae#!2g~+=iUGsFLZ?UX#4#|p6kYebPE5KJpX%0W6kMb_5Q(slIK}h zY<>njo~&XL{wH~EI&BkriO;ov6^ih7C_ z-XZBH5N&yDjtkDn9DgC3vuZJDuL0JRGguVYjXb4(-@bu}kOrm{aIhVDA+Anj(8;ty zZmenb06r3P<(Q8>;g;WgcPdBb^oinhLCS@QT_$a>K$cWPNFaoX+67)F5b@v<#W?Bp zZi#~5#6&sM=F7EQjDqKp&e^hWMxOM-1^-9*yaK=B=T%kJ^O);OpLi zbDC!F!R|~jT}H$rqRnHt*%c(>N`8 za3RVbgE#C!t<1f2TQ%~g4}U=g7<4sHs6j_q zVnasj*IM-0O^EP_d9xtj{qcUPTk6EwYp=e%G*zNyeWjzN2aJU4nRUO^`SXY*Y5qp# zQsM^8YSPK#rL0%1#S(>7A3rffr0F)o)3Nd;EbDFU*(XK&{$vYyooAFWJdW-%;?X&? zJfGEd1=Gl~JnP4|g^TyHzaUaa&-Pobyn?)GZUsyY()BFv#}5j`f1i*C{b6|lzPMpb z$FXYm*U9Yl7n1NlZ-kW6nwJ+Lvkfe!kdG0i9tZVN913#B5eq(Qdf9#QyDLym=X%~10HK~% z&m2#-ACWS$m$!?V1-_hf?z0)q&(glPO53aI$=kaP`Y9uzIUGA;XLp}aN)l*%o8c=? z0PU<$@$_r&oe-g25(XQR2=%N`@-X(Z%SMPtM9~Son`e^)3>=M`XXc*wC?C6Omw0Ck z1p$*yQf_=LQied@#JkY#EM?bQF)L`sGY6{k87Jj4DUV{4&9lM0w^?=f`wugW&*zM% zqHW_UwGS8Mxf0Xu{eLCTt2BQM{Qs6bzdD%sQnSDI!0GSgxd>}~2h?H`;_=*x zxLq(%hCQYv6At)zQok#tC#yT2Rhzgb&m*bdsFEdee2z$O_kAkDQeNQkn5IEV_LK4O zMoKegMl|mR<9-pE+W-Mn*QP1rF>}n!CfS&Z6t05Z{C;Hz+L-ZL7~k(jWj!D}%Xswy zWGJ3tlx<-k8BRVYvAJC}m;lUsE!ZhUxB@EQGsl=78N|zf8h^V(QAeeoh)=954D|;@mU!RJmy?ZlD zn$bYmu|uW?MUenm(bU%HgM3MF7Ffg3S>2%W>kZy zaA&w9tVEL(K=~0ewRt_?Ao8*lq>@HIdmY18?*vqVAJvAf(K(Zxv(oEP#*9I%DA+f3 zp+Ne)5KP8~(UWJtBkcbuG2wD-#y9V1=u>#Q$WnwernIV^Isn$NM*kV@vQ0o{bFMHrcl3HDXLQ73}oc{4y&rGH1Bk9-Nf`)huM z;Z<{=$^OmzzZSNiZLw_E?*~3>S={&jak7${b^B}gl3M3&(_`n5=&FAq&(BxDX3bq3 zqX!As&Q~Gn&E29dY_t#{Gba`9;s;C^vVUzoqCcVkc|&UE{Z<|^lG*D46U}ddbQ|k@ zA5_Go(T5mh(OQ7%Oho{K0u3W)y(AiK^D=|pK9rYLu}bTGSeh;1Gj#_SHGtKV0SAx- zZbxiWx)P)z4+D6a$zQ+L7J`z|B2kpS%G9$wn8@cws2#4H;OMJ2DeR-(@hmpCNCwLg zORxxbhd6y@r{D-=KkvGM9{8i5+xOmU?T5*(Y6wVNVrsY(`}2O?m8%o<PZBG&{w3xd z#-Cpol}^j=I-k0yQ@7nl{Q7w0#lkp%{(e^`dEv9m5Aa+9Nz!|?=sKMcbDn;?q(TVO zR9?(+>DQlqTV|x6^UHsLT)zkWUWW6e4{AMKGcw~cK zjE+U5pARJ4C;C!e^pG7B)+ee?k7*LmLJL9Vkpo10F{P!DB`9qKG?HI9l0X#!_qjt? zcB?*=T8Pu67k~)gf`~?8#C;)eKG4HCt(5b^>S0to)sQuOgz7A;dxdka!I$F@3pfBv z>p{TV^g8)gdZ)LIq9F63*a#?E7wyflYDbQaHE57BVxcEN@L`-(jx7#ttZj zFq|er2H@Z0#~p@ICdMNOC`vJF_8;MmkOUxUoW2o-)k7zcJy#R-WnBRhY7q~G@qX0syc+{ycfC$KgVJQw{iN3e=H*eRk5XfZ{@G#bFB$K}w z>!*$c`Wv)<(-s2m05Gm5WmAF$;g))OSPoFCLz(mj@g%Yg|%1Ck5q6e-rjAW+VmtpvI zF%RxAJccpU$|O~Q>AsCIG<1j$A$^=xXwBU)w?rYYU){FWq1cQ{>(HlqkRb79h3&$3 z-s7jvdQKez7x>;UOVJ?UPGX|zwuR7+Wogc3)igu?_(I&ml_?oP~%b5GZ%$G zsNlXinT0Cw&wJLKu;;0{}Eyq5HK`Fk}9g?|m!- ziG@+ka*#hDO%(Fj#xDXQ8=^5EX4Dk@AQFBwi7{WL3o>Lt#Tm*l=nF|CGDi63 zSl*;>Wa9Y6e=*uFtl24~7{{%Cs=#($dMLvl&Yxuy36Zz21cyC{AZER`XL8>4D-?sk zNNa+46kQP!To6kC-5fm3MVmPWek{XS4J(0Pfi$==mXCou>Upl-q&sxW^;Nxr?n_?z zRB;>*yOAMt2}5(@TPgcIeZh)3@#7_OxG=U6c#&nC0vHF)!F9fc`{se87n zBbPJbMn{qXOMJGF`qc;|YoOx+lONJ4I6mJ3x<11|)@2m)`jZHdCat>`9P>>) zcOk}in@j^(>wzW7T@Pxssjel`9KyMH8~MzcVf9S`%w#XXhu1eDS5)u5KqN!R4HyK4 zAj2zcn}cTHmU^1c^?%*=klf&&%vudFyDiK6^pI;_RP#Rs@L+Q_84+CX zGH8=49$X)QM6`G?99{kdxpL=Mjl>bVu^jKU8MBi+b}c5)W>)XQ8LGEMa5y+HvpYdLeIWqjE*U4!E4(&GMvx;&SKgta5-&`` z@*S&_j^3WYNx)m6d*_`-eZzA+oUTIHxcg^z3yotpY}}Wvlk1`=Al`Ku0z8?rd16uo z*#z{wvDfjf=_SwLNrX~YhZ-@Azx#%MP9@8p2xV?UgL6x1NF+C!T=Sv_{#|ENFPcjm zJX2W0EEEN0U0k`v@jHeQZna^1@<*IV7N@@Q)`7>?EfDw4OHUyU^*p!l_T1#elaBh` z0?nL_sIrU)a#~p)NQAa540XjoUe^qPEQX`T<*%y`S9vuhIu4IIvG8-Uq@IOnh*fXA z1UJ`@aJP)irwreL(|HGqp_E3LEk;0F!@r(10hvY=+()mjildK)K;tF-ks~w~v5PY= zKF18l@V}=Gs~!fuXF$KF3G1+`2{H+Qt`!Mc_73~y3^~zCm5_~By{Lm2JzuHe&}7D8 zSlURD9fv{_-z%EpWqK*)n%UbXBo`;7e^1EpP0DFZDv+Efm0~aYkx8|-N%h4^&EJzS zz9~cyyO73Tcj*HV)}kQJ9|RCF3FTO5}21dBd*4L&3Cq>*vj6S zUG@qSpA_!&^+&kk2Ym~M8?{VXf`le#pSAh<<=pv>-!`?*Y@>i%?@WS!gv|`l2ftlh z7~@-9@tilv@R^VbejmHI6x$Ii>&W0y~hm&3Fde=aWn`MnIdw6b^SBl)P)6Q>p0o@KSh9&lQqwaSf3=cTuy z3TF+94_hF`iz_aQt4&#uKAbaC@N$05YN?H3hVGgV8;9j8CxIyGS0r$hwC07o(jopz z?%uje$+}wmx{<|#`k(c-TJoy^3W{-%?lX|CDMaRgJYoz0GqrUtg*bFTWJ<|9tDZ2~hs`9nX^JzVkrqwjT*=nyF* zh@XN-nH|Q+ZwFgjm{R!$Z{tWV%%P@KG13s{`fV(Ob%ZI4o92$)r5%;&ZDsgI)}QV7 z?pyh38i~QI&K(@3Rgp?eU)MPDtD0E`345zu1R$Xu5m}dH4k>yR~%B z!Vg9H{?h)sriI1m)>g?r(q`LxY~O)@e}CWnQyRyy%U5d9ekqP?sOBroeHViB904#8 zh~Q1shaXZ0>bZ-D8oMK9JKQI$09V$cC5zAU0aa{kr0#<+Q=dO%9nxg1exX046gcG2 zIppa*biZ}@P1=It{ZcP!)Uh4KEj8LrWyV0`dT55@lGR)`9^Jh9{)iF(O?%nYD~O!Ft>aGUL{A(-OhuMYta?tyGf(K#XuRXT`=)>YxpAD= zczmhnn?z@bGXD=H_>YObkY5QulvWx43Tc*qaJP>UHW~YR7u-)y+^(CvD3SMgaB2nm zBBhj;`bJ@L67pkGrvz~ zG3EFzg(jWPK5js}MEiA^%SA}T zQyB5u+{(D{BBW6lgKU|WfJDCoxvjTNwSnREl~xfe7T84Mgr{0P2Rxsq_>%gYMouk5 zV5|mPG@B%!msgGr-+fyt-Qs{n&2#Z@osMsA@n5NAQ517&0}su$5o#nly@9D3yg%|7 zWK4krifl$(c@<_63=&0ZO5s{PD2+GtRDlRtW&S299sqSjT}*Vw*uM8EH3@p17lU1!QT zs}!BBmZ5!c4@+R2+@G$K*)Ogkcdu{z{jRi=Ao)W*CLX>Mw~nGArjb$arluW5I@H6| z7y|vC_fiTH@|VenYfEp?bbl`GXD>8^lhfBc?gsDp9>DK&-vIai@%9wE&KT>TV2;1mQu>HdLls;BG~uVfxLcZ$gsKHyVw0?um;H#%EjW zv*L^3jiujO0|y=q5pHDlNv&5rH@)VwSDUw_#v?BnPPuDnrgrIuSce%&vo-6{DsxY; zsV*DFy;S;AWs_y;C)G#rVL7?yrO^{k)vuyIG5MGnndvCnWPkc-VPoftQ?#|WD9ldN z_vulzbH2U#!p=1gq=a(n#nX zzN`XKS_(Razt`btiS{;n<$QY?r)(N`n!@4i`MF2gHTE;B*nBJrq_ToL-!WfF;Fh@{ z&pBp-9zR8RsLb9JeAMib4fdQ^i{H<&5lDJD-CRi`Is|Q$8B)@2R#}S_Fl6DcsBCxy z&!yC6l`9S3_(k|ds`)=ARXviYueK=e*M0KJ z^v7oHbhFL$Q%3TF07Aa}wV)Rtyd8b&Ds9mV_4BF<|q?2m7 zIysE`c1jwQ$%og*SNtSuzgM)X=v%wQ1$nL{nt5)D9-L8+7?0kIj+ivlD}FI#<1m#MQ(Lr0Z}}k}9$zWA++V&` zSM@Y`9h9y)1gocdEA6m7TXJ{jmlpQt!3V0(Amu>*>X@U=ilsZ>zi#c&V^_>Chb>w- z^8Eqov#4-t$L0TeaB5a@#CKTx);xcI{SPS9va%3+(4 zvN6SqqG=4L43$g2Rbl^Q^h1V%v36dIQ?AtU7NtrDiIM*$ih`-ldN^P=J^OhD#nc-; zd?I>W^bjlZytTR;OZY^eJA8xjE6ZcUD?o-93W8z-1`tKxGM|d^Ex3AtsY_=T^qac= z!bg-Lb_$U*2p8nreGGA^$t=Xe6|K1hO3pS9h<%B}3?BhKh8tvjzr(RP zq1%R)1SwxKDwWn%dY3>7Zh|31zDDlxRUCy>jX{PBJKK|M(Olb0SDrF=k-1+rf2yjC zsi`Po6>Iav3T>&)##>VwpIvd63jLTx>6;BD8JK)_(6CIdy_a)wP!i~!o^_Q?i2Zp$ zG<;S?jkwod&v&>r0r z`6|cp3p{hOW@Q4+UZoKnVP$jKTc<3(DfCIii=l_W+G?Gt#%H0=Tb#d*`sy!Y$XFU2 zUA|+?+P>hv9!~8iRP{$1X+v{C zo{LktQ$K&)$>u#}Cc7Z`i>cxrk7iB+T;1b&k5`3|uI&8m!7S@5l^|`tr^$8U?p(`$ z@iw(#X~`lUd_R!h>fghN;t6_fG;{rD<)nj*>o=IVC0^_KXV+v^($%vIMGo3gBEthR z93|5$2MngB+}AG%$jU5S5t!_<>GV645Q!B#p~s=siEtZLgWn zf8qIjUzSi6UEv}x%ELdDEB%bRJSa`*hee2PaagU%V^`oCXot)X-8(HzO*?p6Azo!T zT|HXNvy3(;9!o(d5KQ(t`U9W+kH;i`4b^)`gXAe<1aP%|vZF%l>V!4_%bdL+U3%W3 z6n#C7LKs9rWnn!;>_PW>pt73&yrxLW3t-eCW3HVb8O0o?kH?f&?GchAs09C5ePWTt zq~AzeBkU=Qds^Jo!^>Y!@!}WzT3`qK(<>DUzFoI3M+}~Z)(#!u8+3jEeHe$NYoBuK zA^p9D8w>zw2bVt+96!0Xc=%Gb&ygObmHlx0_kr$G+jx2$QVZnj<-+sv*;j6>LL__N zH;S99>2dX1dv`9kTq`BRuQOp*U-ctWAId^7Y_x|~lqmk*!}Pl=eBYv%DS5lhiGpM0 ztD!Qelvw^W?TBrTw~IDDLBB~Tq)Z84gv#&P^l{3Q9e(nNl`bjP`|G`|#vDfTIk|fD z0Ql^qV+z&ZO1>7+Ue$=?vIu)jv}NauV*HQc^epccUqsRuWcz zQO2!M!BE$(owY)Z0M-}RHL8O{wsGs@)^lecY*-zEPGU>-mC3+YezI!-Qot@BC+m4z5eVzSH0 zT~Y8p*8f6o2fq`ES4XOVf#-BV*NWI%5J=dfufwCyY#}TNk6bQj% zI{m+3jIC5wQLo)Ln9I8wRF2}~N-203bg-~@lj}Vv&l6Njb)^U1>{tOpPw~3Px|oB6 zpzU4^tn;ci&QDTLLbY3Ph>Q&R=K3r?rb7#}oq*BT!EWPYO0fak*t;8 z2Qc+dw)8%4@|LHGJ*T;O^XR!TwSg85WzGv~zOmIN^Mq57w+#5(Lr7=?tmJeEju^x1 zUnHOAK~dwc&&?rh;~3~$3>cT-YnBT(=z5~|3N;2T9?wOxmTiwyI*k7zTBso>_;Fwx zD{$~UH9le@T{2|}3eg^Wp)G?$`=&(9Cx#2vUim%7tzm&d@{&p*R&rieZ%QYWa8}u1 z6vrvK{3-bleu6;qq{brQZ9wx-@?_UASbt?QWxHl5Km`MNafQt~1v-VOBml%j(gg{Q zQCL8}#c(#x=wRghzEMyqwlT&8xniwG90TC2@lj+2Pp1;F&jqFuj7rhwIRK=LF-C02 ze){4g$e8N|3Ta|PI3+hUf#D}7-KG-kg$cSE1S2Bu18^D>HRWalPE>!XEj4p}T4XQV z9Ek!_yG=L>6Rc8gMPhCJDrfw2`mf3ms;=4kpIg(q+3v7T3m4m|<?~t6Fe& zmA%ehwibNgu(l5|({^g5rhxud+gmCHT~p`7HY9z3jl~N986UxtZyG}cAxqK8CP-YH zfduU3#TBHC8a6SN6tpTfW+TR!HoF~3yI4MZk+mzA{hO8ZJBge2SfW13=plXnq`?k` zgD_j7^AU?wyYUdjR61ILbBG6^K9%EGk+ao34w!1WRevXuScA!&*^19JIQ(F#rsl*!Y&{-{5ZXHY}@#B z>LhP%gV3$TiP^Vkl;!uLMgCf6wdO?$ib`CvI-{3yCMXZhG>`NV7a`>o|4xaHHF z|AjnvO+s;cjlWp?k_i~iBGoir8qv!|MMl#hyP=bo`PCym-p!M4^G5u^GjwQ%-`RM}@A0S46HQEM&0ext>@Qm? zZCdGWTH9{gcyHQ9ZrUYmB6BzGr4iy@uF`)7Z@8_+L*kwP3~B>DJq3Td4{@X4UkPLJ zbQqP@E~9{5V#KZhHT@_pcjlCilF-|hm{6Kp6hZ#vh4*I`94y7CH*Ybv45Otz5p$0xmi8!>e8dyA0BV4E3CGjuSqWkPr|2D<2N z5aBc+lkLoX-xMf5%9fB*zj;$(=Y-8AVbAX**2k;2Ddt)3Kh5&W|Krs1``+(=nC1U< zYWW{v`M*vr_y3=!mj4S_{(n8S++3O2Se{;A`M7m~moE&hFHQa3EdTdldC%nh1z7&S zTU!o4`3o%X{GWs6|GBpOROPhs;J;2SXa3J%`NU{%_tezirk35a{dJ>*?}qw2`+MFF zbhrH7Ebnc5*4frPaX<2HS6h4Q%clQomcMxZA5+V+zfCP`YpS0G8&C;{A@#+5xmJ{Q`<4~x-k1X%T#6{n|cl%E4 z?Te}9f3W4Zf^Yr>mOI?N6&DyB5PZ`&AoQPW%YRNS9bLVUPB*OW-OAOk-ItNEv~#;K z%gwEwOsyP^E$ofVFW7Qh9YZUnxD@Cer@z?pn*@Q7#J{gC;rf;^U9-QN<=5aw|MRJ( zu%xP>go@x5Wr2%_xH7-E62F)dR7~;m#njT==bvV|(SKu>b8oQzHMQ(T{I^rf>YEo+ zOUegieE&4dX~I~o@;XWk+c+5>S3E}k!z`zXMe`Z`V`@ozbOr7MO0M*5Ib!PyjQDG6 z`Kr#qBvjUcM{FM{2CalhRW#MJ!EaU;A@&UFvSkye!FO7#4aC~Q>L7yMx(5y$Nh42k zpBR6cxs1z3J(kWf3GB8j0If~WrmTEM=dpb^74vu7w5$-3X4bEBdiQkDJ5TNlq``le zK3%jTaIWsh*Od?kQXP1MQ)`0yA&s{E#Fx$m7I{7e>#^A1_&r87QNIr>4;HngsCY$z zC!)ky%0v-!H~Il8i+dFO;0zgB;l|8(icXHD1l~yB%mf;;hB<^r4#G`q%54K`O3AKJ zuJcQ_av0I7?Rg(2AqOml372e}C#u&*2x|8*MGR@F-l^WmG}b*%xjLbta0A{c-t8v- z{iK2xVPm+F;RG~!Jx0XxdoIE3*f-1y$wBhOJLK*xIkGKZZs**OXWDoO6aUkdEKAg2 zWsqrCdFZS?N*6s|Mq#fqmH}=^G?xiQR6s-DdfKJRbsPu`r_pm^w_q0BtjPb5w)+ff zstwe=A3}hTP*x!Hme5hE(gXxT?;S*X6H!r$h=7!Y8hWTwEOeyzUIe5!sZvEy1e78m zAfk}NbDn+n>@)9aU*4H~S|2mBX6~8$xBgd&XgYX9*-84__p;SvVk)=V5zCFq_&Br7JFRaDRrNF0nB#XT-G?IK&<^n$d02JhxW&wkRF5B6ie;J$iM#Rgcys{B|{y;Xz zdmH+9d=0u2^`fse2vW%O!yQ#YridCfh3)nV<=OO}x+w`ApCe_CY{@61HcxNPd?5Y0 zrKR>;LsGh(JXhYhg8HG&-UQ8L>}p3Q4C#e2Rtj%a;bS8<94Y_WI|G)cS z$xjp|JM^c@62w2hx1y{G?}dkSt5kolY)k83$%px>La)9sid)aJnIH^YAN(kKC?4HQ z!}ES*uxgL5Hi}@#O|ADDA~2YIF{vieI5mxt9RLRW4N;=Uxen2cu|H={KWc} zAZ%lTC|h2t9Nj`>i{v?x-)7hFju1(2H{}0vMT?ZEIxmMK5JI)oK21RxB-m@i!z>?b z9YDR~lrX%vI-zUo%~7vc^eWs6-HeNU`}(MadbteG)-dE>;SD#{*!%ZWPp?fCK651K zQ0LC5C0J02i1xA?lshi!AgE3pClj^x)_>$=6hF_XdI(p=)9~~}&)622h(*6riJ2$- z`dB0AAPl9(`1DTd^Wq*y5BAS&CF@){Op6hAz*Jh$S>5L)@R{MI-2DMFxp2C2-g&KB ze!ynjkSB|GP=eM;J07x+KJw$&r||=R?9!#rr@pwm6G^{=+z@B+S8sHXNn-Y2zek6j zzz-tm`qM($Ymr7mB}sbrsj5#=YV>My*NB8gXg||bV6-qLH%ow7e>@F>p8NQnz;hee z>!J~QxjOC1m=7*$FY4cD$P7;=`0j>rQkQ6H>X_8+=b2|+Ez!9(JeA&hR45)_qIXwk zI&1N$NV}k))N6S9)!9+8GIgm@l+H{Z>+u^c{ZftY4pus)ndHcOqc#`mYavwaA~A})?3gr zsb#*=sL!d@Ji&40#(G}zXgGIfpHc$HOnH^ooQuz zX;~3QJIXMz9TD~83S>L|p!b%e4Nh>wu19T9%JrCv@-ed?=~{$~RUyj#@~dWFRU_`z zYwA&`&n#&|#@ww9Wfyp7L+;#xbGuPM^@axBY7Z*4IId$hRaT-<`9MYEz=8iguO?L~ z-8~gFB`!V`X(ZYgrlbw9(5VsW9(n7&mBb{x8-tGB7u6D1{{Hp0ic1b+@3Ga%)oTwd zY4mT2k`-*__P^`iq`k<l2t^#OenSs-X%l1)xDst_UMgVc9UdB)_(ICqV#YZrp@=<~+4??z=tQ^>?-jUu zbv4@Ct@GuGrn0hinxOHO`w+jy8|V{T)~U}i6P_r;pPEPHut)K6@fkAOK5b+|1gD=+ zZzRG4Gc2k7wZd2%OG;Ja{cfuYE@u$lg zgx8|d79V#ls`&@pxtcf{}zUOy2r}=CADIXaMmIDn$g2fT=RBjm755mjHb=uX| z!%&S66y~prAAbDh@cEC(4VfzcQTxurwAX>c+(f@yk{5KbA-y~xM1%=*=a0#VrHGMtsANM9(&Hp49eL=3lI4K$9V$d5SLT z=I%dxkH7pf_Uk3?JFmreqCyUbX%%=ai2*T|Ip^T$(7y;;{MnNI@#*`w7YCmL|NIHL zcrO6_pa^oiLw!<&SfBurfZ&A_K`Xa{Y1gP1#RI+-2bUBFoCt)F9|W_{MDr+wtgzCS&)|8P@a4mMzHGq6$*6ska^uvFyL+;D9_(i$w#J`nlsFaR_U{do%@9YpRjh4Q+E3U2u&-wI?x<2>dA zlLbvQ-00?+K-g6n#TxcgSMVdg5`bH6g;%|a+akTzH^J599K=Kdos)2r4Q>L8?p#W$}4FK@CvCB#8uU%RmCt zZ_CdENfh0eiw#f>bTU6C`Nm{o27#+qKnTpqL$l$PSw8@nKPEK4xS5VnG=gEw14+W0joc#FDF2vHuV*06Ew$E9 zQi(vC2}=sOBTb7kY;%?N8bHxUpm}@)c1s9QCQu#a&=e5Te)h)}0`OBym_sHu=SezR zn=Nw{nq$HO&ZA@GroSeQKW^J%QrP}xhrmro(YS}@m3TC5 z67mX_3n{YTkQ$nyyq9+O^JV3Vf+EukS7H0arYHAH#VLBS4D)+PP{_E{y$$a@p`IyWOz;^6l(G>>KtIC@@Gp#Ozx= z%+rRUcG-HRoI~|=C^20QNUatlEkHE=PJ|d2v*D-@2(%lXaCR&ZqYX%7sSdhmDkdmx z?`M8*y{yM)x-(D*t>qVXQM-MQM>wM0r61C?F`f6MA>|Qx6rJDVU6v)L>WMcTOF-G7 zW5Y2h4n#eX1D)uCf*s+aSL?vUB#0!Ox=|V6X=7pzsNMZgd!4PWFsH6inM~s<5QYL& zt^zl+nUvu5(Ux8#bv)S+!|i&r)p`@SS+g3!=>aJiLnz#*-N9PiWUCV&sk2zB z6}4`#`_rJzN4YRzFPho(1rR1;;r@S~J2W)LO*E3Cn?d_Mo8Jsc9Kpt7jqSK_0tNT6A@|k11wBP9J zeXh3Os|UP8^YHgz7a&OLgO+g?@9;|5;`f`)0^OkcO|+JkznwmS8;IxYFum8llm*GXsBNyA$wf!1j2*732FcN@n%<)d(D%sZ0g z$mq?(bQS5~4s7K0Zq{Iaw#fzt&d%>6jD7Ksdvnl;B z<6ah`W7prpT%r3=B9_uOFoTpZAU!&O6Skt(2Ih_U1ip(>;06I#K>yoaBX!6*M{m_2Q|Q1krwn`r2gwAkc2F!llLANoxky1I@n0 zjc=BZZ@1GQy8ALcoaESLO2+iC#NT7son-ph<)14a0zBjybD8j*l(U|q9c7v$PQ-cM zjdUD<%H3?%Ynzs%=H%Lx!@{3P$NP!}jTbCUULRv}e+)-`7CcJ_WGj5s<9!)k&Tzy} z`A^P}M|a+4ngu5Nte;Nam4)hXaAF<;hKp16Y2$ZZ&ITc>pb|8XhdBq%tj-}e0OZB!(!N-e@V^5o3F13GL>O5Z} z6F?P{E_=z)T)|NbaZmN0`;L93Eo@)*5tyI2={sgbz1*11Dfh9lVM+Ud6(D}5y7v(Y z&RwpT@scb5Xi+?cmkgSXS|O8J<}se8b;Rybd-j?<$&Eib(3r~ z9{HBGtlyDgLohlruCJRjQCS3kwJ`W<)%n$C<*VJrR|n1wC&djHyA9Xi4YyYt_d7S- zS2iA9YF5X>ZNKRJlpbNK?MPX{Ej?uBsm@YSTv4V~Y}Xc#9QX z2}`Bz+^U$}`c=b`+-VnW2ipt$HmM%T*8OdQY|GLF262Y+&WJ&rs&Z(|a>t~`x;CK_ z%#T~X*V}D325&dN+HURKM&yFY*2ua#$-2h38@`gkYRIV9wtGdb2loIg;Ce;p&V>5b z)GM?1cDsppcHSD$FDC4+TZ=I4A5cxZ2zr;CXaiHF~v_HF5ZmV^UI zl^a4tj;kKX$x1B|!=EqA4?Xy|&J653_qmILMOB|exebqA-8lf`4opIhEngp7y*-|O zd1OO8cHla3;@Y^Wbn*|i6cfIvK5_qa@<8lcRvCRk8~tOkUrNTmZs2}NtAnF;hw;y0)qO^Ks}(9>0q`%ztczD8_J4UN$8`|rF9S9XiMznjL%NSj44)FA>xr1J z@97fI9xOGJUu+hQ(*ZYCg$z6G6s0tN)!^O3KEdq{A

iPFPN*rFW->KCwSmkn`0nl_A zB}j2?Qw;g5Hs;;yQ-!+k)nEQcv)n*v=dxLbqp}?iwk#LfHEFyV^9O%B=WSLiwXcR> zb1H90C~z1sxFn;q#Tfr?uUQ-6yN7NH{IPfTC!J?)?DZ$Vht3V(1!t|<@0y7|OPOm? z3^c#e*_BD^|I9s+`^*Fedk4jl>KdbRXB?ne( z3%vdd6%{O|5-NG{om-H8sK9ARNBH)1EmD-jyQn$_rZ6~)b43oS;Q7yJ3&aNsl6&QT z^jUnR3ERBJD6EaJY$a?i-f4x8*9qTtr}|!^i^KBlS>&zYakxfAnk&O z%}}QwAH=;PA#kYq^%z|T~bSrw`4N^G|QW89vAbS*gToL^Dniuo2kCyYT^Im zA8N@3aYC}FFUdIIDELpM#$X!%P)o%jE_IejS*K`$MqSyM5suGJ@iL-=DtBo(x3m(P z#w>GuG&OFlMN!L1-npCkWFc1_HSEGJ@ihLDT0SkB84Jrg%TMF-=Wlh(H*YBVkpFy~ z(Y2^0ZSP(QvHJ<@VsdfkAb)w&MnFX=^<_wUf_QoP z;keEs>nS>sBg9}k@fF*T`b|i?=esIth0E3!W1!anmyDeIpg?iE_lVd4`%?e)&GyId zl_+ldOlk_)9*F2@-aLL}c&p>dTrtP`lZCs6(!PrxuSeh?yza(QuY^3+O*iqS;1pSk z)$HVxab>}uuG`98_n;XzwA9TCNVS7I6FYQAGU+O2=ug8)9)( z9ybi_{i^%7=b;BcllmQW4eF63o_7&g1(CCs3$mQKhvO^Z|+z8dsR}oG=$S$y&_@%AQUz<{F^PFMHXebex zl`E@8iSQ6t;jooA*mk24pU6(A2Xl-Z_!5-W;HB>w&B!uS|rN z%Zj&~hWao{th+3biQ}HmlCMcx2f!_6TJcUwv657_Ax_S$ zP_;3N^$8wWz2PxxjE(k8_hxbz$68=KI+(bQ|vo(*M zFshDLe>FUNNiEAW8C=A7ugH?OwR9|%*-sXE za{f(b*Y}pWa`Ucccr+pFMWaFV`E~N>S zx1FcET=@gP#>68FaMkL7(#8SpJ)|<~A!`4()33;?m?NfcK`n7CdouR3`U96G;&_S! zKiq&(8kD3pptLth>)HE-E9(*mN&^lYGVe)b`)((xnYe_;jkOtou|V=cVu;aiwojla zrDX&ur~pLsj!g^Iiydz-YDQjFtP7(PhXo8ab9rd^C|!`mSs<$5o_?yJ!z;!l5p~)< ze8M1TQoPCjyD@z5b=gr&EKISLu}%wTC!>Sz%yl!oNxnmo^ON=|mUITcM}C=Uj}oPl zZCio#a7)%e`JxL7$k8_W!#eXIhdhqLHv`3(-FRn$A*$X%jY4Mn@1V{eVFT;pA z#K<3&!%5ELbW6>xE1&anHH)lr|4!b8^zx7i=*pgPj6d`G*h+QZ9+4bJyJB$TxbKgkx&rr}hwSr2#5-WH0?zrxGw@sS?g52# zq!8CV40BbIa#U*2p2s6p0CO!WQfB<+7R&TIB#clx_UF-LM!z|9P`M@hT>r@WPur@y zMI^wic-G9TjJ*D8AeYv}&*(8J`n-8S=>vwcS}bk4pm>J8`hZA_4{`oEeG-IO{hMHN zO3HNYdFkE4xbB$#dpbdznWl5Pyde4L-lG1@}(6Mm1lc6p0kh)g*tcfl5}WrTo>u^h&CyQ2~~1 zp+@b*kth?vs3IQapQx)FrB}$zx>Drpp@Dcm!H6ISGN7$%)}gHZv-00qlBdk=QCm?g zndET!ZdUhb2IO0|3G&eWx1n1UTaPIW@JejFDrsHanp@o_T0J<~R+G~RWuQAN@au748f55QAY6Y(ZRhlAdutC4PsZBSEiB)+r={Kmj<9^AZY2H=hb5!*>$6N% z?*T_V1o|Cz$U`mF*^kusGSq2V#de??j?3gmg8ev4b(~R`iyV@?keFqaW9$ z7duZIl^G=d^R zeIh)=BSM7-m8qhZ4>j+?24|}^-H>?Vqh<1-a7~8C@gY>)0c!C+NDa&C!TW*lzWL#Q zs8T0D&^lidlIjPQ|3EAygMHv>kX-XHYQnm9Myhsbj&>-aGLl&rut^8BhNp+AE6;%m&>U(W<^b$c@M{ z5r@>g0~mkPKZjyv1V>2NpjP<$`sE7ORn2f_{s2%yl^>3Z4Nvk@ywglC6hvBwgo0H^ z`s$SqmU1fsM@h0Ht`kPjgywwY0#(0xJ!pGb?*I;ZFB~D`M+&E_mdP>r5fl1Q5I?Vg*B$J0 zPoRP`NF+i+Uo$fQ6mijs({lwIdx8+8R=}`EzTwj0jJ5#^jp_>fv6pyC`Av4N+ zJs7?jR>>LFjxIHGvp>!=8hss_5i^r1GuqUWA4<%0Z`Mr@ndu)_ifow~?ur&6&1apU zrR-3YY+Q@5`5(3jCuMV-Tco>kxH^g=^1k_UtT~Eu*yc{NC5MiEN0;SpPbl<5sGyD` zpQsbZC{EVm4z;91#0UCi^PCqSCcnsr`iwo&K z;u-pb>pe@NNlm8bmU(i9WrN>*q@Y-=ZFKyTSo~OAOowF>u<&?6!|x#TsSs6JTzV=W zG^a)^4ZF}_dHdCys$ApfZ1dRkC(z8rY-C;UX5A%Q+kjv4 zys^Ztztr+EHbYA^47gG6XWe+ZR0CaZV7BpSvAS!u=rXie)j^H#GOuU0Zp1Gq8)Xfd zC&j;6c6Zbcw_0}iW)nroCR>8Wc*jmYgilLFzgM>%5wXo)W_+3YT-K2ZZpQd>2XSkO zFth~_xeo+$=GkytZ1Rp$fCOE7_48#u{2%V<_1!mLsF{j=Out*6wi}Ck zDolp}`$&LnxxuI=A>R8AF+jvXhQkmm!+XC3)dq))K_H}BCX#K`={g=h0Khr{3Yn+AeaZAg9jJ&nC)FN{L%e zUEV25MxU?p&s-Zv7--pSaYIA)Ked-yS#^Jo%AxSiSPQGBcK5UgiHpCbUQ&~z?f=;n{%5{%`#q&5bpU|AP|d)mBzl zmQ|LQRFoB8YQmB?g>MRT{!tfy;lILXZE0DP*Kd8hYMs$f_E{ zu5E%EOcpdP{h#uU`WXWB>8(T4U&mkl*LdyJ4$l=^9xnGOU-pL=6D&$=~Mz; zV*Sj11xB-tvcKqei^Fz|ohs{fr8_a$~sp z)IBtxOp+$}ym7$;Y(VxIvrElO?H_v+l7Q!)O;7Rz3&|qnJG-Ft(R44NtPd$Ew}2>s z@m@i|jUkzd2Z#l~Sg*-@y|!u>+G@E`5cS(h!4SvW(J55u9;1imMV6D^BOkd7RO`^q z!1E?NG(Q>KL4mkO@7TnP(Ys&IuVT(Aw3S0Wp0=jqAgBICS`t{3Y3R6V3o6IBVB zx-wa$&&YQml3xos66tF#KbkT;wn>T4bl01hglgL+H&9dS6S7|$RV1~TrWEXpyg!jF zR%du8lRB-}w0oj5`rXZR+~t;9lWqr1_}7m#Qbd7YdSWJ-6N4IGGd|4M_WV8h9LLmf zsOlbD|5!aFA0mvgXv+GHv7()6!6ZFMeX5co^Qg7!TANRaQMOV+!(7w)naKhT8Qqym zzV*OFv1w7NHwLeX{A*nC`qAG5renDbjf#oi&8jC65$M93Huu#1m zFq2>Eio`w+h|7TpXm!J^_CtA-G`@)scGCpxhoPu)p_*DfbXoi1f_k~ITZ27}t@{z; zak*4?wcfEV?nlaw=F&VJe8+jVAEiu{2N0vQdbwE-@LGC#bk7HS`Q;9xjpFi<#aew= ztPWxY3N?HV!F&km;gc#KquWJsJ9{@B^jSn*7`82K`YX zL@j!aS0W<0&00@0lUBk~1t~ySH+o|{X0xHQB|tys9-6wS2A6&03yAnbv9I98_SMDX zJvYOj@#NCqSSq3G<#4u)Zi)2rE+h(6YrBYEw5vlEo%wyIuA|dDA#xNZ@CZ4d+;4Jj zdU4-cnuG~$5M_x)blzz zkbZE|gr(N}^L-Rm7?=JX7(!P2u_0;hhREqg#uBv@57PX;hFVRl^T9XNX{PS$m=m*d z#R3NMWFw(GuQIQ|9z7A(4b0%&Y%(gL0@6JqpmJQ2z!zQyFJZ?>&s%id?A3Gy&na`G zdF9p`s;>E8#RP10`5U+dl&j2JAlMN5fk%Az3*EJl&(QM<(WnFlt%2rCw}_*tQkgAR z$9!%(R>ZfCJ^ohCGm=kVApVya^ev z!4px{WQ(OrK+TutPlfWJHjm8t;q$4EVJRB6mBXxG?OXa)0dpfOC#}Ca_T#GpH+4Uq zE&l2}9jgldHS+1=?AKcmO*NK6ZxzgT+66VJ4rLl$C6_<#1`?{n1@zWn)~7wyR9*B6 z-D?66&^wd?45Xp(nXS2pO;Dre>Z57`1iDTc)2z!_L3f=| zi|Z8%V2V0T+2@5~yAG^k2+h4qS~aOn-Jh+GF#WH(4lDvj*EE(@5NgtgNeqjtrJd0*pE^G>t|Hj|r@fQ8T;hAS%N(qi|*xXEvBMa^eU;5chvQ*)C@ zT;DCaa-&;>_hT*1i(6wL)S3Y%q(&kn{FtX!f*23qT|%EICX9rl}(dkH7;2iWH@~R z)8xaF@vTD&ySOmU&z5B58r*fI6o+)354~0LXuPg4%Zst8vs?UFI&9@#F%q1Inl3VLwD%OTfXM-|+P7`>d5UQM34yZu(GxbXwzO zt~~z?aa|23?kbGS~w zy?_KqzcGJ6k8lGPNM@e041>+0wbX`#bKKYu4k(HSFd}- zJA{TELE=HiVrwA*>WGWpTQL%V<`aL$Zee<;OcUW6t03t&2deG62um5@3bStFoSnE9 z&_k{`je(FJ=$hBEN&3M%nCRp!5ma4N-yBF)2LTgVF_>3)YAWbtlUk6%UVNSvRM~>#1MhB8( zE)5UM_c<9#<8XCG-P5P=6HWUEvcSW6PKY3YOr``HuobdmulEJ7Ga%M`{1aA{4{mX+ zAlL>s;h_`pp(s+?+&D_(&>D#6FR3`Naonpq))FvdrWCL`7Z=t?XU@$1^oc)_ka%Vp zv4390;0D0h z!j!lQlMqVbRZF2i0=-{Nxy;u^ds4j5@oZX6CR+CVfmnY1QVX(3h7KTSvgX-z4T0-~J921AqJ`vgini2B<^Br7Hz;gW9R55IRi zP4QmxQ*ppUJIzbzIryjWhvpzK3FJ=~B^Uwz2@0V@X8;AMdN}~+;d1g)EkY!b4A;;*MHQFOnsxholtQQp;6w#z?@QM;69i0NsO&Q5d zE?!73xq-C4LFv?EMXxGfftBc6g_;^u4w+-)ECCXt`b({_xbk~Z;s@+@CAc@JqyQ(+ zf#1p~q2$OLm$TyOPyvEsbk-yb@wxg0BnLXlj-JpX>C0@cr)yovZR7)}vT(F9KuH9Op;cMEE0zB@h&hXa z)<29CCri%5AC42PySxGp%{TDU-&O{8{iAmt17a|Y@a=q-tO7VDm|Hc144ntXpzk^B z%GX{_+f%mR0DAYc6)X#Nz882Oy*41tpfi?ut;#ut;$>&$gh*t<95c1)!Iv3<(J4jU z7$x-YV%Ph~%l;0P#PdiLOx~FZPoSqG#z5<)6iw>nq82&XouHw25x$hy zbxrXd9ZY#^Y3X8Vr4G_-l0b?sWAZ62PAMPMsTc`hoVbsfT9h5Isu(Iwp9}E(l~#Ur zp(25$QrGd(d0P6tq12t>%1z80itx(8lnQ8Sxv5IU=65CoZcg^n%5!s4K1qmFX8ERc z+6=7nFRO!B03az>SsL&Nn^U!gd82#mpep`ozps=oyE;7d)zKAkf;6V2_4TLksMlU4 z7su72m}=3VpruwN#gb}Ga2cA&rX%sJPOhy^VX02>Pn~iZohVzqnsvR#vwAIgKsCEw zZ>iqkPrVUagNb~@*>Sb5Zi8iZ18sk;)zUv|(1ESdXPLSZwCS3J)9OULt~!}e(rGsZE;ZSx-Qy{{>mbm#T#|Z zUhN=1@t-f#>S#mGW3!itOZEw%wzVaDx*q>6>rU_nd}pb1r>qlS-@5z-XTeVa7HE9I&z%U9s$SKzo-u{f2J`@EuVMlw6v z!prYUr5KVQ0LReYmuf7yF7YTU##!S$4Luc!zco~t9z&Zx)K2Z`gFdVFKAo^O8wE3` z{%-qrB})PsDUOUZiOfx*zq-Dka;+cgNajwZ?P>$u#R67Xz|{fp4CJLy7+~@lfFzOK zb|CX+AFv>hSznssXY3*ZRD+Z=gJ9!9rldjW@}A1;%CJaay`@ zGspg^7YwvltG~M|{0L<579RYmFn+&#{P*&EL!0-mUIUvu?{7dRoY4c%+D9QbRo&bt z?smVwuGV=19R`9JNjcPv9igkoeM}s>LhTcn$w}GXcQWM@!D|zWYE!7)5sS&u`0J9= zR6X2dOxKC}s#mCc_~Y3GU#fC-Oeq*o%7!zsj`cmUneJWhMYT^WKGf29$fn#e!{kDK zN;R7}Gt+c1VC|n2sISY6j&;`^ zU&0Z~XT*2Q9;#!n)#jKneRPxMGPo6$nn^gxNBsIc+Hpbfs8s}Ag+Wg~!+jEzs1h;$ z$au6^6tC9M7D&EUwJ zoxhI<-|p?GC-JXd#o+d&+eLR56EFl6W8P#dFf&(0x2yb@Wj0uA|0B@fx$BU+b9wk& zD%`w~UwVe#6J1|{;yyA3?(VEOOxTrUKK{6g*#XJbEPP(*HDY|9ujiw&% zj=CEG?yD#AYU2;qj;-5&L2Ag=dVflzPc7Kt5Hvi}P%TCY>A&-<&Ydh=32=R{=88QQ zbtFrz8p%`w+=1UW);A0>XUcJ8&&7b6{ZkVca;FfaC6M)6Y2aShDWvAisQ333l7U;| zBf0O-Dy!68st|g&|JaxRY3d^Hd#lH!Sf^ZucQ-`m#!C4K#% ze4W&TQZmD6O(l}DVp+}^Fj9?S5cwbZ#{Xgpc_|-IUz$QDr8opk^=1f5@yu`_?4OM}DNDi@5tiZq7GRBDe_mpKooiM*El z@*yWZB9m#QgWc-LZR$P`TPHL{zt6HvQz_i0rii#Q)$q{t(O>V~hbtXH#0x*aRmU|} z=Q`KA9peTz#~Dsbz7RTXNP^@*I` z;V@5ujOv)G67a&dxH`ivmzq8XdbVxh9<4af0!x?;4>i(uy+)HO1TrPfZ2t}nKU=+$ z+=F`VQmZW>bS*N^`4!bYtt(Z%hu8LM*AE%37_YgY)WoOO38Gb4uNKicmpXl!r)P)y ziF8+u4dj1N-GeGr#U+A?$$-}(D^lSEIeHN0X__4;NH!=ItHj~W^O*Tc9QZgUw2F;sn zlj+_#=CW8mX|gLCue&sbzY0f10)LY=b9+*7OF4vDpZ#*c()(FBMj3MNIYvyTHGd}1 zHOe~2%V@+q2eF*Uy2Q^jw78`F;`{BAc1yHL;mopM+AhZN!@Sh(nSx7G7#m?c^fH9p zYF0Ar!hAa1l|M^BlP+0fOF3nuVHHQ*h&U@LqCcB9vn|_bbO6)4yLh&#Sp0=+h1dLaunL^E)Og zA1ok!hfYTAld_6&2YYgXA+kjyxc{V{)d~uV1PzG%#i=kz*RZ{}e5Y2c(#eEGT=CJx zi&bkSs|6M4&EWbN%HME-c+omU&jFFFH$5KAJTd8u7lj`BH)c+H=pF~YHxM`H4)eHvdJl_K3qLl;oJB6K8F zDwQ>CKTo5Sd=RA1KlAFPfCQd%ht=iDZIBe^42XQ6oQ&`bW7Bu(6YZ23h6exO8kOTlYaXS*oe}{$1v4gq(Gm=#3cA{K6}y|TPs`d=BkfLI^;8D&R}t+gehd@ zgLMs6y(?NKf~abu^yQFQ3#4b@Og*HaIYPc2lO*-X`S~aOfXGERoYl-iAY{#T%xCLdPfsAhohuy zQ;X%g5GVYdb-ct<;8&J=Pk-db93)$sXFaYlsQeRti?@L7e05J*#}DoVLH8HRZ6@kc zVL_7IHRN7IGQI?PLNedKk$YdX5+E`%ZPMjZ@dHkfeFlpJz^=$x3qSRND zE-3aPo6GEiXzGJ%>PPWDZA;7iO${Crdp=Fp<|KX?roo8_CcN_U-pXJLQ=Uhlk~W#? z=u2T@f6t@oGe!}G3TV$Ck&K!D#@u^GHMRbW)(J@o?GOL|9pzW2D@yaTFLK#dNW)8$JILh+NqGnYW&Bhu3+xLD=A*n_rACo zw@wrZfI1lLS82PCK5TbvyIc<4xmlE+d{)gO_u4dARxjAYDlBL?{+I(_(V~jvkGleU z!g;>s3(YWVuvJCjUU@n44c*>OE)WQg!K09d$sunkgU{ef2^K|j1yrEo)q)Ya2+_+6T_{YS{4(*CgRL8Z;$6>zl z+;Gss{tf7&?iHP?{Cf=c2O;QJ+vj9(^I@G84!<@(UAB83CF%;5+*Il)B#6qux73@w zsyjhu@$xdDZ;@TmSd4k~rKm!vo4TxpY$rlKKBEu=I1%-4MA0laBHLhv>dmhDL}sDx z(n5rCd^dhA@=a#4-Ktk3Jj^wu_yFoaxqAFUUvJ5aZBs`Y12bFZ9o(ywa941$`W3jUuHaC z^5UWpqki`bl}AXG4%>p(nlJa<7pTy)&fGn1|k2sL%8OZmQ8|J_a+ADUi8tlD(NE}##vc4UUkwO zM=RMr(v)7)yk630#j16|tTpbiE&edyaam(uj_}J->-uP$tFmUpLoN4){wVBokGWpY z<$j}se(#b#H?{#IWU-5swv~aFt$dn^n|7d6S{_Y&AOR6_7ZK`@xa*0yXD|?UFc1zM z#IX(Hg$5(!2O~8G31)*)PJ_|@gE0ghCw&Qn;ATp}63bV9QNOLkSSNUbRC(rtPFaOc z+>TBnGB#yPM#mMF!NT5d!+Mj2Im1a;W`h2{JVVwi<$|suA`hG|QrCKar~*E0Qmb=Q zY8bE7pD8vh-u=A7Uaww9uQW&xW2|!hkzT%zG!0_tm^{q5KCIRJ}gM+c!}WVW#hp|MH%u_=wQS7u|coyOky zk4^Is4RMCQtMx6+lylccXI~laR~jY^LLaz3(kx|-BESt2h^!_09T$hk2-yVuV9qBe zjr}+RtU9WJzfi_OZ=nsYQFHQBJuF4%@d}S--y`1MZesnT?&?@Ak8Amh%j&v|Bd%NH z@mAV#U3tr!=`9BXM`pzC12_eF$rJlBa``0z^D-Vpp3=ugN|EvC!j%-mgdja9xr@U; zb-zmu(%Qm5w-G(;+ukd8`Y3n8VaCT&6QX}JOJyJ_XAnC`0>VKPL;11y`)K#~(GKPN z#_z+OUx(Yj4!`{VzV+*1?dLZtv$XzWf9-g0`S0rN_uZ9mJD+y{DLG4JmcD&iJlcA< z|9Nq5YhibDVP|9hXmxUL{q5fR?9Te!e}gA|-dOk>Wcs{1_xaPz>iWk|pXSz=W)?rb z+gO}fUz}WDoLF9*Sznk~`{VO+jfyAzllzQ{DlNYq`uL8#IX(10xzC#Zr8GP7aDOyw z<4^b5pQYKqfTjPjG;2!*mR76m)+((3Gd6p5DOdX+*wX9&EB)DDrP-(BBQHjWxs#4ON}khS{nbT&i<1M?Mdy^Klr6b zf5J{|EoIt4;7lq#k@0T z{taHzGqTb)q>@V}viInZ~ZdQZd`ADiY&TLs&1zQetUr|?l48@kwG4|p|_ zeNC3LV(I(ODRnN~i5b>i5jmU_@SZ_Qs{wMbPZoR{3l1g2s&uJBh3c=*FY^YoS-3iw zF3X!utMfQ4b8DfPUM;HqWIRBrCrhRCnG8N|(Dg-p6(vWbCbCJ1icwSG@ND^3K&r|grn6@%QKPqy42$D4MC{lnuIaG|C51dT7MjD* zt7#bBhls0TW8vMpz{PHR`YGp;3ekt^_Dn)Ia*w5jgjLNDm21UpUwU~pb{TsgV$zWs znQ8}JI#^$V!g8*7GD1E_D=YO4DGBQ==cdlgVdh>ASD`eL^1r_?f2XO0IG|Hy;3bq6 zlxaAZYZl2_Noi^c_^&;Pl&3{kz!Hbo8eZ)=^Xfs*w~(utzvhsVVlEwstNAerd1$TX z)O}PdAJa<}t6DBLQ(bM8B-Nv&`_qCoHnNMwmk{!B)y7tT3yE4Wc2~{GxN2+*O{vZ2 zUbgzurx=C@%kMgAY>&+=rzbVH^CVzf8TmPP^2kqU?@N(G&pp1#GQd9VdE5FhRpYk$ zqFlOt+}i>+adnLze{|LAtOsyb>M~n{nmsT6RZbcDRJFJXpM1k4o$4I9=92G4GMRz> z-u|p>{p;Hr;H(_fET{E7a;txipMQSkpn-8W(wTB9tqF*=2J&J>8osL8iLPUFWMZX( zIX9{YEnbKv>Wm8G6SHyiyiJ;B^%{=!^Nr9_nkY>AzJiIbHJ!V zZQA`21ux#`CJ&5GAMY@CbJgi3i7p4KE^fFss<$Nzjn}gKwqrMFepOyjdviVg*zjbI zXQ-ARAG^x#TKP8V8>FaJS=Z_5)k-a&@msc<^~|}|s`5A6DH!exgS#xLN>PV8wB2Xn zGl;tS`%V%nFw`3zE&nuUZl{1;lLxelGo*5VX0gX1^h-|!fhv_=uQIVYok^G!zJi3_ zS4&hK_ec3*hJ-If@DyHM%e3e5CiKWs>ufPP8u$c3XQ7Fc>N76D#x5a-PSx?lXdmh5 zo|nLdNA$GJA0K|gE{6-m!&wdY+6Ac0Qn}zFc381FVa7N98i z-YPlu;?p7A{CHl`majzUkBRhHsgm*w0;N@4a{SG#L=i*Tj(sHp>7t3w{k4=bTi)d; z`1y#_Zvrl*HfXW8v%$p-Uk$ontrvONR;JK2GOBn*?;w*1!&bj2}-PF-5<8hJzXOj{<+#7)+#~;8bTGX z=?pqywea#jx@G8eb~^ppyAm#J0me~cYWve5rY90zT$(p{eF=H*wa?oe>m2!6Tkqmx zpGnBx^k6oTP@=GtW$v8FN-kFHA}njs9(1jG-sr)2KHG} z+h{e#gc)z#ve{xANE@_xj*}xY!8DS4S!&!%UtCp7SFqh#A?OLj8YryXmi6QrZ0-=6 z_EA_q*XfIvFUX(pnX^HKv?d1BLBD?btM!hyy(sO1?Mzmu=Q+;QP7W9Iqa&YY|_RyA@yQGPB zKI)u=;H;OOSlxi&NU!$v4_|M=R9jP=m+H?U_78apKuB*y;%yd9iR=_UPO^v^k0f1^ z3D_pGH;pnP6MS1?ls_)~nI*sRY@NNB6d)$TIxb}V1yi6v(yMuT&PHo65bTu-O_Ws) z{4#;58s)xRmSUe!Kz*{eN>gz8A-pj3x=ZAwTSRlh4Xv_d@y16DX5l$v_ra^xoGc>* zTnuDZOglg>k~3+r;#GuPpP)z)B811A#bVO31umQyz8>4BSa41imu8ra77%`mEpO0I zMRTWDbsP*b*U+iu`nDA-`L!aGdTar6vDyn+LmwOIQyGI_2%U^A_=8#64*U7vCTFkg z#@QTyifbUQXO&()Tt++$K(D{pK&@YhP1k z4taUo4$UIg_5%Z?ak4GK)*!012pON;7a*3RicpQ#iSL!#@6kzCzh-SIKcaj(_8)9V z3SBV*3^ejLEI<6vA#Q*D@=|TnZn1;%I+5a6$K1Ph7KdNK6Mo|7!SJ@^O%Nwz3RFpe zE!1-Gz4IbbeboM!DL+_d!Jo$AUWnrPUb;I)_F?ySZtuEqoxa(6TNlbG8K^ z&CN10eL^9sW&sGKW5TU+sM#Z8ND-+xdRj4tx8*3?)qD3`0_3eC6@nryMI#qnSl=%M zehP$pI^dzNY03b+$1{AK0?SzdaYhHI0}vz-Jxn&j5X0ZL8vJM)8q*b0kQMecE4c1E zD-0K0Mh-4og~J@~nOFvV$U@z-j5rHKU!4HaeuWyN!zCx^_^p8VpePof+y2_XPtn`F z&!~e#bSY@SV}`&a%TPnX+|ji(lP6K#V-^KwEJ^6Q*zf*{bfB|^_X1=5&uHSx07MNb zoN@i4ZNH~@l8%qV7rP?cgkw4*Z2I{P)?CyHU`5b8UZ*ahN(M+&LK(r4Ya})QG-r!FpoNP0WwLfQk9HE>Z|BcG(Q8gMt7`7^*!ib+ymPhrml35x;sJ3(#%sc*lhD|M$f?ZM?z z8SIYG7i+2gQ+lFL26W=|{TJNUX$-|f7;#l*8v=*{o7-reYtzC4sX;!M0r^%U$=Iw7 zOcpIF?=6Ww84U>m7}9a@2Zc;Q;=mx9IUt%R$qmrZwLfnO{K~d47o*40tKOib0m&)3 zG{%`w{PjocX*B#?Hp?z>-`v&MT==e9+78p{gZ zO~R}z;ueXyy9=VTgZx>eKrWPrU=T|rkq~=C-VSqvC{Qa?1T`*tA$*^iGXn*tKGmTU zQArkMcF;wox?rFoIJeQQfF7R-_eCr((C~DD`(>DTK*#MzYS^Vf2e7)n^ci&A0WM9YIq%5vh{6l)guAud`l(&Iv<$5l?o zLONx@HmoEIYRot!127M#sa_~~;!py?mt>rSRKOXA#VVkvtg1UeT?B~FSY$)DR9FwN zSudc&7qf%YApGdNOSDAnBjN&bg=#}{N4(BXj3Y7MB4wGSG7c0bj@u)sY$pa$#4=p| z!ufvbnva2=4Glk9XCLmQP+I15BDW@|`9}ttKU+41#Bg8DbN11Xqhd~gA*}{Z4LFzY z6vMhJAt;7#SeNcX9%VPg5WxJ}4N)cmRJaG(oqIyZkNAbpG45unGZ7gfpCDFMsEPnH z_Ch>CEK@Ts0kKbgt-<39OkYWidDz5BJ%F3C!?3->)J|e&7yXL%selIEcbu^@Kz(7lK|I@ZKhtbiX}rKQ9?fTAMfdx~o|vGJ z2a3Fo7qI{tJ^?T$0E~(Dh%-0_-*<3UG@y=an!qub>o?xpO|K(Yxq4u|B(Xjoh_-N<9!KKux|s+j8}5 zHNdT+tzy%0_HRjyYn9dG6bw@y4xU?skd%b%keNo%H5~Z1-z9C3?zV}AwzBx9Fd66> zfU(S`{f#8sj1AB_!pS9nLVilT0K_aX@#w8pVsLTRmJRC5JEIbh)-oS(<@46ZKU#EXcvw&R)z=&h60Fe7= z<^g~mf&afvZ4k)Kw_p1DUry-dY^2%ZPOH(+Y~y|Z2PG5 z$HnK@k^Pv7hL2sP9TEsTYrwgskY>W}LoQdq{xFPR)RV3fs2zxGD24bw&ScS~pqWQ^ z;5nF~w@Qd*OiWT9@9)CLGXj!4HOv(PeIRyl<>;_;cS2)cd(ycF&fI*;C-hsuG;=I3 zpuUfnl;!r^5cU^YtQ<#a_;r31O*QUh)ul2pXU@LxqkGAdBR|*8t81W~fObL*ZCi7Xw+Qj0ej& zPU!-(GLn9!a4~owRu&W(9~-5fY-$EQXOrgmcSrF%hahEi8q&Q-yCT`eBRAyc)iiuRb}4oe7tvwR>V`hwlD}^ zqvr%<)Cpj1rms~_#DM~VTFriC`u9KEbLSvC3&`Xy`YjBjq<;OTNAFV0)Qz#BdpSml zXvVHz@46XhwRhjc{kY)zsx?&HOwEq zpAXpNoO!Iw7@k!lng1KVn;~^FSQhF5*z))dHfCJ0sAd#p5zB23b7x9LTr}dfYJ2C$@BG zyAbBEB*CIA$>hQlIR`P${5ofJ!5*Q}Z1kORj*km|w&TNbJBRhS5wAT$-Y4cVhKL^j zRJQO5%EZMLHZ7P1=DA{|MW%7LTYkB@QhAb>j`u_riCxRYgD-IE2nv2rsr*EPg8MV9 zEaDk`OeF%@S9~%-r?0GM7p&)WtmnDZHQ@BoMCzF%G~qc z?0Jhz6JH$Fg4PWuB$+2?r{_B_qEtFSsp@4--1RK;MKBRM;~xLd6T8 zzkG3w?hw1>^7i{BpQ9Ckj#t#|)wXl#XRX@v7wlA^4}7~9S-skKe)ofKm!J%80XnWg zG1KmqH&S~JDE1F`KGy@vPj-!ApY41nMSPXHjrLTcwysTBG4X%Nq73d?!nSQuJM6ow zG^h{qm(A6(x3!CSBwwnK(vnoJ`_P9UM1I=4TJ&Bo*;0YRUb_R2!hSWU9AspCw(9(v zwgb1@{%Ui^%HT5l!Ol&G>z3>?-?aHjF3f((J3C&?ej2GHf4=WRoXDUD--Eor`#a-B zUVcYge!*?~s$cjV$?Vq|b{N-rXqr)%z~>iBIZVBLlz#n4Q+_4$!BI}d>$tRQr-haw$I(k~DS{9!1(cQ%EC))W3r-``r z?YfR_@27yAjmY)yrpJ^0+z$oeuXj}hUmkO_A5pJu1YY;mOVQ>jOSti>74++MA2qJ+qit{64-^n}6XRc#vji^V zk5msDm02S0YW|lVG}{hBtZaAJec8X5r7Hz0_kKfj{366f%gU@|OEuToOKBb(a1Wwg zjkrx8+x6v`Z(2ODZTC~I(p=1l(lO*e95zvEqZs+L@~n0pDxf2UvO3gtj|kHWbe|)lZlwcK4z=3?2wkuu!v|Va586f?JdTM6 z5`31z9-qmY>YQ)${T7v3dfq3a`KWTHY}mDkQLbeL|04Wy46p4E{|z?T>~mj^guDjx z%XJ>}+8qb&ePT2%_*{2;vc6J3H-_)}@8c(Mf@M<6wZhv!e*L1*$zTW@JTJOlgihX)N-ZF*WFZtg5rm9D)CQcD3v zdFZHdIyV?+%5a^2(NnfoucCdXPkt(aTnyA+-WFi3J^?*pZfa^2#a#J(S<3S~RTXKX zPpOlQvWUj{g3WC+N(_v}FUyyjfxR?!PHJ$7yI4ABeXZ2E$tqw`q-${gqqPTr?{33b zaj$zM-9urWbdLd;?5kH6`NQh)?o(nJz6h2k^r@lJ={8Hw7vt6i4W6~CcVK>;c2O4` zO6($wMl7Crm9xC*4mXSqEDB~Wn^C-NefD;FbfO8=$KOd{Ch+E(^I|azO=ft zY#NB+l^G}PvX+%7y)tgg+`xH5lX)3nBi}f2s%-N5 zg?pu0oWs}1g_Rys4yh+P+wORrPd|QA<+W<-U4LPfaUvz@T7BSBK!$DWGH6w2XX(Mq zfb`XHy-PxGA&=cZX4WOghGw^g)8EbN^STIP0LUM$4i{ zUCB~DSk#FN>WwOixGH$0KH_Ii;zcaSVADUUMIW-VMO21O>0Z;K(W&4p+mVdJ++d#) zOO>oDiIWXpGQ7!=B5XnyyfH}Llqf#!ry?ahG8oIpC#Ts6-xI<$2)chM9*D1bXv@1l9-3MPcT~mb zknV*c!?;^qg5ewwCFKu90}gf7pUP;ZWXST%O2ulP^c%{wHxnQ)yULzq8P+lR$p6}3 zSoP#b;}o`6{QO^sFW3?;?su6MFt?mgp<^fGN%Bb;4Y;nktaNg%oRFOTeaxlxsW?m; ze+G6#)nr%gA(IA*A~h&b5(lucq*jWqyBope%uLzNiOThv-W;vhNjlIso$0E=Sh-Fn z^qX@Y-W|H8`B5WkE&xrCf$3TnPiG#Ut5R~yZ%cJYlq;;qQ(gv3sb5;2wA+AkQ8x|k zxlP8Rh?~S#dphZ(AHzCYVzt3?b9bA~t-H6pS*o&^ZVJ=9zLjKwel9l13G1v`rc-xmd5%!z!x^FYx5c9xHUIh*0JdWdlBb=pE;uzxpbYuBQht zVC^lVl}KVyn^1jSo2lDSH(w~i8|-&})P)vB6V2){RVdvzswb9{`%P%8s;qb9f~YD& z$|V;ym|vxv#Bpq6hnKRl4!$&~cGR|(wjc#QjM`WIHtL%D>qtJX3RIHSXQEf0DCJtQ z@3t(TBfXBOl(wnDguQjE&mfLP(>KJgo^!KBWxjS&k1ORgUAFliqK)XObAYxB|I8_d zb!at47W%og)NBk6MSlxtYCBn?R7alZzY`g8D$BF|{JRg)ws%a<3h_q1n_IfyC}3E- zc)RKO1w~t=HDUc$h$5q0b7f%1;#4*H?iIA^PGbiJ_T;2_k;6Ni-KHE`yGD9f@CVwZ zS2vh$Wwc9O^9m@6igOq7?at$01T`tmyu!xgm9IJRWW^7_^2hXUkhB>+W-d=Eiu@u5_?CaJox_vMZwd*^ee!U569T^Yj``bO%1I3dgF7dv zWrB@N<$Sa`SL-~Z!kv=+yWWJrSPt^ScAI3!O`K@%0xY#CCmzZuuGaR+qyKRJed)eH zt=b#SrL)a-cMf8PBJWiHk0|eo43GY z>*6%);(B4bh2@^X9hPrA>Bn!2fo3JA~;;Vt(#gA&-EzFwy@!alN49Pv>feqf_$N>X_YVq`ZUo;|!o+nQCY zo6?4D{c_lX7elGDs^+iZJ_^DW#4w!K6gN%bsr4P=Gwrz;hPNbDf@|bCopxRbb3;+b zu0)(5Qtg45Dqc)g@GkL3t{MT|k`3vgFa@cmW8(XDx`f%_qE7O(AV$#|q-0Hm1o_2K z5F--9V8YOSCLy+j{>3kKjDQ9)LBF${Se{%F{}50&#cD*_tKoNg?o5Hz+Tv<2Mqadz zR7il6apii~dTMV(nwdqOQ-TN!5iQIj%?vJI&F+e}S1lRr4Pl6IS<=Y2SKcYq987~F zeP~K%7);IR4{RXI@QY_}^Awm6rCCyHt6_89ZKOdp*@W{~w}@Bmd*jZ=Ut?=#u0NHS z!{RQ*RxA@YGSeejL-R{APIOBX{83otHmO#>ClgJa|u@7{-Hk zMLwz(kT9h#NXk>$S%kH*?!^enNUqxcAIbMibQ^JX4~}ESm0Itz4d?6N{4VM}K;X*jtu5I`jcR6@&IK8IvCwK4DhUZU&M)I+`nHTkQgOr|L8zEsq zkMHU~Xzp)ei)BXf7}o1&SB$jt(6=0nbeSbUvzs`%^t+W~)ip-@lo^9q)P0>sL}|^*N1@^Rl=*A)P0(?C5crhL*rHVIRUgb`dd6FgE2)M3t*i#qcdw+2=`LN= znQhaZER+#9WqI)EN`#C7`;D@Q!5XU4Qx9nr3D;vkD{dM0_*5-THP1K#PLuHnjAoMw zk>LZb60)xuam`*i&l-b8M3WLwzk%_z23#~6M>CTee0%(`xJZ0`fhCJ2Po(VTN7 zob-zPdgGZcIm#)vp5l}FK2IBjgJ{H2e{st2)KvH&?f2Xk$>u0`B-!K>9JGVKzVk=- zISfvB<^3z~Y+8lv7AfqMO`%!)!@Adn{hwZGvlF92WuiiS%&mS+`Cy}|U%;RtJYEoK zuk)D=5;E$EoAO;J*i_+4Q9&|McYVz9xYs`D=-L;ITFtniDi{kp7_32_&!*WS3`2LI zcVu9~=ZJ>F(OP0XSI~5Uu2@qY{5cHRb%YQh40n^Jzf<(=Ng>UTwqZ~O)DIw1WK`fj zGtpW)N;YEDaPzDEQH5IqM0?O|oX?>6*|I3E!Nx(F>9Z5n@&peqqIboNS639_d4%i2 z%#BYm!8rV#>N<&BVroWp+Bss>uQ(W^nu=?5xJ;CRCegbqD#ioqC}SaaO12`wthpJh zc7V6He`}!$_gR2d{({|5u?U}`b4zG^ZW5L5cE382c;^)Siav5c15;&&zcxshy%kgQ zYYNLnlv<0jJomH{VRuIbTZV8MUHvfsshGV|6UNOr;Q zpNsPOOsD#Z?)nZmB$Qydb0v0AH?rnjch@8y3vvC`0|lb)=uA4Qz$xB4Q-=94A2Fig z=a?Xpu`>>0`kwxIAKCBFWWIg+mdv}jU$lXw33nywz=vfK=d6CrytRXZK+PhChQ#&u zY45dn;Q*a39C!EZ+g;3CG*!oLP7~G~<0JOL@G~tzX3pF&#t?_apN!!hhVI829oj2j z&*(UEUa&ii8Dq3r*Cd85Q0v-sCfO!FBd`;i_DgBwH8&Q3Byh+A-Ekr@46q3Ci3)$F z^jI$Hmz(W+&6}%T7L5#xC+|ejDZssTh?9?}?TFywivo_jR=ecEhiwkD7T`E9IG+N{ zNyo0Qo_#==JBEE&i0L{P4i-~khsQuY-{eT%@Q7%!kM|x^NkoKbZh}bI}V<+WyqLW4LsVgLsPwJriaB;<0@oR}`{L zQBP@McY#^`izdU2V+0Py1p?_F#stCXUbNF$7{WL>RLms!y?mV23YJ=Y2oY zILJN7UgSNUEfEX?Fe&Ue9iA{fcZO)O>(PU*88za7(@^enQ8zF&_DRkKN}$pgqmMl! ztkFcO{~xf3c3FV9KUvAozGhnSzC9g=?RSK`e(+m~y?v*zIvscAG+e6SdeBPj?7b20 zg%x~uln57G>dk6_>%=nxjK0~0_VikG7!hixwUPt*%)MK5&WX zT1za5OZw7xNsNe9GDxwDy*P9w!(ttT0iWiAoW|fUe9<&myP0@rJ&y}-V>oSm?h>ry zJy9VlVBRgC3y&I`z#rN-=Hjt4v?epr*cum8owbMKu^`vT2mQwQ<|u_AmmDPQ7J9Sx z(t3LT1_=WeYll7Un834p)Scc;yW)|*KqD5gd2-DBjha<{Hn>G(Gn|9ym5pz0jJ>6lw?wApb!=_sW<<8fi!gfH6`H3Op6y?reLofJMf8jyZF=EcEQ%fT;112>TTM)7 zi-d{kwp33rtcrGhh6!d;vGSc8nr2c*iL{qZYhGl+T^6I>QSCnCeXfmj(7*ic*|kDD zQE(#-abNaLEYOcr5QFo4?MEHz4rY2-+utfa{n`@5i9QDp8M~Tnzp%jpx2d@WF*Ezj zbar4owv*QLi^yiro7HRJt9SsqUgWqO1_uK^UllMCVz_JtSPqAi* zFG$0u`-vwiz=E#cHiI-ix?;k9DL7j2gJq_Q}g3DxbrUE#6*X;n-9WGAX)4LlL z1@6aBZk{*`TfYJaH4!NWQ;s0vS-X^li;f&`@wcb@`1$r*nR0Ho0YyXYqW=T7qm;k zt>V_LJPvqOKfx;-w*A{v#^v@q0{B)Jl*^UIpkmc18h^iwAcDiIFGSAZZ-I|%HmEI$Hq%fe?3LmEm!}Zc@}*| z>fL$Yoo?Oe%I1O8Yi_iEx5$CY84owbsH-1t)?IQB5OtGdHmZO1J-^Z7YR!6B_>~~` zpg57k2=BE>?Vx)Whfz;gDE$7ziT**R(kWN-4*i}Sp6CdAV+Nd=g>}r`x$QBkK*oEB>!AB`_anu^VE81Cnb5$CbrX(zQ>6Eg*JWfW%|CC zKl=lZ2V#x~vyQz5ADpVZJE90{SWO(Uq#rk;f2mDRzDz%%NI&`DcuM=%E6ZQ6U4Fd@ z{52i(t2ku|Nbx?JdEMjsp7M?^c2<=B=*_R>ihF?D4r*6UIJVg0L~=*i!}ni^i+u3r zm&A_)Lhix>f`0I|m&7GS7>7+*D*5-k2z={7@`6#Lc^cE+_OCOt;h9#H8Rq1D+Sm{R z{UHT@6i)x+JNzew`HhxBbRN?iTB2bYZPE$X9dr)?!73n^Emx3#`6N-k83VUe!dE33?d z83i)mW6t+D-nN;qUC*YTdQ&d_KK}82e|wv9 z83#rvq4BU2LFfp2iDq;pXL3UV4F!9{mAi<>b8*s<-7k{{3_vZbDT29uqD~G363tPVu`pn-DA@G#z zyl{s3)nMVw!y%06;`s?~`74yy3%al4WSc3kFC>VRfC4U zmF3-|zP5{J5YNsR=;hQUi02**PMAGxYbbk=Qq>TzA*b?+y&%=SmGdry|2FAvnY_hN zS?TX(n)7D^oF%I7#-;*(aKnHJNxQ}n54B3eXvwD(a3qS3u9C(2X%50sPoa_HxzxQ9 zUGXW8(M&{z_zatfbR)f1?&G|75+l;h;g2)jv`0$h3dBRBPu|q1e)98+^MTZ`vHk7t z5y{%`8=D*@ob9b=y1)!uQ*Dr@kS&8>C)#STu5nzzf0#;p|DygS|IgI_U-k1pO{K^C zD}N*ZhkJk5&;Kt>r912M-&UvoznMyVzRy0|TK}-M@{T$I@M&#vYw6Yc((H$&xs5;Y z|9_hRApbo9@Xw~w)#2+Bx7^*FIg%6Pg&{z$o~H&EBzb%|5sn> zzk~m6v*WG*W-9HSdNncn;^k=X^kB_j$p6^CA^+V?FS?(1bu^DZ%b!fN?HC*T&-!`i zKa`~n|4~0Ltp69}pXw_ud06zYq~zhl!atG!|L~P&W&UUV{J-**dj84#8z!cyMJN3; z@1GIw^|!M0U+U*~LVR!kf&6><{Glv05B3l9yyfoY=i=_|?CN#H#q-~Ie{*YlQ>*J# z*q<6er&9mM7XKkDrSkqdhUS0BO7%?Dbd1%su`>5?RPbLiAW^`Ni1v>EQ&}2!SqrQD zf0mX0UzOb;j7~=2x zxpQ{4+mq7E&Y1i-nRnRo77^qBr2gaBiJOIIoMchRWtr9!Ndl& z&y~aVEQ*V(UL<;Ky3aFO)G;VKs~BkvIm;?|POeyB^wWteYMP@GeHP=fU~Sh(Gaq~s zqeaJD$l1m1g%_a|mHwTBE)>(mjRudjd)+$j(jqb3?T)jA=lr~UYp05S=2r2r>8gca zOCMC7W0%kO`}l{cR4=ig^*UF4F@$zIkN>d zA*}{}*%npTr9`DxYUKQ_YlC$Jjcyb`r1@N`e>KNk{;D^suNepyJ1V_@d*5*Hm4g+x zyrEntU^?m~%p@eF$~!AEr*Xwj<7GDFlvs+(8TP4CHCTZ-5QqG#2o#u0H#jBXXmbRO z1ltry0jSqXK&DQholp)t=YCcFEHCsEMo@f%90s!$ zPjP23rsMz*7%N{FW6n5oqRy!elZw=d?sQkx(p*EtRJ%=t7V~MHwUK2s-1^A!2n!Es z+ZA?QatcEw!Wc*UwW%nE`I9KQj)v+Tebgr0ds^0BUwe503?XxxwN9>Uhqe;p;y!h`iEUhA$tR@5&S zpp?{U8Ec!3_B=UZE}^E%T8&n{&7w{t5j#-QXt1EB!D!+Cj^T{1=b7biYIk~^zR#Cr zec7EnIG$!XZ}qGozFwsAiL|QBNsZw%s*2;}$=-w)1zVCWN$fk4&PuW-mp}Bj?ihC8 z`ms;G2-Q%Pp1M1^hA^}PT9!6$PVT-9df)J2?{h5h{-sE7sQ%1qiPatiFTJGs<|Q=z z;BYnEQSGez%MR5l$!v8IO_J^_X8u;z=yvi~{-{B;BeW$$RjfpTJ`Bn)ZKJcw;|N(j zrEwc-+}q_uBObLQp~HfIhfykK^dyakX#w7VRR-EcjEg{Z9K3CTue z6Mr}RDY?N|wmN=cL7l!mofO_OZ+_xkqQLcjz|UBlKb$bsPiRipQ`pPU(TBN?n>A+> z5wcCi>8D~-_?0dY1p9#rB~nq(^#Xl4{@8T2J5y)C~|Z0L-}`JNiq8MQSmK#MQ+nBI__jc^NkBWPO(! zDyP#UN6>7z(Hd5$aSoH8y{Ze`_pHzm)tiXBdQi+YR-r}NBPWI&JVY~AVvwd`nl3r<(0tyN9yO38LWk$G@R5zG0_QA^%d_oPW#rqebuT^y6^iDQz#^CMtQB% z*o)PO?)nxpkM=iy%J@Zl$QWt7rO6%&E+Sym&vGkivyB==`}p=V-KLE2n~?B|(OeBOzylTUkzunnGNx$95_Jv^}` zJ{x{;@-ac^Blmsd(Ri3+!cc8Z;OU10hk9E;NQDSXry-}T4|rK1()9)7d2+Pb(q&$w zQv0H8=zAU6Se+S5%mc?-G|Vw8;mA)ZC1^N2b7?u&>{g!B$@dC6cS$hC5=x$P*-#?; zN88^@LW=j-dwXUw_=8!XPFoYE(MsH_GUuIQ-zvYs^k-|}g>LZ7&iEEB`2#n)6qBXX zuB+-4W!4)r7@OeV;pvLA9j{#Fm&qIt7aYtx8Z6ZA1dYpEX)#)lms7W@fR^Wy1QL=!W29js%rnm z!q7@L13ludKD?_TCF(?8P9lc9WA#qJg!1z@)1JTCi&{0HeZK;!lUS40dJf&f%!^Bl zQ!^*mrgPDq;GmXV)`^&rpZp4d`Ounb(v?Rm{Fd*uB&F^aa`6$Cu2A$~*#!u_a1=iTv&(#w|d!14WppU0~h=2mjdm4o7w|6D)sxD)ilxcD?jRo3)|OfBS1 z>1npdG0vMkUoTAm7xi;RS5P4+uJvRw$oJ(>8&FqZ#|IF{BAiZ%hB^M^+OHkQ_2(bj zWe>aPczNb!ls}4gviCvIpc)XJEYEh34_g7(Jv6P5mJwjtOv6zTqbX&vo%rVY{7HCl z`=%uy!|R9h2T!;Lg>{%i9Jwxm(>Z;b8RSlQHM59h(t+6EJx4x4eJ7v2Y+vI?g`5Cg zKFrC7ioSmKIa>&XNCrhwBpr)_yD^>LYDkxaP8g>^buctEMfhWHbTIy4@%N!O;WytR z>8m0Q~^l~Xt{4aS;BgjF65+~-7*v%)47@3nE_Iuvox zW?)Y-Jaw8bj!d^TfX|Wv%F06$vQVVJum;7*I?FIUROD(_NLhL4skKlJPI7qE9hA%Kut5NeE*sSv}?g2fln(MtwVkA#Lmg4eP_pVNhO(s3!F0Y+C7UM#d1 z3)RrEjxh!Dx_nSz`X_}^wA27N2$5wECt(32SGZRZ6bhzK^@*z4iC`}Zu2YPx&I(DG zAtq4{i3t@%>%$NQI4dbDjE0}y4<9XI4(TO>GhavR1fim}V<3ycyOtoDnm8IPh*J#6 zTMZ84u77 ztxcY&02Y)21LzQe1LmPtM21Diof$fe5*xEP5Ojm3YVxWgSh$1whFHWNM2SRDYSNU4 z7=)=wbsSJ2mXi3@d*C~uSd*AB11tnt(CQ*ZVu6A{`g@pk#fjA3oz%01_&8A6gW9p*!oL8uBhq>Y*{yP1X~<-PzC- z?h+skt%ZE@F+(WwG?O;VS}I8w(XUQK*9o$_M>2d0 z)<^-UkS=p2b+W+c!C~wJc3*`lnOo1qfy^D|n3`M|D*dGleHs?LdcR=T2LW+l+^V5Z z+c`mY14!16;RA^z`wS9{-bajeeio=o$)j1!ITa0T-4~+qmFvea37yDgOnD$2@}TU< z`L`-k%_O%m7`cH1LG^%@1*V~TP+1LA<2szOAc6*%*{=eeArAhB!K$3aG^i_w!8}e7 zaE1NDK?^{9!Mpfx*S+feR;SzV0BRhjK%TOPBvFt@rvM zb})qlN6Kvyu)R1OwmhKadLnT=kF@ zK4qaAz^`Cn84ckFXnJZG6)mzed*}kL7CKH= zD~XnTAW>%LE-|!mIZm!jHbqq?M}S5aG`4`MMU+I-fjT8NtBHHFY3fSrMtsVyLgp>5VgV#$~P&Rotj-gahQ*2N8Aj5HgVq1v7vC@uYVF z&LIxyBcAl4pH#l4qYw69zu@xSm#4UpV_p_Lq$X{Cm zj(ZGsKyKI2rxYSjNdf?+ik?*u$;41wVIIaB|Kvq$Mac@!E16RYg&dC;d_4tts)ing zN1yg0vdFuoA&qn2U>T)1>nbAtsIcqWR1Od2ZQ3J}+=?bE%`T(4h;X zkJPr>Ee&{i&&;H#dv`xb<@m_&Ge)2Iw6DCo{D4`n0vg-!nCCU$l`2MZ%_wkN(cY54n>ZZZGE8ErsaRpcHc2gzklQJOAEAx0%aq6 zls#m~l39k7y=89@5R@XIs3@Za$}T9#lqpNLh=A<9DN{heB11qxmWm4Y@cG{3caNOp zoaCIOY1*b~-sxYxdOfb^EA$W~FWoYk(D_S6;qw|S{2HXCAKqC&12lwTcnhNA09!<3 znzb%o!L~j_*ueYpk*{%6(!Cx&orKZu8RP zfE@nZCs5S~;tOOT>ltSV0-N`M10f{9>*z&e^XITE>HJ|hP^SxaQa}^y+QeCDQSk@# z`eSR;VQanLpc3HycNMtWUN0?_Nx)yUw-nNKB(;as86v@<_v_IdR5ISb2L8ROZ zKC1W#wVaWPpTltbWgQwBK&KhqQ3Tz*H1vH7V5tCR00$PC(OId&Ckkk1rJ>oEgW+9i zGWTHLy2>z*nyzj(Umi>teBbgy9Igwesiuaohjm6IGD#}aECISca8PM&q%#A`ATmh^ zFKzp4<7}4w&Qb8G>+oN{U=EQD;~6RhjJRgS%ViYjse z#Me`iHwQ7J5mM#+aX1&f2($e-{aj5b<6<=Pj=9odbKibk)(UgVDSQ>m9v>m{cip3f znQ8<-u6vJjSY`>J1B>%mYRGj!lLV;Z3Yeu}^p`oUzkWrY+T;_5&^TAjHs4V_52`l*F$w{>bq=;Owe&dCn74yv{j&mTb`p(2GQ10SRKE7EP^QX6 z>M(4o!4cDnV@L%7{AF03?wANm)+`7sfbC0v`kC|zSojHa^s#N}6Pq9rz)b{AFr)q8 zn)~K{PG)E|xIFi|qB^Tehq;=G8Bz+aZvr#qX4{`#)O(;&T)tjv2%E_T3EYBcp^FB;X*Rc89ejA1$cnj|M!b>+rt2E(hCKJ9@DxeOpfnt`7;Sawk$x&9F&Y_>`0J zzS^$h*jd}%5|O*>!5ZQPvEV*z2|BC;z%2$HcFDUpm1JqdmG84jZ!t%c^GSc@_xhTe z{56VRfH{lmz8ehTcVCUmf)2jSZVh@eF_u`ct!Uxu>>SYD{Ll1rBKN^(^@9y5^UQ?( z&6fvkYhQO)540u@4!FM^tAC><`*!;D+u6%+zdOF2uYLm^?ftF!ronx9B-QrAw_vf`Ea*RxU0zzRXv3OZhG4Q zxX0v=khgvA^`jTsUY1?l@6+{eGm%D zXwvx8od3rxI;OhjPXPF&BmBOE&QW*geXz^6U5z&bQ#P&cC|gbA_}kq2K=6>Ygj#lee$G zBdbr+v;GS&Vg?|wY%=B`8g89`l}azCpZ_2ApJ~4Sztq3i;LQ&RcMqT5g1mJ3|Em7k zt+ve)I%!9ES>oKf9cYzB1=+24ttzemQU7zd>8ll!*mbBv+{&Y6!P9%$|C)aOkNW?4 zdo(V5W3@lW=9_cJlMCm(;5uHNH{t)L{@n-ezNLXJj}V(9<52PgxppVFCi2uAO7yBk zwI6*{|Cjo|T>z)N=f&mlgXF*T_6~+qR=V$BrBccRJ0$vZe-e-0OUGaLw#M_qO)k(T;C6b{McXlb8sLX)+_#zweN_cJIMfbrH0%aMd9yfSPz@DVSeJMwc0* z<*I_wQl3U zMpEOEn*K9o;w1QG{;u;L=yLjb`0JAbElg!9o7yj}*OPjRo5Av|oh1g^W=Hn5m+Jpw z4XufyWBb#HB4QaS07jvv_XOJ3~ZzF(^Ukc7Fa4vzF{ zaI;vtonLMLE=+!opHR*~1JUErkdhbGj|B?YGkpN#LA-usk|*OctrGoT9n zx%ojLEPT%pMgC>9a`yHgT_rbMk9M6?OGa>Jxt+J*gy0J{G0MxKn;D~eL7SCF1J#t* zo0Z(8oJBa?nfUbBl3nf^Zn%@!1MQx3P#N)NK4`L_cCP*G+LA-ZpWt0Q!{1yVQz6Ez zuo{Vi?2j$2^dk=gdLQimu1zui-rtBR<%X2%3=N;5N39tS?+h^foMTJ6 z3T`hs`FnG0FyQe$$>2HjxwiWLJ5*sIi=^d)L?M+E`n{LAFWY}AI}Gl9PZ#;o9x8E1 zQT^fOpKQ9b&HUKa${BM;XTi_KgMX0|7eXr~o^QY|{kyD;bpbh{bQ%{IyQ;;1CjN4D zKvZgMI-h>M7QFf`Z(H&B_8;p83`t2|eE@=s_|O32eH4YGP{0er!dy+r7s_|4Z$0K) z`$W37olCMAE`8Ex%W5FhjAW4YRtHNE4cx687@DLX>d5A!2w$|Yd|uL^78uPN*-oY5 z5^1HQHIu0FXM9^FI8DR=U0@MTuccP4LV%Jo7*}^kwO1->#Kk)omulO8H~ySqG}pv7 zN5b7R#zjXUP^$R~e<7UTY|NE?GDK0?nLH-M@g)uZNce2-R?W@#3GYND*Ug&_t- zk`tWWgDOkN8gRz#DezPgb+hNo)f7C@JfdH$Ca%ysHF@Q+x0zpgi-N5L>coe$k6W0f znPLz{jN*TWY5YE$x~qctQut!z8MUD9*a23Q+mIR$KLL+=o2RA_nzz&<+=@5dCKjY4_RvdHkQ1~5;Mk>R43-67i zwF6YD2U4d0YI0J<-^?rg7cw`0M+GL^&D@ZUisM%j8u%Hkx-nt)qm8+nB$1k)$WG-K zlL?DV3VP9Y)jW*N#Ohe!#vbvrXqou6o}umBTVrh859|VlLiCllIE49SnB};Faa_xO zw}RsoO}@x{^Vb@I^Uc_~#Z_B8@{zlxApiqCLwWNfKyHXD(gThd2z8dcmYn5vzJa$4 zxz;DhxZE?FjDvdsx_hIMY>h^b)yH`-w@RhO`%hH4bq9gA!s;nNw^BvGK%-)g`3ATz0TW^~rXhzook(Mt(p^@y7 z^pcut*liXJuLfgDJarY9gEjRVR65@dN4kinZ;x!D;zab z8gPt?vR+%h3c0?>Vxj^8{lc67qK$g2tSAw8*AG-E2Qbt}#u8P<(Ou;LZN8metSd$W z)k)KuA|m~wD5s0xs_$8ywuC>1*%L>di8pG~HjIm6BJ@6oKchoX+IV)GoEK35@T@o> zZA+9y*X0d=tdv3xf3~8TVbK>C+uM)x(T#`qz#c}DKH``{BhQ+3<6S|Lp=1_V1s>NM zc}kc7H;i2g1TYna>cc6Z_1s-Ca;}5OHPr`UH*j6O0c|b((k+44;!Y2Hk{2RGAX)`z zj6C3dgz7stP@bth#5ubPL+DRI(UGD~J06cgBsg`8bL7HxlFF87X;WXj)x%px;QOvp zDgGQcf*_%m`c{zu-kGEgbJ3{VZ?V#fpSq$j@b(w8P)I~l@^h}v>yX0hkQZ$<0qmOj z8_-pm(l2hqk?7Z(1hwa$BZZngG2}c$7RfdhBd>M1vJf$}L)-*@$|?35Y)|8Q=;e~h z@av)?LxbFw&*(cuy!D&W=V!fb%Q*6KGV}G(oQ2V@He7w2R*z0xw~kSKX5mxEv1DSJ zLD*P)n!ZXGS$ob{0xCOh%qT%5a-u43oZR^G41sYysGid}wVY|fXgr2Uwc0&4KZZl6 zjmP2j2dl=HH=v!K3Mv*acz5vf+36LEx*^<^AL6ZH+GM`V&6O*GyNyL_q} zOm4DVGLftakWd}mH^Oa@PbPN_tr1Rrv<7h6c?hDuR%CbeWFERAqHw)+tIIt$z$pWodQbUq<^qKr2r*RWLh9E zS^@W7w`+nVdXJMi)l|Y5>r0$|3I_)^$A&FLMiPMn=@bgKs+tP~(v&o~aNOeZ8~{2- zi8&T+W_5Lw0sx5Em&WuvkZT#$OZ!QFRf<4Km~xQ=w0vSBGr`K%v*xd6o&d1aj;hjV zkRr;G-Tn>bjtRy`C!hSXhoi(0RW+qC{OJ^aRdxEIWVB-@O=+1RNvB?e-(S2wB_fpFr&-KL54OHz^JrL+qr z1K38$NP_qiu#SXMZ|YhvPsR0?{$L!m$zTB@!<%(o*j)B&I5m*E_L`ogPDHL-b9xd!F>)7l}nmsJ#dUYKf6ZKvV7eH_k zys;+DO#xME(PEJPRBo3ZYz3A6j5(ws9S%Q!=5S4@!7{70E^H& zbhjxW1E6B)xpCS;F%P7pbvu+@TG?idlNg@pQ==)cxM+2vv-;WU(@=*{X$tBtWfxhT zJ1VBvm_|OPP4elwp&0;tBPN`%7^*};4Tzwfh%>Nr5-o|eQis?!lUb+A7V#a(+)j$|HRgAT|YFLHB1Xv_;$rF_#mZ(#>x* z6?kf@LxK*z4hw;a6r>1e$bpwn9{y9LD{%=!j*XyTcf~!b z@yTu8ei*C`jqr8{#3s@16q>o_w?*O7XnZW-4&3B*g*id!ger9JCy@*teO^= zuLwAO?D-11y5(9=3%x4x^^Jmsl$j1n$=&_X{ap<-e&TjZO|)IPjc6Nr-2B&^I+v?m z4sDWttqR@WcD8#I{Qp!pHPl2mDztL&Qr;c%cURiUkMYj|xY0M;_X}AnZtq(7f1O-~ zfLX})zkjvEQ!tzDlP&=yH_nc*T6P~qTI?w4{tg{ehg5D+5?}786IW@5?ueKBwodF2 zBoF=sTWxgQ5l0hQ-&fA+LdP>4F@%GkFdB=$Pyqg}dnUzh&0QwBmA-apC?&We#uOW$ z7<=|Ehwa;O#u}5Q=$?Aqfx-rs7_ckB8C4#iUH>h*>F#TEz*$KG4(*x8i#|~g03Z&c zGts-}C3OVh&gpN7fE;mn1RXe#EJEf@*g<;pVTlheP#*Gq3-VLqXy4%whnL1IpcBqA z#8=hF=KaTO(1#M@PNji)T}Q0o>t{``hRYKTEc!*po`FZ7Iio& zv@?}R=H5)6(n0?0el!~{a+}RRMJPsw2ggA;GL#OM0vqd^`b0OAS8T=D>Yq&B#U#>> zy$_*4*>2RuQ0yPv{keKtS(6(3!&vzXmd*!$=G7d;^l9uUq)LctUB37(I>8QmNF*+tIb`{`%k-p_EJi3rxv zPkV<^if16*vt`vw^*>IEc@X+Z;s?$~r!yxs{y}f^$%912?l&Jplf%3GDIPL5X2uXI ze{uhMp_&zAb|r(p`g!L_B^5f;d!*I;h*yI;`$2E3GDoEwgyqApt@VdPS8)23M+H|^ zbM$_a}7wTWkZz)wAK^~Ii_p4`Zyo{ryRu# zUV^@vguWYuHg`f>Oye5Ef4?96)Ar#{``Wg)aC;Eaf(>qo6}s{OviuFQ_yJ)e23-RSMs`-ODy?_e{%y9c-ui;u2uN9- z^V=mkB@{f(Z~oi1@K=oN8|RzJIbJW`FSzW!@`xU2j(-)7H#`x2^?Pmdx7yvKPr|X% zBe_1|&zi$?he&A)q)hTKn4m;mE@7+cN$rL`Rx#W=Mf_RNVcSf*JQ+EA>H1Qx1#Yi4N|5cUI*y6%UqM z#d}G#oL_HBn)LL+Na==&cNd4!ge`0Qf63m8+rZrk8k2i5Kc4p_szYq)WMVqY=FQ#x z-|~A44c;>~cm60`e!zp1gZ)2>hs2&(#;bSFm5w(?UdRO;oGYJhPnTKN{!9HYy$kww zaG`Q`_<8Wz)quaMzfX5Ryb1XBSMB`LlfT>2A*nx&+dMw`ndBd!6AoD5iEI(PM|6fP zVcE3=5Yq;c|E~Uh@@V>=&(3RaKyDBeSmPnNynO^r60bn6t^qPmRgRUOj!)MtMqo+A z64AFXNYu{rQ6eC&{s<9BedDDK6I_B@!laaUCOn05*;Az_bY|g*Te%MhSPYQBkbZY$<+a(7*hlPQQ;D%+ z*-ntirWTPBkej7XN&4LSF@#-v{-5xlhW2r z`%nhZc2!Hm4LW7c>rBsT3e?#p>eIZ2;rabyOO*}dX>ar2Oo;_oHO}4DDb*6dv;GI# zM*}20FH`*z{}b(B{FCZG`1@bP{-6IT_BSp&{l`cDKZ*VBpNrN1A@)D~r`RX{7qP#- zw)h{-{(r>&7IALl)7)jP|MT+9`qI$<1Frw(zj6Jkl9RE_|IYP8_TQm*8v=J5(Ay1x zJN1{3@9fn1@6_JfsdE2PxPGG z-@j{l*U0e_1O+$5KeRX|p6~4Z{x~k%JWm#qUtBTUXS0#m)V!ybkAhE18 zur$9QKQAXIJ2Uf=?WgDbw^V;ZTwFXZEi2(^8-i-Ar-~UgvZ~6GqWvBoD1=_cEFtKznGPnC*Xy5$b(7sqmGXK3eL_qAn&^}H> z*Yy8Ov~S}1pQ-+}%Ozf2K{p1%DCRg+S9lqV5HQF^)fe?Au*tD6lY3vHeYB46zf%2? z{HFga)$jdu#DZC3d>#^= zic_Fs>6s$@B^}J+C~mgjuA-Q7n#wuVcTM{rtvMY0TN$c{jc8tRpK>+68J=V}WZY09 zC>>#1q2lC!&E^iV;ZkA&3y;=m0{894tQ)cL zYdpGq3QT#?)bt`|@mG>Wrm!^gJ_1iEX;1BSAU#w1G4%1<`Ino~R>PXg3c>m*GNSkC++0h zg2Gyqe|@i%0IMOl%yX+eMKg3nNmQwopy;KY>Sl}Ra^y`DJ$M%N6yz&Xwn%>0;nVoM z7qV9>c+aYV3R~$Suy2=knefT_+O&M^xr3ZZLsZ$V3F(M(4l@L=)p+_s%^x$Rf5pGG z_5HZte%5nZf&9|Y_$|Bh_r`&?89%u{iXtoCOtgb(wocnW8Kmz4o_t<-!{X_0!8Ub@ z-&f5+U&N1xU~>fo{9qFHOWr+Q!?dS+FFk9uk4>H+V}%G zS$X>9qtsLq0n4dzJ#7UvMf#04;nD6>T*7`y@V+Be%=WC5lK#%kF$$+A_=V&@XZbU_ z+sNx>&L11#1e$C{;+}laa!hBiO{FMIFoxtYA-hyh4l1CEV9$$^QV_J znT`Z)TOg8us8&V2uXLN2>oOOe<+>9O*~~k9n4XxEbDGTz*I(%qDE8rzjEqu$ab_VX zFFS zk4(iKF}j6SGU<|i!JCG~GL>|dD^lO%QBn=&?VwM7i%`Trr^5P_U8%@y*nr=8d%{dXPO+BOrM48n~AVn#bd8! z5iH1rXpx2Q)ZLoenW!c5s=InBkrh3kAZ_Ub?L7~;=UKJqzD$y;r z$R>7ZyB4Z!;VRkRJeeL+Plp`+D*ZKmpol#5O)shkJg{!CeVfuBDoP3$Y=tI zh|!Z^0c5fPfDsspo^E%R(H=@fa{Wyce|L`1;(nzcl!;zr>lFkx02!Ww6P@T`hie{0 zsgI*D{#0`Idx6H@g9lO9{QQa>~!rL>4R15SF5 zf+xJ6ApP7wVN~-18ys(wFU)RzvW$Xg?cIp%b6z_HU?6KeWpFI%Y=!tI72r~qiI?Y0 z<3Sl~WPkD1=rAk)gg+V8F_&HPcab`MVhHiPtdqc3^d1k&2ciMgK_B!uw;+YC5kUH& zlP?w!B-Iv~=to!4R&%PMHJS0qC-1MpgXQU)^lZ+5()|TTY`&8Q2S)Z33;fVC&Fs1- zCiEnsFG3X@iR|WJwT9;xastvI6#!@~Ks4u&D?W`{eaJ$TUXF@@HCe!d3GnDmRR=Bj zrw_E}1lkT>AT>P{e+bYN!RjcXnY=(4FnBcr`mDq^lVG8Yf?Kac`MluVN^l$+-ed#s z>b^;Tghh8jO+@JX0{P_YsI_dVj?gsJgjmYJ*jmyigvVv7$WqhEQ!APS7YAJTmse3Ff`D~JfoEO_{pnV&b9^%WixUJxfGCuekq zHDQYe%f$C0;w`nK#eLu+N_5qhi01NyS~hF%?T90<1YY@gspF`26g=NHI>KFrGL`=( zL&TWv6QUQ0Q8@h6D+w4V{W=g3`WcrK3SY8dEx;v}h(tFF!0!Y>{x%D*U4x4>$N&8R z|HhV*Fb6(VO!(QKOmD%yVvdCrLT_ZkgWavJtjR8YfwMAD*K0!K&{RjRG$GA!hKFz_ z-aZ8W@YY%iDPWQ`|wxy1Y!Tg!z z_7zJ{U{ECH@ZCc;bN2i)OOq?C$4b;tk#wtPPD~-`XtGG}q4cpi2(TN1j>r&l%|H_% zAPD#}r5z{=cm2g8qnP3O%ie!6!?(gWX!r#h4fcU%qRn31<%8~Kz8KsDlXpWN0O(^{ zSc+d|z9SR3Q$YPulWwbyT839QQ96^nI}@9g5v`vk8Vv0)PrC{Pe-?g-FbONET+>8zAspELro-k0Sq9K3j`PnGIFL)i3hd3XnQ8{`P zgrnfac!(S*@#zqJiY=Kul}`i`5qC&e3xe7RPzC+a@{h~7J)ChjD`!r>Kx>M7B@VtP z3O^|UEFtb6TJS&bDW))giD0J(!*LaG+y+Rh2n|WbMA1did?3K@xCweLXsv+ru0LXa zaoLihc=cG8>fjnra8XGOQqpumOf6gNOeCIuN)X0mFZ!GMr~oW#3wPm<4U5*sw7hV; z&HT7fg#_e;RVMJ0*7)}YsBjU2g0d2^yYNQ-BD3p>zfff?N9-%HQI&YQ_<~%jLJ=>p zHrBrUrc5a)G70dOPl`ckg_WIIwn8jZ8Xb`Wu%tioEuvnlKm#I*h;$*yN~l|9r5GxL zzO13!TAsO_((N^6eH8_Lv88O;uV#2}*2~5tI0y~>TPH9O46`ckOk1<}Lu-LZwGueTbbRei3UFk)I;@ZbFK1tINGJBbfv>y{p;Io+QLkB; zPnS^{MCyJft71{n`XvEtj0Tk6N#I#OjJokyANJ=R?rWU`2TMqxO-3Qr#cx*%xJzPOM&wtPGW+Jx zP0%F@d-v@lCQfV7_+&1RbH1xi0%rMK|y?XqyfsY~6Ix&4J!L8Vuy*jj=@jl`~ zfBPuOGw-HbJJB#>)55#Orh|U#4I0o0>h{^?aMtJO6j0#!9l5RtB=W?Lo)F%$Ts>{7st=dpBRQLjjj!~cb zIZ8H>`Qzh09C@Ga(Muyvm#dupR*wBQ!}@J=`|aEM9hdu^bA4Sn2i#Q$JYmcxjsrfq z0}``6w>h1?mj}?CgZESigB=I&hYg124nArd3~%fXGcvW9@(G6xac9GsRELTYLvRvb z7fwR|Ai)g6$Cmx3D=AkiK$SIR>>Av$JKcXcplAp<)tQ&5&njpBP-!F+%kspXJGM@M z6B%Bfi+mx$oh|27/RkG8gr=E;t>F?7Kg5J_Q51oryt zTh)!Rm{XVnz+|JmMn*_N{_(V*A$R=re#t)V?cO~E+u9TY+aBIK>)6^tYH*hJ8K&3-r zUqIM!q_jtm3A&Aex(P$DDHa+%ZW=Jqm>>~2#-T=7be#6oA@Dz$mLZW%0Ncl)lB^xD z8Gg(ZMd7qOa%OZ7s4_ldNj|HzHl;|zs(WYlBXDwCVpiRp!UF)duBI?0%%ax1Oq`T9 zB<8eaChwX9C|Bm9izl{?rf-l<+T5A9-k5SRW zlK2&;iN{XNPxqO-ITwCeP@&&qJh#j!A5=4^s4eO~pMpJEbTVJauGYq= zQNG+~PIK z3a5Ifg1zL^Ff3W|_N)2gTXOX5Ff*iirw)}Z& zS$ArJjA`Yg+6vNqWi^Sh`p5E$Y=0oLztiwphHOD8nd9M#=#>c_^<;gTTiS};-1^))L2!r~ zUy2ghrXt^_0&-K{ZIk?l>0uQG)8F-#sLugK>oVr^&Z|O($s8N7Es4|xuVfy~_&W8y zt#n6db$2D6d}?cj!E>TNcvMSUU9-h;fSYfGk9@*iazl`G=hGF$7av;i?T%3;4lQYQ zZtn4ID*El)5)2x3J2~nG8LL|wLEAa9J4{oXe}X#hH!-9>WeAGtK;xH7)|hH&zj~xn z7ZIS%$zMgR=31h@==XJ`NJIk3M(D}*6jOZ?6k>%V_qvbc%f=+A$U4Q5+e-EJRAfZp z=@)?KZp3K{U?=6CHlyGk!@4@-^f-LX1liv%>CyF7pnFR&_@L;B;h38#HnHV%H+^#% z@@t3WlDZCQ)TxfK`tQ^ixzsKu86G5K6Gfq+aO9yZeG}zX#vzo}#Y=ILln&Wd$*V_A z3S>u2^?lEZopK5wB;Y}?f^BNuFpTV2f$W`4_fRe=XnZ?K+#AiX{8!_9NBwCB)6W`s zQx%+76>Wjsr#w1Yj%w6JB|fbRGY6KV`D|{dw)H#rdyH0o;dczjq9F3z8KAlEw2)z_i@wE5LK2 z`3_6>uOU;Gu@rIG#Wpx_dGf04wQt|(*UmqX=vbRRNj|0qTILva*VVqP6Ctj=e^UMIr~H#q^^jW(*;c*-!iIVLoR+19<7L*>HHb(5 zr1~9qJh?&}zS=f;xlCh=`}ge2;@EGoE20q&ts(oDXrHyvu$|BASRPgIjhL9~>|_y& zE3oZJ;?juWv~#ztNVBGD`ggRiaZ}~wq*uJySPv0m|NZuSwfOWk#-+C;WQ7#mf8XNU8}T2bi}JL6GjZ*$Yu`lTGFGnk8WC@4ikupACnS*0!uArUVO~}StbY;Zgd3t- zjrDR9Sj>dJVt;D9Jj{Ka)f25qyq72Z#H?sg^D8x)l|K#@zuPiP(*`1+q)s9hCC8K zq8F4r4(GH-T42rKwBb>TQT+FUR+nWb1AZ@4RMH6eck6DwEgbjItlMN&7?AJ!xVH6; zcb@g-cbDDyp3B{1=Ucee*Q1!5``qU*B0|>UdVaCz#S6DtJ3d9oG_7irYd-@BA)bKf zbK_(c>BpLRRSq7bP8+v0sBY2uZS}0)$i5dt`XYm+*>UJ)pDu`z^F;Fs8fim#K6FQi zQTZ}s-8^2NbVg?4+}IzQvD-qP$(OJBFebXecY1P6ySiER>|IQ!nR~cQ5Kr)xS`5)j z{k#MIqV$z6Yn=Se!X2Vj2r#*^eU{zXDl z6AxJgcj6kI(rod&4&y2rc0MT$0*X zu^{yJT^+xy7q!6Nnq0dyw2LnniEm{0Y$R$@N)r2VxBY>D7bjBY`7Jh_D<_>uJ^-Q; zNkk*aIR^{+HG?<7CNOPI5-%7?$pFlLI-@DllhZC$#YpbR&jE_l)3}}pM-%y9g9@WX zn`P`DoP%V(Hj*|pb;vGzHo*ft`dvapGWZAEN_@+QfymoP7~1t`-y&L8R{j?sPF-0T z3a7YE`I+{u5Q6i~nG7dex7S|s4=xg$oJL_i-)Z(ker6F}6(Vs~;qw2sPmn=HxD5OT zv1l}eHdg7kOiH+wb}`un@}Xpu9kxqX>gg69Y(|!X+OMv<^Kt%n@a%bI)?NP_z)L-rLxr4^KrVsQtH`wd*WoiJ_v&0~C=I-u9vE zQv|4l#K^xB*2TxuuBoNjo}G4sr9}DiCk}Gkr}FV@#HU}SeHzQ=c=w>NMo_pI=XNSJ zm&CP6w36}-b`yN8-ZJk=)96F-gVY2UPO|mwpPFrM#5_!H>yZxy?3OeBfiPk3AJ@V>qV~kdK|Hgn+ZqP^KYr-}e zD>jh3L0`w0--Nl8Da?q&<1v}-yq_18I0;8_5Qo$CN^#H*1Ntzej|Y)$7b=d^duNQ(f1<{U=*Y@jZZ3$1i%_cJ zJE@;lx1f~w7vwKSAw~p+fG%=!hzc7n*2Ojo)K(X$BpX#wcX&qc8`Kpo-5GW1Rv{{b z*&V)yvPyLtyW6kn8*z+#o$9{(EXMUZZwc)dNR1r< zIh|<_<7j0uq7&>>;lqLg(Aa3S#H+{khdxq>=MW)Ihzz;*KB`sLAE%yqog|^tyQ_5N zp8)Yt`ccb!gDKmN4?8;_bJ&JN!y!KCxqmCXLEH=n9cTNR>r*{TlK z`3wOl*y?C<;v8H-2SGYAh#u*jz6o?>B|oH~LGj`ZnHB9kMS6l68@hl`BX$ zl9@$-@GuIQw*Gjlq=YIUfPhL~*1CcK;5l)Y5ugSRT->$cMV}1&0^p$ia7I`ucNkS> zm3}rB6xpUfFa08KV>oFH>0Ts%^oEK<8t01zRj7{4qej9U^re|bvQ%+3Z3Z)_kw;?J zH4La4XPWBHajcE;^)QhpEXc%`JRcBksYGFm>qFxy-m6m7Ss5m>#W~JUy$dsZqdMAo z`DW0_zzMVmFWtywV>Qw*c>L90BOqB4kcq0XxCnzNTg@+MoeXJ~Wm^6Wam;w41BygjiIE}L;{KEM1pCLR< zpMWrl3#}LQfc$V|Q6@;^FIAYO(f0l6r_{be#sQ4)?)!mOzp=&{9IrivpQk%fKa zV}wb5PRe0bGrSpyvfTi*KbfjC7!``m#$wFs$X;I?p;^HJ)Xado5F=ve1t$dLWuDw+ z+J}f(rH*D$o4N=lr%^Mfc{{~1j^nI00&athLJ2(bIDY?$?2;*dd5Z+IGO-YHwrG&P z&orYTM6!BH>=neh)!hA>j))|Lq*q54Np5LZU@o(nlF(w#LF{xpH2<4J$TrfGj>bqu z&nQK|)L^#CK)pETv_dj>Yg^AI5C(KZX7!?H^L=JfuV$k%XAP=nb^5K0hXtnChtf?0tIomzYo;Ht;3z-Z!w!j<3zDQ+e{JL zOxs2_JKO(@w)>1~YEctD9w3200wna_L3)#3Lod>Mmo7yV6p^Zw0HFs21S!&`OYbPX zqx25aI}!vG6y)WcbIZ(~nfuO{S!;jFm+Y*S?3K0m@A*Fw+R@1AXh|^eCf8-|ZL!(g zrn&3^v#hzf*TH51pm{X;d?NdNlIZ*^mHA}j`4p%5)MxXr!{^gd%+XmhglneOrRKU} zI1jf_Z=9ksWWiZm=5c_9QkaFR-w>HlERhy`6Pi%)EWa0lUpyUEs0}S4#4iI8ywgTm z-qnd;T}bBxx3r4a9O2h)!Tbu1>)BB&hu{Wlg2p3gGd%$SvO^|pVlHy-R7;W%`|FdtZ-$&e&wKd<#2lCXlv!``N}cq3x@pu{uc72LVeyE zC6D+rCxiUnPW;0f|4V(sd(kgH;|hG-O#+RlkJ(V?#^4_Eo@Qiz;ze6T6OxS;ba_4L zF%8o8zn>b0lA{5sP{AHgfl|VnLJ&Gd##7tuDB07`Umwn(%w|J;ZCLs2LRasHRxO3) z+;ZR6$H^ z1&v~>cUsQVAD<_~5@)e7pY#5cvE54+6LTk3rzy626E3 zA>sRPK;YKu%q>7H5v98~(`xr+d%F^G`?LY<;df9!THoPCf2K?lp%W zH254g+_J!bBLi*rN-TDZ|6qYTw=%HMd_7HZ8O3(X0v9Ix7RNs0{dWrZUmRdr;-3z%{7(m1{GS|Pp;u9M z?%T}29AI)va#d7F(yJsi8XXrO9}^oJ75z^N7!irGeVupf05xM16vC4hf=K3l!Sm1Y z=AYxfdg=M60}TGB1AOlPS8i#qSC5&rBs9^l?BBV`9u)BcjbA6 z<+uc8?+8fW;g@FPm1O0SVC5EPxjneVnYqN6ImMVbMH%miGUz(}0|Z9?n~E>TLp98+ zz62&EXK(wl{DD`ThW`QrV+tSbd#68r_xUX%?5~P1x-n@*YN)PcGDq{Vr2pSQpxd&P zCs(Imw~tr-Pdw(5YM05{rRJ=aK;xY%%xen%7If2{&YHz*&JcoXn6qk$TJVenqScm+0Qe^jtMx zp6|P=Z2|slxzxqg|lg@qPadr}d2H)S+C&8o3g-Mk zJReYy2Hk7ic@DTIu)*6*<(t0pmZA*NSwS{IXNX=l{wVcKDv-Q+GZ!_pWfKmI+k?HJ zR*2p}lnZX|Dx?ql7F>1RSN0!K%?)0UOEWEcC7Fsx+|uxn{EVFf*e$S zVlJp7v$%a_dLK{`s0I>d`dc(3(JoI$5bdp~Djqi*5pux?zeOxSCTl(gZb zS|p#3vA$TckT>CAEV>=$I_fw?zxJ!!e?-_D)$!2A05(p_d_y97kI}u3R`GSsk--EG ze(86Gh=ikyzVCw+&;PgC2P6m%i zvn#$6!>^5|o$REp%Tx*}MJIVp-x|5<7w8q(R&3HVb{tXu*Dmbg4g!iTTY`^acEX=;$F8@)nF$M>&`WwY5e5+h1;x9Gz)F7Bv)~b7 z+y{w^aRXA7kU`?_Q?wrldqS><{~HkK6s-Cu2vp8MR{aG6U0`eme}X`GK+*pV2oxV2 z)baoJDhFD~`6mecmRzh=$Za|}WYY32r7E_N_kqT+#lpALrjbJa=YzvGKfk^1fEEcx zYK+*^oTd$E6$!r{9C4O9O&^Ob5_zXF>Q>1{IyZu}uh|oI_dm^8g}$R5W~q?Y07il| zdPH1U8BU;FzU#3MNGdiGWz&IK*n=8YEq*s$%IY4Jb3h$QbuR*SQJri7A!hBgPTk}~ z;#^}ba6An+j6UQZ>!;jEa^|0K7y9*FrZplJ`XPOEGQTcf97^%teo{(J59{_re06gR zG^6cji*t8y{L)i}P|w67ZZFpil6A@umt)vShu-ZVcs|dXdNBh&ogR4?i^&yK?apY) z@`@@KD)4bBh5oJzz6jz1zrY^EZ0x=J41a|Wlnur?P;!1lLYlo^_M`%(cPEdv&BR%2 zAW0WW%fk3`>zOl)9j$e*w;38t?w9ri+-)$_6wwrEYUW;Ubcc=BEvuMp60_4GgH87Y zcIFsI9;Fv`m-lI4*V|I10q1q#Jo2VVu%1`{6Y}WTc+>Q4fjc8{fn_rkmww=J zm^=DZ=m&QZd& zk{vl)-o>UrYwMiX0G>$0F{&Ke^$xa5CY@PDPwJW8hm3LA)@F}>Gvyo(`VSzmDnfi@ zjVR!vn~A6zrKYt`l5x?)sZ$+oI%01y6hg#DK|sHmlS0Yr-6xof6Z`xd((ddcQuenH zI;f45-W}AZSfqh|T;rG_(#)Z2BAocZev``ba>(pcO={!F7JtCyuq{!o4iFG5{MwI7 zuNZlU8!H@uy1W_n=)_7NeHdnn-1zkTML6N=$WApF@yYvppCBgo!Q;c`&!`3hz;Bry zK$|@i@>6XFsrFtGuf->DF@TkTWY4p1ee!*9c(KY+oIwT+bCJ$@vC4I{?#l&I_ey1U zDg}2rMD7IpGk(QyjilJnFydJB`8zvimoi@*ii&tq)`xKiu8LiyB+rfo{kcgwfvx0K zbHml<%h93&zh*xC29xy>g5=VEE$tN5x6F=y)y}6~-u!T`(6xMMj{9pIcBxv;OuuKs zd%LKzZ=fl}3@$1=g#D-wQB>7Q)D#J#dY^VK_^=Xs74q=yV zt9x-jguf{qV4tYox#;+X8krw)F}a&@CrIu72HoLH-D@7H>b-Tmt&R2_f_P4MxZG+0 z({Gc)oBC%ALGK##NCFYWav|%P^PR@{1A1z*Gy2d|8z9+DnsfAOG<=G*hg9T;X2%S^ z);rkF>lgjiFBF;O$uJ^*Rgl+u;AAx6J`9H`A91 zf&KR;UWh#m=Qb1G3B0kzhj;-X7#P)sl^!6FW%nM?7AJNUzoVZl9AE{;x~uV&JsgW# zH&lmK6!ybOvN{n)H4%!#1Y^Mvr+LCggQ01HM88(?L@~l=2%=I90H+%30~7JlDnTy# zDOc?;(y}@8v zNI(~E`J5h(-zouG5Bw&F2+t7u4TB#Y4DDWxXexZR0*D+^2Dr|Uy`VD3t2QE63MJ{X zc?pISxDb)4#8`iW@m)Y}FvMG{Kx3EN^CLzC!&1@2WP(u7Rbrc`fNex{WH0zvL)aY- zoV!n8F5dtUXIQyXsQ6|acP@R485=R$20s`00){^pOw_L)JA;7X00>d1pg#W0Yx{fQws~VTD~d5}oP1jjC>90o5n;2uoESU>tbIYmC>jdHBDks| z_`M0|<|MdSW&15*%mRjB4cPzMLh_o!AY8E5Pf<(O;mV64nI(1opT^)5X27;{=*!8 zzmt09Li~OU@?9aN4@R8B8O=VZU%o?F-str7#L&7>1nos3ut#z`2v4#G9$h6m*CT4n z0fIx)utTugFhs{W5JQC&CJf|smFS^FI`0-CS9%ad2y4Y|28A8ii!+l(AI#&L35O$x z%;BH9wep!@F@n%ZN$9w1mNO@;J}2w5SMunf)wqVk_)RnTLqis}SC$zfb0&&zyAmYsPD}WB@m3;TJw`7Ji1qeB61MO9))x8dt5Wz>2hkPR z?ahBM84dU~hBzlj9mfrZq0Tzxg5j6u^jF6kW69^KkeE+|rXwPng<`?A#G-oYxZGKc z{;<1JP-gBt@X`#cvcPf*Sl%UlV?@x3b_`vg#0MN;md#0$ngS_Ky|32szD z`Q2d2dMKP~s4YCxgDm?%BfHx+8_&N;qBLJiA*x{Y{v2E?-9->z0blnC*h(0=WlMk( zL_A#3lXZjZ`rRr#$e?{dI8=U055_j7qmujR)uA7q2}zHpV7iY5K?;k z?2#xHrltw27!u>bv5BdFQ7*-@v_$|`D#P&toHZ6#Y+TW1JJcBX#*1XRo42Y=J7k48<_3eom?iooh)`F^o zgnz;MCQCt`j7D>z#!|6-VEh|Tu#vhN5RtQ_StRC8THR|}7h-bbL>*nrJoKavY1ptb zDKnDuoDxeOcb%?4xW1OV8b=R$;0dslRs%*Ch0r!g*)>@Ay+>v=K|`8iGbqu|EG<>> z3~in21)KDWNI`o}WWCQB#R#&c3HC3W-)0D8LUi&QNp9P^8hWbF5Pn7?S#AE!3PM~8 z0WeK*dl7`{Gf$QK($Kc(CJ2jdw_eK^?-o-1RvR($>ar$tg*HQEkf~8tk6(Uj8D;u# zo8ff5>zf?gnA`W|Ubzu2pL5qvk1m3&lS@i}nDKtTzxd(nuMZg7kKd#}65Cau1$?~7 z`1rH+=vxA_m1G;qk1L%O!b&|+*YKfr90z0XA?dH-t z>6SW2sd?v^+ZY~di)^>4Bv!COolk?UE0}G#uAJ6?b(xy5y=CeW&UDhnDWU0f7uT|b z`^X&H!z7+iOwDx1u?zEiwX5>lF;tu0%XGrECy>{IKM8WMlfF@6YZEbC2# z=$mH-eII7hg!Yx!b(-ZqUq!*b3>$T0-n&3e!~#iviT4+K_xe6`a?&CvXzlMQ=rcRP zk%A6zIlqi()55!HBaa#zh|3%poa)zAAm)b-est_i%^ZBwHki3In0+;vbGv?5W~e}> zABopqm^oD1HdKB{7PB-|MK}DUpua}T?soBRQ|2Eaux)Ah!_{yH-AI?r$gna=)*388 zV`PPlQs3UJzIX&t__X;9ln_bI9m;!Dx`` zr#=1AwIwqQvgBH%gN@FaWXBCtPmwK@6vjy8AFlY>%#kr9=7Rf#U zy&fyM!ZytTS&o4yDnJy=AWJmJ1cMEe)iwzpC&&d6jDyTq$D<4YyI14#o9+TtAlwjK za3=_S!#oM92I-?YZ-yr{96{Cym>3_-p$bGB1fsvj<`aYpR85(9f|Rc(5!x^-TaZT0 zgv_$MK4KCZKBW`{;*^DJ6HekW&p;mqiH*9!ler4e*#urYCzY3l&}l>3h!SSE#>{g_c;8g30WMEE0gh{} zypumX=v;o2;s$L+=1n_SQaUif#ym)K`F4ILO}Yfn?Imsn%BcVmJL=feem8Qvre`}E z6WhXeThZBULN+_X413m_yW0x$ryhHHb+g>rY_X3>*+1=RDgyMbx1lUEdOG{sWc&9* z_xL+ERe1^OYz`V89oW{*CO={b&Q@3Nb2Rj6*2yN(7bETEC+%lAsL@feh}$P*nfWBA z?hOD-=a$^HI}#2#63RUi>^v%#-e0MkwI16l|0Lgfy%)K@FHn8BRY@t7y{o}8Q&kCP z6kj=d!Ko*Eyr(da`83(6qs`gA$KCnWCAQ6e>Og^P=f?^YXZyik2!5kA$+uh9Bx+yF?8Fg7QTc(!20RZ zt!(pB#4HD7RrL*_@2{K-`b12^N38nsJ;@{^+4TKOQsz;8NtL>r_ezZk4A~!H$&}ZS ziC;1I**$st$xr&A_h3SFB#Vu(;Fs4p)sRpUwpU5b5$;O3#Ft(pB!EPhxmysZOI~2A zx270DNKf?Z#M4$eik#1;=PwY*<8wk~u&JKZJ(f(Tinpbi%4hwdPW=%RTN=q@!iT1( zc_Vfr)JZf=vFS=Vgv7#hQit0ee$X{2PwA_7x>?ZI+vRWm0D%JIzI!w?JQ~>cquDAM zCP%}?#EaYo-Y1h)P51ELgi4{!C+dT)e}fKxINElF|5@?%&{qTMrWjr{*e=CvQ)DNZ zlTmhCN6Ws%y?*YwTPJ`U%9dquzTd4MB4*8*&UE7x^As67MH>5!n4B! z_Yw2oD!%eJu?r&JsiwGYYn*qsaQ2tmZ$Y4qj6FY2T*41jVA^@S20>0F!92?7-%LT(tvc%zA15GW56QpSAZ z(PfotBE7BnnmVGgi-7jk?@2yq=*eE&{{aFi^IX!NU>5XwugQ|DKE_Hwg*DhAR~r=N zshiwNobL*1G|#f@gztsU@#xHU|W8G)%esGclKn2MOW zQ>%S~A=Yzx)iKT2qq|A0CClUb4<+C5cQ`kC3|hnrV>Ma{#)+cMo;JSmSthQ3Hkg1LOzro@b34Ml(|et#*NrgNdi` z59IDhPVMcmx#;DX+2kcZM#1Gk6u8Z3{)bp`f2=b?_=e~d(8yi&4sFguZ+937eL=E#}Pn^vrG>9h1i?w|J zj`|WtCr0ls3J=8fA@xCoT`c+q`#ckkL}{W~8&)2zhZ60W=R`;va}n*cOJ6pD(0H_z1-*gqN!Jh(c|=-Hj{c35=@8IVp92R+d-Bwg;+M_DDifEYXc~HujLi3z1@0n=b~MM#K5lC%r%K zmU5;{UysEV$5=zS#Mqa}6MZ^cS*GF}l?WCp{cb0^qnfSHZJ@)${nGkI;y!+1($j;O7sTGAaZ^cGV`K{gKV| zVtSVnPH}%V3j1zkXcQYQTcOaGo zw1wP zoPlt!0)~K(Qh{Z!pe{OL8;n~B0OZrED$YdLKyv(NNBy`|pp_zR_eG?P*r=;Ts}j9O zlO^M)v0W3B?|8<`laIX)=8ZoVVCU%Jl`jjqTi{sGb?MoQS=$csJI{&TT=sX35Pv>$U;WiQLk zka&##6gHq+0+H|PrENRWT@6=2X15_%0v~S?_hI@GS4(J5PX{uq?s(qNPQp75Lm*K$ z{?u~EFVUvG6Q3{o1x5IX;vo)X6O)R99q`?k7kMp#B_zFH7oQ~5`P1SgijGo$J5*7B z46mP)eAla=5Cl|cM1kirIJCSSB3b6U%^D_d=;LjXmBcY~y>G|)TuhNOWG|_vq?%Vq zJo_D%es4>>3&U!zg(w~EQbgwL=wr+Ii%& znst@n%&X9-U9Fv}lj)m8=5O+Q&UbU1&?S6K3S;+OO=y*2$#SYyQ-$MNoxu8L7htu) zh<?}>!)R?_8=%R0#uw z9+H9=?CvG^(N}1qsj(J|j~=U2Q7Kpzg@^^;W(C{laoz(qqf1J`1Ke5E-(0#cPSXnQ)BAplMzuovLNZC=xd3Uzb5D6qr{7LSGJ zI&@9o0OWkb!(Bjr#dy`UsE&ZhG^NO2ivq2;8C*Ji!ZRYg45g&15R(oiP5{8(6A_x$ z5z>Ks4*|ga754=Lp0@`FVY<)`gZE$6no&m>>NOL<8|+Zw6K~YRjZhJR;1^_r+h73Y1@_$wY)W;~z!3T`4VLO-Ms!U=m z&N{n+p$YOOWPzkM}SYoWI5k={DqXnS0f_~Lv zjqzk+0F!pFOt5s`J#){nxx=6rfH_GbDB(i z#s=mGC~WYe_K~`NOVxB_YI0@+CnLHS!E(O?RU3iYID~pwS)YfEGC(bW9ZU}7)(z$VnW+#N;SwR z`NAMIO|8;sT<*wl<t=ZPX6#hO~EZGKSSn6KY5MaCU@B zAQeXqvN+%F9vI_?hdH4oBGplR)6ovvGp_8h-{ytgdS|LQ-`<9pAB9K34~%tv^&f8$ zU;}17=}n)E5@1si-bG9UosdrgL4YkB7&~gYTwj-I&~(-C8GDqN?<`4>u2p%1 ztVMTj8ZR+RCps7Cfzssczwx%7i^Gso^XOwYDFw2bg`#G|F~}Dcb8&jG*l>O9)i9k^ zTogTOvmCiuFdk1oAIC}i>UvTYJ#S|=Pa|sv8%ktlsg_l8suqWhH*1U;M^oFqUP)e_=VXtY=w{;!#?53^Gzi4bRYiuFd_SXra=rmZ=)mhD{dz8Iqxw$hlDs%{_=Z z7U|)rjfOtt;2JWWWwaH9e?$)XMhH1QA~@S3IIkc$o+b#}hbZNcUS@sykQ4TefKUp6 ztk3yUw|l?t;!7>qwwB7)r}O@f$|}%g7392%>$8d%u?kLIy&WtkXjp~xtwLv334Orv zBBV@QGvv9}TNv9Is+9K%Z%!>}8I-Zh%%dQPf6<8Br)Zemz`XRX z5n6pW_z~FG8Eh|S=w=%g_0>3nVg3thH-6Q{^4ulLw!A6FDW3|gL^jA1@0dWfXT-M` zlN0&Gb|-?9AV$^2oTDYV5*+Sh;T`dL{@?+~*_i$x(6aY`0WGh7eEs?T_~+Td)&EI+ zasFzvVq@^vM)R%F`TnK<=W6}gV%Np|e`77bY%K4uP3-+~jQ@xD;^*BjV}Du8 z|24Gi{a0u?)pa(OcRHMMFjDfhFLkFQ`S@eVesjn{{r@+?c>hmmY5q58S!A*CMs+2c z^M6P%{?T9jAGzgl&-g&gzi`Xj_+n2_{cV4-<3rOQ+_ElnBF5-8zF67X^jCbbic#UBdt2E|dPN zyZocS`25fQqW3-Tr~j2(+Som?vVCBA-^t9%!Pwl+(Cq%dv6f0228wF>B0(`s{#HDH zmKT{HNB;>eqvTX{r4??KrN)1wEXDsDWy!%O#r|)grJnOYpk>UzgO-kWJgtNbXq2Mq z(r?$2quKryT4qQ*-Cz38!Q27MuJc8e|MzElP;zM<1nG6gY%c zCb(tK`P|8giN4s*)@g4s-Xq6p6&qN z!IY^Lak-I9s&^R9tXv7~3$hhPOLpFdolm=L!~svl$GE6P&CnXySwEOnu}SJIb)*Q4 z)>RPeB8#2^-&0pLwYe$a3DURw9~FsJCG`?<=%Y5$99L2|gURCVBzcoWfX98A<(R(%D0Q6-rMO& z8@39?jN+bLZKdpcB$=%>Q(L!TbS-obLF3^QNiv$v$EuB8M*K>QKIB@Xq}JT3; zImoMs&3N|H8#dsc$V`tARcOOIh*EAOL>iU($-p0J(q(5G2zYa-}_EKIb>=ReCfYinMB;hC#tt-w3=-D2+gf%Lh+L(|Tp3xO~JN0xT z*}$PZp({TKaT$@FXE|pVEh-#5%dKmu&>L6shMve8`0R#9Ea*yh*iTGch⋘tkI06Hh}6(W6Eky`@| ziz7KqL_%BqB`g~Aj+?K6Sn;`H z`YrY&UTI^zHbM}^1XtBlo(y1?n77|(O3o;Y7q7Y)Y0aQ!?*sjy{UU|k>dc4{Y_?%e z;uqNF>gd}=N>xS=^!JT#hzzQ{p5umSNyVIKqk^>Ga?e{QYu+6Tvm(kBWX@D2AV{=k zdcs5)UaaaR!nGP$W7`X3QxR?%Pg>trVw43-t~|;7q?f={GS-*xzjtq(%t0SdbWg(v zn#++fOher1x7;%Bkabs%)biMz`p^0vO>_8y!FkjgBjKymN1UC$LvLvPrvq9^q3heY^X7y{(1{^bAC@tOo9>A2I$)C5e~gA#=*{ zm9Nh)W-YGtY_{!S^s&%7&wXxTe&x$H{HM!2G4{|O{I{3$;Fz_QWldxUusI}xdSZnr zps5{ghKk_hg+UXJfxQT?5H-awX-%&wh<(5kP5O}2qDG48`mda-GKqw>uiM87s}WNH zHWrTJeH4RyeuTm{Uti!1Dh*cn4#(J>6BV={_rk4B1M7bmz3w8XKmq!+oH;j}nw)2% zykmq2%&8=Ax;}PQ#(}V-1X(-SUrt9wHwThOcL7Oif}bk1DM0pVLYXDi>+%Aatkx+g z>FRf}448!Q#l+KS_2LISTcuaRrqU>Ki0b3UV{G(eX!=2}!q4w6lN`SABZ=IuJ--?u zndMJsQl$`79?)`LSoq%1%r0d7_0S;<)5OHFJ(zV@3kD-b-mWdE%()}HBp|Oi2OB)q zra*t-E354+VF<6}`nEW^o?1UA#`yHPbktSDhkr`3l%a!h<`l5CI(+i5` zpHC|SzEm8C!TeWLPQG8J#wqtRrLh+?pm-S)56Ou#DL{8n;vI3xwik6Qfg(eP1?x13 z;ztY{H^CrW)tVSIF>*}{IubSA-3Y59SOdPedqltyV{eSUJ#VqLgn$ zqZ55+ViJ44Tr`{N_5_6ScG$Ksg1^1Zefye1$&p{+_w(26_yhWR%NiA$AHrT_=F}B z6MTlNPt=cq!8!>3TH)SXMR42^+8Ydoo2gOtxmgzmVuu9a3lV3qF*BO+*Rurnng;TA z3KK9xF;#dY5B%DgSX2j8%X55sS0Tg`5LtCKF;f#o7bA*9Wcv>6;&~wXiAb$2af@j< zpKmx$E>Y-2kb7j9)IgYtni`u}1ck3RUZ*b({H5za#I>3`)k#R-87t}rgF=l#w`@7z ztrDkI1wJu@y;g%ASJ6R&8QuHAy{o~nxk!her}oAXI10#`b-pji2;6F^pP?{SJW;%L znl~8YEI8oz3MC=`aJoM3c)@B`lH3PT$gQ zD)mNTA{9L*799{XhgS*7k|V#zQ<$G*D%g&F1H*`}CQO@pz0#c|j{i!yIT1%8B~&sQ ziBA@Tw(T9$0m31K6CyGb38K?l%%BYXaimTYETtJXf`+A+gry0?zHI7Rv%bkUPoXMF zq>F-i_@z_~k}h_nKz_p}C3LJIyHY8tvY^8rX}skS!HI_nrpJ+a;V=rRHy^ zI#mJPL(sM8Qp56uc%qp*kGOJFxWySStS5U}@ z*|E=y zzcXtgogsr)vca0D3vd*?#ifcj{W8%vQ}oxn@WWMTv>DubvdD!ye$AKPpBrW*B~yA? z^71F?k+^)8MPcq6r9y6T(w5TaC)(majW0|q;tGncscp8<2+-n3Gq0dPB}3C?}WWxs;zc zAeGzDnel!0k6ZMide9@OR}ClH$GJILg_R$ZN=Nbowk;Sf+}>Lu-~Xnm!j`TAT2|pM z<`a8X5wuo87pp2XvWRG_Nu;aEc+A%=s;M%nXgl(!*5PfeklU++zXi0Axkc}(8R@Tdfck-r`1DFD>UmzlVc70>HK zzdx%pJ~x7{m8SW{>696&#=xtl%8gs^739=g4x1h8=dlWvv^rMYmnL-#Xy7BOqjqly zOs#TEs&{iYsOv+4ncuH^6*WmUwtCmIFh32XZ3@kh@sw_2Jb+%iHn|(WjxIBa!89c- zHfaMJVT)vPJk9rwSeSaIJ z1p0&eb%M+RINUiE%)H8ix6UsS7q1i7q67CfJBXVIa;j(&^9S~my;4H(!dwJ<-1K@(J9^0MK&F6hyhIRFX0Ny- zh|LOWZ3T551DPU71U*4EOfbXSSD5*VZv5W%ivyqyM86B-ddihR zH4W~TSnBic?5=nyYAMrm`((iq-CvqHOpWZeu^m)88S*d3?y^#NIWlZ`GK^z4;<(l^ zti|Ze3!4ZeGn47Jr~dn5u!Eto$!D~zth(t4ERwm&2njO{K6{DhChEs7;K&A}DE z`h?L!xCP_RYkfA1{d{>S&nDAzok<=K9mA@S_Za!?ZU_3#JAl6|Z#gpNssCAGX%udK zTbb!T&7{a)8Yd|D*mE#&&_*$v*+(!1g(!A#YJc+f>Nn{eG6`$%yjkoM45C#!oSQ?h#?6bV0mSnQMXpp^_7RJoRu&7zfG?vWmq8;YI! zRy}oL$hL4o9lhGv?%t=bO|QX+V99D_itPpk(Yj}mhPO`V)%3b%(b@?1n0k;3d(4W3 z;)Yl;J|&!64x1IPne82$jmVN6;+>NqnT@NEeVI9X$~^xnNH$HDJ~4JI-9r``I4Kc| zo2*3&#>~F8ruTr(oZ9upj*>KGEaY1+h}X;m0|}b47F#M7cWOsdwHfQ^6^z?SB8^FV zwMqMBNeB5zhuak_M;2zFgJfrwlKRD>cFQ6m%Xf2^g*%t|Z$cJ~l?NJl7iU-(oD>%} zJ!D@(m(Q_A8>~}TvsRkN`;I;66R#Es+7>O@`Znmhq=)4?mt}BxzeIKQxM3DUtfAIf zB=59WqiR<2)>q8S>sD%e!>w5pZ-uSUYP~y&4!z2cQIeCR)#k+h9L0g`YXrl1o#(hc zkIrO67irSzI`8;<5d|v753*P`99LNggL_6x?r?b!mGaREY965V~cDP*Vt8Y#Vx|* z27&5wdwvpchD{1lc!CIINm8>{P&!&^huKct$A*;trUn}QVrSy%lxOxTTgdQNrCnkD zZPG1HO@8>s7*}W=@BK&o26h{`3VT9!d#ZNjJx^CVSax7S>&-$-hm+gnLKFq@FhMyL zwH#2(Z=RM%UCe9y%VAr>A(i6e_BC?*M9h@I(xkC+vTh;!aik#ZlU>oS{R$%Ps%%nU zX&BLi&6P8DzgC^Q<3~+H?fpbwXUsIQ6LnXtVK>@b{s$z-I`65^w#(ubhF=IuBp!nj znLmwj_OEc(xRUHt?m0!1=6yoAqPJ1@NAfAmcMP~dZ&?Y}jxz{UiC)%Fud@ydp8(-c z7&UfcFNbZgkf9l)mJVtdn4wKGQz^Xx~R^!ie>rk2(fEQgqyW9JuN}9_P76y`_1|12*W?ds*pHj^0|k~xit^ww~O z(-`j?l^R#r^u9@XM_EB%PbNKXe0W=4`~zB29B79SO>>+jogMtGyl8qnor>+g{VXP& zDYX4BXz8{7&SmPV{=nzNaVUlF*P-x_8mCBC1~q;k?^BnFLT%GJW3AJ@9yM7domTeI z8@HKyk1wiMp@a$xP3JAY=@tuZzx2j2-f{2M?i3$@Fa~io^D2kvX5H`4zP|H%8@PNn z{ese8sM66+?>UXlwf}df`*lJC5gq|8ka9@u{PfTg|LWcio**K$X7^Ff6tJ#L;C4sX zXelpBNl+1gR@yU1yvEE{vBio>y`{ufw96ZhQ9`t*TlQTIib!Yj1=h&$;>=u<7q(P#7)l~icA-4IabC=i(BS= z4g-)I8MoM=4+|UImUpB1-xzEdTSl@E-;S#0kP7j&m_3@Y_hoP3=P}aaF5#;T_F?9! zL_bup>y8#%%4{-rkrcmjB#NUrcEh)ZG$V|c+H3~$RQrKXYGU{*+t&$re{T82d;?Dy z*N1{%iLWJ>yNiji60c)VB4f3Q`KVZYOmoD?25ytl<*=DTB|Lkj80til`CEnL-{J6D zduXaP+-M*#E|$-`-XYJXc+V<)#l>OyHMu1ML{$U!%YlK`^Ez|ia+KJG+|c-h8AcVQ z_~wfHkow;t|9_mlcTiJ(gSQ`&00{&*^eTpq^j-v{L#T!(y?3N4RS`o%AXGz90YN&_ zr79puM~YNIX(}KnMUW~*lpptV?>_tN`|j@S`<>`L>N|s*$h|RJD{rj z)1JDxhU6vr6(tHgJZlfPm1h;qlu|r8UF)Hx84QpQ{lcB-mi&fu!~CgvLHA}s0yws@ zVZ575Y*h8WV-w{3+TEki_jlE7=kA+_9!DfB{wW7&y;9w^dN07*QdKZ#u{&uag(82< zE7b`a)1R77P(CX<=79h#vlePWqAdMF& z!rc{m9@g?`NMN`w68@U_=(q^w;`s%Pg3{#*Cqlz767|jyt=8yo9)>Y44AH^zS8hxs zm^F?wZtBGG`AoQGM-(#mDfE9w@h7=yxv~Y^ekNTpksKgm#J(iR+wFx$2GK8b^gWbU z`8n}`aK&o+4@&_Ez>?vD9oLTusGq!@bnlPJMabO9q=KU(9kIAo?uj|`!Y(8pK z=D!O92(CL{E}yMkbP8#ygU-%z95L`t_FK+XI=~8zn?8T>3d`smFNSVPuwQk9cEtNd z!=-Zq6vW{qZB1QF+t2G+K~elF@{et=(+aD z6?BC`km$wD%h9W*ZNAl#biWsT(b4Ms8mwcyst%94UomAV>I$)Hc160Y3|N<#5Owmg zEK@7w$|6VroMZm{++?rd#^uDvDlkZ?lo3oJ!&xa>MuYjYprC}ou9Y6ljT6FJnY_K< zGq{WgB?b1YCIr!RlD%L$;y{Uw?ob9!HD<4(IxW}hV7TUS9S>hW7tWpdpaD6~CRvz5 z8!ff}S;3QLBAH~dwV6-rm&*^wg()drG+7Efa|Tr?!8azTqrEc9$xq0<<`v;%behNo zMqSlK=ONd8OXMgp8Sz_*3B;gKzC|pxZlADCxy8d_BswuRv_Ieh5^DjI0%F3=#;+M-mWKrrRzZN?aaF_lZ>nexV zK@J|tp_-D;gX}%p+(0oGVL&879?9`JW`+487^QoKiQU!tHL6qZJw>{w2uawEYpH1| zA?95Km7$%&U^(B!wXP~R$-68}zmIja_k@A_yf}a+cVA7assL;xGY(~HfJ#Mw6%<}+ z-=D$LQCFwa`1cGXl#lBR7%}k+XS0(zH>y{O03kWcklV4E6&CFq<~O1EzOtL@$MRl= zG;TFdwiDu1F4=R?YmM{`kkwdfY`UC@>+Idmuk8baNJZw5_2K>L+8-Z8!n9b=%;eM^ zE)`7cGerZ9CSc^QHx}c{AP)lZXnfy{Ixb>4SktDj7bRK^yUoX`KM?Iy45;H>q+Q`8 zw46`aJAq{^IZh7!C1+9-SazNW97P#3MZ^3VRJh;Nvm7U>?$U&RuVBvdu#)YiSM!>@jSn=q}Ho+ zvj;umqxo`3u+s#{peg>w8GEXZ^iQK<`Z5_}-6_zJ@(?XhJnDMcq=zE*XW7{+9xKMe*oT_JUFvk=thh?4(``IC}h1~fNUPa z@4cjpP&*E zMeoFtD65|$o7HSUuW$shaFX+z>Ivb>-(IPckbocxtnvyNzIpYe=4h-{7Z-vEIp&3A zD)AP>P=YXu;O@h+5-`wkC4+GMs>J<*{cY;LQFWvscK9{vv zWp;vzSMLqpWXmKi>x@2=T5Wp~Y6s;;%S!peW)jB?ZMCylDTe-c7Y$#Y7y0OZr{X^U zaGm#r{<=zRE|Sc#SJJWZIjUG81A`0W5wD!lF<|I(*?HwF6YmGAef}gNWJM>yyg$pd z-=9TSS41~G|4l`$uI_@a&5Uli9h_N{;GGj6ouN~L(s6IoaSYZuk2xbad6C5`;9bzD zr-IrUr@D!1t>r{id?PBg6BT0D=6le0QP_C6hAKElJ)+QSQ|NQ4eV!1h_u#lyOgJHH zVK5&GkLXpyu3godK_QfNGIlhgS&#)W`bij^hlCiuOh3zO$VH;DY-Omyi{;w)p<0o| zSX$LO8G|~j;s&jYk3%;e8LNjj$f_-AHix|^CM@1DXf=$-S}V0iLUG^8GNko#Rxa|A z!=2E#)>8%v>KCZ? z@Y#sr+MCJZkXp2)`i8`1{m4QfeA>Bv4ae4IyE~v z2#&pjYsFXlWXAS0nooPLi?@uOt&BZftoj2*XRrvprx*u+gi%V3LrLSePw0=##>sOt zRcX0kCFu7j=@fnFL_wn4@Hq7}i|zh6U<8X}Frnd_pc@$n2eC28np}4?VIUo1-Wq3l zI6*NDVXHQwu&87lF`>w%wE8{)`b~kPG6hY8sYOi}?1pgTINp&lkF`!nuqg%Az?G)S zCzXT3vWZJ(3VBnLpjFe0ZJXKQNpabC(%SFNWkdGJGftcEO`FP2n`uv*TTENHPu~ccw!~WuMDS zzyr46j?-mJyfWA$^u%D%4Taa780{ z^avcQ4afDtV@PLWKf-Uhn*`;;&u^_xW(|DEDYMFIw#pfp`N=X^#Uu9Z*ecqp)de$C z#14}aCEFDuR2s&osaU5uSz`mOiLhBL#yX>UmeGeR?l8Hg;YJ4XMhYV#UnRaE7oNWb zFFu?t4Vim}pDTMfS6(t#(KJ`tH&-=1SAD51)7>O?RX;Qt=BHwyC1LBUG@l39emStI z@tp@-%o32~caASBEWXEv+m10!hQXrt$qEjmh7Q?$^U zq{$97m%2CajSo-_Wg1!x=MpiXf2$Vu|1V&=Uq^qDbpO|k@qbw@TsYWX-rri<`@Xol zxwy0W`E-4HZ+&iWefId<#LmX2o%Mx(N9TtAGdkCGfzEAhEN*{W*#0)R{cU#Z+rrk@ z*>CI1tE&s^UuKq;=l?5)?qb0B-x#`o_6k?#2AAi@H$M!neP~|#(6{uVcX595)7-?T znX!*E;~!_n7C-!r(Y^d1dWAbZgzeXu|CeOpzms$&HY-n!meLhJ5%~TEru$Fr!vBM$ z>wfod;li)SHICXN-FWdfxQ5|2<>;7e?3q>Vl*jZpt5j;Py|FuIxqqf8H?u z7mV&%;j_}BlA?m5f5+$^mK5GDEy~Y(lJg`xD=YI!Ix#&x{Q{$V@PL?{oRW~3^!JSM z#fC9HAt@#{?xInPiN-l+6-;W25Ho{Rd2!a4+=ky??-K8va zD&Ch#8=6doi=*^{3NEtP1qY`jroEjmb(oQ+$ZQ2`SLn2_lJDcK$8}VIqeXg-=p&ua zFk6AM#GSq}_x>A{ym;AVDdH+e>A6k6#ogW;bBz!56>top`xP5ZTGiQyUw$3$9~J*m zTJ|7_DD-N0injlxvw{sCK8b|X6{5oh;Ff3?=4w0<$HdnFSAWhc!=Q0i(5SD4xWUV+ zPC?hmsYAB$Z8=dQJJ?12y>hRSW(>SoPooeH)ksvS793Yb%J6de!bS#w7=e2V#0W;` zurzVfke2`+vg-9V793P>77sItA6G`x6_-ek_LY6j_MMYS&ZN`R1EkuEy^?$(6S3$N zrox%w`_$?Yu9BpK<-{P!Gy%x(kMSZ(2U0U2G-eDRA@G1k{ctfP=nLaxh(%FS&;ZeF zRV|$DAn_@^;(lTQE!Vj&x&n4d52y^|@AcLhKxPvo-w(u>XbyZA0xT)ieGv6fxDTQL z+BNsJaq2aSg;Fh>+aw$8*BQ_2gNIuM-|!zKKJSkl00)DYUZ4{~>88GEdVW;|iuyBp z{qQhFZ$p04rf#6RU&3m+7U)y5*2q&gr@A42a7^^y*K0syNWGPa{fr+KfbM7+UqtIh z{mrCT)1_6nqHIPJ$6u$2$rP#yfQ5=B7Y5iS;!F9bmNc3*?v9UvC9R3w5E9=c>;w>* zDp=V|XORHDoI#=Ur|=gsxc|EsF%9-{;j>ya0Oi-@H(LOZIb~o2^L`3Hpiiw3K|4l4 z+rIZH^2>Q&oqE4d%%%zMGBiL#><6oa`U?}~>&bs~ihrs@Jz|_S^Mww;86T~4=GC7H zm&8vnaaEfx-FsHkYG|n%b4Q1hGFZ+WGU6qLUK6?l6iEtS0}5GqctthiFZW)dW7TdQ z{|tBcUmLL#Pl?3Qtc%fhy{GS0*3g#aJyJ8?esy}hBCRd?x*zR(s$Iv-VREqliPNnC z&gxhB1AKC-AyjN8^Gf60E5aUwR0BS%=MCyAMsdz6c0))wpBgvS^05^D0L7W8lwRmNK z=a3sUOSadsURK6sd}>SQF4f0V*Qt0jjhc#7rLbaf>9L zY;Y{CmJOEAdZJsZ!C`xuk(*^_)<^ao`71DG9aO|Bx65kIA4^@eqzhy%pVOhZb(qF);&DQM(oK&Ayz&;Rbdr;PP#%5#&JT z#17Py%2A7yYr=|AuqSvZN^w`UychPNkT4Pp9p!Gv5@fAr=sXXWbIGker0)%$Uw7nx z7q6=Y7iaGliFOJ?&U6z#_|u_d8+kByGzrM9bRzRqUD$Ps1Qz!Cp6K^Pq{AeNFWKY` zmJV9Pc!g7gX>ROMYcLKx>!F|I4b#z7h2DJWy+-) zrD%#wiwnTBWrl`cska(!%{@#LD|X9o7usZAG1d`;-fN}^9~#{X)@ zIO=Hl^PkhB4iI%MhTL!w%zoSnGp@xlzg;9#`afoj|NCm;GSjQ$K8cjNBu~RHZ1czc z3Zr!?VQ;^1{yKi6MqN*gGhE?jKN&z7*QY&xyTY$@GKfy8&v<6IDs)jTl#ds^s1|-U z3Xhs0~`A-ycbm-C07%lqFd56rd~DjtrrG0D!@AyAF^&49U0z+ zX|J5tw@|&8>Xx`95O&dXVSvN=pxXZft7{!8S7kF*VF`8CtB+7gx325m{?R+0qcLeT zR}9UR!m!Jcl0?7hesEV*oy{>X_+#CH0Ff?*1bB0o9jG;)}O( z9UWcFe$&F3{Dh)6W(v(9Yh&zR;l}K^Rk-Bo zLWnVKjcXA{Or4P6`DB0GxiMFM{n;{A{SNkf1*^yw{fCS>?v~2}N(-MN^99ooC7iw4 z%qG8tX`%qDsnl6t^WSy})prTsBNxc8*ydm9RxTFSH}B9Gcz0Jd)k6BSq&8cdnpIFH zcMu;v!~)jv==WgQpEnnKPLI#O(VR!Z6I@#4oZ~l#@6 U=V{7q{#;l@NO)jU&|* zUp~i0g|18gZ5>TjN{)eAVaUQUuuKd^GX^n(p+3d{EYWld(F|76OySWinbB;`(Ht|; zoHLlPcggM73q9C7ZV{RN%8N={4R!pWa5Q!Qk*coqtqSR={ zdz3N2oDjw{taw>(PWjFTi&# z#ydRrBYyvZNg%m9WJdpsl>s?x@!$z^JP}XE1>&_%>renf!qYyY5+OnHSzhYPf`o=Z!sT+p(Gqy&e40cp zkla)v)%53m=&n5z7iD%h@L3|gKOaWt3^AO|xLTVUB1qks57Ci?_M>4|-iTDE_^QkY zOkC8^^|(I@kLnZ%9ubec;^T3sN9Qo&sRF&^dTMHZ#$7Jx+B8WR05$u0zx)kgY?VP; zmx}PF<+DyRXL)GF!sI=Z2sMF0CK6?KQbq`|kgmkb*72my4>B|3F?zI1NJ4{PnnwX> zoevtS1~R^pDn3EJVFi3968R_aD8X1GFNZ|EMB6JsP-Z;%1TdY=mcbOOE<&$5+z$Lu-Gj^xkK?z zg64b&48hRlyCayL5ab(fD$X7Oyz!K<*Tz~9QRvwg=`Zg?AXDJUtlF!^FDgnTX zTNvg#MWoyj41pr`q%@=B2pYBm0m%Z!I|YjJsR1VixOG=Vd>(9<>e3LsP(qQAWPwth zHpPTag_Gpl<)WJOTe@U7iJ6iMYT`AsRWoSfj^V1=VA%3kQ=Uj z<}6gaaU<{ZK%V~BDmMIm&oaZDY z@(lF)wDR>G5LI+pzY~?68Pz$jz=NR@xFpr$t)kkE3h+=cgHS1HT+C=hB3*a|^^!RS zC=Y!4tRH!4QteWSDG+-Kbhh$!TxG*!O~dP}03q7XS83I+24NH_Jx?(Ur%_}RHT{c_ z{vFVnEAR&_*p#5G!>qK-W0B2FTis(Y3`o;}B7}VaqENY!JOG_nC4T}O+4#Z6Q)*ap zslqGXn(~6)RfucSuN3Hwbp z!qs3df3&U7j1XXC6K%1{BmD|cy$zDD_mCE@(NhAxomPzwIA7<$}U79+2U9FfY&EFtFqo2D>7ZnEsbP;zQ|Y3%@@g5 z^WrM74AE1IC`(LJ&0%{5kpz7`$JDe^vW!x;L%7n;v!738BLz|cA-2?L z7BFzuiJmWgueC)0T9Gc&-5yq_t}!QsbYzdw8N+qEcHeHXISds}AEb4 zkhMib8U|Lh7=<`j?_YNBhotrg7y_zioj25=vJzbv1IR`uZ%obrc{ZlWS`(WWK!Ose z52V?JrXtU8=IX*s)h~U4jXn=KXs*GpVTs+;M!D|sYSx$7Wr(_ zx!LyV&26YH(-j~ie1UbGrr8aft-zcz>b)7lUKT__Bq4%mgm1wvn!%Gqn(sRlluoig ziB#F=wXiuS>fS(>CIi1csj|p5m;v1FzC|wx1Y_V6T0U3XQXv+C<{RC zAl^GX{Lkwe;L(U{7B5JHKpjF<6`&0UwO>H2o)QJYoY;o}x zM1>k~5NHc|O-03lW(QH5GZh|GG4JXRV(&m_0CaTVHhy5FQ*53`qO+CDW{XZqNZji; z=zbuqOoFBw2R|nwN~$OhcLtvi(Mb9s44n{MvY=^<`2BW!EhJ2~wmYVpIcEXbG?Dcz zytbvr(h=x0gbwKk0?4~2+^T^PLPe)Bg0n;*;vn;;DS9$M)?=37Utzmr@Glte%*}eo>@%SdyCf?Dh_L zrvfTnq_Ik+8bS|MtI;qf)KH8r_9LmNKef*tc3w^C1)ef$PEgC>frSbIsNWlMDmGzf zL=gWoXn|mw6VWKO|Xt|UbSs_&Nx-3XXjr>Ereb}`goG8$;&2sb(3VnQaKs00xc=I%&=>g_)2K`*7;H%5gg|&#v zR77C_-ELua*X3w!>~vY+FPgd?c$cw#$5|pXtbB2kp6j>sc>|!~{aYgR*fUyL{SPpB zU4_i#_oBGVkS|j)^4h}?x&ipv=9p{AXMPoNV7px9@bZ$U2{kCyH&zl$O2w&_InHtg zPc}%KF@^pgV7kAng)yvVUk$Tm{VryV|Ay&KBX{Us>&-QiIkmIR*G)@}aE3@-3vFKbeZ1p-d}G`0A2Y^El3ot4|Ed;pSOq%x;r>xA z+;yp*W%+Byc+YLyy3AgBFl@P+{1^37BGU!mK7R}0U=_tLE& zU(6U^z;s(5JN~U&xb^wSnEgEJ&u?$)wo%o;s)cG08ZDp{MDJGH1unRK0n=@1BI`q4 z%3%-T@+&*9yuk5gjCdK|H9YloEt6IP5$VO?Du)uRVel;8RiLE-7Z>;%nt0{2-G|mU zIc8rO=#2@7_G%;eCV5c;d4?#$3LSerD$z-KKv(ePN?IK|)li**qIZ%Vjl6LdeNeZkgeUP%lW;BRqfqZccqO!vIij1;>SqWFzU z6`0A)^1C%NC$iRO?pY*Y_F*nNVyF-imAvF)@#5UdcE_ud^vf(VDOuyht?)V7lWXNA z$yVjX1^isq_B|d?o>yCkRNQQ$^Ln-YdS!HI<>l7bc_nJ>!xx^_J7kqpuW2lAx^!1! zuZZR)wZM+Z>d46mxj)K|Iw8WhqKLIm3nbR==d{P)pPa zS&?I8b$xQsi*myVTrUe#`*n$h-A(=9g0R_V9i=<#X+Mv1Bde~yFmIMbDUD~8oNfu+ zIkmlrEQjTvlLlfayiG~I(bpVLlwj#>ol9kC^sWv0I4j7FoNBu~4s+NXFOxk4XFYH54+)fxJb_5cZw zDmXYtLHF8R5>gRi_+iQ_UF0Wi^5sQl#s_97&7ppV2QhBEJgl4{A9utPeBJnM_r%mF zN^j;S5s}!Jx`!}H$&G{}{#nfbLYj`vMpcl&uH-*p2iXepeZtw#ZT?YbZmH( z<4I8PQRxcWjMyvBbW;Y6XB9McRwFFo5L{i@os}mCXCn~pZxZ5BZn>a`BZv&iSNd{- zVl`T@r;~AMadTQ|x>PTHF@1WvCf5S0!7{z8rzUwKuIR!=EqyZzPQMUo$x+^MaekL) z4+ny|ks|TDURU2`tYvVopz)`I^`%J)IHagdnntKTT@f3kT>jypG9f!PS?*2Ai!9HG zv>+40q@Aj^ zxQR+@O^ul0t(8ByX(*L?V`ow1>G{_SD%ZvNQEW4TFI^iZ@YQ@e+v+{Hs0d8RY2sNM z9d8}g#CI74_##Ue8ppWX=S1H<8xzjN*T_fkNRFO=2&-Tl28ji-S4s|{HWRo`O2Q>< zXCH~kbFmA)5ejs%O~AZBK9kikOHNHnu)?uV$m&RNdnGry;Ofcs9F>~qi4ImVt$g0% z+WErvnT9>DkJ`mia}1;lsI59oDw8M`Mc!+%V&q*vy=bb!B-Z|w+B_8)hz5*JmQdh% zo-3%!=}S);$A^7c2WEO9ff{h?>a}hfQ2&sg)GH;&zk*~iv_jlSvI;|!M{H?ZQM$UK zz=cP?gm{IzRMsL{0p;!Up{QR53xh02Jl!U{VX?kut_-*)(j{7hQaeDHp0^A-7^LUX z*^O_k9k%*JNY2Wzlokk}?>OF5XRu2xPnFHTcp=N+?5xt(b#H682Ao&7Gz zH;Cs65-9+^?r~MGh^n3vd!RQW5pkfELz|r3dxA77kx~CD`K-iPYm#H|z)-_)y(B5Z zxVTv+XcQRkvuolO{Q2pj-d-n~zIgP;(m}COgTo3vfQdt@{S)M zG!_y3h6!Q!OM%Aa@k%sXwr=eesR!Nt%i{x~`kE8%+wop^C8&9JwM!4Khwe+}rJlIy z=vV|;xK!mwM?9W7m#Ytm+Mno1>ylIFa8D9s&Pj$pL)2V~dSa3@uf(00)GDpz!>e+X%UJ2vufZZ^$%rWc?E*J8o+e+ zvLurQ_^v)v3lar1aDkBJN*bmrl_G_1-nL{0CrFGJZdVf^73?m~2h*>B1sgR+n!!jd z!t2|>d5R*Ab|qeTrc>%5S$+VVG*8^s?94_=auYQ_41i^12y&Pf`YX9uL5O@6T;aRs zOg>fwp&>S)%wU3fnbn<{52kCtYRgcGi4f$FnsDbVW%GEa*-nKitx;qqzYIZs99v(R zs`oZi`dH)9471N*uh~M9ok<^Vu~&?XWPa(fwK80^wo90xWfzlVF9MT0?!Bx>;uMqZ z@tq)q<~E@#5kYGzo`IZNuSi#TAwjMTtYnuVAaTig0VXt#y~17R(Acf2MUZ#G z>AO*;n)DlMY02x6w6HRZ&b*1=VYykS?$$<-tJSR~GO8go@|GB5vNFR-2Cknmo<}>g zn60RvRbnZ@-EsqOEJSdBHYs8x$zqjZ^3ALPdeOp8S@TQa+vV8IMr@|>oyt0fm}$Qy%UBC%DaQ0~vmfzb_s z<&Fm|+;GW*IzJ}OpYMOe)5DvaLP9JE*4j4Wb7+|~uk6szq6JB6*=NL+o7)}g_ z$mgqz);?qa-liO57%+xj-ncPy*qyiF@Z!8n5~z!7Nr~3hWq=neL(XTa2=Xi=a$XQQ zC!F-6k*19Caxi3Rg&?2bC7f>rKYc}CUbgDh%^z9$uoff0^60|?T)ym$Q0C}qxv@Y& zeQf8IS+sWM?Y;~zgAcx==`5q3l0)+{h3{=Cv}_m$da)uHCQ)FVMCI{7+d~U$!!r?@ zn>{sCX6Uc^@^`Hnz6rrT+9+XRDkII>Sj;fF1%X`Qx>Uh9E>k=P_44K_;pcPLXuX0_K7~D--Pz}w^IkE=i*y$q3uTc1rP~YR7(Uz z&d7}I<74^ovF+QSWMrb0N?&{sPTBpM3Me+riUemhLc0heLt?J3!WMZ|p%|$5ahyKs zYmouG;k3DJzOGs1yAeY()Wg>lEcjbxQxR+A_t9~t&Jd$%b7=`}T_ZwJ*Dx3g;w4;! zLCwR~;(~yA^=>`F@QR zO&TTBn<{+A88YONXb0} z2~=(|u3qHiAW+X+ylw5I+0-l+&<;(<+2@ld%90ganzIqa^mjg+|kuV4Qg#aK9rC?J>MV?%J!^v;l>;%7WO3etU zD5}LKAO*b!&e9Ly9pxCSPZa3)r!rvLM{tBEPuc_fcdTFgthWY9|=-b7rPuh|>At zXQ&tXeJ@8Wj6AT};pRia#Xozl1ahlm5?q#0(0;Posv|$6v z9zDtBe6Xk0FQMU3F@Bg0jP$;sbBvR9l%Q#40ogpdufknkPcGJa z4FXmJ-CkV8B5j9c$-=|&4BJl-BZSRh8SFr9o5bf7dUsQ5(7`1<>nEGt)!6F6EyHu&eRK+-$oyjprmbsGQ`qA#cZx`? z)nMgMVF$Un7k^#7pCc97B_OM%?0=~=AxUhVe2hXi+LBt(KpZZURKQA}-(86SB!U8Q z_5MEC0aE#Jr=oN>n>F09XgmY*J$BsuZmEDCzmp)@_e3>E@j#32_vX4c_(XM*BrAuN8%T!uy*c z&Jj^hK8%v~yywl8BkS-ls(QUTz5Q9Bmh{8>DckYQOaouVZhGIf2J^C(zBNZiD}QV! zX`6$O?V4#!nwvEt`kIe;p;QLT{FYw{cvOze_PA?Q?4~>{AT)ubLJYRN&7+}7=I-Rx zGxJ_J@P|B-1Vr!_6U054z3KL4S>f7BpD`Rnd`Hu{cqfr$NQ^M|zSx&VYNXkWdS@M7 z^W7#5x|fVlYr+7!@@M?8J+f!lx{|sH2zf6Mqi)%?MHiDBB@-;kHcB_y$;&4Ay^)i=l<|;fdf?jk^cE3~c~&aGHtxOjX)j}E@4Sa| zPtp;dp4`%hyCq`@|9HR?*AvJVdVBlKEe>*fu4Z4}(KfDU7dO7A@)@QhNA_a6SkCd5 zIt^Uo@etM^So<8NG3IWh0piMYyAl_iMhp%vibj`_qRa4Try!=W;8f%RCZot;C)Prh zGyt@Oh2ho2LlTcc7Fr=51?~mtLyMzWboimQYP^j+C-xcz+v1_c%TL%fvU#$fC`;`C z&LXtJPe=J!ixf za)c{z6~DL<6SziH09*JTyzmZxIujC5cJkyyZ<6In^3GcF&KGQEaNx$lb(+I8-Ef>* z`cqwkY{V%MbYTgFvZc{qEhulAq<3AU&sy6{XT2*!$8cCG>8h5I>2;U??k{Sn7JBq< z-sa%U_ODE(J$eK_@j1Z;X-{a{V-bl=Dg%1sW`f{;WYDmH@nzTZo7d&Tab9OOW%z_| zAzk*7dx<0ggqS^kdy@yzED|{^fzSZVp~EwhsO^u_aWh>HRL=uCgI&EM@%g^jBaZczN(i95&_{a*H_x2mHDE@v#)mHGyX6*tg#|!HT@7CS*-t9463)2Oj>IC%(U9)Q0RS?&C6R`8y4&A)Q)e` zL~s5SnQQdvq0= zXbAYh$#>`Q$G3OS1MV+*pBx?S|4`)|4*3IDKt>Pynb<|cg_@CmM^@<3O# zQlUgK{DC%GdC>zkiU=S@_v#66hKau7YJ!w$1mC0IqC*sLd#Esyl%2B zAB3=oY|^-tz6!^#DWgD$q!}9zvwG1_}Uxw)aMZgn%4#7cgHrJ{Sa@2{rreh zo=nq+rp`RtFHAi=+d~Zo!|fzYS9)({%tHy;hXer-K#8Pp1V^}zOAasS6*)9+cvrvPRD%o9}*1a*x= z77<82q4hgyH7Vi@g-OnOgLK0utJkW9Jm(?Ed<}Ya?}{5F@<~=9hZW;7pE!5@o^6ej zER|~vIwo!+R-IUk}3sELn%xKq}@a0;#&NQr!7wN>!`hmc}lctwa z>HS6H>On`m8)a0ea)Mm#@tcXoAg*bmi`GwtfsD>VVj?t|hq+$M^>~77SmGn%@@(3Z zc$4%;@hf#MM*tPwV7f(W_LYE!9&?wHG=RB|OPJNH!^)+Pz+%lOO5>ejjiD`T70#!P?)h$m#yt+1|?O-q+K; zm9yRDqusARcQ=0StnTh^ocvfm{IPQQbY5AX)$m;*j64{$>{NGw4O+g#=7q7sz`k?i? zz>Rvp^;+Nc=br0TF5har*DL;WZ@I*JIaA{!f%pGa5g8rsnHYTa&)D+6Dk5F4n>*TH zUMM1OU*wOcxV(5fQr_2B{g2-A|80p7>*}kk%KwTj|HBd~{_ic3ytI^zjEsL+A`dPs zk;KHre_A3jiOK)8M4U1U%~SGp37JZ9Y5cFK9pAlc|Ljei5 zUT z4*~n}C+Q3yE3DMt&}QV-GJ6Z5>sYnROfgN@(p}Vvr}{wEnB5#PpYE^#?rfL4K8~5W z>b9lZP+D1IUwX?rEu>i8hrT{mNSIhS;lg`8WmKp5lZ7-L?}jEsb^p2P!Ul@iW;olr z-2*V=MYIjD))V*O&t&{G6}cI{^ioL9*Xk|XtbEhhx@x|v#~qe4fq|AJp}Xiz^e6ji zzg6AVOGyYZ?W4QIF>k^pR^n$M;L0mlMmHBeqbZsQ-8Yc?aS>kDYH8cA&>gg+trhFD zes`H%N+n~Qr`nhHgVoC|IqmrtsFX$kQ_OA6Z$2`MA7zBk+gM|-FwO^dRB% zdIqKNiLYtjYLwF2C7uM&!48#yo*Cy1t4%7stJkI44}70LXg|1z_U~U1c!BAlfqqyh zQF)j6t%?ashvl<>O+2xC^wuD$hjfWSq6dFGR#R3Oc}p zhx&4Z%;9ep;s6yDO0E}Q9QMBJc2WF)q}^pyln=lE`=N#bX5bpSyGxKx=>~^R6_74L zMG*mMh90`R8>A6wq+#eT1qneZ6#<>Y@4xT*pM9Tu@3qca^N6+PDHp8k{e685*n`+! z(Jm+U zbbT_zSQw&ys;8Z3=1gRQxadBLHUY;U(jLgEQqmnljZHD?Y2b9Xj~JB@&W3Fh;mS(| ze}Q0o4em98;y)dTsD}CxwQne0+EF(-hmyC@KzP+IW7yTgBgLS_%woaainM1aq)ss_ z)yS}#^jQL1WRmz1WJJs2EHQn&m{Ve8L{CpOEEjq!cvNUMCY&Xg>y+@Cj*OagoTb#q zl<+%hj#;dnrM8Wi2)-N{dw6x0)&ngSiqIUlr9Dp{)+xQ4HZtxYeV&1iDHSc#oN%!? z&s-WW6>lAx@bEp)+Jcrz4rxw4%{5Bp&wp@ivYdXr}qL6x`Tuowh+U2aFi1~X7 zkFwTGV&+A0XSD%SBCcu>gfjq;3KjJziW!jWFXf)#;jQ8Z40?!JR`(COf@rNbhxhw0{c|pWM)Mr&JOC5@SZNx&lfrC!j=1^3njIqa7zsUK5@n9A z4Y{bRC(5w2#8f8C+K977l*GPPdnt_ zN#bIiLUV8+!CTrt9oWw|O|e?!FS;6&k76R7f@9M1;LHjS2vh@t#I%39*1;C!d=z z!<=b`S?Tk^&HQ%x2L|`UX5&+XBy!=0h}R)=rEy{g2v{I!*p|75QmoW|;!ApuFFeLt zg(F-5FzaEZ98L}6H_=5|g$=;~(NSX4yx<6a4+-k&Sd%s3rsy(-4`OP`p)sPv4 zZ8S%1oVl${sUK+;io;6vsI?)l;MiIOd&?J%LzaFL87%pZlmK(^vz6`?8u;33bx=*B zN?qwVlP`;xib|t-Io3Vy-Swx905C4=6;8zCxp#b;tx9%Y-#o^ww~63^b7hmbNqZfK zTtU+H`hw><{-0>R#HqFfef`#k4op#~?Q%QpNt$xQ5&DUyne21Ph z)2KkWTJ;}J^>DFWif*dk9bDu@P{P}pMNBWD=G?$YeHfulXxQ#6X?6WeFgXJG*r$!F z)dn)DBny8^Z?hEUw=a^C0O03?km*QdTR41MkqzU`rYH&Ee2T!qLO#)W6SnJ&%Mw93 z7%2&X{}@D0<%3!|;AjQ9Rpuy~0wi_<(i|c_63Cyx4LB)BkzqyH8ApK1L+xKg5G5eb zNU3jy6rjz=bbBk(aG#s5F&%)6+==GyQTqbXaKY6hP3;ki?@HK!C3~{$a{M1xu#7n%>aFhc+Qf@!BRi> z@K_2j&>=Ov!ih|-4dCTAg%qG#k&!R$WAUBi6IcOMA&)JYK+wL#y$_@u5H9|vgvZ_h z(}8~)brAO;Bxv!CXE=&ro0cGv;RmLfb!!PoEl}oFe1I<;ofw>?cMg@|0k8=SI-DH4 zG{`wbximEmrc51mHOUw9qc})Ym{sFND#(ujJ4``J#RVt|4V^$i9C?5?>(nSAES!ea zi9n(oI1yON(O62$Hd4#JBGs8D4SPEcI{_kb0)5THP>%?_B_&^JYJG3T$4!9XC-`H$ zY+t=d`+}`noKJJ^$)4XshY=#c5dx_?CA2(GbutIyG}9fHp;MrYlNRz+8b0%2*y2eT z*ozBgD>5qt>p96NxLwdS*Df8&#NAGJ9@1zj zt=M1b3BRDDQt7qr*%}zHh&Ku}b3o4Lf~Zt@_VF41?Lngu$DL#6T-3)zA}RPxzxWL@ zaSF(sf0Y9{C0e$I=wrduK-hyIk{tyCa6(RzQMxNZMxazdn^5{wn%s}h@kFQpg^3Ak-0Mb({L2g^gW?-{}w6Wk8@5wPbT=3=-3mM3?evShK*Yj zh9jWAdT{Wz^9xl{9U@a}3DVr9fa+!F>-=n*%7V}7FtZE*|03*gT8T~4fRPnu=Aw$r z;zi05NBGw>JWiICyZt0iUA3sdxu`p%=+71y8;fuXO^Dr#bqx@zYh^Z(V;NYK*d>G% z>p$d5MJi)H1MVDmMw#g%qX5Co61HBbht?yw6Csg7QI~lc?kUkhV9^oFox?4{AlmHu zWQgDi)K#h|+=XI-27Z58aM+W{H55A49EclKDliHxoX7|h!gGC#Bxx&olpqpfz%Db7 z2Cr6CBvB$wm03_Ztr~m=l#G2EgOgBoPq+e{U_+abhu4sYA4D^Fm?xE4J;n=6WLD16 zA`slAsV-rgC33)a4diYqQ6uTpuYw{a;MrBhkTifT4UD=7e^SX3mRI5VbhwhRvVbB1;Bf4wjKp^9J1;1 z-6^%Ed0<3p{sXFL^k&tQPU>xV_X&whRm;q?dhCSy@xy9Zm8Pn8I<9`JS~O+jsOG(B z4N})u+|$+Q^)?wX_l=Q=>fJXYwVK6+o$4 z-nTV(Lppn)Ydyp_Jpg?#$!s^NRWC5zMakbwo!v{n*2{PUrMu~6mF;7s&zSyAO7y&=@bMIX|h6X!vs-2gbXwQs5yKJkkHgAzgTgLUA|@!|zCa4csc#*d_gD zL7j+a^2UY3s5Qq|R=gQHh*Pc)8mEI~4egF=Bc*<$@7PDQSw_qKob1*{DOGXJgGTE8 zoFY8OTCK*|OGZ1gohW+7)Pt1X$2j@Pj)$bOa-@%c@N;@FGd|HdPRlWdmYta6*H^Zh z2o4`u>YP|xo7k{YT)CO}C_A}hHTl_ZazA_WuygWgZPFErn}0NUd%H0}K6&9cb(yXI zmZcVV+wzy6jyyl>at{>$2Kwh_YJ`01snQ69!Qr&gda)-A2D1de;Bt|j?z5YEUeJWo zi>CfF;<}+Aeb%r7s{_#u;26tTa*oM}BR{H&{?E0+y z17(j$Y~5S?C=h$99&`_8X|B&CBH%Y^#QFka9oKMz(o1eRqA46vvnY-=k9e?{t9zf} zWKm^$&PQPBrOj-auCnX!e2M_M)%rr|11c$oRkNg(2fxV?$15Jw%bo7`Oef|oJ(sk4 zR|Y5anjcV@uCMJCuNj}N%}nTa#V#%i^UH-5A2>rA?_+v=z5 zQb`|i8$L=1d`z9&O2GNp5c|nn@#AZMa%n*+*?=twqfUAO?B`EW>|W?I8;FR*j_dZP z54fqUHCtA?>#Q?#yY6K50=pXn+e*Sa)*fPN55RE(TtWe4?;d>i=z8y@$94VtGdsol z^GPj_<&8$A-IwxOwt`&th>!kyT7Hun?(+N7n1q#}T*0{qn;c&IC>_E?`GaJ=1A6a8 zWS3T$pk2Vp)Pr2XEWLT;4Ya6M)BE>c!`pq=+ye^xz3L53UAevRICKi5fh)tI&HK&< z_I>0|B8|}0@(CHcu2wCvaHl+}-Jin)qa#+VgZ`V*tk5qM7rXm6AIjN}M>i-}__X5m zxR$FGc3q$f;w_8vFEwBnU zQjM``cKC_PwlzV**No(EZ)c97+ehISAG~x9`HRTmj}G6=03Fu=#T^Fy4J|?svFJYs zl-nnf7sGr79SZv6yk2HBBog8c9XyI-IheVR@Q?%6NAPYz?YnPCTcY0y+$S?O5R_w4 z5V`}jYKtuQP-lzLcOJG$Y+t~3&V>`GXY!#Ybx_rAO;Hlz^sYlv#pCj(^DD1TJ@^Hf zMZ9oOSZ{_wO%*2V4ciLy=lZws zGVy&`GDCxZ-inC48nRCH6_3y8vxn`DjENiG!po|E-HIgJjm8k>$|3#(yie#C7+lbT^9NnceJF)HygH?TheOZ)_iemUbw<0@f z_8SJZKKZPuU_IeCU2E8==|9<$z&i2Hh2SoE-UbKk`|*0j z#;=DC9~bRu4KMf~VFHHHmr2E6TfY5?9s%sxrMbDWsqE?%izNTL72%5E@4!<2(!&Db z@f%6UA)rOx!pkw5jYOI|C$!|IcBk)A!LGt;G>&V$%E4Wv0vxmS7O`qfZ*UE|$wI6& zRaxUN^rPr0DnXj@viwf8TxG>G^(<9x`|T#2l>C%n_b>c}yMJ6DvJ>y-D z`-UQVQjW!6wFX~g-@?oKPy+Q49UsnaIed=iy$qP;0e+lNU;ZY2_1Q*4;U314rkP_U z1Jb(+1h!KK_wNaK3~78ZFpx&vS50XXhU+#Pn?AsMKG$yM-)v%Oxqf2u;HCGGeD9Af zu_ZL84=4P-u86Uj{oXh#)g)<v? zLi=i(t(tFSB{n*A&_8Izte-cJCl3UgK78|YHfB9Io564~d5xoL^$nGpHq;SL+p6>M zRF2Ou{EndZR`6V);ZiXCgO*K<`UgTwuRH>@WhBvInqAs`qOaTDk6I3^JXA}i_A=(e zsCT0|h$}XVEEd}L(}F*}vKHnJkSdmse@k5ujEOD1D&ic_$Yi$A5%isPR7j1~<;y*I zaac(}pX5AKZm8@KTK{0#so5~9gF^y-cI5_c3b&uo(3(NZ5Axlm?EzwMyLpKb_M5y5Y)&` z%ubTnx{V#|!WBZda3Vo|d54XmCyjdHL;(}!NrFdU#BA^!==&jC4W-^%-jof->P`*{ zp)SCqV{cOwD=&cZ-dMmSe5Az{JYOH(#e!(2lQTnH>{tp>9ZP5ivP(cgh&Pwa@k}zQ z*8^#ou|P4~FCzI}k8|%?G_4+&Dzz2@rlX%n**wEuX&jBfx?THW-i9V zJJ7{>7HTydQgFPlE*VNo{PHFQz-?C&Sg_^~KH4s^Lmxb&rJnBu0uykz@wFnP=K^kU zXh1@Wl<8V1m8MvzKnbr`Y34$QMm||>^^nLw!+cFt5##P~@GxluII6Z6=wY->9Ya6M<#+QUzJ{+&=0XAFyxUDuC8|NfJftRIg(Y7H`utGtg^F`uJlLR!^+B zLBeK6jAUQPz1bj-sB~U`;DbD*a6ZDXpHA63m3E77lQ=r0t4>JRUMu@k@eL*DPsXuw z-*)U1GzEP@HOA}S;aQtmLIX`xW}+0bLBud&8x5Xl5HTz#QKUo)TOT|?a;S<2AZ-w zR6?-NK6v001q;~0uQX@Yg=BE(?qz5p+0!o(&&3&QP4?JerzK#UmNf$`5SexFad3|< zJ;w8yBj#KY@cJSw1;6W|c=z?U;sGU=&C5_I2#8YRDrPFnjSxgc4nGui!Wy#oF}RgP z!hDKIDNh>kc6#F{JF=K}fiS$_3WBWR{`i{=g#cwnGBuPe%UkPET-==KsLhbAI0cY+ z^sktW&WHh-`=bpM*w1mtuOLu=H921|e9-u_nXhp1Ib++S@Bv%+RC;rKN&>M#ap1Uy z5hN2r1|svcfm(r#k_R7>LW~NJ2sC9t)~Jj3WDdBc@9|X09$jW!yl1I*(%2f2)rn9b zPzk2N5+Hw~U-LWTl-{dT$(ki30wP`Wh)a{3?&D@Bd0-u74Y#64Z#cGJ0EdAoQhNUJvXxHb-CeruO>fy4I<168MF+cJ5r25D}miOnkUc+$nB{lEk#??R~uP|r$S_az^%#L5#D-z)By zVTa(_b-D)1Z06&Ud8&vc4>$&P@3M8TA=0Eol^I2)6pCRkB7?yiO2G)_)&6k&n{p!+ zh^R_`-|J?xk(A~)PN`VfEO;k?SLZ9zKWZj`ncy1)sCVW zD)1F9jJbS>+-m3vTFu`N%Dnc$n0y$`JZu%J9x5~(5)%`eJ>>m-I0E_(LvDu~Kr|dF z3PtLuM$T!BB9;7;hvJQ5P@>8+Sz(SEnwkUZi80WmIi>jLBk-zW>q?a>l*S7-NJh41 zU*HIvRev~SH1}d8Q>BCimner_Yxq(#{%W9HV+3PcSF(o8MTsMUdnHa<@hjccP8yY+ zNH^>7D_3N7a#YQZRy9(qLI>H5I~MDtP`#y*c=-$x#7D6B*=V0tw=#zF>pfhajXYgSmHcM>n)w2NMB-y9;S&+^*S(PJZ*6 z_++G)p)tApd@@y`b}t#ynmieYoIDJL91cvzw2^%F8c{`RnW09Kv+*LUL(S8}-mTsK zT(3S9D|lF4^FoGN@|~KeeDcNk_hjUc+y6T?lv?NXem5aMXKTQq9pTov7wpL9uu4nL7$An=9A4Cl?%&N1ZDbr&1hA{702@14i%ItUk zS!sU+?cnUE>{_|+v-j}k6udQrDdxP45=!}uV5&x8)?k~teii=-)v&qm$#a^6lUf4E z+gqusCZo;)quZie^=NMDW=`LD(m>33V~x}uO&Y=taX`S8+XjtNCfACMnZJiv&d)#C zoqza!{t@1SHN}Dr$AYcc!eiA1JL3g=`vnL8n5<+H9B06AANHbLdoj=?7^0Xqynt;k z6tT3Bh%zb8H`#4l@MMU5+H7JI8-MRo_pa;WONuC;2dIe~gV+AyH(wUwdQ2AF7`(;Ssj5-=3^r%q7Dp;tD<6Jo0k&H%}OBV z5hqJOdzJ*`%rnx>7W|;8-q5u5xS;nl!LgC93>*>0QCYfC5fp?u&2a&+3e6Rm-$Zxv zJS5+HzL0yRJYP2vScx#RNby;Tbh0?|)WLS1cVr&>xi9%>HMYta+2ux1FM!k@Gff*_ zso{V$Jcw+%70kSqQ}!()tt}JNEv;rsekiPPt?N90Ku~Pe@z`KBLv1^sJHW~lGAn*J9hvT&wd+H2#q}mnWfQmrO zPpKtF+@nUiE+wjvTRI_nB9YqYu&;BVr|lo{-dIcibiBjA#(Qne^?&tyjde|LYa8FzG&R&T z)K&dgzgJyRR9Rk9URqpIT=-YQSCn5=n4ery^t9xk%5zFe%5A)tn3$Lv7yVz#Gcqa` z85wn}Jcs^^@*EHpbPGNIJ>m2JSLiv}-~B%&e4bABUN8Q0!WSbY{kMM4}|giaP%udj7xqJz1_>h$1aH=_kyc6$ak6>!Zz8i*?rjfSzY(#*>8?dKu7QffyB` z`Ce!2PYLfd;#r&H-3q>kfft#XgU|BKzbyUyW)&NU*D;uWxzpL}H>O!#d1+(gbVkX? zF6LRk9+o~|`EX)o-?217Y?Py|so0??N%N^2vU2N7Vwovru-UTh(ZX;N-;~+J_LGR9 zZ=?g)N$2CMjLntnHE%D^zHRkKW2g>4T=hIQd$OoE%wQpVi2ai|=BH4z(lPTf5j%T= z{4j&*gz2Ma_BuI+;Nim>U0}+AazrPi)03Jcb37(ox2SaUIQBJpSbm^6K zOjH&XWFPLZYXl585hP&4iV7o`Xn1zg?c_PwL=8VAJA}MnhZw&m%t%9L>ev_Bsd%JT z?B)6qi)|a~#~EuWdj?-P=7S@p;6dOVo`jcZ=5{v4c7_YbymW`k1C_MO=Z@r^@RdV&Bw50{Q1SaMwE<%^P`>&&M@B z(F&<)kBK(L{*ixyif1pVHkii!#lO&}ASZ{I)r_cFa1L?zGe|{l_~b9(>6e+Ren#&- zRrOrpPgwVk96eFm^~C&693aUcB9jX-@2pbb|3kHHKTYU?SVNBs{Mbo0_4u`$?pXWl zbN0)xzxMJY1h4js(>$&Y%FAl64y#+gUb&nho?U!tTJ*R+ZriK9{@VHT>-D!D{5v-% z15{6LPKUYbZqCLfzTKRo)$jbim@|Fy`}>k(-R~c3FTef%xfOBe&*e_qlRv-q%j*7I z9kqV@bA2*&2Xk|=_yqI&a<2~a=jP`(3OWZF~Bh#1zmPxi;H zfg|sfj!IhzQXjSx{g|K7${=(w%=(zcNc)qSANNoWzpj0-*Kkk%^G4|w6(l&rK(^Y3 z|4(4`!|Rd9ickU#CvvTrfB``HhZ(Defq_Z_RI810hR)}~j9oK4DTh0GB&s@r`Tvc?y=H{zBQtg z7G!@gvuvqS9fZ;Lxr-b7hds*w$QraR;{PFj4UGpQXHB|@~^wAy0G=7h3-0iv9i6R*=3 zKm;mLzU77pIGx6hnk+DfHCNk{V4Isu{$SP#{9sFVtz9>=gI7SIVOQW~TH3VGh-=eF zq`{{&i#g*e6;Q5g5cEP| zW67|qO&03&=+?X8-vWw+e8k$!673J|YnABvqRk=2t<>%ON}@!Y1#YR#sNdC!O4rz5 z98kn+xb^D%y{LCjUo!uRMS>{Dt@j8+JBhnAa1q+5p{}(1+xzZjM67FHQU%kAdsWo! z^f!anj60bNf}%`gLVD%f>YI9cb@;7pBhjW^JndfEccHO3%Ki9^U+Iwytk%(UKFrHv z1R*qTrk$U?>*Ojx(3z@-pS50g%yHBrqO#U@IYZxb%0E?c2>QrO^rV&Zk9&k6wpnvu zI;O7B(k;|k7A~4)?p7;3BB21^P6aJgSyOzmaWxI%Qx2KLlfTFj*~NdBQT6Di*O7n^ zwXzxY>wT53(9;%8vbJn8TII*9V!MwmB9}6z@abzxLYn$izp>L(=-tIh^4oc`l<`!G z&8dmB?;uz0a)FFrL?4;~a6Ew6c~*>O_{MSu?JTp6>p@n11&SVHh-gP&cwagYMQP)6 zP@dP12u9$*{`BF!GT1eR7B205`Lbk0cE5?S2i07Z-_`ODg8i7e^vw^ZVp^Ef4X&LP{V7i$&*a#Y9*{a=zUU+c=+(9A`(Bw?ag=dHaQeu!RE& zJ&CUp2{4|J#d?x`AwsAk)tey8&QGt>9YdDW0^1e?WvR&|J_#58;Mh$C#?O3cZGs85 zgG=j4UIA>FE#guINbMF$?ui_cPq_NFUXv1F8!Cpir#Jagn^8D09D^b$KMB^nB&pj9 z?hhnh3GuJuLe}b&Quh0}Us3|SNHRE`ZaVM^AnDr*MsM8)KM=uk0!%(u6}DW~aHQI{ z-lrxHvIL|IO9a{)_ZSU@-VXDfL^WKJ2qL1}Ad0_@09Pk?+C|LdDZC~e5JnI$1Y)6k zqM%#E_12MlLYm!=UwvMR5uT+SD6DvnLnfGfy6@E0dh^xcevi%icCTV zxEMqt=ZG>6K)8FWKjsr8mID`U($Hm;NIMGPArr<(8Nu37G9&&HufoMfl4O3NYzv;> zGgpDNzluaBIR(8mk44kQ^=f0UkBINiU9VeCmD98ynn7b7lOx3d&W?bIXlo-4z~qsCh1yHwAu0u4W479O4D( zbSfTJ;%$ib)mb@RDo^n-@FNm%$jI}?_2Lf7!#=!!pb6;tPzw!}cX1e>LJSeW$WbC}VU zV!)QzS$he`T#mJ`Zel86B3()w8jlUncj8rdTq*UWExW@~ddOPF)ucqG1Sv*wI60P4 zgq9Eq8))vAg<6z{`<5d!%M);|pI|D>HQ2DZ(73Q^T&}HhW)-k4ssfFwuvGveX_re?okh)hlzg3Z zjp%7*okhj2i~Qy&S$Ss7v9x?GE&1S8^^SDi%6Y9yZ_QPdTxn&cWni^RP~{YDCB{YW zW`+D$6h%yCeWp^qZbLmVChI69U1ZVl?pXuvs_dCG1=DK7;4?5O-&+c!x14;6j|1O6 zfWPH=Cu869_Tl#1JFYUKm{lnfI`P-0jq*X2M=P?zjyz}tvEsYp6s?BGLA9I8Wong8 zPC-qw@1zlYl-r~7G?s<;vgi$?$)vQU-BybJNJ}@mNSj6%T53}o^EK*UOF`%u9lyxL zISA(5y}jut_HAzwK5ZGrp*pKCkg}*4tZb<&X!YS!XtQW5WUH|EY(!pX*sr!3!Ydtn z+NxRFP|*so*X=2f+ehHHUu?^iq0p0IwC`ysaFq&u-Ek$-uF%(Rs6|*$_wFsIW zN^PlJI>R7pGRj}1@4t|CuafqTk@jbiB2C}5W{H+ccMuzNjASWfTzAd}SJv{qR}y~5 zvr|>!`u??2dkRj+8fL8Czp&DMwe*XV@-$sn`rG#+I9{k(d37h!0$1-{GfYN7Mv^5a-XEiIc<`eZ7d0`NNsr|{Ivi(&0Ow=JYiuHGC%2! z*SZ8zq)bq9BU5ifQ_?>LB{M!`QWc~UF99riaq}v!$A})!OoDk(VIf(+JuA4>RqjF) zAU=fO>tuSYNv2p0@D-Dx&U9@fd!H5RQ+o~YOb^^WWo$3%x9jU?-0sR18Ng;4q}d*% zN>58F0)s<1r(JLPf<8d4dc2pA`S6fIhP zWxxW35&6O+FfnA2ZUA4hmV*@#kAMYK!DH7H%w#z&{N#X44SPb;94IW_oHUjbh^H(- zpNzl~209nq&gVF=8(4a6m_qaK4r&9>2%IbYNZZ%=!pliB75M2or84;0v#RA%BLQk( z(ve$qu3?-xA)%(!l@@E_Zo!bK{%9Rk+Ps;@N@v z)(r!Gry=*6=MpFUV`p0X>+TGt_g8E8eyvU2R~-Tguwzd!x5%Jdl_nuDW}VDQMk6%QZ?=@HNt$&-%vveM+di&=%%>JPIU&@v#_tm-kS#oKz^H9YG)8A4nextcZ^9=g)?;cO+9!^vVgDazE9BM|q1nyN<&Oe6t z+sG}t^e*@w*ZTjK_l~6>yjjc)UQpF<4viJ|lcNmFUYdQ{HZ`IGbMmUHEUap5b443v)b?*c}_c+=nok(Gx6tGHOJOUnHSn?(a( zY`z+B2!mWXFSv7ptWuz?MGnaOEtjjcD!RSm$qOEn14fSJdIiV_kBjF802k0=JI0?J zEm!Jl4XoD4FR!lb15yL9+^Ksdl>cNh{XP)8p6W}x5^$uN1k%vJ2@9jTH z%@a9r!RWbK@g3~#oy1Wvr5uiT zecfLW{$>Mk?*UT_0&0H%p0A&r0)XcM2Wjq{<_Y zR5*Nma#-{AlY9L^MBHlbp93eG)fRv3wmuUtF`^@K`;0bw*eqa| z`~#+f!`jK}$=bT;Y*ALB_2o&@C}Ozo$uW)lXXl2s7KN{!0i+Lg24O7ouMLjAY>?S@ zdU;mx^auh6^4}i7hcgntq3gfh2$HV`2S#l#sJvD6VI3#FWCb79x9^+gXnts1Kg!Rg4rU$ zAc!H%fFX)Vf$73s0sI=3fs8YQY(XXwiNDY!pSFlGfe?A7i*_{F9C3l&fG@BfqrPbx zZBNW0MWQ!l^818jk{Q6aCNj=jCTs({VUiv&nR@gP87D+M-Zc4iI|;D`26zdB(Vbka1?<#`EWn@sAD#a4QJb?n(3p1#$BvY8L{BEbJ?`n4Piw_@waA zor1VK@KtOMkqgO%n>9%N)uky#0M7PBsIl34KG8ziu6qxj(I%Mqk+D{+fi*oBReIpJ+3Qa9x@o*L&J~MwP}j4+n3d zXSHIyMK?S;lcU>sPvl2F#Ash4ypfRettx-EVaKP-X>A*mZ+}70amQDtf5m%4*dR}J z+ip*q{s!+TZX1NtbGjc@KfgV?-=8D*2JGIV>ojuo z*R9{E^FihQ7%*e@N2l$8p?Zw(KxyOjlrLgJ%8w2%Y3;;HYB`9sKkld0EG(m z-9QrSm53%t5$&uu2YXql@+1hODY~Oxh3t(?P#>A89lQ(*j}C;B@MQ{j1$^ew$kJtX zYEVyp5g1O(v%#Yo`Y!5NNI~H52saohmcxW(|;wGi2 zBQnK*UyM_s0Wum@8OoV!8l}*v7s<#2844b5Xk@3j#%)r^rSz&|wZLqcpG?pZeFW1o z;>acCMh1qe8ED)){AQrbv6DbatC+xo?K4*dnbgH;{%oXkyZ_ovnD0eqqRoq#NWm@$ zGR!r(p0hKJz589vY)1iW2%!cD)kVC!otvF94V!;U9>uyW8c5bg9TI)Fo0nV2sT(hj zz??r(H6HX(9lkQmk!E>lJiY4k^E-@QyxQ@5R1pg3c=8LK7XiKP7$V-B}9$Y}Cyw&DH2 zww>TZ0Wyc2{wU*H>s|a=rgnR|6jdbi0=830#m5H6xMa(faR$uY5oennqmb~OES4_& znDXw@3g_tbeTZ2o&s=0&}C?3E&YGvwcrKYjdMEA)-zN=WgmW+RhM#X7hpKbVbJ#vOix@~;qTO8_Afq@{O7DBW8tbtj~nSm-|7_E{4+Wsm?UcQakHm({B zd}$6&S&*b?0mOo&l(7utth6QYNSQ7URF4LV4-(8neV zkXW|Cghw8UgG5J8oRjI1I*2n}{5FTKi13R7I%07acPPtIW8-!N6%2D7n7MipvDVKW3vhgSc z%VwaPYk3Cw_;OZEBSE6|tiQHwbVp3pd0)t2NW-chCxy<(dM5A&q_{bV?8`?6qHcGB z^6bmbbSF|5kjnEAS$6xmY}7(i-TQJ^8=2L>(bSgK*gYJtDkemeF`L7BO-3q>)y;)C zdk@Fg#D@g1I*v3M1%FOac0yPqZ7b!lcWr8T*7}yl8D3YmJ!AX`ZkXD9C%RnW{v*W0 zuRk5elxOzn9*agLK()-YjgcvBse&ROe;%S_4#(fqgdpLJe#C@ElPl&QKG;<~7K z?{a@HHS63xq9=h3?g!*Ss46FWLs>Jf5bluI;J4?3jP=@uGEg{ag6U z&Rw}DzKg3HKWke}yi0gS6U#PBr(4xAf7}xTLx}3pv_AEctA!zk>>lFIKE|ZPu@Q@Q z9}Ugh`U`qjGVIn&U)I!6@7FJ#IK70Yp*(wb&R52XwJGIP?^A|%Ve0es-Cq+1EL1|N-sJ7@uwG#5^le2)SsX2>Rsg``ox;YJ=SIT zxEn=x;O}`+){~qs@1HdNh;|D;Et@L%z$2Kj`||cNnkpu%kq5t1_~+v+$n|n;y*D<{ z_=j^{m&(^T_%PSz#kFbkpY!hQa(4a3Zmb<7j*0}9N>8+c)LK6TL@t&x)(t*_%%8Ex zqOwFk$`f5E$cOZh3?SEKB(BI5eF**@Z0!7x!N&Lfo1b5=eti3N@#W_HmRkCowsd*6 z_w(f6jB{Tdum5A5`|5Dv?91kVQA@W&-QNyxm$^57?9G1NU;oDf_t(!${~uf3eLt70 zj}A7EKCd3{F757bAAOoT__VzFY5m_#bpI1y+S{D^uY}{{+U%#5;l0J4|1ili7|9zkPKgS#We;?=mOI{lOr@YiVI`G#xcW--t@4MS^ z?w-!STjkx4gLVWx` zvfQqBORQ7=Azb=Tv_{gc(0{Ql{d<=CpSC5R;A;^9K|Ys*ynOy$wRGuURZF%Gcp9ql zcaR%TYjRuCfQ|nmTr&O_;nK}m8n7XIEmbr)QS{${jlYFU{}W*2tkh|(|4W%0=l$=% z#>jsIY;ZI8j^Gt7RsXUrv6l(Pl^XwN+tNSF-2WNaP?pS0Z>sL~*A>(FH`|i=E88HK zMi=UPE|mw(f0emkKBU=}>P-0t86SlH!?v`u^ePKEYafE9aTDr^#j z?yRNX5lDB$u=AYJ5R>Ag<+q_9(;pk8`(j3NxZI_ar)~X0=6{(F0FJ1SiAn}%QcdfF zhe=7$Fc-MH$V>#-NQ=2Jph)|28GHPjw?8Po&%hDyX2&|)uUDdnb&dsB$T!Dc^D}T{ zJ>*)aX_tI;na@$|pT*P*(?|K<^4uaMYKtfN@RS_9rAbw=R%gaERPLe+R5<%Ardd=b z31KJ(PJ8I@A@U8#S?t6uMI;uP!0@~bWz5*J_Wq7q328bEk~c&q(WmQ|>4em(lNIC> zKarDJxge$JuM&Fh_E4^V7R*+-&j(Du*^IrxuEMnnG@St_o3}U}D#u+*RF5rg2t!M( zc`$~G>)<=*%P{CZpHKHrPn?O3VXiiux(#VCV7&>xCk`a-hTG#5ty87bZ?3XH^9=}$ z!(=j8=7=n~%VkrobCad%olXk(%xZz$-Y4M9gKXLK5;6bdcpN_6+_MT(#=W~L@{k+q zi^+U1^OX|5GH3M&jBqH?-$u<;pnqU&K4B7#$_vpY?9}8MuEf|{%xgRGD(s>@cDj)| z^|}__yD&52c0WV;o6cJEm#H@TvnJ+E1N&bdIezHUyI4tu%4OE_4c;I(F#pK?qI(E# z_S8{2TtoH23^{|%S7nY;ANo9Gi430vLLmA_t&T>qiL@gT>A=L$yRu8p37o_iDZ z*;ByFQ8a0j}lzcvB!F<{R0*u?}q zgzoBVNbSmZnz5^}J+Y7!-_%o!Hr0>kNJ~ zQ(XJaRjRs%!(|&~eFB6AY(P*Oc^T*Kbpmaiw&v+E&5Q#|ItmE|-!QIaZJ`FbT6b=MViv*#X%jQMWZ~)gtTr=eB+Yo{KoGY*K*rg#6tXsK9TM9WZ)HEQ-ACa4Y$A=~x15NvSRxKlqh%S~Q;FKx`Ra&BDDspC>HQ5QpO=f=eUHMk%F^ib0EYqaGg45w z$j3vhFtYKKkgy)|p^s@nRj^^)*K`Mqh*y{%C1d{as9)r&vNX% z>u^1;j+f$@nnuIknvW$_Z~kZ7QeLK8$bYgeg;tCGZCh%z7M|%T)%t(1Eu}{8mWi-b zV-5ddTaq@bHooxx25dZkX!m6FRej`M4W6aO{+aP?WBy*PkJ;sO5tXwor?NPLIxU^WBp(_@fgK=z9ersksagwmy}(s_92$`AgFJig*30L?zsN zSG+gGAP0I0{CA{duPqw`Lc;W^BXBVdNnVG$ztW{9ifary<{aaXZTyVs@|WH=uA2S! zOcGwN4KT{#jn$j7lX$w0RY{a_N}rQXH3`8&eBD=Z_gg$kb$26wnMP2oVo{Vs(@Fyc1 z#_wFOKjP-UHx5L$>Tn9V*a!NlkQq^Sv_mq3U)~RipZZXKJj8(<%nPBj3ky?r z<6%lq{kX20NftVL_=aq>?jRmCkuG>9LtgIt7gVd3ih)5Ghmc7mDlx|d{(6}Id&Ucq zs|Le2kV;e&Exncp50aL(JCPyfPha7tp#=h9QQHnB+#jyV39Ga0eE#zi30Nc5$g#_$ z;z$uy5gR3_7fWPT83%hJLre&l$jCCBGGTy(+qfAUUb9dVITiM9z-%L=;OCn)^CxYu zpKpY<|9rcd`lREN+4soBpG$`mPr44Ce~CH zX^^COa0r%;qojwx2?n-O%ZTqeyXiCrFd-R}I#l6fiyyY=b6Wy8J*W~=Kh$vb+xb$& zk05xD96kHh%&Tu!(XK{dIgya_+V7F%9>NPU5(-1D%t;{U@Vjb~R&Key8**(*wL7l~3kn$GOneX#g;oj)(~Sm$Bt^)g=9U*I2+bD5LB9$!S$ozBOc z``!at`tWL)+cNq@RX6$Wju408B{WmqLwRhc*UXxAwS6 z1zmGD42y~mgX4MBMS#`|7Q%Qa6%XA%u$?b;gf<{j$Vf84^ik?sBRM#JlU*YyPJIrd zB?VkmV>;WzZh~fwS0Iqlth~>{moFhdUATszyJmh!z#S5J)MMb7C?ncb^6<6}mQ{z$ zEuL#}2F)r2*vZ)2iv~k-fw<2M(IGT_Q+V_#hO3HdS2bcldWKgo`UFq%+~O9YYmnlE zM@JMGLe$97J zUtg7CFxR~hO6|F2W*EbcWCDdlvY%M%L^GU!ZQFHS<)m9!Vfd|vVGi|6!Mv5h&2#2Z zbg02~LhambW!}V2Y0g}DJasC@N&*t6Ad{&iFKWQvh6Nfo;ff6>-1e#QHUc z%tMYzX%1xHg)>Ou(rG3^G%x)M<5aZZ1_|jVo#M)+CasE8qa=dqSYJP};a+ASE2Mr@ zCpShTqBc`B8d4Q8DcS0r^AsP(V2>Z+$e(MTh-k!sAvu88wl@JmwI_o4(&3^OL{Xq5 z3?RHrWuc>EAR~n$d>W3U6KwTCYMXEvA1Aw!%XYI|2*7jCGIM#yb^NL>*Qy)DGM!JC zwagnShd?e!WJ=nJ=~riAKl42?0Mx4SCmevqIonhQ5`M^% z3rcqzyse4Mf*`LXPG^JZvLVwFCuj$`HTWPg3g)z5S;bs2(Oj&?WoEat_IxK8F!|zP z`3TFr=X-E+W#-0eUYhgUs0Ay zKEUq|?k!;VyHw}k4yU`%Xqn9r3WNl~RUQf_kWX?O1NYhGxqQVQjF?h`io-uLg!2>~ za+j`xPxLm(1=HzS_wigG$(oW8cQwjp2u|ni)WLY0Kg7HsMF{ z<*4_o_B`B}EIfDXT<@)Yy= z<7ggzX~0(_kotpzj{S-}4d`jEO7Y_%^+f(st=2~RgIDsyVyoFIs^4st{G@-Vp?LbR zQsjZ31)BmOKNqXK42PuOGmNgGF2f6w9)_cspmTw>ZRQP07U!dDiNt`OyJav_E48(Q}g3}aSsu~ae=s~H*KnkT6vQw zwfUZzEM=wjnd!7Bu(7n?1d3V<1-3%zID)wO)No#GFbHmV*PvM(?7ei{4B9U%U{C-h z02I;Qx(#aG@)3o-fI`LBueH^xi!^*=d_3U;6r%!OMHh}kM7e$l>~4zBC!U~+@Mp#f z&MWaIi7*#%H*YI6gBzMpHfX-6aDymPw7)!tuP_e>A)*qQQ8?(R0^0)R4EmzQh%xKf zI()(rNR5U}jy9eC(xi(iB)vj@{m7W4z_>ky&jh*KzLZ#fFO`JXPcs3^D0d-rxjRO= zObwcY(ZYQSe&vWKXHQbD*09b1hl{S1Zd*qRCHQ$TinZ|QvHsEOik(La zXt{7Boy5wzz++vo73Q}mfvF)VxEFLBEq2guZZJiQC)ZFx9X~H}Px78S<>$>2Cgxm< zy7-uHB~vv?x2>YR;js#U&TNA=v@v3IIGLY(yTc3#E;vRrc3!6ZAtWXg^j+FYcF5HB z(_In?UG|fjdU5zRWqM#~tP;s)qdwISc5Kn5TTbbWbbOPmr>i zXA4e*>;sv2zUw!87q*|7C^0%WVmPKfue|TnuH~iTQoe=2bE1bU@Q7&iu(yAaYQ``G z**7=C++)hxliZP3$Qd`q>p^QRSKH43BHXGz>(vESg+knogW+FQx2DG7Tbg{+n7xJO zp-ly~%u5rSY^(kg-O*$59b?9|!aifQ;9PxmeEHaNiC4gP3TaQx{MoIZu8Vm3&QZ~EhI%sI3L^P*6? zD)Q0#6{$`OgCGXjlzD$gEnf=HDG!mv<0(WO1)e()yJq0e-)6xO#Gtoqep;vjF8>m$ z=r^44;=wG_mcpfxS|GEke?u>pf6Dxf!pv=&`P`95BE`eaE@+=4_8XOsx(vAnl!Fv3 zdfvo3oE?vBn3heT6J{|t0>Hjz7Oac21BE<{@~0uwCkAmn^a*|4KPNV_nn;l%vy?NV zVa}ksOEGiAw6pVB&ht69=5z1Ozbr4jST|pE3wibT{QZ>r68VJ(w-&1E#=)rh>bDE^ zzZWP%i;ZU&k(lYGZwo0m7c0-!RMahY{a)-5dee9I%@2dQfm`!E1&hy|=c8qBj|I%% z3*a*CeK~p7!_{Zez)k3e(_7pxk?P|T&o^eC@hO};3YQjzmVPcG0z~K5SX?K}ZeTGi zM3gYw!V;tRo8Ro%{cpjy0>U9N;XhMs=gc_QOppS%?$D(MmXev1yqG8Qkk0p(K|J8h z9+dSDKsf;L@&SzHR|Z$-IMP>O4J(L}m%{Zn6Zg2#kn(|aq)^m*?TQx0kmZXRY6^dB zCY-^x)9<*aU(bbqxNz;QUCg7C4Ri37G_-J_ToJWT;)4y{lIfD;#MyXTB(JOB$2tkB zEsB9B^`r0;IG%OYMcBc--p?b-jW_z8Sxow+rPV7-7kKzS1)lp9I$WA7uT4Md1gpmYsninn{U^k37^O`+mg%YoT$&a^*~JSXF8sE zgW}b~`ap>A`hnzHdFqvfsP+ApPYR+8BRxwGQ>|{NO2uuaK^xK=&RLe#ixBBlZsdPq zIC$SvgiAXm_jBh9p!A}D1NUG;sMV!#O!(Ui7mE+E212N>FIinPt>mNFMT&#{=gmE( zf~&Ts_>jUI%w8R9f376CeEs5brTx#w=bZQ3saJjtukW$qc#6T+AP9IG#z40T-U3sn zK$aYDe_X*ik&&_@ufo~CBLXc1Xct%je$jwSG{EBufNs~J3 z-ix4H_nkCz{;_vHW}AvX2v~WObnf6o)4sXoZs2X6knabJO{< z>RNpCXwu3r`o|@=pHD2TWY9p{ZEpW}KgBDKdIPzu0{5{i8w1_?44XSo19=*5bFQr) zJ%6OnbpH2ZR%+Jqqy`$t?6Ljzb>I;sc-Lr)ID4$-`b{zc5d4z1yXtxrR@-73pmSwt@hyZ^mpB2rv zBw<#hm-kQGQqvlEb)4+Xe5JVBGNzY7re{K zw$!2M_ii{_{xrC|7grKVXP$Vh|G+s!^}c=cap?u+}!9uKL~lUMFsJou~3 z{nAEvQ_Z}R{q_mNBBvkQ3s3Hzc>BYNR_1;s@P%bVp!wQgW$wEhg0wRC$LIHt+uD}H zcBRUm{8i@u^=>{*w3r5LME$ux2su;#SDAbBF(*CyhWZRE$e1p1>EvIwrH(J>m)KPp zbr{vC6y0jSixWC*o$Q{~`lfo8)f~2_qZFit)pz|kohh7wK;VF4-&fZ021A-{=>-aD z-SRbu-BB9zJ`|!`!J``kf^n-&NUhINk`j?3pK{sf+g>r0-k@Y6@Mja zCTKh$VrPGJraoITxS|Bl#J@l1DP=_zd@A@JT8^=jK$Uon_~ukx9vNvV@%7EGbWC;} zw0!+pM?R5st}b{u*YRR3k6Z+ovG_Z$J?9awh@=J|7jny)wWUJ1%R|8wa%V%+20SUa zT#U(R66NAidk$RFU39R5709Dl5^JTG$pVre9*@LK&sg^h-ZRY>KPApDzRHO%oVwUbsp7lH+bW9cF`drQSvDl<9#ga zC0?r8dFn(ZtJhO;)#*EdiMGtP+kM>pgb3Hd)X26fA(apxVMo)EI-e@?!{>1xlpYs> zJuLf%P`T9QMGu-xiO;3v)7fNxPf@OjyYoaJu}DWxaS7kM@}`xZqA^tQGf#~k?FOq} zwt*k2YZzOdgJpHQz19Omhpk#(oGKgk$mgEAXJ8IZuOEgE3)=rhWs$tsU zv}xH_KEavzbi6TH9$TRy5vWPi3o0GI%)c5ToWYM5!n?dI2<`1*65tj0Z1WDepz%WO z)#q#hNkZ(G8Ajm{`w*oJ~v>pDv!J( zTfvAjHn}!RPPH?nTeVD7@}D*eX0T;dloy4igA*~hMOGB)S69ADTC zX&4;(_}U6cH@z6txaVBwDAr;)+OjXNx^>yVpzYP0{Uq5I2@@U#Pr|@Dce#W-Ht^PE z{-HTNmfN73;Kz&%gaNm7p2NEN^7gkC_}6U=B^%<8Z}8-X+^skr9;ZVV7=iitoej0D zk6;)r-W2t$se@jzEV{u=cck5Z5~2f zkjPaG`*Ys+GkhKVl3(er)YhLORlZ==KFX&l*|rA&~P=)sz^Qeu$k_A~Clq3~l!_%D?V9SIt2AStD-q1NS-HR%EL;L#go!@TGuEH?F zMvSWPjU@XgOsA)s+mDg&Au(gC;4XTEIYH}t`~ZqIC^{U|1`pN~yNO~u4ew!!LcYK9 z>uu7~>Qn0s)jN~rU7`o-I-LB|yNNaDJ%!bb`J*dMwgn`38Co#lq7b6Aa%tC>sm2?% zoMXO|B6s&=dAi7T= zsXL%9xl?@eYdWfjRXqy0&eFWj5g~LF`YUV-yUekukWj=L4U;onfyvDEfEm%LI(1Iv z=ucBiKQ?kvG>zDC&&}H9Xr_tle+J;6(RLTR&c!uZoWF8k+Zl`|xo>_r@oUZS{2xnw z{p(9RKY#bnjxiqh5q{x_KQOn}-<5*QoFF@UYtPgN6jLL9d9Xo-^yS~+O^#3vG#n#DZ#0=C-yLoxv5hP9t{wZ)kzxsHc8SV45?cTA?ld8+@32U^cSlh z83YkzL_l(D9Zvn2?lmR>|2|qo^!7qG(Z0(qh;UJXbl!*Hf4&2;ywmpt zgp}6qKYmD#HlL&C@F#J}F#^>v_vP;JLk1mb5>pRY<6?iibpQFANkSCuxI+wajh?&d zv7i`O!1imdG?*NFS~<$NP%b~w|GKnF_BX+A#ynZRW)FwJy=fDs#oz) zFO&XwK;zc>u3&q&GCRYJ2OF?}-fJkE2)A7jaGvVDCa7u*#b)?Ciwz~-<~0bRN%&2Bu{ZVEYxWvWq3GNj-F6xc*Bzve6z=O z4zhb=^I{S#)r=yCPbpmLq&*efLtV+Bi)j4J)ey${QRP_ z;@S)Xiz5ZXi2}T%e&wCM#n9|zx#6)i5DD_>=0t1{Q9T#4UrVa-9E&}qH_gR{!1K6p=r0u#{YRq_D*|DyWWQ=i0cQdFrVSRu5lJxK zJxDz7D35bem>%S!NCK0W<-}u{3T2wmGd7THkwBZnH0HVFLf>Yl#WF((6r59#B{+NH zzy_C8W$;QVK75&1BPlIea9k+Gisjn~G@L+;h8~Z8Rg&|25tcj}M>#7hh}$;>Vb!N% z52r*b?u41fz+UPo4#F;0!H&dCVRNQ5_Zgp=h6qV07cMUZ|0|KrFUvMOU#=X9EVumCZ;& z_Y8bLvIry__1V}E?Cn;pi9OP#$(yf^WAlo}=JW+R>0I8v`WgqLzQL$^2@+dnr?3(( zo)%0B26|`FA~>iS4(cI_Sh9vU#wNok*oUTes8`lwRj2JPJ~M26X^4Hssy+QZ+*+W* zJPwO%plS#dpWOjsUtj9T^fkjBQl~{y577OtIFxcR`R~7cxb}7P2a3 zo5Te4MMzslkg_A+I(%HSAz*R9@BZ4o)DkA+VlR7s^})x#SzCw(OjC2Q_H$>TbUrZN zt97hq5~e+8;6Xjm&bo^)l@tMHV}9&HEScC?H{ibpwNz{nurVCf$2~C{G{TvGhwDAn zbBgbDyfz-c_?&*db$-Tc>^KnrcD&g>PGPGUpsk zAh2e`dWlP8WS8+QP)hTglIKgKlzA4Gcdv6@mVVouk#`+dkKG{-m1@I-f+qLslHo6!bwJ{`EQD05WQAV-f;_g}`AcDX={jHx}U)A4o#gm1c_r3| z$oh6gVCjya0j*e`w0h5tcEKv_ecK%VNB&&p<}#~1oXy3(&BuL5$v!)SF`)K+JUPx& zVe(O{`=7Q81RtB@GIh6*wUrcklFG*WP8mlcnZKOZL+OD4VeYls6~^v7?qT96k8qt_ z4x_BOlkDsVN|nc-NcT#dJHdx~s^|l8(<5%!BOUAcN7TLg(2X!h)lKyzqhDwG7**d? z&U>3=F3DhX&a>uf;vcU`_H%BruRic>TM?^rj8ze6myd1Y$=+^xcm#7FF>&i{k@LhG zLBV2O=%O(&~ z4B#J#G#@$1f7UwV0bNWpKE^ycDhitUz>O;v#t$q9roQE#u#XFxq)oc{QdV&4zWH{f zvYhpYcKr`q{BHKI2dciQ+h2ba^}*|lAEj#rmZ{y?<&8499NtB3PF-yY`{Eq`rS%;3 z>4Pt7EnnK}-*?Pj7Fqq$b!COdb^@~>dzV}-RQx@P76z8y4SIjw+XHvs@&`X>F8e_p zVSTslK=M~7u)p#j-*C6){NhPtM6zKKYP_Q6pD zxa8x7oaOPk%^6o zpRC{Z5#J{en-36MMTqTq#7@h`uHE-N@9+Cz-w)!yALe`~A4wrl{DY?XrQb3iaSI_4{0b2=;_D?;JnA1O$KOu+m0jZ3(Mjx6F;s4+SH96s;uT zgv3WzB{Qaii6Yw>*pNp|+hWJ8f_MFdCtp8R6imRI<=ThbAKtz@w_Uily+H|172Y|{ zk-i!-tTl(-d2PP~oNj%r%gXV{o|BE~K?t+@lb!W>GUQ#_!-W&z2$4Aa<_F%hN7Etc zXGjP~#Q9GrbZ;XJ(nLaVyIJtvSXu=uFwyuRC`6?5iK+LFf>$H!UR<#Q$9gAc(p;YO zwfmc$HVKKg2Pm8S-yJIV9G~o6e75KGde8aOp3A|WE5kniiIkhJGdFv|)8vbcmb_vjN(O(Ra{Wj} z>gV7dY{n@u4hhi$8k$!T+`JP{vzMz66x2u-2`)*lUO}$~$hn%f(K~m=e-IRY=o&=C zW4R_l<9D#!?zfGAVR}FHo!r+S@?1%dPsdYQe-!V|-MxQE;*QjmCE=$EF>i&NhB!KFXh~(O*LGqAMN{ggfl<;isVg;2L016XY&tO zS?>RwhTWs3VK@FKr1H1#YyVeL`QZOZD*q?t+}^^Ie_+aAX_)dl_2b94{~(o@|2tCo zFVh@NGxz_8QT~rc?3-85cBjjhUvw|h)^yk6bm!t!$L4tH`p~_tXXK5(#4nxkpP$Bl zYrVGqIOJ1fB&`?wnYJ2&K2xr&J-WP3>&4c2ey(-Dp7iRym&dtw^FHCm)@4mV27cb_2OeI)(?k2L`)ora2m{ zJkZ(D-PuZmmAl%SJKLK(S{qth8rqv4j%7qX930Ah(oECL(HwIR8|!JBx%%4bx|*to z)ejPC9#%alsVFZgD=(*M=IZXpl@#AEx>uNXzvyyt$=}HGUyazz400No{Fi1fDf!{(XPCcETlC4dLjDz8j=UBeeD!)@ za9EwKWs!<<;px-==*9X4UcKZO=yA#a?@a6^C;TM`XHPpvw|^7N{UZ?TNDIUoncEqf z{T+xk{AVEc)D4uSVSZ)VmP?NbMO^#_KE})16VIeh zl?K$iy{X2F{UKGDxm@mmTQnT6ntE;bj@zhS7as5Gym5a_=8s4XC9p5`I=X9u$V$Qe%tGGtz2S^?S{ zj*H>v=9K0-U+nFoylb+!6AxJ~A6qwyJ1Cz(!G;aM& zX{H*DjWyQyW8xZ?)Tu#n=AoTgsghia{6EP;FV7Ohxl~u^4l7Wxh8N)&y_Ww+zEL#?_~P@ z6z66=eYPA<10JA-Yu|+xrc2j~+ZT`W-7*Ql)EKDvwln$Oe316J)H}VIBf{!2`cSpp zeNbj4d27a|(o2C$lY<|bz&K*6KW%@9@J!bwts+;KpC?pef`eN;?aavT0Of*}5 zcZp?s?p(mJySNUPL);?<&&H{axv6Fo_9|IzgF`x8YTyi4%CJp@PJ&_irp_hF8D*|0 z&67MjBS(iCW@c=*PcUMY`Q#Z`z!lsY&-A&eSL|L!uu%xgcjGqOwT;8gfhW{$^s^5t z)tEe8@pk=l>*iDMO0B|qFqOx@xrd`U%0)+CXzkv-kD50xFzGs}61Da9Nw-yQv4Bmd zNv4_}Tkpw+Uk%2G)(tHLdc_eL^Xr-<^m~=x1x8?*#exl6QLlPYBDfmswdHOsi#jna_BmRL5lIbc+->{%%?fvk@|E|FG>b!!4Hj^p{`;YtAGpsxlIKNFh+JGU!tIjA>J#{eZGTBPZ@h+` zEV-OjuP8~JqzX+UqlehaSqCz7hGob}q6Fco6%V~C&9gB$NQmr@UYXP#!5B(uh0XBi zLUZHSZLEU@Vb5z^4n{A$H)?tm%~FeJFq!M)-=~nwYTbFp=7u!)8^|fOo>B!|5jOor zS|)yC#0BKIE`v()(*nk>A?-*2iitMj`swlLea-%LrV^S@-WxNy9%-_rWL?#lJC z#igVDCp|3nK?x>r-t!-{4x817+#P$fs(J8qDy2TO(&X*B;{nYVTOamh?CnP6LHjbx zqwr@YOWXMe9cyNfB43X!?YA9tZl*lC`N`zn(ZWI3;qymP2V?L4936CnSSisArpsV~ z!ydRfC6;G=nO^I#w~Kg^ASJkHZr{pr_i2!nICh2g#$mt6Y(Pnl+pEWxD1kj?9%Wb~ z+%NiLP$c6A3^(t4eyJA0QQkrG+TJ9~wM>z-d}eRC2^oH-mz4S`6g1j~)h5V7WKw}h zY4Y;OZ$;M7h7KyJ>KS=0e8{K0q|3n_}rt9*#x#@q=easbqhu!b=g+j z<;qpPjyJqF`1}R<^@qRbrdM=Z(VZ4arxZ1dbCR=iB_dpQb)teaZ>9ul?%FG2gg=N? z2j?>WLNt}@hj_(*Jt=ThJN85=pV#fh?CGQF`pQoN7TTpf()STp~n-(7viB}~| zRp;m{AOt=_#c}(7pLx#iBL%I4Gz_&AD^`0;NxueF#Ew?ciTS-zR1$e%aj&+d%2u;&|A-imWISYC(&Ka|$qI)2LLOETUo9Zua1qpKJzQMS%J;kAuo{CF`|6>@~$*Pw#xnKUHGr8!p|>)LtFtnJo#ShgT5ng zSHNHHgrv83*KVc7@AZqvM{|>1`%fl+Z`?Tkxy;smeE7`b&vwD_uQiMAqt}yv?z)!z zHjX&9qdvNH)PMZvaI*W)!Q}CupESoOZ!}mv8mjID3W|nfVHQ0I=0hk97Y)pD!%5Mq zc%}~utSdn=EedetT#T1u41*73nH<9t9F*o-5z1QA-vgjNu%=^SBY^DkK0)E-c-iqW@ctmuhGuf;`! z;5K*&S2Rey>Qb5wVA{y?*_%TN4Lh$+XrT}s=vZ6vOwD9smIA^>8se@V&qj}6HH2N- zN>D(>XZ9ePqnQ+?c|+6_LUW1X$MATLh6FAgof0llH7F6f1$AysESyU$nj?mgzhsks}K$)9EtV@rPLFyhbLo(lY{KFABPjdhKcyxr1#PeZc2I#(}*N8G84zN z91X17GiK4y*BA(QM7lO`#|B4S!82(quqOZ+0kk1PE{PLGG?Pv-3Ma_TXPo+xp)ism zYm_4SgM9^kC+rxTj=_=dTqB=ygA{I(>D`zL6%dzmIku(KM6t0F;j!P&m$R+4FAk`e0p1|Q&Bbh|~R1_V&84oP?Afj<}`qQyo zKC%46F)JO1y$%R=mWs*UkyzZX2XDrA|jsHwEDQ92Z4%OL$jEMx! zeh`mUVE(AU_7-5`QDAq`2TBq6OS$oEZjfLNUM)?2pJ)wDTTVI8_e6f z#>XWr3+QkKJ?obsM#?8vektUL2C!6p34umPYTPr7a8<>TSP|*XI5?KBh(QNfd(Uv6XEj;Y;``Ybsh|1 zDDxCL?n-ijw@<_@#P6h=SwA$4(Gg&cWH`nbLERLjkHo-`a``r3%hv;;kPLBSYB9n; znkxa*l^*9IQh<|93T)M6_*puMv}ibdD0Pd{iN;(4s`heqRe}GMNAnWm-A0yK68aqq8 zq6~W_GLa{M9uvN$1X3tw)w%|x@*@fBZkf28mf{jB4+Ihu2u59p1Y6(UR)V2IeI+^L z+*y~Ark8I3&>HzHpiI*Z9$jt&ux1rUHM@&dlL6aEM%Hal`mNCJ4^=)7k(CV( zpwkcNSHd6|=B+7)O;xrjSwl|6S~fenG#NlRKWc3K{OefYe3XXqg%NDsKM0AFhmF2HHrK7P!9!x-SG;Y|@?{D@|IZin30 zE7Imygsq4J#>^EC`OKq0k>z8XpvNwwm7@+`nPk$k0^;BaC80&+)s&_uk_qJH?<`Rh zYXE3MM9^Ny{eglywgBb=|#XztEJqsg)yd{;sySiUJFjY=U9I|(=qBK zZ+#L|m1ZlF?uPh>S zApj0(Xp6uzGrKXj*K|bn!Y6+6bfVbCk5xc-$jqyoY+WGAnQgXp6WIEgElY5FmTg

~!6k65TyooiBd2 zzc7IfQOG~Xx|3~HtJ6=Vse%|pfYqQL2pxsBjqxYo%SP9mV%rVIbk1G|6yyN@@m>=Q z{OXo!S`&il1>@Xf8-`%U8`J!AN^J9hWSXK-UGN#rLgCp>Y>O1qE3+8dYd~+=C&5$+ znPL%E=Kn({{;-LKcqh9uyS;s}y@RQvPph~8WC!2PHuXZzfkrqjme@#vOO`4%f)FIM zL}fp73cyo!VDN35_f<*5=&>3QCMV&p$ap7609k|dddz%Xui5f)Uyv;PING7il7);H zE20~bqxPk6wUu3LtNhYddlIO=$Q%Pa6VQHk4#SdvSE5wJ+y;047LQNvp`uBn z%w@fktmzX#%;3G?5riU0;wHeFfu<`fu)X0}uho0>m21gS<4`Qzy8u{LWQL!W`mn7p zrNwUh<|c>PbXO42dkkV@BLjTjfc;<73;HY|O*YRgmTO>JT*ix}70Gh}00Zq76%fjh z&YwhkYT1|cTcAyVdF=+E@w+QOyWQpaOZ^hYxhekp#;P`Ccx8~D;%oRF5yt5T93)-Rx1 z4z=xV%5O&T_c-D)@R1IHFy*I|1k8fC=Yq!1zNCah#KVQSKd>+0OGLTZS$+%7A+|cl z6x1MqVd!G<7=@KV;gw_EW6gm1mjZ2&lKFx<7p=Mrx!*(wJKn^-dLvmeKY8y>teY5F z*Y3sdp!(yJZ51_b@4rpIt>a`IiOL`^W#Bv3>z3k5lt*y0)C1pN2XE8K-S6w#sK0pz zl$d6y2m)osz_a6{nOoh>cMYb%=r^9Qb#J7We;HVN-#Fbin zx&JWbEsq!l_Q&nP$xcL6$5%J8XlC?BIz%`gJ{D9bF@c$Re&Iz8{NWqXu>V9t3 z(`D5=YSpJ`)vs%nz2u?)pVgrHr>p6wt_pop&G~57z%d8npG98}Gp}`2WYZU0xy>4# zPKQ%Dc3ERn9W&WteuYCUk_FGztf}*|Jh*_Yn=8zkxV>No19OoIPThJHTqW0=Te1`> zjhSuoL-KS1N0IB+mCCPxrU_->&ns;J!}kq(=ccZ>T&d@3Hbcs7d_Lv!?d2ubs4K|Hvd>E{*E5|q{_t$9x!_;d zbDalR8kgbm3g36SHhx@U$o2nzcmTgM_5FAK_k+7@phvaV+MAzV!yjGQT)!?!o!?}f zjH+PYLLP5&x^Bf^`@nsFi@$qI@ZFa1@s`MmZPD}F;;!40x3{J5Z_9RXcM`Ycj<*#~ z>?j?d-%)YhN&c|y@5V5R<5%VbfM#F7aa7`OKXCy^f{dXt0nFjRUaaQhTs4`>w z%lcy3cOsW?Cmh3FB(2Vie9PJk7}_0#?&~J(G6z?CvbimSSaePYflCxB(eQ8pb+2Hb z?ZHmrifufZx6pDo?D!!1#9{3DLzn3d!aMJ3(oVu{3z=mwjskPugt;mFa8jUm1JS!o z!7hSerznT4voJR_a4DMJ7kA{h3G>4p`9{;kegJ+7h9iTM`&Wv-+v7H25X{l#Df%mT zAaD~FhzG9F{C{NnIt!TRGVI=M#Y8P?^KJW!z>!Tfefx=DHdFMT0DYb-%;tCsEH45q zP5ySCg1G?nzWCpPJ@kIjw4yvckM7S&SNl`Te{9I~{!>2#$-kU?esdvz_=*6a6>l?s zS(^@ubnf4<^8ZH~HtN5?%0f>_C9(0(1!M#ILQ(UjCcJ7kZ>ltOC782v{!YW%e71UE zcJCaKmWG{4a$A?o41M8b{_=vfi&(?5`^jSi8?~>pLw2S!UDLyad=sX1b&ULN}Wx}5WTzQ9-?PEy`##~;yV_?YGj6^WQPo-%{kwH z^GhHKeL1;E==}DU0&q|`%>d=Fx1{pH({E#Q+wLujKLHwg7hkU19wTZ#a67C*yVUib zpFe2w$>LeJV6W8U?BX_B_Bj{2!t1x)l36^c#?2o^Hx`UfXdtkgJEY{!>qmapmSnaUc-yrxccDSi#Ib5j1A6Oa^i11 zvO4-XvkwV;+$cXP8``;ctEj1M@S|h;<&UfL?QVbBO}2XyuF6Jye2IJ*HQ@jChnv=% z2H$z=hQ{)z>f6r!vDI3ye=Cg^93<6`8`f6tQ0;$QNH-Wc@pOCO6yLB!a>#Lgoz}63 z^GX}owUR9j`E!f8WAon4i374qVr8)Ozy*2?Gf2aQaj%hazFkG+CN}k=hS<=*Y#_0nL7uH zg=7W6Rnj1Q$8kv5DS7t7Kuv|Qk2Y&UUA;_#)(79`y-pHI7W#AA7J_WERu7$B`>Jr7 zGK$q^oDT2%YU&`80$N)4T5?9S+W5A$PH7=FS+h zS8;W+Q(BNK(q({VpOq><``*F}ljVrDz#Uv>x9ASb))kORcQ3FO*ED;ohi5x3TrF8D z(APJ;-iDO7ut4&=AXxTPWVa_rMPc_@)_xXel7$26L1>m%C5N=Z{V@rFybfChSt?(F zo2~KB!FH0XvOo?X>k>3H711Yg9DDP#pY`GXnC6%}brcT4pp=|9I(b|>FzI!gkeDkz zk3UfEiBM&Vw=?*LD95VV={BBZ6ti8rxsqy~a>>3L7ME{b!QK{fsm#Z7B=3P5U}zgV zO3e>W>wgofB3NmEUU@mqz4exP$l7RfWDtKr>$6JE?DVs+c4PtewcuCptVm;WS!x_c z{LT2|UF23te|r2Y`C)m2XFDxeFz63Wz(D?o~em>EdFq|`az*te%~9wER}a^2 zbEQieHf|;D?gN%nJhCB&B!>_J>7@sT+~o~mEO5LNmcg?=gs123|N-+Qzq-Dt8i2A`l^sAMmd zsJ%M0p+6-YLe=>!Z&3>NsOmP58K+s9ZCht0=q#6VWWk>pyg`RP_@YycfIhktuW0e%>|Vv`QTI8*ppdbXU@k6?*eCrf+gSn`Qko&rBu&ZuTRvf za98hi>70?KY~(;REqRZPF!LM-6f;N`-S6XKq?N>qd7bLe-Kll?1BTaxUCvWWr-N8O ztgy#cF;Yu8oLGsPTTG31Q=6Ov8e-7tJaB9kLmqyRf?L-vcd7WjJo#!+YB;uSbVxS% zUBv9Lg5`Rn%p_&UzcxwVG_F|OV|g=#uQ`@iM=sWg%fg-iNyaW@duZ}W@;*BJ__H{x zFFuH{YLs-v=iH1lsFFWc%Rb4Eqt$31n?HJ7csbJ0ZkCZ6ez3y*tYt|&<*kRUzH8PL z(>E^pZJK1-JNu><(}g?FCQVZ2xtuLH~@z|eLDC~?W%uU zXx>Hd;ngBh0nbAe7tAyUYH&ADw8gONv;H@;x#odG$09|~8=s|no8NM1TIKY-{m~O? zwed!xSvhiQpK^GT`DT3e)u+5?AnU|JtGLY<&JCEaj*0zc)us8z9xl2ga{Kj1f2%gZy7QoxKjvJWS)HFAbs^>&+zFD??eohFet}d<(G= zX6=}Lv#xK(h;ufl7?$JLtf>dd2e}2np1m|8^YSafj$5&(*o}h$3$vi|y>)VLpL8mM z>Zc*Lo+SM#Br^aQr>7#=Moye9OB0>jzR+dv&ilZIQR08`2k#+v^Y|%N2x_a-wIZ8p`@;y{k4%c@cR9C zG_B(6tuH>J5-m)+Uvb5&05>OzcRiHOoEom==T~1(l^>ACG0W&UOiH`Jg?jhi&usXl z-AAkBw=Ds@aHmqgI&{sQ3*g<^*Vm?(dwvt9@CV^{I3;drUa5;-`ixgHJ7`>m=!FGH zH+?B>7UMBg60Zvbmv$ZhQzRjRfEr@~W22+*+EPA;5g~plBI{*_&QPtM<7^g%>v28g zI-*|mu`jlGAS-$2E9AhJKa(_fJcx}TgrlPuuN-}=?OZ-#JZl8iz_QRPI75Wv42YLNK&3Cpsh`zh-dS_pHw zV6X-vRc~BQVG^yQbyRbmpfN*GpBd2DCTL=dPI>d|Yo&+nfSX=e+-XgfQlp8*SdnoM zt$gVBbLLJKrg!tLP+h(75TfCmb}a7D11#e5R=rmA(kuAG;t7dzh_Ud zrunV8TX8g@b%-I>+_Rc!gfMBx;`0`*XmwCSBTJ)^F|I7G{zXVTKB?obqBC>d!93F#~8uxocd_NWUJ593hUhZxjZ zrHzyQ%Av;j#L8Tva28PyO}r~-ZIA`6D~1}^5&f{XDRoe%PlS`*cFRi*3OmP{!Qh8U zPcowM8VG2e)KE3!g%LnhUwrY{qExlLQGMr$pV44tm`yFo?m_p7jB&ED){9OURD)q( zcLD^V+fUozUzm*4_9%(s2m!EXnp&*q>G0+^L37-44@Y1&Og$Dwvt2Bg)7hvW%4K10-#~CpBLj@pdxwuR`Q}UbQUuGf*e5_Z3l1` zVU*2b>a}vm_wON}m)VTb<|^gT0Iy*f=NKhXNgxLNEoo#=Dit?mcto?m<%4ReIbr;0kWU91~T2pf;Vy2N%-uOxy&0Itd% z&;UU(?j!25ja(cqDhx8e{6u{#6k7*Z*`{7Yz(qVO>uZ;u*U)dy7J`ii z_s^H#Q|-0WQyj)A1bUOchiep$ZB>$}NhkV`kNPo=qb<3nKRVf7^m%KdHe|zFg z4I%Xqi&s#S_TiQg?;7X)%w}&o2n5OpCGWf<8_nwPQO+Q#BrW%_73%dFc+fhr*fJ&Q zf=~9$Y&{#!d!KqOkroZW&8O!aA}6jzQ-$Km;VHe({1AYzi zr0X=e%K97`fJftKmnoPj5wLADvIslAE z{zE)|Ojth5cN}ovq&SVwzx7Yv3by#rN$YF|*=_rcUVWF0V}IuH?t=p@r72+gD#4ZZ zmW+EfRs*?aH2FzC8H7bY!T<(p_Pe3L0$Tv3m269cU&HxQqN#*v>RjkTmJJ@oaP((5 zuBP_Kl!fFE`^1t)$g6VFBl(m!E+xvS zU|Ym1<{qJfv=tU4&(nNBFlv5~Tort~_lTDdsZ2hr^TvJIRkHlMw+g2Ly}NiC;HNZC zIbE4gY{=^5!Ck(;=vW=N8yTQ`i-5R|OU|FueX4<~B*2dHH^_s$PXM2#UU)XY{r=|MEdw=m}wsZv;p`~B#`EXm)5>9_uCG8Y@J`|>a+$r{cZQ=uE= z{I#k(#4`5H^1tC3<@Rd+H2t&bhez1<>ikN+uasJyj6cBxkzXkBq+Q-R8f;n-t#dkk zeVhUq4vBg4HwP@}e}LUxdn`%ub_9a3=hF9`UZ*IY(@o=QhQ>VhPrmlP zt?PEf{a0yX6~v?Qe(3ylQqS4XRkNhTPwD$-DZsg>bvDIs=M{UFNOf$FUzvI?=B=r4 z)Zb2ftREnWJ3DG>=9Aw}$cF=yG*$nOS2U|9Z|6A|N#Pna=13{){eoSWX{LK=6qcrK znfpKQ+$8j{`o2RocnZ05}I3f)6i1RCv(dDEPi&Yp0*g%R=+ze9kq(vjw zr~OEQ`|XhM5z@?}dkIW;>(k>;XI09{Uv&6HS~v2fyxs+zAAI9+=By~>DPN6-zoQqh zrLbY&6!CT4?TGsLMUPKpB{qEpm)0Tn+1ZJ&V&_!qpzeQ9iraiXb$V+W)=2VVKkXd0 z>g^GhG56Cn%FYJ2dNVD%-kmPLBlZ2$-V{Y>jPL1RUseG;y8JwvOtQYqccS;x^=6zv z3mbRd)HjTDWNYks`OG_=kr`|xK7-w$_>WqAUw5@WGdnz@$t-hnH)hc2ZAT}5;P0+} zS(<_7yzO|TFFh7zm=?A?RILAn08qDH#SNn0wO@@(IsEOtBkj(Jw~Qw3xYM`3byK_Z zCt*f$=;OOKirjnYbBfj%91OX4GUm+JBJ|<$y;yTusTqxvfMeLUn{}#t=1zD{mNr4bX9z!hwLQDB7>)pOBx zpPd%^>15u;1_1x}UDuPOlylF&M?Q&1X9?Q}KHwjooZ9SJMYbjp973h)PdLAs_!iX#EkDnCP2VFQUkmr+A-~kaGR` zcb~dTgxBA^wB(B+^0kXUi<=X!yuNtl^$&|9l)T+@WFs7$A7dQ`Bi!RpdI`46x==Z%*8XAmmS6~C3k(fxo+C6 zxsQFz9)`YjQuR=yBFsdo>fY((Ew{bCgg3M?g&9xL*+GSyCzH1%u|x2yDeI4Sc>lc2 zq=osNnmqZ3(Yfb}yO7ew=6~ucb==?T$c5MU0OkSh59^ZRgWr-Ug%z~0m5(il-n-I|ql5)af3J?S zj}lEp4LZWVDZQ+=%hQQ0Y)iGPb**)6KD)PR16xqwsWBTYcW(8s7aBPGU2U%8Y)fqN zgYW8Zx?-1%bG0{$Ui%uTAVD3|>@`tA!c2`O4?8RJ{S;B%^GO#|Zxb&_x!sQV8EYlk z$>~_>8u--^?QX=cw&$S~SP9d7t`qH0F{H97dU;Re)Zr;-m?@$1Q! zsE1cIM8E&|`sEArxSRAMoDIh&k%%O4_~?}rc#QXvr1c2}Uy`s-qBP}^LzgAx(B*w; zT3n=MYm$b(U4`Q^_*fXCH*8 z=6Z%G*H)w)RMx`vIVY;B8Xl-5*Jy+=FqC#<)n*X^0d8RuA{Noag~{P*T2XRSZ5uc( zR%_yp2>x{aq;ou3W;6h3?wGVX>d~1hoE_;pWw4^|wx}V0+jaTyfcl+{hKCvtKR@`T z(Y-TtRP)i^+!f8oKQ|w0KKXO-OS1>e8vN*GlT6a;<52C^divTscu7XQf#A?ST=%2Z zqEMyWgey8~3m=NmE%PCXC?oRhujc+^A0Y_jLqk`Np-?Qso zv+RfcPSqLAi*#-Xyos#RPl!#_omCaSblJx7)1j9WalCyZ-e3?U9QPpFA$xeGK z(Uq>L{}Z1Ky;iY`@c!$%CRp%v=mVGKyQ%e>BNvR_>X|2htST(U9R4J{an<#+ptf$4 z+dak3EB1GSmw(yz`NEPu4H82P=IlnYg}%BS%XI(d>aegdT&m8l+^RW|ezZ8CCnyt*sF@J2hwO#x5<*CK}zY!3$%1q|iUG+Tge(p(%ivH zPsLxhQVhBSKN5pvjFtH?4;`&qpafpboGYFLML<WE1-~ntiz@-ELM`N>#>6g~9KBvws9Boo}n+ zY#zhqB57F~c+bgT1uoI3U8Cr&Y?D&F84(%$!QAFdmKW0brk(P_o|cZyDMGAtk%^7M zVVz<6dUn3Spp_W5%I2p^ni~RIyz<#j9u~N`w_{CG0G#v$5v&m^NGdAl44r< zdxu?y)nV}l7lrBAD!qv%E2#~acd(dhx0o7Rs0iXe{7T&a(y#pa{_)S()n7mUDeWJ8 zUH`qi{9j`GJFEZh?eFYt9(;Mf_hotS%ZIHm>)*GQetw$&`gv*h(;};}zrFeH=i1AE zC-=A4-~9Kq{(k{0-{yN+Y5mWe@Bba)|Gf5QYi;(^$}9`7EU&!X_%O5detvUlVq@v$ z#?r)xrP-~;k&VTPjm6RR#fkOB@%4rAmBm*qzrrf*vk1$|+~E89@sFLx)0KTEDmJ-;*byoZHX zo(w+yC$`_$JG1O`!g4A&+&}RDO<4XTxo_j(X>I>6zhcAkD^8{sj+$49|LIp` zqmuv6{EFsL7GaTBL&>Td$*LI2ux`qR(#i(XN(M+J{UeI{haH0dGq%6>zwj#}pT@&^ z4GAx7M#gR0t8LR_xU-E1+iPCrX$21z+uphLAF+L{DKiff;;5f|N8Ln~O^%BHP{+mz zH^30kLs0E?R4-b`eQAJ$MoNQXF?M z1$g?h5j79Hcvs;>1^M}Xw#{@UMbCBo9VH(maCGTRik2O!NVnx{v74-{M&bFZfpFW# zTW(Czu$iUI`M70&)f>^zly_cv7pT`=!mh31zJ6R_?!k2_PdWMt=FlM6Ys_

Oo98 z|Aj>lU?k5iN?ks0JQksBhR{94Lwb$o6R@P86;R)IR)rrEbJ01ZR9#_St@oUs0+VMf zq#LaQZkM>Ty2ek(MQ1yQLgLZY&YyVnoKm@6!p5z+^<#5r3dw7(7X`qxOH!rZmg!FL zK^sAO-A34ILD;I$8+4O)$O?L&-$KHSFZ0E(SAlWEp#>Hu5~MZTr#zhRb6}Cm z<5@ABq!o9z=GnIvQ9c%Y)v!lO^c=1c@9a#7ej(!6YucKkMWttTZP-;2_wd5jXUvpf zf3=x>PIDe!Ij$VYrQI2fvbY7`O*VC6JvzmpgOkG6KAU}xwSbIXLJ-jtsO1@G11!+| zA%*BQ?d5v3fL%U+KDQ-%mOlMKbhUY{kWj=O_#Y(4Bgk80`eT4?eibceRzQEiuC9v3 zFoznp`>tYC5uKcYT>L51oVnF#h&f5xjE4BOWL_&l3b4RmQ$1r_-669hB@4Hcw|K(& zE!HxIbCCY@T!6{*yKxao^!oxMtIo*M*7jHi8%JbtAMeiy=jVrY)b^$#c8*#Pb6Rys zjX?s_v!pO6`;!>iv7L(XHhFWQI)~>E-P?iQ*4io{@bld$2>wv+h)^5z7~(bGhQr<> zN!L=#Y+WOy60N6^+h&oTm#b=i&R8f6Ls6)f=~VOkyLQ5MCM4c0<#Byn1LUoUF%fp@ zaNRAQbV*6GDr>pZjqLHNbTZ)Z*m;Ev*ZggpFqZXGD(v33M2i!{+{&DVRN5O%Q0;F$kHxx9-mv5ip%=%RNQ6y(8ZhQ1#``hc5oHf;_9bIPbF9m-( zP*rW08SZy8dF13fiHu>nibAG`tu${j@CJyLljP7)6ueOC3JH6{dpTOVR|05TMU

    v5`uhZ-t%hoHR*u7dn1i2(V&+ZrG&rS;-!SHf)1o+X}wQmT8#8;1( zF03xfwyDF;2B^^nPmez(}J?E`(zcj1E&?5F< zEmfigJnyCfu}D`t;D_8x@FkIu!*BE$Tzoox1f-q}!`;RlCHS%kp=~)JS9k2BihjKJ z^ZcW82<6`wn=X;ukZp;tLy<4RPGXy~X-R;!iOgh%Oh4qWS`J2}7jrJ;TiVu92HO!r z#R|qE+jNTLB5G!?;HjyRUqOv;HCLuJwMtab-dkQPZ`ripMIQUJ5%0zFE1Z_tg^qvx z%In8-nuKfr@+)4CyOSl)s{dENa$MGq-ejy>AT+-zCofK zbt&LU2x{;fXr(>9;#QiQ*spZB`Nr@7cTUc2S^6F1wUlBrx8V;%3Pd4Q z+W~za3@0b}0de=@s`^BZ3oZj5~t354|5kk@;@pQ?x zMZsHtE~&TsCZ`6zU$ZvsA7#ze-(7E8sT~2^G)OYsTe8Z{eJ?BgdOBRxnwt(C_#~mS zIg<{5>4Cq{q??@6d8Yd{K2!Oue2i(Q#d?gStp)GdXO0F?)Z_-?0{2v0mkfsV-6ilz zb#>w*Q9*wQsiv|E8^vp1WY|2-G;AF??Rp=4 z453@~u}1{6r%FDy$Xu3Y8?!$o8hgk>>*Y1Z&GxNtM_ou!rhS=aje&Qjq=OyQ{ zy^KhAwD4KTzK_0@J#j-@c`dvJ@Wj^UgsmQvJ;(f}4&QCebuK}gJ`{c}6;OI%6s#&Z zvX3_Sn?S+cSHLwVnXgwQk0zLU;a`8Rt$L<9DfL$+JB;nvr!LN}-*)DSoBj2-a#F0k z%&sg>m_*tHP8Uj5Y9voTvM?6fN3lXGTrD-`v9f&Uy9r+R4nJx&i0x7bAD!$=01R;9 zIT88C{=fXn_lL|s+nG;(uQ@Rf=Kt+iW}T>ij@B>(z_?5W+|MOg92Q4n5w?6B+{ltE zUyzd_$loO>SSKh9;Ca@sOLXC-X7Gpi@klX(j1fW3i_pjhQpzX9VSxfI&H@k{7)#KZ z5mnA7=sEw3ywHiAXsGT!F~WtYWCLB)f};{iEb?LsknF`o%vj{bnQIA4vd$+iIdf^x zkbJ@fSjh&{88{upkwxbSG2*O3b9Fd#o%P}p0`r~+c<(urU@m0TI-vl;5jX>nLqbJy zAYY{jz8i>n`X$39Y8;3|J)eSg;p)Ir>CAF!9F}%HF)(-A9a5p3dy+=Y=je!*Jv&27 zn1MTwQw5f&g3(}6ErcE#>WoHQ-A-u*D1k<)9bTzH`?NNI6~Jd}R6=M+g9VYv1ws(L z9f;#L#8n6);SAzCt)wL^NY~}p!>FHRV_5GJRWY=lg8s|5^*|7V*eRB!&SxT3{V% z5ce#-nZF^4A9EcK}NSU0$oDHKS?9=qnDOx)?<3K1YODhEO5!wcuN8^5XVHesh z*q1mm==@pZ$s8_R8q6>N69_e#%`u7Qa?8&+$$$!DV5(sN1;N1@)ffLMaBe@>S^S3U z&)j=Bp|o{EPI(TdRYcX>hhdY={XH9S2}fX{1vtbs}gO3QLc<}U|0;>G!8>IJ!@eO%FOf0Sa?C*TI&h$;|= z(4df0BGHpUOtn23=bbg?zb9k2qow)udG;;{|vd~2|fG&D~c z0S!MTIu6g;F5zs;xLRI>!jwV+O9gw6x>bN2!J>^q%FqgUPb&uv$1zvVyNTledB1G* ze%u*b1l!yxZ5-{MEuv#F%m`eu9WL{sx7Z( z@2&oJvl8OM^}YZ*VTACI5YkgY6qd`dM(-QS0SmA~N)Kl?4sgcEQ+heFv9cTDkq_?x zH9m;+MZs?%3wSxGd#hHKT9Lvkvt@HjM zY~H)RqW)S5ry~@s@Tfr=aW3>yhcp!5@?}V|D5#dbH(p@JQk?lfye9{SbLN=F@hbZw zULusBSk5=&hb|-JnCP^k_BQB5TQCKrdiM5CLJf36#tae-<8P=hm(J3z#JI9n=vLjo zjCi=&2yRpZnID#RYhsU4)ffjKqI18&nX?uHh?Vm`8gGpX;{3hMnF<0_ciGtuW1>tBWRIRN`eBbVU0x=^~i@?-2{gB7_+>1l-jF;cjf61+W z6i#@-VcV!mJqk}Q3W~SoDw^$*IOs|eL>-9*9l=Pr?#fIN?=!%PJ1PhQ*g|g}fod={ zRneqvcRRbCfw{1i%EPh59TeF)QTNRQSo zTWWZ(t$4eQqvdi7))yfX-&ovxpAS=;CW{caL!4{pY>(!k^>EA}__(<`q6E0UBjcYU z5rlIlJLAm@#*c%)w^0+XZ=7pMx+DGyC+@Y&>93=B9DD0w&VzF)PdF?OH-U3lj{TD| zV#^kVl;PQO=37N_+ag&X!&+DcxNn>H3y9lGyZ2Bu_t!<<_U$?`dp|c9*mZsm38Qw~ z3h6Bg)wYkmE}uk`(FmuZUKc!|isyke4k&UC#32W+w$*oT=k1>vFyq$=sh9PQ@L??+ z9#{nWwQ{u3+>os25EmHE1m55C%>T`^IHogKr|PrX_~+GoKtCEzGJ)&ba#QUY{JKzoe>o#Y?a;5a=L`;)DVL&j@Zla z4YzuvqU{g$aFgbE$3cK;5`Tk~k84v0*PLN@ibo>4M?5A*9(9YJ>etOtK%7ZJ zNMQNAj`D9w`81ipg^%XMAzs93y=XCkqqc{thR0k22R7T(PhN27DLmABlQVHbYEqkT zc3b_B?r>`s`p_S_0Ym;dL9{v(&JRWKq2;*e%YivG-y|I--O9a##Kn;>l*1Y+Zono}hmFk1eIFNp0PXe=DJ;jwX zbzE}O7!i8zZgp5gy^iD<0r4e8Bl^mD%f87#TX|=6-jsU4h#=?kC(PVQt1QaIXbj?!j?9b=8y532i|W_$vLL)cj1n z#~>wXV(;o3Xx1BDE|-%;x2OEl-S3YeF-uks zkB@AfLOhs@a_{_#R-Z3IBuvU|<$eI9mtp+0y&(Qm7vAz?9&wiQjA7rMGh2f8eh}aK zkaq)`oyOU}4G8`D;MvAGqm{@PIFLf;^h$sK4Z)S(3YfaIB}&J`T})Om90u+0*>+YB z=^VOM4rF6Xgqb@oi=S>;WVNR{AWA{p`P&t|T=qs=Z-lp292%EykU62+v!xlU{!5*3 zOjVP%$g6Vcmlt_T@H|cEh0L{uGYN;>A?tC`o6!x*n!!2}V2dZi+;V0@jUS$nKs=wZ zd}}@2){QHIw?BwvEEVyt<_d4(?GaNNo8Fieu8EPnm3O3-rLq9TnRlZ3n4;s1&o@^- z6ZL1O9TA@%ixS$F_dTz>xQDL?c#kN9^F0_8d+u-jUkoPlwF9^0lycZ(zT}eA%y8ay z+W;@$1n-fZ*XKpmWz-?PXByp~D=BOXgM%*U`rhU!${YBiy8&kdZ|nE&Xl1Fkqiq6t zR@ef!mzknTTrolU`XKl6UAq3PuJ@bITcT=ZuOZrDM>Hdh`S|_JH`$hMv3>SFss(4z zywAM*`hH7Pm@kfdCr)Zc<|1gXY!57`UVs4==Lv7RA4dp25rt{K)u{smOfT1MNXXcB zT+h%z$@lHQ?OH#i>r~*RR_Wwtwh;jbfHc|1b+6`Ernr^qhP zoVmTn<+26Rwq8UN;_lk2{O|ddP-J@1Dk-QgY*F=we&oCU0=G5C(qmWu!X(_+om0~- z0^%5HNY~2$@GI^O9?b#rwnGKz)1@XC^Mk{&I^Bq(8jeZ^m<~o|PQ?S8U%yQR|HY zKAFGC3m+m_c!+j)k-0e08F|Vgi51(QN6eLGuki1ho%UtpT`TeX8M`_nSyUQJlss`?MPqURfr2K-Gr*!z6_X3{^g{Xc)=zD25^ z-acsg$FDdaU$1_;Nks*PlMo#8_W$^m{?eFSS5QA48Nto$&fZn zQFG2{^~(V)zaklx%YfX~>-|@3Uq{6@gsa^~Hq#=zIx;)tAHPDv1Nffd_Fl`LZ&kACT&tk?g#e8=fH6Q<{kX@s2n zC$?{SL0V0aBNpyI2(x9!;1+qdOF!L(zcwKp!9uLVfE zW}v)$l!~@sRR${Oo<3?F-|?fVRct{x>`zh*WDNt1sO3b{3t!!oI!RMGC+lK<-4LF~ zcdUqDiF`LzOz}3C>T*!~mPSFzZUQ0|L2u2gkD{bXyMi+v9_XJW1DKS<=RLK51mCFt zoe-LL>Tj3>d*CgWUx|9=tr!xwdVdXXR8r+xMjfRSP?gS0oa%Si`?xeawkuOLn0Fa{ zDJa+cVEh46;lVjrg+g7L&bU@pg!+&HG+l>*tV>mc8KX^(cHf#m&gVW8RIW2@B+H{O zaF&>AAmA#St~;z`j?}tKlYxFI=c+tExN)bF3qQ1eg$F;iAGE1|j*X7EWom^l6%&-l-3%>bJ!XRZWh}{N~n!y+4$&#y`@- zsky53;RovFI^+V~o$)^P$!jCo9gURhkAIu$CO-V3x9a>fHuv_v*;l=r@ZgNDk>{rz zRX2~D$LSWHFH{k9&t!wK9=oBb_Ex?BSh)Z2fQi4Dd+rsg2dFKt;^kPl=ym;#Ax);y=Z|H z-!NGZ*HycKpk@>-8_+V6>sW4Cc0n;sSM#xUtI!dlUR z5fz{)q=wFzfg2!=u)RCT0}0?9Wa!ozPiH+9r8n;7lkE^xF0yga3L|D9X&C#>!K>7@%uq;UOdBV8AjOL*EnmqTX4bGZy1 zyVqLU7Wdv{L|9ZM+ueyA!(Q%^FppG$s)6y_cfp4wR=a%WGDvZYOHGc5*0DK*J6w$5 zkFmR+lrvi}>Z8sO)3{%U#t2K-3{e`fJh_~kp06LgT6rmP`s1O6P|kWK%y5E}KtL%y zL2-4O<8q0she~|lrQT4-cMQ-eYaYTqR0UCXD>di$)(?e0D;&548SLLta1&QxORiJ` zB`o7P_oUmPM$I|tWu@vqr-r4-=TB#!-&&>#uGWYMP-nkfz{ItzFwQS=1_k^z===co z7q?N%UT>c<(`dC&zWqX;eeBGI(=+F7O`B?Z#XRIKSD75y36&uwS|~-wSA#MyVU`Ds zb_I#n9V$uw)&w})Gz9y}hP!p_>1h;Zx94@9g$ew?*qWw!s}0?MZk1`HYOis7Y<_6` zw6U%-?`tGk>YCO%<{St2i5jQ0)T08-?W;LA=ljx%(La+T4uebAO0} zoV0<3mo_|5mlQ0HIf+R;20v9KH^&`*(Qb7oBAIkx<9^qPJ1#j(!kS|e>N12LZO)2^ z%D;Us4#+I01Nh-9a&2^~!KKjb@Tx1yN*jjGOqxVih$zQ7iCaz!tF5oo(6w(Id`7&6 zVsFwdy7hUq9UZZPuhRW~sYsSVvtqM%3M1Z2@IoegiE5==I!Ur#tJzo7+z^`~R&qK& zoVy>r|6Dv}BHIXLG}Ktel9BI?VOgw{(k#NxFW4%M_7Q!dA5oSQvT3=1V!e6Xx8shT zP`T%naP&=<WIyB)U}J$j>@(C37W2uCq2QCq

    %swh&CycF_OVpjynl!4|v zaI^Sq(tE`h`KLmO*85@)d`IkAMwZo;Goz+$M&62ti&ChT?|GHaIiNLSQ=&g?Lb6)T zdN#AieLbX&eJ($cs%$2wJ(laZZu4;-!qgN9$8)6~wmVe({))PZiPL9|j0e^)w@6)$ z3WHQbtJ5y@1lQ-%1H6utCt&;+4*75L;r~kIM`cY~_y0WSokWpXc-&fx*_H5iTPcdW zROUrJ7+B4){ghb}bjM5}7D)lwRP7-L3V>^;}Ai!(r1|ny%S=8NC#;6(yW*T0hF_d*pFAcCg&^#h!jn~2`W4gXL z8&TJlEh?U5IcpZ@GnhqnHbq^GLWWIoA{&xBhwYr!c48|HTc_;ujAGQu`pf!i(z9i) zwx2=3hb!3xUt0JJ>l-269}6s3TiXXEfdcNF2a?B&)#%Vfi)}HD%XZeNwqunr{&5$} zHD{w(85*@X=cz0$V7QF-COc`f%%;2X-44M|Kq4qau*n^G7dP~G#`;nR4_~_kCfqJt zLiYCW>=r-XZiu?-aL%^mQ0MPVb>~C(gn0N=0Ctq6I>wCO0?h^+M(hl&^vGx?YV3^< z=}GrJ|4mnOE|H%~r%c(4#7QmA@w`wbYHSNYXXx!*4ioK#59ZRvDu-TKXh18QW)JDt!b;$*(vo z8KrS-tIi^%?uDadj$%Ya+CB!lC^@F~>((=|+m@1q8o#l3mv1d>SlneuYKxH~3!OwO za2mkaaTKn*ZLFUmsj*G`Tg}ghhO$f)h)oEq;>?0idN?OG|16pJ0lr zxM++Zbg?h-IH-E7rHw7#>Oitjh*NkRBDzPE!A`;^AX<^Gh76&@DHXallO+s-e*DDo zKYZj^qM)mm@sg>haem8zGDN{n{gp9*f8?KFOsG8oh?elUg|4N z=<`hf0TEs00VAbKxBKoQc0|u+j&5)0HfG$ZWcpW~o9`jO4-Hkays_j{7BKCe*(3Rb z^GLAFWY8a8P3dWtYcON;aJ2EFN|(VH2=h!NGhJlXbe>e~c08pQd4_gk|2 z`FNsgzT2r}$YgN`Gubnx&Y3IH{q(@NI{KAuJk*3I9qNqNvGKyMzhbJ6OI%XM2`wJ- zG$Ag5lU3IVF_z+@HkFY0H;y+C!Bpu7%%QJrOSa_NRNbOC%Ad18uyEvz|P zqCxj~RXjF1dlGLnt&<2fik>Ag*zzL>yJ&~29DLl4c@r)3p*DCmoR%I#3J*HsWLBaI z@>K)PPtFoFk;Gh;;Ncz~0ng*t%$`IS7kqEU_2mBJDdWl6*

    f(S3{bYkpoe^ zvj8<$^q935kGr^cX|7LOs#Bb%?u_UC>ahL|XV_f!D2doV1?h>T)%ee#!cJDuic~?w zsz|^nny4n`Usyk*2I#a&Ys@+T86$Y8%IKcOGzu}rG!&a7M@wne`BFh|QHctCi}P7s zW%ed>bslrwj|i{!3ZT(a+(U$q1B8!kB}zSo+}qiRy1cu`T#$A%Z<~S1Ljg1#(J&f1 zd$~x69+0vPYQp>LCKA8N2TZ>u2-&==-~d_DD1k`eZ8Bs_9?Zu8A<7B(b-Z)vOI-%Y zH=g)65_r<={QCyYuZPXZYvETs)X;|b-J_@tMbzD2{B_L7sE2LMW5JN#Cba){4Fj@g zP_FM&ul9iP<9Ndv^5LyOqwR5N8>HJ(#}Q=@qwzu^uRzKOjhhBh2SIx}=ZkxM4YvuZ z<#WFaKyGNbWCoQ*$ATuoe%paa1%Rnxg!cp+&=`05ls(ptS?46aU5F)C`3Gi>FYZO2 zx`&t4&IWtosMlFK3`vba!mrV(!U(`{Kac>p`vEx5pD%=!J^TQ#B8Fmh8$r#hP#poS z2Zv5g5I*vhNTe*t1wpV~)a#3Iv%}Prhv8a|Y+$3p!=vOgobLXtJsf{?hbJH5kq;^x z5DJ|kHAT%dx1yJ&$;fbQfy2D4G{7-XVlwXSo|cNN6<7yfJDmb zDdZXo0p-1Y#^Hi6^VH}u?wvJM4_QLxm9Q82A_7QQhZAsTV)Du4!!QkOmFo7AA=3P0 z!7|F|2{aiJw0fFt03VQOZ01QjDFP4h3bRgx#i7~2ARGio^v6L13~v09Oy!56!TpE= zUJuX=G<1=Q3R|IUQ?N5w(P@G;jy;wJ4_Fl8Y=yvWL?k2l>;6uHu&{8}Lq9tkVB@1b z4hh(1_u7I7(2iNlpSE_uIgGR8>8#E?5S2*6)SXV|VUGdAy%}(Mz$1^xkL?l8&6$eY zrzZ4l6th#KZAkdK`P0}45--cL!B6c^s?sAg*g)bma$-IabDkChf_oh%qqd>iMil0R zRTvAVdCgESJBP@PKn6`$#$h1PJ}Ig7Y+nE{M>!LXW(yUg5-DdEZc?u$kUxzkg0b zgq#LFm#m5UZ@k@SP*ZFF=>0$vl2AetdNuUkTR?=+dy`&Nq=VD|0!m9rAXGyKrGpd& zr79rOqzecrZd6oCR4gc6RFo&%eee71^KZ{NZ%!sJGix%LwPvkcbA5i_x~G;$PT>Gg z;59bQA zO8%I!0a>a5Mxsemj<#g=*WaSHX}`Q1G$Lao?eqf%3(6NZU)k5bAxG8#(?)P+_-B7C z(e&*C{UE*Kp)3n{ll!dAb`IVWkVZs6A_AbtuLYs!2T#e1(FwjH1-~NUOIEs433kvl zVmH{m`@{Z0NK#2kESbcA(E;VMdWm7PP{$4wjw3aKO|bx;iL}em9sC9)1_6!6keEsq z0RgW1T;wycKxy51rU@d68!R~(=D8GRrqC6#1o|TXl)dqt#+N<8iooZ6AtxUZnOwrf zX&IYEth(hkuj3KSjzuzh>uZJO^&O4QgFl@(i8lZz*2 zNqHewb`tw|@xZs32cPQj?lxo(2{Mi~*~T^^_{^4fMzov8tWLlI zA@(APd=MoM1z&kjXnbc6-XAYZJ~nlMx`mVB8r+lNh)!?hk##J74jl7`Cn{jZ&Ka6p z8GEEt5;S-(M&AI143i0W^*B836SJ!Uh?^<+N=S}PHw{g1V&W=+lpuyV%s#JGJYnPh zAfpRZFvX{ioB26I-8NFHt07VbP>3s$$c_Y5eLB1}@nRYKWdihw{{{oH&GFpg=qlu>@pjD#Pi&T? zSE}jc9Om6+JT`RF)BHCkq-K&JAGmtguAr-tBiEDaz6_j%D#$SGAb~4WbeT$v_AAW^@qfT_H zK-yW~5Yevt?Rlg1nLsc^_B-EsXZ40sgb{z=-pDANHi4G}8P^0vUj^ z<$kW??0fQ``fHO3|0#_cBOf74P{L;TaUSpM+ zSfDDl<>s39LefeX;apXUBnE=fgQUCBMxT^0 zry0VT*~d~i+zy{yWOx}Pl*V{#vD!q?RFdM3z8WiR%H>l$C&^WHD4eh?sWC3BsH3{Z z@3utqE5M$*m;R?1o7^Q}GsBiwq*jD&<(-+oQPX+gKIj6+RCSx|oh-Gd$2oSgn&ZVz z8BHr7nV^!Dl0d(=OZ?4Sjl;#~Z)i#+I4~0V%HwpLeAF8zy=pnQ@J+cDq|<2)df#|@ zH=G67HRqHg5#U;*Fr`aUAqrxhLiOdBdKWnJM)#$f3e7Z4hx2x;fZhYW(^Q85BFS)jj#Xle}B!;!|2O62p zg81g{Rzm$z*V-_Y0ICLJ3YM+{tCP^KFb_^L6Ixip7o$_P!CP5FC;7dP3*`S+%`8w`n#94EIDug4S_7@LV@ zNZ%;2wAjBvUWo5|*#0%cVCoUwgPl0{+55XXbiTHq?SKB7`?2v=GXB{5lbFz49g9?d z;Y?4Ng6^4sV(#9~SVy_0xV`2 zF2f?gaorEij-Ni&E1FXf9oe>cswzooZV7ik!7OB;>ReFU3W8zQ^jW^tVD?t7hnX-5 zcd=s-3|ey{o8B;Rc%8mzeI4m(1m7}sOiy|?$eDIyGtAgCEITqW@z56Gz1iN}N*go! zUJn#W-I8pOUD36&5E0xhVO!&QL}U;e3EZGfgXH#;U}3u|$kt@~efp+vX1u8Awa2FT zJ?XrnzPf-Z(xlPMjL04AGx2JURzDKXx_sG`pyN6fbmrsvo5#dFp+u9+<~Q#`B3r=? zZ;R5ymV^^;t8z-cL$scQ2cq0c4NJEQs(wriBJQ9}FM8>xFvX^%juaG5tVGVJmgfnT z9=@clEhsvMMmmYg%V02`<+KWhYH;YK zJM-G$4|41-QdyxQ2uHXD`rETPNvQce@eoxXiE?O;mwr;sOSK3Wl0KdA;riVy=_YHV z#yr}#=%&vq)(-cBG}jF!n{izQB2%W$4>HU;C(WAu9P5r(9m1b>i7$i)C&&o?_^R8z z(3Q&8EOXX5_K&_D$3&@5GM?AI{xOIuib}oab)GG=yHCieEvJhQ@z{81{4{5K;I#|B zD)-dnq2?VGFPq(TWoXb2#K-zguMVW&Ki|&jRd1RaD1?K)S-#bEN5Cam1Xc9o<(<1< zr$Y3j0w~Yh9<@2`wcJm>KyeHg5%P>D?@?r4dPv2fr=#T!#+LqAw{||W$UzQ==r4cH z`|9#q04fA(f3eg4hs%tB=_OEJ_OsdQJDcS*X5E*Yj;1mOSoK@99Zn*Dei#`ztrYHn zVCDepl7{Y88#r&QK%uwIhuLp!5qogwr^e`Ruh8@R1=+rZ>q46@(x-B!u2iF_4b0D^jOvy0@|&q*Dm|0diOL1FvTvm9 zHLn=RI%d0cF$RNTO`KCF)WaL|6b!^3vcXiWrezD|VqAp-{9xC73pJhW=rsqwucW{I zMB$mK&Q_W4FpPber)5BVlqlF)E+HInjaENSeQH)K(7vH`MzJ-X!R|U6p>A2;&U{WDp5O9d$B7sWz1av8m;7KQF6Vt+uMbyZZ{?eBH- zG#NH#`W1u=PC?gTf>JYV^H>V~9z!KY6HPnCeDjYlXb_)2a(dkEYE>N0D*ED^H>`*6 zG;ctIugu59jGmsIP^J0a+suY`_j%SXxYmlkMl|hPAKd3izDa%68k%LrEQll+Og;{K zb0?eMI_Rv0hbV_X`9w?}uXUK%x){FOKwU7XC^=qO@b&_ebJugt!{_#XIZv@FN zX%HH7UZz3RlKb7L)^*=gK;?UXJic|%)p36_H0k8>y8PFk$M-*9960%E_tw|@yXA6` zbrYjMMKvm*5*Zq4ClF!qFD*yL0JAH> z2m)Bx=YT)4Bg;&8MFx_c9kL?joeYA6vN5KVHy`+S1PA|FUq)ixYbb*H;$$|Cw{zoi5#cSoePP+Sc!!(}!;SUpc3@ z?Qt|0_ph8&Tj=}SK_6%??!U=7y{&hrR#>g%s=XqMFB5oaI*yiediIZ;)6(>v#res{ zkH!~f$7n65p}Dz7Q-jl!Lo^ZhXrz;d;%Fl7!GnHU(dj||-GTdeCwi~{6?MAT-AOAt zb$8yPLAbH2r0WkJly|n#EL`cW_Lk(Wx_@!Fn(9hg%<0WPD0uGQlIS+B&lWOHR?kUwM9+ z7IONRh09Ec{-=eDiH;7Bj0ug14h@eA3BO3IINfk^{0qeeheielNBI2CIeGbBIOp{* z4(EQ(*V*0cucDK!qldMUzs#sYST^VH^DaBI~3Ma+oPySC)CmY|tP@I66GV~ZQ z3Hu+qPSaG27lR?=I)VIV?LK3o3`SQy{*#OI*a)m{D#!X(Fq;3{#XS*gtXD|TE5C}o zcG|?@-!4vUis{E9>u{yd;~Qrl-f4MpSFa5f@3iHjR~R01XX>|$OTMzu#l68X6f${9 zJ>C%EIHc8F)510p^30xGS&*Brai#1f`7!j;$YJx#zL3kT48s1|o@%&a5q+;WS#pitkr=>BcM!6Tk8*5Z}fR7r?#*i_`MI<8Cqd;#R=$VqdO}Mp5_)@)pI&ySY}K{ z5G}<)a;7;R^elyQp1`hrN;2zpoGqT6r-QaLHLz&G;HMC1C0=n%();ua)w&XF2|KkK zJC6`$F-ChCzH(u4m2@-6k}W`+@uCdtjApvnMQJjP$fe27_ylI4vEz`hZS%^J5(>A{ zTrUl%hdC4gTfB>vPYR9*X^JvNiRn*h8=91;T{T5qW87YwO90LU+9m*hD$ga-n~^M2 zU|ypE*+5@Sit3bU^mHEFY=1hEx!O@uGufP7q7hV$L6qXuJ7*QL+>WCxo1xKnvK+=7 z-p?szpz1#Ajs5I>cb`x3r3e|Q)EEQbsgSZjR(`jaCm1qAN4{PGK zON8ioiRtsBwEPUC3=b)d7|s!M!_5*g%Kc%xIoX1l8jdU(u5+qnYm5 zrNnIKiF}^mipygxUCXmqnWaYkp!5KFm6!2oQPxj)&`UIIgp;4 z2IopBYOYw1C~L|y&1^pp-hI=GHPztFEp6cx-N#1wJB%A>a~-qq83?kCgw0Uv)P35F z**={(T_n#gt_NcsS;B%fI%BS3&JVvgjWLLdGf22A_kBazwam7-+J@H6@;B-HUTq>b zGdD@Ue}Aj+2l5P}oj1-$jK=OXvZkxTSLKhW==IO{sTp*EgG zJeBQ&&u@c;7@w>{BZ8>dyKEyHQrGMq)bA@6Hrpn64}8U3dm52M*#RrvM&6Oht=MNU z9ju!RIisdorFT{J3aO_q0hD{fj9-#6}KR^sj!Pab2lV7O{o&Q;0CrF=b<7`n%rr&IvpWLbx5kq*);n+lVmM zyA7|~dPN>~MzrFYg^t=$9O==NK`AQYiUseasQ%qqC92V}is_&%;XYw+CQkl5k2(&6 zc>HW09s8t~$0W{xEzdyusCLqSOcD`eMb!y2G!x~$p&ti(@8TF2{+h31h}jhGsy+HC zKNR6AY(P5tKn4rd8x}MoLv9hnq18@W9Ju3Y!?ikhYgMSIyUCCoEp3_P0p*>Hm`=A0 z6WY^mFcj+@^BkjwG56%_u?pYI=nN3W%TAzSJJ1R|QzdtVn4Z=pgsv>RFsmF{+qM@~ z+tzMyf&evtSB>?V0ZsC-oGD3WU)@z{*N*h=aqX-wNjdo%} z`qd$y$b1u~jgFAv?2J4Sq_9`1YJho;))s*ez-}sV@R(MG*7sWSlrq3!Mk-EEo3Zjp zX-=C{9!}S)%r4z9C~6bA%sHa9Ng10+}y7$35Gcsxkdn*9qQ6HnChoT{|3+v~J6Ao?hd; zcQ~q;)0X9Lxz79Ia11lsmJ{Q#EVpwwzA{6ksBG5?`4dQ3>-N0jY3gpf6ykmmL>Yb& z5nY<@_}GR;s=!f+snoj@!Du@-dVJbxdsM<&iKR(1l}ld- zp<#(MiXI+2uV*o4HTo&9>U)>ieb;dnOS6sUD)RgzKut9~`*HXg3OXVrs+x6epfosL zq-IgonVL44rmbq(41T5F`^ zULwx25nEn}kUfXWkzQBK(VdsGCHT(^U&ec}=a`11!t+FZqqGciYzsVW>x8Y<{Mkio zo+`8&e94$Y2obX*)oZNz+47n zes$ujml6Ah_JxvbLQ_i&>L0E~W-Pr>foKY@`uR-|SL}>bP9hEzrG!PI--k5If7g3E zpJ7w7@eZ?j>7u&CJA1?0$mK)Osg{%sy%RpQZYL(^=SSI^!6Mh*ZXJ zq@*$>kEpfm^o3aKMbtu$^N$4KNZpBAkG#8mOrXoEGZ@X*Uxyj&rnCgF{ku1UJ0#I4 zHQZ{QA@Pr%t3C0&+}HEpT#wzIx2gN0LD#VH@Tn$?j`(+K#G0*$@RPI`rE0N`@aMBe?M>44&Nu&l!v7 zF2U1W9J49dc@S?A0d@dz3N8f+o3dT>gcw$XsDp%-QGz^ecqli!6qHk%I|W0Raj)^&2FR|L`n08XZGOIz4gTbLyRV0TDL zq665wkN^l^8ydcbfCq3hDFISL4>_G^^lF18h@2Y04SzM48rGfWbDrd7N}@wBtzzL9 z1JYIzOlK$3GD?t2gPnGO0|M+~8b#90jT-h;BoE zbR%9-vR@n@LQ<>pRD=LJt^f^Nz=SEHMG|hHiOAtjcPmNnSYZL}T^W|7j2@D;CsCNC zbIxYoj$(*wRZt!wSj|cSWS*t1l~#deSD_TCuYlCUfdo@>ODtIffh2fBQ_-;e)`B+M zTuyvi^{y?>2 z6fI6)Lo16TFaNsu=rNq+E&3a3a=!+u?(^TOvf~4cD}cfbU84; z)fNVP&ff2t$hnOs#jqciAYAOkfZ^3Z3iGc)SB`DQHvpd^gw$)vGFnaP>Pog?edZ5n zB?BG2ZIEO+UnQ$_3ee5Al*}T!Q-0@sHP;mMV{0`KixT8bE(BDHXLu#q!deGwK&vdG z8SKivC?yVdWRTqHj@ax7^MM_}G6jb1MX-hg>JO?{$3Y!fL=Co5m=ow3R}Z#}Gn}s? zd9tLdG8UltqCB~Fs#t2#^}uRoZ#_oDcf$!Ep)0l`Lv)F|K8XHf1Nf%mX>a6p;CaR; zSopah#2X4zohSU~Abng0{POb#U^OuLDx6?mf2RQkLNdL9d3*MhhV!!b&%u{GVcAtO zx6!Qi$xwr8ZgMhXwk_0VUUab)9Tf8xOfXd)l{BuwYm1gFW88^LEKcMVnB$O^3*EMof3n6555ZHJ(EkrtkRV%!$ z7ExD{;i&MC<*Oos+gA09XXi8fcB6(H^mOn-3jW2EF?A&Zn0vDhA!H|NfaK743{==f zv_R=vr=t)mDJ=|oj22$Z(j6=}TInu+WUX(dgXA`WR=db6kenfUYAaJ&4b$l#5jI*( zEpB+%Ya;n-E*Yxfw5e%f&$~bo9mihC2m4HdyN!8Kh*PVqH79#(nCMEbGJ&e$&C2YA z%ZxTB5tHHFE1bYkbGS`L*FcRSy)%YB0wA3)TCRSlDARfw+k#<2BDH82;q@q6=43;FPiB#~r$?PElXDfB?Ze01wVBUrgK@G5`;|iK+}JK1?C!lW zxNn=}GA2c^w+d7+K~RsqKWtlL%0M(A^CvWTt!@T3(G1Ydp6mU_Th=tcm%-`t{y%$ zQO1F<;=jeNQ8I_Vfo?e+k(7KS+p=;3KPL!oyG>q^nC+OIl0ocS!kk`Pp3NFYyxG-qmA&tlqVwpuhspdT6Ha&WldCJRjEa((-UHr6E3%f3A zwCw}zm(QHEDB{Nrzeu^(ayElDE2~%yP6D{M;QN%G zVv)zA2WRTtXCqoTuQO=)MJ$Qkg_QR(TkpNvm-AjoW{HwR>};7l zP39+`Hq%&$y=1i_J+gY2fzA4-vq6I7DO~lSVj>j_*`EvKwmzdgH>O>&Y8Jux3VE4h zo0*aft(#jY9*@qVKsDOADk;!xMgayo7+iY=OlM;lN;PKTOPhm!4MEE3ytykK2HKu_ zdh(&E3ZP{Rng(Fp9ApCaNjlQMezZRt$3LqR%06aSi=+#oDza?K+BdJ70k^dZsqbo! z!x^36nvqJJ$rY*v`caTmVJ?euz`3dYx$DL!0b`0hF93|~{JBqsWpW>rke@Ep$GyK5=q@`^ zCh#%2O{~46l0KI)r&VK|5@^#1;KD!yPn{?p+Uoea^;g$P_VteZKf6xqNxPWJU9Ev# z>xn$=%ALK#U47j>!*hEk&>iE-J@bJ*%h!9>w|#&=_a?ITPM_O%O4@gMP5iYcFHpXJ zRh{s)pZ!G@_h4$+*>h2Pl^i>BnxEG$`m?5PddkbZ+YWmja8SZAtH|;er~Jt6D~HMc zxou{;eS~{pCOtkgF)7(a3)!U;GFx&84G^$6gJM3Opy(!7wlaI?GH<0J>B0~Lao-rY zH6A0D;6h(uZH4C_`FxZA4zyDO;SU=WY_{tW8=t?k79IGk!suTkD$gORuOMy?__Tca zUc0h|u=}Q!@q_c?*8s0=tC33TO69aovZpUf>;z8O?I-uK)7H7Rd&{h(3D57VN#3&q z9FOK0^UwVwMbPm7z{Tw? zLEo4c$(`vZ^4Pz%y!zY4J@z|^UyA?!goozhYX0szT^}gZiJo%!@Y}_WUUifi5;C}x z2lTUUU9(wm;#2b)8Na|8{ZN0=lXEu77u(TzCCu|8#NX zPptzMu3J_9yX%xH;C^r%{JbmV^;kL0#l1ps?ETqw3SS$|K4DVv+r^dZrpcd#^~6y< z)U-Ly{J8j8vJ#AYlEX3l>E%qNN##6p$Ofi&J?+HnTh9H>%`D9ZvyX{UUp?g@> z0q2yD5s!c8=Dqzfwg5gnTu6+f<+VpL7E1HThWoz_l+Y)>ov+sxt|XqWg@9@l%w=v{ zTFJ}arM6or{ORJ9#zi|URSZN{K~k+t1SW-7Pw1HydY9-kWhXROEl+)Ax5$v|LzA{$v*dRA zIvt$@r+&+?Cv)?!^gz) z!}=a-{0D@^JbxYgr-Vt^gL9>B;tl6<80!n>SJPfiyDDSVQ(j$b#n$>O_ftv(nvPov z_LsXiF|}k zWA4n)qi0bcnb8V+@aW_4r`+p|Dg6CvFQo?`NE|cysx2M5Nn@WCaom)af+Q#uSjffS zXjw$p?#?;ue$G^$SbQced&{~!`b8R_K=#t@VK0^^jsvG+m;2DbgH}Hi0o-bF@n-Uf z#mh4{pXte$$9=Sav9_UB^O|v?zURv4{vRkU<0|y+y9>|iZ$d2WBP_72?A~L#6Fk8a zdPF{N+ANpEeiaF(s;RkKbv~xbd-kT8hbE$bY+sP`a{=-c_zQwiBW&72P*G0Fy5mnR zdL9>Y^_wQ>bjsr4${hR?Qc)vF1*%MNcfmSzXPYdc`hNv0i5;JX^&( z7m7kwuW`N<)>wJDQ0yJSIs843fifhTH(=;znqdS#weZHn2jHoEJ&?oe`|%rR|HI)r z4^&IwomBSMAb-q*XM9o=Jj=!9Or8w0+Ih=1F%V9|VudF^Zn&;Oq350XCx8((w!Jhu z?yas&6iJW2L(IXJsOL(sCEX%cE5$V`vGvZR3PM;azh`z#C(njnWS5FViF@AYL4{s= zQpX;59s3bwj(gHB%5f^tl5Y(h@xEQ2CQdBh0AaRd6$}?gma!&pULK8~rVmy{EVNDy zP%=gJRe~J&Xq{V@vEWc9nC111t6-$W^%SI|g_+lIOU)S17pWYHkf36GQ>WXsrMV}3jD`7+1Uvy9LdSlbBW{iWOo{i4WYs!N(aN`^8TN^Q$c zn3ST;5Aj7iwVjxk^^b06{up1w)^JKL+|sDzLQ$K(;EsqMTn}zf0h$QmH!b)hUZhOl zxzo2f5z5of;(!q~Mnsp!nrOTHY>)e&G~TAJw#xc#!P=WF>S;nSN3+@wA<=CUu$%# z8vB957gUPz_e;gGjNl=LQbkQ^k6Z&8pCmc6y&4G4J0zGo4{rK|jV*gmSlUPDa;7(M z;R2g28&%v^^sS>$J6x-BTYPo~svN+K`l9Z`r=*kKEQMQlW+#rbPHwkMwk>J#)v>Y7 zcUcj$-_3sNd1Pg6Pz4q!(Pw(I)W=O$!W|joj?zT`m_4{-ze+yhuhl}^iD(+P8Hapn ze8JWe5rWKHHEF!|^34m7f^GH7NG1?!`^+u9X7 zp;JckZ21temmfoC5@8)~1H7VlUc8;i1QA?u&0l#GxlC_!sJvUN8_Gx-3Z1vN&M~eN zrlOlP{;=EL$1iEjP?JF-+NzVk+Kc%47BA@q$z1V?QhN_9J^2J#gNieB`H()X<;lQj zks7T1In4xWHK{Z)un{fHGo`YId<0Hw;iyW8yh&Aigpe({pm_K^enSnlFz9(Cw8zuA zu^tpXyk&I_(L-2u9N@if|1jbXs_))W-!Wz4k&fCfB~6JP&fmo#Ue&Jwm;C%7d;g$* zw-Us>QF|aneKa=ee{QFxXz@wC78R4kL*vH4fncv%IEXm9BN*Cap##nM%^LXqgN_s zn?4hYD19wYA}hT19gYS?n;S|j~nwA@ifR&Lez zkE1-q6A`eX7AR0%5_neDSl{72%I;b8tZ?lwSAD;9&vl$F9pC78ZM342zWozZni8rg} zpL)1NU#4v)DJ0mh2dvVD$sLY0?lDV+18dpIngC-CS3r*vw?g=2DTV$lJN@mEEH+7C zrYsagTY~MGN{N^#QlyK2KXr@vaO#krWI2%-pV#q;k7Ac{UlqoN;84c^UE>}O7BJU~ zS`tctDyEb2LUdMf#V*T)E>W1&2Ej-_#TaisrOK>Q^{^}|<(_CBic{y1gT75Wxc@?|A%b%3DP$n2I3l)8MsV~$>-YKr!?UdG)| zI$zvx*I>s}7S|?K%nQ}E>q{{MhSB~Jmzm105RUsMl#^4oRmqq`vku9IpM4YZ-PU=U z$*4iXMP$J*Elz_Sdih2+*;Y1LGAJk@O>S5nP=uS0*Y!&3Q!5BNhK*7E~ld-_+&T4^oB^daBxC0BylV4 zqDzs|eXv`&gEA=vV`?xJZ;z{*!c@(XDD(FvfkO)smQh=gVBN$@~I#mT$DNnH?SzI5oWi5nW{N|8al7dMF4u9ZW?S!f! zpQw~LNIKHa&=kjKRggns)Yj>X+-bH@NCYA+Vha+2O$Jc#&N3;=vm$QI^w z0mq`#vRWK*ZzD4fm5;KjL%)Ok`C_T1$??c_F! z#IdfYcfbi~NIbVYVap}QH}yP%TqZm#i%zBwchGd1l?zk_*XoSLx`9Snl**8R6`;=s z1W&sj(0@d%fQ=eScu%L0Lx>(A8F_=GIVi1E-7cWlcD#BLDr1=?t7ztCYW0a3pclY^ zFG+i%Mh@Q~)s8ygxl{cR5TpC8K*eO`XJ=BnRfx&90~mY*7(OqS3os=HAfR!cuLuB$ zNAg)bAm#o3QUnE(w3MR!%!7#Tn!w;!wlmQ**>Vn<6b^ASf<|mH*rB0DgQU=nB?iH?xDAMiBwM&UCPG95r+9Zt zaZ>Z}TsPGz3JrnFuizzLgdQ5B4j4Mbo`1XVm^9d>Ak@QIo5lO|Su8jiga%(cbd|P- zhD&WvZ1p$xsk#=jRdL>PuXKTxx~;Y@|HT z{=?bA(JJSS{;lMgDu}H*S2P@hEI4S5A_Mcq9*4a3!;^jK4}mTivV7>TCvf)E)eh%FhQCQqkw zpOhi~Sfbxk96<_KB)d|Gpe3-IJXw(ws;s`Q_luCs2~}x%B3MXt!9ZOOf%Km1!b@pB zg3wc+VY-4obR~3jn3QzC!2Iiv2AheYE`C;IybGMcEr%*lpKAWr4^S0EXKGN`PpUpJ zFB$VERK168z17-+Tp}wb#ilyu_^Y4&*ckEAJ^X#O?1$Q4K*E6^z%*6BI`!v7z+eR( zWXY!R7AdoS`qr-?ahLVc1K@c?*8oGXaFw|`G${W%X<5Krd?g@dBh?&39`#$t%air{ zlOJjW%gQ#6F}5MON5EQjvI_-7lJt9?69QOCen_PUwE6}ABA^BXa-ReraDZpelC9K3 ziGXB8)kC)>f=kX6cfckgb~8{iCbs>X$D&SBTvwDDbIq2UD|ON+w#0@FBi zA*^)Zb{RuwPAHS^mkUQBBNb(FvCX&iiNDsF-|+Z_FMqLR_&7J&c5d$0&yQK7rQ807 zTlf-^nWq5jD(wBj$(e9&yyDXf>|b)kA*=8T!wG}VUFOTaJL$ytwRb)*YLY5|*+Qh0 zTWX`nmwtWVhE^axV&|&NH3rAoS$&u8R9FWD$GN0Ff5CiXImo6tqW4w!FS~TL{Lb-i z%kH<4M0u!`iRhkh@09K53k9It)_Wtb>X>UgNF~kX-kDF2?B_G1Qj$sX=c+`}`=>Rc zPmh!9)s)zSGrx;N+`8RuilYe7{q8(Z0%fSPWXoA$%tirfhut;QlBeeb?_I~FPn^Ra z4yPQRtsA8B6|wGgF`xVD<@s9l99a%`ND977-jsuu0ngrCvBQ<5NL?S%;Ub53N1Sdy zY4r#iCIKzGa8P4gegc9FyppAhjUu#ObjrKSuGJcBuj{Lz*s;_v?r$It2u)uPtAAbuI*P7ZTBM>uzh1hsfQ&;jMTxOFoAZU-V#`773n5=bC}?T)XH z@4QTR@k&9Aw7CG38b-`FHe9RrzE!|(>?x?%UBp)f<}=J=c{Io_|4fVc$2=GSyPPec#ehT%8%+Hse9e|^i(gBULL zUOd6MLyD##-5)K(3^Te}mj?9bPrTE;B4e_3>3B#| zB+I0K@m#{lkMtkkRF*dNMr^`g{GrvDoH5XSIKAKB&qaQ%k#H@1_eA-S*wR-c<6rM@ z!^)lYo}YlefA^~tlPolfWA%u~1JV{w9A9+--1wxk1N84r{dUj*yWz1jC-H9YZql_X za{~wzM-M^C25g~+iHuzTc5(meIx(vuK@w(vcb#^AySN(#Dy>Wpe|Mb%ckA_BK>kWY z?{_8Us`S%PKY8By&j0Q@@p^OWm0SJpI!QaF%7a5EKkUmawI=lMUF9j8V;v(? zV78P+z`J_cDUP}_*+U*^F-loXZ&sVyy)Y+*eHMczA$pXp^sh;J*-Ksx5H^o&jcqiO z7T4d&&1fg5*I8Dk$;=10#@@vNKrw! z>cu ze{*s&hy69D(xeEB?A$S*m_gRC#!vbAuztxZ^qlA^o*k>RHL_eOu}4$Q%5z*KCENRY z$M;4wzyk4eqTe%yYq2oCQ_+U`oL2ky=`!*<`svMtm9JQsyi|JXD*?KNb-s2=fvs+m zKv=Tu>>Ifu7-N<5nV@Z`SYL|Mvc- z%`2x))i#}@?PK-ol-th_(JejG^hPS`ot1?;a408p*T`#iMCAdQ3IiwtU~ zc@TQKm7rEidtPrG$`2UA^U=Ca76kPL60Pgh2jvRD-(#b7omf|g8P7;Qp!b4Vz%)~_ zMQRTOf)MOut*d%vcorO*z&Excgi?VTk|w0nt%)lr*jl;*(#H&nTx65TyCJ(Hp8?ba zx24u0Oe5N|KJ3Fa?ZQh0QjbjXl-la7u&!)&3&a8yr8nk^lPGBq zI!T9PTM);@-jvG}sz|qoUhY1Qq(^NR?--d>2t!$3V}4wGrw%61(=_d?+)+9kFRofE zH4}Kctm@aU}$P zb~!WS3(9t+;Lh3;9FwMDUh~9)C$(a(fravpGua2m^$@*O^WaMe=~tiz-PQNz0p^Ix zF~dd>opfUJQeC9FaTAq3Yx`a!l5iR*87C8_>z`l8pfZIi#^EHqY_ zF1B}VuJTAjobJ_a8^++*V3qD6c%mXvM0OQs-#yIPub8URyvh>U{Xp@^9E z9YHI7Ft80?%jB;aRgI1?=dbo8@UPX$^eg2^5n-X8#qdY8aay=wwm49`-dM|HthzMo zHyu%%qY)*MiMDh)3!f=!-e1GXy&DEwXB+5NGO5hf*BN!0oD6-G_O$2lK^ zB3X(vB_-RP^Sv!AiiH_TeaJi?obv#R44j@qlkZ2Gf3ie~vW~PeohQY8nO=S_+$)U} zB#ZH*=2J1erJ>oyw7*EdMY%sCEhz2(aYP;5^ZN}m2;ZQhc`Kg9Ob;6VUfc7 z)FM}{CD0OH=_lOfWCYe530})?&zt|HVgHnyrlz?4i9IA~%H=5iw8eKLT zo!>P&Q>*M&3$$LPODq$3onslk7U zsfS~IG%+>#pl5hwfF`Dfe~YQ9-nzfVR0mB=-Tj>o8!t_1933sVd#Am%x%~F+|6NSg z{VAqs4Y8W4KgHCa>9DJr6*YmCm9%(e{!cDtVyA0lL*r74G%gkSFD@k(min7ZkumyK7#%YW9aD8}6Sb4ZDq2R$ntxg; zx&Pft{TUFG)B1}`{VO2$?|PW6-=9#5_7+p2K`F@p0HruVLX;PSp$`pzLn&je{}M_q zPj)mss>G%+3jBsr%2q;~Jl;+A#21M>apqk&7H_)HpwtJ7AT1#FAVa|7PV=)4&Fjcu zH(RmiWvz&y%NBQUy}TFedSf(pbG=;;%OKz;nU0nreqzw#1KSa&;^>RdWCUcR?;^Py zdib8mIjy8+iL?uh$hBcFw6S|hezIFxoQy7J(*KH|JD-vR)+sK#d++NP-5-koA7ytM4)x>r{ePGlGq&-u@B3be zvXf@)yCEc5hHTkF5|x_8GKj`5JK4)lB!pDRo?Uj?iL$Ha@B90m=Xspxb^WjZas7|u zb7OAKjk)oe<9NQ_4>EarA`c#0MBmS+(kNJvS4vNrzR9H2sRQX|c(%D)+txy9U&Et2 z&bsfQ^T}!1T5FxPjxQL{l~^zgRe)$KanS1naE2Wgdp~NnKm=-!b7ab5)C%&=Sh#1D z?dGon{Xsk-NqONM5VIMH1{W4Dco0C!T{z02VA2!1A;C-}2Uq8k7Av0ti9}`o7OfaR zRE$o9-%kTbynk-Q+nOOLGqkSBxV#JoQ%BwOfhzp7j5<*oQc(Al1nx5EC=9;vp;=x< z8Zvc?qFgsh*79ddMLGz@vLmy|nlNR3Cs>{c7YeK4G8b}5tJ8D@d!&P&2+Bixx8B2)WPCsx);mC@-Mi& zOor~=+(e#+1`BB)%9R37X`Ix)%D;8!jE+^`n;eefN3c{F@NbL_HZg9i5>p8i(}T^C zT-rNz5cc1r)pFD-KTO;HcFslq(q1pq;z$#6w~~{(iT*(8r20*BRjPMWb0u z4Sb}~=!Vw^V~XoB1xVw{z%Z3;v(v zAVrk*wf#c@9PNS9I8pp>!l<{=qoXou`tuw4@o$0|BP8Cr)EU1JNjef>cc(S)rmOy{ z;_J_F(75=z!2w;PYCk>r4H`54@2nj_ zIG#$BA9;@gUGyLj+jpcW6TYTF4ER;2$LF<4Gle?>2ZV%S$RY}UI*9u=;b=;xI(V0t zJSd@Q+4T+S0qjY;JVmL6eJUHy+ke{`N-emU^rY*f%q%2Cy*E#{GZ zbTzCCHYs3;rCsQ{EEOquy;CmHmO+S(~^tlG&5W)eZItRTFw`QDrqn$;h4rmI z4}WFM(}~+;kI=hB|H@o5E>^`Y_S|p!m9_hzujiYYzz?0KoIUxEH zB+PIS&$XWmH!0C%?-`6x-OmGJOSHuehoWuw^EvuTbd`FB;vVk56reBF*E1YWNZ&7z zFex>>(KDRVv|lJ2TWaiX_%(fMzeu^S)bv5m*X+~%VkCVTI?`|?pX;DR-=xeUwP&PA z^`I0TTV`2oI9g_VP-fFtX5G*;TJiAU6^8zm&1b{0n)HL$9wx7B$9u-!G#!-t#lEr| zNFNAW4yXvuy2Et8X1w{-D#w*8UM+><9ey9D-j@KSV!f<$K%al_Y14?K_#?9hI|6II zexJ%=WS)766xF_yv1^Gscrua?kHWBZI-vX;rXYN;8`nf!V<6)guO0Z5GAPZ&lEFMQS1fCnJ-1NiTO9Tp#q}ufp=nZ!3ndc?JBtJvWAq=N|EZE= z3V|&e{k3g)zr@|in^&6Ti&*w!i(>LK_7@OWO%wXU+x0j;qIuO?yM?lQE>aHfj4P3L z``e@&Jf|=8O-#gatm?V1I!{O0=>3nEsc%rs?7f(MqRo8{q_YCa*nvMK80;dKeH4#HJSm#(CO9 z5V>O1g(M}~cfi+Mcf`x&YV0+d(jFy7(dz9(HgLVrwi9Ol2Q-UxK_%9sud-_;JpUwU z5nZ_R5kUr1rMk}7&4xzq?=5}9JGrtKOv#1R)Hn2P`#w6Go<}q^em2<&$T<79X4=p+ z-nSFAUE$#xDRR+dL2y2?OkMm$a^DqAM2)b^mV0AHnGvsM2aO7MBC zau4ije`E+78WeOcR|$guh(LT@b-_b$PIKx)KOAh2zHZk)3ge;{50)LH`~~8QTDBFvKF7Stc#WJQW^_#NTcY2SM?k zu6V-yQx<=4*0~tAhfkITTMuFB_3x<=@3EPK4Ba0Vr^1VmAccD1dL=l3eS|UxMY2DX z_XC@e9-1oQEN2xH$kHYwqqJNpo{cpb$D0 z;JXL>s$e{UJQ&ASZKKwnnDtUJ*$o(%lc4cKRLO$$RX}w9AUY72M3g6kGEkU{wbKD9 z<>F!O!IyD~=h{rWKmEvUni)Ta6@WKgli?eN1||#O7Fd&O*$7CrEm_$FtYD)Jqq+)w zN)b*e2J8#)5f;y1w;_g6NpLy({wnJ8TOK$xxE+Hyn5Qq_1%az6I?hEa5N*+J5=k-V=WNFKREQvIr<4P}$LB34(TZmHAwUzoOG|Ep!{q3XNh&W$46L&7 zph1RA0pMJ#nk;om-X-Rz`7WveCUTr|!g_DkrRb^+{0tmS0uUH^W4IuJz8d8#C-Ik) z3yh{80dgmh09cmh8=3(u$C|OrK+QzUaO#w80Hgr1tDlm=d5?kvX^#ClzQ4?-qR4^E z<H=(^_+j&mZ}Hj27la@bg)`Ul=@t^X(j}t@%N#-w(Ex`6mf?f)XUMODcOc6>xHR`LSrgPQ$;iY5n!A0TlKHvxM`+`{ z1U_#Hh#9_|Q69Lj0-Oj${D=a6+Ps)k1!!_a$1dXiF5eFt$`7&( zI{yi;SPLejl6#|Bq6KK8oXU{8wf8Bw>oAXg z9oC%aQWG$Au^2l2i{MWJfc`~5XSdEEriK8j3zXxW;<&4O>uwT;&UP1U7E^b=($SW! zw|oVaI0idia9+zE^ z0FY$aDXxG5+vs+Y43pRlZqaz-cXhC83dcwIyW9;U9xM^>id8RjPF1BAiM$K~G4z0_ zWBh2?xGmC*sMEawSK0;vA|B7(q%GG(JYzd6ydW`T$}r3&J@tw}N)k_QfVMYai1_Sx z@0u^N=su!9Mmg9zXOF1D%l$N}1jLibYS{!d>ZV%@c&OzF>CLpDe?bx0!^;QmGKj6e zdTR?zSHbt?ARnC5!3XtDYHtj@-gsOD8r13ux$pecTJpVsBa9fUwwfUYZOovOzf-OM zWf2M{*JYJfx~(?o0%D0qSK|v%BdYMg08r_HPv$bLVQ3C$FHZSUhda@G;`mQ?-$8ZW z7){q%zG~3kt+R}2%YD_hVdJo~esx9-*i(R0d0wPkNM3eUNv0^g7uaERhXb6KVXgUK zG}@Isk0{NBR}M08mI1UKj5IOm2S%Mv)p4*g+xK3z@`gaOoNP)Bj{|4Y-N!(60>du@ zJDjZyRr|-6@igaho`DM88o3QPmeZTCL2D1fFYkWv{uU02S5bbf#$zm;w#+tA-43RZ z!m7&&KL-5em3W;$QZmwzLDUA_)MVuId#XTgW;USHZE&mGxjL?q;xn}U_8(y+@T-%G zLaIedR<^x0R}S+g1YYi)R+TA3u=s*4`(h;;KUzhvXIHQf_*f_c(Q3fXZudtiU~((_ z*vSRkEJrP;S2W2*H;;HH59%hRel;$mJg7h2Y8d;?B4!ILs?dMADFuA<;8BOeXlOU0 z`KP~Nu-6q`Qp0zgRwrp{xpCHOP<+Vy$~NKrU#I znHkVSiF$Mbi)3oYvw#+;KlQi(&x4m&C|$l93JzVqBI@8oe@{LI<;+yW+W%$#LfwZ- zDmhU8JpJ(?edj~qD6{-;K?9*})Q3uD^+ZM38wgk!hUDe|$@9l1iuX zXWcm71bAY?p2$S|GzfUn;&Yfc1`))2Z@;D58@)R;De9u0^vCDQ3{Yrn)~aXrgnNq8 ze9V1eLRI_=D0zI5rCy@(6PjB(%io^^J@LnK`Y5bULSmxq5ASbtfv53qm=^unn`Q%F z>YD7?-;wb??!qFOSF~YZx;Dia5wVgj{T`q#g=qo6RH(1MSasqIc~Yx zrDQl<+L>Ga6X2c&*cmUg!^TZ_ti|}GJJ`RkiP7|fIJJEBnw-CHvkB#t1Fy>gvEwO+ z3h&q0F=yZ6Kf)1>p)30J3$}6)S9Qj?&?uf+RcqI&HW=HeI^%P) z)SAWUyjAsg=DisjMpCqcZ;|4w)9lQwI7H=AcSnG|Asw>Mc*XFB-&KP@bLZ1sDVz12Ir zb^ZHvKcD}1-t7^G?W@r3v3@_X!Ntkh?b*NE^L#s#aiC6_ooy=o7vG&9);k*&zU#9) zn-SZ)6~6MOvfYcTzf65S1*z3%Kc4jagfGYs6IRI%zFVYp`n**rzxhuYX_IP=j~yJx ze^+RqemT*TWq8U+;PQs6UlEmdXRWPnbWja|AHJ!N;D)db ze~&2cgUmrxlsGC+BoIxeWX(IpU{3ItfM|wO*N+r;pPu^jAB*OlHeLgq{Pt_eR$0%f z0xC}u_?dC@aw;SZN8%{T=q>RLkkCmCP1O{`*7wZ}@YT>Vdx?f2YC!>!Fn0 z6^Y)ML=MMX&Vr)v#so!={|ShhfWb~RoKu5e+O8NV2??aNt^emxYSTK)k)~#uhHWJ` z->xrPC*$9MnAIOPlxkKj)+|7-mQNC zF&Mv1%SzCEl6~(KPuR>!(9TSY_{`(Yq#Y~?Ti?3-aWvP^>OOs`-BYOIn2wj|Hl6kT00kS@ z)L0*l7n{J0Ie#~!oU(alshzV#ilW+8lkG>8QU)7u z6wpsxRd(s9xU-h7VHm49Fy~fi;*#okSWf%($)<7vCES+LE$czih3QLA)m~1=w|;-? z@n(wK)!`-ebfX&y>7cq%PA>ax<)|h{Qr#?{{jKmFm2US!BUsTViYj~03zUnb#Y7s15;qI-p~Xy|+_eNqicxTM=wW!1lPhUlE#Xrxqu)kL z?i~BnACZSrQ#=C-Zoa<$vH8tGFYrR2qdc<;#EB2TRPpOSN`L*i><~5SXRGw$@+S|S z204=o!Rz{-WI=c9f%QLe5tSZ%r#h5>1kOx095q)W6TLt^)+!eqy?-hY(f$yx>ZS<+ zXQ$ZkUV0J6%v>uen|QJfhl_81hCXan4!$F|tc5r10&~~2KQHmSFy^OAciZCvMA02b zKSHGT4M)*j2n*+35Y!6zoXD^1a_Fg#EuMyN`u~3}L5puCRQhxZ7{T7L~ zP2$sBE{fi@^L!AN{L0|4AjK?cwp#<=p*R*GmcRiKgH`L;BbNo@W9|$!Y$Yn02$$Ylsiv#D>hh9Sat6637;DA_@%fbo8@HHBiI#~Jb;nGb zhO3T5A8+|qQ%`9Rmayk5Dik_;^qA{e#y6{smXYN%y?=I-${a>txlLd2Vv}I}jd4nG z)Y%*!lQo}HelECa(Sbul+4Aa#>L$cu3vB5U>i4nZD?X~a$6Q^W40voU)x}o$-X%iD1x$}I3z*f-T7tFI zsgEzBHOv5PA@Z%Y;?qVpgi#_&i`Jn%F5)(H2r)TjWyYyzO)8l5c^=*@wTyR@`=m;a zYl7#05L8mR@#`j-TiH16Om(s+(7rFq{|bB)gQ>hhbuW!JV7aNY@}slvy}Vqh?}OiN ze7+NL{_%EFPcxQ&H0oZqNudBu$ft`cU+?Ae>IkHv8!j2J2Ik9&I(3z#2xu!;<%@=j zZ$eI_n<@7Tmbfzc$(taDYWZ6!OqM2J6d*-{2kmUk8+E}r`Wc~)7e-et+1v62O05s< z{?@Q4C|~?q8{}!ehyheMd`3$HjKWpvz4IMFboXTSc{o~XKXz$<(R8Bbc>C?T+t;ZZ zP@GnBs+)kk@p+5gcE91lL#zzlnSfg_ms|gE_|=kkl>xGWL-0VV0y{PFOF+6HdAsHM zrAF>=WNqC0`!!oQ@qW;ys(RE4Kou+;H+Mnq$Qa}RT=aXl;CHW`GuH=Dc4_v0)YI^Z z_3vIjYsQ45#80$qO+-@SGBoa%@#mWrN|bM#1@0jUjg=e8S6n{Piaph5QLiRtFhBdk zIu|k&jgN>=%%tTzDx;0dd?8!%K-k>xquSrhJZ)N7Wnim_xn}G-! z_*F%oHO)?j{0H4lSSt_Zhq`SthfjYCb3t$f8J4+2d>8JAU!-w6gHWW>+NV_!SOtZh zUs`oUwGe?EdF|L7@$i|wsQ(~T=6DvavevOl;y2;3ZcUL1YoBMjW`fh2Cb#u3)qjFh zyi?P>_Ar1%;3s!|LXH8E&>s|t#=&q-3b)6Eys!1PSiARrxD`M@MG7TRfuoNS7=MP!;}YG zD4oFD8O=%{uuSl~GMh}89Z@A%fvv7art8%ezxN2CR)(Z&exL|Dr25G9<`FL`R+pIF z^T}lxk#?SPn$Q;Jr!K<{VX|xtSQxt-_9dqhUv+B~otsee!6I(s~SjEAZa;oi17mhM&;2 z7}3R4X~|B6D-~Q@nkpT;LtKmp9vinOq-m4glfaMbh>qIYbKFFex`wB{pYR;|{(ceD zUSVOs+x(@ZcB$jb9(9zW0m>K8Wp*hmL4=Iv?n^e;Hq#g=_fQky?jbF>{~E--F&w9y zpz9Z|B;OIvazV|ONRb|Y)Yf$~>{%|IewYBvuPPi*BoronIJw@PN0T1|`ut-}9X zz9PgP9{9rV3;r9V^BIAhK3J}#rp&m%)~5e^oyj*AeFD)4S75p+BB&wpd9N;-1*5t4 z6)MUD*-J93kQn&xZTbWh8Ofo4WJh)UZQ!ICdgk4M8yo=7ME`~KY0txyS7!(1G)C|eCgtO#YOryv0R%G&CCYr9$d#ZZTp@tg21u+?jyl)z7%N)j&ANF| z4lOvbWg>MO9(fgRTLO7hKUqM$iQkP*+`bu$9gbBXT43>cIx%IhR0_l4SL`Qom{Cr@ zsalW0vO=Op-(=QD+lrE!x-Hwtw2?e*+lyYM2f6uGEv&Kjqt-2#z0gG=9L9_{%T=(J z^*V5@4$+DJ$^%dlV=nBXVHILM<<-Y&yZ{K*HAXo8s;-rBkjue-C*iWXT{y>daMlgw zB`Uq)1e$n4&g*X|3EMEh1_kDyreQoI5~AqrOJ;1d>Fx6bZs38=2~l{90`aE4?ezC( zGC@cExw>7sG%>Ev4)s#VV6Yc>+hS*Vi?Sr_qcpKJOJV&5%$-;Yyv0s^x92l~8(KA_ zl*Q+KpP~NcKp4C^F)F|63FH_xRE2|r73O@xuX^UggS3ggd(XIv3c9^)6C2x(M!ynb0ye0yhQk-PovQw1|OV5`-r$K4QG&nOWV`F zi?!!Fm{V?^cc3>8wV9ivi(AN=lcVCTdNag6g=An407&C-01CvaQdI=N~~r(p%G z%ny>lWA!&Bunzb}r&pP`NI><^Q(BMmZ`}Gr-$F6+j z<+kE0Hbx-1Yj!2afaAcXE$tfQU<;BuimnKe+`&v$+@EF1h6?)*N7^Djbl%ceBx;PI zACl5|+z`;6DHA>iBc$W2t%ykj4Ueg~{@1oB{RN9$TQgD4{`&~#pefFYMLhO9kG=3T zr`?2v-RttOWGKx3@OFnRNx*l--Ql+7tcA}mLV#-KQQyjf^qju5^bZ^R!uu=VuCDma zL_AVlrOvZ27F}8MS@mV3lj5_5w|ys5+)rgNDMvOk|E zg%jdDqQ>4SqNglm;YJe6u~c;1^fxViZzmkm5M}wZMl^wZ%{sc(uj9KsY7RB@eAi4%pcW4$w$n1<6Y6VrLE;m z*jaG36i1>XBm!a&#s#g zGtNT$C|@Nmw|Zf?m^+ykQUrW;xP5YWw{j1?XHDTjevyx7sf+n+g;zH5CEjm*8EpB& zu5%Focx)3SwxdCJ3tQIrcD%O{Nhsuxs5GBv5|lY-o~XpzAH?9N{k~_uL~Y)%qcNQv zwN1Rj*T(G4pA{PqT4!@*8>y81GIVB?1>py?)PxTkbf0ZP0$?}wiCrOy8!JSxY~vy8 z9(yF5O`J%M*yFkj58t`NJ-!#!w$~;TJ{>`{wb|mmOH4^w=YI|_0Rn^^;b!sFS*DOt znedOZ){T5&qLJ&8?*mrceiEvl2PEGqtA}s}Q<8Ci_BhihN~$0dxj1bO$Peh9kQNGB zAVB`d&#++igeQ1ZE(I;sPka?bvJx89{!{G+=e_c^JyGme8K^Ssr=h;DBcgIT+;&Lwq%t^$edXB?H%}(t zxVg3V?dM(4klBc?gi6nOYdBOdq`5DXCUraI`C4j@;R`*F8Yh{R-};A2QS*NI zT;}=~!X@E=1sa;??(mcx`GRZI6P_H>f+5^5PBXBl<@#yiL#HLHr;(FUuU1d0*w3oP z&uWy;YW2?QZk*M-pS^i-))0Btn0og1eOX5<8SMd4Rf4oR36&Jio^q(e}8BKNj9koq3n~ zYh`ve`cDQj^a$==daA&zw0@~&78%=!N2iqPZE!x#KWJiwuOpSh8}lE&-2qA ziibuB6dsp2=lGeVr;)Qup2E0@+AU9?pZ{h-MBi#E#{bh$ir~y5U%2(|`5IKHX@JODHRek)%nQ+EQ1#siFXz6&WBJqFJVFmf5iWV<91vp-NL#fT9OY?2`^P!ZC z_p$6^XY~0{YU@~Txhp~Z`agi!%K1?0-prkNJ*B=1ac6l|7K!wb96(-zxiS!^PJbsKeswLcW#Vd#`>M*!3o) zGpmP__}b4;u`s%f{|TL{W~#Kmyp|~b`*%zOF2M}2&}viJAC`cY7W3mR-m(uppklQ_ zhf*8bq&+2cCXp0407#brtLbr`wQ!&o05IOXPLd$(q5$|++;P66v_`TJiZZ|@8-;3b zd}(=szEhY)QV33X2C2?>A{l6kWG9%2DK2aBeAi~=zpff08Z%{cUBoEG{x9^qrnsj| zVJhm=<$-9|vTpV?I%#G>?f$j%^|sdqgCzmwskg;;KIzNiIYC045_wN}Z6xy9snaB0 z#;QKFielwGl_=~TVgo>eClCrM(8|C2`io#z%1H9*&%Y;oe@}MFM;m{ScmEvk{L|MT zto=UPIX(PwvcLKJ*UIV7^Jn?@-s17k)uY|-=Y9Rpz0H#!iw8fJ4}L6d|5!iSp82o7 z{&ZvPJhA`pef{qG|DM=S9546&Q`s;5XJS9!b-GZ$KizRORsLUz{mQ=*`>mys^`*&w zCHBMX3+KLdgI(n=);z{-d&=>e?Q!KCkT0Tl8 z12YqYGZO>zruLB4Q*3(l(B5c^Z)AWh3-cEnlOdk zzW&@I5tULAzNjpGLFqsGdPzmW|4QslUH)y6oCiOB|6hGQognF!8g3@(#k;)fg6>3# z>t+8dMB)|K^FRA~)=)RSeTA?bjN z29?vA-jK={89aMCinx8alDba??;P>xwDbL7G}fTh)$|E{o`-2T^ex;R4!7el2D2cIzZe|V|W`^5ES7FDtrQzcDx2I&>s ziOqKN{+n<~&HU!T4ecDnt)UEw*o(If-m-~^YWLLK-}T_6u&Yv`bY$5pxWZ`*v>mv; zmNWU@!=2a6we4lz!Qu4Syzxi&2u(BO?R0Vp{F0S*oWW&vAO*oK@2{hF?Pj&6*j=gp zL74+}mLkj6WqNDlGs<5^vm24<3@Ls+Qkk5>*Zp|Aw~tBV^tkf z)3dbyu983q7rs3$_%|lJ#_teQp@9hpZM4(1Xju|g!p{7q%-1+C^-9tDMk=QQ_WJo= za441-i)>zaHY6D){G|&}BB$YK7<~(b!F!)p>xl9((wS!>8wiobpi{f&+?_Qz_P5moa32h-Rx$xlLB^~Xe&l;zD&#`m` z0x*LvO|GA!H&M*|4BcJ2sz2jN&k97u4GbD>suI$A3&fPVyGFnx`ZKkSu1Gf0px2q}S6Y{G(dE?c zUN_ZWF9x3#$rl^+dD{NFuW#t?^Zi#}U#$Gupg$n}-+ldfcYn}-@9TeMANT(M?dzlC z=iA*Mu7JWqGy@58W5kydI--x+ZpZfVc3ufxGLn@2j#{c)6tslZy65L?ONG zPYp>%GA{89Ck{R};UwIVtlsL9(jD=j8=YQSOt&P$ zdaXn?ETz!G3H*anG_0g1mqDNrU=O)%$Lkply()3D(n0%m$A{;b`&Ls)ug7>S74%v& zUFn<1s$tcT$(!>uHP2QutLiK7b=N1Uz6_Ur$;|?(&~|tPxE?DArrgrMpnS%S&#bt1 z#@R(QEw)p2RTA{}4!?4Kk|!lZOzpwej;(nD{ayLB3L5`c53Le%_L-K$i5=3KzRKsA z%nfPcBI{#GiwZhKr{lNnOWHdxG1b2tgusdm$dX5-DTU*XCqq9NsuwP__=R1{j@q4} zTBLcX-Jl0sFu}t#ZRyx0#WxHpV$1`;v<@$oDH*F(C>uD%7T7*R{KNfa0$+6Y*$7O? z1{h~QS{73~=|;!ZBo!Nfzi{iM$ELp~rJ?t`%%hVp7({K_XXBO287I9SrnTwgy(^0E zPRM{~0POCL~fgsO;L zUB5M-JCr8V^O6D!_JfBFCsKVbyu!N%vB93#5n)IqMfCN|4z@Rq;jiz;$Jjny8biE2 zDEG>Wx%pv=tr(+_e84=vjAmOyceJ|&9)1?{i>XNWE7HzqokV(=aW#+`|e!xn7`&;)RoS~o!Lf6gb=n!t!28~ zI;e7}r8?TNdFt#9i1K#=7?+8m%*@2Xo?#HezaQt(NWn!eNBX%zU1T(zBgR(RFGr=iQ79{+8+#@o@WBEw0 z*v;o#1JLV^_yA)$foa(~-J*_%4ahR=%Fj zSQT@el#|3qJ(j6muD%ZdPa9$!NuBA381n-OrUAkdH)R_=UlyB51OrCF%$FOP&^jzk zVL(M9P0nouVV5Df3Q$-Bgc_eF=-gkK4+4({IUh5dHNqzZWN-wU84SbhpwfODeThIA zc!(}Fo<`S-zjiQuWu8-g*!h|TP@uqo$)_6y;VBmo9aw;uTq7Xjq?1iSK{bS^1#YgO z!#tBg7d#M@HfZ1hO%6N3QV{rMPMg|}i5Y@FuZFifJ5ia_HeC_&lB1bHG92GK$4g?G zyJDDD02LzJuq>!k8MJ|>r(J+6k+h!S)Y_GS^b)I_;4t&UFmRsB3MLY~5Xm`2KhIQC$20 za5U=UZGiP;-j!eg$khlYF?;|ZCIJ0en;!H!%{QdzL!>Ib({rAWQI2n(SB(NCX*5R^ zSAGzI)UX&>UQCNb9NmKI`|rwC9~r;x3V_Lj)VsS3A5-9~>rHm=plfzsQon4@Z0K{6scV$rhtFRx{LOhqw{WqXco5S|qY!QXDaGCuab!-@ zFicmWnHJD-E6i0#&Y$prgONj)HgO*Q8p-e~mq>*ZtHm&^ASEgi_*aQZB5CIHuqU@Z zr9txOOYU4zlD!%%0hoIrA{IIG;~DNmGI0b0th;nOXokso>Vli;h;~M9e3aWwbME4_ zT1nO;TrA{r7PBbIq}x?!oq2Y?xaRn47f^ zqQd1A-V1>)!kLMA+O>3R*IA!yJ*(eks2|K^&CAP{7d*O?14rdi=D`=lSfQ%YQzZIt z9)OwFGc3TcH<-^!@iI%~Wh(L|6-AzY)Jv7LdyisX|oq5oO zJP1WTdg?x!t58=kVGLbZBmq>S3Gox06nE_BMg@QEUX2w*U3^nSIh1nGwjiOQ zyNK=zZ5$xjo2D$EfQen8FCT+IL<4DM20smQ4x@6&-8qy_kkgZ#mxg7UdtukoftP+ddlSHu2@a4x z@Le@rO)GV2Ev6h9ci}|>R1Q=pOW)a8D02ZAmSwms06eVbc(}`uge-SRH%#KFSlnQ} z9GtW>^{P*qi&F*QHmHIyQc{d?fT(>gip8CvD`dke&n<}qjOgF!*CVpP$uNYn9YjXb z(43_gl3gIt7_dQZ4(7B9Q~lCG0`Rt#>7D1}#>=rB0`GcW!EvHVH-Yw3x(@)QWelPX zp!|LZ5vvMhV-Vnr06AA?G~Hl!BgcNV)`_v2Rqkr9MG3^eu0~T1Do6VZ9LFqJ0!5W5 zUI$h&2=$YO6(9{-T~9ew@3`6E{I1G_+iW=<5CkmEUdaekHZ*KhKv5Ehtc-ktsR(ny zh}_heHpG`II4kCS;e?1#1DtNvW+Z{BPn!gq8g(eRw%h1lyn7x?!jvEx9xlM?1JX&cGKOO*yt1)Y1ARMBxzK@ZcRFzo`1=MgAX8RB=WN@k>)0ODjaG zHGrZnN&XEk@C}%;RiB!pfbsRMl((*_dC{~6h|G4pAkDk`Zi8%gG`P0Jz!2dJ2ITHi z#N&=oikN$Ef}nyO2_yHBvTdp84`|yD%3E!?_M3f!?ZSJmJKYAlZLrrj48*rOpm`mk zd0CWu?QmSDiEeu}w;`+zrcE-KrTs|H!(rU4<;L7;rTAFH=*>zl1(hmbd(MtXag11H zx+n@#6&vtj5Z9`pFOJ=9q<}lGKiqHcfI8K9P<@CkfCyqgr_1LkKP-Ao{>^(Pc%cW$ zkjU1$0GS-hETeeSRxF_86Ws5~I;nk1d zRb18so;oR}PJA!twU2*Wk3M7R$M;h)whtW+y!g}(r#D|RW|?g(WNPoAixi-Zb?vX> z@l|JR$bZc0<9hm-(Z0Ds;MxlfBew}K0R1FIZZY{o&6cLj z$Q1fSq0eJ`>g$O}zkQyze3ndays{X4#IR+gHt?%MHQmpi5&y%l7P01<_M?X7!#2F; zrrWGX&7&-=gVzObWB$0g*pIn|64Il_yl2Lmw1fP&#{Ag^0%qJ868i4vqU=tbV?`npLk3$4Z(+lm>PmRMIE z-fvumTrs&KNt8XEn!OEBtzc&_VG#5rxml^%!VyZ@!C7b?m1h-|mn;CPpt^$wZdb+b z*UTK38*qcb&awcx9AL->JTU-!)jV(jbrAqqeF1J6Ko(d$lU{_NsCZ2Qs4wC+2+U2A zq={P~iG;y?5#px6*;PiFs=3?1JfH#mqF9Im}$w(>uN9?`ywb>7jB-hU&{VY2n0Fy&#AXBv6@m{^IiE7IB&iK zMYgX{?k(fYC;epfVO8HTt*eC!OQ!zIJWp1i=B;AM8u~7z6>SQzxi3N*$$pfzhPPb0 zj#|^!U>C7jNzy>>UIm`*uqgdq%ZfAM&RurFuG{5pFwe3vbIcZ27#nI(A?7z+l-8?F zk&+thx3Q~l{~Gi1ZTO%z-~Tn1l-cqXT>BVj%#Nh`yuz^ zD&MBh4zEnxQhA(F7-zCcD^(eS!H z3;=g{zOnvYhgj_Dm`{b@+w~+Y&|DLszsqugd{>z~yFHKEs7~T`3;1@K_m!K*f}yE^ zdiIVYztP>D-PwiBt3#tYW*WCK>vG@rDYc>C>Rm|3GWQSWQR#yhKlfiS?ITe;cJJk^ z9R>8S9eP}w2!3)npGSpx%IutTIC6RU?t7s$zI6qP&46q2VsQqy-XDGGTppffqCp1v zJC2o-j-%fn$M72lnn|n29Vz%9V=E;c?z$2OnfG~^GZ>h&$V@punDX8;3CILkE@KL6qJE zq=N_;dWX;v6-gk49#ncUR6zx)3WA9AE=Wf@NUsWr1@q>=)?T}b4jGxY^b{i@Md_DPeE~<%^JNTuo{d)raRowY^PpXlV)NiWLvEh$X z(Z3DL-;0|)-D$dO1PE%I`;UFSAGjkgM+PS0)R|?zs+Yp6e(8$BNKSjeMNX`|(kHiW zPx>2G#?#CmdVcG(GE_Rj>mUBMf3rErBSHLY5XtjHEsHV}Mx#(JYw{oxDqY&=_J=-` zsM<#6?py=kxy3;&c_f--CPfl5b@4g7yYHEnFXbt-{{( zOTM*I!Ghbt;&v%SNq=sY3N1RfsMI&df1Lf3J4$e;DP=_4ixc;93#1YI(tMCd(?iYR zNjUTv|Ni*}s{_#QPcOVW$`)kxsZ%c;R_kQxT^3Uefy+a>DC;cJbQ2p@#Hew<<#1Zh zU9Q~dq34&Wk&!{W`4|YKCiP2UGMKidiBCc|ODnQ2Bo*6V&FSJ1r?E^UYDhjGf?vun z+2a=<8-p3PmvfYBD|n)BwkFGR<2#iO+{6ZIkD((x?wdb?pUDrIn}4hzy%j1?&l#i$ zC5|Hf%2^YkUlMMj|3JrIY94i_s+-y-j0yd`_Ku~&7tUK=;-4bR`suR&r5o18LXMmL z_Xjlxc#ODfk%G6#YaXgSAl)b9Z|(7eeDxoz>2 zJ7rBCxq*Mg*3oYo@TMV(-6~#%IKG?>^gCWJN!9rX6C5im+1Me)^L8-!d}1EzHZa zNqQl-*jIw?9mFrpy+NPPSp$@L7DJ>-_P>MxYlou|Za^pv&H=c3^(4rlH9 zc*+=?_xqee4}NJcbDF8Kit8LV5G)-zao^ixlFGhXPz6-0?~k{GtaQssRbGV%3AK4*l0~17v}V^ z7zS&Yq3jidsVB<1m!3=E-uEqieBP)lnd5~Y`uZ8ttgI)?hKr}VMRg%nr&IRzX!2YB z;oEtQ{4bpkk|R0=o#B@13eJ+L52=M50Floa#04U`p>6`Kx8&rmd`jDD0&qfqv{Ow7 zxutfl1&kBvLhP91&ILaS4LMWOczk-|dzXSYToZOP+QQ`Vg;jC)AL&x#AK>9<?t3=r@|Ie-&64m zxTXKM;lEce))Z1nSv^lw zx!}eiQR-!U@hhc5rzMe}*OksC<70j`fOYc>cm3xPV;J0o;nEk3q(}u=?T`{Gi}BHd zYa8E9KovhM5nUzJQr<*%l$?vvs9?DgQIXE<1`VZ`?#hgmznkw48C;nTKVA4n!<`mzQjwKq5QbOoUcF?Ap^~eMR>2@ z9Xv;yJ$H03Pd@ByCnP9eb_qjW>6tW^wTiL*fY+u;G72Z&0*bJ@c*vxRp*aikY3%eb z+an3-aGb8+<=fn~F&?1|9*Dg+rX06EM>_|xoN#}<)NUE)#?SFfT3H7d*;GnBT-{35f;UmfscoHJYc zf?G%p0jF|SgFq)ua%PI*Ig^|j5#;QbhCqttoi15Ut(o8nDAIO^$YNEekKu0tH7aI) zd8J7x2AkGWl}iI|GT#Hc*Rwi==bRY|GpP92&ag7fYA~73749$PG}jL`JWjXXz(Y5s zH3`^v8 z^03F(mJJ{7AaPvDfbwR9;yZvf$=Qc_1sdPQKGVg!Yes|rq{$$WAIl{qd4w9&WMHg} z<=v0*#m}J_0yW>fSEB@64PC$Zfw#AXPKyCah-Id3(vkkEJ{x?zIujKxXcS!cI&#)I zNNT##Lq_0PP;Aqs*@9TN7KyJ(00g-Gu%}O@GB~8#q5h3DjZl=c-`C0CGbA(Yh5g3# z<}S{84yCC(t8Pz64U1HKO|8S89P4~&}6428&gbvKOgGQRoC+Q6A)llwD?fRI+Eur z0`Fc}(PAJG|B&%_JniDI(lh<*Y_fB4<8v3+HE^QLgx*a-YHeV}`3L*zpw6%D-{;t~ zzn{E{3H{x1RzZ64b%!QenkGUFV_{S>eHm{-mklV79oKq}S^}y?UiW zHa^e{pVORv7XgGIOS)L-GVh{()?E+LcwSo9hW?;&U>Ot5(Gp91i!N`9lE&R5VmM+% zZg7H)y|ZP@uhZ&0myP_88vlX1EzZFX&n-{$%2m#p18wP(9t+OMV7e9(qakQj;fRP8 zYSB1&9AkW_fhDSn52lgSSvow9t_itmN?mPN+`R@MQkVg7vE}5pANT$;E`kH>jaO84 zV>=hT$hrn(7t)FNfU<<)VyiLYG1x;nuq6i#Lnl_RyiHe#70Ofc^H;UWTIanQV4N~W zTv}FBxv5nU7ev6^-U8i-d}VIMb}n~0R^xe`C53%GyGW-hx#%?`Qk+|252;>8_u`y1 za5wF)JH6ChrlMlDRA#iSP@UHGgtF5~D60LHg(1y@BGo23Nq*^0It* zoP9Ye&LM*Y@Jdx}1VBrA-P2-3bny4&!8o4QWCu272N@c?=A++F)OIyOh^V+F{d9+n zqzbAh;|AF+k1gBujWya(jfQz{8RS_|L?PxoI(SSdUP8#of>T+8yTA09kh#{41{mT2 zfN~*L(OiX>Q0DxrU{M|Ys-#RRWG#y22BVA-)~~xRG}Fg*fIh81_5Q%Upn;~))aSc; zAtQRtewp;dONFZguMKX*HUb|&2U|-neNi2JKhj+x1b*c(7|t(}l4#u1b_0Fbmif{c zxkY{pT8B#LO0MAB9d3*avR#r^8~dG@651XcV?6Pj&F81_^jborJbv&((={0yk1U#| zqa2bHu}sZOXErZkN(g^{*YHj*jkz?=0-pIQty@CSwCYSZ7G_d*IUkLT+b!XW%^R*Y z1EgNX54>!)<^&6C<~{RfjQBnL(rfV5_y9W(rm4_S-1lY${ALJz=ofV+>cx#eI*?T! z{7&cfMIr85A+QFO*)zCVNbg6*L4oJqF)^|OKm~|#x#?i2p}joeE}ZbJDTY)(l8wd0A_h$tT}J;5kPO@d{Y~P zhw|bTg!@BBO+pMZlL?=IeviOEFEF`ViAmrEG5z)&xp&Livd-WNnj?Cy4W<&{3?XB^ zcUo~?`~tTCm2MLlF=7386U4a*EbQZIXI%e%-n6@;PL5#5iK4D!%Ty+c=d-1b4S=uI zn0GIYxy11szq3>oY(mo!z#UF_a2`@sDtlLOp*L(t@PCG zb{x$7VVoL!Eh3m{^qC!?YclmiuhYBfnIdhX0zp;dTJLIhfM~v-` z@l1|Cn~H(i+YSr;(pv?N8CD9oN_nfC228&2tnj59d6@As{|w-gmA3GBT)MqGZMmG9 zWsW-L!qBXH#jKo3%mB}9_4$*SftR-%0HdAu^;I8~yB9I#WkKr!@N6b8nni-Qh$2;BAS|qi(a^){k9E2StED2Wj%04d7@!u)5Tt z^MQj}W&hoKojufZBf^h7PNXBOl`fvswNPWmtQ}pQ9Y2OTKD=Sk1Ggg0R?hbei#YZ= zdN+?Zwhdez99slBEpj`3e39qw4sn2kuknDltex;g+`aQe7gi@NKg-{J5KGwNR6X#B zb#aHDdEejZp|9np31o*Cyp6eYJkN+Zw0K@UcLKZylusOJF;y?UGZO>O{F3ndOXrF( zR1AtpHNc=6FMj_59#F7pY0(5YEhT1s#Nx-&kv2|A*3Dv$=;|e4MjG~z9XyPOrOyt| z&oQ+wC21_Da(reln|pVQTHJdHHR4o4wC8eK+Ji&lIB27)C(AdTRlh9@{Yjt#i*;GA zh?+t~sf@+SR+2Sl0oO3)*7zTlF3B9qRp;|pUgJ+zS0oizNfOcHsZSPuu)313h?Kpy zitEjSRL){q_m!%4@pBQp*Afk-QjEtjAOcvH+8*g27x^4`>SVkLLN`kFSzpO^B zq^3L3dFeSsk56^3HdlU;g3GAkE7?zt9KbeoktT$3!&?Pk>=nV6{q=vvt@{LkeeA7# zCp|Dk^wQjVV8*3D&_)njedJrJEg?^T#SOH{hO(kscz~yz=}_b!kNwh(CwE zOAo3%XiqmD^3BIoxyOiXS}AVEdaT9Scxm!&V%gS6hHoA4imUuvP6-}vGL2qIY;H2h zt10^vBVOhN#Z>~wR_q8?*DEefcxy*}E2C;9lMfH|z;j@|UDLfoyf6Y-R_ydruE=cO z!WMeODHpVTd&oQI+BRT#tCV5s>CzTAh<**>{p__*fun6hpHHO|r;c=D@;}nybj;VnSd1sWH;Jyzh&cW9)`43LEZ&$AOC=~7C_pfcRq;hl7FH* z^maRKcDp?M8c_4EKIA{!q79GF>bVAkf59@7Q1*pqU=5ego}9|~c5c!b(yVSkv- zSmw!{i42kcSkx92(%b$j%evw$s0#eGoa1Y^-d7>pufm>RMIye6;=YPyeieWA_0pT* zm3rjEs_hQpLo2qp&gQSu->=e-23BJaK~ZLjcbB|1_2_(wG;Dp#XpUSQcx6As*YyjX zM;ms!@!QS>Xk7?zAq+k~#9qlfT7NlXG?b~Ke;hQK77h!gLE&W&te`mjY~vj{1{Pn9 zH0A5Z*d@~kn4_42Z`r*?;aTI3Ls+xGO$%G_Of-0O)HbsVTXyPcdlPIFh&K=XboY$b z=DL@|O}wNM-h-HKaA18i@FbCllh~kj5O=l>PS{+}Y= zwZBKaKmXSe?>`~g|5WfU_WWFGIGKI(_k4Hv%k=*`-<>4qyBmui|M&Us6xqq1{m)MJ zw~@l7(f9w3%5MJJpLNtt*y+yOexI`6@?iVTgYEi|y*J41TI6oM&lb7ht@hh`<+WMq zzV#BZ_1tmmA5Qjqx#O22>y<36#T2QzIKF=%*)9Jb$^P%c-H)C1WFGrptKE+On#ZoH zudV7T$ry;Uc-hla(At_`Ut9C)MPB8rm(QQQcve(iRuWZSTvA+ETv9?tvWtlM`T4my zIoU~h1)llDzlXbz(^AQ|e;@AR;u8|$eepO<92OVzSG$WMOW5{lMaBvF*Ko1Q50m~i z-$g}*|CjBqU$A9hVDJmee-X01{enEa1Kh|wwui5io42F0=U)Y{lbfxB3z^5Zuyy*& z#xNQy)BY*q#S5By{By)BqoghMpE_Pi zH4zEbzjwU<8OgrsPA+))gysH@WXJzc5ifO3{Ip^OWfK!s>0c2qXFi8ed~NAKrnGB+ zo?%_tP_A;w_FP{G|3KWcD9F6HfB9&!!Q)Gg{q+@NiFHN8%qO8i_E#+uld1X(Q)1j~jV~rgb}c$M5LG!=4!HQ#p6@YTiec!J<`ZJIs(!OcCFG zp770O3l27&WbNzt&XJp)(v2{(iy1i@Nj2KBqPYOOK-4Vey&#}X>Z|A19c)_@kWm2H zz!ENn2N!9JF(11cF7Z>ZYADIdui@-GD%|ySDY9X%G`f)^H=S6=ZDbiIM&~pH_$|!{ zOdqg>Xcs=AMeRQ5w4jW8?M!+C%^t0JK3yM>U&fZHlh4SSO-Ib=xw#H~UOUul)P|WY zl&6fU!q6-?FhG2}yhPF4yg2`=tQo4a+-+1i#)uT^sq>Sy)5n)nK**zVN1@-0mzHaM zBZ>;BOGungcN5nwV>oem!RTZ~qm`B;Hc|^4GTMGU*NS_gA;yqsmY%8_$Dc!~o>{EJ zVSkShOFOY8qIC!{GOJu<4iPpI>SAVnNcCmF>Ln#goX|#Ta*ObRz3;o9w$abaRha(# z@hYvu@E1qjTn9U1jxAM2u=XX&ImBC28||PHCUu@M6g^YYNKO;eTChA7>)mmY(@zmn zJsLC;^%{I?YXRDcka17^ET8a(<|f2yUlWp=XI2D@S7RgE^{m4NsZjo5nm1kLU349} zj#pcNoR?uQw0k5XEI%IEzqz5Wt!p->CQkb8=Ao!+6{e{k5$S0QJO_))ked8p?e2F% z!%YKNsJ_o-c`iIoOk-JnVXVtIVPae2n_RDJg3gzb8H1G6=?c_bWsxftjAkYpDzWZ(p9qtHD~Sx=oR@)%z}rVjlH`|wR2hPXWqKS7=I4*;jNtJ`#$Ylpgh z1Jvh-o6jzeo>0-7S{CP)Z(IBToBNq9FwA>D?4wsu`=oijF-yY^TfN7#7DzKwkPiFQ z@b(EMKRnCcWDb+OLT0U>T08|Qal8-+V-TU|G3cdcei`5LC5*|?3Orhr0YCDIyC*~7uh%-6%OLrbSZ7~Hw1!W6 zTrJzJFG!|Oy{KL&mxa)iprI$Qx$2iq1L}Q`?MfViAUcM1?ZqJRBb1TZ$X(U=~hxqmN#Z#K67XC(VK{MJ%?S7tlrN|x~I%wD6( zJ`$IF8MEd=62BX69`H4z`S%y;)TTjC({DMSf3GWlY#K&EVhVocahSJJi%K(L0K308 z!;YFh`kT=OE6;B=R8xF<=EPR|eGaq;?;d;lhrYt{e1|HYQbtTO-pHz*Id6$t+(47g zetc!Gp|MM%RrC8xrIP(cg4&$#=xM{Ve3lGpHDPLIAh#Wy0sz*K0M&+-bMx*d46SL% zF5fKHDctpW)-~6o^&Kr=z~h3u>T;A-lXs5&7kUyA}-Vddp0d}qNyiNU=k;PuFMI+8%+t3UfgDW~;y z>idf@97%7p>U-mW<9--B-4FMhiJLd>9L8)%{_|8g6 z_Nm|$vTd{l-$Sz>M~vv-djg9(l%Zf1MqzdNYfESo2~6o45L%{tF-q*pFtk7z)Y$8Ke^)F|D{LZUli)Ll3;wqDpTeWtt- zG_^Th9xNtICdNz*035mh)Rqo70y87rdqV?6reO;8!{;_0EWWwR5kyz_{hs#O%`~8aXoM|l&}n3` zuIRya+kKUesQRj%Mh_WV44|YD)rW_4xpI6!QGcLy=(RDg z#`%}S8e$S|$|NQiCK;vC-)7=c(SeP^>Cwm(G=PGViSE+~EfxSd0MJt%>Md}1)`-E7 z2DUFElEIpg*tQFEc1(R)7Zx<63zsh?5MZNZ-gt!YO$;VILMYOMMpwgNNWe9lRBbk3 zA~^Y;E^P^t4pig6XaJqkU`!+Ty-3CdICrHs(x+SS%P@5hdaqam;h&v_hJU# zVxrq3Fd9Oc#bIHGj42v|b!OyTlu_D@rkB7VEe_#O(U7lTC`CN3%1G@rqf6Peg?mQ` zWnb8jp)ahtQmeuE40h#;xz`@h;0nT%A~<8YG;E@c;Yf~tV$~-RkBzfVc3sxDA4kOBeSAczoOul6 zG8CeAl^P^UR8-SqkhBvqjA%HF!4N73;joKv#)={KI9?obt`jFv%z4PnvpbRsMC>g&ueRW83VgmRFU=;K!iPyqe58C6TR+%F(S z#R&bGG_Ri1iPS5*+%xf3m<#(e_%jg{ONz#V3AoFPo(~HDeo}1H$d%(12 z2z4V2j5CBbIOBbdtamC`yl+8hiy)1L&=$BDjjGr0NV+?HPpOulk}MtRQBO;|I9HBbM=gVrY__z<(^GM+0Tl-UaoDhU&^c!@?J|7P z1_oBmRIL+DS%)cc`BEjon4*%P;;_;Y#zLk7JJl;kF`RVLT!ypYPGnvuAE|fZ;Gt@zCjTv;%df`RB4(KHkoxuBX+l@UV3=xXZVWgZLI3@brs$Nh zEhYs`C;=_gcc7t%)wC(n<@`p_$u@@ULvYsJXPIB(iaCPr&t98BGKvYp0x9Tjo>C>c zKK@diu2%89lfd}hhACN9qp2KrV+pz&!+6vN&A9}7-V*Xj?dKAU+8I*8h&-AUxCsBd6 z(+v6uQQe84?1IA{6H_Q_s)1^-Up^caUtW<^10I_}?Z_gsSv6fEuuG%5GX}_M041OM zvfSoKgO##32gYf@9#z-yw!ye_YvV|11c`eb-vBNkehyYen5i_~XAQ=MHagoygiC!#I9emD_f0;@d^vdr@2bFxg2S z?MLK2PNmq}jg-sP->d0cCz*wcQ-)UwutUc0-OxzDDg__zt7bB!bH{q^&6E;)(nW%g#_@tH*>rg zRJ{-OCL2sTtfG_=C{2T|kWh73bgMy$)sTT|r{-#yZ}XcQY}}NP(lFW|8cYnec`LaH z(GTu2IT|1|0L1ofieC36kfqim8uwng_k18GuDi_PlEQaJ4`ys0(QGy#F)cM&ykYpvh>T8=x?_;1gjNBn|8xs^qi1$0v=A2|s!`4pt<+2{R2ILaR~iqbwd`zUqEs6*t{KUvhev8Ek;NPj|P<4-~3qL{AC`B_6iKVHw-$~ z9%~-$(7q2NP1Hy=f0Ec^FXi{j7aM!82L{t!oVyQmuhqN8i@-$w74aI+kDH#4nl z^9OWhg#RtBp$l_u%(mTi_mV>pPvE&~({i>g_#yivqcQ6=p3U0w#CIWL)btnkVA}Z_ z+*fBUa_5 zyi89m;~+;P&H2{mJEJuGpPSU@>=Y(E`5`rJbR+chY=yiK=h@Ecj{YI*P!qOalrKP} znla$$*vwvFOB{3d`Mml{(&{_wx9=82dgk2ur}rP&eKujc4xlHhFS01z`Kca~Keu=n zxabiy4PXeG(HI7{B8hoRtUVk{XG_q3AlYwje`YIK=4xH$Sy<-#vkd23`6>TNU;(-3 zxFS}ta;bIY%EF4|pA~7oRr0QhywfW8+NFKin4*)*{Uh)`;i1|!w-;eANxW+*z%|NG zFwuau3%V;@WNB(gg^qvDxYbVXALJ-4FD$VI76v*?!@P(f-!_mx5{5v+ z{M$gjfNd%YP}+jTQU63agPAR2tCIkFbq(f^06CKx=n?r z$R`Fw$plJmm3a1N=f@i5i)c_M-%e-D?w~1?gvRECB+MVVQ^Wwe0@(Kr1G;KJy{bW! zA3)9{KnWzX#1haAw&PFO>x6?WG!8thx7UV2og<(*NfwC_pj-8Uw+7U8WDi2JPK^fn zz;?WsfTREx2^i?-0*L+L0ryAi)BU3wQxMlH7Dp0dPwe4gbL&@|hHY=yjtA_U`Y6yx z1L}u7s!RE1d9vxXbm+bGO>Y_avlZki4N|(!(dB<^R==&eNcOES2$K$V?r@_aXZY$un&^kQZ#{HY58Bh7)HE6yd4mqdPmsci3)!1bM=Db01pfzXv@H zWGh_&6~FpXDrNcX>0x9L(7)|x3F)Ua>#yje&7$|)?x>AMDS2lk=%C)d9c5YfgSLoQpT`j$`l0{n`Ap|_IQ91A^|rslHRG%NZm;?1ci z(z*B|F7a+-?6}IUD`z_^%tSQ{=oKX1a@p+K)w&NAoG4>`IO;DA)oXTy`w?D;v3lrE zTdv$}{yUP5>>%?l48vkw!ZPA`UiPkEc3<84(Z;|3b1K(hNSK&t3bN8LR))={)N6a+g`UYCg0^ZuawH&(k}kbA`2vr;Ab=6f{EB zic)UH{%_wv+^RKcE*>W~&6SNw(#ya*rM2mmUW%6~uCG=B74u|M%C9Kv$mp^*-Am>8 z)#yr>d}dQZMzWP0I>ZkwELQ7^&d72$KaP4gL9XhTWOAmFP^~09_rli{(L$&=^tsb+ zO6AXTKVLenM@H1fGHH;n(1`F@LeZPFo!e(fLwZS(@w9e^OQ)w0lL* zYnu>bWow?aZjI*BmQ|N?GSakh^~+g~mpf@s7ngL7Vg0o9g{Jcjvr& z7t)Wv*j|Zpr6^^IrRSUYcoKPRKA#|q>b>BCFsF4X;X{34#tD^03MDB7fSquP6`S>V zQNBL6+D-l@f%`jGPp*aVR+T$qAKjhtAcXSKd7>jl@a)-$tqHNGG?Y0F0at!znXaC> z-E__&$ua8{y2g8B%ARw&beF%VyY_suuvPE5Z=q~q*&EyM#!7wG&sxRUB52=62{*B9 zyAd;SwOLtjB@#;Wi&7Pu3tLLX$?NdkZ{-lUQ@!$o_uA+dVoQ8QURh@Da!YpmW%p)v zxdm)j%JU zVvQDkVzjhTW;s`3U^J(K-pciOq-&U>3YQEup6QmfP9%L{7DfCK9?0MpOr1TiA*r86 zqP7_kW6pyf%L}P*H;B^vw(*hRlr{7WIvl(&Xz7@~wx2S^Vc}`hS_UB6_cKViL?Tq? z2@`Gh+=!T-P`}7{H%u6v!XfOI%4Lwr#FS#>wC^)7xPp<#43Z6ZWh0T=O@in6u%O4W z%eDJ*Fb?Ko28Jf0Zl^L#f}tz19Cb5>|PhC6UA-N9RU(G)2%-?BtGE;rD?&>P1~8IArGyQ|HKb9UN|2mRqHDt_Stw zLm%-+sQ_g*YYcFMt4hgnrJ>TUaYZ?4M|SAFJU|) z>&q42@Uh(VEwo?3R=#xoa_)xCGk0PZpRlvey{$OUtH~CI$A_B&XOBIvQL!X=1tn%# zRutSUs~{Ke7`~+tR>iTpA+%zs!gUx%L$RU)$#+TJOx72m-y*v*J=efjG&DLCR~+5Dt0P64#F~J|=yj z!hu0D|Mf}_R-6yJIDZLipfPwwr%S}cXv2h_#daOC@~R@^L~N4NGqk>B%u%6|pGVHu z0VlxsJg&T?#~ATx?d?>W7Xw>oTI z^P6sMBU_D3`eb#YGk_90Nc$I?bL+2ALc3aG-1d_Uo#ORqQ%oDzAj9j)*BqRc2;X8* zh^fH?`DQNWKsASC1F&j-cBRaQvgV4Sk^ttY7-?T^w_!6?GHAHtJ54FN6P`(wan{a7 zv#>DVooe|}ZyM?=H?Nq-e@%mH^X`}1CcBiL%};;s-9Pa)IefibpF3)L_q*CsKzFzF zD{orvVZ?PxrN$f|er%Lxhm(8^icSQH#3p<5tZ$ymd^7C$BY$-T@n}l-MLbiiVatlK z(HCLAFzD?zE-JPITc`ko2gmT?%0T2Yy>iu2^bW+$Zab^z$q|W?+lt5S$6Gi9kYDyn zSM@5(4XlK(o$TZ0dq5Sq8^c6iOqxUj8*7XfGq9=s_6i)QGJ;}gBvRSc`^`&_Q1Azz zNnHxty&&uM`ch(b_x0IAbJh_}c3eRR55v37?%|o&S7NlaRz@}h_ES|n4&^LPiAfKC zukw+QKuu_Jq5%sfdt!GN1&{w{$@@+4MrDhui=Fx$ET!P)vwHPG^OOhU#b7EKDqbWM zr`r)ek?xM-LN0&VjUFSP6ve7^5WI;mmoDs|^;{!^(0?A1{eKr<{JbCjX23c1p@CKxLi)Inv{elV{dNM`lLYfR&5Rlv=FVQ4 z>5%)QnG}IkTl}G@Urx)6vy^+g6cnb(wR?Z#D$5h#LG(&JD%e-yQwI$%!p&nd6S|*8%WFJ;*i+;JF7`eR6?fpS~Ni*r5UoMBVXpb^Bjn3u13WHB00D!Md zR4KRL5P9(Wqi!Y0Xh1Q?Niei5bNmA!>8@ZPSTpoB1%VvZv*AONrgP?X!+p|_5m zR&x4UTZ?FxikDs%t;O3hb?_qf4c^?NU}IWEbGBsk(ETyxl};+8lQa{KY>7d}b!sl$ z5Bq=_X{(Tr)I6dWM@yY9=Vo5+Wb+j1<-y93QUV_SdYCJk@|H!GMhXAnU_?`Ue&#%? zqZaYd)63Jc9f>Ix>;%3#Ga2Jgg&`YPZcyEdyBzuS;K4x$L)*pSCRPC)W@nwwb+cA$ zvl_HscM5r`8GC`&1uNZHFzfdn(#CeG@{pB@hZ~SXk1Z}XVA@J$*Gn1e|FHUSJ09KYSbC7=QcQaq!C4kb3#yV6M)0X;f>>Jtbu^4h#ZD1Rh?U<&)3=l5s-@}{Hwpy|BgrdVs+0va5}hwt!+gMD>hsGvdZoKF>6{T`!WwUGX$T}4Q75UYa$^3R!x4cH| z5DAwzDW!-{XUN|H;Mk6mi&E8k-TnPFLIbrIjL5cg6daf!Mst?~ zeuAm7^J)qj4H( zsTCmN0sN;IjMxpd(026>Z5W5bkDG9SQSZ&TMvRdc^@FxS^oVBk51gm+`^HCwXjm0l zgc3KY6xLf%z(8TY=^x-Rj0R(UfEZczPZweauL4v0jluSKG$3YBc>)y$$CAx$ zVZeCblBEkVmIX1S|A79BF__FlqYy*NK!9~4R=e7&FEY)ra@?Grp4J+#po`b;qM(>I zpw_VN$zoESjpkohVtNk%cFaZ7PxS@_xG$u_U70Cn3o@>5-WU|U>RSn^wl?p@s^ zF_@Km!_*{TIBMRu&1^#Rd}>mo(VSPrXgogF*C)LP`1OSG1uADMjLeROnE7kS{N@@XP*YJ#lV4u z?lr=*v!6atV;;;z=GQ$p$97eu%@Jewd2T0X*@-*aNW2h?s)ldtq*?e6HV)xw_oh>K zl4Wa{c*YFhSK_N!r_jy0;eFK7wFB-tb1Cqdh?5Dl8aUdUbGCvh%6h6VA73JjeGYW& z@3ng<;h30p+ZXtG`~lQFl>B%W1#`^57x())6Mx+Fv_GDdYi)ny?1L#h^DYAP&MYlV z&~!l;&z?Lw(9mJts&mBzcx+Qat8fw79c`v7p(mxXh z7l%0>3WK$PMxunpAEkGG41p_*!Hu)@FL}YYj&FbG#lLEpe#?Vz`9x0wIs!zn_rnHn zAeS$_Q}x-)6@BmXS&w6 z+CHO*GzeKf7cYJn4s*0HUet8Hq!Kg9JFyVML8|Eje-p-kd0sp;;&=dbii53i>fIvD zI~g4!IMr6yZ*PBU z7u|zYbP|=o3#RE`8Ee&TInaZeNWd(m@4Qt&@q$MEB1LmuQe}gEo#Wc0=%mL54!%{M85z)IJqI@tY@nG}c68FSdJ*zEA(z_A9}q z=Sx0Sk~?pecfiIs(Y;G))j;%gE4qB=wFp?0102!jUK6-$1+`?Dqk?T-3XRY9!xxUkA9lz&u`5B=li-YLGJ(?mLfOi{sj`C3Z^H!_vZ4 ziRA%)XtQkG(z6dD*rwNbQW&?72;FEcV!Gj~e@4|FPI>_&=9fy`y4bn>QUqVj6EMy| zJ70hgb6tF<=u=X#hu+-%=pj&4y}$R`Q!bc>Lu=6l$wNeXAK7fED$~Dr!iQ@7?ZrA0qwQP7fl2=}$aKf}o?;CEGQR=3M< zgFLKF#X=-Jm&CHZ(JqE4c!r|_pB<-lU>w(v0pC>^ z7*75a99yu5Ssffdw+T~V-?L#yE?`f%GEZ(jJ+yywVt418!_Z}O-;=ko9|yFHyvY-9H+X8$xOaL4ER zK8_d=^8IrFF0<^5JhA0 zGu7)SHe}mA0JMKCt%x>HBbE56L2pN5qHJ}6;V}~`r4{hn;stm%P9N**9gUqns zpMCh0bmR@2)(czE2a7P!E_&iAfsiEO>~5)g|o2II~My?Vw5Slmd?U9R&MdkqVivn?Cq1{(fHi^ioeWhW?TI4Ox5}~ zhw#ZB-BSj^k7u;<_G)dYG;T3m2{m>FdyA=xvsiQzU(Xo-@T2ohqp)W z>mQ$df0d$Ja6N{i==fqZwQ%vQNV|L|)SXgwb2^aGNO@V0T6WD+yR4UHD(XVi89$ys z!5}F}FsIiV$KV|Z#9@|CG7+9DgePHe9eY+WPNH_x-+t zqn?z1WbV;B|M$%O)@Hfwzc%jkIKj^`Z2v{(KJ@0l%iR0ATKhWQc67e)_|W{1#{ECY z)Q$CjHSV3InFDd=FME2QzHfV8UzgPISLUAoA2N4x;a>Px<6c}sCaV9QxhLipc>E)C zPa~uxlX2?Af5EBAjXMq>|5xCSihb}9O%B}c(h7~^^R8hrN)HqNQ{WyJc`qs~7#R`~ z5EK@G4E0BbKEG}27Z~ar5d2h8Ax}!m%Mbatz}^3jr!T_I+sVc2?~VH{N4LKP?teAz z7B)_1Hvd+-ldWpQf3~W%Ow=@QkYjgp)P5x@_F|NySZK09P$GX|!oQ%^*9?`^4HU2H z%d6?hsp`tA=twL5d$Ibe=>Jr@d;F_aP4z!y?gDG4rU)fhqI?36VQop9naDp`)pD9O zmR^u&A2Xjpwf+xt_Zihxyf1tn0)Ye)*r9hrFACB-8hVG&i+~^~MY;%xfP@-)D54-> zC<;oECPjJ=y;lJNsY(|W70htXz0a9*@AJ&8DQnG|H+h$pH+$`sz5k!z_xDG)?%$Yu z30l)5QSbfRnKJ8IkL526vz_*Y4MvT=_vH(hdH%QdL-nHiuHZOEja}K@=?}r*zAO*T z71yRPwSu-{uel)Asjnam?pDo6W4^VBX0YhlC}MV#>^EK`9Pr-n81C=}kK8G{N3IlW zSsJ{m6dfkz&Mlgu)Hv(V4UecGGNMMW(kqelF4&EB*mJz(HxddVN7D<7 zX+!l`iPL!$b>(TU?jd8(f+|>YdPPSy@7cr?-d{N}!>HF+QweHR(t$A*1Hem7y~UB^1u1B=j#p!*n6UtoDXx zV^cNPRL)W_I-+pU!^n~yTaOtJns^1$9RyxME#y7bhb%X)YQB-r`IK-~g?+E>{Kwbv zYP44luH=wTqp*=0>MT}O@pSsNo~5MuePq$^`^UZ3qM>HB%#8Afg`7s@N9r3)E&^s> zJOcbx_n4xqRFhJgr_pCT(q5`1R2#y>EI;?Y88T95)Aa-HKg3_N^ujWpzEX?U>+w~5 zTBAB3c6yAGyOR0&J*3y}#Pp9$<^!Y>bMfhzTM683O5WY`auTrn?Zg6v^BkD&Ly%V( z=&ci_uWD%jVW`*hV=pdS#0sWlR?{JLrL~U#W{N&0tIm1&0otSjH09{`)En~scs@aZ z7W^4s<<+b_`%>P$O@D_xObk5)%Jv@Lq+h;2zJeGj`=d+K%9gN?*?ElaWI&|aYni=_ z;oGGv@V=@V9>_&F3~8ur{n4Dc6sns84nx?~-IN}atghHYFAPT9#hsDq>V8AbQ%2rF z_A$%{sg5KnOo&;jV?W~gliZJVc{k}Hd)7a29ikf%Cmo#XZGx>>6s^$?b@cE0e$}K) zv6srOyT;b_mgG$(Hyw;Tgh#Fh{9D8M`+dlv*ojD#&>%9+d4?cTio2|a$Dxw)e25M; zH`79|3(~-%Par2)35%V(j84;}5)C-I8$EGS)m-{`YdS89<3vYK!rDqFM|Q_LTg0xG z6P=_c_#vMpyC*@egO9e$kzC*5gOj@3RGckz1P(# zDLeg{>2ZqiN&=^z$fo7?Z@p_`J**A>T67lkA_X#o$iP=+4mBe4Z_P)z1HNV2QJQvl zRlcfDF&zAv{uUUdicTz!_cZY?N_li@X#XU;e=gr8Er49t7~C`pQ}<&Z^7w)D?er|+ zS+`vva=FC6yE||jL}T0%}> zcmAud(@-UUo2$XP2Tp+967Z5C)X$CB>1zn$Oht;=Ee(A1Cb>Jaxc7nxw{)y2_z@4~ zpIM*0BAi3?-=gt%Sc8>%%UcSxuTN~hC1uJ@WjIO30g>rJ$yFOaHU?rtJq7n1pS>*q z4gB!1Zh%fua9a+qM-3bEUvrRnvx0DDeJL+$-de5Y@v1*7I_LvUQ{SV91}^G`Fm~Rg z4g2)mb~E5wx&51L4!8Nl_4Jbq9hj=54bP^P)YJyLc?~$_-OvuBT!SE8q<7!O#S`NeOuh; zkE>#Fjs0+M-=Jou#aY?@EV`@yrZa?eR^86#~T6p-M1tE=Sd_3qwKXSA~+MDvc173do z_{m7o>@3;$#i!imgDr(BmsR)YMalHF)({2nmHUsVpNW`|Xw*GgK6*K0x2*7_VO;;R zG=JR!!CF8rOu*o(AAsmxxAkZ!jDw9BdOmMA{<`MD{V*PV@zJ;;hZ|mG|J2{___cS8v7zPCWARvhjRz z$n>VE%WCu~Sbpk2E-OaW!|AMTRgpwWJ5+&Z<=yh_$H&RH38%URA(IV~DSS{RqAFqH z{BU(~WiVX6{UWbE%{iC8jk0atwKIO^I{4R0gC5L+=P!oP^><6|eqX)MP+vI5X?QL2 zNthsYRuw~$74Q*9H*Ue;=&u1*B`4xAtk!To35T5Jt^t3=Rp99mPVRP`$#V#)MyWgjAE1&nJ`zlQ5>qOySf*yM$QIXwHvl znvozf93X8*x=9DY3nh?O-%Xo&vVjVf0fPsF>7VKVemZh?b#XT7z}_UgeW4xeS^{Vy zVb&BF^u2aE!Lf0Nta=p^gQhyc!C?`AfGjZW1^`*NGLTOO6dmcjcg~E?hNt;9wmf@Qn*f`60D;;2#9~fB^jw6eNbjr?t zPN;+=!X^}IbR2ulfZOsUr>j(O(sXj}^rnZY7$QFQ%ne{4upW~EsCjX41h<$!j*pb~ zi8b;%D@0-!I7DPJWIL3^WhA^#WAr28mQGcZR*G@XluqN--^JNO5Y_`)C;U%XY@RB| z11}ow&!hl|7I0W|S1dBYA@UY)brh(8Mxl@=8pnHhLRCou#X3?IGNyhYeP${7Y)%Hs zp-n^b+|6>q<&aDOoym)1;0_a#k}|=-{Ul#Rz)$eBt4CBE^q59DGZ zf-a-g+D`aRNk;5|706GXtb=CE7Y5j3PcG+IgaPIc`Hx77IKC7ZkQVZiCRwaK1y8`> zJTQ7mlB!_HRgr?dfC6zg=-)>`&rv?eq)7HH!`Ke&8~&+THNB89(7VPz`->lBqTv^; zVx{?t(j~9S1(EYv_SeiSh-xvyqc~=rpCg^!>8;_qZvGTB?`wAcS79LRZN4E}o{7k- zw>)B!HZN$+BzEZHJ`o)=%d-K2fn;HKK;Z}AJy-~y5GcA^GQ68RE}S`kf&jTgwx^okZTOv3gm?>4L@6GjrMD|8dvs)(`mf4)2hJt0@YIdso)W>k5j9as~B~x{EFGF*8bkJk*meuMHhF$6HLyGo-1}0ZqpS<|s zO_WHWCS@z9XpN!B3oe0JP`8B?@Lc}dubkG%_b(GxYd-mL&Y|Sy3aU;%w*URpPQuXv zQtlvEE(LCNKth477afq64%m4IV9-Is(aB)f$rRejlH1AF(#f&ZnJ(MO#nHv1+{I_t zC2)De%0)n=~m{r2VLy8o#`?>mUsi{`LzxE zLy3rc3@m%}5H051#82TK>_h=KW6d>I4}K9SN9WKkCpl zxi=CfE3vd^jSgimIv>%CaiZi_ayJ+qF(?0cUueq?=zTk?1@1ku8~d@O*m_JeqXy|1 zZ2!4uR!T~1$jh{Z9wD|E6o!mbwT{EQx-*u>0sA3gB-knfd>eq=5vOn_p>Rf0+yNlB zBfywd5aPnj>Jl`g5qEqigvAT_M@+4b0B-;yMcfBWkFL^QOjbvOuNVR{D!^@E(&`AL z!3oj005OJ5fJ~-tssIudQ~VF7ZWvC1FyQNGgkS~02cNkT0~T(bCgYyuI|k_)&VaZn zj7MfzH^G$Lv)8yM4OJ+tRwq4{(cbn`cj5Fd_P}lXIp85U%zj3GZPs-e6s}_8zE2+= zHc$O@9#b{1kv8XyoOzfwmDH*tl{cq1G5stIZMDx3uRB}{T=C}7LN>%hn>^@#h&f)SHZ=5uKGnV4~s5xqoX~@g`m;NwsgLHCAP;4C&v4IXZ5KR#> z4BzaL-jo1s*xfL2UnK`J1u|k(48dQ%$OLq9mb`v-?k(AYTEAxvVVW)!}OH%4PIQzcBVJ_rPtPr z18a@HyHZ`-DjA!F2YT7w5*hh)kGKY(h8nojY=gLW*brZuLgAeG1_^(!-r?M(tmy5P zUT>%Sx>eWH{F$yVpTRJcN#d6B#fLqXi9M+@hKysXrctw(tzS)({9ZlOGG^EfmnuDHe~0f*s;7$4xzSNg*PnC&0r zni$|a!QoObBykTB_l_>{I(?k?fwjpm=-P-+RPBSSzp~k^^WPagcnuU@u?J6xlh^=v z5KsSh?Gs zd_`LGd8GTlC_;J*mX z`wfUcd(M%$VJ`~G{XEt(LqMe8kq#{&73RGmx=6p4@;W!}FdX11$<-qNz|Yd9t?j!1BoO2D z`^=OOY+<*7ZN*Eppt9aS+Ylg7r_H?6Nsv_d16t;ZZ1N=Uy5f9QM`3WH%qH51LyWrT z=OuFiP;JBltBV_RIrb~auPX+RLPtwZtB$JDgv@{< zuk+d;?;sM$@qh{`uA8FuA+-X4=l)H%=G5XSIXlrG$JN;tc@Kmlr6ULD+P-KBERkk& zNQ|Xa?N|DHoa)4J7{Bd@X_zj31qbtlP*yM5zuggH%s1f`v%aG$FO`2i^m6ssQP-8u z2>23r74p;+$?`{{!keQjWrsDYfxNIUri$_jZU%814&v z{z13i%T8B(<@790#Xv#^oudtB=fGBTrAJ)n^)iaUBc5 z-AKBnCXn&QUPK8XzGsaY?q3=!>`W=IzZFCxKC0vK2HA)t{AKZvskW2kCiLi1d72GJ zhDzotn9R9Wu7a2kP$XBwUTiRs z2%bG>^E&QK)mfuX=Kf*`k-b@}^!+|x%$3HUT)!g}olT=&*Rd=5I9s$@8!bOdh9aaC>fsEmF;uGIBw&Yi5sr*fSLNwF z3v3MLI=Q#VZXOk=o1BiP7LKXa&v2AjMiueruF#J=KSsPetQYnUa87wh*PWf|8=OS~pB) z6a(6gpw4fYm#i5wwYlqOsX&_M7jCPVc3k(S)j3}7^DNz40rXoZQBI>%8>C#L9$swgM>>rR5` z@x5mXo4@KGsw&*rb0?Pvx}L}BXM>lcRJ&DV`(9Q3CwKy?qX?;UtVl&lvt3Z4qIevrWFugNd+o!{ z==a3sUFz}?-)H-5&$Vlb!_3EM2g&wEE1*hj~%qih{JA4l2CHMAng?|Wwn&*=hYU* zOvq8Q083_@{c3FFS?pv+GDDR-^BzR6>it~CjUzSG(wRI4qQF&$eWibsi=q7^zSU7p zE%CWRr&Q+@b#$9LSh^XmoY<8FsDA&d7Fl{@z9V&ux;tT91$vGm{*|QoT$o&RwN5Gk ztGgp5lBv$r(jAYNMh2j~bW)gF)D?>rhd-Z&7xE=+(9hX-IiRXxudK*)LUB z%k7yxyXn)c5gXB|wbWxQO(S$B=B zy>^*!RdRLvq-2dHjg%~#CUkDzu{bp#Wp?XAM6BHyT}*`Ud7Z?Z|J+!20{KxxD5YM)(*LJlM!u+Eux~OGn$RF50i7--LzIueAPA zOA?{F#GSoWogv{eTkFRH4(GtSpKAA#5X_WyLJe-lcQ@q}jIcThF!IpM z&IIKoLZ^;@;?39in5eqfQN`f2X-GN>J3){ANl%r|Cx2pw{aPDuvO0i&ppw6#`>X|0 z7e%?ijtyvReicl3!GV=9PslVMNKGPSG3Y(T4HR4JB`6KNS|wmJW3U`?xN^N%@xkW| z5MA98sM5?Okek_N6f?F)sSMNn>e~MX0i8vuNNhdaGDCYT498xKEd?0B@E2#_> zd5sViI^=gW)NX*SDW;l{(hLmHu8tmV#t#p3=+`}tD@T%F<%5W}Ky5dMr}(f<(QzM& zvrwxPId#w}jgf`ok;Nn$$GVZFX~Tk5a$^k$(H7gg%rKg=V;D~|x;Bk9C?C;{&@-JM z@&h1&9F(>!jVmqMwh?-v8b--(z119)UQr+~-k7Gudfl_p9oP^CKf3Q?93KJN;lr*g zL-ZR(1NpF@J&ohV`-Tm4O#!7}43I6Cft_5X^WiZvFNl7}D2ik}wT|4t3=L`>Th$m3 z(i7a^h|?t*hcH4+@q-jH<5Y%_hjk;AaPn_3avDY~%y42i6aD?$2o;>Lzy}U31}l`A zobBmtpQD$f^bji8N1#dWeaL;jNnSX)i-aj3=OmAYqCkvk)cN zJE`b*Q^K!Faj@AtgxU4?1Cle7L@7-(k=7xZ6Sv0c(Lz8V%7^vp!Sj5VW0w2+0}zPW=6nvD-T&H*V# zUiDcOzpXj?(Qn$7FG0l1vPLMn?y;rIt67itv-f*vJ!fXUHfO!R&-#Gpd>QBb_~-m( ztajN6nd)G*5K6h+FAQ{NxO-QJhm9J*=A#S*r#kw9cA1gFp zzy~A;n8nUO<7Rp*?97PqBhUnR^m+{}sREX~Op|M8mO28($!MlAnx(&oX7EEuYGF?+ zU|AP5iD8Ww&G6^%p*hRqLya~#oK4>RLKMMf*KtS&z8JaF{*=Ww8eg3+v{MO7V)Lk@1JM2e->3{y^FfNOEkq1!^7G=V?IE+L{lol_N2plMMCl<9x zaj`Z{NM&nRm@C80>5HZ4#$|DS!;!0yMSJXESYPeV0?N@|ZrNg!6Y{X5olrdI@FOCT|NA=@_!tj{g=oi{9dj9S9tdS4#%6h49~8ATKv!O z?Ee#vNBAEc?|%x<_T%<0!?SJ4m*LsnhW{e+cK%0rcK5%8Xa6PgR6iw)E=6(tFF4-t z|IYEoCI`lcds-(Z#|Arw2RaA)I|#jP6P<7RyIVVYJ18pE}RW_rK~qPe(V;f7f}o4tK5pS)etux_t@s&=z(^ z|BTS;7+PKyX#bI))iS=JVf4Qec}cuJ@&6Qg334}d{weab{!`@1|2L7R@_#1s(Ery& z9@{BH>8(x^HuX!9XNn}G3;lPI_q>p)^25N?=4j+h2o6}RUm{NtH`{r8 zc#F~H-$dR%;SG5Sqw>v~Phtu%Xm2GgmiSSCGNmZ6+x)VCHx@@yl= zO#?(V;#B@bT+NHT)+UKxble#;$08=sxX-*bOx6I+w|?a4p3s0ur>Zj&SSlscq*t_7 zLT_HFj&S{$2h6AsW|6i2&~N?l{dtq{U*zRZ&=H*yxCildgZbApv>&xZ z3Br|Hh9@Ho1b3ajPVP=XKPE%4U_&v{UASnetY{up4uOq38X|Q4tEni8H)t8TI}G`1 zzgg=(TQfh>c&4E#R_B1!W#coYD)*g&SURD5$WhS%2epE7CW0rpdI2qf&(#Iu z7i6S2Gr=ZbmeusPsHa5a2_Yyqm&LjzK27RZima)<+=2Io;=!8=GNN`j z8(ji_(PILhf$nB7=iLWP)z7JjWG3>_bt%zCyWAl(JVg+=4v!Lt&R1Ik01?;-lpQW) zBJ;bE9#E|gc3-y=zk`ekHE~ijG5ktVD4+0L2f-bBn}Pq1W+E(wC%f4>0Xf+>mOYL% zXV7I0d*7?3W+*RFpgBVItrrj@SN}#>Q_m5~dIa?GaF9+kMECa;>7F2cb3UQw%{5jw zv{Rv^Cil^AR3p#3f;7^!F5Euj7VM%z@lvC?U!K)r&~%c|q>IJl7U%$Y+H-=zYsqH= z!}k=wWsfHb=vE4hc-Vf+nJkOuWN+0BTL*gC{er&&jx<@_Fu!Z zB{zN!5XZuQ|3`S1Qg1x+pW)e3HRi$p2+t;$Y6$*+7@obVtE_5iT>QG6)Ld7%chK@_ z<@*X>a49cqSDsf#jar~0VbVN0`)lv_ceCex5?W~)=57>x55QbWi?!^O7m?-UtjqJt zY6&*!UsEIQ4%lZuQ+|pUs|~Qzu`OA9B?9-XkWjW(MVf1mf7nP8`c~$qhR(hh zQMmFKc4Db#h_=Ocd)=1LPX9<1WOT^u1VWrxGQXFQE>u3yKR3&*o>^s1ouCNYkWBR? zxt|QvrTj(r(Z+pdt70;lwc8P@IxqVSIi?BuGg(IWrLxF&(K=3ur@Hx#wV$9dJz{3E znyQiGAcMS#Yhy>Bka<3WYEPC22+{@e+GtCOtdefscD;?qU*2-ahTp<@K9`>WSRWXO z*E$*~xzOV&zN0n_?qb}!2W*%i4vN+F%q2A1U?#$M@gk`pyqd<3M}{RT7YL889-v64 zpW~4s;ulVFCWDTU2I0=}325ZLv#WJ2NgrT_YhU}+F}Y(YN0rQ-HcvLu*I@7O?EB)+ z(vDHXhq;l1z~(>8M=1?0+lGfBAOEbJjW+x%JUiyj1WL)oxc08%HRU`1r||4L%UENd z+~{%2eR2{c?IR>UBHq{$L`6zGY8))1JHdTiW!je4R=5*R&0cP|&ICY^B!2Pwj)fa9 z<$HxG{1XcWi#c?R6({LU1Bxisc3xtCk3DXCfZ5>S7Nu;06C}Pp?{DGQsQNWhuy|?7 ze+%58RkZRxK7B(5qLS1hAp!X&`jdBkb-3OyYI-B^wb;EEo_q;o#wI`8aJ^I@c29R;s zH1>q+djb3M0gD3VMDpm5sMT=cc3O=oGN;7J7w4yMXvw!@ijPK}!PreBC=xXW)W0~V zi;#~#DXR(1FUdP@S-79=Qx<6`azBMV^!D3twD%JSAT96%n*6lWE}941X8)pY$F#G^Ai)&AB6IM z7=ed=5)8!vp|FCWl8A6gFvj|o1~Vz-lIAg<@v1aFw0{=lL@A@t|A0R(n#PZsStsh2 zv>S_RjIf)K4dj8O_JcdFiVDvHElPpsBoKi{Vue)X{rQ9Z)vVPYoM9maLC?nxKSnTT`?~y*1OOx;enc}5K$A(}KdUH7 zfZp<^R;(yFcXEDg{6mNZ!P-O1$qIuPyo`S- zadU&xS-v@5Sy-jX1E4gKnss={HyvP@1X?)m!Gkf~Dytl?^yQfd1^C&PM=%!F)-1fJXh89Jf~ z7zgy-0Ylw;sn#?CyFS+yI2_Wb;#e{$kJDu_SD*vVU~cL?@dS)7$+9C1o|bi=6(Zvv z>!8WqNS;N8$O5fpNfabAk-~KgVe`Sj52xq8^-;vw=U`GE9@EUYUEqlVU6T$FHUPAZ z(*!;uS;52TFxePy#|f1 zf=*0Q{zk%aB+%hi+RyitC=1|?@pqmbJ+2(^J(i@}uNHDzqp2QOxlMG*21!6c++y_d zm*023Q^*pFbCVvaO^P|qp z#>2Ru+24hNOrX8!%TE}{2^z=>VHqr##jrNu;%GeXW?hz0R|}YIVJrz?5fQ)|4Pjj@ z2*B~$6kSSE!9_r6k$LEDkt>D=_6FEjm4G3s574xeh1q`-82v9_ZDMIBK zeZ@i3s^FXVc*1t6PgbExX!za{DdT3bqzGX0w$MZbFt>dbR$X9Mo%rY;e_|Kw%_`ag zaS}2l=yWv+`u;WjViCo}Yp*Y_tEFjABj7g`xy6Z08NO`d2ja!AwSf3)k#Kqa$%xVf z#U%S08$Lg0UpC0@8uTv-C`6HD7zG!Y@@OE%ADI^lCKL#NC=?wmsAGe~c$BJ{z_Y6o zb6!J=QM7PgXzY>a0gA~i4f=)zdU7TLIuR03>>$M@J1 zeo%Ayy)DJjey-IZN++BszB61a!JsQM6>opS4{;GK?tNn<0GhYvYr-_ zz-MIZy6*t#t4JSxjX%|miey*btfJU3thTn#pVYsz*?Q%u2Y3G6KvD31rMPl0rzl#V z-dq^56az2##rDnD*;7(K!sO<&`y$^Qn+vHk#JG#?G69<}<!^YmR92^eEMJ>&u3W zD*t@AG$Qk5z;+1d_S051%hp-q0qyc^?Wfdj zVJ2dD>oza`A||R*=0#?)Z?a=qz(HBN&E|)TTfmR6Or$X1_M>~Wlu!PaA*p*{r1v|B zlcB4{mEw!9sax7u4DK;4cCLS9mOK%2W$tohd>8csxv=_HR+-3rf%qi+6AnNkwF>32Hy6TQTtVUjRH8*xe;CWOYGJ20l~+;G}^rek#S+ zh@^85e2b|v2VZn9uoyD97uW^G#8xW%Twl79AU|~ay|1y{{7uUc>YU7m;KHbfA`r)0yXc!t0?Z5;+Ut%7fPfknqb7+~(Q zlx=@B4L+W68!^*soh6?DKU6{ZC(l`NLLA4ZA6J;!BjP*@y7(y-D2i29$Qb8cF$=E1!p?>9msY0ziZv{?o!2gpMBkOjoEWUN@5kX$x7utO53(RC$X+FF@zQ~aqU>O=Q6yTya_GbbfPg# zOWvS5*>ue}bg4w%TiF^a-a`3Pm>{<&PG{6dkYw;Mbfl9h3a{$>D4MMCgUG)SsmECY+lB&8- z3w%WOeoz8)9M^@DG*oA*WTB=t>>u@hm3u=J(=Inb5XU%37MzIQrq7FjeM- z@?~n5g5!!e5PXw9@FkN%o2DZPg@%e`{HJB=SI6rZI@}Y6igT3w$p)oK6QC?FppSTZ z#oXK2v#Ld2RN^-U;!K2eg07RBp$3bO;F*x*7>;1ok;b1>b-ulgpdAKE-y!l>tMgG_ zs|>%#{J&9H426UaUB#Shr(tXAfl1$f>ny;(^8_Gu6M20e=5+CuD1Fj6%>B_^9(l~h zk|9uG(M@#lIXyo9AYC&2^cT4k?v4}BCWfcQ{Xnhe=imJG9xk6&300CbvGER6HiU~$ zXJ=I?vW&t=okfC2H2%MZXE$`x`ES0J$o{9uvu}%LHTy?+_8%h8Y}+Vb{CVzTSjl9kToVAK}^C6wNZC_eS$nx+@SmAGhDR&xHr7+J5(#y(9NN zHYX>5h@OA%^{LNr;n-E8DU3+rU`kgTRSiPWrqCx%jJZnw))|%c3HTyYawYRe4!-lt zvNP2&mxJ=X&va$UCA#bvztaxHJZKr>FG7DmFurx8w&|~-E?6e(AK}^dbhy-a3Jq~p zuodrc%^#*ccg|?7s46w;2mY0{Alk@-t`|(-#5EAkioQKy)fPymwt-7^FE*?DnmV&< z`Vo@KwMRlbu^eY`lkCuof6p%WV6la=_mNHUUrlO*epM|KyR47C?h82k9<|xUZlVmw6 zL`oiK8V9CL{uE5dbLSM4;H!XE*rW3MVDr6Su564H2~j3mYx3&M4y&co78cEBMI-f8 zom*F)9Q=x7;QBPKX`&Tm6Ock?36`~X;`hKX+HOnqb3EBnmBC3-VbrHJB{=JC?@K)X zrrSU@v2`WH ztr?`t?GQyP<~f83WhldWwScW|hxrM+;8h;lo8O9-qcBL~!EBnAGleV&0>LLw&p0e- zL^V>xVUVZK6gXBJx4LdnJX(uw#<1KC>-`mkkGM)o5&_>BkFkC6?DhR_l&^zD5{$@N zIT+(`CZVu|GWFJaw)rD>>t)~#lFON|@Vkm$O&lsZDe7e-Rl}uRzXX8L4iz1{2MKHZ zIE9WXja)w>RLiUTbNVT=e(mYR%?1F$ZM*q3|VV8Nw!4qZghb6ZZy6NJpX*94u^uq?4-*T z;E+F^@u@9GY8mARoWv@}P17vZ_*1eg#G^iBY-4X`F-1Iib`+alLoa_9Iate=0{%1( z@Ha4tqg16-cHvJX_#)&qyPYQ@izs*(O?Zkjpj2oyHW)P#O6UHG9U4hX)l=S#uN_lx+m z8qaS?kk~__I0991ZE%g}?h)ORO(j{*vzmq4(gLaqU6FOLL!`rwnob2^dVMDYcF($- z-F%Tkp75D#4i|N?1+^q<%YWnb+aasnkC|$xdQbyL7BGWgKAGPd z@f;h9CgP!V^>V_tBqV;+(V5*$XQh+|)PHC__|_WNlrchcj^=T*S*4s3B9kaOVTB${ zHRMtHqZlQ-VnvVAxrbB?o`^Iv0tv}r#O5_Cc1Xx&=g)&)2gv{`=ou*>C2hRz6~s*$ z^ri=V3*k++u%&x;ua^nk@tJycjrIY@_!S~f3!o89pyoGXHW9L=3NRVPj1)LZlX@%h zwxlmBQt_LY`I;Lc(r%IPkYq0P+}xR<4OtqZhZ_-Z$tt__DF60%Oib@i4C?|h^JUaJ zlBmaap@3^q(truXE2Y;T%gM{fe1plABgPd&2eDK%?I9(He638Q&o!iXyrUWhI%b%*MCCWb zz`?!oIygWe-*0s177y3x)kRk{updi?|asAg?XYF4SiGvpFAdoX36P*S_Q% zxNm^t?v7_78gq0&%xVrwUiWzKw1HFwkT1XAe35sjg*z81{vq_X18-2ny~riwaD_R` zD9t;?JW|RGpx(vNClzBYlCU;p+paMei&fC)>w4c&&A-2mPCiB|h^W|<8v_lZymDgL zC#x;~2hHL33DhTQ$k+ULx8c|Jww6@XHab3n)Uv-gd45;pdiqI%CbAn-WFPT+clWJ9 z^sIGk$ObF_DM5g;`RH=KO2>tzTgTv{Pi>zeOK0+e?zLS8^2h_>#FU@KSyw;sU!RDq zHNO9JGxtZ0>B>>t)AXLci+hv|6G{)pzyHF8|5U1I9QNdey5Exn=<^wv_<#J)ZvVxE z=4))^Orm5?SzT>=JlimppmYli`UYlLR&IX;mJbSO;@bqJfu*Tbz{kF|ZPF?mI8;tn zJ1`0U&;+K~Pq;4Fk;9>e-D?GQYFM$rSXf8?5cUkVHOjG_+YmC5U4^M1v#2?sY)+Vbnrh$wjqM3L3JBYDvePO}=dkYZ_PrF6vk#4SmVI1h?}gL3KwXsr>Sk zM(c1_b0+ap9Dzxq0;Xx$oy5`1+tfW)-fh&3%Z*YVO~)D`wakX$LgLgWEOClL;4yQp z!H6zv6)+5^nCa5G{3Dt?fBpoNzuQ!{-NB*P+PJyPQC>+5EaHx9U@LCi!D{Pb0>gL| zoYkT?2_I1y(DV5M_%^b8L80VkDXyoaYd@?SSqgtkt&>1hHp);#b4Y&zYm6P&1yqAvtx}1UaA);n+T8`X(0&6ib3$$f0-AEf1r^No#?#*t^ zW^MLT-O>7fO;_#sg?{|SL<0ro)au0KW=#lLjC)aU05$LstEb8`;IB+Wk*L?D+i&2| z;7>7-JqfFY_1k|P=#IP~ZOdH<8z z$Wp7^ZII}z-+m9)ktjcr01ZGHJ^`0wY&4#t4L!f8C*ag`rK3j-RjU>ZTkaVqMc{s; z)FO3b2fUDZO@<}9WyDGFQ9>UEXZS))|DKEC3x(mXz!4OVCLjZM8t9vHTUs-(Xv9Zw zxRhdKaRKbvkK0Kw$|0T0JJbD98BClsT6Z;0J~oK!H+M-z^Vy-`L_z(h(n z;;WDW+GyhA5F+?F5gHw5Zln9MiU_xa(9=N5)`&n7P6LTES5Ufw8fxJN)4M5@vy8L1 zfMddx7%WYhRBL!7>K7?ZIo8LS%G3b2xf)NSQCosXVlda>t>9LiKp+s>cuF_#k|W6>bfYqF3+H< zf0hRiMK~w54|Dl0 zBT*H@mYV07Dt9ayS&5Fj<4(d>9CFhxEd%3wMv?t0=Z0}AXsd3oX$(H*wlr1~*W#H( zyvc(bT2=RUBi>vz_KQaQO!Y+Trn1V+lxtdJabrP?M*f*I(8K9-r87T%GDBc!JYR~Go%_Z3C3E_O*;+~E` zvPW>aw;|6g@&0Zpzezpc#n7{kc382IhgtJaeCJOi;!4-!ibin7Mvymf{Hm8_!eEej5Qa{2s38`xIsH}AzizO zb{@-KRdBa3r0+hoe;qbB!c-$?Su2cdkb?}XA}}p+O@|Qc1bcbzt3(<^wXo$>5>CYs zGMxmSp`o7}N!zk$ye>UERem*&!}v67_9_;b&)vM53tq}>zna8xZFOW3C${tvY+`?Z z30|6pa%_8qTY8zL`B5%$r|eqR;nHWC;*58bZw!pl#+u7?`Z zjs2S4IG3ECGjhDxt+1_)?O(=hVrPd`aJtr-&jIzFF`Ug(0v;$>@6!fjb+)g)EyWp9 zM30|I(p6wkTc+`Eyt2?WcTdQ-+tBW63 zCbs@O;JEMKimJP_xr0~fBV`Wfbix&^?qc4(AvR;Z20>NApEzAy(YP0uY*?8M*m?5 z)yWBaeX`Z>{9U|AKoT<4LBJ0u=!5&q>UZhNf3*7jw+x}6xcq;bu>Y%HKmOl{{dj-& zBq3$d{|!bc%3Sa_j4%%s^}jGeqvIi`#OG+nn-{)|{ax%gShL-EZIC|ZP`~ycVn3_G zXOZLJUNI}_8}?7i3zx_k;hW_)vDNss7xWn^F?evXxQFOxE%fjN#4wiLy!$3dIX>|Y z2Y+p%j980$U6Nys4UGSn_&K!w`5}fgF5b6I{WV-cyP7P~#ylNnERP{yr}s?7-OXWa zN*-r&UHRUmJ%c?5LOOcLVYe6bXUe~QCcXK7%26Vn-TC5di9n93skt9Ex!+o-)z-(N zk7^n5Q?a}X)j@S97$3&qWQ~8oB{$=s*2$@vtMQSi`&tN#m4}nww8Gl5dXV3HB9?_Q zix>%2?I+5E@`Ld1?Bk+L;Z)~hO{4e^)$us0e2-;R5aSv|Lsf*uRr?Z?rhvK#w9r{Y zK{j|L9j$%BdW&&f0r0ls0wI;a1sB#(2S$^OS3z!Z=v4ZFx^*=VZ%y>2O<|qumYb07 z0_^a`=rfw{eohQM0kqz_N1Q$PYF(|7(?V493=}(jUWeD!D6e|my-+QTNr*>@3gNo? zLZU!p1Ldyo`SI1#`o;V^0B3x%D5J>fMKSe$6*)lU$^$JRk;#_RUHvJ)<^W2M2}F96 zRbOlx-25JVRhMvilJtm{(*~WJVCAx{St>ifj#>;lv!(WXk+TeQ`yl>f<4!1hsU9OI zv`BrLxBDF`_#yVXx_$CZVyhGz%SO{CK&AwuBMRc|t9U=p^S%5IFJOcb^8t!lrh+sm=`wX?$Vo_ScTPxmKb9VxD}~MfKQ$Xq@y!DWHyS z3uincc@hJNQpOq*W7@Q_frA#-=PbIR_um7_%d#2gHK>BFGG|sAvwW%3n|^%3icQdU zQ0tr06JU(1Bx6NQQ(maDjV1k5vvw+iF4=4n#F#ujLw`2O_=UlpM0ES$hBbN~^n9Y) z@;0A^j|TI>2tnPPp}JN#_(q|l#z*Mu?;lmo=Sq1^Vua?_MTi^IsO$t52K>4Ark^s8-x2#V(_tZNM`m^bYJY zd=?51FRm;za$eh0*Vd81f4Kd=NJS0wlGn#{k_+-9P#s^lbsH(b{FI7ajQIzo+wYto ztLVMH`c`4APl^JcIkfT|W|rRv;+co%J`g4w)NZOV_s3|9GM?Tw5vUw;P}8+a^SUD~ zfc(jz?q84Jy=!Dno1Z&$>V2$6%e9XKoy0t)7wAeOX+L0vz+@BYlrHhV5g4XOu;CKu zy1%s*u;KumA{h`K)=6O5}~Ocr%;}L znFS(5H=r-r`TC0Fe#aNQ1pv3A7c7v}h3XUm>>&eBx#C`>aSgF6nepNOQKe@leeuYBSFH!Jfbgcel z0oP%XZmyo3)#J$*N{6q|NyQc~^{0yM4vTF@immDfr(TC1mN>#oZ2I)4E1w*edKi`1 z%?wW0HXfGwCY3n+U-j#ijwP^Ak^ws*8-u zZdwn`Pd6UblqZ#W-7t7Je>#6uTR&3f9X#}I>HAS#JN&h8tii&2uHZY!VqX2uy9*n3 z4;x04yd7R;;VV3z=~WO-`T5je)PX&0<}+T0gndkM#!?BrD31|GVYoj2-a(q5Xo;E0 zWcLimD=cs0#7YCI_NmNbB+vv~JUV zr7I@sgv&9H=KVDyyAq4o^iD-y4Fgn_OCPdYXZ5h{cMw1e0JG?Tt9ch~m@d7`Bfvw= zDy;%li9tFdx`R9D=N^fN=%HtOyH&k)9UL(bo%Rd^t5JXK?L=eTvFza4lM1DcX!sp6 zD0WYxNASsq&JWM2Pgy_4Sw>Nbsa0}t6VZ7GE(iAVirbbpi9s%Ixn63eOj`#j z@$37Ni4Rs;m5l_|_sEOj2J;=!{nO?b+jz`blCRJMJZq;PENV zYk$KCe;;IxHE+xyB1Xe_DY6+_>@I&kp+K!L<<^5(sF0z98k9gpIaU}n5oe5#WT_@- zoeR1S!(dmxwXw(U#hUzFp}xXRwQ~QQfB292>*~nLSXCAQ_3xuI1h$R-2S>L|qo!ex z)>dlbPU#8KVej5j@$~mW4<4C7H~(;tfbJnBntJWl^&cynt>4^!fW_rCAIqpc*hE2V zkcjY#2TeM#SHUolU-$+ZrrZudk(5;Y)NEpa90d&-BP^f6@E&839AU_M3|CP&n+N44 z3S*%K`q9TO>j=q3M*#eY74mtAyfxqtdq~8bQ2^M)sKv4Xw!NtRSi~6*Fi%kwwP{#= zUD%3a1m{Y`Mg*eeLs+{g!n}y3^IMojRz$ULR4zVB`S`&mk{XH>7TF6nCg-Xw_3Ul{ zICiE8APUBh7-El6_5hy^VP%qjP+|Q5ghQag3Ku=1Lh7Sl_e4q_+uwEtvQLR%PA5pA zG>*nJ%E<#fSi^ST5uD=zd4wm2XBaoiquX_W!QlAjM`6YF@r|+ZgF1jUE?U|Y2hD

    p~I3mHnO@OM};a~UQ%@ovBUm1F69tiML@5%%3iFk{ywAtYBg<#FK8A!EsI*n7T zwit`j-9YB?bgIDF5;%*1po^lMi-2dL!Fi56`2=`A8k|FcSfHR3;D?%d-ih)+ z9n3Jb)@$^@r-vFtyl z%fB-=iFg(8q$m!-y2p?#2p?{TES58bqo`X>_uz*_co`~-s)Mp!n&A@#?743iHG2%T zDGYJf{=6=9>t*(({Pax%+>-5_as{(uDimCKg&E6vISycSVIOP~A_Q|8jHoSz~o zYV0vQZKwZ6!O()Iq;krANiKy)fa&<*g&0TziuxV^vs{5}qeTa#83^s*PRgfSZ1HCX z><=5VXQ*_jO$|R#M}SiayiSt-=0=-)hW?X}^(KMm0^|rfLt6xx05Cjr&IJf?Ng?>j z9yJ&P`HrU4S!Li1pjdW%R__jpI!^ZNdrG~}LPJCOkXe&Tqi`dgQ}Mkx5XuO*6ffqK zq$WX5@t{qLf;J>WkZ&#xKOA&=fuf)ten`^kKVd+U&>oGR2XP3BS3%ivGMjj%pCZ8h z7(|dbkS-1MDJl!8DgRc>&oiexEf><;WAJgxEhaD|_&yPyrw8#vf9^pONWzI_EKJ=P-MZLmLSuIpub!8A;yy;s^<(IQecIQt?+jbLNac?qOL2w^`VrCQg0-RPf@4%haE5*kLWwm4&!2Eg5E}S z(62KWof1IN@nqJKd)l_ZDh(bcOF@(_^|g3$)I*<_Z~7Y~7%sBacR+lcRG#KT zk|PL|1^{(-@g~4VI7M+s$CQ(xkNo2h7b8WeNp#-8wCURcQ$JnRfjagX8`tj%UXnjL!1+# zJRgMQOxu)hcmiX63`1>3+==OJxUc2|;|zX!hJ`E0ArlFtO4FC!qUu5dnGt!L(oJ>B zK;aO3mlYZjLxB~blIxR1)Q<@YQJ7s(bBgph5?+3?a&;S)dW2C z5aj4W9+h8STg7>JXIobk@SK{mECTVZ9iGq0__X@UY=la!gd*5UVVL5KRl!4Rx#k|_ zroQavp@gR4re?b42EIg=$M&^N=B;fPy@8wY7qcSkP2NqzeyFS&px!0Il-cWDfM5P9*Ql_8Z?lAFULE6GqE|tri z-t!%_0%k7pAMeApBKzr6&FHd$M?1j7aagebts+0BM#cvYT3MV9{SK)OieKBnexhz8z4io+aX}bC4?Umordo z2Pl+wy_EsjZU7e#(wDeL^J&s1@%`OQxl}qArL=h|uQGB!RDtiCv#98kB7q+ZBUWr9URAJ0v0!xV2Y9-@aBY9QRZslb0s29Lao|)Nl1zZ# z2MPAD$b4@oUr3xVkM1KX1L{fRH}@MNW%#Mz@ysGM@BBEYDai30@8y&>DPmu%r_BhD z7WrLqMgD3n4JGC4<`EeQXEV!5kK2>CI@&#~CztnK`3I(*K1>I~IqbS_C$T3|^UpZ4 zxAiwcXefto-e*m*0UX+Au3JOmuR_L}W)ps~f43EH?HJ!A%v^sIN9{Cc6Fqy8wJpqH zFmjQ-0wp{A5QtWtWfGZudKK{AWq(!%EJ+tXSq!+qW0lilUc$qhS_TZ3Hx`ZP-wd$` zp^xKSm^YQ3P6&SIFw;1HtG%~{{mO($ay~SfaE9vJyO>M;r{U8=C5tfdb4tdGHP80bdrIp#r4$8B|FT5&`Phz zC)?|JtcKr#@kKXk(=;C`JJtuxmmheL&Bs=GA2NGZ>{7=fc^z(^CbJ&g+iaDizPds^ zUcQ<*Y9BVr{Nd78+J`eS$y*JXn>PIKbMk^`SU+Y3zb$-lw=^H&+wk$_(#O|JmYKgl zR$kt&zP4S;yj`2O-PpR_ytLi=d%K-?=Z4m1=e3>Q2Rr?FJAPNwlHCOUK(c4~Xs<^cY&sqYoql$Zj6g{H0G{|S*YRJ# zjO0T7m!3>ovQqszkruH}W7;m2b88uO-9p?1&^7_Ck!Y;(fVJ-zQ=hNu%U^4SzfgD3 zZUTpvK8#nc1J}`C92o3PQxGm!nB>Q3?N7gY`q*7XGh4PD1*F({QXF}pkEB+<-Q}~h zUuM32o($X`V$M5ROCN8xAH+^Buc_$CzNwVcPC!a4i zm~R9h8_BU_JI2F;@b4JmZ*KfwbHdrWKYcHoq%AWx zPp!Mc+1tZ^_PTu^UUo2j`eW?6)x;aNDIcqi@tc>+MVU{}@6DvJsiz#}4e8s6ilTfD zimzDwl)791Q+><#V_?iml0`^0cVGJHZ?&2q=uY)l`16!3dlVSs|C88HHgMl`O*inG zZl302GdE2yu(_WESbyb(w!}X%!arg^3*?!6a1@JHW5v4KW16#Po6{{mS`=H7F+!zr zp~j1UFv2kZEp;8Ik-WdeerM}yqrVVPwt6yUXtA7*wc`v~P zzy0ag`;Jt`@#*9_oE#LkY57EtID8NMI8|mJSZY3Whup7ENq+FW#xLhp+f#DCzQy9h zdP8X}->J*l?}xkZ9;Kun?e3gZX&;`yEJZ=@+fwEwK`d4VpS%)z%Dn?o&l6gR>&&h- zkS6!**UB}@3--tup^lJWep&y8+igtNWQ;JqplP=|V>qCK+^1q(zkCK0<)_0J4)Q1b zhUQ4>3O;(b(T}mPsMHfZCo!bU>F07F$n~^a*5F*Q61q^J4pb%Qg{tVHyD+j)p}K&k zuQJ-sFqKUbU(Ar=!9W#tnK89@u|mq@9p>Vy<11C?ElwXgi{z`p4mZ&lrd)A0v`T)4 znUb9O7qjTgY9FMd9TnruO#(teY=&G^mW5^}S9MtlW>XiZBV{vdw9qgOEmfbqcn?c> z?C|G7uDkcEk$0e#+k(#Hm`NM=V5Nry*W1v^mmYLa*j~D1*XS|dx(BYTUL+Q=7T6S< z>Skn&%JrugOqPK&ZD_w&&0_Zg>j*Y!nlGiJk(@>BNu-gp%Xvf|+&k7D^5+FH3uG0> zG9L6!i|I#A?6c=yK4q_@&d(b^X?RBN*DFaqY5nmY21@O8 zE-r8L;1IkO@uco$jhue02hJ?_TWTGr^BrWAL}Sy-+LeM6rI>N%Y29ENUa(c5q288n zq?u(;YVorpFA2}n&&Y$z zMRt$d*~JbqxUtLklY*?D*1zI0rCG;jh_n&#ZHz?$I>W)@Xw|U0gQBF2GtX;MWIZ=i zDKi5k-4u3_U(I#i8OM=%!t^y)9v0s5I1^AZEMK9g zB%(xkiL{*To^=LLEey5*Ju{)Te6|oho_J$z1h|rpx>!3dn!-V9zP2yPo?nJ7ef(A} zIqfoEV}-b46?JJZF8S?=sd$*-brSvK3`$nlxXFz44-Mjdk)T-=OQU0q0_l{By=2&IIfGNbS|(j4OaZR+8lY7qsk8gdcCl{~ zU{{A%bf=$%q%3vfPh| zLfH^t4p~k}&wedscmz5*=9R?k8d)4=niAgpjPJBvJ8;yoPqn?{>FAD!p&K++OktJp z_hz5ss7y+DjykgCT@?4vvvgF$Ge%QY!;+KYnx?oquWu>swWcd4LAn!vH@`R`x&zAMgA@=kTA@oP0L^fGq_v zvR$p*QzP5UPxku#pItn{?%tUr^W=)}D)*j8vB(nF26w0$f+k;sezk;|We3Bxc`TU| zAaSFQtB~&)r6U*9euKLb3CD=wxP22_E_?%Z?;q2}!JQG>>0EU*P8ByyDIN8@_F&;s zUl^R8xu+74&{hCh;|ESM>(KbgqL(14fe*@ms5Z*a5ZF!4+%+2HV1~4~ z>T1F6udC*B%KdiDCEGMTyS2Y@rX?UG$(y@!jGYB@@N-Liuz)cgU81Nwp z5fV81=~hS6RIF~Sf{?OI?&E#6_R;azME5HmDRAor678id_Jdy`b;Bq7DIN|#4{mPJ zyOrgg21L55@`oQ$kxm3cqWbyiJI{;29=7m_-0gr_*Q>J=KHtNZ^20MpTDj-irCb;t?)D|!tI*$$$%>LksU{y# zjoC{?ZzlE$;_NA~6#dQDNHT2iDr`e2=qwV5XTUsxZ7uH`QVehkA#LvyikMg+)s$*6 z$jg@{lBCGV^AL4W%~-Kb1_NoFZ#fp!uTqj8;q6hM=8xpQm{4caso)!NpBWrZU4I%2 zsK*kh75k;r6&m8eamFpX;&5+R{p(}wXF#=5# zfkuo2=P=yN&6G)X_X>q?1e~ayS+1c#p?0GXXH4Jo8fdaH1dAbQqR16;Y4GiC`QVE% ztLna|ju?@zk>waE_zx;E7BG9(m3v-b4V+FCp)aam3kl_lnq`a86**lL(~brr5+`*j zQM!W>edL)(^lYc-6ONX1FX;{12~klhL#;*1Y(h9Y>7kmh3Dp?}J$Q^UP6ddL}{iV7g^ui zMxO{=G_0q<-YmUf*52E_00XHR_FE)WTm<`VV(kkJTS5{B7KW>QhcMugF)Ymaz;NO# zv^k@%Uel=FrgIvU(4zvj^U$63f^pn6de;nvI2sM#Gdx|KOjrPozN#M@*Np9ZJG_zz z)u@ zOnk>QnSQ27$e4s??AlK8O@+LP75!6+A?{4@p(J=~Sdw&?^F%MDj$j~|gexgD*_|w{ ztmiqDHaZ&(rr8`ZM!vosp`V`009iL1Uo$=3d4i0rM}DOsUJ%A1l1Az7m)#wF`UTDS z8EYPStb1!`Y-OLF_BBsx`UMjXq`S@APk@SD z6p^k5bR<+;iF*8yLVF{`T*1vqSlFUk+MGRFW_7_p<|`(x0(X6wIjSI$vE`ZSZG$T{ zBi=t*CiV=hRgI&v#x1q1>ZM1cn^g>brz6E^k^p^-!V5C23OZ{hRf8SR7`OQuy(^QL zL>P!X7LG&>)I_8@J(rMo5lcw)V;INJqo58f}l}DsnsiGxV!R|eMP%dyp8O~EH z_NGyyc`niR;&d_nL^kn7E3%3~#r(8aX!y!6<1!Z9v|6H?oEdBrw5b_uS3di&IaiV= zPVZxa&iX`i;*{%EV+%QBCCkAizv&yS2y8SuI$H73F6{oHN$|)yLfKFQfHOa#@e!MP z*N;6xJ`^1n~GT=nxAUgGvqpSTus37T>Y^#ZwE4++=V4a z6S%D95RIeWWiU-M! z`yOBW4o`S~6-_9kS)RIXwJ!Q|2lS_IzKQL6PO}Afq!cmzv4i!)lgJWM&!{C@cUa${ zxP5Ls_#w$}69nsZtS36Yp_+bm>hSoPMys@Wz-lVAa_MaK!rD96X&_Wr0JK9OFa?&naXFV))a=Be@p6lyEy66Hm zUSXuQ4#drPXvGRKIdh9ZBD3eWJ8fR!SN#B2P7&8AoONXXWR%VOr1E8W=Bj?}>Os#c zhUij^fu;f~aLZAu%Oq3x>vDPVmbC9x%bZ`W5sV%|b37u^CR(wvykLWn8yAl}FoezcCAIH7=-?w8_h_oH-WzeB zJi^ay`96Rp_Fl#CdIt8pn*pAWFKx|pfcK58yzWtPmXp1*ygPAPxl5Sxi4?yt<0sZE5ALtM7ArZulp(9s&>Er>Y{z^>vhH?v-;N_ zhS|3olW+JN=r{AO)NI_^JKS!|TWV+9Sry*t?7ga^?d55;(-XAO8|38{v(t~*7|t|V>mv+K8)A9zo$??(2oZHZVElqEFb zvtcb!b`u-gOwj31Eb-lH`&Mz6_j5HTvRlP^fsm~Jnev9JLK>p(M-U=VALNRn^T z-rljo%9l+cW~tAP!f{M(am?2HDZcx~$3k>3{kkJopNiN-?Sd8ZbaRRO*_-=0$9~!1 zgO9q-wU_+^i>#A5ta}gRgs(tE+p==;{vUM@DvkZcW^h7vdU?cyjLn1GWB&~Bm(#WS zeJf?RnSQ@#rfiYNzL7|Mfg1sNxPTPhFBlI0HzLF=Wo9l(cY0P#Cw3-|=M4))C!G7P62xeE@O4gZO2k(qKHTL`IMdU>IYy}~ z-x2|9dTSGUn;VC=FAvG_di%aZa=iZPhr?^%4zJT4Ild{R`tCE&wh+jHr0ClVd2i;- z9yDnfWT8WM;{)h~@==QICl6z`ZZ+2^n?o!vx?~O=Y*7)vB+5el|c>l+Vihn_p zoA*Wvcl&b>`thGT6SiApKQ=_}*5CP9<-bu8`mxe?i)=Qn@ZNfJ>*JdnTV<|WrA}ML z*S21f&89Zw-1x>zhqXLIQmWh{PWT;$eSUi6KU196{u508OL02(m*sSz?JvveV0ZI> zjVHhUgD2Pg!IL{Gi~flxkEH$`PcDC5^6+&98BZ=DG3~= za(Y?{*>9Riu8+sZ;o_5Uaq(nA`EPh~>>oTi{4c+0fl*xcl~}Aoc+x-Xc!8WA_w@S1COdoFc6Ptz=;HZTcijG(tM%W^rev+DDOqc3Zg2EA zv#Fl3wXTsRS#GMK`v*+EqGhbAVW{%I*yI#s=vC2xBmv(&sWNg3r;48=&Wk_?T>2tG~?TqI^b$(wrX}J2tvL z5wLQZD`R!V&dHkHrn#N%hMDA|?Gi`7dqZS6oAP=j#Q6h;$n=p68#($$k50RJiR{^T z>6ShjcRy~jywU%b(_N&$_?-S|o*LgNuSsk3=qhWtm`j#Y{$ytAwKEHp=61$}3VwR>1=pI`IoU1W@yv+0$L zT4puSC6;UhPXF~~U2t;uf^HicL_(=RGMps{IkV_w22&h52~=Z~o+>EvYAp?H^u-{E zVMGD19C|woh@z!@Y^5p6d67If7uOWh*oI@D`?>Iby(TfIOG5~^E3+jgm&?30m0dzr z8%ek2Kuj;TdC3D<*^@baKaj1+OARO@!%$im(S7{_4`aYH6fSh*x!N4#pj{F=$d>qs zDtch;RZ)DuwFI9#2>PH5d@6SHNoU!#V+!m!r(h_;_ALGZEo7Egi~gY={w00fcM?j5 zYtjRs#uRu~)9U79yac$V&Rwqd+FEiYMD-myfg}RXQcHsrN~krz`1q-575*;1CR|-; z#ZW}Rm7s2uW=Cu-YqkN(%NzsnZ-kTleI&rlu6w90yGhA1M5_J`^)7WqC(T`BuzoiU ztGTOs*|m(%Y7|{12ZPvi@u~Teb23bwAZ8&+^{;g2ksw5954KZGf*krL@U>bU7A+49zbO9KKwS3!Ci@YRUs}=Y{^``a>QLRZ- zYVG?sC>f{+r^-CYMpt`LcV-^R>N=3oR0*3Q<#5cQD9Z~4@Ivc`RGh(-30@`jCRQ-k6X zktKGzqq-H)vB$lF8(g?%@dDJ0r=~y6*~j{|J*r7q6M=$s+@*Hb3OOxb*)jr&A{f`0 zzdvyQ!uXKvDMd)?p(}!afEjn;0V92#qNY!oN3U&dHQ@2n*_*lozYF$%8A;)ToI*KC zd@savN&1+y?agDL&H~QdCW1OF$!aQ_$&Q=e{O?08G`l@`PH&GWl!1G}>9g^|mr`SK z+>YG)@0mUdgYJV&oivYcq$;x&MuR-BsRxNP(J;Zpk#FCt+dbD<+3(k(A0TKPYu9pI z0>wk}T?KCF4Pg|zf(1|1x`f`hNA9Ka^O%997|hzNGVsXrUNoWx0=+2IK_<*rM6Gg_ z(9eR!l|}G=m5nsQ)~5+|&|9DDo0H#$fC6Rmd*&KfvYz@eq|-Dm$mjIquhpvGM>J#w zSTvjh=;5T$StU+6*A+F)>lSN{Z)jf%}~tHW)j{{I0cf2(gi z#QLi;X0L}v;`@_c2fj2|tbpq4uHQ7g%`#yY2|f!H9%P&?F}U{hfyQ~oP?{?Y6L8S3 zm^6=5kGIel*!n@ABD<=MOQY?z4&5GE<0-Jpk0HQDX$*Noe?v_>gxp!HG^G_OH;j43 zRP6OkhkHv(n^tlK=gT3Rk-c$YKpnW}{;F#gq8DV}>BO>{YQ@8&H<*S?8cLe&IX8gL zy154%O2n&mn)|9xq+ST;EIJb?ptb0$a>-4JC7#6{cag#0P^8L(C#JJkNt+SUg4UHN zmt2wBs)hb6_131kFttN)S;s{jp9;LI_bb(30IVz;Mid|Dl7=;lmFon!j=thGMrqAd z47$hI^hP}6U7Ta?Jd22VFmMBrMt_&mFk>;nO5N367=A`m{p`@(F9B5+w|S#}@E+qV*8~PgxlE;Y18OXZwRX&dqElbsfM_%|yXD8diFAM(50yelANC;Mse9tS&X} zgOPT>OZ!7RWi5v%r1HlZ&r|=N1a92TBnfQCrGc3GtHxiRy!*MKFxD^{Jo+W?$IlNa zhDKtn@z;VgzczJE8Ydo&etn_LQ)d^_XjUM_R{U+|qfA2=PhlQQS*+VO(~;85e+?#& zfha=8!XyazICEFBS+%@r@|+{J7+4(uopg(WoD+JN-|sizniWJ$k_XeDag)L1^#Pfa z0UdI)%cmK|avk5L(Lu{ruDkTbJIX$1m3uwp*Eug_$m~Jg#djQ^Ob5lPQf8QS~~#a$8pYkP^mBIvSIR@Wa@MFLfC1EX+}GxCtS=j2KR<7Fz2I>tKJtVTxEo1E0Qy zW(40wcSPptJm{0hP&w#uyQ$yq z5`trcXG22kV?}YXAvUoc>`~$z%z({?->eEJQSk< zJ5m}b0OvyxPw^Q0S(dNz)R%zB81`uD@tDNe$oHri7E?q6`hnmkHbK{1t)D5<_Z|&D z;wjl%5h6Z9N714KGibV=fWh>IKhg<u&oJrnurtF%H zz-IyPeeZpnWvQxQYQcCZ@lBSmlS5`_y~Zegv~j#jDT4kI_INp8ni7YO_i_*z~e!`gQh>D}ou< zKM|m0;ms);Of~-SW+j|V$(^7f9B9}gnt?=u@ks;pDA+z3%x#Al#(6(R0d?(3by{)M zCz)jg_!Io&OK+k0EoMb3S(*2UJPHV(>_xYZ?7&OVYAdFn8sd|H&dA;)m-i4de?C{v z@G%1F?Fn=M49g@)JOLz4f+0>jAqz-2wG8Y84^2X{8ojzzCJ&q+uou$H9$3w!V$7&@ zxmEG?l6$0LPP)?kz$M!Kr_a+&c^H|xFwj#9hGGJ^lEiRq3v}!;U?YI&Jq9BpQ~=Ge zB}=g}mshAAQ%gug)rqKXqCISZ5obyERg@BlAdxBs;?lYqcxgEudMXVoL#B2S5I3n9 zXgVNsCe zO#uS!coyIXc0CnOEkowYpUs~$rSI}DMEDo#HF}rC-MB<}l=v+H4HfPeNujeUN|t@* zV8`g{d4+DAzKbcJo`RtopW6c<9@#oiO9OK6k!R-f`QmRxN@p8?c$xCi&s-eHJt|6e z6rbJW>Us=>MzK93apPzif2OCGk&tHU630kclq^LdfuV!|t|BpDHeR|Yy{;m0Phs;u z4&;Trh+Ol<>+6&T7Qn;rs*r~ZPK`Km0zmiD?`U!~@GhnQvC_ZHJiLau{r%6WwI=6W5 z+EsG}|7p-)&Zg^Y2l~kHZ?+{XD~ImU`G=Hn33qG7gep*ejm4SjGU*zZFw1Qcavq62 znuDHbA#J*?Z@;T{XsR)6B8%JU1MTbdGKWxxOm8g&zf~+>hh6gf&(xMGCsixtNeWon{tG6Q4#a@tc`X_kN3ryS>6)knLt1rKU z8g5skVa-NAs&U&5#u$bPv{6R&d5UMOs+A(2%IT8{8AmJ3fd}xD=gq?jrRV)jf1egK zQd3?%(F5KPjr8ZN%-spQQAwUAbodzqkNCQP%B)EHVDQ?9I z6f005NN{M;7K%%;;>F#H26vYtg#v{_1#+_1f30V&v-g^3KQm{)IWzam+;5W1J=cBB z=lcHYPM(2ZdbAC-Qq63*ipz2Ddr9EPaa@f+mHL{9Ss}Eu0uKV9d1oYqU)crUbT~9L zUzT(1Ja!n4hU)A=b*;Kcle92|@V#Mzfd+J;tLQ)DF8%zfb0i7`t(72VMYA|^vm~E71BywP=PQ77wvd?}V zrAk{b@(i4huIpRrZ5*YtGJ8bcEPZhM;mJ4nHKQV;-HTv@CEh1p z5)I$gMrEI|aK3p)m^?ZdC%Ml1h9**;(w(~j7;+U;~j=<|QuaJnV zy5GDLAEvsG)Xg8YHhh1Ej+$h*p-7xXN<4jw7He!sgtyVOPl9CPnQkUw*!f$MQyk_~ zcY~(5v#0L2Pw^fnNTH|T%+rFB(?S^YfAvizR;Q(IrV-3DvXV3M$3BuqGs@XBv2@n! z+S;n-=ErSRt6h`}FcmFH-?zCrhOR#QZL`k^Aq4`=(}%M!XdxMj1J=D?>LcXy(-^$<-P2)w!V6 zh3wU(_SF@vKE~Xv%BL@G`~{PP*7mcpFnR4ORwdu8ovuZn)3)}R)qcx%L4do#3}W^u=T z%q-^DtHdTX52$Pj33^6Y*G#>;HvH^fHiT|A(6ZcvwMpmPY&UK@zTxct@I_qQjlE%Z!JcO2gDVI{3C6lj44D6iq6Fm3?U z$#&!kz$ygzj34?e3FrWWS|;s$pxAqPqRWp1th59=<^q#7fl6)!RFinpq(Da))Fl__ z(6wt(eUR4xutpO*NHBWFvXwZ}K0meDVkQ(qP*U}X}}4!!r>Y7_BM@VH~|!5tc{4xl{_@agr18z<1= zbdQ9L=BeAICHl-H$G~j;u>Y3EybJpyTpB<9;qc;zbJ7ow8i32IOOICuv{0bA^wkTi zE9;yqI{?uBbkAFw*6ei84t^Q-P2U`L?s9tRdA8dWeC?FV!227&H*f18d#7pqI!I@) z{MI1lEfjrv_aS(lH|e4hdK7iG)OdLW)zI+Cf`l{QqDQ&gz8c+?KtH^sta zhOLSBit>zKrw+m0)0O6(k<7o3FlmA=MxWfQ41Tz+wFhA==z$vLGat|1-Xk^p>A5%N ze-s)2FrF^oBTOTp9p1OoEpgOpXN zWOi!DaS$cj8Uuc*ijT0oh#WXWDRF>Ya0aBUQYR_4kH ze_ala{tk&Vkch*=WWzA~5mXo5c>bF1_K4cUi5V2Bi*n62q3Ei79ZVpAL0cqtyo*Ou z@=D#2UW)SY;1gcupSmJ%4AWt8swyyF>*DqpaiqD8{(ApzP6(B1tC@h;Z7#GJ6;& ze`$ub)6xoTg2b~ZwWibJ1296-{Q~xu?7lsRcCZydFZ|ESzG1kS7V1T&pAzbFN^9aX zWgz3Z{EG+Tw_`SMU=x2}?i{-=zcd-c2JBGvbCRsb)W5Pw-&Tk+iR{Lk**smG(-!_k z>*TuoJ-l9VB~QoXK!5SX^yeC^YxU_kLu6f4Hp?NkGM&V1R%ThNU(h69g9l?u=!p?8q|Aoj&3$({s_S zXNyBjL}FpGO$QFOz*(faCy6yhDjfqqC_Ji~2%j-cOyPc{y=mKX3+jfZ{sB<6=+q`? zwMk4-&^kg>zy-j-O-p_!Z8F~fo??C1Obpv$HML!U4U2d|i&v1%s{rRMb3e*{gQQ(H z*BKkObqW-6#@)t_9OYti%C2BA_1ak6#^t1bK+Q)Go}8O2Q)qwpfupjBK^aOeuv$SN z;G9on3t5%BsVrrFCd?413~j^)r5ZUUiO8SIG8A*+b{8WK)le+Ag%uGVWr6MCcXhv> z%cH+y0MUe&GPJ*Hqr}1yT8jawKl$RC1xfv}RhfkhY{p3>S*)Zj=zcol9t{gva@JKJ zmuw&O?tCGT4h;*DS?MCN*zXa%nCZtoHE68coz8oBkiaMR9q5cT%7t(c1E{55aws&{ z|1H~tJCCN~aqdNB)Av5QeNGnq6$$-%QOe(h)(IPz$$R3$sPf{F{DGg6P=3>(^jc^_ z@E;`e18x+p^CQBrbL+@EHl=d%EqY~-2$Z?D;z&Zy$X;FGGh;{c=oFlVKKPpdK_j~t zZ)LEltWlp+k{RVtkrbc$1HZyjVNl|24I%$%9(9Wt57&gZ)I#)hWt6^()*+VI^=;q5 zoLwK9cfTb@wy~1(o^n6f+X%sbO;(e039?&27YtS8(%w2o7;?T$@bu2F^$^3s(d>GX z6gJoB{*_3W&<5c22mg+bd8OE00WC2YJ|i&>f`_3xbXjCRzTUW3gXv+kPrWruaw;$X zkKQqduI)P=%2i(dri$=uA%Xka5mLIbq{x+2noFmCmN=^fuUz)hEIRk#&l$@-O$fa| zj{V}$FjC9DJlInlpwHwc*~>zWPBIHN@5PYW&aYMhSC$WCN3FmX^;-}dqXFmMUx{wo zI6YjN*8Ynjk#7b7fc#P=p0&IryZs)RSME3GNf|N zzIN*k3ma%;V+(5cKh*gy}} z!$gStO!^edVqvrB@pc4Vqf76(qHm3*OelHbWK2*9J?obYA*1gSmK>N~YNG3UuXn=E zx(}lvu>-`}`j5yWQfwM_v}=8LH&Lg1zv}osYGwRZpD9Es0P=?hrP~bMI zc%xk$T3?U=rBF;8t$jo(CQ0Tpp(H7j#KBE(muqQGWl%9oPq}kfqS|rjFgqbhVp##v zy8vA}lL{&-qdZ2Q_)VQ76Cn5mIbi2WweOwunwvE zgK!q%I^=-pEt)^~_rOtLmGiK*Rzb$fmzTLphMX+qIEMavk2R1_r_GloS`b6JPsDnI zPP}xk)7p9OJd&Fk-7AouArTQ(u76Aqe0U)b0TK?+%qE0ctZYxcHc+-O-6WOumCRA} zkdxg(*eY1;g0-JstIwTyQ73I31G;~en}#MDDEChLB!Y1`r2R8_1_2J*zhpKLR*tXR zxm>PgH>?ExsJ`OTf-?PNe{Jp?Z7`fCm$dERci{=N$$)t`0^IxH7?1EFnd_Z^^# z3^8}8-nh$9Z6Sv48Jv*?$hUOJj736A$$l@CSduQgmzihafAfL}fjW^M`1S1fcw{=m zK==TcX#S?~>BlHDD0bWyjy+oB2V2>_qfa;6(l{X82Mg`ya8%t=gxHYe#6F(bki^(_ zbD3voJBnQB6b~d6&37Fpnj5jp6Qz#e|NI-rV*vqgjhe@m8SLu%Xo{+1z14NU@3y9y+Ux3dyi1`*7z1rkV0bkq1^b!Vr^mEyiVLqLxOqWb zF88BQNYMq^YDB-=#egVIzu8fkups_JzrhDdLl~4i2;M||U5=1Jpk9s+_CZ_2s++}( zaBSl6apb$jnnL(M_z^B3agW-_EFyMpPO)6sh$cmzKuPWuJpK(lnVGx%3wUzB(#(wd zBK-Oi)#G+@W$}+XFafj7kM<+srjXMkv6qDsU#F$Q4m+aYVa!4!@frByC}c%AzNjBk z*biSw3^^o^6w*eDdfEW7z)#ckcb`=gBKVF;N_9WAft(VxtvL3S9nZ zB>3S)GyxK_G$)26B(sQV;bHIV`yX)Q!(m$I_3w&Dtj?E_a zO2@{Qf2HIIsL-)QcgpIx#{}mX&A&>ggR(T_VdT)&SumquX)Wlnb;8!Bf0<;+9 zn7@ah!!nQ!DcTDjBjM;F5wEQ83uuFVG}&%E6nltpn}z{5CUNkQ-jX& z%H#r_4$^OgWjBs8TAMWhtm#e*o=NK#l(@1?5 z@q1=!&?E63czOV&tMZ!wGtE0aXgMtW0<8LHGAu;8*?W2b=bm8YbZ2!aNB@LG1emj1 zPdb}~Ums*@sVk!qx2&xq4*)Ym2DEVW6#3$um=si8N$3~C#asc`dU|SnarRCTs+Tj> zu<>0UkP@?gx8v(1_1Su{X(W8cKqIb=2V{^sTLst9;EdABm@?%A*VO4h9gERD*0bUR z*DR~qti~7$qm1WXgxQE zK~+e(HH;H1bp$1z3_X5NjyscSN2IhmYthge<-|eW9FN#Fjt`lZD$*NzoM(_rPi>uq zOFZi?Zj!h#?V+(ymKtkItzQ`dijL5)j*u|0ETqLX_*i88LKx+_F{?_D@!~qdp$z)2 zK)-$rkTf)3}{v!k(pgM&Eo!l4x5U)O+}GbXui#b_Uh3(zP+Z zEIAyGvxNCo5x%}_R-zD1;u=wE4I+e)T$SpqN}|NmUU{SHeVF!fV||B~_Ou+{#8jgmsgOh#J|z zRmT>L+NJ@0b3CqjVPYEzev<~L%!6X4s|vb$?SLA{bk>-0#wl;NpXKW1{OGYo56WO~ zcCvR&PXlg6IgsGmZvH1?giJH;^r6E0h7c|7W-TKVnO){oqR4dfgi)JE_3_gIO!^$^ zmK!jm9=pwWsyUTBqmeh}gGE+Nt+Q@jsV*B?uXiDAFU(}nGYP5sVLB^oe!A;3CJ)@S zFjo3Z8p@G63~zWjSMFRI((=bWZZM^%vt%_eaNXD15PRCAKP4tIr@Udcp8KRs(&Vuw z=z)kq-fE=c8qjqCqTR3_w!5{LYBS{cT7_nTTMDGmVcT80Y&mAc=%2K=3>K*#coZ3!oL!aV2xt_CEDq&yX5YZ2n~f zPQ&c3?cKO8VHDk(p;_cCW14+nYGYZYEpj2;^={nh@69-kHcOf>%^{njYrEcQv4NFK zHXRWLJ`PQwPTcG{$$o%dSA>@KGH#VaOOr#?4VDW#>d{5{gZH~Yor^C-ChTG`VIup_ zuL&Y79NqXqQMaOp8pMnlj>rKWFZ6n>TWsXGQMAauztFzT-GfhXry`CuB=>q+S44C| zQ*?1xnh460Ee{#;G~dsuvEJeB-BfKb;Cd&UsQ6`K1TZ z{HR2hsI0kzQqruVQs)f&?LveTvJp^ae~?z3UUP4`E0jvP*cpl5ce~tARNPNwIS3$) zwDL!NO4CZG+ix-3_#k%FW^qs~g6bGR72ARGHKSiBnx-gzZJ0Y~bOUr*fJE93Q*-yi z=vMt^9fI9V`$a(22B?ixqIV>&(^5+%z<1XIC<@_h%gz1t>Sj-$W6VhrerGW1Ljut| zZcPPHgK$lye$cIhz(4rqKm3Lrh^$H2n(3 z3%Yd=KlQ*Tyr;3Y_v_>o8T%;JO3kOWk2#PN!z}4*B!N zx?r#0>mrL0szQ$6(;OKzJ*jBF5j|iNhwm^EeoqH~7cc~2lHM2#emkL*^b-2$R%GfW z;_fCIzMaS$UPz0A0^Kf( z?Jty-PE<;~w+twhJH1~w#k&`6AOFqy^g3`e*lNv0Xe&lCghqgB*(7>;@R zkl)*k>xm*3Ro0l8&g(@||5Vt|D{^uVV)AwSgk^rvf<9436j53tb$Ydbu7`hA($B<& zpHYOrs!#`y)1Q`xM&~6?1PBBa&C`_|2b8$~BA|aNlJhHbVL~zuT#*Q_O#h|$F(8xf zDX<+}lMb$ZnwUqXL8zCI|0=!I3Dqze{gauvNr|!6|5vK^%gEf{xwH@rAMw&SQ70F1 z*SGZ|*q>u=7ZTPAX!DPCqYdEu=)pvt=}et8qd>Z`=n;pF&s;2Nj(^5Vq9`ozBiCoT!z{lt9~vUC-hJ|T*lazJ_hye{C(D2?1#g=N@PXGcy3ZUtwssYJ4A zW`u!)Be=7}&;&sy4cuL9~J{`=_jZ zC<-p!3db|Hfj9_bW9O4Me1r>R3J_YG@Z4$e78GkEP}B)Grd9nX5?d;ay{ zp#waY`xOPB^98r=`%n|RmyQqb&6Mhv=vEFV7c0Kat?)cPyyQ`HoiVZMojbj^Q13in z>v~kpP?un|I#v0M_Fm3g->dWEqpPA~gZC%}6_){LSY>An?L+(MMuDB7*FS@Q3s3Uu zX}uBkI{DM|a37t2^qR@_*M;G`w>ouh$1S^`=4&0a%$HPQ$15$q59-HW+93WR%e()t z%JTm~@_OcEfA!?c%E_0dlP`-WdkcSdTCR3RueU${-fsTA-SlJqzmw(vUcKJ_Pu1(a zb@bNy(m#Fq=fA4g|1)3Svo?dhx>siZgD*e%hcA!$moKmXH(y@;KlSB*;qs-4w*RVL zFN}TqUvPQ*oqf-IxD8e_dKoQd|&F zT3A$&TY$atbMx|Yva{d4eVZAZm1Ccso0|Gp0sGnC3)u0oF;V}(<*4ZJ$baE-)8t%@ zm~82&h=0fBVF5mWwXc0&ym;>A>;C+OtA{tXdL7~Dj5XzX;^J6bZtv`Fg~jFnF3X?V z8JXEUG5S~XT3yFPP1{IC(?IF(vRqbK=da|ogsjFR#NU$FqEgDDlFASK|Aouh+@t>y zzLr!LeysTLk%FL@`~wkLJ|St|htfQPQrvI}F8;@ye2+MI#o2kp{zLLw$Kk(ZIr6`g zG$ z2}R%EvnWllXn#*5`pPTAZ~0Npi7NXezsDIncWN!ueT=kn%NszPdW|ceTCcu|_)=mj zj!y}FBNnNATvR$NpS^P=Y3!APruA%E9-BS^4sW7EbBLbM%6wa)8j|g&o5`|0PM+C7 zd<*5;45tD{B?<4o7(grI2kB~u5-K$5dO@Qjputq+bI=%$8!oh`Dz4YM924~M{<6Z(2P1R{;h7`UWEf{KiTN(Ylekne+@oNuIDI!W zqU5bSg}0?7oli=xtn8lnXdWJ4w07=$AhJltlntA_E(Nl)DT=eDyhd2uVh+&p#MuY= ze%;|foj`EB0eOnGfvu7}KLdfe{5P~HsDw@>6RXXOnu`(T1~cR3-O6vYL&%84zsjue zr_faptg0qeeJC!kGV37T;gz?QmA9y-BQM_kXmYoH0pY7@jP@pSQlnt|MqKX>$02-J zrO^LgB{>QxzUWp;D6RqxBHg?{3CrhY`cj0apnBX)x!8(LUaQfSD4wx!p31fH&$!9x zvQ#7q_y3`)YI`U%0<9#mGe(b)wvTT40R^0s9}xw4UdVEIGS;cdm$+Qc^76$&?-A&? zzfPq7P+Fr##pr!EgD`s0Q*Qb$)ATSNgdw??4p$?24DYAH9F|_L zyJ*B!)uedw9zeN3ETEAzg%__eJ58Zc4&O_V39pg&l#{7`pL}|K@f?h%mHMkP4(FWj&>Q;L-~bEas{Ktd5}isuQ<@#?4-GuWb%(qb!!(8 zuzBbR-_9!$)uAxWbE#AD(@>XCBN>J$L`2p{*jpa6bMAZr$P_ng{cl|Vlm5y~{lYN+ z>7jjDZ;G`K(Xfd(p!6xFWPql8;9Rn52dU=+&@Z%)&u?H3W~EU!9gZLTn;i6o6t7hR zciWGeoW%G~1Jn_R-2?wD7g3xK#vOn}DvTQB&`jmJg7E2p63R8QvQ5r#9`<-WWv0P` z(o5G^WBbspu^zhGuNoYpz1(+X-ipyk-kv6*!ax6@qqzU;12H?r42qRqwmr;GhyAp` z3Lc(DS?M$hV>`^l%JQVJv#&5zK^{bd;5b4Yi|Ck|HKDS3n)eI?CFna(ylm_8}T^V<4hgD%13I^MrJT z7gE*kP(75J$rx0Zry9Oid_OAKfLZ~`uVt{y%9CT76pE`EqpUS5J9NhQ1jm@)#?2w5 zdX$iX9qCaZVhL}86|r1JFB zH3Kg_zJ9?6^0F^_M9t7mW!^XZHDSe2J4P(}5Ra{oH$v^XJaO@!7Uiy1zjjnwXNDY= zx!wK#7RrT-k@YCY*jMnpWZ2UVOoM2zY;vi0lL!Z56j8*wZ0VjXyzQx;O z;%_DrVlEdXCI(^ZEhM^$nGKmsz)ezaVx{*6j#cd5q++s6Ol=;#X4@pmo^ne_)U%mh zMsbYEwFoI^Y&NwJ3zsw{FKjyjk5ZnQ8YnKK?)Sze#PmPP@|y$g#Fm*7&C4>=n?s|C zmN~-Ms7kJ)qo=s7{{1YJ5=pB^2!U3^aSQW?f`28imv2t|CR*37#;-bl-+T)pYm>pj z!NJ`?;NXBFsYJ+QG?ZC!!qQs+E*?qR;j*w#O#pt8M3Q(97TQc&)GoO-K1oXWX@qne z#3Pi{JEP#TDK~IOi)3Rwkclh3v)>T$%0DJo>QaPG32vel=oKgTqb{AV=*85}6OUV( zb}~gObMx3bW&%g?g@K@y?DiBkr>Fp9YChM)t_3jSNd;~{=7k{j0+G&T(Q>r zuOHf?8)7YdD4ygog6vy#zk@zb)aP<-&Y+$Y5Y4wiidRMv+Cnui{ER<$F=h@gt+XFWa4Wws5TI>-Dva5J>raBtd1tEu_Y@>dcm;}SFYf{FBVVd zO^ubv71NNbF1Fq&#(`RuuIKT;u3_1@cj*nuf70>E{UG(8BgH%GEXKXOzOV@Uv?8Jerh67jl%F3`(Yx2%{<5fLxv?Q<1+0 zoQY2K3SW7scWaYuz;VpPaq6E#^)?~Dl%;#Rp5Jc_(7uWR$|M$YkenGn&qGo`tPt(3 z$KLkJf|<|_w8Zj5kvvv1=5F@lYBK4rRC*|xp%YZ^%nM(JjAYv>nC7MWRZM6xw5nS2 zPXX9d9NO3iQMH9?N0V<)rGqB<3pw!4a3E^AvA-?JES&`CL7pU;-anL~Ea%ej*PJHX zkKg%2{l%5@#K}p%(?6jn$3F!foswZ-kgik6eHAFb6V&;K73^-Jmf<^Q3UG0~1AcO5 zyAyQ&TF4g@4edO5r%kO)uu0mj0yXo;@u?>0MuP`WvvfD_^+Vs?iiCcGN2x_+*Oih# z|Ctl;`N4`Yg>Ex+_^xu{Oe&rg;Z+yN^5EWRh={{h20m_P7M4qzZlitMnBEI47V?CAsVf4>E(y=|&`a&)u1}Ona_hj{m$oxQq}Fx3sN{ zs>6h1N?WH#sJ!Wn1?EN9>0|hbxGdkf3=j%#WvHwIF`!{&=Sh#Dz1;m?o~YMcEwWg! z4<2{|I%uf^CTC>o==?!KoJ=Gs<)!hqA;zy6XO;C67{I|MM4|UTguX3JaRzTWS1IC_ zT%8Jz-zDqgAU?_!KZaRJldG&F9O$1(;R`%t(5WPx6z#`(MK}qYXNMexh$La|Lg`xc zBN$5YLrbxdrdO&}Xy+Q*BbM<#-XfSAL7sZ?cL+ikBC+@ANIadI8p6P?ieKZ_wUMc6 z4_#I<*io%F5vZg}_5wXuVc;b3^pcsm2iz_9*}pJbRbXT1+4V8Bej5E7n=ctj*zpR-2N?yv&<>D?q?nP}8TINYPxe ztREcERvAlG31`SFhrVlKVi=Lf*CC#OL!&>Ki#~Kb=7ghTYYBDUkYQw60HHi#J8XRc zP!`!bFXJ|o)Y3fXvh;Ut;>p^O?hnd}Ttrro3nC>wsM+W`VX~DYF6xV2+-_D z-b1=!DD3VLWDLK2GDOb2x5MZ~^S9-?a}pZca&LMt%WLetbbie0-ereztbM03WjIkZgE zrt{EtfvO_<^z;dI{^*Iilm%jE6j$^H)!big(Nd|PGzg@0aG`WEqkN`L>H5{g_>bOM zc{%mt!9a4kWBm`Zgx~~ga`(6=vb;|swQDvuqr1Dnk!{^G80t=BMfb~OIB8^qH|-EY zv^0Hb2zqLW|3$s%F7xqYa6au8Ls*>T+K96o8_A#F%oP# z(wH^UQc=v;6yBOO{OZq0kHl!7+2}yv=up<^ZRE)C%INr?Q8d%ol*HJK+1Om**h1FW z(kS(41(ko>*c|ns$|Qs-43Z(^xWVLibdh!-;R|CU&cYi$mheS~&@Xo}Ylu(0@)ep) z8UmB|u(!z&l}~&d$RMrhA*l%@kaSx&BQG(di)%#7(vl6s2k19tXt^sWZrr-Mgl5si z#gXI*jnJ*ON!T7ST#cMvQq?YtvKvhK;D$ornBpO3l|tBcO1xY6Mwpy#HIkunPz>@S ziRn2x^NjpFnxy8lvF%Lh?3m0MWN!~m#2Tl5Y|J@E_1JvYs|2i9K5KG?e{nS1zB?mx zM!>^2XYwiDk=ggWZO-jx&VzYgpaF6xkCZ*q!87|sOzr&3?D(dcH5~~e@6K4<$*b)lHWN*|6Z-6H^C`mWl zUjPL|H>unSMYX>@V1a9RQO~&I$}f8f?7gzC!%QEtb0q<&B#89M*Vgt5U?#Py!hn3AU6UC zTca@`rTLM)OIE+@W3?f|zvrQ_=R3LUxMtv-K-~QCem9I|ZDXSDc*pPgmQsg7oaRRA3G+)g1Ed9UXXWZs zoPD{}ePzM@Ka?#-!TT9@hiNG@L-7NmbVmr*RR)=(kkkW;+5?-}gB;S89KOTh7YAjx zG)+BhxEa0UG~QCjdYlK;p1>ftV`ZhomG`s@795V%$Lkg+ zODkU~DR%d&p3HWfH0ggmc^?Q#IN{$sK0Bd7BnY0~QWyn(J39aRDE+W|*T+WT1Y5uc zCK{$OPR-F0Q5j`#t|7mXkk~4s{ST$m%7(%!QcF%O3+Q z;x%n7HBiNm6q@U8GOWY~?w5M0X9m;XT_ez1DaSl3%hFlAPp*E14*N}2S>cS0Dogi^x0mx9!pU+PzXeW$Wa}A?&L}On~l7tS4 z;Qsu6_oou^K@jEwdW5{WA6hYop^YSg60eSdnCf9vu5Hc()O^2rPrE=JpjGUOHc zCv(ix*RuseCJBW2h)Oz{Y2CR>txycuQ#E;$ZZxXdWrSCDLlH z{O_{dph5*@GxnbOrAFQ-%jK#v{RL82c%vJ=Vk}KES9cNUI}5MSDYMLDi=**Wk{|nK zf5~#=bKBw6FT`(}(yc#)MI$en=`>8bU!-ZwOJtjPf@c3N%Ugvpyp6=ddVlQ4a?6(p zvK5(??|*Qq`}9}x8Y|2D%Sejj@}5U$5jL7AeRG#@9dCa{c*o+8-}&y?-;&oiN3}<* zol$q5-Uj}npY-c4ExZlBy}7|8j*g7RV*;Uv>##P4Reg) z^Up+%h&svFX+G9dyDwmTGQ+J5oS+*@aKG(V3=74GEJUQ^ZYNQaN=-7HO$x9>itCR- zwW?DLIwA7!Uw!?lM2`nN&yNee7V}i26{3#SHOT3+>3d;&?`y7;g?Tbq|Ib-Tj`#l0 zl8=y|D6bK5ysie;2?~nRR@#e{;16vz4VXC1XXClu2A z#F~Caz4xx}Z@d$r{aS#I?^9uKh&Si!1lZ~ifS6_25CZfylGpCYpKReT zd!bFN`=Bt+cQK-hwAwhv&0KU(X%)XPV0 zS(0GcgCqLh1`j9KK2bh8T;P6+eLz)Fw#bqo90S~$0N9tcr|p>eu%c4ELR>iy!};H< zY)9DAJa%oM$5J)lNqUflX+6_WhF9(C-0KFN@4oJx*;y@8atlOvH^XY}`k{aPtn4>~ z|Kt%S)$9LhJ?A<|(MoyuOMIWn05oh%|9bM^OU?_6>)-GZLx<;xu+>)aFV7(N2WLVB z=^ZYDuYZ=L5f~9l`E9Dz2EfK4!wPYF51U_ZdaJHSrEHdzbOgjyqwmrMK!*Wl^zC=W znSG&}eF5Jm2+^0{HB05I?vdRmOmz%HpUCOxk@MNy;Q(W{RqZ;;ANRlkASlI&xoxPCh2$l zF$;v;F?X@D+(Z21%WN;rkai#QY9>Bj)b;IIg4`%NQb~TRU_n&Mw{RQAYepx#GfBfr zClGDe$Cj#T8T0awTnH`42JnnL&R!c9>tHrMjpojzRId)ZFAwV7uuobA*wBECY*=i( zaBuy=(tYAGjCrAOF5N=!pQqu}mrcqemTs>&QZ!)r;sBrSNmf12K~}nE70pP%>#Ag1 zZpd@E8o%w!C8#Wyz7xZ@;|ZH!RSj-Ca68gG|;5&?Qn z_r~w{Cnc;&wb)gtL$=-$&_~^E-0UZ~J-oAM`Q|ZTsYFwXJ7YU*l=Qh(lIai*jx5X$ z?m=H>PCAoMs{oSK@R|rsk)xE?TV(ywo%n@wntHU)QC0s@l4Z{ufqvUkIeig5?I%2R zKQ{JMRSE_Fwi|T+S&~G1^c{+p3*Il>%2G0qrZcCu?i^nuvAGVt96T5fFRYhgs0+{b zr&1}8@S&l4D3k;~TY;n8#cL0ng$gv3;3>=0_*qp@RbT4c!SBkB2N<*la1&V4A!*Iv zxHuO=fEO9%S$;ZEEqKZW7}^M1qyAdM+#jiOibZlv!w5nPsC>^2@jO&6k(M^gy8v%iO%??$fXrIDy4~5}v_6u2LxcdYQJ*pTTkay+`b! zI+QAFzUPG}57}PQ!hFv`Cj*f~fT->!*&EwD!snK;JcSlyJhsJ=3NF#~Jlo**rfi9t z0qbj_%~hJYlIKAfN^^E=vw@WKK|^saxtx2FqY^Pgw9U>2pO$84HogpNy^l?NNt7M| zRt(SRO|(Vs*up<$a-^`M9;r@4>zfzHX)6b0_III$!Vo^^8PGd=JjXg{0B>Z6mu&vZ zyadk@zN6#W`w7R~~l-EA{b+ay*997&s>eSj{%Sl%rQ>s5^pmoRAxI9?! zgO%h_Xe1tMZSjk$9D0Dl(UR=bAHt#B%r3;NR11A4i50H#F802H14RBlbwqvEP7{N` zkt&}?eetiM9;VBnva?UWk*?42QJ;5x$eJhH-F!YRufkq8d|H?Mb`v4naWUZAaoPUu zwC~+Irucme2DjtR4^lH>JTB#WNQXzpXNGxjlwS)K%X19VyRFyFKl*7o9ODc6m&v~Q z4JnZ3-T@U%vMc?p)3gBlb3`cJBV--Ib+JEIN#uts<#ZlreXw-oq?1s3)Bl{5<|Wq> ze=qENd6ZjoG;QI5<=$utLMBNq{@#k3sLB8tn^%SJs>-=f9nZqS<%WOje))LaBTLyI z!_R}}^0f!3D#v|V*0Z>+ANj6IZuwaAWXsFWzf`)`{CXz~%#NU`m3d2j%@8U%uN4xw z!%6ltUOSU@&pL3Aapn+t@eGEUYKuC#an&BpgdJrBC~c@WTH1bf8Q=8Vzvt=WO=3d_ zq#rnz^u&0^UeG&tV(M}x!uAg)gI7D9h`#YqIBnrr{2-hIw-$|RrpH!6W{&` zAA0o5=&JtU=MVpr?}NYS0&UXvYY8%K4TVO!E4P938qZ@t#;QrOes2Ruw|B93y?WLehLFM; zg@%(fYmWdkJOG{S-86xTA4Y&^uWowp#F>I_MzaD(PpL-6Mv}f}$=+_*lf<T1hT89C^>9~^QP%hHK1txdM(|zq%q#aipz0Oi=%x7CAt>J~ zWSfdT8C5;+N?A zypKp}Z8Sqfn1KMQ1-%Lv4+f41!jkSJ)XHxm5E^oA!$a~KJAImQ@me!NBL#5}IZ$4f z3VNe$f8KySdHOA{<&0+9)EPm0&xlr4K~D+#xUQS8WKhecQtf&jVW*NchzNVzQhVLdle$8yHjjGhgT1Tb}5E|8p3b@zUcNEXkQvw z;&Di10BitR9qHFZ*sSf?ocGv#MPpC+*n^a@#hIR^dJUewv6b+i)g28CZ5(;n>DYQ( z_a?{qw*2_clkr_!O^wNnRyj~*M*e*p)P~DAng_TqfqKORaz_jv#YrC%Ogx~{3geCl zD6Bh6X+LK|rT4If!p3q$b`xa z2iBd9V`5Va1JQ%0;{Hu45vLPovDzP-w6l~M9v^6vxyC`_!4i%|b=TUIc5#%#B-G3# zG_%_H5tDSOlk`QC3=NZv{gX_ylgzu5ESHma08=o|K5Yp~8kg4wFyh-MP&P?a|8le? zsJ0G1Mc_)3m7!aT(7lIk{BcI}>QBLS`t8df5fM#?4=KLp*24^oP4Cf7M;J{fIO+*} z9;(Wk-sc9<_jN`hv}zU*5;rlDkXR{U5=3S4x4_|99@N)o(duvN>bg37!Lf?Mu}axb z&RWUcZPnBPv9<)V*ZVV9*E4DW4UHRO-JtrPV){RoXJuza)Ka1H{dCHF(ck*&zbHR3 zrj9k?BQlJyGZiMXPym^8Cci9Hv*rWIa1zN8ZT9p~!&<|qV|?cc-@3n


    rW%i5^Ci<{qJ*38OqD=gB36%T5iv_>vz54aco?re#d?w8sQ6lLST( z2T_v*Q%{9ZFNAU~gb6Po6&Awv7b5HyB3~>-xuV*QR7Rst_0VSe55Q5I8Iz(n(q7?4 zA=5?#sY>D31ny1IcdC(M!u_(9cFndoHus7)g+)Ml{BYnElcy928!7(U!w8%S(lNQ7w(kO(>I81=IoK8$ibJ7~VjW zxx#U^U!B~afqu-W+IG$C)OLy9$Uol8<2xn~Y?oUAW5Ku)9zo*VGp1-NRd?uOco(o_ z2-r)~)77qta*>HH0u|1V#?H$644dr4nJ^OlGo5?k{n}`}Snj!6to(ZL zAL^<9N8|QS-S&U1rw+_7&y6lEp3l~=&;6Hf8@!k-{67AEW3uDl8mg`5!x?7-NnZ!v z9d;(1v;`e}3O=g$I{xH=4XA#tcizV~RI6PMJ~|#$+8tC_9+a6Md@%V(K(*9tH~-02 zI$}Nk!D8fGAQ_O0ae4~ zTy@kt$;b$i;J8J9qD5cAMPFc8fH&5-`S|@m%-v^Dla0FQeF!8ZlyHZRfQBkX5D*X$ zFd)5$-aCjiL5hf=bV3hBI!JHQi-HIOB2AFcdlQgeMX8#XXFY4Lz4toj-RFEfGx?mk zXEKwST=`x9>-lqU_y20#{9N4~o!tv$q_2#d{Xf#FruNSNOs87fU!_y^jQ<_DDQg&9 zbyNShx=mbK>9#NSs+)@RGh_3J{FiPMy|4C9-6kO~boaqOfE((+12>7kfg2m|T{fP( ztlVNqZqXYzMXzhvUg@^$oOf6_??CYcqyH0dJGKKDd18?dq6U0>mUk!f+6 zh1IWrF^~x%Wl{Y*omwST^cQeb;*`x+Z7d&ua|PU39N!>Yy*l6mvl)88biLzfx%m}v z(=H<}pcOIDE-}q)*t-I5@2V}cp77Ic&A2TIw~*dMc!goJ6|yZ8&d9T>=sM*#Yht~! zs%qA{h{+;i)85szSKZ>Y)Kl7bmMo@X61p?5t;6>aWKJd}QkyJSyfo766E?lt-up6% z&(baV?WbBY(aGelXIy3>3GlakGTH_ML)_>a_+vK&V^7dC5(_O75!N-YR|}8)y#-rT z*GU8J6@LBj5s$yUT#{(MPQme7=X~uu;0uRwQ)>|)h9lfqW5W?aL_wW^4a`Ga+nvT3 ziVnUyy}K02T?|da0BCXGUOCTkP5|hcqmiVLuvdf|thp2?IP{s5J(^S{wE(rvqGzQ< z4W_1u2NWLI$&--wU?b&(^~@EO1XgY3&4oGEWbX+d7ezT1Z@!K#SGHs0j>=ZlRsm`B zamc=MY{FuI>s>60-|Q!VNaJE6b6Fz+`Sk|@PRDV^AldSSSjaF5wF{`WzEp&ilSey~ zC@2b-Pb*|_Q#O|FxFn$(sOd-ndw+o318eTn+5r8g$V4CYCf!y9-ReZ z=Y_niOAe0ITyLKYYk2z@WZXGrqwD=C&}L8W4=bBBBs%5TJSY~ z+2rD+>vH|7Ui~Tj36r>bn5+a)vP(6#+ip@-s3}Ka=;bK6Q*OG~MKfyWB$r3?9*7n2 z@aNMR5Iz?Cu*sp~h}KuMd#FHhgT_Jb&$*YIYAnR$a8R6meD{+Ltg!}l`-b2f2_uX={k<8Q?o)#6J;r+KL+H^-juqc{hd(QT7K(j)1_Wg6%& zz#-qr5SX9msg8wd<;jAiB3=ob!#NJy}aL z6lqZ7^7|$bN1~z$jBOFRB}~JfeaL$tmdMszMLej6F4wdjQyw*DsSuJaZIO49jJh-S z{Cn5-ykJ68Jjb+f%02S;3Vk>2?nr+n{`BL4Ml{*CA4F$OUZXmRm)~TEDZ6}e40-!c zI*|!+t?G42mY0{up4G3G+0ky)^Q4hvGpM~$xLnsm&exbdHnTe{a>%=YYKL1OTWz}B zvEfJ3y+IE-J`4y(RTp(Y!hyYK)$*b-JKgI5IT4jAx3PRbLeGZn%xPgnj;$tG9VO+G7jY}8^y_3CC6}rf z@f!B^8(aamnwX+nSLsxfnWL1Zfg*vYeP1ljk5b#oiv=T825heVNb6NE7EbLOaFG0w zj*BT4DNz}8GWn4)HBc<}u5ZxI??>hmd5L(B%GW0uKe9H|OC%@zu6{25$UcZEky=+7 z@|*dQb2?BWbJB+&dU5{a_0=CbC=yj%@U`Pys79$AeLpT-@;DEOEtS8iIvizkoWFb= zsyI|XtZ8#xfTSo>e%zP+6uI&g+`NEl50PVKJXQY zd(37)P~<(YVLRM=pkOm{3PBOi+sH*#F)Qo%Qz6vKHXPQWqxX7-p28zE-fTQ-GW;F3 zl2qRN{7iYIb1Nl2H@Q+3!Jc-#P9l7XvPv5EH8psd!Nu$$Rr29j5*J%+HL|$oS3Nx@ z7cbpvvQe@51TYb#ehrX~-r(+<`t5f9^FL+B#}-~!v$ z-LmeUq!;+6FJiBYlvxmois8hnMG%j$hn}-Z;#BfQ!@a}qd`X#(E;!cS_i+x9dn#&T2^whbKV zVurVoRZV%26(*X)N8vPxH&B26Z+ajyyB3l%%`Y~`5~9U|R`6f2P_1zjW;Cs&jijm=LCV$*vpk z5YVo;Kev5<9vY;Pqa5OjVD9Nsk=yj$Q)pk#tH$&ij1ZXdoYJp_WAAcJrFo=J4ty7D zIl~XS$JJ-8tFKGWo_+QGTAy<=ur70PHWUbN$R*L(ko(j~7A`}Y-&nU%B6iOCeCmOA z4i>J;lsJ;o=2a9xwOOGoIV##AqA4Fhtuxy-mbW0HA(_2l&~iRr6W3VrP-EL<_I#r0 zYh%^Z!EK9+^T`3iz?z8cIBq)-Z8}DdAdqE4mOL2w8U^On35s@F|2EUo`&Rs|2G+y( zVwQON*W3DlU1!64v}ITy*{t0}Ysw2qvv|aZwd`mn!IqpcD#65zBbd{^9J2wUN8m{i znI8G-G#w(ah0vYIW8h->Tg^%9ngk4Zz)9Q8-D62?vFAlbyiC#;)EU7NXa-$f{(%>3 zmdhGEN@=-V8+swZA1QeF3gyf7x>sDjpB3&|azPETmQW3~03PXH%zVR%D}EK)dqOEi zKLa_{6It*IUIEQ-aY0*HcppWS6Y188drH2CC(5p7u@c|)l|;Ru#cDBa>8~_5qY01G z12Zy2O3u{p5yE1itSn{97;(}zW)#EfZi}|0!uLVXpof`rYjOU~Z#2&ObuEt4UVdl- z=liDiW*>kEyB5duPclv-cIXoPWS^igAn;mV2b&X6awkpd&~8!ZIMCgckrkK7X)a z#vY=5hUyyjYc+no%KNePG_{pEwBXwbrS)&!M9V*AUSE265?+9V$kI?!>?dyUr_T{R zyeB1oP$6IEr!<%EsFsGUL zEW_uY>)pxeA5$7Wrty49iiYEqXsAo6$nzb<6Iiy|#Q<%nqGRYG0n1B(JSz~Ifu-02 zh**Pyc^T|i1c5bzkYo0c&ps}FiZ8`~xZJ}4Wr6m0heLRVO@)Vr3!hl?h!gN)pm;#V z-6%}`fHI>7AZaI{lnv7;ei4|eU0Op%<){z(M027IJPjnTIJ^eNcaU4=k<2OiDj9!B|C1XM&(ggq1gL7;W=0if>GK&U$X>vs#Im*AQ zJX3bIn1_Fqfo`x>UXo7I9V-%RHkb+`{}VO~L%xG|C&+?Es3M`sD2k=r1PCj|q&84o zL-A7(@WaBH2|;}NiNq6r*^}|)9f+LIOx;l4jyqUzhqck2BuZ8Z!iHG)G{R#mGH+;< zw-Mo%JK4s@Uy7}M2^xHWaL6M)&5d?_lF%#~9y;}qr!RT;mHv0#w4R@dzDLPXkJ4C& z1s^y7-o3D^bn2tB6kY}j+(8O4nj)eT;V_)6)t8F>nY!to_?#{cOr=YASJu2a4Vr#` z{0ZQGN{TE%Cy?UMD!4@jXmF=2T!MB1Jd_Uc zIOD9>MZRFDV?QI`NsWl@G6U%F&4=8=L(-V;tdsdVSg5;`! zK(R8wC`f)lK-qz1!Gb`a1u6Hm$(k7~dtqt6BiITV9fQv7c5wdus))<9EEPfnR&Q7z zmON#t0Mt>?CrC=nT9~?YqZn4uAV%7U1#h+&q+sEF?l5^Q_^L>1jC;D-UO13YsH*Dx z0tKWj6;j9+i*C^f@dC`@Yz2hYB3HW~?SBz82?uqV^8zrU*mS0#4+}T(E7nLTJ_zF4 z(uV1d&~Qv{qv-$Y`lGOw8p8#7@ZF-$h*b>=BI zbQNln7U`%K8Tb_rWxx%#O5T*yQ2SDj04m_R;%Bnl2Wj?@4)_-U=AK77O-M7uCNa}r z3Hiq41Vwb10HZ~KhbmCxewUbt-gcR3zEL$bmt2OlP-~_@o)?hEl7qHMO8qL8gUX16 z-iRLQ&wa>I?mJ0BLA6b0x_5mP9RpBcc3Byd)q4k8qE=~9Kw z7L1(No7C1-nFvbXX%sgFNL7JwTd_Bf04rnQ$9slP{gy0&Vln+KT z=XB^H`G67`wey7qWVntLQLgi)RMkuMet+Rrp|qMZBb|S*xQP^yJj@Zx zzZdRg*pdK$_56CBw?R3!fdbJ)j9{K7CA7q;(XeC! z(&9$r&zRF|U$I_$>mf_IUmAkOp6O^skdSq-a7mwyv?n<TZ7Y)+OliH)SbRDWwR1CG$Xl-y;s1=w*0 zIA{AkzlT%Fer(99%g*|OPC$gDHuKPc|pMOXV}Da%o7CueO=>yJDH=Zoa9mHNQi1lWwT# zEqTAoP&FL|LFo{E<5w|s$sZSIGHO_?JB~ye_tvMMbRGxa)%tmft5D2iVf!}|nQ}>B+!hfYxrBy@%MkQNEf9X+KCMcc_jIwjm z-%7hBXKu5pWBBg*n6KzRG(Ls*roqDfYJ>>>&K30 z&X1#0#`Gg67C7mhh0UTWP?}9b$uo zST2DL4?q*H#1p?khD%@!Kjb0)075hjxhjT&SRsb(yjA9N@f_f~);X8J*-e6Ziv!SA zE;M6z9<&T;%bu}b0&VST8MRM8YKMS^AvQ~3ek9fH1F(JItefD%rXb|__u`2cVMXhl zD;Dl%wZK0Nve1TrtFE3KvaYfGLuC3YBihsovBWM3A!dp9AZ%Z!x&CMxq98nRv-aBG z#FoJibC;cfWdVzo4KI*Q&0JFeL~4QBq6V^wgUDWobZM-vdM!M{E;|WMD;$D}ze3mr zzlH2q#T zVV$)Qn03sX%*o-(71(mkU9+?P?ivWOY5)GlO}(;eF;bJx;sD|n2>v?hx4dK_W)@*K8=i=g20l{zO&s()WcM4%b)P8V>I{ca}Si62FF% zRWmcLsowu{YLz7 zB-sAcuy=2Fao=_4x6rhv+x9}6s`~zsBk1S;!p}Fv-(7JKDg2G~-BktjzTInPTVQoQ zhYcAAvBm!?wVQoJiFA%XDL)2lEb?l{|9pX03E5o@eaYtEwi9++)i4m^W_3_80&2~M z-@=_1(41_#pFColeI$5tXZcrJHGRq;gjh!4xD}#wgIa#+khGGt=EgskFTAO)l{X5)SoG-E9lg0fK{DE-rd2oFJ0i!C2Bq`>hb&3leej- zZ&1(Thp60gR6~9*JdfvE-`y|RSFyT&Mq_)vX*Df)_yhM70F`l}??q7U>AP5rt0Li&~Di94RXMV)PeqBU@Ba z>OZm*b{=V*ia|uH_vC53R?I$M7ak9mewWf@q=7e@YNWqz!(GPdmK{4%`@EE?@bQwA zsdY5>+{)pbM&+Pj_`KK*+2#}~dqME~HR0*j2oP!8dZF?CzI$Fjaij8`_h)sB-dV7D z>|fnRFgJOX;Yn=B7~&jq^>57a!62((D;Cpf29h!`V@2~i7^?i+CFbxIH?%i@AlQHl>a z=%!+Lu*gP_7u?K|Dmd7hua`Aa(xc~U{TBVj>nm>f3odIXav;>gIGV+QtIQ7Ry%2K5 zDl&Swsv2w{qMWEb6ZxZ3;$r53dQ72Uff_%)Pnexpmfx?lif;6o2Z~D83o(>UcT2fB zz z_6@uPg?Y2dQOu($#0GjX4;Y!&czdl$XJ~Ia*RpKTE@SgJb8UttT;-R4H@g)^nvU&K0HnjJc1+McoxLV4jG!NOu2 z21b#M#y1sSjZlgFiE@|`SY|t`=di@HFZ;6cjv}fbRho9X_v|{(NV+ttnsryk`)EFV z<+U*^ezko-W#ZC&&%{J=nmnZ!e2YA-0UTC4iDV=O6gUTeR~7h0#2z3Wmm<*5Owdp8ou7Qx9TGx z8Noc$1FjOCB#>rws3dMVg!NcqPfuL_G%N-~k^r0_$AU{}muc zzT4d(cAw$Ex{dtHTOt|hh3o_+r#&*KtO`6Mol%=hVe|w@u*E5xkVRL)f&Vz%woH)R zGt%ni!4oj?)VCWaM(j*OLQ!6&)%2ZE0)mlRLY@Qucq;30PK{T6L3VFkowwP-ZiTYa zAy;nvYGP&j(xKcv&dQ8;4C4@$NI;>ZZ^qWGX}WJFng1$GeW$J@@VJg73=wKqZ`OBt z%+4gDymI5GauLlJ>&PGGcpLhSt5&HzTJBuDP`94AWU;GV5+BM5Ur>&a!U+L9aUmHo zEuj*{P4NN#Ndc6k4`nLvwu{Zx%BX+n(w?)%dSX_xUtn%BoejtPF(BgQM<2>Ja*31p zt&^of>F>kyqeK44<+#WzN&o4HQG3y^L#6O&uqF`lO=F$vOgTc4VuXD0Y?*#ID_{Cg zEjhSQg!S`r*~`#KozjiZV%(=;_ig;*(h~*9UjX53o@s-oNMtFLbzHxZH1B?}y(I7H zXOx`@*5Si2{4V*m-S`l_(X~6Hx$TtI{yma+-l!JS5wq-{D&0*+s?CW_HkTg8 zknx0ol-oarL(*ODMVkW83RkWP`nvgkHcjWt&7*J=-16d=jo+r@Xc5oakwspR!(t}e zPG|?jM>}Twa;<1CHhPRA$SgxQycuBakArD1Q!eCFg?YK-uThVD4Jj36sdm3=Abwb` zOg{OrNkLAkhm3hZn$}3Wr*vPr!wmjz>az}G3DZQbdV6kr_ebAicM{>aaL2LhZv#BA zVLQ~q9N`~d)Z%Mn_1$AGH=BAkF+JEKskI#C-a9b?YKcj6AjeCh>l@rk4x29lsz9e&3`^x8Op4rLmQBSQ2bfuMMTde1z(xI(zMv}=;pvIn^A z)3=<=Ejov0a7Ee=)Ds~h0)kwsM<4POf9AoQ-nDSh0}oipg(F7Ym?*S)h+>DnMc7hu zP{X*NHsdusRAc)eAodi+mCUqdLV9K8P6J*&{7PWcxWh(D*mGL-rz7q@$J`42A&7KDcJY1_{tru-a4> z8+cVkaIi49Nd^n)CF_i~AUh-O_(jg7CqT=-+KIfS6)|G{$E)tfD(MqJ(YGC9Yn>F? z-xQuL%5_=n)lJTWou(vYOD*It@~*(7z5!~0%=^GMa|d(-A9$TOxwxRH$Ka_&g@ zZJL0a64ViML^-FGk*zY(kNstLYQiJdC2u|ACSz(l_$3l=Ll02_KM)%_D;~`LTxtAZ zc?Fq`4UouE`CNj-hKy!29aA}mr=yXUj(;u?g?PU?AwqLANF5t zLsLN-BQ=R$70YB@>%FvHK!j=NJ(fMowu$@~Sji98c0Z52D8r}OLSn$K?XvTY4=)JTMA#5;2ned)+3&6%g zKtnEw43SW7Nw6h4elB@yBTfXB=H(l52MGBQf(mmC;yVQi`BL0v0C%>aC|uHEW*7-& zA_-h;h+~Hr0h&K>GLVvj&rjU_4onG#Qw>RRzb|G~Pn7dX)%mcEwQJ>gRpYXR& zJA?_SgWW^KjEEL_pr^BPMm(|3Y7vb|L=-&Gq0P1s0=C)V&ibZ6dZ2-;ORTcxL6~?D zAHmhvD3NGy!Vh7Ll4ppxU5Kc5NHdDaB=94-i@Z@^%icy@5bje*ZxBd1=r)E(;T9B6 z9m0pod9%?;8>$do8X|tsj5dSbHfjmNc8Ms5+-FmiWQGb65TUs{gOp_~nbY*tNu-k% zuijyktV!IrAROCi;TdCc9LWbI5={#+8@nf|9YPe^jS(k=H3y3l6NwxL^I<{s;)E2> zT7wk722+Fn%A%jZ)d<1p5^)7-*9;p)|o~s;H6LLKxL;`!&FC`Mw?$yldVvY>S z$WoCk4T{B=DLhyu)ZKiDSGZ~tK`-|G6Kocf>+6%INbj7t9T_s|O89U4@S15oMSW36+w$ zOR41;^#}KY*F4`t&N8!Cz!PsUzn@>n*Q-TC3F)xG^j95N6s^b=A12n&I}3j1PsoFc z>dcDz#DRHutA(mBF^r&G!J4oqR6UxTV4IzYo|~YOvD`;j1OKq0S*DIEqL~2OdV5|9lsIS(m>mORg}7A^e8C1K4e2zvz9TmaIS}crywi=v_IEz zP>~)dh57FF-nBN>?JUK8IHRGSsNQZUU zd7H(2+a2c|OM0TGBQO2st7?Q@<4`XmAHg|UOrXa&uVq`t(AzQMYaew)thXl56nIwH zd{}aG+%UIB&y^ny1_{@)>IL31dM$21ss9yk;LbgkFe(}_m9nHC%s^t?sO=365Btd^ zJvSQD3S%wOhl0Tb9*~B^Ofn=2E;5~*HuA!I_?<*q4J#@*YdR%u#MOQzXE?)v6Qi?h z9IveHr7&7hk13XdKF^4mK7L~;Z4$?=73n>E4>wb}W>Pr_bsvng3S(!en2F&YvgMx* zn$rA~J5i%Q-(H9aFhs9Mj&3Gz%`l6kbU5wTQn6K4fTk;L=Q{s_f<3yp59 z4`KJ6jXNFc)EKkVAStbcb_GB;)uS6j4C$%O4zqNc?R6V@Ff_uEt*>HKG$L*V%tZk@ z!$rD|(vgin$&#{0Cq82uX!K1T4e@@M%xLV8retjN=lN(ZP3zyLQ{6bpljy(l{M)AQvWCbYW&K~rZvN>G?dlD zgx^E|mp3M$%S87TNBl)-+`*>$qSn5K3OTxW0TS83wXbj`5Iu-e!F zq=}K8QkvqNKr$i*#^ZtCrsRs4#fF6#+LW6r5lyDUqxGuKHqevnB`CCx? zGJh4hbb~pSfyTXKn=zv?{Pl3HeSX_7xCi6*Har%#-BZSl;a0+ND}#Z?!5ezN22rAI zwtc-TcFESKJKye$k%O2Gj`Y7Vh^~%7TjjYd@42nwmd1GEmQ}=Ja9_r^^~d?T?b>mx zBokq}xG=5WcDX;RA04GEw0qwDCVmpQX6SSOlZO2#ZOe~N_P;6?^L_1&xFWQ$t0pNi zrr`xBj z`|Jk5wGo4C*U?*lq|QbD#r%=vG)y{lwfc{przXh&1^q}XtX^@u z$$?Z_#H9J{b}H^cPV07ScVwc%_Ol#J*mvhBtnSNmr}h+R$Mqddjrp#(Lr9#oy+K=< z!A3BFOIY_th=oh!K}q=dqbGsV4dC4%Uwc3OoxyPE$BFgfICQglf0+PgRB<=dsO2V| zLyU}i7Z(&CQnllS+x5ckPK!aAYFz^+zys&56XC9l27^m>FC! z-&j0^&>gYh57-uMR(p+u39Q0#VjTEY&WNMWDM#w*M@<$_bfAyIt+rTVxA^Wxah|LX z7(wy5kRRf7KSB;3g=`!#{XV)w5_N0wiTM3Z-kZ=bMV{($i=j21oEE%ZmQG$)ex6u{sz?lH`{ae%w4I(=CztyE2{4 z4XD&Q)c!uqb|^M6@K+Y<*AhXblM;*FA143AtiXAMYY)u*Da>sV_GAe5xCiD%@1vV% zo}A{H<#>|hdyd*a^-TjS!;_98H^R0=a?ZuL0kgrQwhNE34k_&ib2GZ~b4h>a|jf)dKx*X>yBk|76vFr$eWQTK|;}of&BO zm#H2a>APapLjzs^s)r6<)kAy#Q4jrxuWs%B^r@qztNndv+uM(=|Mb;e@8A5JuWqf% z>&I9Yf9gtn`?k8Wyz)(HL}l%p@{;n>qO#)LyrS1nOG^K#tgiy1x!M0B*8bVWe-Z0f ze-Y~hZ0r@Wj*5=?m#@ZPu81|}zh*>@67n=6Gww%({@09X;6E~=SH#-K+vh)swa?!r z(TInSu1cc0;^KdmL?5}?J#?}9Z_3*CU&>lr&+PAv=zmq#_vJPJqamvN9}Q6~($D+~ zTC=&w{HL;(QT?CQ6HPr?f~g<(zxbW@lRqcRwfdB zJCRm?n(k)h`+qb<>2H?2+iFLXca6`Z9PV+x7Zz7DzZYGY1*<3#FfPVS(EZ}zHexM# z1Zo+7GWG1+Xm=d=ZN1p}vaNS2>qy-%6PC%8C%2;tl&16Vd;&P%{NP3WY#)SuE_-ux zN`E@3lgD&Vt@XWkK_iQ>X-2k{LsTta6rOWxuX%8S=W&T$x5v_aWFS-c<5S*mH)7_; zB_3!BeQe*K1amJ1vJyT--=!EX(tJ)%Xq3RkgXjVL;EayC+U(}YELDK3Yf*(*XiD3L zJi!tBgk=7NDvZoqc_~`38#5YS-ltF?dl-}k7|lwEM1;cTebMotHOz{>GgP@5@9)kx27dsBgUBJ7^bf%%_$mq}Ov$u;ywwK+##e;;1H$*ubTNd7Sl{Zr7R~ z_8@QSJIj779}|?LKZq96{2pb;uQ7a$*14FtQXQ8e=qH8#!g{jfDZg_4SU3Vf+=wFU?;lfkH$|K@t9XlUw?gdAaS>9K zdQT>A4L&@Gy1vj=E_bsY?~14=p3WSdv8Q(v*QK#osvZoax2u=W436ScdH!zJZKY8o zhpIk{hQsH9>_q@}mj6-4$Q$%0ueYeDH)xts<&G~-cWf^%lFSA-)P{ZH)o4!SLPyw* z`#hD7bNa#h8t157^kwiKwfE@C(V)y&%OqRh&lYv72MyA@OCkQhQPpY+tqLDa2a`tJ#09X5|qUWx6`X8jDy+cxA$3v29coSMNe-gYN>2^ zMl7?E^(ZUm#Z<>Qsux_F?ClnNe;Df?vx2VS?vb21jPo5RxPH?6H?bx!L_TncJ*GIq zV$=)&Ce}v@*qHxDtnc>qY5qS$tbeE6glt6)0DA85%|2qHzlk*_i{_4`H^2s_kbcPV zwNG!1@uu8yfnPG2xrHn#*oU1vSJqLsEu<_+@eA#dj)InBR}5wF*iBvkNUIqkidPE_ z+{82(t!O=feJzGmn-kZR;a46R(`5bkDHw3lKz z+K4x7m~%HE6D3(%x(Vm_cxm5Xk(;qZa%PC!RM1rxm?{j_OMOcb*Q@Q!wm{A&PmP2K z<@85mzqCiQcT4y3ao1}*n01%zo+exC?pOzh>T@EhYUPQQzDe>Zg;5H<5$AnpC`eiu zAQ?^?oHVe?b?>ZCJFYIdM176d^sL|LYhB8_fi;2WXJ4$~^;aF)@4}hJIR@gMIwStH zVt2>!gSX2b(1msqdyk#Pdbi!l*}Y7reiLserftz{xWxc`53gcae;%e4zzAz$x4ysYp~UaHx5(o@tV#@R zGcJYsenT)ehst#)kbSz@b~^wSy0uL~YPQ-r$0#HrDQ>YlGubxPG}OB7`uL)LC3AYq z>Ow6lj!ch(1rcEMg_0ciqruC9_2s)>t|M2hnF|OIRHm(}uXe5&HACJBl*EIPOUFUI zZI^dg#laN|0Tz#0rlx;Mwta3Rdua;-=sKisr+<9*?3X!bAn+6{1kWXaHXDdRp1MDH z=T33rZd4o4^4ac-$Ra{SH_OBxCTUxsQCX zhy?b3QZuCiM1lk%NQxsQxF_1&f ziFT`s6?g)U;sQsJRTK3C%tVyOJxfUCbsT$_Gdc~Ga1;vLR7TX};J>Hhq1N$n1)LyO z`c8&$*0XphIPn!NqTPz}07V*g6+Od2snDFk_|Yh`pae?V5KwKTQE?pjkS4W5zd{$F z(?+wU14$v*?<$ItC6MptCT*dTigKgIQ4|y%i9O1|gHK81-UPq6fbY2prd-MG`M};O zk0KYKmag!6128Lt>+v8!)A#7KDShO~@FMAxbIKdP|m_ndHnAt?O%8+~| zw_nvW>UWVpmf(K9kxYe1Wj(X-lmN2t@MPgqiH1qtIk`^nTqm#Nu$Bpeg?cU2D*(Hw~#SI5eS0jI0!n5n3d?vigf(y`YMkxdn6#y2VkbP0t4f0H|=Yu zMMK%>o*dp9n1pBR#+$=Zi3#Z<@wFy2hnY}94D67`<_Yc^o=BlumqJg@KY>B0>D9> zkSyDfbYm@P1(#OCqjJ%wRmtN(C`nUzz>v+u&RMS2e2`(Ck}n~P6>w5X$tCaChTY=@ zB+AKCP{93bg@kO;+^YGnk_+^6;SwgWErLQ>Z7_-#&__XK%E|d>=ui?4B9h9tC6x_$ z`Cru(4waJIWdvPKkmq&6eD#3_9Q+tbK@*0s%uv49UqGBkZhcP`>SnPle1K-7)@`AD5kN~hOT7r(DO$T_vCoV!&$2R;loHO3~c`RrK@P4Cs++Rq9ZhjU`BcW4A z9F+3-GY98eW>65%-VE?qq0|zsXR(Z|2;>{VWy-7rGWuk@OD1oUq!L6H(0N*B zvlDA+ph&Y1*@x$>A709Tup4WUF#!gm>9cK<)9C`Tx9y|L;k{Nc-~Q5QA8M^>`)>Tt ztHd(+PN{v0ds~WN*+z65VI7zAXJCv>=X{dt@Se)rw$h|p_2fn2{B!C?_XZeiTX&0` zg0oWVb|H&%^TgptvOHrj`XeCvQEd5bpdEqKNvk)pAM6&ATu+L~O!3*f7EoRX@nMTU z`aV7KT9(g8qww|@e$8XUnfqwoKC7A=>WckjN})jGc+mU%KA*0qd_qZe$(wa4`gbX3 zb*X;nTI}ppzw9DezUoAL)-(GIVf}27_1WaZXS2D_7MGu`c4~{5x>cEp8BzZv)-H2@ z`D%COo=p+ZlgkbUv!1f>&#KGqzH?U3>1pS+bGK)DCOErV0%G%;>B|>{-#5_9I3Cm-)FEm5k4SrvwZr`84*z1iTHv?*% z0pL=b>O()=<8IbHR^vNgz^v^}b9Mza?W-Iz}Dz7Z*)0f7)a)eC)#) z2Ai+&e~p*SUz_FzR|m9&a%o3u8rOHUW~h zaTvlvzMjtw{h8DJc{v1<#-$v8C3bZP_s5a8;=1i{;E9uDhW8YK})##2zT~Kn%4;L6|t^V=4hqkl4Wef3(BsZjYNc*yp9=_njeiR z6k;rt>z&i?-x;kbfDZ|Yw7ZP)v2@z5^lb@_k?W5kDaO=y?bV-;Ba22s*33yic#JE@ zk)OFmcJC&8jM`+Y+{&JCnV)cT9U8uzfE9ZR@lQUHC)Ps(mPo)X7j9WIxrLqd3DD(1 z5z`Y+h5XhE&z?F^0ApGKy>?JyB|LEu6g&^44o>Y5SKLA&c(K!<(cz3r#as=5SCA?@ z0I;l?DrnU#(x55{0IKI_rjKW8S*XjhYZ|gOAnh|mLbG=d!F)Bd^Tcyq^V$%CneKqO zWS`jq4UOhXnlHcSI`rC=mgij2lVdEx!z{G9c-Q$^3bpvyc^%mWrv&f}%feQ}#Fnf0 zs5xzXC2juvg3Rc=BVzGbL+zI|U25#&8HL(~D_uIp0)9}%n{nx39vG~twjWE^MxiE_ zF+p)%X{UARxGPW7b@~139QZ(0JA3MTHhuH&B~|otJ(0W)i?&{X$|rt+8m@zC7`rAz z%kowAh98Q0C|Rs(zQ9SpV9|h6bNyKr z{Lc1&z>UB&zlo6+^}K_Y8o9`Q4x;e|E_Fb;SZ2qtgFDGzx$rC3mxYPz70OR7wmuR+_CIu!&p||e zpwchcy)8Q+f+ib!p;d38I&5mdSGy-6tG+=4%lI?s?wf?ZY+^!~`t-z@O#| z@$wfA*&_w(qZe{5PGN_XL1@9eqv!Z#o{bn)y_KLqfTBWA^atX z-Zf-hu^*dsp&`a@m6&U*KyFiWS9FTx9cZ(@XCWB8;{qLi6h6|AH+y%^p$Tkpe`Ssdb@8Hx$6`OJr>a z5Rfd?V~NZ`P-T&vS|;n7c*l@K;ts^x?y%!_fG>TfN6WjP)c4I!Nrm)3$SBI-2#Bl+ zJ}jNLwUgOlNh%k~7?38H_|C7v)o*JN_hFy(Km{jfUbCWZVmkyBGNo{0!Hcm)vIEMC z3HyDB&}qRm8?g{+ZanY!C7ys#a|z}BpAFG}Bi3?s;E&>CKlTUY7yQ>AyQ`JwO)4&53D-FC~hcb842l@ zMGwB$>n&X{_wwECdu}HPuYMKF@)E*ga_l%#r19E~40dC!f8(n@Z!Z{*55JkUBCe2a zdg8Xw8i0rVNgk1T`P;-$j3m=JiUojp{@mYdg#EYD7)1To zy357+ek4lx>-_c${Vnb)IFa(J*gPWDS6+(II-Pghr$!Y^Z{SB2%dS59z1yRB*$};{ zLZhxC5Mlg#w!bk_un5N_E%HED`LO`!Wkb}fM*tHQ)>YkKwsA`!!t8e^e{PhOVc)Yz zOy^PKBScQO`n9s+n!(x#@v7<+h`>t?)M&MeWv|JTSz+8oDuK5R_ z7~R_vg=-OZADa5HQRnXWhWYL-9HrmJFV?IfRNb^bz%0npV$`Gd%xewM1_EmAp|rBG ziIFF8zFaXWHrzz*9wHX{&d9h<*u+$qVajA6gyE$yLf-YMfUXnS(093YO-0m%zDSC# zO2EX`$Fds?MS-jn#o5kfs(Xa@-x`-wxPPEIgZcU195cIf@6_cgYjrM~QS-`kI_se2 z=xMIQIb6&i-HF%&Ry18(eEB4IG()KL-`XLK}2>usN^J9#2rsS|2gwstyS zb#|{XL>Q;8*mjHGq!xl8=kb#MJlg=dEPKIVb84sGv~BFKceKuL9cwyxL)6(lEYPh% z%N1WM4_2IC6unXPZPkK7YIsVGVV+6Lt_sOkL}Ap^t|Ei*l!g*6@59&WGT)c(l_YaqW< zE&`E0b){rJ(d$Os_uKM&BfV)b5yFlO z&1wa6IO)*9+bc!y1@l~Ul6fY1a14u;D>?$cKv4%>P_nFb;phs+&mEj;U)|R2eUSh{ zv?rk( zSG9tgyCqc-^y?ZBISJW`1Rj91#hZvh=jFKJ5~`pX1lIIm)ZWjWgb5hCsC_X9k_S}; zJ*rgk!`09%8}}T@_bzej6D$b6O<`w-WYIUo6)lOEs7h!Muqs8z8GyAbK^3>F-&aeO zAE)v~L}`T-&`M`^h+850uN-CpT$TQnd#=|^Ti=Uni~6%MweIKAmIB%qX`HPQM6C6g z$jj(1FW%ir^Tx)C2~LBU%1<7`7RYLLxrQyEyjfXD@hVwm?gMv`G33S)EY^mZr^Xv| z-##y&YLcs%@;ar5QhAkmB5v(*Blc76(#mWUc#qTexL0CZ%S^*$dO8*-(v|$9jtEKL8tMx`x?aw9Cp%QIwSf6Xg58(5idM z%fRVuT^wHG= zZavooXIHE#Bh`%N~tP)T$WdbKim^L?OALjKB)qVRq!X9*dxc*8*4cT?TLsK zEXPhcSTbu`q-?#SvU$MDFSDW)Ki?6}w(wnE{cy8b^S)bb3m48P#CH zpYnoZ8Amp&CB2@;qw4$4F;@9kH06xmhFf2=D|=tAt_@kUvd1_g;&rQS>I(t8Wz@ot zH`az|y*wxW2QEMLGOOMw`WD>xyBi1jR_oXN5lmFb=Qw;)O3N^q$E@#}( zSzX0?4nN*G$$c?2M0a@Z+fetuZ=@S1c_9+bo&A+y|Lj28QoneSehq ztL7;D3!1+@bkGK9EW=+bw!MAv{dG|gOGL9}P`kdk7vQJSwlYuH;LdXW_0XMn(rwoV zo6@P!OFMnd4RK8nbR67^&dOBk98V^9RF3l|tRrfjErN0hL%6|Ih2%Y%@W#4*Im;c! z5P|qBa%}q@vQe(>YA6Vq=$!yMrQWFSr1Gw)8MYN>_{F+PG^m-zN|ltQY&%3XK0+Y? zB6~7~vKsEq%2rKe?m@Zs+R*n29;;-2X|`ACyV8Wp4(&N0iq(^rw?y=?4k+1Qs9JJ& z9_&9ATdw{xNA$ggcf7+W$8tKA zVs$oiHB<*GWxpTk4=}s-IrC_ocPK=Hg`-@tC=@k3OqC3d#ot3=&oEfy2kM@KeF?)< zYC0MN?=(_slS?O6j321fg=(brBnxAG=9EX){ z_cYJWHSMhi3LH}st$K+->UbHg;^JhVLS?;T4NG#>@(aomt6n*Ofyy4L*AIG<#36T1 z25SzIw0B;Vi4W~&4ytVo_%sgIrEB*}N4!iZYU&vp14RQ9#E4)O)bP;qPIQh%uP!XM z+ltsXpEC+X>_egRVJDj7RIyu5#}^*mD~v7;8(!Y&i|+31EFbP3?$(qVtQB@JpHZ;kU{5Qp$%CxWQEh86*k ztEyW3pxexiU|-l2P#8hPY^0Kjl>TIlia@5;8VbTh?Ry6oFZhFHhb2mME>9p{Dnt0C z4efeg-4~zsZ@m`aWEuyb4vd}-&X``k4Oz>c4(&C4xJm3ZWEvPg{U~EXiO4K?aTG~B zbs=sRz&?zUFa>t7VFNL z$s}01C8Q-mjAqTV5fpakBdeAf)39ta)tpc0kCfO5k;bnwaZX7$| z1euP8&X!m|m>qk#*^hSF-j>V%bBnd9)HK(rY>ShReu!u zdMT2*x2Vyk4!g9!v$Qm8lRLCXGrRP;HSS0rqU=cag_rzmN!)R`a!JH;w70F~O`C_R zHsw1D)}c%FE4HQHOV#JLk_1b^pR7w~tnUdSieXFD2)lAuyYgT=342@Zn{2i}m*SP; zDMTRihOzhG#gQl1mjL!CjO2ZHg<_mtjr3|H$o@9e?qR@^p&Z#ZgVekH)tbiD8tm#$ z>q0N_8jNv`lW&bna*bPUjmKn-*LjUE(4q7g#n0GBz-Tp}u_k20>65>P-T~aRiDr{b z+2tX`NDFj%bSC?o0Wupjfr$O>>kQr+FuE&eaP;^ox&-zC`pl~?>YJpXScSnTOU$$u@u9uDLk_b2~9_lnk=|C3jo8LIm? zuQ)o?-GUp(4YXdCV27}sms981-u8j+_q`nron5Wn?M)r64S$tjTU*}uzOVQk{v!q(686|UB~K?l=T1zFtAi%il>@D_ds^8%GlhdqXo@LsMG=Q=7X+R=NfjI{N09%jcJ5 zQCZXAKQ_;GWbSB6Uk;xCwRs+#`j09s%q!u~&2zNGe|SZ)zc{%^1%<7rhgv!WMPJf2PSa`61gzx809NA$@}XBTGEG8FI2{j&!vXf5bN zGFb*``ezT;+TvAyYd~kc2{8&$HuE1nSY0=;3$vf4KVz4N{~v?r4PM%fj07JCO@M7# zWx$#xy>2uY?nR#sZE2vo#ER2edZ7=#!3r!{a|h$6Mts)YYgq&7c04Vsh5#4qTO+UC z`&^;Qg5VY$$7Xy2&)c6Q7M%S7BgKyxg2{c9%?-GJ2dbXsdk;SSb$@yE*K5T|5&2R) z*jDtGsxE1+p}%Q3OgMU3BT$lgvCt#x=aRaS3gTPGcarZ$I0d5PJ|Kj8_Z#ji1$!)p zYXi!Yqe?^NXcNTjT)wI`BL~jXF)sXQz2J@ZovO?yg}LijZ` z-ZXoP<3^aWgiZQ$WhqbBjZ_T_69DgZ^M;79lW{luoDpzS2B5@z*>!A3JVPjhnD~)Fue|FKBZ}FJk7&)1;;)3{C$;O z*@;M1#OnsK^!@UkQumDvDD?K05}AoBZ7v~=AfkrM=@rn{Z7yEW#>7c7gfTqXFMLHO zAqyZWUIzlz6gTG)O?0W7gP3QsJZnu1Af&l^ZfScaZ`5ciJv%s^6pT*52q^N``l_Y~7GLv& z=ptyoN8S0i?tdYJeN6V+oi@|in4e8e`=@RO>fMk{W#d5dzrMwt@!Ukp;zKt?i1xyIgU)M>2|6nygH zU7lExWfZ^|=>QR;7gwbZ#U(R$VqCPf%})5%I-^eqImUMEmGFZb4ZU_1uo0mY(lR7} z^e{}x0IIf5TX+itQBh$vXZxJoh*5d1%LVn$Z#wcvEPm#fy4)+ zFVJ*Q2kP65Dw3thBA@uDsdRM}N#S%@DY8aLFK&Q++KkssSW4QhgVu?V6Ogho#7+`- zKNY;TqWI{RYAjDGXPxV~M0re_hsSPs|Lm&BA3fLtRP}%E!R{DxRs4GomU*OH%}KpK zDdevnth&}j+Vj(50o@8M)4_?S?@voalm2&u=cTe=D-i$R51v==yJ|gI6m7|uFa!G*s8d7CgC9LOsJ2=B( zIP$#Ga?zDH(OHcq=YenQc~W_nn4~nim(qCaI$E-%f$Bb1s{KZj#j{Axx24w{SRczx zDbgxZ4xVe!d^p#7Du>J3T)fA+r0R`3ti-g@zw<)L-| z2y=akr+xBhcr)qd!TCWTVwJU%sBn z{WpW>s>Bg5EyLOG&VU6Zk5M368wvaE_nelWykMhGCO$y2|)NHtD(qz zLWV|c^pan7f;DFS^9D>qhU9K=Bq)z9d^uFa8=25d?nsx}fr796Mg=s6^EtegrNklw z-(|D2ZbR` zNB!}qaXjj*!S+-5G&8j%qj zT5v*mC+M+js-qAMLszFw9x??|=wvy4g*r`Lho$zo zBoUmT21IqXLis8mM6^oK2~h7>QQSI;XFX1N8W6G{;Z3hdRNF{3-jMREIMl2xz)C%g zRVjrK84dNJYRXT!2&ScPq7o5>Xm(N>_^_x*g1YfA>Y{weE6mlzTU6-)bfJop>>BNj z0k2F16%kE%Y@?}oM3g`rP>z78kEhW2q$?6&o+}Aw`hm`HWP~?CJvgqYBWj=<{2LA> zKL(K=0cKeb?jBv{YspT`%v8_m7rY_+cGN-Zv6zCpoYia|->q#^$-HDdld8Eeor&B8 zm;|m=Vjs|V1eyK!v^Own+9t|wZ(zlayaJ&5y+Y_8L9uQ}y=X@k)kGzaqd4oJih*L# z^-!Khs-~6HXyT|y=_fnmJau-|uks-Z_RR75%po#f2wzp~6QHgN()kdeOMjj^0D!V6 z&3!3-h$xniNSX2>C-AHcBqb4$M})VdNQ~n?L{O%Jp!A|S7;i`kjQU0)B%)<7R(E>*Kah1-p#RTE$%$o_qkGU6tG6pJ;9&kLez<*418W8RXamk9KT zdLJMsrlnky0o7N@tsGG?As9cc#3mh4lgLs7S}yuBetJGEr;dtq>$i_53-`Ursfeid zifQRXBrlO^o*ksZj=B`%#32iC4rUF(0cx1f4^e=3kStRM7>X!5CnnRLeR0$DDiy6$ z%Vc&%$5n&%o6;facJ~3CCgA=9m<80P+<<^1Y78vzRRlFNf@K<(x-pP-z*Xu<_GBMK zaY{&GcHdeQ$Y{39zK-86p|Tga;ahZ+&MkMJMtUz3OppauyzC4UtwEue$aIC4I;$y* z`aU^$oC+gYZX}p$`rIw3iK@{%;l_43Q{Rmn~}g zDk>*U0oRJBWm>>V#H&}Ug!?#1@H;Awjza%4a1%?ixXUZTafbG5oP?>o1M9J+_Aj2? z2a15JR%$d=noo#0WfgrvCoE*~`DAAR&p0R@Bbu%n$5k#1U;*k}5OfT~_2E6${0dbL z;zhHd(-pH&IO&`HmDq7b^+T9gpb3;mn{#@cWsgox&qsyj`7!L#J! zSN^57bE)LDKWb@G;XfJ8pJFHm5K#MOsvAdj19nibeZ8v?U^372y`t{Qw>r}*DqBnF zzIXk;H*s)wgMmiFfE~#375fdchAU;HV11}xGeDA0;Wu9&LZgLx#YnLW1S`tETcJ9` zsjD;8J7@!gc8!n7>-S;N$yb^GVhMqBdt1Mv5yuk=N^pI|J3 zahNmlsxzGUJt49YqTdX*Z*It@j{-5zR5gzikmItril2}@69S@OEbyXdB7R~+Lcqw7 z^K-lp5MNM1OF(FR512fn$XcO1!%=J{TzP12=)2z#n9vZ?Tz{5LF&NP@kU$TwhPVm3 z0#P>tk+uCYK$e|ghb9oha&`7=dl(m60 z>+PEB2@Bc>@=5zF-~YNoKixseF#P6mE!A^a4Phtc#?Sbzf@irmK`RLEn=Pdmt72Hp zW17_G9{`c4Ym_#Va4}6_hlYZ=!dkF~3WYKhy6EELrU}t(GnKn6cT0yr#WuU7xQeK6 z9RSz&dRn6aeK}8~2c3!^8*GPqUF@|@mAPuFn!%iG7c@L1iEQmPVoz%O$XEHX_y|?j z9Dq$2sKVK)JT0rU&Sf?RYXiT;Gfm&=A zOByA!`uI7+AAIrA%_6oDud3{>r-(n2zP$1i+T#tkT%e*J&_K3HQTzx~Dv=;X)Ufb% z3n7n&5X=No^+ad^M{R^EDsrg5d2%TV3owi+SOXlnOe&w6mw^OsCPs}#Ku1^Ku2SDX zpk>ZyvUmDDt3(vb=BO>@M7X{pbd^&6Ex(FmK@aG@4a7S4jtw7m8YlV5mRQtN9?-#RZm;kckz zc9&!kU>$KT-(KJ;^P%FLAa9@=bXf%9UFL68&o6!Qb;t!wK2o%r(0_^mZVVg6)|6+jWN^i$WR)|(uXyu#Eu1sTT@i^&;PT z(q6vgl5cS8x{T>n@$c($9Dea)8_FCTYL7NF@-|3Q7qpf(^nPz3I5rIwHjQjH7dtmh z@-{8nHm#O6ZGLasacns#Y&qI&IX~JO&}Q+H2R_GdW%9a^1;ITPw*3{vxcpp`t0|dn zw)vtrStf=eOxWEO-iL`8ILix0;78v?i&zA;?Ii!+(deRVNfnMc;vBYe#4MSQ=Wjt2 znbSMT9_8&8Dy$VK?3F&+Gq+zWZ`&IkAvCrlwuS>XaKPG*c)x?Na@0%^L0s)g)0(#* zX-q7D+}|zS>!3o^w*l6OePhHWASK*CIvAnar{p~77cnJ;A3*Ghr$lIkI`+v52&WHC z20Q^1&?oL{!gd>AQQ^?JmzY%lP@tOdL;?78cxY$*c^^l-b4a`Q2(V20d^Z5}t&Qpj z72S_Fp9nu26W^sHZ9g(rJt96nlB_;#Xk+T5I{tm{SY`Y(Yl<;P3OyzMSknn~qyVtJ zpy#}MqE~mKGk$0VY81w&7>VHNCGLDt&N#8KCy>5jL~qL=yZl8?;>3*ev)ql-+p4GL z$6qw=8fv{|IN>-_)!);7%ZdAbYN>yyX#17_>%Q3yMw?|r3I*qsrB9Zh8Q0nj@7coY zOCeV{w%lx|i0a0zZqRYu_@a{0>-T$K>Mqmb@2>%m_2;P0ANZW4L8sg*@I0 zd&~Lw#W|1axxfASO((t#j-i;9vovZ3owtVX$LlOPzJccz)S~%`({3 zdV1a3LWkkjmi8Z5v8RIO-k&{KFssoHqHv#)LG`(RK3R!wu0r&mJy_Ld{a4QeHuYZr zHF$n-i4~(G!EPp>{=kZD0oN!G7m!xF2H=6sLz}igda#wgsw=T33VBA=(MJw{44(Hr z1c@m(bKkmrsuD~$2ejU?$d(Vx%X$jknU~wsD{!6QH(Ym=s4~YZO_gZ(F-kWJydG`s zrQ(>)C(p5IOZ=&|Zdp-|il2II!7s%7C8tJA;xPw%$=B#5tK9TvoQ(f2Z#Q?H)N!5f znG&yyBSGx5w_;9PS6s&1+$Fm%i1`RbQv*DqIG$aMIjK}ejv==FGB>t&CBAWTjJH&f zrvmkJ34lL(;(8)=*j!&Mgej%+;jF-dea~GT$9W&9=m_575c0KS zfs+V!N=t($xT)5=&X4(V;KEJT>^v*}!ANGgK_L@Y{nskd6!yR?q;oZ;Vr=9%*-%a~ z+fEi==*h7znijqF;vs}(hg{|q*hyL!NvGo%d|l~=ki^sc=u>;SFmNn)i@H$kiWjYQ zEOU|gfLa&w4FLkCOX6@i{zf1mj@9t4yaXa=%_yJ%{Cu`7FMNvz&_o`rM>ENgxz_P9 zKnJT~s>(l%B}-yHmd~KdD>aOgF&U@V27j?evlfN ztGA|59WAy(~ShBc6fd-DL(-_Y^P;I>ZI(dgPIkh zE_?_ReBX@5)RgC9zi;z}!**iNkQfBATczlR_O}!_vz#z-=KlJXo$ofshqjUNQj`z)c*~`gb7ksSwgBX*pL6W* z|Ii8+C{B~3romhYbpS;xbG77Y~f*b z%%ue_XuF8BOGXDr5sr;=OtA0u`G48w7YL+~`3tqW_`D2=W4@82FY)L?IpkE?j*y|8 z;oy6p=)OjRqST!7rN~*`6O4r~uq^*KpNEk~_ymq;nsmK2HoK%7mq3qb!M79ZMj0dQnfw=a^b5rtrOFoqZi50#ID|c~Qo@ z;^((W%mD32+$2q?((m~UeR8t+EhHg91ox@^uy$d0;P3^hv^TEV^(md-VZJI?F%CChP+2Yk9Wd87r#A`^-gX5HYWMKB~d{&jt zSt=g34~4CQDT+P**!v>R{PqH1d1ed1f94kZCWcqh`8=6d)JGmtF{0`eA`&E9N|BM- zuK_hMcv(Q7b5tHhcg-Jj?CMgg9!@8EP*+J&%_ASkV%m1bAj*yd0A zqpn`Ct!p<+hc}4uK_qNL!wPS))A{(wr;Sw28%j!O)&P;DyoXQ(BNQ=K9q>>g9a5xn zsvT9(48PMUx%VKBn0X@-)`;%dAcT>VofSnC9eF1@9U=gT$}lvnUEM!d zzve9G$n^>(G{lP^lDJc_qz#VfziYDUlOX3L=mqYf;3GHXlLLIgYXi0RoLiQ=`9g%V z2x%eAUDCh!3&omBYzg^O0gY(t6GzRU_dHES9wkF-%P5`E$+9U3xir14zDo&hBBRDL zeR=mZX84D&kjk$l6We8#D-3Pcv88VE2Tx#4Z_P~NIqX`K;dJw}4Eo3`@J0R-uIU-& z?<&BHqX(XMHb5}jn;9q~N#_<+-<%@M$+@;!F_HVgW<>`y zOKvTZf6V1ut+3FUnnkFo2c9mEXGcE0?X-QmgI2{I~6*UF_d zSlceKV%aT6#*X^n-LdHNNdHbs@>Nx~KWr|=hV=6|<;BO5-%I#=C|8_spHW}ZTi_A< z9j3PL9KXZX&1`tnngS04ul|k{Eg`d7QDR!7#tT+;c#Gg~{M3C+D}*AT@{2$l`^lyk zK^Q?T3Yx6}(h7_)g5HK3@X#F1KueUw^9wlMsT5{Fu_q$-cjNm^28S%m>og} z*AB7`G{4#HN8Qp=w<+1g+R>m}e4LPzpHM1$c?L%)qd3HBre5kcjHa+933Ln2*}g7H zfnmP%igm`Xp3-k9J_(MzUL=~It@LXq@yU4&2u(B_+P3jT0fj(b1h*?ZxszDcju$?S zQ>y9`?CO#Q~@WE)_EUsFm2BIFm8XNZ(X%H<`E5(LE|7q`TfXIYB8(S2()QR~Eh z`p_#F70nI!dSi;T0HLBV`Be(8yUIN%7(-Ot6FH+eLOWz5IT7OugDyR}9uGu0u~x>h zY}lTG&{35F36DBz({q0o17!MD^jaQdSRM4Z(6tt^po?!ZBi^anJElM?3;irBan+27 zY(mD$fI5vi@=CMB(eIODl2f7e#93(ww zLrXQn^A6$#!EK-E#0z*RTFJGFE8{a;G)hrgDiZ_N^pKRq!B;Is9@?)WVX@IYgKt~7 z9foVmz(X}3I8h6#6*XG#z(V!K@o(rg8d}KZHq@IApz-1mbggzI3;N-LcJ_>h^N@P| zWR`Nliv@y?_ETu;hu$>dR(JT*hVShDj?%pwaUMcit@H|^`N;-9az#MuLoLv1xtleP z&7pQYMWO=Zs8=0Uq=?Ke&kiQ-WBU7!BT-7)m+S6isGCv2FYxm%<*%(YO{~Dzvhzy7 zqv;w0SFN-e7B0&a&DlD7NgdjefS#@+op_e=9>L(Q9CRX4qMt%t>Uh+bOlO)xebv13 zAd3@-`s%j#SpVFI&+O&P8j>$2>rvTc}skVlLuWmDDa-Scj?RBC=f!H z4tMfFupxiA#|jtkitrEaZcSH>KB}x)A#|?9#UCkT3~S7>K^#Q&o~rZQ}@;H4ukoK-h?t@+zZG0Z1t3 zYLc{CG7D>ibOfK{MAT6O^GGzQ{6LY$ND_qYFeCwgcwm5%*7|8R+2K7P^|9CCVo;~b z@OFk_35@~CufgSE!;%7S+PXK3j#}dSPrS^=$acrRpSFdH5AjzJyNpx6znDzkP&>M% z9V#$+RTHPRh+_6Ie0NInc%0c3bJy!so0Ss$d0%R3gF1Me`k__4Tr`qmgm|(?i}qof z4m`$O{Jqx5ok)nW9j{4S1c7?Mht}F82Pcz0_y_0Ln0w((jYh*xn=$UKCa$@O#?exr zRmQ!3nJh~yxOy0Sl#st*gX{|5WevXT7oKqam*xg|BEiq}Jz|GZL?wt7m^}wz^#Vv&t>;=6*+O^S3L}Pl-o$MPqa1iT%!JvWUrT%&x z=19aEf+T%U&7V`wb#dbgMCWp%d-JU4DrUNXq`64!?8{&AubjF$7|5(eEd-TFi(WTo zsj`?|7H5y4Z$I|1NT3-5;tZvUjiiPAJBZ)Q6TjJv`6h#iw6n|yS-7C)UjXyf*0JRh zvF|qL%9s}{!IlLGD=Wmp%U|;W!J|k-l82~XPOz1Wia{}AA$Mf%WfDoud8W02Wloj3 zF1>tVlEuV`d5QJxWH@@s3ew~>q_P=@FO;_^DzSdjx-iU6mVSNgna9FQ(WQ;o2v6yh z6H(NrKKPop{#M;mEIOuE74jR-Vlp$jPrO{-IDN#s9D|uYQMLWDX^?o`EZT12R093g z$u=(7_M9E$;p?EmOzjCYLNog>`F-+L?uR)2po*6=F<2Q?C<3O{R*axi7k=HBfVC-4=&>)l5sf-!^4lsW(pC86Syoj5;4aE$z z)k!x$+bi&2fn=Q!1pNw1TO%n_Wey_B;$FB#@4U60iGC@W&i*mzHlYT0>X z{YWCm{o)>+!%;Sm=#I$7#^Sn)iKCi{eM5lbY4nB$-}3Vk$Dh$_+FNrvQyV3l8+v)O zcS)R{Fl_1{nrTaJ?*CdaGI1n!+C&Fznx2i}R3Vxfo6#jsQ5X_W5ZzeIX2#~CZJXHw z!xq=nqJ!F&W3rZm$(D1Vb5+>l4m-M0A8h-`IY#2ip0#1bN!&e8_RFm6ixuaW9d$V% zm#5O(85%AbX4~nm+iA?(?oYQLmTrgCZ-@46hfQsVZ*4z1+kQ;46T!HHKGkrI!i}Ys?>sYeor`dNGPCpjp~W)G%Uv024(M)xC~kKp zE_I3JWQOYeeq5RwI$e@FA_n6YhiJp@)->)$&FrS`><-6S$#UGc*QB{|4RZSc$}Isc z*@BjeK+8BXyGri8w1GAn)3syw+Gg%YRo`d$y_XKzN1T$^9Fo5?$tX0juj7D}$3W`e z&~$n4iw$o#_m7canC+?e+D`5d$>5o`R3%>bG{~n^wEh7*9XPs zBdHn>B1PY%mmfr=9i*8ZNDP=P(p!cj@yc)B1(}4zWp?`JxeDxg#gK zDNk=Le3OzNVvfshMWRP`4X9UQ+#|dZj6TRl5@Ih1eVIP%vrQ&-H)Mnx$~7jf!hrA7 zuF(wX2N6d$+gSdlSg)hck+|`FX9MTHnF|re%`H>7=rOwSL}N6Y5T7Q@l=|-&R)~m^ zFc$ygt8u>GgwMPEj8*Ktk%?01eeA7b;4`x5us5)NC!{`c|Dt#YgXz_6l=vE1_! zjQ=&>`L7rjha3DW-iaIP?j6T9jEs#9wEY(n+t}IF@(&ODUomXs+pS ziDAPZNB)IjO;ZbW(9acOqW=}cMur6ZiD5(jrQGTNz{~%khxa9hEmDxb#IR1T9+wi< z#_?|nYhmMLYUyBXZubufYhdyRhSm8K!~Sc$Q{kWSPR+kCtVnPQpKlT@#ER1=j?*jt zPYfF;en;oOiFf{+gyj^F{2RmS-uvHSSa5Z6W?u^IvfTN9fnhNpluTG$_vB{pmyNxE z{{zFa^l1!!fHnNH+Uvlwe<$phr5QsebEi_MqiPWIhE zYw37oEv=Q>pt_p*)B^OP^roQ(B{5#)pxN`Oeavc&zLg+3t5okkTq=w;#8R{$*p6J{ zW9F`ne`_9j4_j?~Yl2YX_9^7eQgYu?8v@V+4BEu;MN2TSJ;(~*ZU zcXB9w4?Ev8Su){2Na?34eI^a1Jyo=UImPs<$6I4>7I5tm`dRe6Xlcje1?=BhYD`gp zm5@wsN(SMVf(8iTmN`!ifjQxHG&+G|m?G^SKM>3^`vHRnM#>N|!XA*7c;R{tebGim ze@;KjR#F;&&XGpoGC$RroJ6eHy$+vX=UJ58&@|&whKP{RNcDh;9F-ht=tnSwy|Lq5 zRJv}M+dabHaZWTNvAVa^wRoHpE#7c%$lg>aE=us9+FcW*yXlGv2HR%=R{Oz?+=}$? z-Npk*kKJgT6r42;e2lqzvQ_w=H&UVLQ#DdEy(m9ysElYn0kVi!WiS;qsailO38ndt zZ(tu@aKDoDVH1L+P~txAGopbm%xmKBvcNr3&gb)vSD_)8s{I{4L;=0xewpg0>+~*J zm!(ahGM%yKnr;hOkMQe_r`ilJNy1-Y;-UI{vw9tj*_cAgB=Q19`3f?c$D{=P>E-mA z8r(XB$|^74@b+~7}I2-9z=t&r7+{>u0EwK45iM>O^8XxzTLDP6qT(CZb= zz%PDXj<8fA(q%W~`O-$_HiWBV0SRNKr0IC-lwi`>y*Tjkb(sRbPI&_yy>6wnqOOpU zz<}%~yX#72!=noQyc^J0y+w1VT#v@z{WgkggW}qpj_7+<_v5d8S9yXIr){ARC_czD=HcI)I$tgBZvty}L-We)~QwSnR?gutk_0RWA#O6Z2v;unye z0j_#}Bw2PdBqZrfX-9EeA!8c`1_>$Qy&ioDD{$vjW`0!^_Yem29ahMHA_{Q1sGuDl zG$z~mzlDv%xfF|)IVQ2kun}k405?gWy`Rrs~W<1J1L|G=$yE!$mJUtP;CY%t}LZ<_VLmp)qC>>%0CY%IMC(vj0KT~s7%I^i04xq@qTLEeu%XSS%WRqt{L_`Pca}a zlvgJ(Fz(>-(HV|A@cx}N3`*VqUvzh@FmS-84@3F=48UQ1&tjN_Af2$LuIB#Yk6Z1M)n zEkj}xZjeeX*95W;p)+sm5MN>ug%97q|zzzC45;6*=-Q&c}nykd?EU~ge(Op#7g zlTHMBawp~3b#GaLyn3zjP}%z#=@xvtX6i5b zv-XVNS$ve0`D$cE`NU+bXR16V;EmfaTB~N2sTWlBRk6AU4p)B8VD;*2o{bzh-~Ks^ zdm|1i)%_G8XHSO${%x^N#aN{jm{3~PwoIbYXtL2B0Ui0 zgiPn7(QU*v=>J5*XoIneure0RJB(ozM1XL9j%UE zBO%eZ7FL00!BaxXLC{((_)Tq80kQpgbb8bl?bRNx`zt?7HS9J&$GmU#sZOpK6FyFO zE7N-;8I*n$!bhj!gg+;s4wfWZrG1HRQp6(35q4Z-ZpTD&C`8DG z9|8nQtbp_QAEvuJWLyadYoH=LiWEHuyFLpPlcrt#7I4oc(vKda!xre47)k*NOe<%|Vc;@auAZfTg z5vK8>!udmDS$}mI>iunRl+1&I^8j|!^M$3^jkV9--sLh@_j$@dB5TnM=y0#$ZQ2}MUy zl|bSW{m2c0mCA@M0F=jE`__H0g;Fnzayp|xNKOVKxD^tHh!#i3bnYO^_z*m$RErq8 z1a@oULNHeYS$7vC8V6bIf{OuAEg7+cseo(*b_W1ucg09x0$cIX#D?&0Evh-!nDPbG z+B8qdoRwM+3lN7RE(BeNsF8I6C?^vjg|WEVsJ#McdIm;nEl&0170l3>7|rtr7f)8l ze#mAi*lR;Yq?l8bw8y4JT!3Q0(KMiiBTSj z!OBBosUQ}|8E{}CEI`IkVlD0xOjR7npAgD#*$s`sQ*k)n=$sZBn^amaps{C=i(5}Z zB5_b6cqop@ks%p)j6>U#e>oytlyd2L_7sVb_aBP!F4K zNF%mFAT#EM83j}p7NUPb1%lRl$h@_xBX~58!wJ$Pbc**G`T>mlU^)ZE>7(gbI z@_jPo5<|3yA-h_G5c>kw@EK$$843XqbQFxi%{8+kUZWAtB$=*eAuUHF{BbRfn4KMm z&SH?fN0OLD7J6eR38#esCturBd^rZn{1ONHK$q<)freyzc*u1ZTO%Ncls!i%6;L3C z*zw6s*iJMewfXV=_CqP4RKDHxcYZ+=3{sZ zpcqt0F@#92Au2i?&fZ(g){;l)FdBswJkPEzGH_r6O{M}rvn`+z<$(qE134ZHsK3+k zz(P*dB#IdJG`{O8XrnSD8V~u*M%m3Xz(C^w#;gK}kGPE3ckl-S2;WP?zIU&} zmEAA|3*--)LwgCu0?v>aM8jvHy%1HpNu|mK4PFk0x5_Dd2*}hi{2T!94FQ3DD}aea zy$H$^1UU|0QD92`6PKd9n=l3ndg}X#*f;fWCiOD`!4i4B&oOksr#Y)J)bh<7Uj+2F zD(T*>6{n`MPsSOJ$RKa*~yXBq=o5>bq#N38qgjHq#(j@uU?gj zS{;T0Wm8WT6refy15c3#**d)0^K=^(bn)1`&<; zwBJL=y!1yRHdO!KELeDRdpBH_!crOP+d*B}0cWRBol9vld9I49*@V&RxY9c{sR?Wd zT3aHveHDs0x)>W?v(rxeN6NYp*5}#ND2>om12l!9RnOg`v#;CXliGN)sL|#XnT_@s6 z&E<)(*rko}>FiPA*y$$NV;L5XH7G&-BThHo)OH{odPqV$GE{ns9DBLR6B3^2cv{v1 zCkJ$yscThoK_`8{!bap5c40M!rKbMJw-MAEw&d&sAn}Gg9UdoRy64wGqFN8W;mUz- zHyt0ncf>@4zIxQhj}aDDI>NWLQ-X#)>V}JFhU0z?d+Q-eJ?T~#y^4ffT?K2ebP%qK zD6K%$xP*DC#vrhc)$v)qjd}P18dhjncNXBesP+J4Us4 z{%D^tPXvl{6$OkXs*R)<_YI#klau0a@!-K7c=Ba}sQDjr=i?Iq%4U+&J=A6$TKr*P@cxykGK|B5^`1K143x#Fs zH%o}S@y^fVL#dZJd{|zCklmrncf#YTH<9o(7Pxo3Tz+g+1=FWLk~5M-aDN5lgO9N# zJD-TTgUVR~WA$l1;``oo7~Zs}QAAK&GcWR!d~WSnY-cfiYeSMljuj|X)-c_}WsiVkcF^~T1xg#tn7t2fbXKiR^)ibdn1Qi(P|`TkJU2 z2vnPWJh6UTyDa`(7l~+>NpO|!{GxdEB}wv=vbSv;-%Ru9yr?4TG=10u87URX8DlG<~`prn*0J>mFn(<1MFz?Y>!~C^rEkhT?|iV`g&F2--z>R!K>74onm+l zT};<(+|@~r{}I)y{>UN8%9UQk*iQ7d$YCJSH(E*pA}c~ZZp@vaD>FfhdZl;k#TUL; z%pym6;xDWfM0IZ-u@=}K3qH_OdO?T&pgT{+#LfE6-1g_yZ0v<0=`o4l8q81m?;e7z6F_zu z9RJ$nc$iY%iC_v9BilbBy?F6^OGywgd2d-h6i9JHEd#Tz5=rq74C}j27forG0kuDl ztFg5weY(CCn;ss+{oi2N|1fvnQ)$RF{yLs>W8QR~!Q?(#P>|dCH<=LON7#3B$D-_h zf~cJj*0w*(bkD4s0K-OPdKFOCJ9p=)KdV=_Y=*?5Oez4Mm0nz@@zb{|8{}yEmS2AV zWcKgoPEQ|;e_+_Jptb}K9pZtjG2^>O`I0a|=LO@%JYDQyNsT+>(3rpaV+z9>W3PtO z>p3%o-C&xB9Z4#@W}bo~j#>)4g?SGB6weW^?ae zeS*#Vu_J3=M)I;_g1GbM1f`y6@R|SRDOJPe1`0Xem$ zUKwcK0#i#$Wm(*_H&=%%J)4`}b#rjwED|aG%t~wy9{$q{C z{@dnXaK?IeF|sU@mX|1UmzJ9i^^tm_2jPC>1@L!+`Oob)@6d${O>XB0@zph8s;|4& zy+%We$KfNf!as!4S}ZDpul zw=|8VYlYfNC#q)%a|C5iWT_tuquCq8v_9lxs*BrWwm??mS0#@-Dj!?FU`3tUrP}Un zo0u94m!ZNF>}G1@O(5%hH-&!l(Djc4VwSaiuRBPPBisge>EP(DMj>tE}bG?bQ8 z8BxEfaCio0)UdmJ%EqZ6{kZJyn{fe;>Pvm_X4$H(es#ba`)9U*1oUT}fR$gojO}Zr zLGn2#Z~0b#$y@Vg)siL2_+VoKZh!9$u^J4C6tE(@iA^B#V$uD1s3`~I;_YbEW*?#B zxI-y#!><3cA|oZ0g|h6?;)9kB{~8{)T)&sKLU48$`TQ@;C92okB+KcddKyCvIvpGg zbT6W^2Qmj&2;kl;A0zX*> zz63w=jXOKrbz~O=b0?Wvfl3h#Lo4zgyKyB-Wh61d&v^s+TwY7*PblTJ8W%pC6}0|6 zgM_Z@?`CpWt_v<^Tb)RY@WP&&IV!$axYvyu1hc+!bfVV zIigav=zp*ifHZLz$4=s) zKlUMu33C*wT!wZN!>07*ZO2b+@(hkQJS5BjICc<2lOgKq&Lp-R$a>wnDwp44lsD&-Fo23;Xh#4tNC8x2zslwJPbk&SW-9JT zty%e8@Jq#YlZbJ5@xa62W1sYIw%Bu;^v85OO-RjuBrw9z;}a6c1E41BR=?>UtyC)K zRrR=E@JEr9sj4aaYgAW1+9WXq1metmwwKNQqivxpHK6KRNh(EXo(Kcm+#p1ALgI%?{HIThX^`58gAdz@jc?q& zpp5CM`!psd>LK^roo>8{2nFZC)k)J6UY{)tX^vm({N;MKCes?ovMDB>RI*QhbU>@4 zn`b~LgtQLt3LLRB&`W*HL@#u%F}k;)7T(>y-IF8t{+=xbeU4rNy7tq!y*MDJ0kyi00QIAVgrv{_ zvvTtUUGU;3Vg9o?yD?f`0<(&J{-{~s$cctEn{BvxScv>`)5T+PX@d44T^9vafzKzl zO2FB>+zy3ElhBpN8vc#cy>C)B$sFLWa z)9My{9x8W{EBtj^)ZAg2+%1%b=Lhuh?>17Z>*9bXU%Vpt+NYmhsq}O&hY9!>8l;s= z6C|B}+ZNqp+(c5iw@d(9ED?o+J=z=wOo`0z_j9#tf&mPS8m;Cb^H?bQVn-7$Vw%Y97UiO7j*q8S}t{@@Q zqwHKo>;24gSE+F|y%Y|Ezmgz3dj{5jWSt_2tm)(XNnNu&de^*sSQ%IVw7wDQ4nX26@pu z*|J)D=7gfm(tB=OA64dUTvF)|8}=2u!6SW%U%T^MwO~V%=8sBRA*A*|k&xbWm{o&~1DKPastgrEW8F<072eC#IUyKQ<|}mTAu&=Cy!^0P z23_F9shrgs%0}M9A=XZx1H4bvecAdU9FKltm7C|-O(S`$QucOJcsApodhXHg<%XM7 z6frgeK}5g=hM84;nzYZ7O0Gr#KgL&b=$4olU{?kByMx*@uOouRHO_un&O zUCVE&$w9h6qaWMR7*%voHl>MLS7NBXn3^?Pw}wBnMzLB!1rdf`#_qk^RN)7MKj}C1 zz=W7IFQ9+uSGVzg=Iy0kKLE+8aX)EH|4?0siXPan3$&Z9USQE_Qwf z2&v=#+10McKnv!aM3n25E0Ut>*(}lj#Y*k-1 z&7Y3y5nT}=J}{h(Cx))1~pRpnSk|hvd=+T!PG-5=7U&VpPJB6 zL{O!rq?(7bR_O3Rlr_aQ=7P_9Mm=U`C`AWw&jdVXJQUBIYD+!bT&_NsRL~-zEpItI z02r_u?N8g!G)d8}Js!d$25?o{s_etLGcj%^V52If+)zY5R_v)7_yK5eC^k7fgN3_Z z?R6hizi;@V^@l^(T*e~pikTQ$HLb@Wbdg$7-sVUFVB~50An|5oEPEtq7^^I#+g=aQ z(u=Z*8kU(+3NOfG%o=JPjZRmK$|+XMs$dWMsau7KunH5b1$CP(6!&_H80rl-diF`5 zsBlT>4W&S8Zi63;YN>nTsEZ3bXGSxIdLvq~A#wdxf7qsk^wVX>DrdA!8%cvhbT8OH z&I>_QB-O^AXd5h9qDMA7!7F-TW+7ea+vzG#40fss_w-PXsE(?VJxkHlk^?*X+&N$_URV-1OS$vm_5^TaG*pZ1 zNJuNotuluGj+5`$Z|5k5pA)|u4f>VoIEa*h>d}nKs@7utQSCRRo<_^}Wh{l^%jy7? zeM*U3I&0R^N^#Vc(MhBGcx)F4`+batC7n3JFq|Hg;@p!vie(-%+)tcj7;7&Us!vNH z1-aj1m5QP?9Sty_m?$2SW=Q0vr9K|6};)PC9Hh_fE=$f~N*2OZtA0K4byQ zCHzuL@Z)vRZpPxDbW+fCBt2+U_k&D4x4aFQp{v{4el&L}btaLofPaFf#Hd)s_}1Ih zB}oheUPW+r)XO}NBX}A;*0JHN?MyND8f=kjQsmqa9+y2B6&2RMP%||N z&LS%@hG2#tI~l3wQqkm2GVVy_CeMZz8}BkUTGP;*MHrrQnAmZfIsF=UR5!z{&ptLD zb3R2G3Xg*TqJQgj?jN9BXZ7`(=IEus-hu`rf113cQest2#;nD{wQl;d(C`P3-BT!c zH=Pg6O<)U_ctVn@EUe!WR#VbA&(}R)KdPoQNrEv~0qo7ItQ%G2%a_nB>J&;70R&~izIGTGD#~@Ni&Xw zEqq4?I5v^v(~AY;t3xbaJCm4UB51!&6maXMd#QSZnNk>|@=nD$10;;vKK&m3WVyaj zll&<~T?y-IQEUTFAqGXb#(T+re%t!FMb)CQKrf5IqDCR=+&;?G{N>>7*cS(lm8sxt zZCH#{W?aBxM9AXHATu}*g_dlz@X3jy>C&G(iDLY79= zEh#XTgnZIFsi+HbsNa@#OYo~)g($Nj%WS@-=?EL5xaCg=P|K3##aYN=fQ4zn`1MOX z$-I*nU(XWLPVAb+a0`UpfSOb|w4b3i;w1O~%Vxdpn?~XMfsV#*x z_*RdZZ>~K9pA6D$HNpBNx;*routT@b2lFvoix^GUL?R$=8!;61p+l~ceeu?&lI68EHPr;V$RiF&z- zdgP{7=R|k>&~WNzqt9numnA)0E!{ci+JenHv|ENNT7=j2!^hdNqwH}JFLx3z*VC=H z=J#sZbf&z(chaKG2cR~cP+MB49UN*u9&IrPanx{dO1taKvvtpf0K;zIkKA@m+jcA6 zc5mMH7})ll+xFVt_O{iMR%bJ?y|J!`Y~{M21^AkU_!=O4Kg0Y!0(uW2z|RzBWf01w zWBcl)Hac)6`iVwVkjv-v<`#-US^tHh zZsJ@2I}Ek$Ul?lqx6Zi#*BI&&mgRqDP(OYAZvlA%fcn3pPlx^`WbNwh?ETR8p8)DV zLe_WX|AUaVg}|Ujn^p7=Rg(6&q^PJc zKR-V=Cp$AEBi$pn^xuW7i3I-i--WEvF|q#{kSEZn{}YBOE!`t9L1M(H54_$B;bH&d)V_0z- zENH*>WflIj4tJ+kYr*}t)`xqvPv1FE)@VQTnDMU@L$B{S@=JCYH4O!iaPkNY)fL_u z_|1cQu_NG^9~+Ikb)Bu?hLIT|H5Sg1^@GK`O9 zbEzot7KCDHsPk4Tv0Lrg&X!LpQ{EJx5mbGS%QPw5!wT%yk0zw@J@+hml9)dN zm)w_E6lP3JA|=r^^rv93nk+yhzE21v_02ZoeXY{C6E`*>_`v%)kK{ddT7jRXn0TXI zL_55W;f)!kLN-1DWb+KuG|VnpiyqS1TtSm^f=tx?6s3*^m>WRHrGQr{4^&p=pBP8F_wP<@^-~u=#4Brd^K&wttJ&N7yCn%g0 zS_3h`+L3##mBJ|by#$f_M+QAnDxAD{PgCR<`Wfwt5$R)2P^(IUvB`;M8l{P-Hp6+y z$|v~xZCp;QMPH$TsFiboN&cJSbCsq$)xRfhozabU)#dk*&r=b-JjAidQIU65z^O<3 zVLvi4$KCl_2$NaS1bi?b{}ti{>ypx;7Hrr0`_~Q`x3mhyIE&G?p7`=3y)ac!lgisN z$)}o-!u0L~(NMcfQZ4D+(Q&qNm^NkBeZB+ohb^b7DDr^{}sG083Cf z(7{Um@P1~+!Jab0!E&mLEE$YCj&N@Hq~jPt2hrGMOtr96$?&~RDge5>C#Ju14fPXe zf%l2hlSd*+{CXmsUov&`*|nYV^p{!mg;Jh4pfes)Kpl(8-rWLIYLoOzWS#uifV|US zui&P4ZX2%JjI`(zS74_Y9exe%G0#vbx^_VrC4fTq=d+IV$*?0M;!cQFf5O5AK zc;2DX%|4(?7>#!Yo0tVC=mk)SgWmC_fX`V#D%>Z6)~p<{#f7JAdfZ^kv4*)MI4zG+ z+=Sxu65N;^ux24FQq1OL9@q4v&OI_+vTXr}GD%BIARM7C%@-A|WO&K*F9 zfrD})yO%>P9c{r{0X2K8k@jia8SXwhfGV4p)bx)>XrjD!TeFs=&3fv$AkWa`Nd1fj z0z+}E++)S%^A;$O3mA=HkV5Dt@;XgBkoq!zO;9}{Z{*U@((Z9by`q*GA{S4KfpO#v z28HY0EUhb}o#mGfR@EBKjBJgJ+Wap8`Cp^11`S#BqubK&e_fCHBsAoF)%z;H_-i~+ zVkHZ8iyLtER0U;AAL`Fs{09<_1HHIK$k)6mVlI0kSl`;F(@wr zNK~kK(Wi;X=0;zKr1%=AFQ2c@n-lZ=OJ3wI8QxXKOYLr?(RZ-7)}FQ^(ZGC7b>d&N zLk;SaNA)DPmx#sBbtG((A=7QA-3VE1VMUUhIhj(MwL?&^9zm%^*(4ii@+9m(jHFmm9?==)jK zd#xdFgkcruru*%{9y*a{{EV?P^>*4F~vp3*#MEk(R zfykg1KE?z6`4!Q+=DUBN`ZztrA`v{dg<>+-L@apsrosEoXlZLb(=j2i$b^%b0%0}nK5D8k8WbG3WQN$B}p9V9J7E<2_Ct(wh z!pJ5=ms_Z00~L4+vFhCv7+?Ad6{yyCDDfmP>^L$k1bR(?g0&(S0)mLyp(C0G>Vpv^ z>=Ba4NTBZnN{5%?L~yXN`gyVh0g)rWu0pxcXZTY<-9K= z5ElTrd84xJhU7yd#9|>A70{VBG>U@A`J$GehJ@%lf*klSe`q6kpLE#QL2ac6(+O|vF0Wx@<}KFiC`q+uSUDzgBh=mLWsbL&;wj- z+%cur2GI{3&bHrw@j5N~9&KV}E4;wxCXk2-t%eZd=XFXU5Q?urg;dPZNOfRRb}GWz zNE~=fbS?(_Q677fnCR^>1;G=l&QE#K3fFw{5_E!dHH)X{2`>-1iE&E=qa*d@keFn1 z82U!uF=Y@g^;aMaWC%OOrv>8)cqTDH49W%}myR~3tqpx|AMI9}He;ATwk}NMnBwy( zu^cQ^PmF{NC&1QY6blejIEJ8TnPz1|(-ro{IAeh$ji@<;Nge3&5_U1@lBA9JDFvg} zL}XT^ybwn`5>H1GW$|kuC`%Q9;=n((&>ymCotcD11j_bza55Z2PTg%kaIDWZ?-Q_@e?!1NCA050eK-C!mN@!wV-GZUy@pIqZJeUP^09rOUYeC zsbw477V2*+fVk`P#M2$nW?1?-vh;BpSq=l#qYd#$9)ua8e#*#CFX2zTPOJ5V`Q3GK ziG?L1Xr%OR8{A*MT-&hxW06cCiD}Jd`3RuG^Rmp`y+S9nf|aOLU!0<^f-e%Kn^;Np zJO=Sv9+9e3sevvbFV8OQj%4{pQ5#ZOE(S|?V18>{yob3Z4!DBRO%pAo(L!O zl7~rAjCWxTAu+kdrJiji55AQ;L92;RDw^Ei$haad>_u{^UeQjEJjyT_;1Knr=g-3T%&P<7g4#fItiJbsK<+x%5 zN7mq8txi;!`VP+Zi5FZ5v6G8>5+Nh5!Z9p|c=Hs|86nC28S#A9Gz&z;aQ(5)+%TTp z1@UsL1{`V@XevIt0pVt{&UvF8O3V zDN!vdv4vFp?d<1fzdeI|SBj_8jSwX3W?c)TMwFMVNOf!dUTtG)wsgMJTco9SVL^#k zR;wnGjadVsk_9fu8_#O9Ux*pOLn(GR-pMqyv0Ff=L!mBPh_H`}Bm9Xkn&6^)@5)rP ztwu_KzU{@ZAXuUN`9`faQ!EhuK8qWnh%U^bL3R9AcDCRvkSbic#!0ITOZB}k#}&6b z=pc69x2p;uOP{)|w=pSZyC1<^_Lx2p*L8Y2&`ExDKmC0#U%ooEwv&jQ>M$Kus^XmQ z@`R+0gnh`R5CcK!m7%P=FK^NDCkd8)G$f1DRl&PGGwDjFs{k5yiB5LkOa$jtc5aPy zwgG#d6}NL*Bj}dcR}nUa5j~QAI?82Tk0g6C!=h(yPw8Jeo^_ zbb6$6Xx}!x7m2e8$|^AyqLV0QxJwAgGY>f49&olEa0&V+AWysA=e{(s*EQhHJm?oU zkaYg+VbEY;&LCmp6SOq=yxkrDd(cS;#Kblf88j4?GZb^(J`}e!l<;Q=$2?rH*_*WF z?$b^^*`$`r>}qT%s@gt`l!4rVj#O&!r09)Q3{Z4U=9S-mT>lHP;`HDx`Tf5%$UlqO zc@iJ*l@6oo`fLh6x;E2}*7ndQ3VbIUwRd6rR0kcELiMHF%EygLos2@dyQbm@h52r% z!{{l^*!*o&=MoPvw0Tv}@sY1`jVHo12*G9EvPG_+K1#iMJWRu`y1;nvC}-j_NN*I- z`g`B)-tUPs>Ive5p&wTG$I_1AzivzTDwzKLm`i+VDWi+|Br154o<$qbyv*S2Dr_qQSB;tBJS`RpYUTOWii;m|+cIOHuNSXfS-c_GGRfueAMTznzw;Ev7O z0+{_1^TUN#3OXtJh|Fbn@!(I%ji2%ePS#xNf?QOI!aq*dJ>Soj6qu^z&qF^yOP!Ep zQP8DPEVfdNJhEIgL@&N$(TfwNegAinnP$mxeX6hHR=qF{ofz%I+@;dSCF99YcrTqX zo8^Vv<Pr`FwKAQ~{`6nXYg~nf&K}28e;?C1rMP=Vp$)KItDalKr6}yh&ky`H-#l2O&s%3a z)cDo0{^sBxCo6<#ox^s6XI$f@4JpWH<3t$2Wq=gKEZDEXgu6DjodIS9>W_`g9!Exi z0Ot=T%f&X;Y&X>nT!_|4ln!BfonJZ;WHF6v9CdC)NbnAlHAl^HY$M-b~$v# z5T*#SC)YSK`ISwy_ZL=)1yKX(a2%x?A7y?EJn@oLAHJ2)sf&Z7(8us=Jmp_PN_-7M zbX;bO`>K~fDj;mEncz%|r+9tC^KTdBwNJYuoJ`-FBsWhVf}nU^4L>Y}FDmy4V*oB) zFkf5}*D{4D%#jE{el14Xcj&!|sjvlj?5zO=ul8OYZg>{wpZOdd^3?6Ek$mieKLr4U zI%ZC(clQ90t1imz8=fB!{i&F5KaaseW3{rMfy6J?zk}AFVkochloIpg9m*A{KJZ;U z<<%NxNk{~*{=|S3@SqkBUG;h21p^ww4`tb`3us(s;J%$f1!p6jYUSTMM5L)Y=b^?iKYU0+B$7e4|&UugmKEYfc{-84U zQ2V)aaIZVFDqu`%&98?0MR5PPibH;_AvVJ-fD@eYuniNF7IYL#~QN268tc(Ev zwm%|aCr`A5oL9qt98-4NpCtJImhkPB=>BtFGREh`&x~e%{r!wMkrnbBfxl*zmW@Nr zAg&0LDL4r+r8pUQlAOyLz83;Nd4G8qNH!8^HQnb-LT`x{FYEbEbn*HNs{U;z# zyAkdVo-A1`88WOZ!yC(5a*2oCY5z`6T$6eV!iuRt*e^ATF4&04*w?71oLT!c z3O!Yjnm><-Q4fLkxS&6~yxk{IBeJ}JB=$8mrU(8tN-sr%TsuSCd$r`5Uvf!^6US2P zmSBAXzvk1z1RmV}0XDiXK!WR&&=qdktk)I&yQjhqYxDii#$P6>#Z1@f+@LSBiftGY z-Du|Pz)p7CJW4ArafZV6@dAZj0noH| zInx~LeqkD-qL)QO&G0u-^tNb6d-OH@5k6dbw}&*k4bKU~st_<#%@h^pF--Iw?8dVU*+Q{Xv6#Cv zNk40&az#uw*p!wW>Dg11gkz9Wme>M@S-t{^>O@I1e<$YUhg{)(?3BEcNOWl{izz*b z&OXJ7&5)A}eaJ)U!>q*!d#9!G%}a&A4T*3qXz4tSq}v;^<5qA|(|_bAlrA}RL*WzE zow%tKN8}cNp6Q$WfdQiUx8U zN2dX4r!xnc!ID7!j(eBaprpBHB{#jEaJiwJ(?0*v7F#77cMet7eo}0bp{zX~VDf`2 z(}(HS!=@HzclX>{E(}xml%~>@a^CN@`-N@4?mTXuCP?76<+FZG7?16;pIU1PFf}L8 z{6pZG6HU=u7K>!Oc}+juhm?s?i3gdmulk#Pzz}i`7h!b5@x3~CZsG&*{>6yNGF6}T ziR`SAVkCbE+N%;5S-6%YtS%rL$Ufb^kb)yQ*p>HdOQ6@7^;YE`qHhC`P|>pid}RfU ztVUvGT_v?A8{I9SuF<|dqHjyW+|_Dh=E9}(EqawVC6+5^9-?VoPFnN2uZ;`7G*q%dGp$W*P$gdNn&TwXubkMkDPH-A z*;#apmc3Q^S~yWk%9;CtTko7leMJWI7DrPcOJ=!HDn)8JzsDyH+AeW4VDFwT|8TQ2 zEj5K%6hiRz6AV0{p)k+-z3jYPw2Z+Je~$fq#UuP6q}wl_#HN=Qm(J#O!@o$*bxTgr z5)&C9nRpe4Fg%u=3cutj78Nd3;dG`;N9>kTl(-pQznm=5Xd)Iq{t~bwH(O(7SBCV9 z?&@JQxZiyGf-%=a^%OPU?n0TdsDm@+Vpw?a?Vj~3FIq-=`NSsMN7-%6UbXv{g)^no z^1oxenwA0=fc$4xs=d@%`WcH)GJm3pS!O-{q_a_uFEmbcAT3xylL{=R`~uWRPwo$X ze$H~72=5(R=_s++83fP9siMa)` zzU0}DUX*`1$TR~erK=M^uEcpy&Apy}7WQ@e%&IBNjX8VtZ9u&8U$%9T)|Zq;oOQ{| zTn^r+Jzs7IyfIh(q7d4GZXV(38v&o{cr2To(^ zyRr=7*L!$#?ln%rmN;>1N#<(aY>VbqMdV*cTaTV!<98H0^eE3w?tC$4+xh+O;R}SJ z^6%LYZ8bFZd8M=Fi@CSh_P4i)9Qm{D*!l0Y{$3P$5w4}2I74=}#PQny*;GDTuVRGI zYw6RX)O}zxy-#x(XV;}qq>=px9dTt_kJ>LkltdV0FJnXH7AumzkP_?BM8EGK1~NA9DyJ^SO&@*Wut}pJBJo;hSPU5&!B(w);SROaEzkJ zH^ewidN_RZwIn*Yu{{tuQG=Ks0p>)>9wosUm2+h@?^2KGpI1CpEX*KPW;gks*Ig3S z$m=L0Y42M#tR||2!@qgm*SvA6$Y^D&hVB4F*R34f?IlU6X%YiGiD96`;)yCVQJ*eT zzJh0yT03(8qxi@)1^9EXBv$Pj*T?v~Z6EjELHC0mHBOzmWOkZDQxa@K-G9xdZUya- z@r%Oxy&vU_CHs>&<*NQjrMI-TuCMtP;FGn95F3wv>UYN%f~xj)QY}bFi3Fc6v$*jn#k<8`4D|rkKF(DV<||ZsA4_-;xUOWb z|58+(M_%RyBuc(_5!$)rswUnrSbG!fJ(?ix$rX4TiRS7{XVSvr-(fS_+6e*qmt613 z*#-je1EE@=fefwo9nIJ(Wvkm7jbQCWwc!*K?dgT?RR7^<*J0tG{jvB6p&;$loZ;y5 z;p}#8!5$KIj=lhVga&oQ^kjtf+HkscvhD&K=B65*a*kdgF)}8frc#o?sTE>JicPe| zMzl{dg$$L8b2mp`Mrm_a-7u`hdi~PT4dE1&P;+SS12lT>2f>p&62@+l2cww>F}!!O9Yw+WtCf3rt{} zoqQ3ls7e8yF`+14SB*S>%|Yx~R?OHZJ@CiZV~d~?w|0Hb(W>R*v1?1lTdV%sYt#k{ zOMM%0`patL%qHVoDc#%t22?>~J8Hwb#RjpB<9p0Q`!fa(Afm&41H&ca9rB5tHy^+2 z_5DzrxMebNYSMe=KLP!t5H*x_F^YcV*&U#TMKw-b{k*f;t7&dLblski${7_U8D+zT z;giINDq}R6@FZjLfK)uR3F8_2E_~q*Rng5@tHZeQ$~FoiKU%;dmGRs437mgrRAY-5z^M22Z& z`K*~jiq#nGx(8<453@6c*_*-~wrGt?#_kBm8jQ^tamTwz!Auokt_n0-CHh)k3I(-u z+WoPfTQDmS?7W9Knm!Z%Ab&5y*NPli{;9tlSsf-uY20<)}bzOIV z%fiI$+j;ou#wUI2p2!{I!5L%lAp6~vrUr!rNHvL-Ce@+d4nmJU#yK54++YSlh;bsEsdw{j~YzVB>gy?QC!McyH-= zZ}Dhk@f3z!3jlChlZL=e- z!{fuP6O&^@oqu)4|G?V1Te^BW{$|?#1lpQfUNpRDs%vVfZESefTvtsDi;tx`R`m5h zYHKff{yeU}fe5r!RhGp+EvqR17tnUAtgxuCApdb*Uf#opx!IXHIaeQ*6LpFi>1nBH zf8@pgrrC&6#khpT=$JpGik?Xscf%t??%p#<&e4p?m5+)M2@Cz3W=jh7{!6NO=a0hp zEx!O_Vf-JF@i1>6qF3?n$hhmDYDE|Ke*tY)|G6-3XlnOYUR+DxTwT}npM`NFMKyhS zm4DJ~w{iSIDcpf^X#eCtq>7=Ae|i;@q}7c60^0uD$T&*uUy<>@nYMq~6^;L8SB&^S zrN+VCg1Ox$tbf=Q%}|3G0_If?Lk(pk4kPQyEVPRS8&mco_uo7K(-;J}{@3~rUpWc;aHEJyg~uPG>}6m4ub z-+QN{mB4WfQnJo@=x;`;qE>pUXagD^t@MXoz9lT>ZgZh7__*gu$(v!gmzb9qB;hHJ zEv+Z}y5^l4fEL_!WH0B|I%Mg!V5Z{4`|%Jei)?pcZ22->U-%txxy3wr3J7?>W*DPM*- z*hkkSu~Xpmom%L|catlW8@b42+MDv}$+YBxTR61VdxHSrsl3UJ_Y7bZR))30N>5*? zuSAVr3cQZ7rtVu6w?OuB$o|fjA9+A}-Gdu55~HxFu?T)Yk^^AgZU=L5Yy$Zd^>m0l zrr05qi=!!m$U&%ie3xljK0++q`X0{Wd$R1p<5p~Q{4Hdt5tv~(h7De1t?n%(oSff*KyUyW+S^(4g&R^P;?4$!vFCR@x$tu^X9A4J(P{z{ikdy$qC z=f6&c!M~$aJSKmsZ{{5c3_>LRqnPyCw* zcY~3*Yt^16tIi;~LSnW~Br>FK**w2Ss7zR6lzxY#O4Ah+=Od0$oymi2 zOk6LVWHt4!8JZ`iuEB^m1HBJ>Z-mmzg>~TU(DvwfE4#`1%?pV!LIi+b;u*O5m zZgN2kTY-v?*g=j!;rSSyYG!e*t7)iNO4{+ zpW~l*r@XyDk~+-!oiAi2^UI5-vaK|IKQ5_3^(WOCG-IU~IW~N4UhFq}JD9bFUKzji z>}rOyvRQj{Hu5nur9?@q>?54>|VRy+COV*9J&l$Ts4E<4Rn9Kr;zEqJP zarDCXcEn!@Zf4|uN9XE~gqbf~$?+U*1AU26VZEwQ;QcgeU237G^cHZ&>we=*R0>4b z;}Xp?|M-%ou3a6{Rn)q#6*?rPsc%}Pa~wyIcKMCC@--cc*d?<~l>Ty0RYNzXs~FoU zfV2vHB;^~k>D0+!_3sL%y~xxzeuwYo^}{Qf-a|`+6h+i!tkpN7nf)DXg&45fhtKSFG~bFUJgdKu zk$6?^E~?y^{}r<`jYk=^rh+tOR#Z~iHc2QJ@R1>@2v4J?Xjtq4ie z;ZD*1YO8z3{5taG#wR7@6Iw^*lyj0tHyfh+51V&GSC5>sI>=CV+rftQreW4u{-ehw^|GejzzIiv)9C-2J|ssj9>Q6UKfW7tkVsNu&D1^Hw@=M zN$DQOC#?G*Lx$#8KizrR`dKF`VR7x!e(?9ugksa^P~4)|1zK)XGv0~fw~6v$ zqJB?7H}W9j<^ycdM&xHECZH0Ti;Dtpgyf>2x1yt2(IDO2m{0tGa7zrU>&^L!n;I42 z?sAcg80u5&+nTzJ@JUm}Q|qG&+9($oIg+}tF816#B)1|&csHbQp04@j9mnt3;Rmsv zEzw^s!Whxe6CGe9l9JpbB>emBe7QRgM-fl2#eTDf=bBKO5sqT->WI{Fw z0MV1NdRVH3b!gtvWl{|M7zImqL422xAe)5ayC{=TR3Fz#xFlf%0)DxL2}I50t(#$V z3BaZcER~mTg*jP!gUX{+An`rf&vovFIz~Xy1BIdq&<5Z{-(u1IPj(^l>ZpF=DP-`9CtXyvME7FRAA$2j5WKYR{>wPZE$fU3UhIM=-SY%t#vI|R z=}@%*+R#ntvby+zzqn+gliv_uDgevGsKAMsBV{h4I}=hwyfY{P1=dpl)c{#f(pmL} zVBj~@ixQNHL<1uT9=J&P5hXxG$ciSRuSs%B$ul-x?#9RF$))EEZlL580MDQYP!g&F zQ!zFvCH}9eh(lFrR zH`i%o8$hdSd7)O6NehY0gn_(GX&_S1t1~j&l?N!{eneK!H$cLzT$D-IePKT_trJDH zDgotIgZ+$r+*$azvo3f1y5`&;+a>vsJjk&;@z!Rlgz$=AZj~L04#$0t13b-0p+~B&Vr8-q^0NR(Nh}N!@mOO*&VF241+(;1!3;~*s^Jp~z-W$X_Dfqew#Ml;) zx?V_Z%q1m|kSrC#+M(%>aakyUCSWcL96U(AR zj{urt9Q4WdQ%_i4@eg>QkW+SD=q4zMHNJ|b6(w!PdcB+aIZE16s+wqQJah49D5^GX zGz4Q{tNt|m67Z{v002tq(WPj#^aG-Ls29o9e~Igop~fs_z{ zXh($!c>x!bIc~xNrIQ0gQNX7+^;XCxbqzhz4d~}1)vh}h{C6A3B%3;M4Q5_Vy4WVo zFHHCB0NP}4MTTaGWYZ%>A=4;6>QZ51snl(GG z3_rSNd;Nr0;9*ZCp{KTh_ZKBwQj%I63(wRGDx{JPi^3_^-EatzDZw(j?zq}wdTF^) zsJcBVr zTHHw~)>tAdCd5Ud?$TMu{JjU|kz*?8)sQmTAT-jTVbU;ANKt;bwfZ`+NSJJ1`vy;4 zc51WDpUx~M@8(?f=iS(ECO=Y$WzAJLZQqRrc1u}qZyJH7nR+eEfVz%%a7IA*CF_p| zA2NY664DU*VlO&P>=5M{>h-$>fImy;2U{VeyAzIXM_mNZ8h|~Nx*SRBJ#QJY(K6gW zqDVEB?ylxHY(f-Z^!1h6`wY4tP6I>2z-0pfT+ZXsXN=D75HsijdjsU{fKO}p*{~BS zRzoUG1k+c{K=KNKer0?PzYD9nqwi)++DDG=(+;x&e!hmLqd8aDQ!q_1WIw6v8wuBb zaJLAx2vU~z<+x(mmnBo~<$){S^v7JfFv-R{>CiHeY&%9+fiTtDDe>%X&C5`@ov*TM zoHzGtNm%?kw8EtK=BB3MPxz+1Vj*MgM%2^LcD4%_TO(5F{g#0k#G_ZT7dM&tAR~P| z+AvXaRKbzNF>ME%hDx%uVnjDpe#3Jb_u-8jBVp~shUofe<-n>Gj_mqg$pM>7qg`=qN+J9$N5@;0UvJr$->O}j(R7^A z4xiD@pV9A_G5lqtzB*&VF>7{d*1~btDty)^f7Y&JmacKiA%EN-JL!BWC>1ky#V9DV zuKpTT5c&IAuS1&)J`DW<)qbf#_a>!ZivVv^fCTG#<_G@NQ)3(!q4!q(SL+;^B%QB1 z5u;Q_-2CUZV{Q%tecje7pvDxWp`4#C4|d2E&QJO7r^yUj!EvG8{vJKpIt%pZsb?)`dq zd}-~gNRapnW3p{dMhZd}p-CTze?TYWLzId$A{I+4i zQB6*Y5Atl#71(`(EwL5YAv3R~W2y2^HwGA#_94O%xHo*pW(XB#fdXAoF;}$8`{SH9 zE?)1`EH{{H^{$!2Mx!pEtKSb;65kFUnoefo1zUOB?+pK$8jmT8Bn^Oc;vud8dFLdg zvu@j2ZM(96n-aN0i6nQT9(JR)VZ&|HxbDydka*QvTdD29vD;AW2P*W3pm)}xpNt8s zAHsr3tZ*O1T|Yz-e65&pJJLrVSRd|QvE0Rt2d1U%W~N!X6w;^thKJqTvuoZfcy04g zj4_|{V|l@D%Ds<|ARqkGKUPs&u(|B{cYl0dYwO~&?N`6mtRh)B&gg3L(H*(lHf|Qm zN#3GzkZ5@@=w#mYnyKUUf%wIb(MJc9<7*`;WnRXI=cW7U>hMdaOo?>`vz&}RDxZ?H z_T^7Hciw5O7|WEDeA>T9zg=Mdne($7_R~ek=Wnk+zgK~ZNF~Aopqsv%rz$*4#&k@P zqIAlCr>G)@H06w#U1Hi{49+Gi2)RC zIC4@Xc^eK+PH;J<<=&r~J`#5Y`MVqi0@Fct@Bp98diV)hq%6QQ#rY5?_+Uc}i-(li#O}siQe} zIg7MLkafdpK_DjH=~Ip)^|vQX7_x))?=9a&2k3I=eHW9Mn|1~QTp1wvS6$%5Z{l>VRAAyVRPlRmaDM^nY!(Ac2 zCclA@`}6Js#bXjhbkJ+{tVZxJW!Tt8d> z>?{pVyA(mrv4j_xDr1R~e0B_bqetLk($q<;CUAPVOkCgj#`T9?F}wtEVt?wNRDE&o z=f!cCddI+fM?D|kUg%Kld*(dw`>yS+Ppi_e@mFVE-hIf3h~;1#YO|Z}tl}M&k+2{B z_Bpe`o|!Ozo^_gD&gH3ex}`+fg$2t9x11o_Trdx4?`XG2`S$QWP{`uet#NiD>B2NA zACWP~P@{JlveoF3Pp$b(6Z)`*n%A|`De15T)Owr(|mzl`o|ai zf|b6AfGN3R3$5&0gHYk*Zf|HxkJ&vZN(jH%btg-pzxqu|0IDnjqt`W!X5_q8(VP)y zlDdxz`Xr$o5g!+O&03d)KjMsoys8%?Ooe#i7LLhcQfYFybM{Z{FlJA4am6X6=a5cMf(x5FobQk(8ZHOm(! zEqKyp&CBv1UsMJ;Ch<9kpLD!%?gLOc=7HpV9~OfK1>;=;?*)8#U<1a_KUIlvoiWYk z6NA3b5lY*&k5Low9F9Aq58+LFFfG5i@%pqFe#N%-poop<2PDVH_w_5rI`{4$JC*|E z>K>)F=Vewyg3142SItz})f?T)?jHv8Rl}%iKLY~~l`0ahfO0i^Ga}12=dDBWVl}p_40e}#uU}ew z9hPM_%2r&%221O=4O=;8@{GCwJxjRWts3!b?86!_Y1R)N#nI?i6QgRTUm7TV`nO{7 zHP6wjmD8kfb(tu4^$P)C`rgyFUOgzU{3^8g)o!z3zCyNw)!?H>fQ5oaiLasrH zp-}yXf%4y)N_H+apm`3_iq@SFlO|?C9_Rvb zgMz^BD2T#f^onUxwt%kcl4}8-okna-j5`nSD@~2xKss0wBI{tDN%w-AA`{Gu(n1c$ ziF7%mL`u+*Zf$cOHPXIQ3e~gp{&4!Jte1TrJf=a<6d9*es(ExpdGNiUl&A}}KL(Bi zUyXuaRInY5c!;m@X<=dr6O6qw++0gXG;ZhV57!(vFC@iZ^k+2)rhLkW@pi@P?|_(T z1+FRQdrF3g4a!$)R$N@P)$^Kt`vkg@7GYS5!6Z$2?Xf3_x_3?7`~9}4?kzjwf}Kdr zZ}lRC&#vZ0p(YU)9_v!&is8tIlUND*j7G(Tdyik5PFmhCTR~sJ2z6`QmrkePMBXO& ze>E%kW+C)|=c#yv&BU`GGnG1r2^fl~#Hbl{v=~Tz&0Vs@a65RsFF=m1nG%0|l*BG9$QJN3_b}By=v1mgoLSyVK@0Q%mdN zY+c~RZSg{YItoWtNx0+(TMT_NZL%s~7JIQeg45oh}DgwUq2k-ef()@cP`a z^vZFpt$0qRaCpN*$zD7T4HP*F`P^)?XH-9;_2wCH4pDO0EH7=IOV`5mU>7%K=U=h^ z5DIXzpZ{Pr-#Rbk=KZ|Q@spxJJQ>pWcE6HS>}0cK)&d-pW8n0S)`Qg5WZz;enOUEH z>gi$sXOqo+bBpl@68gWq??E1C{5pPs`kimUJgtN~pm#;XlH^zEUNWN{{nLDrBH3GMv;A_n5`xT9-lzB%Cs6Gi zrCu4e4;#ND$Q?)U!DTz(BsArk;kc`Inx>io%D0BB=MLk`8rFHP*ba6=_k4@Oa?+ya zhMlyfec)mAE4LKJ{C1wjrZ%wh*k`@+|7Pvsu!E6~T|`+gNQN{kXW1U4v-7@bd>Us6 zd_bHjCOUq7qQLIVtpQGI_xvLM@v-NjLY|!I>tphoN!qWhJnYwYn&NBgcCeaDsM>N} z-m(lno0m&(`N>bzYwPkHl}g{FY6VyA$4p49wW407ZE}!xkxG_g5F$j0G^_i8h551+ zHC785QRL`K7#!jcNPFya;|=|wD^uHG|Ep~r=>v;1rnP%PZf)y(q_?~29=_<$Z##Uh zCf+vz3%JQkFvleaKl!-=z9y$@Gq&sOK=SUVQ?y+>dD+mdl9jG61#6gL?k8}CgUI8n^~!0VZ_d1tzPApMlkd5Ffx-95S@(VJ zO6|`!giq1cN*j&Wl2EcfKhK3y(SdRw8y@{SctCbRP+m1bRBX-Z&Gqpg)^m5hR$O*k z*)tBE_p9fX^0|h8(D^EN@tI z|BLEppq+%C`bY_yCap%XhgJ~if^1Ql=&J5TcR{YJ)m3**x2VQc#-5CH?W^%Bbam03 zBS16Uzqq>(DqHE@5r)j2{(u@|7A8Ja_3#mfX744NLyG>oqB&lT1KblB*d0Cj3MHc+ zQH6=Fi%nDN;p^k&-0Hdz+#{G$iaww>DO5kO=@!X?nd_=Tw$wLUBGH+x5*DzHWOZqt zG{SC`!bN2mSd)W3xL3iOi_%byuT*1Ww^KQoQbsw!Zb3z5B~_MQGpi2F_%rrAx{*yE zxh1Tb)1bbcgb^R<&{?VE5rM*1UWTwh$d`&PHECwyHKHXT0{9lT8(iv${xk{9NS>zn z2zdu3c~mYqYY9!^pp}!LdD5d{oQWQPisqp0cCesSvglFUYU)O7r}p%{*nDMi8tvi! z)U-)NMER043Cr~w{$1&2>n4S(cS@-8B1LE3BzX46eAF8Dim}D_ftNsmB0BMvF-LDT z32!Ovw=P(w3`9rvmS^;QQ+k{fsTgDOG@L%~9?{tNwKaM-LrPlL95Z3c;thk`+&)aQ@&+oolE4GcCT2f|B-3^lbGAIG%T7!UZqbO-oG zS=+mH#+v9cgEG~R)j8AkX;>~!&(w}sXpFn2djJrfuW9Kb18>e_xp<8BCkF@~Gqv?H z8s0>E;&o96+=uXp2{(*^ zkH~1s!PwUSZU02}54X^1`GT%xovkWb$Y7g%UiKq32!Xg)%ToOEZz^VUbxguGwi*Ug%eJ z!f4YY)k=#}oC%ZB#ZfHma<(O!!NRV27E9~{LUoFn8xY}*21YO`jybn7%Xk^fO6GyD zeN${@v#|@7vG~Cp)TD3r5JF%^!(-5_4#|3bD90x9Dz7!%Cr@A~v1mc^TIzgQSwh#$ z{Jldc`N@1F!-Dg|+r+Ne33i(ZQJX~hg%}PS%pG%wbrymsRg80;X;4dS+mg9qSFC+y ztnJN(dl%z7hq+a@C!GPXLkkZV$7mdtZNx>2XqyG16qc1NR*V<=Abc?zWOH_IV`8(| zvxU($63-m7C0;iy|FS^clvw_vGxH*L0sJ`JE`QZFX7V!a#dv**CFi;rNZTUz&XT>F zUBqEoz|D!ys+ingc2PjgvlF|Z!lj<9Sm$M1;cPM$b8}nyxArYOCKuzA^6dngV~EZ~ z?G8I_w(dTU6)lgIf!LM7?3JOimEq=P)K3O9`)tYcJ5w8n>Nq;X877)o-n zB(icw3T;YCr$nM!F$zqHxXLB6TJ+eh_~1G%O&q(~B}!U87$BPvXGqDQlC(7*^lNjMi<(pocX`==<4{aO_FEoa+$m zTC<30UL3ge5rc7JAv&P z7@H3;WqtO3oXNZB!8iTwR__lz zqq}zECm-Ds8#u^%moc83vfvq=ay@NMFwkr-3V2XsI2Xv1?kEb;>~?&h4fTb3`hA*9 zF?M)G=G@V~7wx|@5PS8E{kjid+TZZy;QtGJ`SX7SU#|WIU!HxOBl4I35x)Gtlb7p* z|L9u(zdHrruP^No8`rDjn=5bM|4-q|h2z<#wYi>mbA#_@dfv@+ugng9oh-7ovP+q%2k{zfqW)CxZRH?81{x|;gh>WO3^gj{IaKjWLg8A^j zAecTx1oPINyLWB|2L#>r3m^&w|AAn7`+ME}%PDwC`7fuS%YSwX{u_d6^ndSK>xkV+ zCnA_!0f{KTC%mE*{ZXZA(* z^=Rd+`c;X>lzs8{*c+F6rMh zluqe;DVJq&^JS%Z^*vjgGM&t47Yq1wU!qH=V|04A?C}9Z;dBgwTdP1z-y%Ia+mN1( z#W!)x+Te+C{?^6J0@gr8YdHF-SW!cT@Dl2M!?S9Z=oGx%6xOYt3#aCcF!|AKXRR~M zzw6Za<~LbK+^8!FwL3e8)J@w(vlldIVhvI7WYtZKoEev(bZRP8pO?=>YhKv7N%RaJ z4!lbgD3)DRZ+6t&i~z@8!=Vr!SKagn!-Mlu2K}SbeOqmVOEgG*J*Scq9AkK-4EVrn znljX2)P1nl!_91))>vo#sUizk!?KXM5;cvhG6lITN2gqxiobT53P%jJoxc^*OtIDKY&N9^OxwzmG zE}doU>2#iGwq7;ngCc*2yx2M>Sd_O7ZKSew(5< za1F9*hwDdU?2&CWMau%}t1MZ>N1{r3as)YF;}`9jXGkl}*#=G-MJkY`bh^uyN=v0n zwmlhAl;abd%wndY%N1wWzbeor0WR*m(2T4l7is!^WYN=ik`sjiHQv8kQ6pJra&5|Zb( z-cg>&Xh*SvrvBMW9(lkdN1cP>&}+^P#_nK@P)uX}fT*z%$F=co4X_kO;4O(A}c z@6*t_eKg4b{QP)S?(_MVNgeTDUuUevbC&0>J^%G><@V=a-`C^Cf1hqW@caE^x8nKl zvxAqPfB(b}h!f7g&ifI5oql*u_ge{+=HX)m42xjagFTF`_*jXQBE&V_Ue+aiocw4J z_3go4&NFv1JRc6p%d*I}=9=7C2EBD@K#x-9#<88j|fE%T3h$w>5sYWX&+95Gy=%6JnK+WJ>7e1jMpByYm1O1YQVM($_&c{ z8AylX4~(+-D0!z5rH_Vc%ur@Q+QN{GLYUW6YgJ*kHX z3_~w04xuNM$v+@6cvSm?-duS=-@wkyliuU8997yQ@{MGXlRMh(2SP4`Hdn4NA8Q2{ zlop^AD%8`C35s`bxHHEV*;I2DUygVOeu865IAnG+j@H&x=y^!V!4aA+t}V&+==?#@ zNA8Mfo6KTWjDW6(G%jb4S9BG7O`|m<$*eUgla$3;$*MF7f($B^3*a%<%P1M_+bJP^ zcy$omU|boiU7^&!Z3N4kDOWssYLZ%IQK3IuWp`3#Ggf8wa(K2j^rYH_s@i5if36|# zq{h>z+HQV$?nUd#Gyl|ThY$MmtxG4hcgCunz7Nm8KFdadpfxV(B(X-!R!GQcwOb;W zP51OV92u&#vhtFO{c|y(oGnDiz2^|Be&| zdMQC66~*Qdw88~?Lxt)V$})ZEP0G+BpkrU)wPauD_TnusCH;=l8fM}9>zKjk_r7@9 zNBPS&JZupUzqu@bHEv!|jfxU28vs91DP^Cy`S~u@^5XKQ>`U;Q!7z@Z#W5~2x`K-} zo(4+P6wdA~2jS1I6B8ruo(}{*-t@WaVX*vrQ?{3a{E0kcXa>fclnK$@f7iz#Awib6 zF$OQ9%(r{k=>mx*$8eQl5Mbx(Gy6Mp1qf{2>6w3k2Ev~+kHId;4g zFl=_TS4!E{cNz+xG(=uf@)!_e0Sh6ds7<|DL+1KxZxMtSKfmT_eBmhe@NfkPf+|cF zjITD+Biy4>uF$1f72FJmuY97F6Np|H@w~f=v-jqjU#1188oKhn=GpY)W$6=zMJ1W5 z`YqtHMLd$L=>>Rf>0jc5a!l(J-Ra7nFqrO{q{XGGghaBe*TpLp9>wD{NmD5*ku0Mp8K)s%NOdX+!`G zb&^p}U!z-Dmv@j5;xq;}*S27V7^2P)m+Bs?(KYuQyek4|uF92%nufZBRqa(x|z}!`mx%bP+ z4Ie=LHb&+e$;R20Z9!7Mak%>zN>irP$ahH*=Or9b@@<%yqx-K#y8wc22m$)BJE`F^ z**a?Vn{}$pqp`cTTqEC4jlN0yU=1Tcmri?qHc7rkL3=qM-IR+GG-O5W!BY{Xk@r@% z0tZc~d*?0TJxCR^;6ePo3uF=yNlJ$e;PF66fgEyfi)8~DOpFdM;@Q1*fDAlMCx|i% z@5ky%Nth%fD`I+0Vel~?(E@neGhnZ90dlvI$K_at^dM#dMcM$6uG=lM9xAVwRA5)c zq683Jgr$%NDDOmP_IVpKS*buT=f)#0*o2YfVkPT?8qw^AmVjXb0$xZpfsX-qBj(LG zS>^9-e-HXl5gR1~z4s>4?If0x&h%k7Ww}fUxnvCGhWI2HIYOwolZ{3bN0mhL{%$D+q#Hsm$f%jisq;nf3O9V)Q}q)u)SQSQOGGfd!f8(7W=#bhZv)Po>C{c> zq*xsOPCDyQx-KT8I>3|`NeV8_AO^0Xm`pyxP=>TCZ`&LWzXiKeDHSEf9EE3Z>&t|q z&CsR+p%B^z~l-bzTT`I(P$iKahijE_9vyzU5BZNp3nB7N;g=GN+(96O#WghVdssdtGVfF@bOWUvhqwz?m3c~xD5g)wBbIg9jcn13 zEx>pMP3}XX!bC)IBBE45jp=E26$?Y!55ORbiDCKz*A*^X=?BjelMw+AJf~R05`pac zpfWv`E|$laB_9XfiGj@;SCks*5dtoDz0KMb1m>RRO9ww1EX3}-0?HmfhIA9hl-!L9 z$j`R<N-NY@)7j_zqDD6}7;4Y-(CTfC0115Q^TlAl*-< zxQn@Abml`=Drbz5KT0g<3kf!W?l9v$ml*9Nt;Iz~Pj#$!cCHfx>;bNf^kJE8YpE}m z?Wc*J`bnvkg-1votD+@ZLJzRgFUQ1`TIS?A-C$fkwPeTxz9w1*$B=E)|#GSRSU(M z0L#)htX4S^=|f93<9V0j&uShima}4OrmGCSb^#-yj6su{d3{UsB)K(xt1^<3_f>}M zBnTqhO>bK9;l}0k66B|kfX`X2rDoxjHL!EzdA|(H3;c7!4P^9LHha(W;=Wojbzm;e zhkV2`OYu3Cy^bq$J-vNBc@|?VuAarKo_)C<6kNpl(^8+MfycgKPr9DZz;ZvU!6X(f zw%;Ja)+nXaSjYNIhH$r$C<|0wF>;iU* zY$0_eCogINV_%UGNh*9;`o21AB*Ml26{6@Btov1xa7)o$b!&ipupR6=$-ceS1fs~xd* z%BR2XU+yFXb&}P;R-I}it?vXQG^drisJvBI?sgdzbsG_z zSMtjJ?xW}~Y_EWK-`so1W3OJ9^w;{zs>d%c8wht8DKo+j+6`UFXoC7F0-)a&nnYdN ztB~!Q^(6d)6vknyTIY0N;?jH;iVii9UpuQwJFC7!|0N8_8b#rc0$eBILAZe#bpJI% z`s*8`bfzeZxW|=2lkn&jt z4|UYR{qT^26?l@jbXrnVv-hw(1~gs>gZg(ho)6a|NC9r>Hrhwu5{L&%m6qEc)v#X0 zjqsVm=J=_kB>+=k^hrCsx<=_EbE8u`=d^I2FcSK+i{>ky<`asY0X0mzF&tnr?2GM~ zXlK1T*)6g`x~%T5^e-m@T@)Y?YpUwB2yGaS=3HXBTZ@{Mz(Uhl2ofG+ zoU@vlN5e2oIe`gbL}WqrX_JfU^pC_T&C+HsrPW>$6fh) zml&)Iy9H^-c{eBtsOgo9)J!3i+koxw0~&$}ymMvN726^DjJ0EViq(|j8}N1|o0^1` zymfMZFRUWaM~!wph6tji#8D4OP`DOS4B(v!?Nqe*nhO8L-2BCdtCyTbdm_2!3=$C^ z*PUDI;9mvadXLe3Q=?$NJ2LaO?dG$A`s4{zH>C$vKzS;nt!}P6dzLU+G+a_C9xxGcZT4L(_?*;51dK=AlcIF_)w{1H#n2XdM|lb>VN zS&BsbG67zrCI^8<;?(@A$zm)A<6QFmKBk@P2tEjk1gFEV=dX5*(fp7|Ik_}Xid>!! zSVLhbDX`QmUm!NJfNd(GM2$$6X}$b8L!S;lUZ>eN0=7*2LnjfCqlr_WbEA2>8$Ca=NML33RbkZ#AT zVgR9?TFj*WUKQ~vdQV9LsyEqQq`KDavGvoWd63Y!!(6n>&|PyAOLr>7$xgrOPXXZR=}*+3Z!Y-Q6X)Y7M^XsY6=0}J+2Zf%lIjZM(i zQg-joXx3?Lup|Np3=KuyX%d2x+3f|uXbOGhxV-2m;jCJKQi7_{*q^fg-Scs!?cowu zl5#f~-OpAme*kJGly-xf&h;bvHs`H7EGqX3xL{)ds1D|FX_qRU=6BseKUqC*dU>us zedHH0StMI_6L7;0sL(Tt8Ka}?*Z%#Fu?hs(_A5%PMlcq@R?(9l>22 zn@P}jeLtoRU@kP@qK;waE|%b|yb)J?a(NI#kV>A$zqTUpUp zCx|@-AFW)#js^+?aQk5O&-)Ysg6R_%DC%jf(xJg5@*}VLGW}?a37m8>-}j5YLtGuP z7ojqKz#jYV@|QX(%un)wr_Y=Oggua(sE0De0uFG7mI*o{toiEmLH78WnucrsUdvGOca zE?&MTq-ZjR%fF8BNkbcv9*&f_Xpm%D9Nd#|dSamS`2vsopK0rVhcCe_X6^$P)aHp^ zgLv1W#2n?Ss6n&h;q;3>@A`;oYvY1HoPu^=^fe@yN!TytfwDCMqtj^Rn?FD4vBf<5 zSK1oF_NP;jpIU2&mwOsi%t@;rDr3?Tu|S{O|H%5Y)9dhGzai{4Zl>;@kh_-2HOX&E z9&uhxN}hp8qT@xK-#oVca&>{v zP2c{2FA3zFVRGmoYE$09aEsHxow0n?4;`R0?Iu?#TDde4g~+|tjtGhizpGDrHqm_K zJ^>~Q@h{nTWG^`X4m&&HjxzQpY!=41a8=ETtC3K!3*zFwVczhPGSM55ot!<=l_Tdb zty71K&s4Qia2(TU(5O00vbZl{_|oGv!BbV@tizYvi$^64xqizV)@!r%XZE8Zep>Zk)rU37fYRQC_J#|gkU){i*deBEFveL*kon*PsDhT_GWxsRnPIJl)u%f$wG8b_=1 zWTXYWr-@F%I^1J1$tCu{noDvav;$d6-?yYIg-6w{j{o@RJ=mc_pwW^sZBIeaj301X z23PBFmB~yokWtZSC*(vmncVq+>ECO|@FDT3R!7SeSf}DVsvSb;{NS zFgQt%`M5xlfD4iVyx%6xu_Koi-N{)7ibRuRW$hd~Kr`*UYBj@8uESn<%nMhw;|%{g}`c}Q}EN#M4bLF zDp6_0S99!!KzWNBuh^-2a9w{I?D&0hP6*)rk5;s^0X$bUNN#%Z|wYRF8h!ma3ki)H^ciK zW5_nYekHGv1IXw%#DhSlipPx+vnLAL-9%dnI$W5-vF^=;Iis&FiI-CFELrs9hMY}TR2Z8P|lAF0hgnJwcVY%r9GFdR=Sd|?_@S@tUVbwc`XVlt3A;`u*FZYyjz_!rZ@`~N#tJ)h z!=*|GSw7AK5SXd%TF(N6%Ps%gYDGM|9+i|GDo!SWsJ5?5Vtl2G?CPFO0$!1Zq(G4r zDt(BCLAJwp3nlx90E=S^l-VVhl^#{X)UnWy-ZmM`2kOz0VeWQkEdyx+BXBQs>$g(S zII-ZKIK$Qpyd^T-Ne&=UTuQ!7F`fA9Y^y9>MfSyB*?Zea=O*ri)iT0#&+I;53mVd+qiE(z&w=?0e&Q2_xd zDFIQ$;@<1JzHxuQ=bZc8=l<*Wo8cd37=~e(VdL?Bz8=1bE^6KPbLI01!wY45ZY^Z3=Ay1c_1&w_8f@h)s%uGT82f?^Vx|;w}*6 zA93v6S%csD0>_GVISW`sSm5jCbi7k~$+MP5ISEePv;;{}QeOHGx4|?Y;)*DGn0Rj& z9!vM=3I#m`Vw6lVS5Ak}FrPJ2y#abM>bu6mOg*Z+_n+veXWc8ljfN015kyF$9140c z#8mj(3Spp$O`xw#`@$ZSv@zgDsWPklHJr-nTah~S3znd{(&SE0S4j{|$AZYQdZ zS7=2sTncb(N>abUslRgP_~NVylQ z$|M8Qj_T)76WNt;v9=nM92UNvi~h20b>(%ID_7E3oLl#YQocoJq3woHjjuS?x)?yz z{n9;^yp(Y7jnVkiaAB2+aL9qe8-<17XPLq!cUlR}CqMVQC|i8rnq&&>6X*UM^7iTW zv~6+TT1}(lJt{+qI@l<44icZ7EZbd_Zg`bA_V5?ewYc98aDgH|DkwRdrwNt!w&ZcZthuZXy$sc#SqsU^=J1NHXZ%BCQOu@66Fo3 zpFZT7DynR~RqK{36?>I|HB%$&*#|YBSche3k$2a%IX8!jpw&LjqVC93_hT3Hn?ZBq z`Il%erqjKvyjeKc7X^X|b|{A{P&nBAe(|lDTxtrkbIpOls}2sYRW|0Oc}4;U?mM}4 zk0Ap=6CUiIVZ!Qf*k5X(X+w9dPv|&vtu<9GNI#Q$Eo{ogVqBPss#QSRQcPq)>MG&u zmKm}i;SGnQk0Q^?A8~r=)dVdDtAM6qrVEb=WS4kU8l_!U*hN2OHB2ky-K!1d(0+uG zZfCmp>S+a=?_J>WN-bh~BH+{f#n-IMBcR!b_uZ?bZ(&Qn&U9_f4$E$(;MB#xF?#(9 zM3(!97E|1sD6dnjgSBag$zO|m@R0rKmzIywpPgUX^y=4;!$)o(J@D?ktuS!w*Um%t z%ivYn(bEEj?*3~EKiBtT_uLgvj)Gr=tQS^(or--J@RKEU?_AAhDqtf~k*h z$rU{^u01^US2J0>uIS-;bF*b1YxR*Fc9fULNCm2PUdApCc+WH1E0|mFMl8_EH@}PcpAC1XkcgT{x6iL9C zMS^(O`=7Hiur~|ley;8{Qk68@3@Cd77n^Jl1PVGGcdtu@_e}2;sL_Qu;ksmzO;Nk&6g4vKKHCJua>;1g0!BJZK3z~#!$|YK!}#OPVWhTDR_QpkOx4q&agB-byq_HT zQ<_X?npvEKg{7lKoLcvphDrp-OO3U>944Mwjg&`C*ph_DnvGRXsgMm#IJ!Q4zN{tR zO_T6*0%V0~VA3WH8E!i0nVA477*Aet(8fxUs0K`SHcxg9X}3iVb#G4go=v{!7Jf~n zLrO#PYA!P-rBk`StKUlHR_S<;FV$GW6eRmo##tag}XWR{ zIq~UvmFWfJ=~oWZi@wvZqo$WKbSKRF*-~4DL~{tx~(v4rp9b0CSayuY=-p>n#EG*;+tOl?sUqPmp!~U zXF)gPG+sV6yUE9=m+K&1L(p2O6jQYkAN~XKW9VfK?q=QE&F4f2o-<9NX$bLkgv0L4 zs+7Qvv;I{yE;m8{c^2*k_T|&um-ruG^z`LpY6{q^_)AI(U>J~f#YnkoQrGCkFG=U= z8_>{V>D*upTXf34X@kb9JPosiA}YmVGS7DnFu+uPpF#7f!Ihdgc4is2!#HN^Ia~Bx ziszh-o#EA@p_1;opDHo$(m*SQ`rF5Iq&11iylK%J^J1#=@5D{!Z#d3N_{~d3&r4;_ zOVbud#T&|e5xX03Ght~4q!Xoh17S(9;PXKbyJRHPJ%6UXU`P{N@pLY3sWrjO_*B^d ztx;i(kb%oDV2=%{OZgBdxGZ2$(*)clmRjNRGPXWS{a2TTK5nf!P7|tVUIQW=#!xsa zTf9=R=!vN~)z8477UN9}RE_gIwd2Na?7ka%dWFuqM!~5CY&UIUud3uMpPHI-Yhv=& z-Lgg2=38A|_}_?_x^LGPaZ(b7xVy}+a&2G9s>EpYsNNqovTm9WWNvkAG2H?EeM1)e zcke|@6npvo^!LTd?~CKh^S$5Sj(>eS`u(pPvj3CV-r9eR?S1`kH)PjF|8Kn4#`>F& zYqPs+vme)9?&6Kt+T!N>R~zr&{y$=`ze%sZN_%<#R@yrmOFtON{eQt;#YP)XQ127} ztJ2;-H)Q`-+M8(m3w!m=&9zL;O#U5vjs1ze`u@URUCq7Stvy|>{T#P4v?pghn+$+W>_v-)CAKvR91F|u( zn8>KVyw_jJy?=VI>mkAaNbX^S?*HYz{Qu^?{+Zkh`V)JVD9Gcnm*bzkJ?sCXw`X|k z_Dy3e9YaeU1M|PCdn*5Rb?>@=Dz9G*msbM5y7zbT6(=F5E+(rkCZj4M^`DS0uD@@{ z{xu-`&)A-U^FO>7{r|yxu`oSrC>c#={Uf&5_^%tXbPnbECS=)C+Eo+(^j>H7m3Z$3 zTcM*#oBPvyX|+_nik_kr>f*ma`&VpFyY*l~{cgXgF5Y|LV|!)pepl|quLA0lXxd#Ubq%pzX%}J zzRfYt$F>^&-bV7$zT>k;)06qgNx8h9o*(CLz&GR`rL-ySQtmvcZGVLL6+IwDb5*s; zjT0v^0o^nXr!=|qUYSy2lU8}=LVOA-Ug@hV)>QdgKdRqEDkT>5<@{O*@3V>x_HqYf zYjp-By+Pm;#2Kq5aTWKRi#TL~89ijDVy`TzMZ>1FF75C}i>_jZd+ba{bX>`!y55)!`ehAz%}G@GdKyUh;DffjpIB{}vB?^R2vjCs_g*{k-d zj#eaCG;0+uZ#X@K-pEeL;gxntE2Rz`$CY6T_8BzabvST6ALIUER8e`9U8T*CU{Ph+ z%D<0`i@XuFuRh%BTivo2gFV24PvX-tWU1JcdM>o7TRFX*WlAU63PY-orjqz|)gN?G zwe1Atf=K0G--D>S5p2~aX!rb1Ad}*kHm;R}FQM`#9le96lKj)>vxO{
    rw_N(n|} zxw!kdw)T6QB1*6JNT?^-k{#-_i|)4LCb=rf8>2YMbw$-_n$85P6!V_AltJUhSJ9^m znZg=ZCu8i)cK7(t7Om7B8`WVu3&QAV?o!d4>@R#DXfuRN8!lOo)*R?cwhj5JHr;Ce zsv={0c~7JilxZ#e5&(a8QF6E8lu{P8C#f5vx;iAJm;Lnm`4%U=TUw5~QHIAB#nzZk z1??-hxeeki>kU*YwRn#AJJ5WmiMpQ}^+&ksA#UMXiMQ!UIZ*tJDmSdrhJY z6Ncv4IizU^)BFA)VRs7NyKzrQVngtmf;`5QP+(z`Ms#zNQO@T6XdxJQ2 zXKzF+e%dkT8BYXG=P~!k*ABVf<%U^AR8z9cs1YMR4bM^;xJ)u%icy|jGgX$fG^g^z zxaqV62=Y6Dd6LZV^lI2nE^(la^+;raXta~}%7Nz2;@L<*qeBLjv}&0k@nsednDa5| ztU8&ftxT}YrhicG+vMN76R}e>h4uCtJZv%;x#_xe&72CcRw*IpW6 z{92FEt+uD1TpE%2+K`f1?ZBh`X2RlY;~%lT_e5bcL?{9Yvmt76^jjVh+op=^@lLV= zVJJa%=8sb3t{&*fh0A;cAkvJ48;O3aT8IaE6euZ&RIfx>brKa#1X#f|LVTdGwuf5c{rR!}Gw@=<7@Q>$NyfXEZ;)7{#& z+B1A__&!Pl=k0_=-P0CFSosV&_7H(>3WVY#dIdI0eNsX?{A2HJnzR!XZHH+yvh8$#bt+CS_)ZTG&ImwxnR;*qaW zx7|g}9iwBKI99rDfSBBWOehcH9=LBAz7Sx-!J-iyOZlEXxz2?Q9L<3wB6+`&#kxPN zl3{*_iJ#p6vWrf7G&xQ-)pF@##%aV;X0FT1``C=j{8s%_dV{;drtm4&*`aKDI~(22 z2PXFw;t05PKl0G1ynGxpM(vsNZbj|9L%g-YqwL3Sm0%yvNct3&7J@+M(obV~{mwVF zZGP-sFnw2zV|{jiRq}j^?Wpt%npG!Q1-o}6Qc8N(M_`75bL#}x90-WB21Pdw;BLGF z9Gi*uee|a;_g{Fl6wRM)!w!NFcC7$2cW6p4M{eZ|c8$AO>Br8C}V5cZG4jL~= zp@PF&#^r)a;v?%Jc*(~4HYz$Jg}ybG&f#iSC7CEm#3w?6kQ!1Odt4@w=;RuQCCNw1 zkBu8+fktvwL>(h9WvE&;`I}gMzKu?u&en}@BQ_nyZr$+M++52K_`;Hu7du6;m8zoho&uZMHeUaC1uPTQ>u z*b{xyLaz|@{_;;dwq^}gA3I|zh=0_lOpC!pE20poq*HP=uebLr+?&odBsnGWgvV}) zHF||dRh>2M28vAW0qJ*q-t1I_*mfD|y%XzYP4aM7{-*b98ai}H#4xOwB1SN9Ka35- zkbG&B^?@nJBRI}4=odQ>7rd)&%xUsuj7Y)}a|r)^4Vk5JW-4>G1?RkLf9i`33%siY z{BWYWp$^Qn0hGtEraqq$0M-@@J)$>?2(x{wW>!A%V9J4?M9M!+B!D&mnDmrdB9|by z^GZg6Kj4CM0VaF^?R!1G4Mp*L4GiypKwKoBLLZUtL&t8Rd0gvDW5!@z_OQccmhSs0RaOo$Zb zj#_*fhU-~7x&RcH<_wG@+Xb!0O=cN+o)l*Q}2v8iL&;d|@Z?KyIH>4Ha z%#sYuX{SV3!Z?6Kb-*zj$Yi%w=uZTnT(hHoa*t0r0Fl;(0al(NrQ71=8}82T7`zsJ z?DVhcS-k`EUhBe#yJ@Ed4_z|Hn6ZCZ(xA%z-6vp<;N(dQ?Drc}kER4u4f<7uf@XQ|HHQoZk``iy0UGG)dVWw(OL z%$}A76qhLmjESfJ+R?fTu+{jI()L-_-hFnWXh zIZ5EYOL^QvIaUAFDsG^9yWGW?ejh*U7w#N$8L!LBgGk^9F5gtd(PZB-1R@#nhuJy} z7XbZ)z({LlV`)V|B=CK$tQeveHUS9orxKl1R0gRAFg_1#scPmoO+xwr2Hv%^G9v zhD`0IMeTM_?YQ@|-Ok#Bx3x##YmXW0PG#!OEb6{a&@ve5o%5@fuG2(!)>$uTy#m*p zp4E{@RFMd%wr-TAKdml3i`EB6&`ut@_KwgKYg~qIZK;22Wji9gFNA-itf9 zkvFGNS%#3OkR_am~vqVTe2Lw{s_ZVADy$Mx<0qY+K>E|uieF^Qf0ZmIPoBOSD0J-!^1woBs1QD&Mw1EVU;^JH2tc%1K+yJC%^Gc5p^3 zX1_haq)kMigYc~Bv9@aJJ2~1lj0dhgyNf+ime%okyCIt37AtuVz7s`2UUZ+gP@A^o zDy=?1-s9QTc9pCyhpWMowkd~3fPlPRwp+ix>)5XI?n#%50cjVGqHB$G0NcfC+s%*v z=YGASp1WQx zD0~|efGQ#Z`Zdy3Y?lWCk~o+Zi_F-Kf3XzaA-_)a2_KI{!gD+=!cxhngYl?Kj!yQ4 z8(t#ekrIB_@fbe2MpOVIZw>DHI@y1>VZha^b^AG0lqq~K1-7RTzhuP_rIL{nkaYp% zu)cxUh(Sk0Dvf3Us`_Ij*#=0#9k9>X5} zr0`+|M#F6Oj{9)9aqLgUpaVqo8vc8YZl#bX@sd9h95_W1HytQC1rPDq5th%wiR}hk z1IJhV1}|-^2bpMFbVdrAL8&@G>snENm>qtXa|Ahk89B;K2);xOk`z&7-Uq+<2|rvT z+OQg0_)K)X2A_}v_H1*u)+Wx6;UK1$#{G>%=ov4A=__6==W;;rTG6nljl>k}@;Hn@ zo{l7uxk!+zpdR$O5Ju84>74~5BD9=XhQg7v|NHw zf7Fw6TPuNWp-Un6g15mPsQHt6P!;Ql{Zq&vvAvpwef;*S*DT9A?aA648`O){VW?5?QI|I~+T5-33VsrSB7c^y*utWfz)Q~9q@Td&BM zCUEH;0uUUOHNo3kg*ux`Gd=4`J7NW!eh!8 zZh+}^pspL#hrGP_?G$qn$Oc#E+%|Z^*pd z_WIx#h2(86&yCJjv1{hx$Iwe#I5-s8L&7in8kXl*A)-_)tJGH$X#B-C`YV+}uS+g* z5x&r0ee!JTRekTeSov*(a(a<+?sc0~qYup|Hmdy}ko-1zufRKQz}_1C3?Nx6DKBKa zLTs0hT3>4t2iUJt89ro|Ns=F*=I0Z7uT*PowgNYXPFn^jM8rGrvK5@Yp_Edf%AODc z2_Qc60d7K69>1wRn->W5gA20NtY_YxauH5*0h_FFm!B5zFQ+K8m=#ke7%^YnMhA-5 z0uZUV_lViuyJ%`n(T}DMQd7>KJ%%0YC}zRvlam-zSvkIC1A~Bs zy9=It?Zrs+0O)(Yy{_BGB-pFiG)cy0X*-zG=wyeF~!S`kb{ zXndbTXU=_xNR-ZuNixl>V(55(D846a)UBi7FYz^Sav-%39^es#JGNH>VUzX>o>1^Lx4Hqo12^~+_Oz(z@L z1+malqianXZXI*Uh~HNxLcAwRJtAK>PkhO^zH(#YN%)iZ7rio|ogPg7C&v3Z?3;3+ z7u?@V6o)WrO`Ekq1Q5LAa<*aA5%-9z!KQ8kajbi`(*duio>aN>>&GbsTxoaZalCxn zOU54UpC@k_x|3BSS$`aM!usI~*DqPNvEK>W(4` zmtT{7lkUy)kRLufyZje?0~ePi`|pB|i*o_e^6vx<8f*U{wpXlVNU1FS^v?}hd~6Tz zy*4${xOD%F?M)<_K#JKx>03HaZ^+h)-2fiz{^`9Kjd%5nS*+=P-772NF4fKRwo*HO zYgA?OH}6%h4!7T6q;sB${B9WcXKb(4jXdJY?yDL#A!2$Ejf(qPM@Oie(&<&RV|;Ay z+TxAn*=3YZ1eIb8lliH`M7S`e3jR6ee0b0ed~DC+%y~{tQ-HSJK6PsDPw!>fdbvJD zZ2od2&+^=TRsR0{8SNAwkB#BPYwAh3=T>7C^o|yS$4pC`ukf+GeC8Tc3zBi^MV8w? z15WQrW~dk3{uT5UFfoOh2;B|-{^juf>)kKswi2ZC2BUv?uOVTv9kQm`f-!pi1x5NR$+@G4??$5={BUpxKi2aF!VbM86v|&8s$VDK7xeUJ{8_|yWzzS=T)2xNp z?YS!;Uv8dgMr<5MXo=tH@*bAlk!#TA{kVB=s<;-pDP=g*8IeWz80=6%aZA8Idfn|<38G&ULE_bt3-`UO0iUj-T# zduKcRs?(G-NO{i6sLGhtM%QqUF0${(4P%(L-yx9@S@ax4GM#n;Yo~Y$F$teCNV8Bs zJo8PpMVC-5JNH0ctisP0#-wdrRV8n;Dev1O7~qgoi@@ml)J8GT zxlL<(By(c@0AX2NGIh5?TVSzPwwhGPs0Jb+b5wjsz{>D2f|&9vtZ%}EEMzrt;&%?N zkCZ4NRhWXDHB1V)*}ZSQ@y*=!_6KMAFZ1DIn0MCS4QnAeKqKYmve6od?pv^^?T5HEe}m;*d# zIaVR+`PeV?sI325Bdk5em6DSfE2SN|Mo$A&7m}*tnCPqhdoFL6#duSwtf4i?2QbJ% z*6(JcGEW;`e5nu?Bnq>mwA4@8|6(7*nE?ImIhKy^3Q**|y>iPHslvX;3hOpgf%=z6 zGI!n$X?JE%=Qhi@GIH#xIkmFENUu7Z;Nfl+g#lAjWtPzD-M9M8xYP<7nczj5xcX`k zlco_qP&sCWJ6v7#d?uEEL79}vu#PJHrXB~vUpASMu)P&iRgyTpS$1WVebYHbL#Xj# zk{p7&w;hAB_g1-`I>;sehE3OXF0q6L!E5l5!`ONM)^k_4EgP+AF@VMq0=c7Pn?mmK;-9T{Sa z#0ZRtzKV|vz4e7rA21X`%=nDAi9ZXo__-W2rLR58cqQz&?-lQAmB`$V#c`AgD_hy~ z$nI>@u_)>?G2LN9a;i8&gN(XRX=j~?AhWNO6ZMw~*4h%6z$!xUIqh7QMp`nB@Iu#QzNXx$Ba9fvp0zkc>&Rf+?}td50~fcRt60Ry0I0m zdO8M)6EQL+!M<6_k&r!qTA*OOn`kff zt|{Tg;CrXH#^1!9q??FhI-rIVq;V=- z&DD{n{#|brDY?O;tqV{9bDALmtB}PpIOAVgCl)3?FF`LA&WBa zr+rk!*R^~KZ%una&#)Cg(^S&cAKSZ~DUa-I%8kB?@>`rna>!E!wD`?$@O>_SF0dEv z$|38+bwhovMbqFagEXh!7nPslJGvf&i_ea9Gwvj&sQTZ1nRDb(ADOq$^2uUxWMl@F zTC?Y9qyA?4p@v#fD3kR~*$ymkb4zlhgPVVs!mGuvna+oYbIptI*wQ3A96vbv@oY*| zyZgH?F@K6q$XPAOKJPgps(ZPYBYyGqJn3@kyI ze9@m51DJ4x(?TS9r>CkzAv-EN7fvA$&ES%%%*2|bGwDfGI@cTqQRd(MNL|zQeDmmL zHOa4cu70U}R9YE^@G@yU`c$snbHL_xL&@Sdb#h%uxh_3qPFLcz&7boS`X(mnzNkkR z)_6GLTF`r=Q`;i)=;NH>6C;d5;Ba!(3F1ws#+2Iv+fBn$;y~#+0pZjaM$ygiWT_Eh zh3`p2J$!48eEW`{`oameJIJJ?AKn|dJbZKhki*1u6IDAywfbZA+kL|Glg#9dP2u+! z=-GqMH;O5gwO??|w*6MAC+!h@>}rgCorhB$ zytLWomVNQ_@MY?E{{qz=dQ8v!i(iwNZ6i4>abI|0lAZ=C{0fT56_l3B^Fu7#(FGM= zfiFm7rk3R1SaQ$XA?OIP6s6HU^LC+k z^Hjg^djGX4j6Sgv=%7-cae%`&KRisFa}&+xFz~CXgC}Dk^0=L^St;DCOTb}3aAANW zq+7^gK$t{XnB)m7qcUr5+mfvEk_Ixh+a2jw>h70w1( zbGjmtEh^szule>UsSK$c^h_BIsre46N2zQOBKxA)J^oEiYLGgNL zV1om&;U?Iq8Eo7=Wa2P<%Xb*hyv#C&%}a+ZnujfihOHKctv82nJ4h1`$}WS3qNIlK z>)2JiYHgsA2#t{>Gqvwy9Y4aN%uwQq@gotQwHfUr*;ykluC=P|@@cyx&&Sl{z%oPW z13nHSnfmIb&LX&gQO&>+fwTH=RG2xjxM#|2v~Sfi>qmk8xKJy${BPJB*XCpe!bdF(0xr1KVWf|_i>B}^a{NN)z~M2U)e zTEIk^PH6#ZqQG|IY`0r-c_P|bEpb;%i$A_jFiwjR(#Q#JN*HT#m~8c(Y>S#~&zS5e z{mXkzcIQ5;SeO*>8IM`h-qO}c{x;#c+1r;PKg8MRHKq}Dd_7iwY8I;#VH>;L6^HpO z*31Nwuq2@tCDqE+8UCPc#35KEju{ch#8;4%g(%E0VQ>esy$M}1B~{@|1#?!Qg#^h5 z1aTda)8=hIbm^P;Cuu+}I+$i+t)2OXwOpBPxxuYwg&ii)ptyn+1$Z|@;Uf)bB^P}V zqHwq=QeszN4SFjke2#u*E8X$JLKQeQvc1aXR*mfmeTtq;gwj9cVTpIUQNAOn0oWF zduh63X}W!B^53=5;zaB8^e8?p)iXQSGWqXmsTY5(d;U`!)%>B2S{qvbu8r^mpLMlW zV>#iok3^mg4&gUG3+fyG3vl%KPjFQ5*TyG4FqN5^8T~Zh;cwt^)!paeJ=eP~9!0V;cy{FA zVV$ z##j0rOU3`xMtv#V|2FM8og=DQV>AXSfB8h7;?@t%zfXHk7?)N)6O>lUi%-ol)G%&x zS@~<)lMmvO6E53KBZUPdM~31 zNAq)iNhKp3S#A1*cy{sR_Zq@Oki>U-TAv#E{GBt??nRdu#tBp`7T%4RbcSED-0b~% z^F1-G?6MW2Ra2u{J>C>U%l6}Jh4~=|-&@wBVoaE+{v*Wf4IC$AT9VoWQptl0rS5lH zjiR|Fl^#iKr)+o!Vy=w4VHK_nghTBra1S|2RSi8kz$Gb|kQEa|EO=H5_rTt~;zN>L zu}LD96fp;2iCdbc>fN^Bwddjj~QA9I9n5>dGDk75Do6 zIz?`hro`Eg=mN~mmBp{Zg%0`3yH_FmRs+n>@G90(nGzDks%%$vsR1seTp_p9(q7#w zSKAn`GI;oqlAli{C;L0#nh4osQyHe!1a43j$)q$>fZyQiNr$z7n$idR__nk38~uDZ z--A+Ag}K89x(T`I_?)yw7KkT92jrO(qh$^6v_X75RFk2b_p{)6?+QD?TRZr-$|OpW zTz6n3!f5E7=34aW!{;X>-Uiy5eMDUM5gnxAg6X}GH$kZl8JI<+1hu-aR)|N@PZ9Jq zU6g17*{mQ?%s-0-+Q`3H0<%3D4oEIeF_L#LNTVlG z+Ci$-h<*V>9sMb)a9z#CEB(4DqhRRp9=cbe=6uy+>#{ow{gE*--5N#VaKlI`eOEtQ zX&yW~C|neZm~*92+03QAw%NK&=LIub4T%*BGRnVM=AxZ=hsF@bfQkx9P%*Pv$(Wkf01(dl9f8DfJ{;f@LUGFQX0ou=d$%+QE?A|RC4hsbizAL zhv+t{WmG8}WtXNa>nT;N_)IAay&-#4Mj=`LWsp;fY^pGuy4J`In#|OixSOaRj*%kn zV%|U`gnbDZL9lJ`ypqyq<##B8OKXhGnh0@^T56O>WMv97Cb930n;H1zxD|9#q1!+=wX{*P(TX1=nJivNF1d;Xg? zdUlrg_>XDN$v1gQC3+8e$rAQVg~Odanki0Fl`~qw$)MIO-F|#)hgSa9Q zcBKS8viXW>^n4_DoX{HkDb5zcHalGLd_zS8t{1TMp=q@vNF@;J1+vIs1d<$vM!xAq z2{r9Nc-frL%I8#{|QS80X>P2BtCU=cy#PIkfpP1)R# zd#RXMN8Vn{jYjTvL8rmdydy}C(c#C4!V0lsb8>gwK?-EUU5A_EsrIv`ECu?);_9x~VSUA#ep4f8Zo2>MnQY!iEz|F_erVq!dJ^iaD^aY4$Ml5Va@(7QB-5i0Vcwfo zJ1A?RqsK(i1xEI}8lNE26)e8tw)Xorgki7kSi-Dwl@IQeUr2j5csGBhp#r;WL^{oV zZQCDU`jFi<>r({jqS!c~HXu-PCWxL1zKzdS{bE(S`F$?u_fg?X6*SRJAM_QLO3U<8 zZ8CJ673w$Jc9!gxz)he!ndK~h6thE3_;Xny@_(j0+-E~&hy{r zR^?IK@X6!B4KX&@OUxyaRUI}uOPRj=We|JsfX`bBlB3D@mPeI(fn9L+A9eKi1W4H- z>b9HYS%nZge_%6(BBKzzFUb;y0>|O+_;&(`oe}dqelwDRD*oYDvcefPd=b1r^%Iy5 z5B2BKU`h?JV#*`>mPZ-DL)zJJV!N=TQIULd(l}h;%`o6yITevUfs8%@zT5U~C%iiL zku)!G6Bj7I<1?o2t3m&WCj220I#?AGLHs3@iw(pn1=!I?GL`w;kQ3l{IB5Su}g9h|WwJq&~%x zC;T&#fH({wJ_fJa!rvW(NY)7l2;iUVDa8ORy8*=-K|)&e-6A@KIVdp5%n+&W%^mBV zQ|N6x8&Hr1#5#NHc*Rqv#%nZ?9}z%bAIA@w0hw#?+AvUmAv_$Z`~eA0u7|#@C*WX9 z_|WeBbSLVeYA_K7*e--Ddegk+MJzj0R|XK&FF`iUk~5G5t9`7m0VojybXf=@nkD%S z7?2YZk{<(SSuXmXv7b!M2tjGO>nz?zOy|eYj{~e@G)((p{KR~~A&QkyIhHmxz8?Sh z2h@=Q$tKAtD1q^;oNd*b$x_%vvGIPE@=9_DMEfr2zkP)RXhWwX;sXF(Y# za$UZxeQGWg}w1ljL!qB~&tDO#F93kpuSM_!8p3!}jOYtSLH!nwfPix-*aj|JIIlBw4z$+Q4u zL}9}?&}^PhmP&F-0LCz6P@*!9Q3-EQlvjc%Ncv$dNZ<)W@r7mrGN^c!Hr(9IgOCrv zN&=OE069NUJ5CiWO#q6^B43A&umZ%kP(Tw*m3@ycE_L``DKP?mir+6KD9%_be94d} z#0|RBQB2Vf$!=x9pEWO1U-O9rEWdO5f6RM#8Gs)t1*g|jej%t-Vg*+2Bw@lR_N0_I z){>5SlgUzxt`WlXaG)s0;>FbLFn9xmj_#slul&XZe^vd>H;=D-Y|SpanKFhac2KtUlUrBA@<} zu9frx5u?*KWe^i+NO^WGEWGxJ5z)O4yIW%ZxQ}vb4K!s7Ci1HLA(KH=MER|XlGZ-& zWWweADQN})FvvgHxX++)!DBm@}EE`1L(TZI~5aiGqVE$+Ka&B$#wQ5S5=ClwK*0*%J zz*3tX>;dJ<2rOEDfdHC`@h4dshz^0HFKzeXQ*ns1}o8nrKh>tF>o!r!>VP za0X?HFAcDxS(sBeZRYWPvW9C!T43zE_HT_;3wN?ein3bP#paZu`(e;84V145+xWKX zzVkQyb^)tn>ySBhag(%lO08QyfV(U^^QMNMUHa4+*D!JQ{cTODNI;^AKG7?IkCf2x zU6*YtT6NzRypF-40iw&jt9sg0%e=HN#(^pAq#0S@y*gBS(TEb;6WGx6(&)*{ADrt&XON8hzF$%H_M5An} zw8Iz-l>MxM5jxu~FD4ABHMk44CuJSufzL>^KbD!xuTF|-K+TTvsNNn< zcpbAQQfJ6?8bRNz{~VZ?dRW4iP5@q7)8VJIK~LTPf`$B|K;XEbQr=CVGr>NiL2!5< z16Ko`EZ|T*DAB+ff(4>b^g6~`nT2dRoV3o7I=*Z$5Yuo5Zse;2aJ~lP%Mk~QG#;n| z&EKB_C<>O#emPsFes;f+l!TEqIfRoHOICPyI+IOi_xQF!+3&?r-e>{_u9hhRO2PZ> z5q8>)uOE>TPVC$DM?w7xRz9eAA5y|67tZ`(aI8YuA(t{%oji8ht z-};H8lAooqp8dV}k}hwSam9N+=)I;IeG1ay zXQ*+8F8_kSJ3u=A>|dk5ZBDbgzH{R> zYrg&OL)fg!^`o_M4w!ir;Tka-w4~2-qjf|4_6Lbt>zdFHGQA%d=RG#2KT!GoVIr;9 zNQwJNiPuT3ZAnr2=J@s;o=7^{0%}5Aq~V*vKIGD?o1ikn4E-&mUcjUluw&U$n%RmN z-pl~D$xcYE>o;BW05w}umEWW`g@BDMiPP$J;-qa#za3Wv{HLU9`UpRFz~~Y`jkLD& zpp4K<4~TT9GML#7^dr<@*-c%gO77jxsQ;LebW4Y2H(iLjWacC7DM8`)kHjXs;YS}u z*Y~zl$vslYsuc8VZqwwfk_P{#=T0HdNFnz|lDGW6nFHIG64?vSrzZ!tuVsDGZK3F>P+yxqq@V zAiFa|+q{M)ZXj^1{{;6SqVmuwDi~_*&fbIgs#+Z2=9)6MBh*hdaTN zY|nbvAP@oq-vT*XVEfLa^O@VHY6g%?yZ}>tApIHtWzhYAZ^iSZc1LHfB74|m8WakC z?^-|?{y{+@?C2P;Fe#|Qf;;;Ykl=zdd z;z){To@#SAdJNK1ruIih%6a7ambzE|8S+A$yqx-yF(;$dakE-FPdU2;7xbGpN*b1f^FBBnHF%C&B7 zHmF~FL?SA=kzr3%KsebcqOw^CX4T*+h!WLmSNiaBxD?dBeXUXI%(F1&TQ)g}4_}wk z5i?=GS=6uN+Q3a9krt~KJ=M{`7RZ~uuOolH*>p3ynxI+10s4_{7fM&_JE5Wr3D(DV0SUk2PkaSBp5+jGW3cx&Ie$ z?->qfxGroD27_T{^qPzsy(fBtj5g7`=$$A*BuXS13`QTlMDM*tM33Hr=$#;X3xXiU zH>>Qm*Dh4io!5ElyZ7FmHFMD*(MFc3dyXZW`Sxc=4lHa5SO}at znK-hPmFEp*v5-VPFlycHO$Mlj>P1E^1wW3cza-!*sgj;8^Dcj!QuZS0iQ!|o2JdN0By%v>Hp$50D)*(<)TJ#BO@^nw`Qzz0tvMJ`X`k(QS7|o8KVZHfEmm-Y zDFEq?;eS!YB>klH#*Zd>HorRAiVne~8({Ei3l1qXll< z*F9e_Ikxvf5R4!Ev6n;YF&W1mLBA zZ-;%#T5ODju+~w0*CE6hoAfK`m&CKP)nasEa@OkIpy>~w=SR`s7 zv_Ul?sfx^}zUzpxPUvHPAQ}=5{IN3rE*=$ke;?a_H>b8=F4--DuZ&F%Q;hxOcH;da zV~DIWNHvTs3q79zPs;h0>9tvg^)geQJ@ zN%p2tU+FlA4gf50y;kN-cfyeOI0t9j+oBV(MNHZBy$Pw$Sa%PGL}%27BY{-xZe}2k z8qYf+zMkRu9O1HbU85qkb^2B6I&g*458-oOPvjmE-OtC@3Fk#ab8&7AcHVfK#~hT2 zW8BN6UpqrCv8*gf7~#u#Z1f(Y5aPV6D0nSj2&Yye?FCVr-5qF2i=*Ul!$?q13@2Su zmyp5w{j|%da&?1BDAJTUwR8sy>U7v1G25%AUr!ZqOtU=79IDSUsbNUo3r!qg(A zs(Lg*kx7CDj$CrC4&U=oX4G2m?7I$ZgyQcQa_E$i{c?R$y3X+QHM+P?-_6xtW--E7 z`8hoU5SR8`Tn^y$a!qG`8X{x%%k_K1ojM-Rq!zPf4mxD2mAiN0qs1jbbn#@b`wOFs z#V~!kum!?zZU?23N6Osdiy0WW+4THzgOS*X-oaE<%boMG{>~rslc*Hn+4kb$Rya{h9F1e})Q#{@K6rjOXK; zV-@S^F1F2$FRVx;{BlRUG8**qHfV&$r-`%O>nOZFW4=PLrx%y@RPx}>9WXbd8JciS zqp=wgpY>x~0gJr~orFrbB!7ZQy~`vdkGrc-;-ocGAul26r0jSgA;?IX_pEsQ!@Y$G zxV2YO(>oDv`s9Jq<-I~Bjku2mASzDVof3n#C4c)lnKvB${6=yvo7Y1MJ$Rp=b85I) z{7C1uZwwFXKX9@6HZwhiM*#<$x;pI7%!E+HIu7NKym{3;KihW?S+ETCDv)0MVz{5) zZA(%~!?3h%SYC5F%*6GLl^C(0h%1ldIsv&3Cycr&cBn zmY~EUfys~;Vs>)`AH@^M?=Pai^^tX=Bx}EPV8iu(J#J)`c-Wljsbh*qL2eE4Bry2a zUf*R2x#O2Pm~a}>p|F;wB;GqTlUbn9bSsl>p+36_bG zZ}?9Ov>0TcIjJ(E+m~J%74D#0J*NwoLJB2-J2&U4Q~A1RYd!M=*?V2{bX~VR!;A*Z zwIV(aSRa1)LBCHPNKj7&z7@O1!Uec-|KbO}mHzoRnfU7(EKluu;eq*ytb42CpCkKV zz1N(E(B8V`*H)i32+%;y;#tl=ysul~}cyGPi0| zsyL>3vj!Tie*>LoiTBEuDLGJA`CVqT$`t#X>r(J1scNX{xci;n7I={IVt=odXPBuJ*lAxL(G4LS7 zDt5m`d|h5XY)A4YhcJObj`V>JQJyvzO>2fJBp{#%7vrErYD}=@Wr&4Um!v#i zoUlBy<3YGptYC?ZU$}%U@=JoF>H&zz7iLZL~5r4GSwS`3JUww z34EIsbS1Mz)t3a1ed`-++!OI_Q4%uT7mLC#`xKI&Q1=T)XN{K41Vu}9eDtIyu|f2$ zKIxD1RS6pinYXRYFY6x!1S&}N2o4m90)jEWI-P$J-iUz)l5(WYu^$D$7ly*wB0%+b zOz>WV!Fb#N7H-tzCxM|k14*r_3G@SVUt3)Bao4_}k?(CCHG$07AZF+t7D**%{ayJ6%To0~VN~Q*- z3c5L6yY5U4Rknf@d>hr6#eMv1?Rh>e$$z?nD^MX6KJ*A65+3Q~mxQL4s);=MSOFpI z03s$ss;R~EgFw~z<)Uc>u884l<9qcB1D}>+6wB2|(b!>r)v*f5x}^F9n1azm#sI4_ zwL!6dtTbCd(HH=lNgO$rubyiiS<+TVeCoYfKKRhYgjj8j9v)U-FNm3m4_-rzjtunn z$+mBSDONGTFB3p59=aUGlIlN7%-(RLW_a>!@znUFEV z`(y)Z@wsdH!iA zo>b~3auge^9W|xutv7~Xy$MYAD5*2l^$QIk%AA_V3Ujxc3>`P8whpqh z*7Qo$r?Pry@j1C^L^M7H==gTe11f>On{ob`dR5EmMVXJ6v6E6E64e4)I8PJ0mSoe6mAhhp48FjXCiHXA)%oaS&eaagVdlEYP}v&k#jChX#zLV=R~621-#R4K`j5d(C|0acew}7(g0&s|$PKhlVqUhR1mbFo zeLmX)wc)n_-Pok6>*oLkvM?bA3h6&BYxDElxNXIXfZ}~1gXf@In&DQN4^lI&WRgMm zC`cr3g&$4pK*+5WUX-=_wj&%i7&zgo9$`-kfp-l-K66&7zU`;c8+S9w*|~;a>4KPN z!cV?$Xc^i^8m}0<*bH~tG)lG)gBqB;UNBloyx_m|QTvc4-0XN=2hA^1K;z@0ru)F**&5!)7AF|R@`AS;CJwk1|Y zK#fNG8*XkV1wnDCno+kS`+?q_=oboMn@(o!pJKBd91Qg0jyCJ2OcNTuVhx?m`c{*V zHh+dVn^mo+8E&RG?5h5;K@IO}tvLTW+%@>KD@n0Obnzwc&qfN@lY%WvNrydE_sYW8 zPcF~7U|D+^=j7$>Pm(n@D;*}D#e)ReY^zr+%!ETuo^X&WpcmjS3Nh;qD;9EFAkNVJ zQnv`q>euGJ<(5#;!6t=dLLu#`eI1;J1DRLYW)_RmA-V3 zn_P!SNt;*5yhKtyE7Oe`(v__qblp3gR6d+CJe+nooOy9L8+tgGd^lfpxX^I8*mt-Y zzk2id%0Lg6&38X;ITZ7Oi)1Y(V&yexor`2cGvZ4XXp@3uy9l=#mdIY7giKeb&OJhv zh98EK>^Eem0KS!UxO2FKpKj4mZaJMd6a;#aT#S->v_YSs}#$OY_|A#T6-Qz5{k z^zt}q?AW(3oD$a(l%NtZbf$&O`#m9{tEQmOe#$tT*S#Eq*0dA|Ho-{3qRIr*&7de}45Dmy%~xj>nEtsca|FX}CAiseHxW%YM&Z zR)y!A1BgjkSFr&kD`D$siIM++vA?a`KSFdVnB!1=5id&Oo~`rjBd@1c?$g6;-8UF< z#%Wu}7v_Bz_{|AVoz6oCLhD)1Sjk;?G@d8SeAg+wc;I{|R0C@k;B=FVQ z{(mHaw=Vx15_sqOaPjXX@b2{gFBtGNPCEF14FLDeF3t=u{1*UtJpcR1e=-g>9Svli z^hWQs|L+;#{J%56OXz>(Wn1S*KKv^N7?+p*8w1?_-!j0Rt$)eOw!HhBaj>JQ>hH$E z`o9|o|IPqs1%D2_{}%?hxh1Qn?q4y$K81Pz9GU$q1DyG94Df&B9Sr-6cQ6#!nRSRv z#C2wUU%u9iN>}B(OhVClazz?P1#|I7gE|2GVKQq7_e3I;FGZhWQo|W~K{-ZPdcM^DH$La5#S>$`(nlj^m zkida4U|eT*{+-ig**SNFO1BD`E$rZ)=Yf_paQRk!NM*iRxCfbq29uzzgemwfDZeb# z^Wm*G4;IWHHPvkv`qN#6lwR6zW4(oJhxwb=wkL3%S$DO^Yj!m&hM^Y&lRH-ET9)?L zjX$lvMSd_MyR9kf=#ggY!f9s~ch&usG55}rtkLQ&=3O>H*b_0E{rrg(x|`ctuMeLV zfx8{S7B4xUmmHESUievXTcE$lY-wo;<9?+9{^wcdLzy%T%ES(i|BF3zW3HFU+uT#Q7>k8nl8SFDI9uO?zPWZrDv}BdtS1rOI zBZF8z9Z*8}ldF`kajLgSYz;(hrtEYT+t2JCD|0z-CT*G3@jQR8&-pgs!p}C1@Gu;jBe%&z8UE)`g)t*Wfulr4 z$7VV+JJC?uz;#S%FEJD5?7xkmro7^b%pz5uFMy0oK0$ii(l0Bl>AShsPA4BXNiQLQ zU1wKu>~ZZ^cib<0qTK!XY)_$?Rz_PxLZp6Oq49;ctLnI>fq?EHQTgGMhS4cn)q1WT zXBBS-f9*zKI4QV!(OTT?QB-a^Wee>t=eELE_wsM;zb^K_eZ+YOk2`>LuE(9AI~B)W zV2Oj{Zm0_XNe{J=>q#%YW5r1yv(LdvKRk^8bbuqp^>mQCxZ-q(|HHxQC*gkn@5AD= zuHQ!_w=2Gn%KkX`{#l+_;A{**=XN%(dZ+RXM*<(7O=_zMoKNW+xt&iNJ64|0nE4!@ z&sv2ET+G>}xLwRU6<1y?xPCaiSoG)@__5?Y>-J;WcN<3n2mH7>{P6`vEO@z!rgOhs z!`!L5T#u4Cy8Mb&5p4Q$rL5ni(yCc?Rh>J3cVe@1b*fTfESK-wR$lZ<+}o0O-qH^% zv*!FYhpPTi?!SAZ|59yhOVi-nt+gYWhqA42$KT_Z-v4zN+_r7K_5KzTdrBCM_p~lKJ@}=1@?~BG z%OlkGgNUdCwUgaGyB&j$e5-CIpex+SS39yRC*n0_Yus?iQ@z$OBj`-EPHTfIh03{pgKX+#Tg?G>j zoKN4csvOGCO7D0u%P?7@EN&AXEo|~teS@1yy00h3)7zHe$3Xx6>yua%xByP9HlTrTPRBDu`W-H_XgPAGv--he!_>;PR<(#JXL%}cuFH$UQq#S zx`aj4U(+{o{o+L9B(9|^diOm3m>mvnfX_$(?orG06e_oI}0 zBKPO3Z0Vdqrk;T)sH^SyXSE61;-Wil2Ve^EXcReJBklQ=H~&0Ccukjd@09ECTA z8}&dKF<-BAt!MK04C-?Z86jO{dD&^c&vc2N^CuB`ejoTExU#RWY1pAmES;woKvgw_ zG^@ENRkW|_0l+K*bJ*xf01VHicGa|zVqCP14&3fAlZGJihD1Db{T&@ByCggFSxq?Q zeMQnY9D?H0-l|fHakyCkReby~kTZnRGH^_SH6cmx@mVB|EZ`wkXevT@Y7IXYr!U+6 zeH65B_$4sFr(1rl20iI!vp!MdQ{q&X~R!_!m9-J%E zC({w5tReK}p=_u;5tJOYEluA_5n2sdk(M9!i;XQa%VO%{xj$Q~2dcf|b%2p5x~?-G z)7K~*Yd}rrY^gEy%C7jgzz!V*lj(gca+U!D#P35lJB@LpKa0#DaYe?%92E()H4yFb z3Qi9Vm07}zl1W%5=)tJSOsRX1ywYd(q^;ht7Tp+>=n-MAt=zbzJ}yF_0I#uYiq(exur` z`1%HkVz~uwPJBSmHF00@2tv8{KH`Q{;m(gWF9yArAAJ1VQeM^+qgv^}$8>MxU4#8OCsF9?Yr(lY1Nry8x1s410^`M^rNyu1oT!ftp>M`zsDtQ!va&o%g^K#Z#4kno z8c}MEG=e=)0OkRyHJj2vAk9h0>o6zNM#*bOL8DYUn(fmQL3bVC8;Z=A(uwoaGYf62ix*Z(mYEbz)P|l6jza=R^x$z zl9N3cQd}mIyh>yBj8mSzOZII_36K)^o=-72OF>DcqD@jm{ZcV$sS!=7QS+%WSE<-i z5pIUGM3b~+zcezunAE1UjQO;ztF#=3^w)VQdEs(FCh7d)>19pn0itOYrExnK=^>NU z2%fi057Uzrk{Z$^Yq3dx-X(<=q}ACZwKPeJ4oY^YrM8)5%;mowPLr&^%HW`WJ7JPJ zb4iNEdn}Vw43FSOfzVVQ`dA)nDokkDMdS|1A`~OsbcSs+z&QZ{J^*5m z)vTL5JWib~I(cTIRYEs7)OL*QX-@VpMM7{b?pwk=6R4gr;l?~v?>M`(6aVQLnY#zE zH;xd>Ap%JYQ#^(pr$JA67%j%gco)c8u(@sWM6A4gbU8W13i-D^^UBr$e9ig1dxRoS zc<6+)q3M+OkWfe&EzxS8>;jqOb-t@^0seRaFKeMgAaQMnN!taX?P{)!e}QHhmjy4> zdXG{YNek2_{{y9n8`I>#+2m^S`Hu^eM2kf53QetY&2mZpctEOX$<=VY{dlg~0vRW~ z*od;ozKlx0nMUBIg8~n$${huLoI6nmH=W0s}k3`lKX-AK4moTS0TT~)Uc!w zf)gTQ03f4G)cY}wZw=%Jt~QxSN)QNE>nN-A=TKw>XGv3kyryWQ>Pd`Xha9qB9mTuHpu?UDKvy>2WJzqgW|K#G(GaAHh+JT`l8LgS zRkQ%1fpSd|x7q7#_!8$smRIWk6uKMvkSQ^X@d*NpILUYcJ| zs2v%>Cktv@HDo0cm6>Q9XHs)>Qlkf}MZhX|;LuDonCKH(Gq&a@6e6=xTXIru&0420 zj(>P_T!OQ`nZcn0@;V2rkOIKF4ZJ#I>--~Wsv(`SeY$}2J@p^y7K-JJcaZfaBJUBf znse@o4PT)zk^rx zpwndn34JFF-IRvzjMWK!Vr|&W@O{K^2n9dpgYN5tI#}w;A7f)C$NDN5Ae|n+G!6hW8$;t`^aydFWN%+8r4$V z(vpdQwlje{_CMbJUcnm(n3XRB;+YYbcd zQnt$eLv% zed}x=26gQgVD9Dm1nKnXRE?q)JLncz1y}V!IDeYEhEeU#UXCZ!lh3!L7lRORFN4h^nyaa^`oy@8@`xkw6_JmHAV4_Y0sN6;Rz;6 z-?IpRZn8+N$7Wn_c80pJm2p}JX#g+8VhQq1yD!-FZm2q7?Kv3`08jytR~bTHm<>DT_WiLL zNCTJ)kM+f9)6eB}Pngj*nlVg)DF@M}fx?=UW2ExGMnt11qwVloT?e9jMooi<&l3Ts z!zmbJ`LDtRSL&bbMMeR(qo)V001eu;j6VFeL5Pm!%~A?;Cjq6vc;v%;msTk0vDupa z0I{1G2{}w4S&cck(O6-^zDQ^wCe-hHtH}Fsfs-43%Hw)!v9=JDu-?{| zWZq9$oI<8c{6h&ANq#w)ijnAAIqYKz<)dhr#^IDGZ2H#t$5+p$U?*mc*y?!psar5s zrzYC%IZ37{n3~+(6DBJ2IjDvxQ*H2sbllA2vxyteLFCDlS>P;CVVY5aTcdJzQH7zt zm1{7iOKvU7I*H^32S!O)8spwrP!Z-ufy2+We1Hz}ovo z19952j@g^b@n$AJ7CCWR0az#XGR0yQnHx;bZMj4wo9?EKb#Y|bQg31r4cBH;3}i%>b+6cQH^%e6Xy>(>u`cO^x)W6)|YwnYmkTY<$-->uSA10zY^7c zWo6$83*Mk&-!zRYp{@C%9m6h2F$#p)tu1dd1#KF$7UH^FyV0UmEa{f+v|@KD8kM#r zgNmPO(qdJ%4Q;jzSnJHHww3j=6dX2CSsXr^G|D$B&<*n)wbQ0V>-^y@=2nu_17kmTVo45J#CynYh*sWt5@%03( zK$wU+I!Ej$%zo?g#H+130*(`X9~IyA!zE;g^tPuq!V!hT?W`@Ur>@^mze+*dwJp)N z-ta$V_??vv&lYEd*NF(hIGgJU*N!5mdZeD_Ie6l!eYwm1018GD>I(xcKIf2%oD#+z z9-WoDbxbI|ftqTK4pM`8j|m-)33pWloq!WHc5tm(BMJRS)`qb)Lc8F~Heon=k z2crg1)1;Hhf+M=IU(_en!Jna*Qc$-W>|UKFk-Zg>V+WDjSQeemVcLzPhVWUo(INiR z-}EQhn}ffkS$}=}_8`uOY;45LKl}JM4-_!YHOC~`3BH9$)n4neAZKbPDY9QfM9>IW z^!!KfAWa&7D`CmT-$-Bvy)B$~@D6SLu2)2|0BM`=ZkPQhS_u*s>0j}ByShahnfL9( z$^J?L>wSExYcPd*$yRTzj$Z%!NnoOx;u;8?8R&qRmQZJa;CqHT}Xlf zt}`q1{ASIn-kP8zv&FmH9P;QB(X9-@9Mj5>+uN@DIno<$&WkabGCsmImcs!$u$-$G zN1B^#-pl5#mR4WK-S7RyI~Yq6^y&d9`**kR)!O?Pn#d<^Fu)Q^x15k*HLXpHPitF5@~M3fnX zytLY_s53-VSj6_!6v#PEG>vcYEG2fw9xf2pSZpB|Hu2*&zwNI(>fbi}Vj9dewucM`OcltU8Ev{i; z8FJTfBOOyWz;56BzKje$^nNx*T@GYy8D@YapbzJKF(4(j1T}GV*(>XJ46nS)>KT=B z&$NodOUKki!)(md(>lm~$yi8AEY)GeEhGU%d(AYGQaC}kl{iz7_}&3`{|iz2CB_bkq3X?E%2ym9>Nlh zR${)OXY8dM(!K!ca#bB2!1RHOJ=Bh(ZW#xL*-T_tLnNWECzZ`)m99mGYy9d4i*CBT zpK3A{CrjE?Jl97J=rXKa*M_+)__aE98&2$}j28(fpSgCY95S~Q(K$37_R_7i7!|yH zI#s6#I?l*h8MR8*BG7XSzBrRnX|)Q@kLa_Fq8b@|FvDooQ`vg$HKeZw@-75zyW4%1 za#dWLJkcA4ZyBbTYRv8O#kOTR7LNsK(@X5ows?MUIjD7HYdrYsPJB!Lfxv6X!A5r2 zA03zcYV}QejpF+qQn0SX>+jUHKqp7xSA`Cg=1~Esi=eGwWaLm2h?$X-p560c%4Gf{;NZ36LavtOE#mKn_7J0$xyPGX`G^41vU zZSeHMyCa_f^%>VNv{zuyn85h2EY{TSG#XL znZ1+}5$vrQ|1_vTq4~L*<~{y|&K#>d&WaSeSwYOr(9N8ql%aHNU1F#mXQm;;qqN5O zL=skF0g?Hn#@z|dhWa^yS4~A)7hb9So}ALq^KyJt?YW&Mbzfqto*P3q#DkVGfX z5k2wmck!PsnicJiq|E82H4Jk~nV$}){fZUL1{X>j1!+Fc(aTB<4*_o1l?V4wMO2dY z?au^h>MfjRsjU}tF%4*9xjk~K_)CN#{uy~D1?d7h8whKB9fv3NB3A{U#wplT@kFQc z-*|1Csru_CZxLq*gz!}4G3cewOchD=I%~caNQhIBBD)C+i`syo7KACYbtC#+CGbXBH^ zk~RzhB~|)lYRU01%m%9_R=?o|x4dpO|6$_lYq4rNt)c^`dIi17amkw(ADUMPzq#CJ zusAhz$kC>_>W?rsq{; zQ`l|{il?3G)g2@XNECijzY@iIfQv*D{FHo3kZEaoTZJ_yJno|;8L_gC(zElUK7G%! z&RZSt|Cs;$hR8dIP|it_Zec8};W(lAKdag_q7plGWZOd?r(Z;`$R6z?3vxHCVq+hA@e~o z)U-y8i@i>u;Gj_0RBd#Wq~0{TV7;<4waUvCrpr8UPL2Rq4bI2T?HKJ)k3Lz-<~k$?cKS3o=> zK*wMFVzdB0g8#N=`1@k-*N>y?i*Go&*w61<*QdC%@e5btKHa`N{`xn$*w1fk=ifHY zzkNOWw)_8%6s!(huf0E8?D{cZd9b&3u(i0qx$t#&E6f#1tlk0O&FqEjV<(EI`Z|Imts z`Fs8wQt3qs|0oyxzW@tfJjHf`s=6x-eXDFABRUR5^U#TmIx@HP=q`-rw6k$pe9) zUZni>D1I9G5XJr|i$6_d^HZvr%gS(**yslug_oM7R~3j)T1v4NBhq!|Awi}pnUAJC zhi0KVWIfS8bKTLt_Bg5_An!1xkZ_{6F=P8AXoQ$oFh<08bfY6r@5`t;SJ{!>?S`A* zBQ+n?xtEu<}EMo+GQb0L%X&}2I= z>fYW?K317`w;<8*$!=k)L)mUo#*4k(;+#<4y^@0DCwrwOMYx(_MZ?}+IgTpe-LI&h zd9q*GxK*}a)q1gqqY8-l4r+R6aksnyuJVJr;d}cB@5Yq*4(q23T@K&RIg}qZEWOx2 z{ID9zchtC%>~hq!Q&fJ`e9*9e)NDQ5H9k1Ln$NbJ@F7 z9Y5ipq>d%Bw1K}Xh0dA9jnbY3JX0{1^V#^Ed_C-$WPT5rn~hjJs~f&%1wNl-tmF|( zf222(nCB)1dLOAr(EWY}M7W$VWEX}IL#jWVx;Ku}^)489?ml~=7;&Vm{gjj7M$CJe zws#r2fTFv_W5`_TCh5|+{QJi`2`f=kxQ~SX)kf;ukgRpGIM9Wntz!&yn+>P!)2mU~T^=~!9>R+eB61ZekhdhMqY(nd{ z9BR4+@k)KMd+PV2FD`G|zHg*F{Vz4c1_G;_-+-~|kJ^`CZg)_nfmW&TYd)e3tcW^5 zXgJC<{1J$Q8dw`5;I7bVYFrRRUEj-3gs%`N38fDL0fim30|(ANzZR<@lpeE=p;^EW zBrKo<%W`8$Zf(*w0EmDr++7UHn`l64r{vA!#x9z4TV~-X*0P4gj892DK`%?KC}ikC zl)4;v9VPOFRvo4}^o) zK-MTFxzN44I|^#}2#`{Uu`o4-nH6P-=tDwjXi&-l1%(7?2>N)OV?JS!K>Y6T@_b%! zd{ZH(QoI^7@;Gg5YL&l8YQ#zTUE0@yEvR{3CyQn;pon^upDg~N!sVElDf6~G1xYY% zVojnD3?;jr79Qk5$x^JniqB+xGpM(5%2wTqhC2X0V}O&KqyQR8SST_ca}3XgB1klz z;}#%JvUX~?5frKN#IK?Bm1qz(F{7pq30pzUo+ZFl0il^r5DS;e0SVzLB=Yve?(y?H zpL*9E3G9jm!Vn5Z(+^l1rZB4dY9xdTdO4yT(1(Nua-^atJOCTxDW?DK8A|p!o0y@J z0V|n#>SU6-cbbI8sy$^{qQQY9Ahbk909p$&0C)N7koQV?o__>5*r24=z82B)N}{<} zne0pV0JL3(OS$zGmx@;0uFVOG%sl`wqm5;4v@x*?aCY;28IMOTzqC&KgRMva!@D$&ao@>jdTV^} zke`WT!q1h6^>;~EeR;yltscI&gnb_56M7+Ni6#<}D)|T|i!Zu8bZ5T(IHgMD8`UHD zeMyiLS>2cVwqqYX-lJEyQKDz02o)j`VT53TmDQ9Fbwp*KIOBxHyyu625_#|fbQq@$ zL^Sr1dq)1sGmGe0zwHej02r>tgdrSNV+l+MQAm?Bjp9zy&JzT<6=3Cx-%DW9E9)O- z9+W}z%6|8$AC;GdkPd?A5*`v!DPkRcW@PtX>B}p+35$I;L_eE}605g3%6I@b{st*O zXo!Ldxwzg0j+T2Ep^{+`0($_dc8K&rT(oikM+03;jV2#H!#4_Pw!tPsJ4iIP*4Jn> z>cxOS46}2d6p9kqDK6~K3Pq}0!3UrqQ7;I(G??1`|XJ78N=Fl^8N?>NT+LfKT$(Tl`M9dw`ZhL^q!*RD?(kqw?ftAq^Xb~ zM)}XAvxMX4?@M(dF=q4cfeK1*!2HLmtwdgM&; zJQ^7F`^=EWwSBJhbZg^`}US^QxdW zwwsfCRR^y;b9@`tk_&%$2gZ4{DG<}|^^!!O&B?%+C) zP{*ZB`Pv9%o zo+V_rIc1r1(GbKom5}_Qu#NTQo$4=&y2cI7CA1-M=AP~L5?h%+N7^RKgP&~Ac1z5U z?|*(7vpI1diZN%4D%Pu0f%t7y2+bD?$?X|s`+Krj>9xtrT|U+-XE7d{n>Z3bdREPV zu|3G4K509)`_`5`<}^6;Q?|(N5BIv3tWeFqX+Nr((j)to?r`z%vC2xG?RWk{p0M_t zi`&Wp-w2eiM`ciBLhoN|t*!k`2wc7tn)!3Jc=PA-^T$6wZg*dQzqtX>qwpnBKw}h< zFA9{3B5g#0OL+gxqM-DF@4urcjRR?Y|LPZO)61)t$APy3i3?8`$)kFkOdId=~2HztFm-YmELXj$7nV{l};C$`cT4wUPwAM)O9YjS2Wb! zSH^=r%-cBZg>RT|YM6gxSioG^>&q|{JtjyJgEq#5`eHDtn21J9)Ep+}#z~<12L>e; z7C#^oXB?iI8lK)5o^dI|q#K$^&yz?W0q_Zapod1&+ZHrNqy$DB*a93qh*EYKiUuOy z+TeS2khOXcH8hF^g4d+3y3!Gh@tETcy^FE!J(@qk^F#Iuo!WI zJRqBp=l~Sm3Lw00+zan=u&q$^0=@!Q3dbVd?Gy5o$^^g9TKn_$&Nhq5CAUd zND`11x{-%m6o8-lWf9cAU0HoAhhzXZQwuFnb@JqMr&ElKfhBmMNhIJ{Y(aT#f$F*= zQKuTP_U+7A=HoI3vju9%0wrjSTuu$Dq6FO)whJ*Sa#4ah^0Mavz*0!)hLwsnDY(BQ z-+M@q<~W;hyqM1}1Lz6)adS+t)M+gvQSt!x_8uOv zK0hTm&w+$JMtCEjzgH;);HB~71p&FK79H_-@c_MJMQQ0J#Bs$n{tPTnXnYnZL)0L< z$Ax@n#mlIIRlEr5uMwq+W!{v4shn~!4AQY$$hltO%UzzLQ!a`Jhyj34JSxC}r4#Z+ zY@o_=$_hWcq;4c7Nk>uY0`%+{5^!9;j}OQ{hP?Ez>W~L>p58`dL*9V$yeIIF#uB#5 zpu0Jc^VJf;;P6_8YGHf;i9BhtAC82mv5Y9)DXy-`%jOAuAOI)3wyGq`%{!ELX8TEF zwOjSbOHpkMynTbhjrnmYI1-_KJ`NX3c?3XyGhr(tx1)m`H1-a~`VNVYxP6ym?HKZN ztk&}y5}8xqZc|H#hY-stAxQ+3;6yVWwH;9My@>a^CwY%u*yPawc^c9mllbrD^L}HA zoyz$lcH=nl5a%4wuTZ?-?|`Gwe4j^xzrO>^)8*ySwIStv+G$0!)(=R=kZCoILDxYg z*rxQBrnfR8{*jcg$aG0+8k4)KIAHe$0-O1BoB2AMdDoiTzrW+abL_C9(2{SK9Y{~> zsyC`LO0jB+CVLl;uipwpbTaX~M8dYc75jfyMaSFM%Rql5gl7EYS>a_Glz|B@wxUj& zqPiaC-F#|8#kC>poYu+sH(H=$FWZOMT85Y~a?p<_e7voE>66(>3)ghzjr_79S60@$69`EF2 zt2DN0FYZDMvA(7c>=MZB;**6w7@!m!eo>&ofdG)N*a=hmwTjqsLv-TaRNGl!xk^@C<4^)KH^cM`F&Tq6zXtCN} zVciG%#Amoe>9&N@Z{;B3XEr>bQapg^{_0BgVd7`IOWDOv5digBg85azxPw9;+4Q8{ zeC?(098iW0WXDI*thX(BwvpEwHRN=+5pdh`Gw59o>ZyuEIG4W>hkiiy2S~D1$nAvHVhZ6$(sC9??Tm>!P50B)f zvXdx|E-^+Md|ZOHt;&py2MxzjD?|>^1EM&WS{XfEp(cj53jqufOAIp=hDEJyv8lap zCr0Z$M~{~qKv@4s^#W6Pzu{>6QE zz(DZo^X?M=SFkR<8xLs(bCmIDhQjBBPAD_mjrhJ}~F zmF94II2}CMRdH8nS@f>kWd2DW4Qf>Om4MPc=uiMMC}4`S)3D`WYP_pOM__u?>yx1X zv&1s>|Hs&Q$Ftq&{o6=LVg<34*jw#Qh1jaGRZ+XNwJFts3}VNqTCJ^iQEIj}F=|zf z8nucJHLI#BKlgo~bDr}&=bY#H{qgsnj`!ND=~qlnEY&cS_q6r)bf4?vbf|@s&&>C_Q7e~+_obvvF3k4o6fZ6$QV)(j zXPVZD3V*pfR#i3&SOex&BovF!JzpI%L4c#Bpq-|1#ir0%qD1xsn0P)!IlhB%c{ZmU zChrrk^mXQC{dFHrX8puiNGGt!QP$HZKK(R9Ek?4Kb4F=zE~j~(B?$O)elni@{Y>io z-K>dvDXDbR1)+(#P8piYYP?dy!Ze9u5$LiAC#NaD5ErMhIF7DuTx1-%jGr5r9Yik) zA;6{j*Pitg9LRtr4<49!uwEd1&LI{81K(SjB|SXN*plYmlrL8&DCUoyz9c1nHNa3zzdoq(BB zy+%bk5GdHq7=OD_92}>%vQrB$L-$%gP+;ad$(ExPd=Hi4X~@^^#a|N6r=cj1w{coO zwO(WCu_2C()!+KC7Cp(hvZ!eW6=$Kgl}?yBCeZVJr0TKp90UeCZEk>op5dfds*ix2% zJMU-_<;3W0^huDWeNmFVa$rSvQwz#|H*u5>hIk^?lqjWDC3xb!rf*KU z?(|L3A86yWW%K%$_uK6`rUw_%U-kL657H?R^ohuau=&yV9EkF>-!N_Ls`%)t^f%c{ zz>9vjg(k&zkS^_)Uu>R_{+|kmcDi9d+5#uU30A>FH>X>6hwqId0!FL1HV?)M2>WJEQ0E=3CYf1_rt5P& zW@wqWFKWM9=SlqddicKS@Nn%=r6VGY_mW=(^di*+5G1x<^yWP z(aFq@k)W~oj>v}R8nJ#*zPw1E=LQvH7grW8Y=<1RGlQOynb-41_CHsL`axAYBA5uj zhSK(KUW%MbwgpZ6Vk2#xgb8^GlVq!QI7{mR*0|%`ZE%lPVfAArqV#F3$2xK3{o#o|4H`7jd#_KGceO#3)07#MxQ_YVxc1)RJzu)7c}G@ zSI%pOGb+PUfg5jr)xe2;KM&{YfJ^+B9e*7)pqe8F9)M57UQ{N%faf^{9ie5WI$}OB zhu=T(TV!i@xK27to%~699Ir%1EePem2tmq-vwMmewg7msP`>H&|4ejfE>?N#&?*ap zRWRSyWRNEcu)5y(SuT(svn^mumi2l9s1~h(tV`R0Va2`NkL-g7Dh@N=pVM;#l^Ywa@i!&B`CbHB50jBa}NaixRx5c#-RCCz0 zYQ;5Enc*nUf)q2&BG>IsP3GROR}j_NK_~#JM?t|n7h>IDZt&@FXX3=Y-OR}7B2LW0 zv?B=2=B%-(U}c^q`OM04Xb=ZCHt=Y)rZ-i+~<&e?S z2r5poJdAMbR<^%Fb{opwN0d!0En4k!EGZ*{=w1H2|2-U$`UZz^puEiLSP|6K#~S@Y zpX+m=bikE%)RG{G3Sq$_njUDMT|m+Lc0>JBV0tlUfwJx#7klL|Du1tD^LvjcJAq8S z84j7i4Iec9_0w0mQRW&4Q~pNZ_X2@|vAz?sKe)9dET6w|9R{`{ZM(lXu{?fubyM0R zJz#T0Gyc*WE_TEaqkFUos^m%jRnI8CD@%>>l+~NoIW8H4h>#ak+9K2=!B+>KJZxL+ z5$U*pFvj*y{cxt~uGZ0qE2=>BdQ8Vz{9@B3QrO;1M+AvP?HoJKtWCi>9!ZUKreIM? z+mjlP@)Dn=6l#73G8;$Vu2=>ts+5vweaA7bpJ%D{nu~LB{#X&fN5bl3yC?uBVXFL}>1%7Td!ZxVyqiRP@Ac7!{cW z00C8YkMgw5FF7Ki?AOwIV!{H1T#Lb+HwyK$YGs9e7hJhNsu-wEPb7u*y77E(Hqbhn zNR9xw!-1-XI;@j~7^FKtON-$z)c|Z#F<9{TW7#F|l+=(GcZ8&OswtI6S^{kntAVI- zHi0QU9L*tm`5a8#y+{A+Hr`(atbX|xAI{R)P5 z$fA*PnY2vJI-wA+mMrgY+(LzL!nux@~QQ_bXZzZ(MnSV44R`F%>3rM zoZW@N<$Zb~u6Q$@siITCHG@G{vpCMfC;UQYMrmRe8PXOP_I^^VkTW>A@szXWq-%R+w8*u-ZI@HSl zQHR=?JzgIJ8~nA_@@uX6=s%~S{&l@QpKd>$54a!3KQ2$7GvViHsK2oA_4mZh zna-`5=Ixp4m6^Vkncn63$))!bOS5B(v*U}iW6Lvr{|*Z$9{!1ie;jZ6pVMvs|AB>X zReOA@a{g4|_^I4}tITez%yy&9;p5-2@c)p8dhu>z@a@>Z1nBHX{o8Hx1LluX5=L&6A}}X;^O}{;6}&BM*p1&fABE!-h+s{_a2@P zwKj>lm*bx5;A7RJQe^I*hX5Vs!a#GO)N`R!5n;i1L;iWg{cFGt^uOij>Fs+Sh04=G zoY$dTJZ?I--~TY+0*)q0Tg_4Y~|(9xcTX{z$?OgOHAe(9w3JA;mu``e1Y z>QEZIEa^5-4u`6RZ|Cc6)AQ?@*~NFOyp-nKFwv~`7iNc?CDF@I6%)4-^6QNl>!hZ@ z=5HIiz?5_E^-=TbgN!0waT`9%ZMSHvUq0PWnwJ^LVz`o0A#1PG2Kgk+{r$Fci&q(+ zc;FqC-0In?+z^Qw^ZB5d+OV9B`?Xd9=;{$3Qq?Krj}Hf1Z+Bp3s3u~&92@VHX&uul zdY?v3?bxin$6s>K)7*}FTRw$9BLGWqp!{h?h@z-d?i0-CaQ~oN!`;BEHz0|{-=kFR zSw#M1LFR>vmX`4w!I^?xjj~}@e27}dU>6fI8^CHb_@ihlhTmh?(a?=9xJX;eET!u* z1vrd=zQQs$nId6xzTR>!uCBwP6cpACELG$M5O1NqZiq&BF>MG7Ur(v_x|9MfVopV{ z05NGe2)#cP?B<+AD30B*KtY1(?h+%5plOtiN+VBH-YAYdX4X+C^`qolMP)I_-emNr zb2(U)y(R~+K$uym>OE~!To*$8 zQKwFP>IMe0i^{}dorsQidVvd_R2&pHc zuxi|EpC0fqpeJWt$4`m0?tSAP7eMAEHJuaV+*Og9FcYau*k)~mr&lK%e(}*3t}uOi zk1D6yQ`dWPlc`t+LtA|tT0$o!C9T&X-k_+9d&se;eHl|p*s#o$hHg<A0r#bXLQN%yk8aEZ!I4S*#tKiN+D+pZ1TRk} zX+e5#z|8dl9Qz5X1vPwQOhkE`mcHo_L%2;(x}5l73B+ZM)fhokhz>wv4L`CvG9U6 zGGfal>sED`S1-k@DMnOhQl%{w(7mh1vc884=+_kF5JkVk>m9iCV1V-=hg;6ML3_;k znDa@0a7Imv{uPe;If93Ez8DOiHn z|G@e)<<*1l<(Y48n=X{kjfNk+$WJU-*D-lNnSInCYHVp>KKy>V^{CM|OXBtollk|g z_b-K2URC>s4$m*ytaHM?SNq49EUa?=XeM5+34A=fu%Y&&WjwJa_?gM#XZs(mvu|qd zGz~9)3;)r!O!qu&z+`DZ`$zlM<>%ou!%Ii4KVI!7KEJ3emz zXNSr-l8MA>I&B%VY`M0&J0nJc0;oAtj*W#)S#}{JE}g<0&|+(;5;QA@ybu3H)TTP( z)7ab2<-0Q>?q#=^AjCs6OkqCN^sP!Xh70-9)?jdEpHkb-^9^##_4~38_Puu~ z2qDXnh@3{NRdX8(8e126*)783-uyD0K1)$F8=j%-N_dk_Z`E{0`_77&xWY0<_}vK; zR@+n9luto#UK+<{TL1TvYU{?xcpA;$T72FGkFLZNFkjQgupXa-35*g_U31 z1x{9a1xtlml2O;Cciex^w*G+#X?tp4AR5LUKD{*norj{NyXbP*{=VMMM$#YuvEDMN zM8W=Ry^Z3Yjp8|ug8#MN+M$KR(4zme-pa6J#{@236P3>NDB(r=8tQ0rnmQ^-yFv|ol8)gadyo#)|oWT z`4IC=2r?6#83|650ioeCmyR*=1e!0k^q>4=T4X2{-JD)mI~ztAtp2|=94r1`P@4R1i#OKW}{g%M9w7*khVzr%`Uuq zCQT9^9FWNIB%@X&xSZrn z4|1VzhC;H&L0bjXmMBnSCpHTTIT9r>rO-QyMxWY6qhe_+R3BMgeS`u(I^9Y(&SKgc z$7_9xwp^z4VFXZi61>UN`#e4u^93PZ02!7ZW$AXaQ@Rrb35yg=vEd98m|+OdpVG46%M^a z4Qq%@1j>SM?K2dkGALKbd!P(cB9w>aj4udJHEh6ft8{1;#xzyv76J0n`pF%9Ot|6W zi&5a*NSY7c(5>B!^%mw0Z)u^GJaRYK&N6NCcgA^tntfHWUmSGn=jE?)x`kRY{)s$L zCb&x#xCMm-ayVsiV0G=VlPdW6atO0AbTc1JrOfXw4+;UUNQ zq3IoyWd<)1D0IA-p1f$Qi3SjrFBP5UeDYL3PCQ1N^Gu#BjgfwkT)eomqn>P=?WeKNmAfX_u%M8*o)I@Fi@5^)nYEX@3 z+V9%WoNnIBs->q)p<(;%Dl-mJ6@y+KV&Z@>EY|v%F|n5AgU-;Ps$EdbI857>Gkf%P_Qj zrf+*+X;cw5t_s|Y1gmC%<*k`H!f%21*!%4>%9h2V4=Xcdp>N^bLuB+0H+k>dL)XHg zt7JmNp(-?IStS$Qq%qA0clAOFM z-zE?VJyL@zBMprTnMpSp^WAGLm#e^Sd9);nS_R$u<$MN8^14d@GRityj+}r7qoOQA z6i2I&EIJ^=69OvK7QRIzCIMX%fpWjU-4_QXhC{cV@5q_F7;nv+60bEm4?8V4;M9Q9 zGQcKiqi&n;1qrA}T!R5bjHYUr zmim79aKB&&?8t(mluPZ|%QlqD-> zta)wU3J7Qg%38+B1;PTFXC%OI5+B(5i)t|ZHA#jxwX=OfhCa2nP)fXZtdMpuA3R0_ zzeOXpJXHCPD=2X}aZ~0AS6KTUb)bhBOOmxhowGq-m*9i=SCfy`v7IjjR$hS_9nSM9 z>A_VmDY_`foEf(LAx~O;x5S|c&Q4T;7yzFOb@2`Q z615G1jYZv>uWeM3WNbFC;hpWd6h*6?5~k(}e$z=C+ew=Nhj#7uW{{CncG238(5mP2 zWV-YkETGQ|Vm30s$M8PO{65J++AcWM29;(h(@#axL z%!%|+KXghSp-su{cVFmx6FHcr0n54niX*DePL}S{JE2NjF|?aR%~bH0k^!B!10eD~ z0QqnoH;jW5)SW`7W!abwXHj;kBBP*x?mSH40KW6e)q=|Wb(fSm=IXBy2<%VRL4oJHh6+e31LO09CO`I~68bGseHOQe5vakDW$ON_@sC%bGvjnRUp>@P zMrq8!Obdd)I9^5bLw{?Kt)K)iCst*>3@1h=R;fb+jpoRX9F596W7i>UyOt>J8Pz*gKo|N#uq=^Xc^8mftj>ddfheCh))kI)ob2 z)iHle`Z&+#`Skh&X!LF9Jehdtz6J*w=a42aS8fR)OXTkwtyBWmD%eg4>fe7bKbQBKk-RG%|GaMAB(ZE^!o{dkf%;rV#ut zsI=3B8Sw$Q!nI8^^xGBs(jO$HJEZ<#=-c8V)!t&8Vjo4+T7cv-qKoI=4e0QQ*zB^p zwFx-?1zmhFP3oF-t`3BvcqLR~{q-7rM~3c;5u>mZ6mJU6Zz$Ze6}7w1uG;%S(Q<9L zWKCTQ>NUECh)MxTqi-egq^&$vRvCsiZ-kw(**?YGIg5OCdECqt8ZpWy@j{TgtCyc- zn5Iqd==k+o#_m=I*#Lq5)20j0K%_L41wFM^l-#J}gERXGt-e&rt<5O)P7J7*e}$@G zi!L*RZh~y&`}>zAYl^Wms!pF@EDBr^iE=CW4CVXMu1F?n^zfzi7jf55Inv?$&E&%+ zltkQGf6d0G%Y}Qn8NEs9yroD>hqO%Y&3i8LrxfDVaJDFIUkST&Bm1EF*X;+g9PbI5 zfPMN)qZ@}#J4X+9j-T$Fyxuuo+Bti@MdH~dySNLuz6;n%b@kqbbnMc8*ge0%f%5J# zUE1Sk2aK5QvFGh^cI)92zYf%zl_&jCFxgE|0NarfUUs30dw$G{*fw7MUVZnNj$Po_vY6B*b6Gw0tjXNe z4wpGC*ow@7f03LIc8ucvPujAZWfw6+WQ&z~=-?Gll+3Req!Z1fpGcRvmpf=k6X^BM zuQn1|h4)l+wxahECMoi0U<|z|!@jtCI@WPIdFl6C+^?yK-?MqY-{khVWdzlxv+nlAweRbb`=#kX*jbj))2igzP z(Wfy{iZB52$v@l@GxwUVc06aoa|B5=s!<)ClH3M&dM1D-J5)Rl$NsC`d}6XHh>?rV zkwI)1Gs9$qKfkNKJ|NwQ(|Fhu39F(=aCUKSEgyc=EcPq>XnV2a`t0Ytj)-5ri=xi2 z-*9x^sIYvrAs*(+MkGf{`B`zMtOHS!bAvbXxXeB_+Fm!Bj072}dwAK!G&@I`FQ+eW z@+hSQr@@1@e-C6_f8M8bjnG^c9LMtd`yHS-=rb#y9gPL6l6&b^Og`t>UCLy23KoUD zdw1R`U4QUGbJ-%gzuF6D&9bUvJ+pN@z;lPzxU|KjR8MZ|>QPDas)eGnp>wj0XlPsz zuZIr@HY{Z@>)Oxq0i$?Z&$*Fc?@1LUt+VnQE9g`{!=&J{cNHFa5gAN2^38Y-p(JLt z{Q4XETDrxdoZtV%lnoHK^foxmQOcWMz~4Wwv|{Tb&Ar)4bdGWhtW zFOX$UEZk|6yZv{R0ma}I1I>oQS8{7IdZn2LzLJcE5+U<`O~a8G@gJW9UsH^G>i4F= zUgfvXmotZce9RCpWoH{>656~T_bNZ+j?)c$EYjumy`9AFS@_n#`UenUDtjIWz(}6Gi0Ah5$NJ?IM9HsjU3cI_Aa0fsn&r`m^ z>{p-Q+ZFvh$}LbT7Gy+zuZMYSNc7%S;n=cuMzS+_;(bF|?Dt~>KKtH5Ozmn!3$_&1 zESwXlN|F=p>J=vQchN9Tt#c%|FV)HQCfJK36(^7)hRCbjmh?h78cbNBojryy$%G3; zBwc*wPgBf-+!K<*p!7WsPTKdoB0GRciaX{|Qx!BkAh4)(kN_=*Yena$3a0H!(IlTT#n|0x)>%-!vr_gVLCT$SHzxiW;dx_u=P5=v zT{0b>8|eeSTz75h=w(xj-e*&P6X-kzTT+yav_8|X6og%%$3ym^n^^wEd=#7L^l$JT z?^TOv_+!^kpDVMRo$1Sko6usehE(Gwb>0~_a{zar-~C8azOk>`^Zd( zR^jcC&$pPSnTlITjmv`iEAx-44>ZZ?!FT=Qmm$)Hxmv%f3RiDkg)oeB1yFK6WGwk0 zdnYW?>vS%XOVBk576zeK+9NA5Z)3mS`x?gKhlswmMt*bc<{9{6h%YVUaA4+uK@G`l z@+@3r1oEEA_e$h4UVr^grM@6^t zM_Zjg@{I@!DJJK(Y~khI8%X*G6}0NaH?Wjlk82xaZe>|;g{Krr+B!bBuDI}8iW)Ro zqkVkF+<8CZ@y}IteDm(BFDOg^lq#l|el++(yk8jxBs$1`GeaymEU z?1V&7XzgOla^M2lX%OPrDRvKE!NzN*4SLGS@nI!kemhvH0x$(C={P#(Q{d-Jo{m1t0c~3XGcHY+Dkjle`#+4vWcG zk2MzUJP$y5dnxGS@irhqw4L??IA{kQGvCvO=~POH>=cvH&a>+j^Xe=d2k*Gz88y;9 zZ$YVZKQRdmKz0j$)#kPWsi>F4)>b)&$q9c2 z9r|N!BGvHYT~ACHCERh6f_VE(iiisA1NLYmZCUXI5Q*+4ROJQ!I8I6NEBlu;eOASAm7;1~Ceq5P&yJSPfHoCz%!f?ZJ3&x=7ts5~ zgyntTnqW@Egx6^_D_Gw;3>^U^1v`7~bRh?Qe3DarZ}4q^AR0^eUPsRX%bkP7cefc;%JzQQHL^S9 zI@!WkGSS>VMYpv4wBVX@q88-s26zqka7wclC z9iD0#dL8*x|F|Fs)%&u+q>WHD#gtSW(5})x+_6COq>9!Wp(h3y>1mI*!6s&|P_Qq{ z5B~!%}0pK z=%uPR^TB2vv2j}ob<$+2BO_+S7FZUMai^fGrxxHO0}9IQ-EGenk;JR`gLhnXUp2(D zI0MD%FaNkdDkj6g!DL$8iTNmq4;D2$bLX(;yF$;$O;M4)Sss6dT_7Hb$}{5Zk^zl_ zklE=kA-_3TR4D15P^hqv61|_3{f@oNE^u^+a_=2S+o2>lP0r5|>2V{h@7O-YnlDCP z7SNeUw=oC+55LG1F0zl}}A zge*u%kg5tM30ZtFF-giJ19qHVmXUgdsIov4z{jT|9A9JSH1LjIX37`9MlMk&4fJ$n zFh-B@y27RcBd|SzKUf8&MF*A+GnaTmq5de*Aa)83x2lsPW0C0<(!&>CeT!K>ceKZH zyy0jEoyRvY@??}OgpxRwNwKi_Puvo>PAZKVO{4CPqsf3G-z_XIfG=j6?I&RDK0>=h z*`E_jnIkdX{`4v;yrKmGnLP!&IoX^!k;vc$jCeS`IYKb-~&}?p5<6%Wz?gdl|unc zq}E4o#}aADp-U?)k#`>0-gq?gxN7lYwb&E&=2R29?Lfk4NFrzL(wAy-39so5QCgK+ zbZYyAWAj`@;1YJLm9HQ%D1>hH!V-mZlr@l&Rb@7s_QM{qY{44e^(*D@k#&9|Ew**= znI0&IMdD3SJ1)$Scjdb3?uT;4Sj4RI9!_Fi0Dqi=-oT_bIXhGHKuq(;?#kISi@fQ~BSyyHrWwhK#=3n4Pf)PH5D+9h3koj=Qi* zfMU%r$0%v8CX22LOULRTF9$6HnsBa3%V_@oS&14DH;;4q$JGS(43*hcnIt?3C0ZBP za9w^BZ-S+i^l*!T0wVi>!-;E&VQcEIK@4Zy!qaO>k(3X9uSGYzuqnlu)~+IK)_K2K ztlF>XMZ2eYVV$jj>PhYh4N#-?x{f|b{PlWr&e&OmfBu7=UeSR&5$=wm$D2D%w(IErP^r@p4;885?d zU34O8@#DoLPr~k^j^nzZu&3MTM*Q;i>&s@M8*VL88O74QU+HYcBeDCGVbPj;tDVn4?M>1SE>K^I;QbUgtz>w)Aki9V$p0{UMt&{d-QEyElN%`}A>_8YBt zR)VQaM?SWvU=w+cK6kSA8##ZytgUP@4rmpP`BelueWmmwi0-kv&5 z84$CuqZDyx`jdUF{ihz7cogt*8Tj#Ci@Oy1zkucaCH&Vw`Hd?ohJ^KGXRi z3~}7LBUiA;0#0 zwM_lFY-XR7@pjQ>v5%*DYm zfYUf`EaJ|n->Oq5_H4Cc$Y|o68Gx{#My4sFy?cl~&vEEG&hm$>9LzkVruqy)q3eB^H zA4ZOFl7G#i%$ex?4sJmA453XLNW1f6;FAnBUW|g8Nz!W<-i?K@$=%-CWiC9#5 z?eX^~a4K6I3PDE!N&E(>lHU7*L+RqST2}8WA4{83I36)6;NA|SvckZ$B^CKKk0oQ6 zq;4LHP8J)pgy%ACc2AaBJhQ02`CWXv%DyRZ+rGh@o6cz zKAV%(w|+=3wTJ&mx-S8h{?Li0CNWFjK9*UH6DJ!sPdS!dC#H&6)|jT(xeaG42Yvhc zQ~r9tq;{IL&xyk4DbbH+-W4Z`UuWxYgid$9XJdTd8hY?;TfN#RswRT@qVK6nU~1Pj z5x;Mzs)w6wz6Q^If2-Yj`xbX&=i6`fu&(*6n2UaA8Yk7mG0*&V&NT0*!pjDp`;oLB z;tmfEc6Lbj*%p2)!=r#YZ18(j;>~bOT}X;EhS6B1z|(PEpD&u@X7eMd1=G4j9pY^j z{#c=K4;nFIB%YwK$X*Ci;m=kPNL1u$T-71WHVY(cCSi*ZyD){=WIfKig1XvFy~YR~ z@pU79Lt|BsSY!HL!Sg%N79rAOd3#kt1_k4sP?m?q@ki|_&>=p{r?q@p2FRg9P*`9` z8z%UDZV|x@?asNSF9XFz{T?C}y)5wjC0phRoFBLHQjFEaN*>vViY6I ztRPNJyu2hkT)d*ZqE)=Iy7ff7s%}V4qPo${I8J*m_!%gyG7^+5|9nLaS3_;hk5X34 zP`F*Ezt=imXDN7X@`ce)HDE1RPkq~P#xv)M@Ct&-q+!lT9;Hx$tAz5OOHlMAg{v#4 znm=+*eQVpxu=2Cmgrt8%9Cu$!?XVqbb>XtFGxPthujSrUV<2SyVsA%qlkvh`0RX+`xC3?S6 zoZ5WlGd?Ty<_SurhTFQy;_l89r8&c&j@+XGMOO5;acsfCMsXs7ZsrLWfj zdoI^_{#y&Wj{oWgF&>}++?BXZWl?XWAkv{>GR*+{4SV|-d4C?@IM!~o%msLLI7L#b zQnHWd;raEA#tKYQu?#DcG}_}r#%u3z--ewBH7*tI`a#Z2jLCLF(%)A3 zhPv0bWP~V@M83n29zG^UT<0yrb6lz;3RZJB2mP+fD3z4i zJrk_(9M>Sgm4;eTGVCgq*58O&%%l)p!qeK{4}dV-vaL-g>R=mOAw_mbp(LVy`IIZ% zA(uErbv2VjSL@0VWW=gCn_Oek&p1-cgh~|ZII)&+F$Bx-?20*>Xj*epqa7*}N zYO?d~XV(4C@)AA4M4n&eS?rKQ@n*@bUlbI7LsEMFj-}{>3TyuT;uEI|a{?lyfj;W2WmrfGPdc|E5coG{r{j+&SQoDpi(*}ryBo-N*Q`p z`41|kuKy1zrR`&>m=arF@=sI>I`HpQN_O@+mhw33 zaccUb^uNFqpQq4uM;bW${$V(rn^--%T3-+8~0um`^=3OnJ^e}3NJ;?NUgFCX7TyW zacJj|7Lsc3_N=_6OT9Ao`qjM{^-F&59zgey$qgK%pS1j2wD&kZ+Rn%jRk2UCXAVE| zBBypm7$bX{SyM2KbDNWBhzBKSG%eVRfTh{KF^-15zOfoxI~Q$i_!^94LY`&KFg-YA znc~-H4F|dEUgQj3OG3UAP4$^mUFSe(+J_MWfYmC5G|+eaYPyw8d3r*FYJXZPw~m!t z2;fucx}KaT4w|WXR}>W`^{9oA!MG@jdYs63nENPf<1T+Xdv(lsrY8AKXd-w}HO1AR zUiVoF!xJhPjsh$`o&xN9mXR%NRIyo_+g)6qCq@otEd|Q9K(p^gJsP@OPG9`7kfDGC zNv-PH%_5X|g`5ioP0iI3V(e2-Qj6kVes>ILr+1$(gbIg4t2q%lUmK=Uf#PN};($*U zg`UA*Wd!HK8PiJXkyZLa#=RRl)F)YsPZTbwn7({Beap|>BJSf?BVQiCMFfYJJt1<^ z3?T6ez(PCO0@_x$>;S9gj#ro2k+in;5X12uaD~5;?r6^Tnbe zQ1>;fU^!9ZI)Rri>3+qcWs*11F2JVs!Yix9Y&)utS-P44BML zk-NpFDV!fgWCt#$v@>GW{MkM#R^^Ev74 z^vBM*%8E9hjM}i1f^#<#WSURGM(m_g+l_)Ix?-K?#0!>26kz%fJYS8A=hXW$mSO{K#X9`cnl;DF)V6478=N`$5Or%eywNUoQ$7*^H{ zexQ+Bul3SBS)?ml;D&`3F2UQBAPFkKyA>Jf$J~9|Yb2D1OyTk_NhwH3N}tL!F0VD? zpNkxMYyXp|dnUqHTAy6SsgQD0d+2e8ILI$tpTTHy65gKc@Y9JSW#|I4(40k@9K$-B3&hw2b6YV!HrPl!&Pi|Eu7>$&TatvgpTxAu!rYhm2 zbK*)e4fn)q443EBYX1}j7I?BhW1MR`EFh=b639ENf@#j`$n}}}JiQeM+U7q=xz(a? zQPoaV5}A}w;zvHAjbh;uai2^NOHbOZBN~d}#$#1rg;ILPE}(47n06R{&}~p3{l4^h zSDuS~Tg-yOQo3ZRp9$628~^a6zy(y#Z-)@NAoPO!&GJ;a7ogIvOdQ(xTT(FL#WTB^ zq3M^c=YU9JrNgH2OzZpaHDPZmoqn8~tWUoGnJJ_;neFC0s>NUaI+`m(+pnKom-OJa z+ZUFrS=uj!AD0+;-l)GiY-UrJPgm__@E4L&cDeed?O#YrZDRH9a$w{+l5&R~HQOt$ zM2;gHv5A#s?}vj{@KIZLSSp=y(iv?u*vz$aBt<%yp+4SG@-Yk15hn^-1?kYb{y*04 z!Yiu4@Av&M3@`%&v+35M8v&7yp*y7{loIJ~Q0b1Lq?K-v?(XhTLTO0}!PdF+i~Gbq z>pADHyY7DgELdyU`~7`=Xa@3AU0gK6Eh-ckkHjwc?JvzhcKYlBG|C=6)$x@_;4ZMo zu-_hi?$zom`~#ZN0D^=h&-%8W>x~MX*SedALEprW)%X9Jz_@Q#bRdo&NQze+vbZTi_2Z+8o~x}=dIqF=y&+J<*^COd8( z%0p2Ue@;a$lGNVJX|iCRAZ5(7Lfqn$sd1v8Yf8OJ>ElBVKFT~}9?ZnoDBds^GOiq+ z$FID{bREphLtiq%SLUwAi+W0|Ffag-Ymx|*+cz?cpxj`C)UkxwXY*RVXsX-IRS=3% zqqn7GV@DX9Tsy6k{AamIj zwH@2pZZ#_^oZ+h_!TlT{RsXj_!o_n{c(*j#(7Yp*LG)hWO4nstOxQlO@?yek(LK{V zh;v@mQNTe0klx=Vi-E!=%|T?j@hk7Ew_9+n63n))skZrJ{=J;Z}Cxn zp}aeHZOuTqcXoYRqom``ltd;;<(bsQ?MNI3)TawVGlESAMVtLQ^Y3V*JBe5!m~F-9 z1p_d*vmwNNPJFSGt3(q{QzV_hsMH5JqKBL2HC-kWls4PYf%}Y11&vCZcl635V60?@ z5A!}zp?>dD_py21?Z=@(LY~G9;oj2Xi*gUd&>n?SrHBo4ywihA%-T>S&rf4c#p!T; z?@GnXzE#`gVg3;_&#nTQ2#`;Zh3hc%F;B>j%Kp7dWQP~X{Mg1NXaKz`z`itq`)nhI z8bI3uFaGXBYs-kNMU78Y05Z>)V2?nM7a%JFFtL$OWI|pbVQWYdaEzv<5U6yX_*MY$ z5rF4iBJK(RE!!b`>2A*rLlK2RPkhKmzlDz*2Vgh=%6^g{1!9ms;cp~Sf&jc&0RBRk z=LZU?unZrA;5xS%ON;||#e66hA_Y={A%et<^#Q)}^f}a#f@0xdz3`g|C$~&vGZUb@ z95|wg|wY`(f)ygmAPbNS^2$iZH3Dns|UF z>V`Z8MSNk2*w%%sU2=d@aYjIhOEgh;dE8xhc=cLf!jZeSV*DZ}6?sME%6Gahr1J}< zM8ScFk0M}LCN6Fso`nQJ08Reg53doPeXy{z&xlQEx@Vy0*9Z@HtE0wAgIJSra@!Aqh(1` zK3g&P*&~MvjL1t;aMS<-t|UTn_&)YDc#Vv%f+7_|VK9Vdj9&~V@J2s~gb7Y0;R>eV zlBNnzkh4AlII=?xOn{tF%KJXFVm@itZNMLIAnuSxllk5>l2et2M%@c_14Vy-2mfiG z1TK7aE(TZ4P8TEf<9@^u=51){MU@fqFiJ>6c_dvnCKSfRIep1+YGX(eO7qT=;fjK5 z2o!Z0o_sK#d>jKiZMVmH4-c?RcMk}Hgi>p90j}~)koI_750_RZ)z{fPv{u2AI9d7o z4+%V^)UWxp4rJr-({m>%w7wbE9Se-@YH5W5H|2;ovDgC`aeSs+eFBsM;Gm35>Nuv* ziWXQ4qbJ+rc}~kt<(U!pJ#$!8I6|B@8p9>FVJCYomh_t@ztaJbc?7&eai@Ex5naKl z7GK{@$-rlNLvfs8srLHBL6JB!2bQ7&^N%m`Ielhn6%@mZ`6#3dO=qs><%^xp3<-CIy(db=W^2DRcgr>>pR&PzaX~ zV`x88b6=OUuaa`4bMV&%Tu;ctF(+h^0e}yk$#sD7F|9*;Y*OP@#oThmy{n>~Asa6V z=~p>-UQ_|oprq%ehF&Ad#S(ypDV3)>jb&iD>!a!{I_f|g58T46;k44{=@luo^g&EK zW5?B_fi>efHItn+)9W>}KWm;5)-F1hFPYY^#??dy)~zI)RDy7bEUekj;8N(-d+&WGLFA3P+}s)udnu@>rt;S zJ9rD_Nn8%8>d6E)JL*H9mXXC9j}VeJbW&1E8W&u>MY6DxcQ!bcB63auziWGjkxJ$b zG7cvvBGO8pDLvYsK&dIfgxOH%rf*{UNlGgz@TIKDS&6#Dfrg;4+DYC6HKp(?E|yua zraiM+m%ioxeuF-b$ug+OuuDmUhullI@sXs-lb6)94;KH5j=>oLdr-q0)yy1cO~& za~ls)^@!hC;1dHN>bAiI*#sW-pvNErn-Je6IkLQgwhc4XgLjD2c?6d092NkKKp+l% zn(wrI_{(6dk$LL=`1V(_hXBFvDIP1L{vUgUn0bWAsO#)DV!EDSIjngvy{SkE=c*rp zCuLcP1l+OyXZ_11cj%cD+gDf<$)-#l#{jM`iH86@pdNmr+jmp{GW4XD0d7h-Px2QS z{4@d|6o6;Dli;?JTwEe*F9&b-VWiGBM`##0bVy?w@ns&|t*@_}APc)B9zqSDT*6i0 z@Iy-*tetA|i|*)z_3`hKZwfHXC5cEYNfwA;C}adb0r3L_x!CE2s`-1K$>P)#+wcOP zFd0O+J4BAZ5eeqw&CA%w0f-X;z@HZ=bRWCjMyMkvnj@(Hpn!4R-XtkYr?dKkZl$nG z#C1K1aa@vL_fTN{WMv6$u@o?;+uK=4Qp`(CRp4GHb5dl^Tt(O8= zoRc$ofm0-6$Pzj@EyIn1z(VmqNWniQ0ONV!*WA<&DN|q%lJ*pWn}*S~`oZ^`(uHP# zJ%|j=!#HGunBxT;x``?UX23Xzp?T;PgUsYKU}TBMQ$IgcKd*?M-_isW-RBwx#*fZC zPPUy-FAAAGhlv&4VM zB#7yCf)|b-Sfb7mpV8eW#L~D+- z*|s?<5pml;l6x-oMvLO57Qn$r3Ejq0xQj5sN$RfkZqH?%g>`cr&@-H+4C&3R1jH}U zc;}X=+4+XL-eUJ33Y-FB(oLXv^Z7*2{V!6$bPvUot@m0O98jzPd{uLEs9=GkCT-0^ z34|i9bKW2joHWS&;17PUPr9yz1A?Fk_v&9>xW7Y5BQWy>*Uv?6&MENtDOyWGdGo|R z!5c%CF}QX2nTe?g{*ntsfznYnV7WfrLTo64*kRmRvHobIwX11f;||G|D6JH>g# zm%O_ZLOX1|6r3cuIP5@9Km6A-1Qwme=;jK|^00rP6egkIkWi?9I9lBs z44dWAct-LhX;k6)30 zEDBnTB%vQQpJSCFr+x;su${8sY>w8+_S~WGlYyu4lMBu}CS{#*N1O@CdA6#YcNLvj z{JAqzcOFD}jw^V+-OEMZzf$u0j&TzC*{kz|S+3^4bZ=@8EAwI_i(~)KsJqwh~e42j4WJR*(f1|VfC1<1m=>84e6S8i*n-`JjU!0{#b9WjdR}_+LvSsU1UveWDN*%tB*=%ElBoSCehM(b9WJT3}88;`;3lhH9n$@7dg6 z%Y$2k#Y^d{p9arpp9fSS$H{8EVc*^O`$YeO1pfsJk_r3h?qE++D1{y#>i**-g_67R zUo(Z`RHWl0d#b5yqI81U`UlvVLNz=3tR3Widt9r=ZgEX^1!8{2#pZ0GBJ8!6!!2B* zetA%xHI#7rxQR)>(y;dNNRHvD(JOihl3hBHQt}4ccsc`Rr-EJs{W&U4Nr6<9-Axrc z1&uM%tj0f@i{5npv%vGYsuQ+NU!L8Lp_9kA`vRVi{&A8*60f|Cm!vaIj5U^TjuJJZ zmDubjsvMTVE*3^wDRh{rwV%+cE%EZg>q30l; z+B$Ls84DsGF;FFg!h7OrU*@d9TEhBj94@Jf0vy*~$gi9S%}d{}S)c|wu;)z$;&`5J z28PBD>N>4R80`d%#2Lv~9`UhM^EP@?IvGy}ulUeB9s;ilZNaM!jpAu;g~s)Xt9-Hy zG9JK;9N#{$=WvD{cp+5?b9~LBkI381y}179Gpo*Rsml3&j5KDRd9CER<_z#m0Efu35ykmL`QTH2tkwF0+ir`{4VNPHl6|?#KA>E%Q=D{73eMM5L zjsgmNX6CVHRwl;jsq}#-&6&^20;FyodFv0ue#=G>hf;S@95mzAzg;scb;>y z9CL2-Dja`|7DyGly;nZwB0n$fY%pxQ8<%f&Ykq!V(f88nQ;(nMpYZMi`{x|5g?Y9) zIg_N~+Te~BcF$yfHj1ScBgH&F=3E}X%Iy8MfG*Cnzim!V^17Hq#K(&fc1m9fG*Hic zNM0!a$VNGD|FYmV_G{kn1u4OgmnWjAw3=i;(ePQSvk}50()m#O9W%MAHL*Fq5S_op z@K4j)y~Az$6mddU)Bw*o@fZJ6ZZb%KyQvv!@)Z@g*lU zZ$usu11gQC6OwuJP&Xu8(oJhk8yCRi*&Xiu|o?$_!DU;&Qm&xf1dLZ8{+@5i`#6YO8Jj zGwE^%hE$&mm`5TVPQy+Lxx_Kyk0stn=X&$Q$2b{Pwg;4&U1Zz7?(O-GPo6k9ZLAZf zqN8|2JOj^zbmo-zE5yl#S&4`icA7>Tt8l1_Ca(=)@8$(kBx=1dm3@ z)qk@hXM9H#=q?4O7hrFD+tobVD-wOq`o;GB$E1n|xFde<@r>ZSRb0g^#1a?96R`xS zD*Fnh>N6a0+@??RRe1!}ov~K9b|_Wc3Z(;dht%TWz9CDcw294P{?08uAJ;}< zwcGZMtRJ`W9QWY_dW4go>NMfHUGXOOOa!axguCB{tqY$@suJ9`nP47kp$(^Lht>=Y zdvW^37Ao+{Sqna7TyRUi9-GZ{V?CTmdMmfNQUqo0`ozv9md{}mr;#Q9?)1(?fZriA zlGegy5Btd?`7scID6uBya(%gv+^WrF9kn?3w$WVlDdHSaWPeG&dclfn&Sc~pnKh32 z;PNeL+xRpX5h!Q9N=L|*cR^GrXa1;gS9>b%4*lJCa)G{XK;n-}+R#u^zWn1nuabTO zrf;ECmfxrD+lH_5_r$8c3EW|1-OFxOJhO2tRc(5V!g2F^we5=eHA|^Tf%w!D!%ZKY zw0X7p8c5=cN@CrNiug`6aIZ|R)`j!@_YZ>iTd1f!XHTn%lgzsxxIuQLPX(owCBywUZ(P z!Jb2P_5Kh?5#*8LNlA>d#Hc%0Z9iuFd+8ifE>887(0KVqtmAQ9FBtJcl=v z(MD(T`^c+!`5*6^4Q-_9Ko$4SvffO|k7moS;&O(HDTL7vVMsifUQZQgup|mI;Oo8X zeGrTmIjf)LNuuC|$}}tdeJ3C4J|sohy^9_qP92gxOGXWsF{Vizm_+|glYBLwH~^3w zSPsh#KZt^M)f`3WH0Q?r7}hZujy#Ip3{TQj6l%Snq?*^K1}75RjN_nCWDOc#P*rSH z8`j^4PVU9sSyuGmR$LTlSG-YpoDMZ;PqGKiG>R zreJ>}G6d!B4M7{kN{BB63JPjzy5I(m6}#z1x4S$U3kM2KQ07Cy7MKVqpk!)`FM z;ytsbDIyZ8CCQ8T-WIx%H?z4svvtPkxvz!!(?9x=Li-uR?5^-^f^OH|zS8FYxOE}L zr(kWX7r9cIC)x`#OLQVVsRsh0X5xFOWll^ zdAV3+wd3BDS=(kgc|=#ACKk@dh&oJlEHvdt7VsTrfX(+FvL5V3oN zv|Dj>d_)W@gp7<7M!cFvzdNfy`cpLe7tT>8Bf`fW{dY^4dT#H3u$X=#WxX$}@% z)h~vszNKeO z4J~EtkT8ZOeCwlwjMVcYHaoE9;rTXLK}y3y14x(kMh{(Yyv%HG?q zJ|b@SXo+!WlXaw=DILIf%7A(wNc%_5%-ckrTF!={#k6~543Oe$dAcXLY7#!0p(Cjw zpnnHo6aNapc>lkd#Qz?Z{qF(T=FR8bFX#UP{C@{v|7jBcBLKsW$_{*cU-MrZuqu|Is8~-B_Dm ze}BEw{Bd>g!}8$f3by+y`2VH*I;eR3KWM}~|5Nw1GTAXZ{cnx<|IvMo53~#obpA*5 z^$&`;v#F=8w!O8XwYk2gtriOsH(@p6hT4{Yg2dg0Xe>xvIy98i-TPlm;sbC`CscV=hxN$sK3z3|6++_V&ne1N&NCZ(l4XL{Qt=$e&O#M=;QUjre7XTuK(R6 zb~3Yd{121(ztvv`=34ruSd;kwMF588^iE>+OvLWWBHiM#ATg^~h!7Se7E=@umFE*i z{U=C#Pm+UQlATY2?Vk-8Gq)%+mnajb$iGcuZCmW9?7vLnwEtZIw#hob^)HjS(gXIt z1Yl)aar>^=MOnx4|6&sVBLL%WBwZ@kEmqH0Z{apD#XE(W+o7vhik|mk1F+Vb_f7UM zCHTIxoa;Su-J8tUXsgrGnvgPr=lT__MJ3U-(nDQ}?uUL&PcXl>?{+tJxGr{Wotc}-g1o6MsO_sOtL=EBO>AmnprD28;(CGysK?) z?-2bmT7)hb{Y6ooc#Y0Ez1!v@J59%0sWM@&|7@a!19N(;tM3vqf45Vjopa|lHY$lI z-NJp@;oUT`#J$(D?0VGKR zJ}o}S@1b4{n-fgmeu*`Si_~cdmq}D-DcXTZVh_Aj1rOm0;5n_K%3>lU)(;(xdsP8M zLwiK@;wK^wbwky$KA`IK!Lq)|SIZ$*MO4u@-6S||$8MHwS^FF1*KAGsD0W(kQh99| z+d?bI53%_iA`5mP7OZAcF6Xfuqss@u<6e}+e$3-gdco~orgYv6%T+oXPFc)*`j16f zuG+N)6&5_sQZ3(~WvS&8F|_(Qdry}SP#iBXlfWBDEH}D{>sFalDOugtN$8;`_gTGH z19wUk1uYRpa%olULO7lkx84iV2aah;gj|xOE#ypU+zs1NQxw1a1S1l<04<)zLI`Up=jVP%?#h{waVOr}@XxDb*a~c6imVE88wd1K z|Bxi@ckX#~Ifk5zJkw^mXPb=H%#hkroHvz7_2#^5d!9--GEJqZSe2JBGU3jX(uN>? zPr~*y%K2u&r~^*fcQ50xNl{9}+g(F~gO$(pmJHIMZ2WOwc+oPtmbCVMUx{;9t-NiM zIwy5)${S-0;hPn_9Ur|FxKjQ-g*)V!5>Z7XBZ#n?dc4c`9Wv4%>m81>Zo-dayGuqZ$PHnD2IYh#}a_$-Uf8^dyK9TQ!h+KI9@xy-)|46f&axJKf zJfV-7$|}x;t`Fb&+W%OwAf+V&VkOC_80$zw*8e^GKLao-MGO9a1z_c>Z~qm5Rge>0 z|2qIm+Y*F*TEx!%L#<#oWhLS;|jUJi55Jl*klfm3fQ89~O-;N2wbO2Yahu(pAdO zRz6IvsIhSB&}N|{?X7MZqlGd;c~%==aWO{uH#>@o({do zw!Um0Em(%d30#G!7NEx64%OhR>GX6#A$zzTX$tz4U!Nq9aJ}YJ%s1|fKUCFQDM~w+ z;UNFhw@>>0ZJ)*he?+n8Hq7jM3}tV9RA|-?@&DE&_7jVyMU;*j4qS=)oTZ9izGK%^ zRYsf9>@$%+8kf8hG<0;f&7t_gu7fX>TDrNPt@wyty|v+0+w=i{(2prglBTRN%|oHw zAJg{QO*w1Rhjid=%#6Es6uHnqtfm+f$VIypj_(Q6gey{pXpeGx%Grmd@68_wM2pW3 z94U*MF2t}y3%x?)Z9%4#c>t81zc42BOx)Z(%8S^uki@5;c)6oO?sX;29PW7=dt5(+ z!$9xYQ*mUqquyIcBtL<@hI84iPEK6g;zYl=n4#+NEjey+Q_V>UEZ;~;Xx56_jH7sd zu~+e}0&}>u=)fB7g0FmUeuC?L$U6`e#Xp~tU`$?%w|mQN zS~zmNyB-_I(DkE{u^e&Ox%iZAXdi zT*krk*@+66d-%*r9GXbC*rTN;aIPF4pPHTmR&AdU_tfs}>(kQg(x`!C(Vn(H6OW8U zyVP7y{6&Y?)@Qx>Uw^(fcV|9QYWTHPEkye)KH@9*5gy|LpR;uz{d?Mh2yV{>zXm>sz2}twWFuZxjr z;ThP$(KJ0FRM02gfUado7D(a#LO3pIG<4^FHi7Ug2k<)#`!3v=5GQ7$9`=%ktj!W} zi6o42C&Gk4VWE;lA-o@$VromF!_h^sneHiHW$KFR_@pfUYffZ8+ChD(I!WmrT^B=c8)UaBM#9O1yD zgqO_vc7?D@F`yRokk6C&ZA)->L^7V0(doN8V*W3A7PEyI-xiOI<$@Ge3t@Y zBKnRbToPuwQ>htO??%yP%_a^g#v(52@0wo;&s!qYj8jH;pU4V=h~^3RLl7JFA~buk z7xR&R`+?qi0W1O5T9xF803&-Y>PQqY5@YT1h+MY9T!J#w!z#*ZJY8jg>2^sYV;(-; z51rP9fvsRsm04gW$TW~WU4RQ2$aHN8e+kQaVg#E;!%>#7*lc(T41$Ic;#v_*^yB6| z%J#O367tOyJj}vng23c*!B*K&*b8F4l)r+ADi+2#7NYY4N_spMXjWEr0FXBUpFzVb z0&+V7DA*=)e>1_Hb|MINoW%7 zZ{2BLFvmS<&Ur(dQ~W3gO!^v~4Zn@e{T2{Hw9ZN~A$tU2P8KusZik;`z$e?(w4S2gPwjV<5ghOW9p%fR8RhSJ=5HEfGKHEg1 zh^;F3MH-w*TpxU2rsoLA9;1~t(M}>wbyFiHs85*k2gIrXVs2pm+R;p1eaQiEQwQ#R zLHc{%q4~)wN0-V+T7JwzrU+9;h2)?y@3Z}WQgVw4of-&vtk4zL>xAYocyR-$&hq0* znrHeYgdQchDJ3@*%1ZrtJ3lJWKPyjfBWA8liP9<&wiK+_1$Whe3a|80IuP-byrczy=D@p86!U)6^u$p}H$*080N=++)iY>LnA2lVfJ9`_hy?4G0j4O+ za;TSY$9!!SYU=2`(tJGl`VkyC)rrxFeXt zvy=Om(?~q0`r{6XDU$^R=dJS1YbuSmDhpIjra=7tv43CyM9&?v`UD1qZQLU-C)h6$Jno46Z! z!YkVul#0@WIv!1@IQL?Mq ztgDp=s1EAt?CNrQ)z$s0tDnAmP_ld2ta~)5dpx&$va5SKSE+Y{%yy%DY@}Izfc6`E zkG+UYYC-0^c)JTwTMTBQXCZ(%)T3v&OLH!ss?N8!&eq!mN%?b;K%@hR)Bud8ddZE5 zWVp!)pZ0$LWl>x}Z@yqfjMKLAvyb@|`&vIC*&&de>IbuGosMXQ@{%4pTHxahz;;?G ze_ObC^b=b3Q!x!pDGq$g?lmZstLH#6!mWLaTL8VjnYF=QQ_8>bq}M7#C5k=j4Sf;` zz4{(QvT(b`?I8sz&0-!(jrrFqa7{x?O6tww&YNB-ddjcp8hr-4+?)|XyJ2$%y9d8U zdYeJ6+eDVg(Wm%$X8rhm+eG$KcDx}uW+1rh?@>z;JQpP3gc@VEA2X!_S%BacNWc{Y z?=NV5ab^v{pz*yK+WRcWsnO%6B6v}GV-xjbQRd)OXB*yaqJAWPg!6cRKRDOfMyDTt z?sy{VH>7maT2+@wJp?F%!ynF1@`?~)E)fgvPzVUrdW`@062Birkm5YWWryHP+BeVoW{BNGnOwPa>0* zu>*7Khu=v)8(7k(drzlI=KKV=o5Jil!tzGy5?84@yBICf(M zfH`0hBhcn*MV7N*EMTDmLz4VOd6orC9B;c`ULwwZ-c7Q6B=lp+5u3;Llbj%d6Euk# z5+LuH#q<+jPTvh35FR94@fIeYm`6ZJ;kbpfBSs7P^;~g_Bvw)YYmFv5gPq^yykUMD zxMA`0DB|)Glxuzexxgxe=IUc%_%khFZW|x0x8#x!ukYv5GjHX|Y<4;Xe+yZJ>{Ps} zUpx0j{6^yr$zk7-ymRy>jF$$Eb;ssV0A(#4RL>mB#H4dlSMgkVUtk%%miXT;*?k{%)aUscfG=k{-P+9l@m-G`y12_uv8vd|;_ZbeTuHXz5({g=#No0{+v`-=d$5CnX=L|m#Iqar@Vl8{Ha9@^o6Kn@2>QGh-1hmu(Zq$N-; zLms7l^aKagh@SdAk2tOOxtt-v^lvuRDR{g%MeQ8e;5<_mAS#?iXutygqDWxwXJQ7Y z8Xm{Eg{S&B&J;*OIR6JDi-js|^_PAukNwK(Pmk%KqMG694FwCw*&{T;X-rZ>SL0t zcowWM3X~{7Y?pYo4GC;{hVzI29p{BSku2p0%wvjsF>Rgd&!>E6G{y?iVSKuy?eKu2De5Yw~BJX+V!{Q zZt|8G%Exyp#E$}$o_wA5`f68rq7fQ4u^sB_Ch7Tvf$j}O^S4B>-0XCCwVxaH9XE<` zKlxj5@4YAAJxC87UXnY-%J)B9oA6#UvpsZwNfo3+;dCKC;q@-uP2T%1KO`84eG8-~ zYrguZl%PYMluYp=Sw8H|#W_Ea{Z>BPLH-;4Pgjp$Tnmt2UynIiV}rFvVG8bsa$A^bhz2*vw7#gOk%eIj-co;``Gvb%f3kB zyUKYcSJtD6cL{@ktX}=oBp!99_B`x37JG@$XxcogTCDX(rd_;r-&Rl$YZ3=tVI<$T zxOlPV@vgai=y{I8C(-k959ct+Ns}}G;dw~^iO=zlMbke`;%I3GNoCp^3pawhk9`@g z3|F|_cs#%L-yUrBA$s6{f2XWVS22(0^y;WX=nY+;75>HlIadPmv1ZE-*z`~?#7W}< zN+8tE^W64di($1#XM3D=p%sIdtXlBv0i=QnT|)sGC80H|N@~Dm0r|r~!O=)lZ+r3- zy9C0q%#(qmeju6wHf$@!O2+0(qHkBmhA48WU?&wSnWU}dRVxX|(F96U{ju}OuX+_Z zu@9b$D@Iv4tal`cMNg8DzgH<>Gojph6SKCLQZYIbwbx5*&VQvUwN5d@&`N1}mCnNg z3W7kgQe`6WQn^Z6Y;zH0E4zG-m%Pdw`3OmQzmWP|@Jo@#eIKsn>~UHs-J_=#=`0G> z3O6i&9Elwk!;GFztVNht!rsNNdyJB*0o=Dt*04swY^N#)`+m%(gDL)6)n zM8B}-Im32bs>U43Oy7^`hq9Sonjaz#t%f1XH5OF%chQbXM(Jrqm-!`}8a& z_G#v0RvM-pg4DMMp~0`l?ebZp+zYZT76r#b_&PH>&G{S$^GY#JfxxG1N80iH!m2u$ zQ@E{Qn$)ZIvI(c!a^$OB;;&XJI_c$y+L>yF~|`&L3OtHxFm0DqMP(_<_#Y z!&lH}Lx@JNe$|30Klh0zd%8uNzWKo?PpLBLS&(`FK(f&B??VvvJ@KshRW3iM3`7|5`FCkFiV=~a8bGUnn~6a1!#c? zAzCXf{qLzI42sSJL1`c-@&N?w!j&LE_eiW=;f}To#4r)b#xybH$H%{J1LVc-L z4>vcZh}~!QP=;?x3vtHjQxs3U`oj04f;QC08ID4frt@?Ibe!_-hyA*5LIs(AG21YN zs-Q%!brU>m5@<7?<%O2$#liHJ{W{0$!*>?Y^Gnt@5x%O*RHJUO)0(&VgLK{kSI=#o zY}uc2C@7)l!gC-`IrWPAK3Zz0mn)X4tnaEo$x5`G&CR%BkcI!jAnm{!3-cfVx9`ORBG_sDLZi5s$6ywM6!aHz9^)_{{IZHt1N}2yjN^PS!Wh#hQturJ>GWgv_z(d&ih`-M#J0 zh>V!E^57Yc;K+_tuKD{Vn|LJdh{aVA1EaE^r9=TZ07x{Cy64DnoPJfn%tZ)W-+i|g zx!Ry7{@&I>BsfdgPyZoQGqg;XQ~7U0hOyTGS>X78^ghSTM@nf_2a&zBBW8 zts!_)vrwoB`i`hGEfc|4CEBXrDXpQtGi^Ahc*{9a$>u1e6K9js_9eb(Gfuk`=dqmn z$urUJfoU>vfxw>2!$c`VN;11lLFQ)MC*@oh&XbKDL(>qL^>pvA$ zPtD$#Or?Cewix&V_f;CHHTYK;(%u)>NsTXseR-j%3R&cN_k%wAvVu$Gdx?Z!~*inGy`!9@Ox$ixsW+F!C)zkB9R&J z0wze(D(N?S*Lt@XA1w*;o(|DrDlXle%_6F=eO224&#@DOK;#dS#EvNoDrxR7+Y|e~ z^329}qB(4O@DRz{lO9(t+zHw`M_dfb#Mj&H7i2Pvhn063nu-TF4tSmgxT(HQ$R}8K zX3`Istqg}z6XlEMhPE%bEG-6cZ;84zv@XRio&Hk)a}0T3zvA}Az`J61%M>$1-w*d) zMsG6Yg$TcQ`V#f5dP_Kqr*lJZ$hTuinX=$KVC%_Vl;NrL{f*P2kI#qv2BM?(KV1gy z1nfN?dB`sA?iTE3%lKooVz)P-{P#1k*50&^GHKuEU>EkgfkT#`&q`FJZ+Mdd?(#dr z#eUBp%OnFIM*rTns=yBc48~_OUKxtL__g?4x3&F78TZk>Uh_?YpZms#*hxX63{u4N zCFGl*`m`_P-`>kfa>H+~X(*^a! z2_o!AW-sou?cAJ_p+3d;E%`fn#8s51^r$oe$>!?D_E1ugDMhClDpR0zb?Dx@YEB4K zH=!bocDy$XDqGl;BO5A>ID;ByRfna$Da{t7kcutOkK_)CmqX|o~=^zWpOjJuH z0?9D!$K((7TbM!Ks*w>x<(a0Tsq}IkU4`FtQS8moB1!0BS1$t{F;0nmbiI6sS(pID zkRW_00WBU@(Kf}|haowYPxvm+FrCFQ2`_OPiuWH1RV8pCmr&atA`VU`?v6=lf=1aS z6r>f$(WgpkM%{$Vef261ZxAuhWohA!1})gsSkyBr`$fHQ^1CtcsecQr*LY zr>P0RaL;L%ME79${7~mZu~4hj#ABMVcT&dF&=18@mzB}ofl)iXj$554@(THdNdm7TlRveUn;wKr?E|swhBfwPb*J>Lb=kFDS4sZ z(8yg$(&5S^a$OaR?uadQ8I&fzDOzFssMm{P;ObXi04KwV$&jtPz{y@j2e-;eJQd7< zL;|835i^2`ZHE79Ql&UUJj=Rs64UA2Jr?HPlmI8zn^x|pPk6|xHd}yl=#F@`&i%Vd z?&PRHqXrdYOX6WG|0hN=H!oqPT9CU&^$k4HK0@xXCcf7@5C)SK$gpy};h8db90}GgV(7Tu( zofj?dHZ+I$oter^m?VCfp!t~I9KEa1jnWQ<0(5cc=df2kuuKByagVBwAOV_Jf)~iR>YgX24 z4@@l*23fNKd@clENy6L6S6Q^MCYRXyTam^L0FQJ-DR!QTw5Tp_K5;9igD>WVp$?56 zw0k9{(+Aq?0_*pI4f-J7O^XY~CW(2c3O$N@5e)mw02}3lPT;|&_@I+~$=`V4YCRygg$4=A-nl75*7kjEppCplM_M*`Y`U&mX6yvFLR1`UD_>qcga_L&QjE4<0+ni#}9E>>N-|n$DQX2Yj5Nn zdCB-!l95=`*)V@ru_ra@`mpwDr@lb1{Ri9Z^e~GoEQux`NHMyq=Wud5Myz z?AB3w5-?mxO2h0EgMwD}i{~}^PZLjAMoZ0G*w6OsO$jDmkcqe;B4!#tmC&>LV|AnRVUuO8gS#P|8-x+pI_jWtAQ7<1YEsz^}P3$2ln<^N=gi#&h?+_ z#M4f0whj!N&W*v-X*xPu*_}1Fb~d$gG`2WxXlAEpY@=&rt!-eXp=*9h+eB5%L`BP3 zS;Oe0x}oeXs^otR6vYGYDX1CBtLU9LN%-&U#D7l{EzbWVP5kd{Izh1=be4|)Tcy|| zCjY{wE9iTy>Q|}Yc>JH!MD3VUA>?XlT|Yg6Q;an6iMxnR_>YT}BH1Iq;$bq(1g z9p%gq3@UfgN5wA*()w)Tsr)owj&u59C)XaUlcU#VuD9cEs+@f+GVyFG;ltZHl^lWB zy+j$MLgv|=n`2rZ#c3F-m92E49M#QqlGh;d`h`8jZmRX%w@kek;dOJ^O;o~gGG@O(Dv z$ZMrpoe4ZE#t`PJM^xsKE(Fe^T)L^MkY7ebZ`Q`PIXp&2?5QzxGQ`4E1_3!rD1&=G zwFWZgb9I_dafs=v+>}~KwUZfPPr&UPdm8r&`v4~)3u6Ngdj?9m1m_b+%Q&m~FItt@(M}36_N~)JLqmZ0B{|6t43;!6q3}6;k<9 z^OXnUZ{_Ph+-b^~y_~0^`FGF~Z8MQIdi=+U}Arg~cc71}DPv z@)Njp{XAZl&(uA)YQ|`w6n>H$r?E*>>3t4B9|NAu26Yn8>M-X$49FPvWr8Nikys3_ z2qxA+oib!zxB07^mofj?U1{38=Iw0IXV@-$1q_Y5pg;3WEj|z2(>hRxJf$)46v|zF zmXJm$9z15@+?Aoj?XV3a{KlkQ)XNb)h8c)^@j*%h!@RkNlBu-NFgC{JC8CIDfrTVqL)ct$s)RK%xRBqBas@J@H!q zq~i74*N&mj;?|g-)%_u)`)z#J&$`9WzWl;SuF;&JeD05_8TaDQ)(=z2I>GZ;#1H&O zY#>73`>{DrHGz6loxu%WBJQ&OD!-<0mH37@0hFKz)l*<+ENZ>WmU%ZxKsw=_BXeWq zUa4@wW1Imn-#jGHe$}mlN59`t&J`yX%mR1nkr>j+*0B^0(Ti!)abQP?GHkjCV^($t zDr;hdJVZob-$uDLEHx&SU)s3#kmVX8QheU8TcPKx;TSjzo`2c?O!qg0jY12MPqMt$ zqXiiQ{L|a7%E}r;B^BhhV1vR2@i}}SeUzVhZisKthj`=yGq+73+$QHK{ZU(aJH?5@ zj0eJjk>@D6l9dQp4$BF=YCLz#Wg&F!{l_<)aC)ohD zqp>jBQGN%w-W>cAMSP3tXO<0M$Sj^3kPg!bRWXjB_B|lQ!6Y7g7})jQm)KK3ZMxI_ z)=TZXa8>P7g4V@k!M#D@O8z5;N8}BCiNm6rvM@k$d06VOFzcVJ zkFk-)fT(8(xMC6iMe30Ks!aRi_o%|DvxEfE#?J}IUUVo!z=`cgAP>uxx@9W~=}r<6 zyxy0k3|pA6>P+8-bCImaYhk>a0$(zjMOc1z2J+m#>Z$)H$Vi1UYZFQQA|NvK+|<;O z%?HNvNT)FJ0^PbNWxK`Yew~kDne;$`+5@pWzn5&En~uJ8eqd_c@Y25K?P%%43#SdY zUpjV~eyBt|EAX-?a%R|c@zquT8=J1!gZtfBr`k>hHKEv3(ro;#^G;=2U$K|UyYc=z zJ5~R+P3LVk$*}2mUf1@OT)p*fa_09=O$)lzKiX_+j_+q}w?*l-NAIS-sQqNvbfwpy zn@z7c|EwSDE4^9sZhGU+&o^{*Sx}eR%(sl64NDefcRs$G*{Oe&{57F0WYO&0+hnNW zCdkXNeoM@`MJf?Fcn%RwQ(--hru?wjbZpCsM`r5sqblPBkj#mhJ}9|%e;gpJD7doL zrck;IB#c3252Sa+)imK|zAtdlEJsnlOi@BXKzYG*iO3YmD3$c1u(a_<$1&-46mRn?_0;IV6dD7jz=nuJ>5hp69^bqhT;!t{`ffg+y6Ek87eaRw~jg-1vdK*|jvZ zl_GG-?bKnfOpl<_)%=z=e?6D`pg#O-oR(hsu5cvf@l(a`I^z+eXZ^EaX`b?MLp<}f z_!p6Rl6|nDC%m`N{GAy%wtoFQNJNWMqTP=BaU*uavqbY82r zwhIxR6v<3cIgd*%{`pMM<{#M z<;`u~CZx#F(d{HFZ-rjOWp+suAqgJ60kusVzQR8Etl@9W%{4`g9-TB^{rhe4a;%*G zC+5T3=!SZhCq~6ph0H1xBhgFO;v`?Xt&WW9yrcz0Unxj~-(Hlpgl&@B8@?cVUYgG& zdFES*1#@u2#_zZ`heZTTL>5uQAx#Na)f;6V-~RM*OC_eV2(|*5HB`;5;{7e$rC_HG zvpdq4Emg_HqhmGI2GHsJa|+_TRGR*f#!WxqdkJ@`?2zj4jm>d(aF!A|Y_#*JI= z|IGY3_}PMO+Kjf^o2$Bk>EuRydsP_%Rbeo7L80FQ+4hT#o0~?THtp2B-`@y6{6oh! zAMSQp9ejIyxVL20{QKkkg92vy{wAx=pJ%HO9n@zw@T|TRq%xMVgTh^}11#c6izLhv zm5~LKAWWosDzb=r4;%oG!=p%a2n)x(O>U4S75;<@w9q!F;i6=As z$T~b~(T!8C5Q&un9udiVVdSqy;QAKKS~faWLFp!czMyoqqqY$&C1J)gL_%Nt}r@@(c za15&Mm~r^75t$Pf#p50sM~ZAKhuxL}Zq*`~#v*vh6j%<)l8mu9>?Z9SQPQdKG+{Ei z1-Xg`e8$4-0nqr3yYu3AAW3)mm|)jxfhFPaW0ZU8(HuW&B98HpSSf0cyTf1l-{Vkq zVaKBgEpeZr*8{iV(IlL!0W0^R@Xb=dJ^;!w0iA{%OG}t2O!&}E zVj+;KVC)LD_sFU!Z7NseSdV1l#R`NAV;gl476WDF!*zmBSzoCC0ZfhwG9|FyWrCyht)rHqzTM zZe<__2uQ96-G>HXus-*6$te;kK|HhPjAxl&fubQ5OeNXqZ=09_e^$sWQ#*hyRtAId zY>suVDWF@DQaJ1>U{}hS$1%z%J?ipU^rIGd9X%C{BiW?0+nJ#3Z{vKIncGNIJ&}h< z5!MYlB4z+K>V^%#14Bei5~ChvbSS6P*dL|@+<2ru7Ow4hhdUr1M#cm>u}9uc;~IRZ zh0DN@nK*?3FqLVOBy?{R8zT&u(Xl>ICe}@$(kbxRsWW`tWIkbGv6rQRYuA7|BC-IF zIiNEKWTO_`u%C#Cj$itWM)M0jbJZ!J9-sCp@}33Hjbqknn=R+!H>F?a$|VlLR7Z|Z zZt{T?+#d~d9&JZqS~ZdWxl*yYa>+RGCeu#K@weIN_3^B3Q1l!fGfIagfS95N5PYVH z?=3kS+3*CCC_KZ5aNCuu5H{=t_~%~Q*ggq!I`Iyi`;i=wE+Vv(s#Kkxi_gvFkO$Qg zvH1+45uXPpBHhI?nq5W_sWb zh=*IVRCswGiefZQ0-}p-k2kRyc)&~TX$#&rFp9d70la1DeVCc-*OmqW#ibRs+6~ z$})4({>T8goXfYMFj8Ic&?Vq?E-Vk=3Y-;Q9?m%w5!;t3vTe(MICzmGDZ3@$)a7r? z3x{r)s7+S2W2|W=80r9HIV^qWln*EcG zDWt#3=}4LgzznQZSj|Xb1^)93DZEFGN@z*nS%SKo|SUz3@cmt`Zzk-8* zLxd!#-|cr}1<#^#R#7Ng1DL5H7tYb~rm|Q;un1h;=B8ie=8<+I5yDje^w13GItEls z*0tf|nVA{~SJ{Wv%S$WMGk>L%q6|pePBZEN{n(qHxP}__H*NH~_ivi?2b&@rR^G3PWK1_PjmH%ziEw!f_CPD0FEh^H}H(XlOGjv{B6&}B4qNB$)Y zN)$|P`9$?#!>KshJ%x(2O24_-3#g2M(0)Be=l-Ch%^aJ|-mo!BVgCBIfo7Alw1YSr z!Mb6TD0A71dyq+~iVjnSNN(ulUKN2qZ-GT+%f%Cp1aoxofU$$K{N}$4ULgt)I2Czk zU>R=lWeaf;EHMER?ga@@Ivt;^*44jhe|x!}fUoa!V>K^svOHYN*c59%_Xj}Y;n^}$ zFp=hXf)M{=_e-uWo}}DSI^rs-GTIA3D7=L*$-g>Z76oMj8oHeaYmYT}xy70|N*rwy zUGsoe0JR6^GtB?JW1j-wc6>X8?qeM->Msrk`i90S1fW!yi>Jtf!550Fh__n~< z{3Le=!|(QPX=RO#6bR0XtIwXSdsxyOj8nLrSJx>S50z(4TEFuEKkw z4aX4P;|@8#_MPhulQ|Oz+E9IYfh$VPIhMQ#K9b1@Uw!}XC>Fq zi8tm{2dB6$e0JxW)XR~aEST2l4^5(f(kl(!1mzeBhTY#pr&WA5vpmO{$Z?ayH!~a% z8{-S$U3hmRQOlLXdWg0BIj|w1Y}CE*nj4es#g>stkd6ORwJ3T{{tK2ojlk9UW9}H` z2^IVMQEmfkX~6r;#q$oTXJ!~S8T%4!a54gOhmo%^5=P$VK={m3^T`Ec>lv*4OmUmU z!xO=z3hV;&E3ow!rz*VGujT&8&!=!0>IMKCZIdWm>5UAzNryUYjaFNp^8iq`M9#9N z)dg_~^B@b2v}!j99>ycG zp-~WZ#f{TcaAWoXbV?A_OlR?HS@$J!&Vbt1PPld+Z0sGdoVL#Swc%=oU*GFre@NsM z5CLY&H<3b{vkNid8PJEsO&Tzb`5K%LLMKu|-~ebFbpwKB?Z3U%#toX?#4@zXauNha zWbL>LvIVio9_oDSP=PVh-hDb&N{;_B9{Sbjd#4eKVQp%RVYfjDa1N_BcDwB(^G_=F zaT=!kGVA+I?Bph#t7W@Y5~0@|qv*&ohQ~_XV-TJ&pzOyRZqO710xgd*)<*fZgs%@^ ze{Ev_l&APu1qbl;FRGS<8l`-~^K33>=$9R)* z-@#-AZMKy&u8%o%Tc{BV#tdU$UfXPL*)=%CuDb3SKL>rKV;i)AY|^JbV%#2pMI3_m zt0g(Rn|C|WN7hJt)x!5?+xD{<7)*IZbp-8Z8fn43}KcZchl;*T%LyjPOr25jvTCdxpMgM}x|N`jEfbbfqqhp-_JNHOGvoDB4k<5h=Cg zHh(7JxZy#(Ftbrd$76@Du1$CM51<;hyhdRLqipdi#a8sx@>>`oJoBICruY$U8_&I`->0&2(Wp;hJwgb`~!i`n3~ z??y+Mf1iPi_(FcO6k-0d=^iP*&><5Q3y*Sp&sP`;-Gf|{1y#>(2p@sAb_pE``^%<_ zU=u$TmHr$bp%x}#dc0=7@|^@zc4SM`?_b_0kDGCGCPelPgPZm(VRWkLahj#afhIZ!ZdT zI)twoT!fmUS9Vmcr8jzJpLUjywhf{G>f*Y??X_!XhHSl6K!Ij3+kQHL3X=n&mqgDS zq`mkdq`@aqH-A!cMn&@O^EMt532L+OiObZw;ADzl=dYen>6@24d2Gc@E+f(Pk(qgYg&J)NHIQW`T3KBI>l>|Ts{JP1x@u=s`djXic*Katc{wp z#EvgjEf(;rd-M$PRp&%oOR`k1vS@4$2nt5|R-nGdvxgmUH3W2>dJ`-c0>@fxbjfvT zFisDTHUz#O)f$ZRn z>$sHys(UM3JGAL-nLYRMj}AVi_4A9`2aodFg~AYQF$bKR$NE++YRYRkhnVI}n8b`D zWU8r4JOg1WgZ4jk!gUVo34ktyfV_G=kih2JPtFcw?4HaK$Pxa+5OZUwnW|o@|E3Be zWK9iVn`Erw^g)=0~BK0#T;MF@IP zM%{H0ekSR&FsIW?sOxj8!r*67@$o`!`{+<@_`KLjr{|^zQ8xE`jXBxtOl)=r<8(yM zOZ(kI*uNfnP--XAsCKa@Gr!V3-CEqzGw8L`9UI}Gb`#Ep8&ECJ3lWy5B#6nsQZD?? zPd`PwaKdlsU5w|UO-9X`LEXx_a^;6FgW7h#ob2eyx4K!Fgs=FbI{NGArQenQ%Df9| zca2&c-lmAIUx6)Ox%hsp4)A`o{Y6K#=lzHQ^x|T>?Qa<3&EkCV6FJ=_{kb|~Y%A>P z21LSe+sS&;S5H_IByD_Z1vp1e7V$W;WUSqVdT?h|Vmbe#GEyN1cDK!3De0mW+XEm2 z(^jA~{=&*});g%1Lqv05+C1tGS634{))(^B1ip=*TeLAVjV zeEYWUWP5wFl#kagyjHyJd*ya+g5Z4d;~-P%o-9+K4AWMQ=Piw>wwd~@7QtB+)J4c< z8YfE?@CHj@r zc~s{Zupy(*Pfz>m09AndDh2S|cUmJgt3A54ts=U!Z$i3ZgGM;iwo1noJQ@g=ID@Ei zFFD=qE6wZ?k-sA;Y6xQ!pVQhSwzf0Ris;q`+s0?7NyvGbU;U73je?5Yh&V1!fCRG% zD?*NJy*f1UI+lEPgUdmril;N_xx#$-8n;N_ei79>>_WKlxFYYyP*h$1$K>0b#mwYN z`=9Q-8EL#lK3tSz9&7Z}29U@_<@O9e-SYovoHMs4pN&X&v3JCI*N>hb`(9Jhd1et{MX@nfTvu%V zzE=2?8*G1C48%O!uK0jWUgCZgTzuz(^HLg_;5zj~m+v=Ptn6_n*NbYM?kj$wwu@5- z(#r;iT!VgLMT@yjIUM(qP5y_DZ}U;nLG6v-v|}6^?t!_}I<%iZ&2x&^%S1izG}y=p zM{Yero6J`k391@v7fdi-EJn9$#HW@Wxe-S;Dv_|ROz$fEqFj?%wB_9R6ucjp=(eox zWeqE$@}I#z?O)m1SH202=8?<$}Q4~Hd!&-N>%Ixa#6GvZ-IQtzL2?v|Ue>Sg< z5TrN{&eUdsDRVN->B)vtu7z11#pziwPv@cXGaDgWw%uDe+lU!Rseo(Q(xJv%)i9POpJ@~brKt`iC%=d04) z?jGJ8e`N8a@uK?gf|=mC#f6^@r=p|dn)e#Ukl&gs9@Q$p4_SFsY<0&xbURyHoH*P^Yr}gO7vldOa(Fwq;>G~r%5R}kGS{q)3MLr6O?vO z9v;;x&la2+U{=m<9=zSme7z;pP4oFu%F&8uR#{#%N+xUyv00__#GOgGMF2e&^Xn+= z#;Q)T6Q4RI^Ygn{JATTVI_)KnpjH_UjipdA1EIQj|bglX~w1^y60Mp)keNH1{Pap&HGAu~q>w_vkr>F~~Wm~s#} z65pXrmx`qsM!hMS+eeH?rTau1F9|SWu4}PxlRQ1OjE6Mm0`lJgGz&$GU-) z9l?q|rew$PvUZA!Pq;kL4Xy1YcXyui2R|mON|HKxb1QAq-=?^cwRp{*g9zm7p!i=M z509|8iy5AO@^1MZRCHcQCGP~eu&A1y(qs2NpiIPIyrFdUhrFDR^jB1ezi zuUA|1Mb8H&uFMeTtbEFg0Da?BebWZhe31%rcgZ_?J$KK$ZGd$631Uf4t(Dkq4GhWM zk*SWX)evN?@l|8^N&QRJWJ+L|+*!TjFIC8lV+)%a>HL(^;=ZSa{o%F!LiHBm{`G=` zTxP~^H_hQX#tnf|?}b*XBQ_Nz-N_fPSpC$9Nv)3%N;}#WQRVJf?VhbDF=%zL7PI=~ zz2Zu>(=p}a%N9@r_~lAdL?k6Norrn`vm_S2pC_gn8zX#~BOIZfsKHns>w^fZ2&qAi zyYR(`!I;_zvMwv;iFF*$+asK?%gm;NP@Cs4XoSyz@X4VpAM5aL=zzwM#Dkb``qq*U zh8`(UgffSY-Gz6`+Q|CC6op|a^F!{A5vk5l3G{GScJHC$x^-@g^~t*wd2?Io1RIrS zwy8YB;f3$iMu($GFHTJlYiq(pt8H||N4Pa8$m1jWCt=#BN6x(%Cisqo)r#?67+f2M zevY?$2C*}A$zNO|%eJyRK&*s+Sckr4`Q0kZ+`%3)ZWTIW6BZV26I`bx@&w&zs&LZQ zA{lM;ZbZnbjbGq}pRr<7Mg(kql$$XHbMp21$Rv@I6f@t~W9$?ow-0EMR)vnD?n3*g z@3g#+tIV89Q7!2so7&$N#pWrL`L5qTzMx`Q2;IeL+<+#YjIfV;6Lpuaa2t(5_ML8+ z8;#3WsLFdr99Mrcuo|1T#cQjk}D{e+t{JsIFtME zUI*p(l;#XYH=wa?o5?!=6i5YnCgZ0sqZe|8(}Xl zoRgiNIh#866Fq3Kd-iwc&|MkVy@dhl<8ud*gFm2dm>*3{r7@ikG-LImznyfm+5g1i z3Y$u3rnxx7>|yX3Ez7Y;n=z!$-Vee9Bf~Zm*}?;rx5<y z3TmelN$Z2k8b;cv+J@)GmMK!C`Vpch@($PZ=N|jau}e@+-n7}TKsMpeOUg_Xk3FX% zJ%mqU!v^fb(&FFJV^0-WHREU1prcO&SSHHR2-EYaJnjLN?q%iAbh#)REJJ!t6q%W( z-}A9-f-p1tfv%~~HoZd2Q!|p-pB0oMDpe8Qfe80s>x!yT^C(2twc~K(2ndr0FGx>$= zs1wYxc=xKVCYylj;KjMu z?|i}>BQF)$5^lDbPDVa@q2yP(7#6zJ6Bw3IU^}d|^yI_EfQhNhoA0xBmM0p-KB8Ad z#a42)2s`>K&%7>OY+Wu0)p-zgDKBN^#p}An*DJeiE5-KBC0{OWeP1b?X)5PhT{*g1 z>D5$axH?y~@+zwK_084D;Fa1$)pZlfF*baCQ}gI0p{v8IyX^9+2dmq|IsNso-BlN8 z%4!11*==kh9fq2nEFy+cR}zBF#Z6&trEBZ#@`ACweG*MaWhk9m_!3=Ly!jPPi}lQw zRTl}0;YQ79XL(7G#K{-FlOGUcg2+P;g@T#T*vSuYdOv)&06xvK{@HM2-hN}jYvaq! zjm4;qrH32K1sf}`H&&xwa&07sOea5+k>Q1pWiUIW4qSaKrM|@?lf8M>i{0^==*#Vq zWMi$An(%qDYE@*yo6^d!DrS`TTJYb>uqc;fRo7sLO>m}L2=GswU}A0G5Wr$JN|y4A zC2hj5Aqq#~L&dTsFCF0@Wicu+w0E+amOUFcCGQ3$sn25kTMXxW1jlhV@9X@Gk3S17+=eDy!OQBo3Q+rdFC~qdo?g@ zCAX0*SF^v=?0i_;*8c7{_ZI)d=XWW8Mq(5e;YwEU6Sm*uVc(_rukj@L$pth9OgO^{ zO8ZSRd&KHfk7LxkPG~;*kOpj%cLNQF;iVSUs^IG zDWmXu*B$EFdq0vyZ<1AS?p>BSOQA^2o#s3`!U@kl`w;N7Wr5y*HYq&qdA~U-11V_+ zyEVYVJUh8)3$O4&vftc$W0z3sr>iJ^7a3iET{cbvdq}hc72$0pGr+gNQjM#|0hi~g7jCf zd?)1Itvh#5CuEt&JRwBKs*@P8a@aq|%J+h<-~KOFwEvA#&DJISZAkmVr85`)ol@0z zyZA4+w9SZ&SlRxsSoz;dWeYVO(|<0NkKg(mrFt~rAC7A1|He^0%5YTw6QxS@{;OC1 zcTF|?ztL0$IX)yzw|MgD{p)1;ODjq_u)y;IHKYHjPB=oqw7PIG4|Q3(BvR>Fc>z)G z8o0jNKCh6GEKmP6r;U8T%Yl6D^R&{3ku1M^U2-PV0r^`vXsv|kbn~xd`K!4Fjgc%X zA|KP;JZ?jdRuA9^4$#l-m9H(cRbu-X!6L^NAMGkjfbNJ=Nv4idEcU~YA^uEDs>!cg&g^em#xm|0Y~Sz0vwyl7CQnDP8ngQ~+ApLz_B%EBaG>#7DDVZV)y?1(13U zuYqgVBeR-#@ag{4grpPV#I}VDqVgq)ic=P1Lb^XP8FSiFm*!`6##B=$4A@!DqX~+x zb~(D56b`x$m=7{RSnCxhMj_UvY{Eq^09hs~2v1KuZ(+)4loakGF$K1eHuv!C%{r>p z5TQC>XO%Q!9?xQ-2PCmLsZbqRqm;e`LtasUd)ze10c9()9X&B&B=@<_Xy=zW7sYwt)|hbYz;k%VDPo$V+M(Lu z6W0%yRv(J9oR8Iif|z$S?1ZP1#n9;3`C`ayIyIQpAel-{7WEnsYrN$7LU+tyr2n3s z2iIUE4JJ*^3jgAK)Zjamy@a44t2$8nRUu;_4n@AaRf?Y{utKgRvZw|(4 zcmY_vcAy?1ePuioTIV&8j5;HhajZ(}q}LT@6ItRh_I;UwiUtd%ave<_#@mG6s2D1Z z*_v0>#M}Ky{9|Cj*h2~RIy2y8|^Vl_cagA>c+qYYFyN;`v3v16;>sVBtvaT5}J-i)wPqD7S zIp>-ku_a+;4c@rt2RYOT&q#K?F3bStHshKH77yHoj(uG&lzi`s7y zM05{S9IbX7sc)d@iP#B_k^@;nVhUtK@1xzq9fH{j(}78_i=g@9W3!Q8I<8e5^~)m; zLbfUISrzw9jQH(pbgG}uTb!Q%`0b6}^!p89l-BL~C#67iTXXkCpQtiN!&h99YI099D=Xi~A` zt(ppblxXcSE<%P<^9LZplRe!P<~{T#ts+qjUme3*$3a8FBT*H$i!5t>|uyp z=!HKyM;3jkei{b1Pgondq;ApTTBIYhCSXUzlX)-XluE*XIXxXxlu){DC=E+D%;&0n zWn=(}VpVf6rb**pN9?lm;h67< zDB_8|x}-99hMa?Wp7mOxrFmsQTDzyGLKsb4KY1%(Pd8rx`i(`BQ$g9UmpOr^Dx_YD zi<9gm@Q_fQX3)8$%L10dzcwj&<_ut>JkLO*5vCZ^ovfG;C-MMER97-#6Kp}o!)AR} zco@lYe?*#n-`|qu)7i@pT8x`d=Ek@|HGWNHd*3d&T0SuDOvv6 zxcOJI{HX^2BL+r`QCofY>EQRz<`B&|8zUKD$L%5)lMO5Rf)XIJzbI3I;3rA;+WYBX z_^C8AbEAS%+N)MYLlP>aDdqmVS`Pzl1*m0bd)K~AkT~HuJmdqdlPa~{!Ff@TP>@5z zl$DE2`WP|)Qj}Sfoxt}5K#KQty5%y$#h}Q<$=xpqZc;#=ODHnsp_%{^v6L21s_qhB4 zW|OFoQ_N+4@Jh2Gt{u&kdzn_J!4r^}99P7CCkOx@kSPLj0E?he2Vz zZk~m_YJ#w1b8Ore7Yx~Fy3Yp9PMYN>%b*`XJOa43gw9;zWE>}p7hzy>>hz+e(1aO zo-vj%M3{2uvSmSm>MHuiX)3B&5zM>!sd@Q0@N|3WX#ow{9k2A@dAV*%oaojCXLn-Q zSn90QsfnPChh$$3X>-D%9qbe6`^7K~gTCXeb#NgYUa;%98tqyHz5kUzdC&HXDDIch z%jFNJ*xTQ-1UyvK`&<>?>yd$At=Dfol7cEe`qrk4GQh7}jdwb=0HM9kEM@91+C0ub z*I#e1+NS?XJA%zWTAhIPkoJ|0Rn#2nyU>tDeIc8RqYfHUyc+x6d}Mfy&O}Rd;o$bf zw;!+Gg86h`NfzN#|K^^rt}Am?;iGKq*Sp-tDsF@_M{fPR(pr>yf5L4F5ic>hbbGZq zY4x32De1QbdzfQk?z|CKUZ03eW~gMfp`)WA*c97IhvfJD*gW+1c;RIEZWg$);04r@q>cU`NK2dA|QQpSDd7da<>j+6> z@O*iMNm|6B4#smgB4|No9L!!zip08OG`k~Rd;lLQz}GPhgNyPo2BHsr0M=SWZFV>* z2zRTSoJNVkIbs$EIKE_)1t>^iSVZI!#R351vq2CNGSe~oMi8bJ6n+QhSQgC&p&*gg z7;PQ|YaYc>grvuV%E>0x6EP#UG0d~ECOq*{Orc6!kWeTS4Fnl3bT#u1WSND>GqPp? zRpb`WO2E{##QA#x13v7FJZ#gBq~xGTt^mx_T5@_fX?uw*6m)+#?LM-W^g}f!9Y$uS z#LKv2v|tgC9PnjALKTJUV;Y-fZ8!@#jz*8G8KST%0x^Z0T)!w#G6`82PItsX>JU6m zxPB>iq>dw^$CdFVnWU2pC1B=*oc+^4Pl&+V!?Xw>08>8@$#IcmS;|qJ>KYQn#&!w- z>YV*yAPZ8;+p$z7AU>HV8DWj7AyJGfl94@}V21rC#zyi_We#{y`YM&FC6-1_DVK^v zlEY16fO(zd-d%R*9{xvN$LIj(m>U*3h&bNLIN=59!()DAyP4wI@;9;H4dB6&?wpKF zSQ_|3jJ*JlzGfU9fWU;G~gny}wU=jTj)1WroUXG$~YgwJO-76VlK!~-RjN#P*op3kBC`=MiCNGsSf7*nln$(T zFnT9jxpP+GlNe9{WU^SF;;h6}k}?dp&4m=%MwT@TuM1B~10tJPGjHF%Z1{9GHW&}a z8(?QP5kpb{KOVK!f~g=PV#n{)0vU7Sq?e$iZ724;i+rg%H;&xImkhx4BE-gtya{w( z^vXp!B`)5|09XacI3wTq4hV(Ihq!0L0z@X@S%&_oSvnJ|JbJYSokD^s`mDwb2&cE23X902-MULee!TtmugQh5$_m!|NY zpn;f5NM<}#{hmt3F9M(3#8u_(0mG9F$Rs9 z!1Bm!nLuWfkp7Ff=5Vvu!bOjD3u)O`Okd`k*8?k?noey+ddb-D>^U?d(`Ox|({B`n zfcOJKQUFvgfC>gs&q-KF0Ald>Wlvtzx0sO86+kryV;?3amWP`7U0mQ)1P&+)4+N&v z0M5&$u$)qwFnWOc?EE$K8WYd2x5fPoS=Q7~316OMQofT8?B(HEvkAPp&%w?B^C2JV zo*F!`%P?uo~PqnHJKr6fG85Nt_Tnn%NCqUTfbcyq9$Q?X_f=4kW zmrO%);iVQLq~t_vfjR-E;m1RdX1TI5LIKwNuO#2twT>UCarIy@rK zIN~cX$4&eiA9KsgJnS=SAc%-}a-2hf5WVH72c$*@Wc(3{;J^d#4uPh3R4}BX;U?iJ z)1Q!mGk3@NQR;5+3I3*$TGT^4aFgDYU5;9K$9=!Nas_!0)q?to6lYk-fh{N$xdrUr zbcUB>^$d_7C%Q>++xrfx90LZ9Wpn%C`$!V_B1lfu<3 z?l6oJP|WJgcNTs`77#qr6sXfAC<~y@wyFiRf^jr9T&}e|nrGD>nqyLLZED5o%%su6 zOKf2c0p8(TY4}!cRQnGnOJ*Fc3@B~D2|sdg*HRSf6BeJOo0sggM;rx2E@7vE^Y=T= zkLROvJvwRroOLfzmU-3jaKD!_{BPbkuK#J;dV~6Yc&3>KG%@2^oqIcUtsjNEVMnst z>m1%r)4r@hkr>F`ZEAO+~5M8t!tUDyS#Q zHVK!mp&8l`bB;tA!f7+{oFWO_T12+jgT+u#~n*4*t zgE=quL8lKosL?eL&0_|zQu9X!5HEfM;r_t&BfSt2^=|j@SSXX`kv>;K!&TXQXwu6p z4vFGcpN3%*#Nhk#0Zhdc?5Hf@We-HW^kUxXXTiN+smx&B0;ND9;3G}5FW&!I69yT) zKI$?EmcL4$#bxA5mVD`Qupjyu0F+PlzdH1~f!5QyK?TV=}XxJU3FGxvaMLk>}@* z;1IN7>j(9n5g}3WD7W|QUgiat1U9ZEmJ(dIw7)`)`I%*hZeHV6}E4lF?21( zO>&~8pXOf=#y$Vmkj;`QyDBREk%Y&#uYznh#p+17wCayaf| z)D-P`!o&*;jzIT22$A*rG?hQx^w)~?mipm3|m#U;>2BmDKYU>(yaXK9G>a3oXBS)IRTf`b?;T; zjngyTs5!_WJv3m>fUPajeoi)L&}v{H#2_KH#(vU=^^=Pr_CUn-;k`3QLh|o66SV-H zEN(WaxQey!PR(phbgy%1i%S;wiomJUDK-hDBae4NZTr~NFoeJZhY)HtRk0JlmoOr z`OmhvwocG_$AHDInU)k1txqs~9ly{lxPEvGt;Q|McVYeA>%{s*j!TMu7~G7K&-m0; zmuXd2$#PEk2&>y7aQTFR=6S2d4VTNCEX{bR1y1<23vMqV!NBS3Cr*&dCX(e7i<1af zBP-7KMEAPL<}@eB)oqjIJ&WVkv0wh^V&PywWF9(5MS0Ix@qj$&NRC4!teG?P6!2w3 z?gHc+tYYruA=8R1;rlW7?=s}?(mCJDEkT|G$eZQRD{h;9bk0EeS=8Vrdsc&o#5Z{! zkk=;isxaW8vt^pd!D}mZFmptaV-vXVqDS0f1lk1i|el+(+d!m zPf%v^SC+33YsSA1E!GUL#tg_z&v3Depl zAeu#XiyIXEuaf0|o72|(KdjyNJKKT(|N9_`gdk?sj6G|wDr)Z$vvy-t?OIj4GR2Nf zTWYVOsM)GLqDJj1+M<-UC`yYC$9sI==Y5@Xea^Vf`3GE)A6{3k)p;((W}HZJD0 zFEmw$;DzgP+s>taKP2p*hDuM*k5LP4{xewya@cGmOZ8HD^d8uV=>Wf;z16)@gOGdp z`LB`Fe<#a}O}M``&pMMW`n;7+|9sW`-!;{5u13pt*?0$S{Wy_o*<{!y2HN2YbsD_#kX_qxw-0t5erAf_;lhKB>ToRQCys?G_430v+{`yR7$?0z1z#* zjXKy6y=qkpUu?w`W*t(=fM1Xex2Mi)RB{6NpDOTq-kI5wS;84rXW+}}yx0=d+{&v( zR`7Y%_ckZmT#H$PZa>EJysLkUbebY%^2=(M21^q(7D|4mS9!y zDS#m=!(;oDx)ncndYkd%QjHCt|2fSUuwBX1VMkd&8(5Rl_(93c)5htyTZMm`FXpt1 zJ3l=ji2pgIF8ab|^CIvCwbw>i7ccOF*XADX;dPaMwQeJHgE+gk@0`YWE!K#eIpc zs_Rhg`+HU9?(g&f2J{tb^`mqt8E+a~v!*wVNb`U*204MI_zu>qdKsSns#iUK<eW+xrgg~EepvOm=lqGZri=C-b>^Ab+P$*i4_YT%*TD~V zqTUM(SlZoqV2i*7&<&!750!h*vxDGrQ)4K|^e3$%Q@;BkK5lPuQEj#*lUP9@BLutF z#f_Khy#d~io{K;w~A&zW9g?V_#>HN=q%{^{3J)Gt%?nlv7rs#N;T0B z&NAuO!)cGgLn)qQKYcVN)>&$BUYDr@LDNYFh??+@!r}DIx3nlj;o;kdA|M?HVVyZL zHAtR)K*3O!v%evN?);YPLR}@Y!N(Nvrx{T=J~_a%K8~_^g6Q1vGA7mZNl!NyzQtLDRUB&d$8+hlF~W36Rz>G9T6H~btmQ$nu9~5~mLwEO5FZK~`~DHR^A?$8HJM}( zd|OYEqa}ey2;6!2Nnh_lYci!CsV`{5(Dp%78b3Zo0{?mR!FES|&Zf*e4o&3pb*f z7D`CAqFwy9j)^c4--olk!ACvml!msi_N%*}CRQuI+O35uxK zxUoie^++u=og00Yxc}g6(Y|E1IwQc)Lo8V|G;l#cq_Flj-4LBGFP zv$-C>Ya#Q(E@M#hS<{fUQp7OT`$INM%b^K>I=ShobvBDv@wNAG$yV5v1v9*!;Xud1 z)lAKwB453UVKtmgJ77F3-aVnG*P8S>Y2!s7W)iSNBow{p;(g1Bd{z^ zD@cjyOk9Eer!7%JXPs!TV9IxTg&e1+jiQntWbL7(!C*^POCTK*?`~~J3s6F^9LDXS z(fEG)OeEI+jQ}sbK9P0i?PF300^4*E{vJM+IQB*{b7nFF2taQ$l5VjTTc#JhYn=eMEUZds$i^{_@L88bMmdesG5%s@K=;hyr0_?nx_GUyIeq zBkO|UvYg875->vOvBGVf%9-FJSF$qCZ)S^|p4<~bI6)T7Hr~{1t`ER2)VTH<<^PdG zR?08}=Oz{2=*VBe_Ug$!Z94Z$FBWsXh)$^jcJ(%$d^fv^&n{tBN;RYTPCbbgEOIKr zzL+KO^p9`@e|WISp!-M3(N508-7e&;=yD9qsg)V{y4UII+Y`^E8?hurDDVR!oLF(b zu$;yF^BO;uG;tggyhR{uul5Du`WWRBiE2?RLc)ndtcO9KocMuvZa=Kv`+vafkl`*; zqvUg^Lrh00g{ajF0 zEQ7&Kx8G-HPbGl<4k;@WOX#o#`+Y0Q=#kzCUC~srHIU|va$n*)q>J6tlRN*lDEhtX zIrU$o+-3Gi>JKM6VsYVKQ8AxrZ=Euq#eT2g<$rGwd-kTC{4L@-ho;p0*&=n19^q;J z#&TGVFa7n0ubivz?EgV--eEvYK918pE@9j02*C!^bQ1vlH@2&;>jYmDo1s_8>{+AH z)C~r1l(Ogq`nF3hHauH{aAB%ikovd*ljn?jc)t~d6 zS7e+`P)*0>kY~39&C9}8`eZ=OL3>>Vp-JMq^@6?C1wAsS^$>*2WG{-u1o>uou)frx{ z8QE|EoaoSaQdFfqBBjGh?!%xlx{x#lBZ!s}_M)C9Y8^q1>b?6uMH&4R1&Hrsd92lj7-(v^lqk6u zS>vRl{?ZvzBu7pjryaMXz(P#%i^j4uMN*FC)TQY$;|jxSg)ar^+MobB6qay;AFC6{ zkmQ~ng`*_eAdD0Wd%o;E=BjDT=FVGnjn4tuW_vR97B`mM zF)_!O42YVU&x9YvpYA!Jz6=N(XY`S_Pdrjd?- zzo8g0GDdQW@>=z4$*CgR6K=;+!~G57VG1#SW%8I2R)!-UJ7ce)&{UB49)F9rFl@=V zm?q@PTTgRr2jF`b@qzy&#paY$6cxQ0F}=(?Xydjz<4Z#|-;xcEEUyAgAhg$vu-^RKn~Bgv9_3X_VgyyUbJ6<( z$Xl^^)X8XZIWqrD!Ib#G*PLarxc>bR=KoOc@gMbtVV5%Md)?#7Kn_C+TI<;?eU2LW#-{7X+7OE4A zLHdv9g%;K++`ON0;}}sBb7nasL`7jg_7^D4hNt)p|6Ah)^SY6~2~Q=6Bhic(FFj&o zkr2XB`JJ)qSodDY4Z=Es`&7mlX~)$0Hc7HJS+9K3SDjsJ@m2~&oULQAl~bj9+T*0< zBwtVxdS%bh(GCX62&h)N_-ij$E|w}vV=EF$lpxt~MUF{P$%V2I4lCb*DLm|+<5EsD zA*Qj9y2(jbQv6&lR`U4-F>bbDX7Qb>WbK`ai+vmjw5)L|g50mr{Snk7AFH4$NM}Yj zQfdX7q!TyVe~&GGYP3v5nh_UUY1`=v%~MHvsyFsx#og>h?Y|R^T{^z!S9VceEUix_ zO?}ATzL|aUAq#?XD5(gIy)m%Vz|{pg`=d=3eUG-h2?(xYSCry@207G&e1Dl7Z#J~P z}~sG*ETN8rKlMFO~-X4>18U?Rf8)vMQ;cxBbv)vFIOhLIuG%jP<-kK zj}%aX%7Hb$zQ9xEdS*eKO$0{)VZgRq>4T}-U;WlT$}1dk zKrm#_JXOey%VsKkU1P%?E4q0DY{8K)uG+TgfHyFGziIua)bQ_S8gbKLeBc@Prx>AO z&v1J;FRxVirmAV3V4N3`_(?ST1-5$Aw+$j1K4`t+mA$xO>^vAGoEZE=_lD9I0rk<~ z(I%?;-Q8SbxVd)wnx1RQ^MKr~NF^dAT~DK1L+oEjHqMo;bh;b@if8jCA-0pOTr1!X z=jz4@@~+-V-rGr~@1Fv^@eST79p0(^tEDm{sZx;FY6FnJ5M#FuY$K}p#5i*y3I7eeMyxqPdj|}Q}S;o z=K5I97EJ+uNN#h8uhkcCUk+I~na~Pj+{j-162~K05&rDVu`{h3(!4+{_yGyCBNp;N zyV#&F>7m_VXpcD!FToFooWWN67Ipe2AltK%0#`Hz+Zt%2>A|irzhS|Gz9O>+Q1C+^ z*SMvEqQsk7qF&=|3e~c1eYFpY*aK#~b{E2T-w*=)prBYO$amtd&7<9<#@+MfhC%NZ zjXTe`u;g7AGN}C1uExgTN}N58ygqUF;X92$-QRkfc0^Vh(Dp^XtfAxj=++l0A1qP- z+hpKw!+^64!?(D{sK$T;^R@Z+M&Fc1zDhw(-aFiHAm3a8Wti0;Pu^Y%Uue)6VEwy? zu`hY}%KfiCPI^0yXsrDrY~Se4pl~KIhOr?DZU-@^HF>Ed#G!_M9W* zHyvZ8gHO?4SiTLi-aare{kjr!V3~4&YW#MYp@*Xd^!9qP&KJ4cRr2T5xFP) zbL=Cg`0HbUe|p6CG-7C4{`b`C?=s4X3Kn)Ns^96P{qgLf&i$dEe}zCek3J4m5f-cB z+?QBm7!B?pF?Z47o*yP`ho;4c6_Jk$7sD94j#9Ue0DU*vFW3*zp z@AyW-v3=gLL)Eck`?1r=vGbc_m#t&hpLeI!yrH8mOjn;CIWnvXNrQe6QPPQS*NJOF z(Aysp-3?s4siD4k83{ZYh%Ui^tt!3^>Gr>&Snn@st3Mu5`~*of5=HN2qg>0pfBqzU z*K)}1=KoBNZp!HR>BK?v^*FJPJ~3+K9zq_9-uelFe$F?GKypA2=dI7nrch}SC%#lk ziRq+#dKYlp&8+GGR@d<1r?BVFYb)iGDZ9$6F-SwuW7%s>5W zACd34vqL^5-Y4RDZHxCK(;;W+i;-d`%0$tq$k**TX*D?pX-~}|_s=0Uua)eNp|$7G zG+Jo&o2c~oGwf>A`F?n1s+)F2XV6dSV7cdc*Vc+iZjZgA%dycd($8~4qZRiU`siKy zlys*+&~AgLB`3ey1Y!_uNs8ykL$`kq-}^n1@SB|Xd$j8JtM=bxBfpnXKc-kci0nTt zZNNGwF$B@b$n2)ePh_)@;o3t5)31N0hWx=2W6yrIO$9>kyQ`l2XD!xrdSDkX|K@1% z1Ss@t5RXHCyk)pP|DBcK0lC`?wxwFu_Q72Wv)2g)>dexiwHkkaftl@tu`ixBl>yz@ z<2D$2Vw|X7ip14PLwwMG34c_X#^N=eflL3c-~lpov3@2SZiL4B0$_;$D-5H8-hS~D zEDiQp1@aX|zympr>%0&6hf_F|Lw2?g1jrt z7yDDPR_mhU>n8XeCMnqS@1is1#(8qKOCpPHnfec{>V1#J7wR0b$93$KxF#P`^ zLI1h`KdagQKPBk@QM3OaBcm4U$!t$H(rT_M_M~&xq(R6nV$ z8h#Kz8z)}e+n3hbUQ=BWUt9a%Que>H^GE-bvJ3Kaa&vS3BW0&&X8098amsm|mY$xP zns!m1{|n1b$A=M!iCBC>JQ{aDK0Z43eq?l9P#hMSQlv{v*Ffh<#YPE6`Ta-APLA;U zr<8r~zol%yz|dg7I~Vb}$3LX(8~>8BZ+iGRdiXe_ZeNt=|4Yigz_MNc!(>04;%n*W>0zW(q2Tv`1eShm77eR);A|5WIFLH`cXg+k+G)eJAZY-uI!D+-$b zXEIw*@~VJ@%6~%if2-N1?*CDLm>0KsKo~E1mhVqI@kvb$@K9o`S4XGwTM1Otl?i$e?*t^{NeuOV zzCYbQRp6GBbdPPveraZ|( z=@Di9^!eGx{rNk7k6Du3*`$tpTdCEtY^FWkv1J9k+OCl3(jQ4l8#kuBS@dR*E?_YX zo7Qgc7F=2Izzcr!lGwc|4Q4tkxB=B?ML1@7-v&;grb{598Ja?n{Lr-~xGXIlf3YSl zQ+AOK1;6fUtlE!l4oDS$K!M$0f$43v?; z7zX|GX6n8f4U3Rg2UM3&+n{aky_S@eV5N=)jl!n(t-sY{fTbalH4SfFZQ+p96G5EEiBf8+CKE> zN6Ye$ZE-b;jPs5p0@XVsQYq-_NU>(F-QXi_sU>T=+b!^Cm74w9EY-3d^tieU;v=H=y4I|JYRZ(r*+S92Q)TzIBUrEm1 zzEcJR?U0fvK|aV)#?7C#nq4#-Zl%B`CuBdRPo$kzGu_}ChSNirN1{p8R$$tQw)~au zCXL{_p+Tm-z19z~<5n-_<#70bMBk<3PHmBv@>lTBT@qT?+x>sOi@T+6Swwws?gW2J z`8jo(lR=UDLm715iRT@}R%d*H8J~He#iZQY^#0N%;7-9XTmwlOl2SO;$zzYTOpRy0 zq4K`2-F$Zb$zwx!8T}epm3Bw-cJ;&+w=q&BfUW$SrY+~-6`ieSo2z;OJkrQzD#nS6 z-)SlCn7(Fqu$UU5J)MIefgFe#-x~7n#2FQEe*Cs3{FZ0hB~zGpZXZ%06*_X{6cDB7 z-QE(TrGSMf)>3Mq<9%*VX+w@v+|+lBbfc*(FPRM9>!xvpi{8SlX8)~X?B)iB*HC2S znfIsG<|E@^viY+5qNFq--Ke|EMY1ZF7~#HPEh#mqyt#c27ssF<%*VRuT)a{o6Vc!W zh8Ak;U(y9fl7xjeO01*|hr}Oj+!D=rt0Rb)$C94%d3lt2L$oyp_&i;QOmehTwi?ka zNW`sXH-8A_)g*6O@pc^}?z>F-5@!eLtUeyyULjQ`5GlTBN#azD_a!Wx9u0Nd_->q; zA15hjIw!Fs>EJO5W0+P6gf$$S%7$ ztiG&yc9=(LWSi}+rB3g-kXPAqY|B?#f(!Vg6d#UX>DTQAYQ<%ol$R7sE3(}r~q_@W?pagpKA8r z4UQ-OQnT+uY0CbkW;2w4jhp^wHTypa`q|RY?u$jRxS#(@&;b`#8@1^wCFe;m#Jmx6 zX?zuY?W7N$)`$}^U88Y2>1Us8Bq)!s(MO*QAn2Qj2Bzyw4^IX~&6|>LjIXo3I2n>j zYf8Co`jKP#WLRagDed0)N1k6NBbxNhqy*Cqe$G>}p?Py=-uQ;_wbM~#T61=l>87|- zq;QSey75%hrqtv7F;{x|`+Y5JKEj^Y7s=L=rJmMk7R)&@QUT19A9^uHW-}gCK<;yTYBY5BBmeEmKB4lTcmw)>XAu}eWG zqw|7qBTi3{rOyxD5yh5BZtn(Z`?v5sMA+IwL_hq=G?9LRA6iVnYL^hLxCL3eycp%w z>RX@B>FGSm04m3iTqelt1+DO@==s;f3vN-pp+29!tD_)sn5!W6ShJ4c#2^=BvpjGI zz)Mz8P)xP4BIqHE9Tme__H(ZZW>8MI$QFr?l(E%>>a=U0!bvOqYj`;&6U^me@%#3$pHw${q}QP)co=&cWe6}k9V$7NsYvHX`h6;=sOv+?S56Bb&yqJTWEUV zckw&7!;gp`a;9+EXY@@5f^9v2(CjyxsXD>u$}`Ly45?V@Jjm!*POlVQQ4H&kUU%^? zR#L8Xx68&638GAEM0En!FNTYMfn+V+6bI-~PP`ZMX@;l6QtCd6ZjlfEm0C3Iz?#FI z;f@^K6~paL$+y=i`&rAMnh1X=$oxh#N+2I2-hq)^#7LcBWZ1ECDp&=3tWpG4B_FHW zfmK`lM_8`Oj?-4b>DuG;tDTKeFryPEqYj*DH7dWpG+#MnllEf7%9kqFSFYAdGy5>ManO{<`pG&%%n zMA)iZhsiYoi703lBKgRY*cw68o}bLmNR`(CH0cGdLegSo(l)lKKSiW%=cnaprfsmN znXaY|_ofQ>CB8gK-qcL#7fsnl(vJ{R-r!Ah^_b)0p=~mZEo5REdt#<{+DAy*bN2MS z6ZlF*$_Fx#D3kWd9?DUZkiVLMHcVwl(+|fJ6Z46insEL^R>4jp1e(}x4~2~a|F8p& zsuL+twEX7<>8C{cHkqWq_AZ~TF=Ery`G8CanzkB{D03OYSi>sY2n^3p;J%z}gCk1yip9Ro(Ig+;U?8 z5Mq2nE((T@$YjgNq|(Y15+f1|@{>CAQzB`F5@|7FaNH=9qYrJS=q0bytN?VbL|+26 z8*Tn7wb`iLJN7j6ej0;Vy15UG)h8jYF(Z00AK2*3(Bn&K&XFZ-9D#IA#df(#ZNax$7^&_U!K?O3>~>iX4XJ*T zAO9x9O_5MwC%g@wq=_zOsxE%?jM{*&q-y?Zhb1Iw%51ooDq5yI8bNd3m}JQ6{qkoX za2i@x;P(D=a&L9|(8(jF&q;j+@T%27X|1w0w=(T%x}1@a#87xIfPtYA4i5qtMa7!} zGOPB>IqlL5PZCL@NtZ35v)=IWAtu)cbZ7wQ5;F}SpV@c`UBuAkj|du$b6;2u6Vz0T z{_X&TuSCq#n9=%Rc%3}9o7HF5yn zpo{mhp>9)JW{mDk2G04A<^a|3#k%>M-IHO`Q{|H?&P@1530LW=W=o@d3-Z})ZTXTh z(}rf{hX;_eMjGl2=sAj7_l15XKkad2>u_ZEGK)up|D7?U)U@=kNOgFQwd3r#5*A2h zDcAF}u`e6`>`WXt-9a~9&)WjWeN>b0WvGESnEz_5WMbe60aOIHKk66L+>YUqK)BDK(ON(-+^%)vPe?IXk|D3SwG&1ukg=T4E+* zo>MY59s21{^}@IuMdKZB`oV_7V8foU;oFk0kt<`pb+3S0Jk$G-p%p$niAR@;Hd#~h z;*#i16l;3p{h=?_KiIl!WgwOPum7f~JVsue%{*mYn|S01hnM?@2_WiF@>4SO^Tm)- z91k9O_iM$V>CWI!(~-L0RF>x{7mt-g1>GG%;!@=6LD%cxTO|o}&R19lf;qhZC6RfV{j*KOA&qH)&vu%b~ebvis zJzZ=yVi|v5gChgrRxWVc*m;PFF7+DpXz1ZS*TT)Uiu_G2vqPF8NfYua{o_^50#kwB zer0xJ#`R!$&CxWJg7&if%x9pmFK&KM5oq^_jJdJ^)>?Sx0aI%gXIFz4=nNfwU;IET z=}AXxxKqzrZ(`2PLrt;FD+mAdTcYsYQiIEqhJM*BAo3`b4g_2R^DUE$MMneR=W0w` zW^gP<-F)axt0cVoyl`^x3Via9i>vedVHcJf1m_;$F0EGC2ATtlpy}IP3eAJWgUpL$ zWM;B89yCMdd#_H_i++n$KMc_9kcHf^oZ}CE2b$)|>FVT&U`Hbih`~^aLW@=Pi;olU zSB?ie>n`lZwXHvF{dJ;qt3K()Vs9Fk8E0i9@EmJ!8U)KK#(iBqi-zw2ot3}{`)dO_ z7tK306E<{=aJ-U7K-DA6=_$ z;TfAU-a|Kb22CD)D*wauypt&>)z;<2yvI5B7i(dMA~Zq+>howT(wz5%A3g|>WtXEb z2L%L3F}9q`&?9!?;To=~}OwXqz~EAUl#LgMMO=d!}D+#=-Ya`R>SwZhhSVy6sxzQm4UY)n<5T zJz>wLcyOkBhZ^6GT)+K@`*u?F?IdvT%=KIRyKeyAO^WOL)P3K8HXjzvnuE)tsw2Md zlrMV0l(JwA2C%*54x`}ll`4uCQ?$MaxZmn`pNm#pi>}xJPP=*hi~xE$MeBG67J&L8 z31^)-f^ptuw2OmtJ)m>h{UIGr;g9$kDnsqoL+cX{azSJ0DLw(GQ!wWqz+y_@Mq0x= zKTPki2$fH>G47fINm=Tr!opC))yDvtAH$8{;YM0i&`GsPd2 ztk3Bhd#NEPzzYOi5&)oWq_XUT5Stk0NHnN>jBT#)M?R6yc@q4i8U7+m_K>dw&NTsm zDc0Izu@?A=5VgtdV|XzSGmL@x>p9czH>PhNm=1Uk#`hV%7SsRfrT^8K>#GUPo1z4` znXYPL{#SyIC9_L~DUk99FeMPz=>KDa&SMi|wP~Dt#pPdWHi2pHopqk|yL$Ayzo%Jk z5a>ikiTkv6l0vznBh?7Er&6P%b*XK=>(Kw6pyvve-TxC-E3X*jay|N&=kA!WmcN$K z@Q)0E#VejJ*dY{@tL4rfsvl3stN+ggT?Cz@PHR*wUHH{*cfdQ}X)I{CjxVKU!d^)~ z)$Fl;q2sadLj8bn#K<@Q^XF)CSgCxgH0!!Q{Ib_-eBbK;>YXp{=w+(qg#&j|AOTVDklf?(|mI zpFOl5#o$h)r|#w3{BKPLfQ2UQ3ZUeT*JvX* zzBT6_;Ntvd_9fYon)XkQ9-xi2Ej|g8oeMSl7YGIS$agX1j{F<^(Z6$x?NYqM-?fCo ziuvO$HLBg<5f^-T*^8ioTa*a6mt+a%OHC#| zr=|ha>I8I9hMoq3F}}s`GR$`=t}a;#w|jcTxcj6CL1qgg9fbra3QQg#&u7{3<7v|9 z(+gDD=)tgNr7dZ6Y**pg!!6THHX5eMI^DI0!@d2Y$z^6?3(pM6o+3Bud@SNZ%nD~# zMC?N@TdZdXKm4OBif!y52I#>I_#Yhsyb7j;~w><)lrqgp- zP#d0Rh7QjrdVnSicmc zZ+eg9{^&TU)kY%7#y7t?szz)m|A|(c0wi#5z9Gaz(8*%RRxVDg@f_q+2xYkDfZNHD z>Gl-Q<9SFTBEx-ST6P+;zf??c=&&v!3}Na|;D3iCpAJ~o-B@v~nkiChgpDUx9(RH`LIW076Sk1$G&gCx`RGKD?FJE>NnPc+AQ}#jJ z=uF;ybo?p4y)6+rA1!7scUbHAc2ED!wGVmmcS~>fNyZ*Oto{+Fmua+eC*C5&XeZ=$ zo&DQACr}qk`Z!Nw@>US;y4C8bXN&l`A|Xhq%Z*Sc+j8t6WR;kSqR%_w(^I!IG3#>2 zJI{2<)NkA7!#iQm7KioD_DyodK5%|u9~#QM<297y{G=R5wv|0Uw9Bl^5xQM5icJjc z^g44t*+1x&F8HE3BhjE1Ce-e9+HBYVC`Z<#V%$CPu;cw0Lj0-jkh*#H0t^2Z=bfKb zLEW;vVlmaqA3I0#ejg+paWSuXy?tFJ*P!XFG6!eIk0cD+@FC1dk7*)j5^Gl~oRZc| zZq_OTI9qCI-uZA^IOyAXK?%HOzIw6xj_0qMFm|0=DgO6f)D5%f0oc9*TO9;w(rzg7 zJCUYRyq;fSRI;O4gLMg(FTPc2Gs=DEUst{^zc?71VCGc1wP48W4RiC8 zy@i+)Hk?e6WzAJ_M!*@82gL$YG{d-bTJ|GMR$pGtU%j?&Rr1Qj^gU~!psK*{zuui! zF>a{ju?}Wgq8?b=Ib%g_nUZl_r8JYZ5c@{FetE>Y%__`e|F@79ud1b#*6pYKY64>| z3SI7&i05$NN6EKQS}QO8>&d^qav14Jl0-Pf5gdrDg*lQ`=guXLW33% zxnU>P%4;rs@9riU2$uZD1}!5NZvRqojU|0*$FVKlhaBGz^{P8sP`#mKWAf`a>-Plm z`Y7!1UP-%0ww1Okyc>U+;c5da8Ivvv2bk%wx6W`XY70 zYF_j;$QMy!B}oDBh>JA_%CnO^D$B=|-B$on!5j8JY*xj|h*&%3PZG5PnCWIBpkiu7 zhi%y6K+^4J#kdFp`lMy?m)ey%YBW)b|998FzqYGXXu}Jw2i6L^j;S<^Dw zctF->^x}0{Q&z$HDS5$1On6W7xyv-xA&9y!NWChvljC7gk}2CfCNE|#E!GsW_DYqc z#;PAg3@73>$y|Noupty2Ri>n$Y(>UQ3-$3Q6E{A+fTH228{GdjCM7z>lQcFKVr)t=(|Td7DXf8 za&#&6Yfqali~iE^S5*Uyy&>VV#`D4K7mpZtmQ4twYG>}R9=@uLv<^!l^Jv^X#7zf&wEwn* zEew84Qem37e6-Hnah9X9^mFZ3W|%3N_k)TISP`mDLDp#fbx+0KBRWr2QRh{KPjz~~ zN*S)Y*AA7Ndz(t0O*KxhOge^{&yz*M03-W#=4iy|>`9ZOC~-~q^@&ZYQ9i2&$^5jA zeC(e(G58w#TXxPFrl>hQ{Kdk#(=^NI$$BrPVzouOax@q5eD(JXBNV{8ijiHVWQAP9RZm}@vFeB8z{fL+E+l3Y)^!{20^r|FFz5vl2~J7t#J!Z(MUl7h-dbu(z;NI-{F;z6lj$>v^SPlolE}@B;3); zu#f>jvY~(glzQh(C+0+DA&QU|{$}%_+9XjKOH4251ZN{ZPe0`_Z>|Wo2hCxTRHz)j zYz`_jOrk9Zl2UK}qb@|QK5fduRtg1C)SLlp&p3vFu*7LT_4X^hR%?(#a0jK-i46u| zETnl?+*z{4_Xeitiij$(wV$5d%4fNkQdeF|kf;11X+ zjH7yr`vV6HGb%}TdvyG~3krL+utK~MD`*B z&Yv@WY4dn~PDykwG^$*fh><`zi6NF%If#mfRD9Pg;_fEemO3I+Sv;mNX}b_U(Ir{< zbcZ^`e`3k_&#Wf*+|$+?4R~{+%Pj4xQ@Y_C-W#i9ik>sV;i)0({K>yYO3pR2I`x)itci*tWiNM=I9R9eZ#o;d7FN1r?ze!>`6{^K zHaR*j)x)=-rSB+T9^2$pTPt?xX)`6-PPmjfQi7g=Zn`}FiPhBWb8cc^zA;02WfAkO zUR1JLpe9vD11aOY_=Zkf0~4>R`}V#2sVVq@E4CMJaF_oT6%38Iw(?-SP6bIIVRTxT zF%Z-PmDK`66mH4oSAY}$%uQ^s`ZY$^h=LEBJ}9#o6us{UEc|-Km0S&bGTkS{FDD2T z=;m@jr)YE$#m23B;#h6nQI3euA8 zhE@2j&O$qr?E#DmUc6ybM`*sSWfCcpl2OO~rTH80!^i1^QU9 z&3N@w<+`dP$=hstW7pZqj;GcGPHfjW2quBzAg;btVylpD0<xC41H?6BF z%v~>#he-bi!mLD`>GH`xF|gTpKTcZk-X*dVCeC-*eR>9gdW7lZA9dO!AciZEr?P(< z@_B7LfE4qrJat!ia_4j3O$ra3VQ=7$M&|V7@C@50y68cvt8-2jCaYdDj#J>)NTAV2 z@WWijn}H^f^J`rda0*Yu`6svN2R`t>4$VM*H?p3*e&fBn-Dt2-SQ`0`_aM$0fOqc2T{AhN0PJ5@y*vq&JiPHQqbO}ea!YwjZk=Avma*4FCPH1X6Hw1 zf&!I6$X=Gg2Ii34sip&56VPOxiDRSZKN>W{tuH|w-hjL;3~n9dIw(f7AO9&!F$_Dd3p-e&4{Q8pm#rv3f3Vg2J%xQ}yx^ z9eIh)_Q%3@(MQgdE~^T=Ex5@^)=_tT$V{=X-FMyq*X^xJ^de%YQl)p$&_gfM1qDQrrhr&zN+(o9lU_mx5do3jd+)u2 zfPg5W34)r-?w;MVyXU*-oacV`|2)qm|IB1&-uL|p`{etbm9xIIt_@i&eN{i=Y4ZA& z!-kIvm4v+hZ%?}QgZ&XYX@aLJ;W(>x>Hz_7ML2!(`lrSSMZxRkD8j{ll?uJvZ?nEv zV90$EFpc0NJhDBQf>F$68_(W}p}B7Ke?-tXx?rFW*)BVW|AL^uXg8L{a*t#yhtUW* z9sdzpmbDcf%F&3w;X2PG zbieB+XXir~pk}ntVWQ0Sj_}u@*C77-O9UOidiSZYC)cl974F_7@mrd{+5E1cB~d!# ziN2FPiHavrzW*u!p^%G7{?8{9VDs-!HFW8CDuad#~)_6u|AivV3YLXoxq4DLMFn6^B*B2 zh3d~ZqD1>;IHM)!UvkFC?$&a?Q9M86#41t9a>c5#cyYyP^4D?2>&pG)N-)%t{F&T8Gh1hu-e$3bgM>r7BwO zJwJ#^{-z#Qs`t^i7Z2B%R0>9J$x+oQy%ysb-vAG-zmylZpqkj~ z_PjCiML6W9_eSx%X1TBL8~(`cRSeve|MqF&mHhX*ug&uNO&5RU@olhM3I|h9RUMViGDl9S=trJ#)fF2cv-EB;POn7XYF1v8NgM4-a=Wiz_a|1E<=WKj z(;js$6WmZ!HEX{GhQRqBq$A1*Tjhj?%$Rs&OhBmisL09B4SBM>FFqGL*Io zrt@*KGTU+iOK1BEs=ci|q*3{?HAjxwX!k9ovZxIEF-HEaxmxLVn|PEw`mEYKRe%M= z@LJ|GGiTi805sW^^-A(hIE}hgL}(NU*G(3YGQz|(ZrXLnkk%RJW5%#g zxC4WUxwvk#<|_wa?5^o^^&;6Vm{q9qw12Fs^IX%Y)P5u;h!f=IFZ|MGoEhp>O3NC_ zHqJ|J(QG8{V2@KCJxlf{`VUW}_ivtvAnE_-se*%puNV7kC;J;G`=7t>@0@>I_>ZZA zovHupor24Mh?6^?=Po6Yowf0uwXyZJxt-Oq?bWfJ)scUU6l^RGf17!~JyW|m)4n#- zwKmhax-h;xKejwOvNSuoG&{07(>1;LUk#D0uOt6zi1cP0{AHdX@_VE2?*G~l*(|c& z{JSBt6vnyW&+ylUg2B1b*4g2P|L{cmD*tVvV7#wkc%WmjuWg{Gt>v$t$Y599-xdlk zRgu2`R7Gn4rixT_bTs}$75Vs|sz~+w{7Y4&w4|^n&42vwsz^~${_B!=|5X*q_^T?C zoSgL6g@S~*`1rWEIJdto6uh}yDELoLBs3yCGz=3M9O@qs==Un%Z=T5IPJvl;x=uvK z-**av{&}Y$>ZQHcv!`xP|DlRJcXji0ee(4GXp30e|Ho9pKXwXkoBf+DVxsz2TjZ9S zzM_h*ypoRWO-<>W=zsG>c%DXc{F5Xi@~@HzQe0U;>?WUx!u1>SJVJ8+CW)}~O8r+) zB=*1aL^^|`7Eo{g-=+!*hSH>NGpC1sEFAgIsRFVrc582gD-(qVxmp=opGu}OE8#ca zg$OQB<$E_rT-B~Fo%?t>RWJpC;U+#^dLkLxjGyxYR%*2-X(N%nLEca)%QL6!#>ZOD ze{|1W*SH)>>OLv#$gR5*rKYAFM(sfT;(*x_uwkddVp^4|1!pk+ z9L44Jz+AOF19CaG%E6hfq|6WE5aUqZ-iY6d<}i%u6%iZtL|1xdDbYO)&VK;qFy>S? z7PH5wfjBytRR?z3KF89>ZW}qo0$Ufh`6jKC>YJy7yd=G)GGa8<)FgX%nW(LcXdf)2OV)drCbfxbXpWm6N zCU-x>sjbJnC{dB7;=Zm_E2e5wUrRsrU3r|vepRK+``v!Cgpz!Gsg9w~XdSfpcNMEK5>;pt{;Od zP(NmlWyWb|pzu$=4iJtF7}#r~_`MT*7nWp__a=CvlYT~wV)^G{-gUndHEI>Qj19)0 zzI26P%_f6hC%@>?9myu4xHXEpyXX5%Jw{SW_k)s5r<*yduJ3^;vkVGC?PK5^6gxN{ zl}5(SUuFv$#tQh=u-D`HRqu|uTgR`f&fBgCZ$w8PyiAbFzsi2wdKb`K&`oi;*`XV| zq|%+&uR;CB_>1?|oW7xP$(B$VJ@!ifIrL#C>sg<^FVkSQwp(Evl{Y>J>1j}>jBck% z#RuOj4#CJ^+8OHcAtF&YxC6R_WgZ_YGl--58ppEo4IhTOEa4Ku(48DC2N<+Y4oy;T zCy(4gxIt77UE!rCVtEi@KA6K$)7y2!`ykQ=p3BsO?iNcuhY*ZfCb*5dT7@$)5;<+k`sB!7{!M!(X2pfgJA>R7N1=Jk?QG5LoR@lv#x4Un z4TbtgrBvG`S?4&#Q1pG#UBPSH07=&KvZGA3%SZv_5kcQR3U6HAUWkg^)(r&k#>9e{ zb#gh{K}k*Fd?%3oIGDMU{XUL#O>>K!jcC-;BX_}YQn*-iFcWu1ma+r^izqxjAr}qFQ8Cym-blLQnX-x9j zf}NN`t|)C4bGa5xl<-wtO}6Y8FJn>Fy2*h~%6>3>%9JO6o;*|1nhIpLwmX7T2F1(B zC^C-u)n}kzWOho*g8T)pREmPoSH#Q$FwZz{a_uQ4r(k=fNc3(vmD)cEWOpT6|Cp_a zHoa!o@QG%FKKpkm>O9VJYF@uAEd!%>KaBxSFpNPeXF$rlO-uqGnfg>wmSu}1L_g-m zNa(exN?$IVzNQK`KmAFsoFEpl509>ECnJOD2cp*QcB)JR@ z`A1d9{pCrS@?d|Q%P-UaohM=|7XpRlx0|%#WhDpW_*&cAl>$h^aAJ0kBAEVrPXu>N z%pA^y=FwBKH_l#XKo5t+Jyimp%3OLPuMSaf(_vgI?F{NX9z0^ASR{dooCV~c+ynP# z>lg*TO|Te+y1;m}^9lV$G9f6Mu`n*)=)wC`{xmmY!?k(Yi5}iy=Pa4OlgP#1Th!Yn zyPadt)nkEtR*eBcNJvGlw+)l-1QkgC{v77!JwaM0A;zzW)l378*k!f}jmO43Ek9=v zhe%L9u{VshUuTGX)tj?c`XCU*%$&*qDbV~4*xgSZ&bZNwjrN7{d^zW6D5$Jjih@5? zNaOt?0v2QWwk?wtI6$WPL&<>BpE;pps`TNBY(Mo^^jn$4Q85A5o2+p+7roiHYRULp zg#e~xZ$27-C7QU5aLzBv3+MAEi7kFm?K2!gyqu^E9QWOHC5Olk*M>skRbpUy;P<|Q zD&zsNY+NMtn*=mQXiI?+`&x>+MLo3bgHWssr|-geb>;8}m&nYEUteym)Fl=QVLi-! zc<3EY?6OEaEF#r5C{j+<&aAO_+?WRgD?OD|6`e{sKd&f@ewq$&#R_GS&{sct{zVe$}1>&u^!v*)9F!cAdx5V|2xD|%gP zf~+s}O$_sz67yw^3KrD?? zu!X^|BH@RlROOerrp6uP7qHndw0F0|D;_^OV$yKnrHrA!`nvw70B&Pi#OoZk($i~| zHjuu$(3jM(RpNLX#2bUlM_I4P*(vwRDX}&XF%-DG6%tSm{S3fKW8sH*Xas@i z%I#W<{1;C@*gJgOq_HyxK*o;-szRTM0q$r~_?RD9338cpKW~Nl@&Z1*JU`1xA?(m| z1LEFQ@;}*sDY`EM;hu>QX$ROfUYisMHR}tZ?Dg;(aUpd{T4sN6FcIvhe9;1Q?tHiMONYkz-5@t3XGC1jhJLToDqwM#OAqj`BFvWPPxe~%I6`UYr`fDVHHxBVJWCYQmUaXu!81)rd z>cefHPXGeu<}-N~bmtj-`_%t@HhR1$5-e+AR*Mx3f}7_+z63%e%FW1aEFW{ezI8dW@u&^L!C+)#g{v|hE4)NusER;!&c$owWAa27` z?Hj;WY?IhT;76-ehD?bGW?G^aX^ye5wj!IFaN6ULG{DdsF`b4`hmt6HbZY_$C}I*~ z(3U&Q=8H||oK2rBFf~Uy{1Zkh3X%4QPgyV)0U6_jpLS2P)5+G-Apx1KvUC$WTnSTF zS4{x0iaHq@y21x+rVy`adVKB6WXh$?etHFBSDa|v}QKX6){+1r}6)RzUPpd;hOeU!$Ll3cH(=0sf12(NMYWM7-Zn>%>Kqg8Tl z#PPGvFv)D|QMO4U`g04IIajW$oqA==X#&#znMjr#zL&-dh6b~?kV|>OSuD$r56H8z z7Lx_8J-wpu1o+G`Cdp9W;)H%$|=M5#P}AWkKln*H7GXJFihJ#ieR(}@$smKYrrQ5;+y ze+D>K3bLM-l*<9hB{VKhK#$YA(2#fJxOdH3n(rdudL1T{{6-W9h3wRVG;-8&PQalX zt|lUmtm3^49clMm*%S+%ockRB=U0PcXPjsGkPVp|XYi4Ii#xw&)&IWN;Dfmwz@bc0 z6gL*d7! zfa<_KupA@wj?E{m&NB+I{#RwmY?U95S-<8!S${q1CIQ7WSgPp`rPrq4i3m^mDSi*~IM)^>^LK9o-sBe8?Tj$p^30o4Ju&V96a? zVdOv)^987Rw5idpiI0%oG*wU1INH>VZ)&t5TTd(DX(iwCX`T@v|GH4*=+^9P(7gSQ z{K&cR(JE|I9z5f7`LQ<_3t2EMnS%(h{S~%$r?t4Ad}e^0cC|IZfpnON;xW>1yN{fa z2z1k?Q9G8uTea;pFRrkcs#65IDGPQ&60y9Xlhq2+X5{GDG^!2}`%eGLU^1r;8EU0^%<{fX4rtvLm| znz%xK8@Rhh!V^cGGHp5tZj@?cOy9>!;T77VI^9tqN^Ava{(NC9mI+>`$4b=ymJf`2j0#gzvtE?&1-nK)03Q)d#ZN;EG-l zdu?qx+AZBP5ef7IgCVS!5pYI!L!Ln$!1H1-xRd0MO;>NL)2;~E%pYD445sRUji|fm z*U1v*udaxU z(YjJ+3h-ksN8fBv{=rhAU~p1*sxq68Dx%%oqP{Fbnok8%ivSUiFYklCi>or zAX|GL;SZCogP4A^d*%hdAwy=-MDiFCyBDWzs#LG#N z*vBE^a7P!qrNo(cc|<>K5TIC3km0nKKV5{#Y;d$zuniEQ2%I4iO_4P7<#TCQ=RO!S z$x(WjJ_PK)&cVouW|1+`X27h=JOj`014ZDe?hL8n^wRb`?G}W{d|09fvFGnzd)1c6 z;1$jq;4=d{fkheyqD#;1vU(=BG}Nzaqk@{&4fQ3%^@%GkQIQj+5&TEU-533qiWiq` zh+1FyT3=pNCp1l#NkfVDv!^O4mk2f!-zjZg*eo^Zy5q|c3~nohx)cPF;oq$@3DNLr zqSZnnNSg>%ZVC`mN**mN`=?c{<*io@Nyy>k?YlQ1PokzY*SP~ z)MHHrMG{8{1biWIPr*FF* zKi7-fGU3~K#Ff5W$@AL%x*TT5GQmYyQ{aIS^W9k8>{seN(uu`4YtOfr zt|}vHpKNWPJ>atZ|DBR%|Kg7dqsTWxGYwJ8*DfX3ffsnxB%Wl2hW;K~?u`TGNxU#I z9wf|4{oz37_@KA-K#Uk~ivRvJ_JHG-3el58N%sRG!adDv!bdmR@qE`9$!{G!2OT|d zU)&u!x{-(PwK-C;J+^CmA}@S=z3Q9M+P*4*9%A-Y=ZP{4>hRv$u}Q_T2|*csjou>r ztFhOE1ADx zIR0~@%)T6;uYC6X)YSG&h5Dt{2jL`JQ~cs#$ZHkjH=?$O{+TbXFDS8H9&^5hJC})dNf8!r znFBr{zQ(*(F8v^3wYjGA`oeMSmz3zaRuEgHJ1dSbd)Rr8ZE}RBj^UVD0+G0X?xeKu zdyh8X?AtctX3##;@C|JpGIKu*eOz`SPE0DzcyW45nkbfxSxkWRU#1G&ZRo@4g*X}> z;3w5$uKx2>LCQaQB7;HtkCr=AZh!g5RKaK{SvXq;v?IOkCOYG02#d+Caf!)$xpX(l z0>c0qajL~4lRfjw2Sb@^K9dhEt0CM~Ay>@4Th%`+es1l2nq!zNJ|a4G#T@@vPvl10 zfDKP)^wnEZ+FFP9{R!;%hJ2WLKL@TJTmL$1PwZe7TuZ9U+z_Ws*B_7d)-!<&(%U}wi$>BH5IqboR5bs*?VXp#{$og|KfHjbvigr4K5z*I>qAI-j!@MR+8 zp=!acAe-1CYUyk1v^Wb3ekq*!{YvT)hfF{98RM)86qj+qv+b#%7+1|ZA&qU}ciyB^ zPjlRjT_ax%5J^EWqojWqF^JOBFb;cNF_JED{IQv|61UpQAbUCrpJmsLUGpptqOFE# zV0W+fjRZ63Y1*}UzT1xwxGS#rS-_w7CC^Qvx8YZw*s{#!#-~L=%;RHiLCgxAJU@_e zO7#}Fq%jhijrx+4?Lj!KjBz&Lm^~yvhgx|kKPXzA+);)=xo$KYbcF;of%)vn$X=9h zTFg*JALyN3U`z1{SLMeLV;mW0?v(93_iB478S(Lg-4U+biAzVMQcoyi`L1xFsBZnr zZ6uX{f&0i@pZd6cya5t=TO+}$v7PpOA-nrz`2uM%eCOz3@I$;!=WYF-G6v9*iFnS_ zF1qPwFQ_BH%y&iA4C;(_WrPH~=@Wj!Ed|{lIFsmE+YJNv$Q6x}_@+~0bEt3kJ zTdxid9z`bKwuL|FMS`R{Lm1L+sXlo~+tWdHf-LX-HlJt?S_GKi#ov44`G|p==5hEl zQ4X5VGo9CC@+BZYaZ0|DybLj+7^qS_T}qW8lgU_=9(B$mnNX~1u)AfTH=1EYrpLcc zCI(=dGd1@j& zntC1^Z;Jb(KqR#-yOeS4Z}#l@Kg1`k+fv1@bma0skd2d2<`K7}+fZtLTV?TshTE4e z3P|#dQEh$V-mLmi!wH%q#ggaK7rX_BeHv_IB?za^SaFCTUIK<}T#RAu4`sw3>2{hE zlP9Zmadg!U!;L0xEc@f{;!iNaI zq_&hyZbiOG%)9kk4Dz90_oMz^sl%Me{AlP~#>QTL<;r#V{%Q5*GQq4 z>6FCL9PQc!=z3TxHPTe{F+WriDbFzzcN{Enf|2@@ovp&040=7(u8_O@N$?w&L|>=j zFe7j{6p)m`)W%z3p}aCxmXJbnf5&?<3b3>mk|7?VAiwP?}>qE4pZwjJp`_1Fhj>?wQh zq92>R2Q=TLwinv)vg0(etMz`i3qtkoWq*rn&}*2XZ{rHtne8RvORW*EAo0m`jk7PD zU;MI#rV;Uisf>(yT`->-5F}j5qS-lN;9Irbp1&M}&-l%dOUGem=`}0F??R*_#5#nDT-8Pd_oP zPnkMu1rD#Ya@=VkjNh*b!g4m$3dl^fNg6k`gy*+CLUDJtgu&JK{ySH3IW0 zZBW9cm^y)$M8}RGq-=$oBri&JO*yCTq9J1-Bhf}R98*_;tlJ;lCnoDb9ZtXLlm2i-j4l*;zL~pVh-+i2Oyh!ES(nA)pQ9&M>`)1^7@O- zGrUXtOW_fiRNnW&u&vw5s;OEZ1Yt%y-FO(XluNq=+jnv&Bim|#k@h29aAB<#yCv4EXIuek`vY{I+MCzOzw&=8y8McP#K(alx1}n`6eZ-q}WQo^zKqeqp+z!%qM>SF=&Ms_CTeKN>gqG|p$hZCF|MM(!SIPionV77 zf;FmX-ZNr>u3kAEYK78WSsa`$844Su%|s5X`1EQ7Lk)RDj8-$ZYKM(5tZj>F$zCc( z!Nb$6pWce=rJ#m4R6|!(b+_O;phk2aMi0C(G*lHb3mTsCB@69S3K=E8+X&sc0$Hq5 z{IxeYOQ(lHvncXrhwXLRril%fzMI(yKUWwXf)9hfL3ZI#|1^wXk#@b*Z| zOM_TmHfYGLp5Q_1Xzep!3@RNeF=+sAqzPjVc{UgRv%yfSJIe1wVF8Z9GP1 zfa}3H&$IFC+|XJD$Zp^`f8wPmGS2@1lgTxpiq_x43>CNyTH6dekC9oSM+nQ4Mr+49 zOhpYftz5(hIzh=30lnjr?}xZ%$wDm~E@~&_yKV=)8@x~rRc*~CIvoEYfgvK9lvErq z_0-{~M2?g;==2(?Q%)9+k6QB<5IMcqR)m}e8!-&^bNL6TCQnSS8_SYSZPkv?55gTL z`!BdA26IeAO(skwF~{&p$wvb^&&ClTQ=4zqwvy9-#7z~{rtPQ3A3QMSeKzetY3evM z*_CH1lriG$I_@$x%|&m}y*JJC+ti41rkQodyksDX-&}R zAw=f4xy(_E;_T=pq-6$vE=k5R2|b?xnU8-qUl=l9lsI3UKVR}`{$1C6>D2uD&H1vE z`441wH2HN80omUWnjNGHb6t3)8YD^)S{)Mp@foB>2wKMtP$(i~?65vRDJlF^Vq5Pd zjxL0rEnu0fGFBIYd9C8mi@!#7g+8gI6(<)y>S`@oERP0m2Zu*=K!^OG!%fhUXV6hU z#21N5d(jx(sBo-`buwg;)p02fvov#pnY{|BouZm}FX9zIMVNXD?G)!E=9*GLCDT1j*dZ?`D%E0f+l`72v2>g+vexO7RnoU<~xpz z!Z@mG(Z5{`@wamdS&Jx&t2nu3<5)-iaP~8q5*^2!-c8Y2GgNwKF@~zMHT^j4!?XM6 zY4?MH&#!*dsWN5!CT%-oCG+#olpmgC?8|t}+q>9D&Z4HS#IvUU{S&92hN8{=rw4X6 z8TO&5^lb>_KM+HY|BDp$8UFJR{N~}o*Yp3M5X0kzw$r)Nz1_=)NDI50^IyJht#17b zW%yqZ!>P~9lN*a8Yl{;b^F9A#ih5>YdT?RxXsT*;x_x=FeR1lqDe8X%4gV=c{l5nd zw~DO(4jPL512mkS8k?K^A6UbY!OpSX>Y;(ozv70ims#qM{X@Nf&r<)5HEe6DZfW{U zle(;Py7X zBr07Sla2}tmk)>)@%SD9*AWJAYNewqa=Id!#92z|q83^o|96O? z$=YJy-w{JO_qSsfIhY*yG>|%82(39#kb6fx`Of^K(^CJZcV+>Va5>$F*u9zTSHmUN ze@jujTbeu)ykYG6{AhP+pytEC6T07>9KAy>9U9ab+|flkc|9TiR|8ccXuaxySVm{o zQatrUz`VcpWHd7j_3U?L{%sof3Pk(}cmY|vu5n$W*euQml-LafQ5>ql8N%IC)-D$BUJUClVrT0W99>{!@2oJ0}@1o zbD~Kr94%Cs_=5}MDcL=+nG{gw*=Hc7-emP*T?=Yw+P3SXDWrz=K=?hL5^TE1s25Q1 zAe6u4?%>tVb!Gq1&NP2I-GbOOXdS^4$Ru40%R$%nQAZlqaH!r@#ZVr{KTanlxX%iARwf;}?-!J$7KJ_bS%5>(l^2>4ABvRpC@Edj+fv$aI zrsXP7W|ZFO(B2f|$_s2{4&Os@l0I-$pJzyLYL}Qz#YQU7f zqurpfqKGjXC4ovK<1RsLxau|OkE+TGr6<$$#Xh4`*S)?8D6MZg8A%)GQ+lc*5cbum zI7?M65vu1_qvcB|#uu8yMFiccWqRn`bAwQ=N)O#f7p`eeola8* z4-}noFybO!rE-sRd^>zeeryA7+f37SA|>I{_eAc-#h#^Kvx`z<;f6i8|4I`!En0P% zbsL;W@>rP~R#iDkZSvS#sgz1pSS>S@tNNo}tY@vtbCu&tmGVNa>~DDkmsQ2?iL&PN zQ11yv%{khZkJ)r7U7jk#M6^-jsnV)Ni5}%+!@TQ7Z=m+>khRHJ4v!Dp8LH1Tyzi;x zO}6MJ+Pih8W-1-lv{01o2U*?EM6vS5eUt3e<`tz==Q5976jfCa^|@k}$r$^&D_U7x z38(od37`+ehkYeYBPOVgzY7s@R_;Xs>`{jw6_JmsvaCB;>fWe!ciU4 zsm}$l_R<8P)lY_$L;1&U+v?>cV+78ThC|g)f>T-t$M9XM=?|Px}ZX zug;IMh$xFtV6D+Wmg8)QZjmx$|7fV(F%F0>QoXJ<7GZgu!!%T+F5N#C<9(cqq%1~j zXpP6EUVd@iVlA`&@wfHI`6AK9Iu2SBsq@DLGDF3BFZw4k&#QRSA-m1N{0fQL2ZiWo z+lKM|lkR_bgiaUIS*zAQnX5iSlE;&NJu^splI`Gj-=)O-i6a~yf{>zE>*iyim2CuZ z(#dJ64g^vg7qWM9=42Z;cGt(N6mT&q3-I6b86TK^z|U@{^7(;jK{^LbUU|?IEJTJn z%0RvPy8NoXuz1?sN4AY3?@B8El+E`8sSHU5b~w6QK3LBFwva-yhZ_KK&+#p;Ljjp=tqq0S%;q(dBzh}xS?XL0SeM8AnH<;;lzat zBh^Tl?8ZRB%)JMm9nZ;4p<#CF!U+DzXXNZ;?oq*fudO}U-&Q&YM?bQ_%aPhViFQ`v zZ!wyoou>M0nw^6I@-$^!6e=p+ZIpB8HTr zwkmSIY1h9viI_h3$OrN_!jaNE+}|tJl1qVB%{k;|KfiLsKv$ zsx31`1X1Vi53c;8Evy2@r?MAAU+-R=&$Loi zmxt-@*h4upVc?c5$u@C3$^<2voPe$nssZ11onsS4})k)fFnygE1tmFP9ZKMs>}f&TB_Hz6N#^mxglI%FNZtF8F8M4 z9~+jCS*JqkWz?QP<0?j2re!D~rZD+49$a|3@cHHo9#q~}p~5zyNgS1@+aCs$aD(9Q zkllFD<<(fUr*G{BSgDtt{7zT|$PW8>Cdg`IYc{pdwGE%3VTFVM{`e66Adi=sN9oeO z+jZ+8Ssi4`Ev(A1J4KtG3<;;AIfx(q3hOaT^8K|mnsDSQ_6JL+MD?0Um3{X2cVqY; zj_sEUEwovYJ`03Z$Vkhd(g;>uY;excyWdI6279lGZUaOENGR=b` z4ZyqK-Uhbtert?$Qrp3*vBHnnE!f#Z$YLq9lMRxSJV5M0Fhiov<|)95F7oR{)8dLK+w*x{JcQrb&}+I2H*x~=qHk7^FpP~{UpB|@ zGvGo-itYfhe@XP&z!h2nBZ57>n;3VLLBzMIkS(Gx){|$p($DFLpWmCN=})#ICB9E< z7$^7{I6qM65{p;{96l3MUp%;pMM1JrRBNlmQ1%C|w6eJnt4L&I^=Ncsbpk2-)jN*B zJ2!>XIJiOa{cv)p@-?oJqxzdbcu|H|Tce>v&@=&cCm@G8)X=zv z{f%L9%6Bp5ME7XIP8cZQ+80u!_kBuyHe!PaE{?=fmEeGQU~TU1=4xuE)MZzlwXXH; zEeiU4#ynbFbT4_H0`)_=2T;-qxB)+S014dY2crz~jrp%t8w6^5yS~l7JY(e#l*4af z^DVUi+X&X;)%<(?u4eoI3JW~7WGyIm(QyLi!&xbUfoOlmrR*I1Bqddff?EgJ}=+R}60HkSVk-&%{G@+`WqmH#lJ zfW)xCyuSEdKka=CUm(f#x{pklRZBU?n;+XD;ysTn__&s{X}tsAd+~vziE%-q8Jufb z++z?L65Oh1z7flNQ#s(4LH?xW`|LA`JHgb;qlGncfGFn&Gf##5kVl@Xfc&{KQKS)S z7oC{%pZsvn|M8Atg|{3qQ70X0%j=QH%pAl~ z*#D+w9_SJ)t!1wK6p;dat>T_4IpYI-)HCJes8>u<1#smrB%SU&&$X8aw6t|>>uVlf z(6$^_Q;3E>QK6W(toF!;ym0zJ#HrzLOMlwI7SteI5=$3tKyho~(;AL4Urg}fXFETc z61JeKcVjwcmi2yD=&q&#C`-#5o!tHFtbHGIb4OKq$ICyrXI>kw|Ap%Yx$b58VWL+Tuu6 z@`|PwV^Z3&;5>Wi-kthy1I-5q*8RIKyYF^Jlx^7e$s|5qDrkI zwynYetv7J3+z*P|JoC@*0R01u@lW5@KCA-TTH8EZuANl(t>z7HwYEvMU9j*kl_w8( zx0Oq^aiufT88vy>aGBaRtT_W5tQJ4LS(8aEBo{kw{^~$kxf+#|fq+i+J-`M_-iRgF zSnPySgPe%S8%N3Ythzw4q$Cw&jjb@SO_zx;kqx%1aTTV!+NG;QWGDz2?ZNKYbZaz{ zxs-O_ZzO-r+Nrw=YsQj!*nqY6V2w6J&wh2>_3wFJ-s7j!9kAEILl`A*L|zV<_gZ3m zZ?Y2chyY#=B8|lPuWm6WPd|rN&e~ptSEmF39I^rI3S|L*AJq1 z;e>Lk-WOC!NT3G~Z5^cgg+~NN3~e$H?YAOeMd^;&uq-#K^d2gL4QQJ+PaTigEB7xK z0loku={<=3)yPxUfW+0o-pe=0_>sd#DuPH0**Diu{-f#A`7N!ZyQ2t#f9Or6TMVpY z1>E#vk02xmaHjWTLjtt5uyNEwVuHctQD8BRR7?bG#6@|Zysb#~!1%XBNOP$_>OOSW ze~jQysl{HcKxrj6hH!GqSGhXEaurt2N*7i=uIXn{+eoD=1lA;(@&KSJ)K@;ks0SlI zUU@Oa8$xvCkJuFfc7SdVH#1;Y)Dlr#NKTIlLFxC&}nXZ@VO2!vI_HXgSslt z?6e{_P@_YxR7pa%(Hgn;#5h+dH?1!{^9vG8>K%;U7G&zf^wU38X; zzz9(l=>b$HI!EN-Mv1>IBMx1nYqYeAAj47ZWW%7nb2?2k@=9{i4a_i{9Er{=(qD_i zSC^2#5l1Lsr`*578gZ6QWWGk4Ng%3?6ssTqxWFF5mLvph`ulZlySPk?W?n=;$J0(MssugkUv$cge=x6Y#h9cx(JO;@69IH47RA4UAe zZj$20QpV))QdBjLP&$iEgO2(mSXg~%M%$O(rvH5@mt^Xz1uIT7~J;O zhh36uE=zFVcgkFrZU8GWUi&w9gf)oz9jRzmzn@U;3ps=ox$W&Q?e|S5-@J|ot+*^| zc>K!5_f3bA3j;U4;0LTJ&7cFfkEn ziUOs42m=Pfe(rr`Va)9^NDv@1&+Z{{CnJp|GXpNqI3!Y> z#3uL7K5r0tw31xjuSI16W(M7#ITEbi{9NcH$r=HQTL5$9InFLX)#-eSjtm|^W)57w zb0iT&0`*yE5i39MbevW`(Jgxo)ZL>_&jMNr>|VEi&8S{<>(lhT1{$t$wD12K-8dsB z{>?{d`wd$A-5q-xhxt7M`r}dlOHlMT$naN>`|phpI#Yz-lD2;m_8GnOkM>7&wrFakA2TB zL{YMoiZK}bShHrAJ%kX2#=eB?MToLhC`u{cdB5ME&-?qiKG*fVe&6f-e*gR&|2St3 zhvUqgdA)AW`vV=vA#;iRA5zprQ^p(-308w{F$qUW>2GH54Re(J{w9W(9F874<08;e zJ|jxNv}w7~KZ&8P{V8`=4iC#X`SrqgyjK4ph6a0#$P&}UOGZ-uX_KutKQ8s=T7O=O zwylp|l)UWcc!LJ|1@mW$I#J-p*W94WuF_-~r@lN}#kVb&&*ph3jBk5Rmi>{UR`j1A z^Dr-q7O+1&@m&BO_c0xZ`W8mC`TUWhZhiOqrgidx3~t>2{b;_{BfB@B0vcNi|430k zHQWq-!d$1W{xxWSeYC&?+oW;n!1C;HX!6C}ydy{=1QvbiQ767+w4QrE=VVM7?av9744ajS84dO0_9TI8^q zQ&h9AhWyX3V%s2;f|Xh$*5k=yWUIjDq~T&&@FTNNz31PCxkb(Phfdd= zU+#Z1mEkaguew>fPHz`Dr3t#4jZYjE-1|3#@^oqZ5 z*7I!h$ida6^`tmB&UxfMJSFO6=Gv>EnkCQcx0D;>Dal&g47E)%NcL>^j=fulTjxH> zE5CJCho~H?T5+bh&F4|Tsowco7EbY%1Xu8nE6uZanagenw+DK+eBhMeX&>c%UG&ZB zlagXV~3 zaqqBKmeee#x|50H@TEBjL~u2MUPt848-(DtWC~cHoq$n>=?Gi(la^)BQGA<4DA(`J zNhw$_rftjbphnFf;Unbxo1(ku|joewCpTqtx^5~LgrJkobM(f1vrSj?Erq> zGqO+mcv*=1MHX(PLICuslusglTg76i&MN zth|T!WS+XEWy^INc^T_@-qk95VqBGz@^V;5z?jXtg(^w_OUb=k*0)%~?`HKPe7U6T zU3F_|+Y0Ot+Gk0m?K+x4DW~KGqS>KIY<^sV@xwCG^C9X7C;0p=htQ~*6{W)lQm?P) z*;L8QOF`yT=z;aZO50q?83i8)@;-lc^;XJEZMuN5bF2q)c8R?@4l<-Gj|S#XK@*z& zHvP`LLKe;URPU^c`p<_>cEBVw%`mdsIU;3wBYR>q&5)og#f!dMD#{Tl;T9PSHE$(n z%SZCZ5G`#=I?>gn_cE2!J^$fY6tA9t*-n1I_p%nMQ9~IF)a!O3R%+S?Tk3 z@Rz5*k%ySVAud15n~M*0985{qi5g22vgfH!#P0yUHzG>gd+|?%d+??k#qf8(&Ucpj zg^MK=G0~d_*Z1Sh>=j-Mnr&i0cVEf;~TpFK144&AvIWlJNDg>1^-t9hp9-=`h!W^#A#rWrR1^!Ioge;LYq!_xco(1g(?J*;Ds;T)yktn9J%2yKaMhf$~RXe zG9Qq#%m#U#3rSC-Xnnjx8(k{2yAj(-@}lAN(v(IBQ~Iyc+#OORO=j{l5*MoAo7Yn%O;HIporH0P?2w-O#2(gMMC7jY{e_AMZlSNOr};oV ztre6J$e!G-?g*gd%SO++u!Ivtc>DH^YHfvNb6bQm8j5T^^L8VmGN)8uh-k3DqE@Qi z7yi%z-c!O@&Ol8@tWn-u5i;7M1T4^v*lw(EoRJNWy&O`%Ca&xixuh`SiXI(whit^( zyB4Yvh=>vu$258MSeC|NTF-n}L|BJiurrL;Q6gTSQ?t)wTz%JDF-I7;uXR$2Z@G{h_6atQWv*D1Yd|=orD*WXO1Bu*7 zmyxJz4g*AY7&2V_r0hsHHY~2?#X!OU!Mmm}@j_e}t)2y-;|Lnu(a?)`ei0c$PEU_B z-^1Kj0()NoM_SY&2P*vcQ_S~z()qCy;n-Qpiqnt;HAB7IO+C<>Tzm)l4M4wmiJXiE3dkWm zxR=MAPAkg*YuZ_*-ry8FmmyvDu=OeUq-{Af2m9_ zDd|C=?#Y{kC*SuT?8}eFtJdu6Cz!|&g;H`r39ZiKdNcDxX{ExbtU6J0tb`%tqX^^^ zKjbqz=YTZWBCj`KxWZ`&yp5kk)(A3Kw{t4bPMjcelbF!usi_M#CiB} z^ml50db*@-7o#hArYXXs6EB9e)L%aS5g(OKrK7;`VyE+JeLiUZY^@;p?Ju4R3l}^hwP*)1b4M%^dlqkm3Pcv`E*Bn27L3g7uYM&qDX9L#~O~i-; z=cmXl)Mm>>Q+Gn0(63&<`YAd{682Xwm$nAFIsO;zfONBgiKwNCL(W~PX^VqcBR&hu zUsE{DDcPITwg+J4!KmcYX@_+%a!%>&tLX;p0C8%vg+RKw>REcB5E6-K#TJJoajc~R(3CoBi z`q@;3*mO#2=X*89irNJKoK{voTQp$vq<9S37;A!?H*wCeu(6HjVBLMglHDB7%t1T~ zs}g6k&84!96Cge?nr6w)FGqnd>l;XE*^7tM(;GEr zYD5t&aBjY3r}zzAIl!CMY{fUd5Z^kML`8$&#pL_~w;q7oK7!lV!B35fD(h!4Leuj~ z#EOe?ef;2CqB_BT)?Nof#bsqVyJ~`+Hr9mlTMImD8~Ga|5bry063N1`E79g%vEHL^ z#yJ)zL>DKcW`Z-oF^Y~Jm_;IPahlGOj{_uUK$oz>6qG^hFhB|(1)Vr{(G@x_nk7C=fy9W^neEo`({#2>OSKjlT3^S=0RriWFq=WUbLWytbCQJ($Ta(s8f7t+_VMoY z(g>Ynw>#dbi!LU2X?y@=`35wt>@<1Pp~8W%IZDtmp!<;_xx7BRZ(u1#e9H~U(Ohj> zw;^z28Baus79m#G78zA=Y9>rP4!C+!n`6Xx!qU2Pr7I29(h}>8rGlu7rSb}!tmS#j z70#fQL-!S~!zu1e7cHX|-qRC$>VuU;kvH(GF9pS1yOmaj9}J6Ft=77) zie(O-jdo2?VwZT}8k+!vKU)p`3YA%M4IaUt{=JIGOFj$$PKE{C?q47sc2Cjkxpn)V z>0(_t|G+@9_}!sYm6Z;$k)=*hfw*up{-(fTdFG>(^ z`3OZU3uCXEDD|yb+{rRJTr;6x$8oNkimjWetefksTUf1Idahdqty@R0-=noTMP17o zd%7$t(N+vRt&|rLVv$m@-o?Y8+evhO5NqF(=Q74Ww3k8UWQg%NaSZolmUcZ+=oba<iRWPB)`mZKMu?hTlz`c<~rn92wc^9+2HEd%~fKFl@F+GTF3nqYJi_9^R* zjM#g;xbL&RXJi#{-_<@mV?|5_NGtmRiqjfDNN!Ud>~1;8RE%B%qsKY;SnGd$d z{$nDuKX{ZH zObTJ`YApSWus&|AZFp2&S5sM6U0zL5tQBQFxlym~N|g4z$mw`SfvhDJW&ePzrKNvc z*202(3S`a7%FM{f_^Xw9H>bcWx5_U456BuHA5V;pi;n#(lo>?{WrqDrDAO___ix3j z7?upbPQHF^Y>0wa-#!obyTtoFQRs{v-Tie7Pw;9rK0qN;U4xW5z)S~~>QM4q zUW&Y{V4ugny?i;!l;PClW4ST!h$f-xCJkH*=HV%}2>!KtCFBS=04jZ~U#mMrW6N-9 ztmA0bgUj5!Hn5(gtvkTL`|!wa&4$ztaXk_Gp7RO4&QPgExLI#Hq|K21v17aA*{`36 zdyM>_%`OJVe_ABJ#(XJTdyAwyU0R@Utk%SBjFhQ>xiSk7-$rqJdQF(nLtIUR=x(au z!f7^RERk?oi&SJ2MkF6K?)`N&9yGtdYRSY*Hq@2TM8o7KZP3EExVt~tqJ&UEKw_|A zIxMk5(47y1mTYoGUi7J0&$QE51tej%xy;HMPnKgDe+`oOK@BGl4e@e3M?kr)zR1I(AzUI~qk1QR_7=U6(C7!zV$wMkN zOCh?{I~J5u#g4u}PS@9F6mF_Tl(9wt158oS)HcR|f$?ECNwi`wg2B(cEG(7I;`xyK zro4`pROvkSh*7Cg0h;50OJmj>#tq30@=jP@P;|F{#W?>aqna)yar_nP$;TGVCMWxW zet@=;v%dAZUwkif!%65j)VI{jIK7Gyo0M{MC_xE(%SqWRDT?>2zxI$UVHY(b8FOHi zsM!1Mbzw}MtBIGQh@xqeSvqyOZ%GAim~~xpF`}TvqJ33)WfQk0RBOobxtQVHg=M;c zi)L;YS*ECWjEzMc>#i+#;8txWXGsKydlqe2&$CM0$mVnIE(}a>-IdYQQ1*te=ZY#5 zDqb3l{oef=U$=WCGv9pWh?(Q#ZmNK{qxM#r@MBfs1ivUph9=>pkf3+%Bgv>^7|L^wvD?#Seg_8e22Ml0}ouh@Vc; zbff`tf|4Rdz)9q6L|d=BH8>zs+va*7t5B`N$#oqt_2d@S-C4+M~F>4#Iiq+FAbd0vt$_@r1-b9#irn)1)p9h|X zMaph8q?tXrHR7JWDl8R=kx1|&MX+ke#=?8tiiKpbMW*nIImq?GFPOS9a)N|lv?tEX zy3nEVcBte)J1AAQlo@38MSZgH$1OouLTZCD^;RCRs_ZfHD2}1X-1bM5ewDI5j~T(& zNfR$79;YH6ZNP`BsDc&W+6)9~PkLX&TSuNG!0<84)xH@k6>pfyQ4a@MFO|E@%`2eM z>Hg@;y_3ZE>cN6_%3xn6l-|3;ex#mxbb#>+yDorJRJ4e`okeX!nA?h``f?Se;u?KdWn&~xSGyAOEaBslQ9W8fp?c6L^M2W|GpSR!`5gfKC*X9lu~I3>Bi4rUj+g*m zSCkO*Iif6klD`#Jl5TO3_)AK!ee;PX07l-+@+=EPam#?B?c7@z_4sY1h@}(?o6Z^0sXX0+voiOe=BVDm1t)J9p_OV%+&NEo=C0%sDFF4V1tZf?@wA zlC}U$^HTZJ$rY!x7IfmeBwS^K3#xOS7D zAAfl1pK+G_OCeNsSfe{u`wcaNGLH5Rj(I31Y#@eteVoBg{?3pHt+M4E#(-OF6Ja~L zK!kH}1&zPX!@!t&kezj~Bg1W7*1)hQ5j1B*@^B&I_x)pISU+?@Ysdevuk=}A?Kmpi z2C6Y~cI$=y??kpoXa=7M)UxRfHo0pk!HC*rp1H%M(E z^!+%nwd+q957X<8WNJ0*Nr4qmpLurURHZdgD;LF57Rp%0z)@r;dQoR zFO3uxwzpKoQ!YH<657K;G(?^Xz{Mwp0HhG-La&fEtZ6nERXZ-+kjUIl$%+?&7J`8X zo@~9`{0uAfGO3ysh&b4Fcj0dWkNx9hQWD^TLX8M!S~+0O+3NK;c!9){8cy9j&h&Mc zsdfAu3<2E*SjY&0C#|0IUZ&Z)v>@)Jb$B#AD=ndm(ffXqvS~s_xc*yKN(~A82;s%F zAM^D)Q*&V|s2i5(tP4FMrKwk@!HSYOiy}8Hp>O4=&}vjO2xbEsmc?*L3=Smg4^72^ zGrE}c6re{W#yEh3!`tySHdG)ZrT>1|@P`z}B2ZqvgMwh3d5;fmMDkD9JJaV+fl7WV_DF_=eATCahGPuq%g@7&9i@Zhv z$&@cz$H8Ia#MDAq`Ywz5Zg%gWO;50r3jeK2{U+eE~}# zX~P?enNoP`d(!iZVYF~)vOl8A^%2e@Qs)9k~pr7C@!zYED?mws~ zS=3W{DH;pLV*t10_gGDJj$P9$+{NXaftB}IW$(}Xx_hygA69-6sk*!3-NoSdP?9|$ zQ?QWHD0>+;N(C7uL1+YFW6Q7(bzpS2dK3ZFEN}&-LU|dh$1JMH(jmQ7uxCTnqvNoN zSy+!8a1RcQs{{Q*Txq1DInL_-wVKg2SWtLDR~4*(3syK(^)`nqo^*B14yX=2^Swl3 zR;uZQaT)Hn|Gfp53Y44GEcMmaG=K;pVQIQJfn zpRLbE)Gy`KP2158!D+|*@4#Nyo9xwp-QcHX<6SX5rNXHKrDx?osW#lGs_R&&W6pX^ z6VRwt-6&-*`4Uw$2!VdbN~(U5;m8DAH8)`lxU0oa(SA{56j2;$gwej@NwsO5o~oT} zubaMAJ6{ExlLTJGHSS3^X(OXgqnOg+;#d`EELCDn8<*?8kV-axj;9D?8rY5c{`y0h zKUBuUg)ugq8-E3uYD??4WKC&krJ=sRxOeHk0_EDcTRu|ie6`_|oa(0w)z5irCePQ5 zIx`@08-1^^H!Kv_W26izC!K979+{T-g#vhmYAEI3dzUdR+cucdj*j*GW~9Vz%H-dx zwhuXV)x(?*hcxTUD1C-Bnj)2!2?11_9k^SwY^9YL$GUT(ETOd~Xol`!LSFzCb@Z>% z1}%s80JWn}IUnZ8)^nWy%?fQ76wEN=ETcM8+5^*@Y-X5feQpm(#FbkX!6r3;bbBBZ z>Oxy2w^;nFZ;kfF7OV%+y{8dPPu&Tt0n)preZD@|GkYvy+RQ-)0wbC|ZUR|C-5l-R zqSNh%J{P4^fkh!7c!GpX6(2)Ka$yl{+|>;#uXWDQQQp^3fvVQ9rdwfzZDjWa6dBzi z&y+?2SIC`y6~&i80<$!7T?_&iuP4w@chQ*kTIcoFy$4q~KSksLY0jtFZ=X*_re=}A zKp>e;zPm55x+J&0^e5R2*~bu2g(r#Z%DZoztUP_3%3CodBb2J^c`QNP=@GMI1<;c5 zt&eB}F5iO5=}8;jJ?;;e9StD1wH$tE_k9O+Dx-(z)xkHMEy2(RTN<*a% zL-zu-Kd?2tQn}R%Gi=Y(=SryV=^Acb;BWfwOGs#>m1pQRG{Rx^vq_`b;f)J5qY)`d z%q_sF?^ob~KuPfE`1xCH=_4dKKv~s=K%d{GR`7BY5jqP@`m${pvi-ck_Dh6OMD??a<*+{ggtB4{KrjfZVu6KVis%gw z`!&u|+*SLtKL4vT)B4du+#Lv|xvD%co{f9G6VCEF_SG|)7frw$Wy*HCKQsLt%Lzs4 z3Os+c%d+hp?kEnFpTHLfC`NeKYBqn0dYAba7ug{Plu|8i;aH9fsn!=~6n9znaFJKv zEYW{wiBW%R-3cD^3x5$#PpEynRnL4vn*8mTR{<;!Shw^zFHiaPK%cb-H7wFsKs=;Z zPQoWRmg?Uuvuq)Nuv*x-^YYLxi{kEzUMGkt7Jo00; z3n*Zx5au7w-Y6vQ_-Xwk2i0CU3tat+`84H{g zGMQdt$Db7Qp+`Q`&1=gLzK@H49IGEmwcV^!PYl}j19SmQ`yp8}2F5N;ke8{0wX15F129v_*S(z%-fyyM-vz`5~KA9Cce^jd2v8{tOj`N@L1MDvW z@AyA)Swg!C9-NO`F&KYmVdR~ES| z0fz+J*iExE><;jm`7>pQe4pwAOrGV4L}eDhI3&P2S+^&&{vrGsP+ACM&SBU2!K83< zkG1=Ol6M8{3UOZ)!7qu_vqp&km~fu=Aw0nBC-kG$Sm->uK5^uB)~ zHW?b2n|5KgD-?$OJwoeS5FM3&ICK`r^1AYy{)2C}#!z-6_ITs(7nOq`{-FELG2ol)=Y{mdVq$Qq4YCl9G?+*%>Tx#mq$cFwjV*f78|%?OyX%wj>V=~WO&x! zeauT`3(#$=I>*ktbbMAjxCl2&A2ZkLqg{)&J*&l})gOIK3SNCGr*rAqonOD{_*FN{ zpIrq{ZozH#T>B_}%qew$k0tUeaNn&w+b^DDfwV`*2JVFtQ4iHAc-2mM@(Jzj{a(Y} z#1jQgsJU{U;^l*@OPzO|-tcA3A$1u{Cr)Fl1%+~qa)UKME^*fIkP2}|8|SUzW*Ku{Q(4uoy$J`*w*Q}l^d3#7Rm_;dm&*M#Q>F&z=p+Y04G!$)CR$Ok1jYjX0YjV#M){FmTd|_0wbMG* zq6B_%*uv&oFGsQEufS_qeA9@sjSG{cg@j#(?SUkFj7N(tKICGR&EK~-+a?U|DH z)$1+xdzaEi>;w82N0DZOnDaQV&p)LdgI}fJEWF9$`_1w8lRU0xH*T~&c`N>)?qqZ;_mVd5Pg-X1hDR!nkwn6OoYS7#;-?Ru9<+t?y)BGF>C#(O+8KyBeAFd-pmN zy-uY$MT0#a^;v|Rbz)f9z4(KDh{>}+-d**1K8Nd7^%9R%X77!=Gv_`W+Q<%gJUHog zvvbXU!OP~HjX0f*@`w{|^J(Z;iR~n2P>&a)nCG*6pK$D0WXCOP{Pat1Zqc~bd7DjD zj1>7sV|Q$(gICKrpYuY%^`AkpZ_PMjj+=U3^*k-Tahv+W_0j6uV`1m*#S4MG>h~VG zOqe{c_Iw66auFLbjky?rXHD)rY+n5pANaZrQx^R8-pMb_H0>1u>#E@U6_;Z=bRNv5 zBMNfKT3(WN+cl^}zwbEoKJMPfuY1&y)< zV+hCNBHAEEnP^WWj}XXxf^R|;Y85sxh7Df>yQoR&TKv@z+Ix5YT zqe=WP)jzt8FkGPNXtyq%A@F@@{;h? zlt=gCfW#f%SE*R#Ox0-#1Eoq*?Sg_}fK+Kb9P$h=XD;G)5i8^4Y88!*6vAN!;8Xg5 zmbhC+Fku`;-!R*0N2ry_t~N;UCXsiVN*GF^$3 zo>RX5ZIXxcu3(iYQRKcV;GLi(cw`ZciFwUupK_ypwpWjh$DDH~=$kW_ZAEY|G%b=| ztjw7I+O3<{m!>MjYqp|3N1+XXPm=FC_o7(6ebdD~MuO!FZ@}+fOHVM@tnUB?@OsmA zET{0dp4+k1!SldGH9Laf_b?B<@`D~jg1JS19}Gudgq5M|PAMiSt>`n{oP?b|$4v5g zFK7)~Ik_9xD|6^6y{}Kw=upssKZ`%PWZ@j?Y}3iAeBzJV(hy$z9Y{tO2iU{u>>?`? zUYPXl6WJX~?s~RGwar~mRLB9=Lyxo$fVqIt`ksUkk!68<4W9K!$3Euy$uZ>m0|^lzxV zg;WErw;HzmGEivJd0wRdJYQ4NmtyPqO$LaDuB$m^a_QH3Z)@;aq|1$9wM9Yc0W_0s zfXCBs^m*Jbe~g;`j#vK57wUu{K7n2X#$~+~pJQp+Ipy}8xPPts*{HU6Z3fR8-xYDX zHcV4E9X)d1c>{C?+skpav6YQr)l=aj%j|dZBXK7W#{}u2t}^~|`@`+GN#A&&$GNpP zSxUKXe&|$?`vpi9-j#jvsC}^9i6rg}TAR2$Fjj4n0l3~<8;z7k+7 z(Ymt}U#n+0_dDs*Qu?8}`#Ri(=KGD&m#t&r`O{} zR$3E)40sk|&#v-wd>0AcnL3An+R-FGK6kjC+1<|e_DU@4aiJ)<-YQ(xvq<9nEf!98 z$gvw__{BLLIk2YZ)-{A9qD( zy@;%M5nO~KfW_0dUL;Y0*mj~2U%3QDh^Y%qnit5?#5SW1>g3Aq#I~xu{hEt;=;VqQ zveMj53gEF-CcR^FB#Fw{S=!VPb43b#HVhLtKqrycYfmQ1TmbWsdoQ8M%5G7udzcS` zU}}CHj|~+2g+31lqTrxtE&PIKx=z$wCwq3^6<;vI=CKtO%J+f}q~eA1*S-KHu!l(h zjle{dD?0G_xivxaDq1(NquD2+-@^fqS_QGx^qYj~+P~3ta+eM`?)UD{C4~1yKs-5cq_D<<7G{+Lc`(I6PXRvGM*Tf@~`pJ4)9u-O@?(tq0 z(U%7L7b19#u1h_vfwIH&M)e4VJ^D|(^cr)qy{5^J$WT8+@GYg`-&Y2H*wW)|>Y7W_ z30e9eAHuL1vW*;vn;JH8#}K>>KwFaWxbAXTJlRg$&c4@S6$8Bj;KT+s!BuFL?G+@koTo2?QT(}Bk+wMISEw89>5sB(5R{v z;dkZ9#<9|z1^xWaa6Iv})%Ymqt=eo0dgw6mrL;*>VMMeyoeRJ0rUE8*fLv+U)a0cb zI2_f$UW#rd6eobqq!k*zza&COzUQe^?&a4?%N!y`8E=l~6Cdnu$&R8DKh>yI5Qg?# z`Sh`bm4RXC9Z2PssITO@Yh46#YteBS>@}=u!yC5~C!FD%peNYnur0zA^(YxtJ0Ss{ z_}Yj7F6a!auw!DQH~YS}3+iL(x$!Tb7EYk-b;UZtZl%f$Lv)){lccnE>5uhnOy(*6 z@DojqS0rt-Ec;gpHshAV{K|J;-Fj>SseKh_o_#R@nW);^yvT+_PPd4r zsi5h!6g;M`J*Hw%pVIYHv4NWE3p_d7YvFINaA9%k8noFYiYUcl=^#A)UA^fjw%N=Q zW%nh@+LGRB+0bgSm0H0(CuG{%kWa=3JltQaPE$JrhZqc58<3 ziGUFru?`+Ho_BgXP_WBS$MEnMX>*o%n}I!lD- zX+SfCL@fbi!l!aa;l88u5gX*R@3w`Qg;L9fG7r0IagC_CD1_ev>+J;saiQ|!q|HIp z6Yd$N2CIX3OONr{wB7~gFLcI4YSDpyOVSiK8017^u`Q$Kt*2aRk-Cz4{^%c18}sY zUx;$39bJ64C?JfvM4!v<JR`b$!?^3S#`SsCDpND!rag?5>d%Gw4 zmN&F%zxVMZ#>w97?Ey#W;Y}wl{M+x!MMq^$ERAn}PQU%N{?_Ez((kCeVw&Y`pNE8j ztQMZ-@2REd^_RC7<|0V)k#l48EuuN=Gs(@0u&c4xe}S3Hom1+UBeIrRS_&DWWlnLP zdqmC0epT@Cgl)4+E{$djtEUd{1IXJ1D`cY!$!k7s!)E)t3%oA&G;>_TMCIR_e8OG?~+^JrAWkHI88*-L(rOFgcVan z?HSB_C^q^bD8)Ukb#1AB_M}^+8!*{_Lo~{S;9BC0Wx-}kU~{o#zr_CS5#vOvF}t`} zYcYszG{o*S#QqbL)$cPpzoFKjL~k~iI}bq)zk;3mjMEXGk#e3>fXDIC+1~H&X}~%v z@N8cF`(&ag1{LdPO!Qr1(q9tz-~$Vwk9|oXH)Ag+!#~{jx=gUSJhkh#k62&wck7rl z!Fq8fuKcy*X!i=bPxZy;de%$q#9ZN9o;O~`;gUjS z*4zveNLRtx^jbfIN^8I z&+tU9YVWjexyKKPWh2d&W*(i#Qc{dpB2^`uQ9cfCxkYNs@=1EIcRNw_^I(3v5)u4_ zCYVigXG#;Q3HObilhQpsFk=ONwvh1mSo-k)6$br$bolxE*PWmLjzQNbCDVV!p#OU; z{o~61_S^sDK_~w^5Bj$M$8z)GLd*XYgZ{H*I`Cn(n=+YB8BYH{Os4n!S01!r=if@E zl*#ly%4GWgOApHRmj|7j`6FgJJJ~-^IjZsZcKT4m)WqOlD)gTuw7Yle)n75wj`7LH z!I8l~W2SvQ9evN6{&UH+y{YD3OQ!YJWq*}S2MX@Z+!g!FfF}N7K>v!F7X1@|mJ}5h z6g>DVW|~R)NKa4ui-BIrtF)&W(B$NQolH+kxcW~FN?A>h{1b!zoixogh@~V=<1`{t z&;7@wX?lo##7*CS!Jz+GP4~TemNq?=T|4Y*J?m0D#j1odxQS0x$bkTqA zr3*=(7m_&t_gK1szSG|&)BFD&2CZqTd94<)lo>UNZ7dy3qrnvY2Mjuzt9oMwW@$_r zORv8BPYjwSdC|MNQpU`HGM28cl>Dz4lw$_^x|!wAv2+Rs{Wz{e_mIQF3Rh;I|M=6N zCDXTg>E(B7HezNPy9IS+6+sP_NHrRUbMaymvfWtDr#w?Y$|T}iC=0zL#5-GQH03^z zC-H}{>Zux4H0!SL6LiNchSDnJ(0>&1&S9J8>~2XBV* zJY?EDc`_c%=i;7;c;Zu9f=U{+$U{?c5;n`2%6xzr$U!@-l3F%SvTR((z9`93mhi9| zL??;ESIU&SqEiK>Nck*L-r}fps8TU~0%4U=#z-b6rIOyeS~d)F#{egEM=ZTsJK=pF z?o57@YgRUGzSQ_5dimG_?G;XRT@$WU!$XR z7HxEXjn;@;vGo1)71<``+klbbWPO1GND65R{do9Vz0=ox5?0m$b9596lblj1JJD!F zSe$d)MAYo$ebnB+sMKQkMwYx`$#}aGDDYEs53;_(VxjgXFZg$AAHB!YsSO6!L{gx1 z#Et2#7V)2?Vo=d1H`Kjzk=`S$+01735m5IhI^*?sr}cb#G>=B;reUmO43(it#Urmu z+jouHJ{=v*Kcm<5#M4m5(r2Td=An(@jg45A6Sn=wUL;0e zj!NB9xT}^nU8Q}hIkp4X7mJ%?5&XJ3&SEOm6M1Y1zh|fO6)w(tkU&1qs;))Q6`ct_wf{VEu{7ywLMfFp zynWD+E(N<1`;)i$;SFvBp$TnAKyd$2#_=BfZSl0WPiq1~Ry%_ZS%PM)B*|N$uclHk zD9dVl@*FBi5jm31eSOGxR0qCHq?cuzEXj%@u(yn4XVMqv!GzEj%Qp5x{E;=?VXO)o zX#xdf@=P|81ntO_bwWF4IHCT!Ia8aNT4^_mC~YcepDU~{cW{yyk%hZA?EhY&ux%L6 z%YJqM{|@_MpC!|D$@j+<|5`G=PcxYDe<+!LeTZPH!o}!M z74sfcV2!HG?hj3ss~=S2600m8>Q7hM9aPzjR#`n6ny$NbQ0>fAZPTwm)0lHm<7HHB zH#;=b(tc3upIGhiL4US=;h-*LwEEJwq1k6Y4jzRw)i^U4%=Pdd))S3tT)Bql`qU{W z@e^y@&l=1R*&Q}!jn;UcAD$n(b@;fDsn$!^U|}-nuqp5(!RKQ0f^k@YXcxNH_kj2H z{K>*$rSD)&W_SL`nG zkwvcRdef@#A&N=MdQE?QrZoTD5m;=LkE8E`KkwU|z5;~xYdrdK(9X0Tm(yh8=>u%h zQKy~~+hnW9+9SSq)t`}OoTg6`*3zh#;)R3_Ge@aS1sgmP$~eE-MIdMMc(j=3@4iIAKkQZtJ66ZN~G!jgoZ^ z4N0cZbo2M&kl0f5+`{ar0@j zmCdcDN+g9sXNah4_*G>DpHSXffRClp^ePhW4-U&=09wVx{RqQ% z3}3*7YBBm9dUU;zUYl=`vT!-ngKA^nJGIhoPBd`kOFYJ888FCFQXbA7y*TRMzkn!6ZX@AIi}F@QxA%w?w8HqU(;gQstb`(30c=-Umt!{QHN|(CUh!8iJ=5> zI?(y4FcA65%{truKp+s$B)0t!T>`AnhZJx=);`6aI~iU&e_ysw6;qF7tw;9MAvv@j z!-YW3T#@v6ka5n*^$W}x4}uE?yC~81Q^B{_Y-2A1&*!0BBVd~hB2#WuRwdMTo>Q+9 z8H$I-%H1ytB7O_PyeSTmnF>juK{4nxQbjMZ>Qsoe3hOk}BE1AE}(~IS%IG=FGXtyjaa>UoL^C}OhD)G=HRB7ck z1yw7 zOo3<2WC@!&_r*%L92|r$!VM4`%LZ2|Np}h@P$Yk_-3%bBGtd_NfKV?P?p$?MkRF98 z(V2OP0_M(QW{`)^I-^^vMEa?8K^=L}g`%3>)XdPb7ER4IKeckvZU}ekfboQlV2GGc%F*ixd-$T;x5Sx3bGrRRUx0 z58O0*t;JSw)DD%mmmZR@-nFY{$c5(S@I5|~T+1S~QQ3v>)O zr)fR!2SLV;PPit}*2KBl(0EevXqM=19z8;iyll|~L8jG#U@WjK4a~meOac;|uQW@F zwVv8VZp|32G$GqwwlZxawLoo;s(c)K8{4nRgS6d*15mrZdhCQYu?g_3ck2&C+ty3E zftlvROO#y|b|~`nm+k!1*P*m=*dGOd%z!1^Kuel$``?+?j>;CQebe8gcI>7Gk4uYf zyHSaX(Tbw@P!>RZ+i`xP{ZB|Mn2sWU9{AwgxgFbSfO!&%7dRy7AFac?r2zTPPR12Q zVu^>Fi%1*++T5;feIBTGZP_1YjACh-_PF!Vq>Z=)FAgc3M7dA&;`*I5#>!8 zb1e#^7Y+N8fo>#1W@P&&@asHKaRTmsN(VN7fSY$UNdq%i)fk0(A-G;&TnTz%l#y;s z-UH-(f=??M)Q&kH+#6)DLUY&FF!(9#{2J-^9X!O{?4u;tk^#W zOTRtH=%;up-*rg~-uP>zk(nP?3okM>t$<<-O%#I*lBL0PHS?4@hslc{rWrn!M<$mx3HC9jue0r-xpwRfW|mW<@s8ImVC|vBh6A4W&)j$BFSUc5!qwNW zeGJBNMX45oq`uC!Q5d}|8QQ4xZNtqW`g390eM)E1#Cu7}#MnEc(ZZggr^?{zcM2=t(W)ODyc{FlPZE$`Q%0Z?d2g2|oe1+Y(5h zO5{-JI^7Yp?9n&w?bqLd#FH}bpj`aPAp@H8a=qgwg9|gwncRj2T7bk|Dw^ASbM%7H zA0Y8NfTT}CZP%kqFKo@7`KPP9ZGgN{iA>8uZSSKe=eIUnfeYU@#w4(-s7;zLa_i9# zriEncg_v&nANePsm;7emXR~m4W7}XRCGAm+&LO}_vd`aSiRmh9G#5j2Djp|1(xKa86=%}CMhg5{C)bO;0V?&&+b zk8V}iz0Pa_F>g?J`{lm4qCcc!w(opGZHDe_S0eN0es}+6W|WT)&;<6J(U8!+`WK)> zve+hN&wz%Wq3jUN=InKLWMlT}G26(QeYPPkk2d6*T+I6LUO#B}@a946A6T{-0M90> zqjw85*}KjhK1}1x)Qp$SIMj||`z$OyKfn0u%MH-*$!oU9q8Za)`RfN2eU8jF=j`7k z>kFbV)2jm;ctG6=eTZEbGe>LW3nmS3_0zK5A-?E6Euie%&#ig%@G5KJh{)H8-(5?n7q_XoqSa?^{>aWN?Wde}8~-0; z>Hor@Fgm%TRn)hp#|DitG3P2%j10i1ctj^I|HoMR#b;bnpj$K!qQ#XD*~HqHrW`y5 z2oZg?J8X{`D=r&)o|H_3nB~x4-0uGED)fk8siA2NGDi4pF0bwUgF$JGj`iKukM}or zJ8uA~pKo|S%-EEs-fpMxsx$Szc)0AjHQVCNB)2rB6ii!0l?OF{k*cU4N-k@u{@mXD zW$OfkI<-9n9Us+Af%yre^1aOu6_1Kjt9_*Vgp$IiW3e9BFeMU}zdPl0n3b2QGPFPW zE;&{p5;ox?UxQwj?)yV8F^e9I=UbxBw;~n#PQFU7B=W04TJkV_M!& zEZx2OUD|yJ_6fliNH!1|j2SdMUAJ6)>2!#$7R4j@z_(BML)JBpi}WrjCbD0`PfDhQ zu;gfhieyTk>fUmVndWi0LJEQLoh9fEjmuDUM3?4XYpyR?2z!4O;;K*79*Kect7JNs ze3+uePw-zKF|Os>QM9(cVtt29P?WSbt0B9;xom%XmJMX-_w~&cr^oy!_^Au>*2XPS z@0_hiy2o1^6GoN-+Z)A&Z_OMT%g@>0s++K2_i1BLzIyzE-4o;YK~LFXE|9yA{?3;O zWyj9uCv}b?Kf0Bj9`0==I1oO6RX!P%5RY~wqA#i}Tw$`VcZoV^xtkd%P*lGdQdoOZ zGW`&L*DX=g=dy7i3#h?8g>Yxr{mGS{3FkDY$WNA!-HIAkRNr-P^Vuop^eH@jTx4q# zt-RdO5b=OfZ9PNXk#UJR+rC7tkXG#Y$%F5!4WmTZ5N53-;#K~k%=eB*ii^yJlBAD> zGdp2#Bm70wzlZw0#oQu}pOavVp`_WDR~@~u9Ec9+vh$9pWIXTJ&HC*|t`SGnvoD#q zWbCl7+{Qh*b=Xq#llw)OTIMtvs}FBZ2cMB36B==9fs+$T8S9hRi)UpVff9|N*`U>y zpd-dpAA=U6oM6`*qxD}{bA*%V5yV$mXskq<3(m0J#o$7SskKedK~j#>HM*_dVh2)M zWr<_w{JZOqht@eev=1dN=RD><%)IT0h$)yFUjI#-v^WG<7=97l83r#wIqHK1Yv_gv zCik;(E5*s|!5^>;&51ODdK`_H@EVH=e0NeZW!QE(MaR7C3|EC{6P#TbE|$(eQY_Kt zxkif6Z^#9O)U@*a9#+Sau~s&o?Oz6lqx3hK5x3Xage?-4&+EFf1%bQPk~|m=c@0=` zVP{2*Mq&%^<=Uok@gTIeW3TJRF*OyZN#~8k55kx1v`Q{^A$@#rcjdb*_N8e&>bcR| z?}i=A>$b}UI}>%6ZF{CTv{{M*qr;bNI3zO+Uq#$##@dQ1ePWY>L&9Q8MeR)cDoxTx zCA0q+OPDkm@#V58Vs5(I4)ht>HFgop6pdvD7i-T9-B5eO$0bu$LwWPL>Qb8`bQ(#3 z`eIo#_JqYb{31f%Y0x%=!G!6vEmQh$oU6_6OB)2%-jGH3rzpSTyTr|;(0H**I3UfN zPkTSDx9#1f(0XM2nf#7^{e~3mDrprrf6kPc75-c&giQq|JQOy-nz$Q&MYSai7pTS% zk!3Nfz*7}>lS9#QUorkdCh@GpJjxVk*NbPgAO+=B0Fj4vIK44Jz5_l9vylrms$1QGAErN9f)&BUZEn)1gpxL97=#BV&z zqNJ+7|NhdfqU2%6VKQW3v+Vk5i7NzFeODfa>owsoO}UcHpfCATC6O)ooqW~Lq(qBE=pFa&BFIl(X8CL4DXQWX zA+VIpylW+)VY&Q%KP#sCC0$!4Y!(Ao6bgQ`oIh2-H_YX4@jEWnd+0hh;jUqPsSc|i z@A3yy5$s8w$5qoz=GK8^^9N9(RJ!{#Hgc*zJ+b3PQaO<$n-v9h;ri{e|C4PJOCcqR>8!A2HApGN$=G=8gA z^lNBk6U~F38sGO+?s>^pKHE(ZEEz(c?@-2VxOqo-Qh2j|zw0t2Zm)+oVQVT?dKk2S z5VY)NVK-{Kt|$A4h4U$Xy*A#!&0xb@5h4Xh^@U5-B40N^R#}L5qPDl4QDuE=`XAQ4Jc!& z7Uav7q_d1bvTB)>GI^A|@lvgv_0^0aKfh$JWkMGsj>Ah*5hXYRspURF^*m8kH6!AH z%*ghjMj75A&&}0et(wVox}c;ZzrJIjQRc(6c7eocB1wfvX?5Rjn}>?g@oGEYqtHxZ ztN6y*1d*tZ3h4v`9XDJ%aUQ4qfDPT8sN&i}tjB4vy@LKhI^;dovf@l;?a~y|9h>hA z-c||oEm6+W_LJ0^#tA2IH=T3|-|iUB3g_c`gx5IA=UU zPoK~!DokRmZo8?fX0z02`ykcStE;^-hvhJAK2s+o7vof*cRXL@mdcf7d2ykvdo<^% zb8JsuOwJ`pAz@yCR@&(e>3u~KS9u5<=$-m9B%x5J*QWwL;6POS_n`HxOGozSyq(Gdmx%mkJ* z2GCqcSiJn1`kiPKIq^Vz8^t(Tz%Nuuj#T?6LY~UC{PR+poPOUx(qB1{5I!tfhE&UD z)UlJnkR#F^2s8II{_vTF0{~Z?hmNtm4=dpM?K+sc|DL#JOq;6340wl~!wz~>8lTH~ zmuzlQGClZ2i|IOKh)-2nnG4JT4J{Qlc{%Vtznq)XB1Qs;aFiffQQFtsS(HfhVDkGM zzV~^{rfHcqgQ6sf;dl1q2GIq1($4)qdxByTi|(F(Q*JC`lr&jEG$VnF=bJ6S0HRl#yDlmoelI*+N~mCu5cSgZE`d z6R0mGrus{V%@drBCM9$EO-RyH;kyeFFObIcn`Z zcZMb~eN9KaL4mRdT*WNX|aUN|n($`EoSnLi~c>w{}wZzE5; zSO?!sv;LFm?EtCz!|lckwR;K0yR%4USpR}Vk2a*?7tU~Qh2G~1yjobA|Pd#kk^Y@qO*$>W=wE5fnZrM|qCn2ncRT|KN-Ou5bHYJ;% zH-#XpmQRvr`?_Y|jZ8duw~t&0HPcM!?BWL7+aBiJ=ORsyv7xg*JsP(O$49t{yj2(gMwJlHyy;CrRp7pydhgV=<}vMh>p@IK~+2|F^H@sX^~Ba8I7 z1S46sPA~Y~f1giYDR6rdeQ_a~$$#lmRBN?7OpQfBs4$5o$Q>Zt`Nex}*r$ zawiVE{v5O0EG_ksh%vCi_~Pfq=p4#Bp6^zp|MbS+^*OO&lWH=BjF|8LjG_XP8<`|GK z0x7fjIgb&Ji3kTMAy>sg0*Esng5zT9fzMqf7*5VT`B7C`H8P^$ZVy(Hp zB;W14BT7oVydDl#Oa1ZzoVco*$2ioXO6vFfQY5j} zO>ir**&28B>Kmx09lP?@nL}kRM;Dm#4bLHiP~PP|w?2Hn6_IfvTxBt3ZSAbKdySUQ z;5oBNM^b1?7vHt$3`U;C3&=cyjTH9zupF0ss!#pj?7qKzX=T9B_Otv9&)o#krcc~q zTBkqC#~c*>`1|_@jgboal9cxsy3Iyq6!A^Ka)UK}7kI)4E;E<_-$pQAEj^ieAHy91 zgDM{?YTZK&h?21>SsMUVthCLw-AAl-a9G^IapGlUVgJ#4}U zK6Oj1p+{5Qk+nyK7YyGwA9GKPd;+iYnzV=0Zuu-MMJ(=S<=9YotVJS3wr_GE`&v^ zRZVpHM`k;1&6lGlj=DcuBf76$)O;E7)y3dc8Ll|+o5jaVXc^_nK;6Y1Q*^-@raQ$f zyXL3LER^qLYwudUF15aXC((cR%Bd2Y^gFi>ckBdZul5Eyq?h`x>|Qsr@o*J)qTR`q zk{>zqJIl*w{^-{CqAvH>(8oN`Pz%y(D*0sq;nSH;x|g1DAT@N5x^{53hL1;wgz$;ZT4k%8OI3f6Dl>*D zbea_Ag*!Zi6(t^u&yf5DVZ}@?8T0oeh7WN=Iz*l$+ohAka>7r0|G`eJRD|ZY%eb%@ z{jlgI@1rMNI*r*W@9)~5X!c~R>s^PKHnSSM8@wY3*8YXH^@@F)?Arkw=)-uWQu2dr ztp}MU4`gv6qQdq3E=NHjM-je3oS88rG}4eJsmTmB&iPQYbgMRqMJ3HGBly@OXDUDA zA+50fVe=Kz=hcTXQx9d=-OS97cPx?@zNl&aZYb_oO|sS)-CKGddn+GdO8^>^9>QLy z{C#y6TF~@&^+)o$qr-MKrZ)ig^Ast=I>y}!zI)}|FEjYw2-sF(ISMWOFQ$v3%A%hzmUd^%>$l8wEi0JWUApqBBvJVrY-fR-MhWoR`?WxVN&JM`Q-!#B^7 z-RaZ}W=xu3Y*zx%cEPzuV3gH@LgvE=A=1fjp~BH(cFUb41ow5}*s_*M;W&A_<=i-> z$dA4ESqho5;x$||^0hbCIRTK+0fdeb)cb#=-oGFI7wY}%9`%2x-v7Um_kSmlDSMy( z9|`37mBr0}Cy?jX7e@cf1oD5V_pj5v|A!UiUlXnu8tAhM*^*%AtKRMPv zG4gKeL+c51pBikK8mymuS9MZB{vY1`-wEWQ-g?UDSZ)8{eBKc3XSmoBHRaB@ar=3Jdc7 zgS?04pOE(#FaAZ|GcwYjJo(4Fhdj?sN=mx%?4Rs$d_qD@Y+Q77%s=JhnE$$bY!&zH zU*+Q%_0XjM1-qvO+lJf;_@A)*Kjq^S>F(=&`$W3CU%%yX&D+`SMz+RzJ2$VB^6|g0 zyX*hJ?#>oh9L=n*8k^f0nc1B5kM)hMb&V{w4a{*D@fUPW&ug2g<1VRc8vX})S3ZC7 z-{f6I_rD7UVe2A*m8 zybI*8%TUVYBP6Wevlo|7txo!kyi2mV;au0sbWDD5=jPL;o?iT^fkx(EUr7FktsgnQ zDHwkN(&I(;0~Zx~zwoG8yovK_$Dy25IaPQTB!(C!cy_MVH|_nfchaPtj~!16PD_DZ zJ~u@=j|-UQ7Z;Rln%~KZVyhPL49by;2yP$GHjH|9YWVt$hPyy8^4!|IF{9}YMn`Q> zH`;g}uoA@O@(0cdBLSo%R%atPZU8#0+op4<6i9sknj2MH4I7OWWt1CYetU>$NgeB$mvDzZus zaKtC4e$nE6r3z&Bf|QqWcNDEYKEvd$PQl&`}91zo2u0%UVf4 zrvWlAMp0V3oMrq*exLX^Y`mRR_(mpTkbn=5vJjmM2e%vmS?K6{7D7M$Q?S?M>qK8WTz^iAbfwyqeQr^^d;%-(_0?e@vw6QnwB_$5n#1l*~aNu6h|= zI6L0n&!iNOnUL*%uq|(Js=#Q#ZDk$bdfTrQh?#4osRJ``+lnV2;dFm@7f4NARNU>? zwJO@&f&rz`lJ^28zIt8JZO}?*v8sxM>KX0nBn6$te&`LB8CA$|nz(18)LAtA9`@!u zFb#Wtea|GVZpdnp!t{fsPfWvmN5_Lz@wVYyZ!l(*g(DNk|x3o*73tDlr*@5qyz)hri#*VVltL}a? zvHg7p9zb~o#5}UhQD-Bl?UyZ;$RL?%mfS9HZ61D}$I4(cK_0y+V(^K8qXUZ2q^(&ze&S$2GXgA}bI zuG5JVC9pLJXbb3*;YQ!F@^%I^RJCRT^QB0A<9r_bQ9=)Y7)cnzsdJINC-r1?%uN)l z!?z$8z~?ReHY7od#ji7xN{E)Tb>u*}qGVpJV6Q&Q#RZonF%0$G^B!=g@|}$xY!{WE zB^hhOZ*YHfzjijw${?2>}pe>D?nL!9fm{xS-+k+_6w>_ zz8kvRc=q<~hTf4$frD88`wj`rcv;je5EbBPv{(J+x`CkJX$qWv%RzLN{Y z|A%_F+sWe^EV=kE^}dsjWiI`n)%%tAqiO#?s&^i1(|vaL$6s}2E-f0i@?0*B&?tA+ zY(y%Q7G|Z0nw{g|j0Mhwr(V?VJL2g7^k7s$)C8=d`{Ju$jy$p2#XJlK8eLD7Z8rN{(kA zwRn{l;PnB$q&*+hPcUqg$T_Knc z=lPW~eY3F%5CdlhvPUl~Su;wR-2rEsiNiR#uU(BFH{;gi>#KTU@m%t@geX5(dTL;9C(+R{r_==BsBDme zBBQ>FojZFduKjitdv0*uZHIe=*>)$R;i-e^Qz*v|x!t0Mrj<*UU1!824VmQDz2cw^ zY3cNDw10nFmgVm{lXk}7wRZ)uKHAmZ^$04K*0M=(S2I4B93RkC;O)|WORG#reidRN zx6L2LhL!plmvT(T$FYh>Kw)X`m@#Ax`(!lAvZ!pf(9KuJYx+K0;QKsX0;yD_3(?(Q z-skgbL6o=sOnnFE5H(W$&jOHG-*w7#JI4OcBG-rd9_69!gpfZ=Sad_5zNtUYmE2{0 znrefM)tr4=TLJtsG=?QXKH%<9^UAs62D9?{pRb+8jfba`5+oP`PqH0tBXT1 zP%S%7 z!w%jHdp=wD?0bav_UOMObtm}x6S002q--XIy z=*a{g2@sqvP-Owav7b>)z)b^7_qx!G$}pk?reXNr zNj??=0x9~U$ZMp864YwwW5u-x0d)FY80hE~;D$;FPALRAbys5zSo1}!R-(WQF^Rzl zIxJfnS7a|a%AG;3BuTLN6iX;M_T-J5AZJY=!_roPzBQ6DB~H%VHef^*jAiPlqPDTj z$6_oi!GJ3?{-z#m{NjBU3|PhhI4ZF=4uw5+My!&7z6{v%KFfA6a$b*Z#W}VYL^tm% zaK;%mF%ONINA3XzTuEdG`9#}mWJndvC&L;fc$>Ol&-aeE*CZ(5}aN?i^<<&ad znMK0*Pp+>{CNEd;f{DH-!>Aagd#gSMmct8(D@=NxDqz74>Kvy3qns?7p_k0ojxi&{fj1-B_DWc z=q~d04PaR^t0(QnMj(XsCki16%u`WZl^kE?K)pFo8daQM?#26qxF32@hzr69b~&yg zX5t{GN+Odj_cTxmKaPBH%{*msOlZDRY26m!xuLO<2LM!N!(a3>^T=2-w2z9~6wB(< z0x%oQ2XX*+=!@-~>_Y7fdNl`_Zw7r5tl8!=Y?_qF6NSyZtSbeDo%l zr9JDlA>4?K2MzEp`xf^4f<8MVMVDl&@o1y_NVO&UUOd7`7olR5Sm%KN%ad-ggN%po zW>O&i25c55A5YuK3iA$MUTGmTLmT#(< zdpYP2!_ZhV@-Ilm-w@~np`TzY-nkU@YCY?TewI0H3sD1R_WcGM`D>Dqzbfs`{6#)) zVCdV6g{vx9!ONrY_17^}(&!yfV ztlu12f$S-WTcK}E)!+7#>8^U$I7>$|v?H~g-$wX3dLhndbPGN<$Du(8g(KkROEYsh z#^!m1iSNlh)OvWob(^8Pa8xs(Rd@YTtfBmycm=+M9A<~h!t}T&5SN>5RrUL|pj-3x ztz^dJZ?$Ro1_$-GZNs%Zh}uWr8qDb$xe2xQxq4-E_0_3>r8uTM#LR_)sQku=a0Z@A z19#PHgZq)LDlONZ5*@xZweiaRqRor-r~{qJe6D$g^ccy?Lh_WnEqLK-*`kjSl=iSmqed99o#^hyf z^GwU!OSZxN0>}l_4;Y89m1Kp7x(TEPjRg7QH`~K|Z0ql}BAJctA6hNg=1( z@lUS{CZ*wx2Y4G^<|+;P#hvS{RMIc%9*lV@g~2^Q>YR6CTF@2=d-uJT-t2SN^G(Dp z(EF?-#C`AgKA1i@op7R@JB%RR;SJOn1C|^@$FXVb+no$mgW%D==sck90p*V_$Zehx zex8wjyQ_C#AdIg0ln_Q_OmngvDD&?Z#x+OFU`X2Mf03J8KPRmize$^K?xip~S2Bo# zKH#g){K!EbmIH$Zs!>{SAsOJ5olv=7SD>4rt&s5E10+ZMh)&n7cx)fXcGeSHu_QO) zNGy&)zV(=%4kNZ0xzv|M_oYBX_=4w|`+Z`>%?PcTkt@;1!1Ow$rOkQvxDvg1mE}Dx zUZ>a1p#yaf4x^BYyO@no7ke#&x=#TTurJ|2R<0MH;ZJ}|;RP?keR|>re zn9g>PIrQCgjEgu1>5KfqjITB^t#JOb{}36RgZy)hz9;t?UZrh1nFd$-a>$0H4Ws&0 z-UbgN`_@o2IdI%4-7I$AVsAcf1=$NEh`&PgNle1!xC*zgM-B-3V=L{hfDmW!=+Lpl z9nQXblyXAcJ{1Mh;;MJmi=LSt^FSSep3sk=e0*WOWK^H0n7Pka_eU7mJbE|hYi|ys z)fbsYM)mHaKgg|kIIgm6)6?crkP+mqzboJo6b(QI`mBb}0RhfmAT$E@(HY=a<7UL) zHAt@1NpHE0GGsll){BLcTi0RcJSpF$dx1f){CWyyy~q)`xxN1R>ZcS(N-=7kT(+Uq zidqHU(C4liP&Z!B<((+=SHY={qx6lBHpZNRSDxQ`ozeT)y3W6A?BQ`YLXdv|RM^~R zI104mdt%5}5>>nvK@5CZDe+Lpbe$HLz=wbE6vA1WaOl}%l}-uOKcC0aeS zwI=r?_SZuD1*^@UxuzREl_EdOcl(XjR(n>kCux4(jXnNMaBBofivw920{PN+Y=KNHt`%!Q^DKX^hZ z=-tp?N~qKL1>6_PFAbV|$M^37kC82=NP`h(w`V(Dce#;YsBwSMQG9FyR$r~m96=}7 zE%WG;T=DneZPPZ?pSdr-o2<{|(C2^ehBAU8otYOx(E-e>PJhuy0OB_u{hNxme#lxT zx!2W`N;ga|n~7+rB8#0-;$N~2+l5|l-c>Tfci38JjkUX@f0B{QCYVKH zbkmp1ahaesEKr9}&X@fo24k09`T@htlW99Z->m(Y)AygZLBLh8@!LleFW3~~6A|sl zj4s628nHhg&;5GL%KT#IIj!oXqP%+h*fAFglK(OFuLSb>l7abpb1464)e?SDH-`PR zV^@ax(!bR^O94yLKMCYai?9DmAQwQjR*bD6E`4lxolxTpA^q+RRbSixJAwQk>irEi z6a)zv9B5z-wF*lGh(|W-HpO9;i~?$xW4_tFy*1k!!F%N-fqeP~P#$f0>ciVFR_FL^ zph9A|d*7;-J^gnAITFdqiqno>Rf_pn0{OYdW5!$6D-^C6>xh#C@~+p%3WrWn=R5MW z+AFb;+16vby??29$7a~R?_zhnp#Cd$)^@GfUjEK!R}TX>CMv?--f=j(`+c_Mae9VB z)w$R6gW3Aoj>qjQ;B;x9)LX|74tKX$IR)-LJNNg`4;qu479D%+EiEuwR}Odd)3OrB zBp6Pv+e^41dy+uzlGEw&ANePN3>hgMWi%4gWi`{4?@kmiH~uGqY~F3}`cDE`o^LyY z<@R!wzTh{vZGE9AQHv(-SX~7}F+x*pmsobVg3$+JYPFH{>u0e#GXJReR~LUN7|Zus zMdP&kbkCY7X&5=1D1QmB>2~7^uQ63``MhnavDd87D{=r)#0#H#cC#^v=DMDfX9+n; zAm>jPoH6%Iz-_WenFc6YnmCmK#!G;R1Y0y{rq;^x(tAs_OEBUR*9AafHRI-Z9yHHV zNM!voAM9|faSblqJwXV~Dq+>l@~5};$TUi`b?6oiY;wZT7Yf^Fd&ry|YBsqsL9l!H zL|C<6?8>C}>NC_hLHBf>LlDzp&AVmM!X17he0`3$jPbu$_wW3;XV9;y>b) zeezviO*7{AX;75Lp4OZBKcy1xG+U*~JE#7tP2UJAyG^vwkEbqX>n8-&Jy|tk*eG4S z+0l@@Dxk6=^jI1$Zx_%S@++w30d{k?x)r-37q4ycf+hO@r196ab|1;b5!;yY|*lDerhU3}cs2%ecNTp6nedvu4I+i{(-5XV* zyOCb?FH_FJ{YV`W+or1dJQ!KsP)#AcRu~tl@nn#Sy}ly!mTEc_ZB-%vz4W#lbl%IE zi<87`!2VgHPkm~aOxnlW+jKav;_|yoxa4s`14{xJ*K&{3g|-Pd3oHaaUCekUFLlQX z;Fb5U;Qc#dbUQBJo2uMf1Vx20DR2c!z)s=LRGwyS?1oOBeHG3QabkGa!}hY?NWs=$ zrDDf|<({he=cG|364=p_g?j3Mc`Q@r-HH7vNmaZ+8_PP=U@s98Hc)(%Ib{-Z-H>>( zZ_ap30#dSo>1-GxdyXlSFNs^2zB9f5DEwKcytr|*t=Xgd;a&&J%qthTQau(6vzZ2= zpNm+vviZAXp%D^#M8<*HovjzL2iJ6!8u^2TBQkj-07+dni{#`~efWf_PFM$axV;44 zOD!-rU>VCB2$Vc$4L4268_Tm3>0X&dURG); z%hzIJt^xk`^3WobO%lye8nxk^zvlsc4l(TR?%=r`>(3_c?BHz^#yGrCJ0W(**z2mS zl?9Y|`y|_2?8x&G)!t+=sTYMPRW0Dg*#`Rn?p?03#EYvf4aZt?bOGDqt zbK+tx%?rBv3HIlw9~C70vdR(K@g@;A)5Q$0PF))ANTt*9NawbF9hn2otyuVY5iSYU ziKAbL;B%8ONUF35onak26K*BDPQ|?lSTH$lqrRjbJr8(`lnaE}I1mhDos7vkUFniv zVecfJ<-ZUH!n&Z`y7B$4YpF(Q+GH<304rcI#?0!Cji`Bgcx{a`i`Gfht zn7i+9IRAd}_sU>q3`Xya-Wk2e=%e>uqJ|)X5F{du!RVuR(My8pogku>~z4v#YefBy(oV8}nUvRB;y|3$fyq>RnzrxrupN_}%rhB5oJabRyz9J@L zm^gerrVP36-P*&Jw(uj{#>#Fx3aVfsw4SfY(htpkKxkBgDqoG&YL$XA1g)%jhe&VJ zYmgphAT6}!@?9$}_(27t3(3mGv%^#fH>oZiDOI&w`eZ$UpGr$tcJy7gZ&75YETo2IS7| z#~yu@>X62?z-?5NSx1~gn>yGLYXt+i0ypp5JDwi-Xp*hgNZk+ld_Zkk`&PG7zq0^O zevc`Kz>)ioIM@|(wug%9=FMC=mi!d}@pkusGQQ~2r85qwg01mU%OlHMQlNnjm?mIi zbmF32AeO);b4)?Jnsh4wkn$@cakW$X&%(SF3M@_bXFP7`bWNvzYp@lO=O5UIap!ff zZ~6pL!P}>^P#zUjg&9lnAEZFu&=Sz>v{)diYV=G$=%UqR|Dhm{9Pf`^XPSOM@XQkajEyrn2naz3A zO?}y)+w<1dHU0WTqHKA<^p-osv3XDRoFf0i`*_vv7sB-U584w~hTo@V18JG~m6++0 z?-IkmQ{>c&XAMR!UQng;c=%G?s6toqYPh&FV3xUQhTxSk6 ztM(MkZoMc>3(YjfFoxHwd5C3X=)PHRqZG!nPDNyYkoHT3@n;$aEeht(*&YToH_s5{ z%!s!Eg)?P@IHC5(4?9|I2l>BX!GP3nL%hAc87T$`F%|6V2Pp)TEbw4uyp&;|C`)Q- zorYXr-;Ct&%u-R&NtQ#Ds3Kjz_k0RL4~l6on`v8f<(}sIB_hKWG)_couHvOTH_!+U z9P}NTx(8EmqxhB3B3nOV906Hq2E^brP0kUbK`Ex9z%iazQ<`-Gj>#fPFRdc5Mh6)% z7GCs*mK_93VEZ>oZX5kHpokqp3r!{$y(BSP&<08p${my3+=%t^ApXTQDn`ia9-Jgv zOA=!{;;DtrCm^5=i1CgX4LT=5)#~{20{tAxEk!YXr=tXfV+1b5L84N@ zg1XKD#I(RHIt6{yxL&ynlIhDNeq3Ixiy*;o)QeYF&eT9>zwAvQ*hT@^SY&WM-YGfG zoKOUEKG$}spVVpQ6&;+s#?+xQwZo2S{7dp#EWlSqASXLQwBbYwhG>cn<2bHeomC(r zI60dE*}mK$VJHpSrz-BI1AsB0O zI!5x?_{F{14M|L$a@=ws<}?|?fO{PhQT$vI^J7JQ!&Q;y_Uz9E;P4xw*@&cXye3Dt zQ6hOgK7B-bGQb57)2t}dq(PQirq}PyO6k2(f?X)OY!qEPb5R+jbF3Y zf7>Y4mXNE-bWa5%IzC53gr>I`rZh^ZjRtYP1-@(JkJ5@&U1Pu=KnFpl>E1+<5ui$t zIbWiBR7B3H6!m^Y0(hN>?>9yg!Gf1`syghBT^KQ36}`?yG1Jkr*3A)#EuoYTWty9r z8N7+kv;@_cN*wnlLZb)VnIwIgHI8AT3Mo)}zg%@b0P}i|kVR*)XwFk5u>G248Wx2r zHA~pAtYCUuE@*X@FyxrGfN8c&z(}JJLq}2EvcI9oS2>m`b7_i}s4ki3!JIrKAjI*! z<0BT=R;qW)<}R{8A|RT6ibVfB_tvvc-`4JFQH+O`HEIx0VqvB4$rN)B^GB1)W5zlq ztk%KyZBQ`~VYL|J&F>IkK}v5-s#;#1C^ZQWW=NC+$btz~IB>hS>62C+!qf%v1V&^`#ziS9bdb zEwork_?{KnKAYbitqc;Amv$1R2H4-Oi&h@i5>CszSJ_%o&{jU}wojwc6vcOtrg^I? zhhepjaQmKcMO10`gi&f5#cHtZle-_+KG)hLiLqG$bLaXgn?e@z#7cIVG~a%rxMkEo zMPF=;jN^SX36Ok)2aVYIH`twBDWb6E%bpaYpXhP@T!9T#uRI6CeJuJj%y$#lXJMkx zDF(w^79)u)&L@W#UDzWY^@f`}d~5)AS*f0etkbZN=nHmZFI!>TJTpt2ee|>rBv^py zhiRX;D7bojsk$Cb4eD|sS>bJ|!bS)TF$Qf*O)L` zCsy&ym}7I_&+pR+78{wmKGSa{AD8dl+4AE<=a^ePCKgb1*%I7Iq;GW+YXqV_5LZIx zUR!Y?KjZLQhpDkCqC^T+mQ0(z`gAhyQXBa+N4PChG#tw-uxHSD0t5!vL*Kqj@0f3I84;i>1eXL&hsX}_Q;BZtG^zE+tYpE zb@v27#Cj*EXc)CI?nQ}&LvH!-W6Hh_0=x^XM{gx>Y|QCr-~MyUDfw2L@NQ~!-El72-g|M&KJmw{ou#xr#s`h{8`0xy+Vcxo+)mpwV9hPigfnQ;8Z>1LnvP54 zbxw-s$Go&YK)Lt^QfuU19$-LU#>Q7ram#*(K3%5nxyG>C(SC=-jz@}d8_J3JrJO?u zH&YCp32nwyWxMnofB$_%jthX^*+VJ#0Mn#EUbr{kwZ8kOf9fKy zs)Dk>^NCDI_QV&v{59C#Sx2Av1Ig|($lIzl-c_{RW_!`czI!s(`hhcEWf<(p@-CB{c(@3HdF-8@MCxhZ-_pmf)c*(_DDfxSm z!Y~<=vj>yCa*V2Vb3qD^t3@$EN;mmjhtEbbxrJBGM&2}t{<(*-|6*@v$*6y*E&r@W8d$nCHk0ryGwQvz<3cTa1kVbaZmRm*ybX{>*9XsMd;(=BvPy< zDRvLsdzkkg|Fa>r5cpYEysGJ9XFhaqD|kN$i?xQTlig0-lgqwV@8!tBI1^B;8aTn^ zTgWqkWL z51?;&V<)B|_tQf)*;=@DMeSyV!p|(&PZaWJruWYn+n?W<{K&6<;FsJFYkx))xaBTA zOymLj946d(Io# ze{bTcnxA8c3+b%oml87RcQ`RFWz8H@7~3#P+zaLEB#Du*u=ou?IJUtI@y&0>Q!+7? zP&28l7VsilyE4-;l>q#le+h6v5SZdrYt#RI3uw0A)GI&V{6JBg7-&95dad5E8_%L+ zDE|xf{$=mPUE6ldE&3no-KNFwTD=?S3w{`?zkS9(Tci|vWBWS%__|aho<_{)d`~Bz zf=trW-YgYqjQqQLSHEN18Fcvhn}|sjS#}5==r8r|la`Rx`dw_TE2u6}EUdQFGGPiL zS8#A4v5^(3sY6ZI1&42qBrY(Cy!3ho?<`Ufo^{vXovi@$>Ezy4!T{Xf(4!>{{4 z4p+~Qw$8q6{4Z$vx78PyEA{_AsD4e$5C2BX-+x^HKhg4!Yq&3t{iyEQU%I@q@*0>|l^0(F^U^0Jg@yTfc{$nH*?+I8KPoKsE`0i*gX;gOrv5nm zVPxooM^-6ChX1UoOGl)^9yl(C0hdF`mP1Jk!Yso>0t4>d_YVy54+y?<{kwb5*FPxG z*Z=P+b$55~Qned)9)Ia_hnt?Zj_#IrE*3U7&29dn%Z<$K4bAM3M%Fq8mYPWO>zexC zbon(czpknOla{Og6;zk`dr)0LOY}aLFDQjOAQ^TyiSup}Pw=CEUsL~oaOMA~smrkQ zNdxf&vHuM%=U~&p6~fI}G!xnKsT0((y#I-oD=K=PHny!cLP} ze09}giWY(pPxqk`{i%P@ax0bwSPM#UcPA^>wDA3lzi7E% z>(MK_C7|$6UMx-n32we0!EZ)qpQFa3PrH}$bx3u%h1$@OnnA{mVU&c5^mCQzlf zgzt*G4IN7Mjw8%rQ#yz!{6=;dCV%iQ1#7cgM@kK1p3>EhK1bn9-Td{aY@6Xr1skbjP*!pz>_m z`8a#PTkU0iA~4{iy4#T)4z6>OA@abjc3N0UOHqy38^OLBB`9Ix3Y^XX`%_MBt-3tGl@O#xBz)Oc zOV#HomqxXQE;Qoht#exBwZ%HP2WUp6*9;5RHCz|Z6u|1u`XhJLORcr`5nBxB&(vR= zZ#TeG^$w0-#;}WcYDtmWo4!!2DumWm^J|Hz(+-H>Vqdds-qj+LIG3;v!rkk()x&63d|G~vCisZb(cptv+^6K#icYf@{t@^I^#H@;- zb3}Yg^B>_8{x0g=RcC_xyjg!y zPUbrT%@ZuIHzsiYh*bAQsGQb|-ZR3YYfBnG&SAV1 z-A+%Z!5cuz<)TR^h?SSB^l>ag;@PBB#27|GNV!}$O(N0KH@Xl zQ5LH$&DbwfT=#>=xj$S$&4Q^SFJsVoH2l<*U}DTSdln5|yUee8BahB~^^QnU;{}7F zTooe)eDOl6Dd}^3xRW?3j(zMBber|{C7xN$NYs^4jAQp7%in77p$HTc*VnDbPdFbydoGut+M4DqMFTwr=qPP?g9 zY$P#rIbtG4iz`WyZ-iAdJ^yB$BsiSi?V!eGE=YbT3gO!*KGwkLWzZ@v z!N_RK60Nv-f-pj?+m~8ABidkdz&-lp4Y#-)YUE{|u4*dboP4Q!(al3^rpf$f{hraD zU*_l+NhlMR$%kwU$mS=|dE~Pz#-X8t zL;m;O!OP2n-w-MmsrzAoHR9&U`4+QMtJ*Qok~iF*`srm>9zv6!?*oyOW*g~HBHl^k z%MSMW^0NuD55z-r;;eG1wE403Pv`Ok1FBsT7uJuCV7YZpP)gNrx*p9R%jsFcHKTnJf!FR30wwfJSqK*j;we`}xzq$fFk z**famAW`~Wk~;A7_t!@sl$A~+FPs)s8M{nL)+{#f8+j1XqAp`N0dCO%OmSzE%65MY zGhO=&cE(=Bm<`S~?3J=JG?Ovzlf?670ak#T!$86(lClKLFT=`}@)6=2jUYqA_e8XI z{UlLp&{jqdP$V+)6hHWDM;U+hco4mv{WYGCZsan{M)jcL!E`PVMca)9;wAK{LXDe# zpQJyDJZUz$+U&*uUL5ba6Yp6W=TRWtKdp*8Mn^F)FMkbPr4U`8tYD5EYUe zmgE(gN*10W0Qu7S2(C>@=I$-BNw(1m-N%wYb%~s}@o?BA^T~aDKbNvrIubJ$)-Mn) zgNUG0Fdx@}mPY**JWs-c%R`}iQRF+F!0)dZRN>I1CZO*a=;z{NhB8V}S16h>DxNX6 z3m$7}8*7aW4Q7nJ&lnXx7AiAD&XEUB?F7=85#I`nlMS$zin5btqLCQ{>DxlP2SJaI z;e%t5q*}x>P-0^Bh-Wo)BVG~Xx%V$Z(RUd`f5oF1o5?xzK#%e8XaE;MhC;%1oZSF- zzW_#N0;MB|#<;ph1EQmuHp!m4K(EX7G*~MS0chlL*i|l?>=OF9iQMfHLqtf>m6t?- zAnv|4>ZO!lV4$Mi1VpQBsWi=FXyi4ODjKvN)J5Ite4IEQeNPZ5gCOWa67LZt4=^RC z!mNFlY+s-tC9Ze4H_0Xypx3J>?vq43HhtLD6a$K;d|C?Xg(eMeBxS%rNJ$8_7j;Jn z-53Tse@sOx1i_mMhQY7z>J&{;gglaJo3?gY0e2fisq0Lk%plvrcu)~EjiM~=R~X$N zj4EJ=thkGgQ5!mMN)d6K5kWx6V?pucIN&Rkf*22@p}Bp#0G=|8OHTNf`V^K%!j)odWTHS$x1l_@>G*_L z>@>j~Wzu&`Zxf|Ujhazb!Ij*3cv`R-MO+Zy)-0jT+~N5w6Gdo@5ajML)ljhL-2~|% zAxLm{wlrxLQ9Aj%G20$YQb82d%Z`q1lQFrJf}Tu14o)ZJ25h3GV%K1?pHrp053CFq zPlkbOGu%>@x;=clcArTxYz(l!$;c&2vZt)cT9oX+N4CzU27frUiTg(QS|^*B&8473zQ z6@kbz-X~h*qu#KCZs|c^>)k}bQ@UVwxy%IJgDI=s`C2F1r0Lup`Ese6P^g}S1~0Ua z-=vU6lPtaL{T1}+V{UB1HT~x|nIPDaB{rRa(keme?V*fHP{JN35G;Qfo1YnyzfxQJ zJ}irj`r)XQv#d-B3t0ZEUSa1%iRcd{Fm;i!-StF4rimWp6i#Nb53Pb#Qc70v#}e2; zNwO?UiOh1csw(;~lZF(MWz90I&pdsI)B>I|v40jOv$SU`Fy`edHwIUkD-pB=P+bOA zL7Ms5-O6Ss%zd$>0|eFb*9$c~>%ev6c7y>5J2eS6^r;^RLEd&iyL5zh!)r)3%hUx` zj97}8pp-^J5MopCZ#d|wa4lteUEw6uQQw?*gFJDPRDPT66jPyfZ9M|Pac~ckA>b2+ z#O60e6goBAqrfLoY*ITkd(^;bQxF;fS`MIkfXK!pAn*w?aRTbmr_wvk1@TYKeWRXT z_Y^pf)ljhFFSfyh4`|vf{gvEur+aeO1!(uKw*UlCUP7r}H#HDRLP*1#@TMS2*XJRL z&~{;SLjuTWFvPW#W(LQe4~J^$CDTW93hDAtk(&bsNok(d4hDcIur!RyOt&?v*$k** zT#2&RnX?d*LA+_pKtQWqY0HOna`_w zS*i$q21)O1bUr>HH$*^h1az6RwmTYhF>kb)khg~Wdph^Sf9201=q`KAVepVb2@ZbLr| zg5Sx#Y(+6t1OT57-6Bq})PD+v_(6#kvE-Z1+jf+T8yrh8-$KH40)2Dos3y`Y<=X+E z-D8Sn1jXwpNMlcj=~TyzZ@c5qw)?PtINM9bA&Tw;m!d6`VQlYk=}mOKLSzJ#2_FMd z2IP?j78Y)nJfnfr20wvt8L_-%6hhIrR185wuGcLL%TwvGMDzUSAQn@N8O<9<&|hQ8gpujtYm0TA2hEBN@XhMu3{c~O!W(w^2LSi zHWY%Jrosn^#x})S{hV})mf|9dVJMH{6l{a+&&MH!U%mKMws6{ID++Bw zPZ`!hg+5MD(F128GZTn`g|(D-MT`xskRQ`CTGUg-gs*lppch%Q`=|Y+>C?LU)K(F~ zlqxlx-(5w7AXkRwDY)0`UF~liXFy4~fM$xv$?Bx(6a_SJp%|LYirFiCPH(f+Q<}gz z;=m_(A!x@fXtvJKr6ZJV-PG!8nuh|%|2sv{iT0Tb$5hlCOHoLisi=e;TXFzUWSFsK z)P(fxMp^*Hw$_^u+Hc2*xG%Zp=*!;p&2g_p^%6C!)!hfq2k2`Y;QfI?lm;lZ!N`lq>N!4Wf*ycA1Bzp0|&ONhBQidGAdcJOnf`DvH=fDQJa!olW7 z7Crr@5zz~ej0UC%W{#RnVuqN0@b-4h=!~V9cEBLl3fiHUWcGTrY@>nl^=~2+Av;BG zu&iKkDV)3(0eu96D%C5u!qM*oAvd%rKjG%&#(K${6O?p0R#lO|(= z8+eLAj2zRwR}}ry+8?;A7{4H(LB3>!;?VCfDgrnY_=dO&BNfE}lKYB;|xC$pHMy8VW=!+UourHTi#x! zC-{M&y7fNAyKx=KyW7z~aGgsJJxU56SXY?cl~^Sj#uMxj2ksCzuXnoa#oQqtK3+=_ z-wU6m>LK1YVqeP>FCN&-%sUz{_|vkwvVUDcA7F|fj@rMF`RpRHR4oo!LssVxK~UjK34RQGeSJ&?8KV4VxTp z_fa%El500jZZ7UWGeCT|e?rG(vE_T$Wih<-07e*)mh{WwqW^xWeiu1G(}is$U4JxB zIl?&d?gaq>v9sc(G3SK=7xSD8l0jXE-fnzs;1W&$oLL#_X~H!B2--AumHFwJLo^#C zg?eWO>T~x8%Ja~H3!FtwCCNhb-3eN%0F@&D8J$g#IDX(5Ej{-c%Hlht87c?2DWkW^T$4XN zv5m&lPjFJ(JEwkqZMziu$Fl5lU~8u;^NL{TFddE}q2SQUGu_mPqhP;*W-|LvwA_3f znZak|KVoT$o4_X94xpJWb_@$-@4O$$x7al;a->B2Z$b4t>$ik21w<54@n2R#3T?hR4?Oz)Cl*8g&!BpqM`Qh} zpimr}-Koc9cI*USt&j-Mot$f0&TfBh(c;)m&D&|z{&}v!=|vp70}oyT)#mwOwAkU| zsJ<#3Ps-tV8IV>0a^o*?yb9VGssS4;{*9KaJ!>iXif`T`Q89kbY<_5@LtAhk8kDGSO zpZyh7UmzExR0BwAJ&ici{EL=1*VLjn`J(A=q9t`QxzCMsu7m37+$8t@qUDT4$Jewx z;zap3w{%jeom7A~J@*qdO&!4RCA7IWbx!OANFW9 zD!g9=$?@aRb^jsA})Hg%p6is#bpW|YBklwGfQPi-QfGNZK}(e;{8gPFEg`T z0rpDf4Jx(1*)T?HPR7zKS`?^0**M)o9YcB&2h;e|XPM`!Q}u0@286O`k^ez=YXaSr z5D$~^<&!fcxhr-ZRHu@*Vp7eGm9rm+P&T*seQrellD_#<$7 zFXla)`cSfv*W9O!|j%P^Gb*2C!`T=p(aPGH5uf>D)nE#Q1+d? zcGM9*>JYUxD=uUoQ)#Z;z4bYuJ;Fla-W<6y^J#U?`!x}W0DJ$p7i-`3{hyCR7DHBl z>pO}p^=s(%uRh-Oz5CSdeX%eJHR+A;4#SJ5yIX}C{)~*-H8;d|UIg6`sr&eJ;9+wk znL$`JlwtbeS!)pMucimHziaQjj{i`X_loS1|8k3tq|P zPuh>P${f|P?S-@q9)e_q+2Dt0xgQO$B2|WN2KXSctdWUaG4rl8At+J6yeXHEk+Sqk+t%{X>3hGFK~g76l+szbQ%omz!Zh73C4ZaSB{x zmHa37bB6c4gaqJqb`ns=E*F1@ochuNY4`Z{ak_w20T&NncY1OxH9Wou6m=@EXM8m3 z`6vrC9JbkOoYTUcBLkuJC(^U%XyJyw;c?})9?$&M3@Z%w6sM-qJ&e%3(*w9(j59p- zf{ikpH^Bp*&0JtIuVoVLSRJGEEl4n6a~0l`DQathBwRfMD)CJDr?W%c7-}| zU_r?)1E;CUW1Q}HP$9=R%i6@1C@l`m%35Al=OKbg5xrHK%EOrn5St}q_jCVT31|q; z3H#SR<+aOBK(e-2xdvPDy0uRTUv?&!v!Ls5ktEoIhToN{RM;rW+>};B!9%ViDk&`$ z>JYAEiy}Z1<>rAbO-qioxYU1k=2amOYrQhrE7CDeoB8r%nr(U{lg<$ zkAm=-uHmz+g;@_^N==7uMx-6$E#1i8VeADdwjylH9o`u!gvp= znl$_kXvy6@hK6DBw>VK0cm2Yw<4XZ@a-zvf^xKjzy#aJ$^P7eBOLZJqbAp6%ioyCgn9-FWqV3}hK*5Q(v2%pl5SA)0XCsAYy$P#S^LFc?Gb0tz3{3V#3FLtI#3KMgI=Psn6oQ^4@Cu zA@K+ES8hSaOuY1-mJjaF^K!*V_QRDk6)tE1-)eoyn49=<@@f@lanq*jPMxzw16+5B zeiz9{*3K`_Q5rgrksk5&FRp=nLIz#>zXZPSecyd{-5E+WpyY(&e$HZh&m4}|5@JMe zaJ*8pOejoyZmj5Xa(MKpxhS`WYDr|;>hZmnHCpqCo1;R&Ii+Wa`5Q=g$;X{OpSX|N zeti9sO^lZ;ilH_mogfjC_V5%v;85uQIu+_mXG*!beEFvAGY5TnPz*#ybJhft`{ZVQ z_2J$=7x$m<&uAa@10|4YInc6K62%LxpFC76hFar}V8-qR?+$V)zf#dk*IsQtl4VQ} zc&WDI{i3h7I~Z9_$R>mlLNt%(1th>p0Cgo?FWUB)ADA)YG7(9WJ^hGWSn~jdiV!I; zMEsbzeG||~JCs|F*yq6*DPVl;)N3Z020nt{EK>&~2bs5rDw@zS*j^60)PE@LCX~P+ zPt-oSK^SKxt;Tyep&S9J%Q1<|I7$PPP8dY4Q20WSj`CV&i_~j~P7^Wbb8>0`@$7(? z+XPYa5CS>aODVcI>1pb1O|U31?gBI{H=QCMp;;iL=>h{PXHjt^GEioGYk}a^1bUR^@hIHqR)&{`{`4UQw;FT#GyRrf> z1P7oue6>Po~b zsNq=09DyWnS98Lak=Dk zZ0fRvJg=ynY$K2^+RtZjn@Ch(1vV3AFx=x+Uu<4atkx^AQCOSVC zYa4xUnTXYIR`8TKQ=iNjI|3VrO0Y<$}3uBSgw;D1ebEYANr7B_GPI$Z34U z9wc@61HQv#dKioW(xX2v&_Ud#T%r9jxPe71QA~g#MFSGOMDo#*0qO~i`bkl4Ifow4 zX84A4t20G!NNperkLu@ISWTP*=Db~7W07qed&VqpXVqZO84d~WcFV*7yVqUJ3q}Ci zE3uS^Ii9|9Xr|8XuKA>C^s`A4af*4o%pIVyH@D;E>)84kxoOU%zHtS54YhIl5W&~M zhI5N_fYTmhS#36TSs*zM{cMZGC~ty=ehgMcXzar7WrozCw^V7LlYeXaO>0!t2%}oH zkm2!0)^OUyYR=NTALVUk?ul7)99QeNw5nRr)W#gF8QQ*`{k0q`+4?rakibS8XmuIG zw*EFY>un5@%!K`&rC}`6XhGZP9SXNVXc(o2dF=>%=k?Z9GX?Gu`*ypiSJ(5M8M`&{ z=Qo7sF+SQBe%csGt3ksJe*bR_zQm<(rYK=48b;pS!O+DbMN(IUO0gvH{##YY;)SQt z^>i6?JAyX9?#?w2;{FcC?Iq>Dls-_fibb=93vI%7rwnBK50i51@4E z$->*!?uM-cyEfaE4E@Dg?NKQsJ43N5{DWunyQ5(;d(%mR5Rd!wtrs_2kopPNMAHuGUGhMhvKe~B&nQ5Rs)!4+rGe^}xQtjA9P znHriff@Y0T#k8^m&c!UMDdp&&z=;r%7npbDKZ&*VNk(HiO=%g@ppJ+b`)3WnQzfSw zrTG|BwWV)B78f=p3NC!c0Y<2}eaOYC|0CK$^_4MA9VQznAuGqI+0oAQe)$dH-HFMX zk*@k>m6&Xm0+YglCpc3hzPi8S0eR}&BO&rVx{wWkS9ax+6518Hw0Qi^a~J@aH*_ht zS%fW)Neh7}_?u6Kb&l8O_KZ7cs*LsG4Q=goGU^#BmS1le5B-eEYpeC!5ctrLTqWs< zZDCz(6ZD9B`l~oO_EqN(SxoSf&DT%r3JE5jK9Y;@54lpCC_!WF1N5bpYkm}M*r&=r z!q46=#j(XDfCffD^lm8_=fVRzjvHHt4;g}Mr}&T54fC=Xa@;uDSWo)5;*eYANiUwP zxv9~i^<1~$41IXOUKUE$JrT3%-4eyFI4V2(Lc$pOJ=^`)ncDRTb#(M|KcbxnJzV!=s;1z#ez(Q|P5)?))6 z*D!il41KJ4!jj)YHf5QU8O;NdoVT$F;-mY7yxXNmib&qi6>(2Y^E_g3Bw{)~SaY9* zfb{A}pXoavxiEpY=j7%cui(y99G_%m6=TX!am?KH1~GpV7Ny z-M81nR(|8vmJNiTISiwmZ2{53z-{%|X@hrdoih~8G>&#g z9O5UfNxn3>7x?W~RuEc^Z)b(M8;Vn#>yQ{N9Xd{IkH;PD<=r!}SWh3nhmJZ)slBHvk$|{3!*-pu zub-tUoX1|Ct&V@X>{goyJHJVtpeK+h^)(TB{n>mBXmmFS5RQ4MsHG1Wf)t%DlKO#;X!2XaXR zc}jq8#e=+FQ<$1?43bcozi7-Tz5kf6B{%9@!JZkm>HA$g(D!bO|7(iK?;K`okPx+2 zlwezGz=gm=>4Gk&LgYLa*Y_&hn7r)id7!g{O?9xoW_>vkwakWgs2)-c*<0ro6t!-cP`&^pkIi zoOy@5k{-wfrbzVYxrZiHNm?J+#1Bg38ubhfi;Q$Se<5cm6{z|1iScy76x4 zpAqi=lax;WTZH?6A*ChO<9Sx2{(Xe|8cX;8TY>vur1bRo(9Brpz+d_8f0NP^|Amz9 z>u4Pw=(~<^ced1bHgvZ=|Mvy%zccB{st1dYc`Jrr7WNHXN4U%CsvkYA|F;PDzmPnapd3t4mQz5MUB}_y zBHZc!os@>e)fW%?|0SiFPbnrc1^-n_CzOn@uT8YpyncfCXM|fNb_+3Z14LZdqy*VVDr;-fw1>#d-_kHEk z?M!cTu5)b1h_b5tF_r};?FlYB6bi6@}!iLY9mKCCvM5N9x8@Lv3t(x=1 zK<1aS&bs~B|7W;rG~0?{3-+=a>y0V+1M<^YEjcfT+bwZe2Tl#~&KD8e?LkY4`t^1ZDKs)XdN;-yS2W&A(H+Jz z2R<{e6y};b=-M{t-7#zDZhcoz#5}doaJ^&IRlRc{OU(4>$aV!0Bi?og`94SFcyN{MJI2UtDPZX%4@Rl@Zrz zqtLxl$|_mbY99|uRnfTap*`lNHGD@xDCEA9N6Qv!2vgHKH^quVb%Yy(G%Tmd z9UtLWI!Q21E~l$Oz7n=SNwl3VXXqS%CH~+f$puouG=?0NDmY2@zK(D&j*rUqoTLOK zSFr6O$COr1Qp2VzI4;J=Zu~e&i-J_b$n?fFSWdAR!%A+(iE$mJ({yZdC9i2?*X1;`6jCLqt2b$0aGF(XSS4(efMtH=A@e5dR>h5}fv{Ig=o35xZWW<1;NFaYbjbpA+a5F~quTmJB6 zjh6EWFqp=J`Z~g`vsZ^JNsf_mcsZ(|G6W2e9JZSg!D#05Jdge|%DPtY+AaXpo2Y>< z9~Z1Kcr`4(?DR5!97C!=#cleBq&j@6i~@fvF+ETT9RzmOk?-I#El=h3UzS0>!4_Z} z9B&u@pdObiR-*1?a}PeCMoMpe%n}W03Wnt>qgN*b^j~aCGM3y0qZ4!i@d3N5}Eq8u?LTaR#WI|_`PLuL=RAuvs z=f+ndGf%OHGwyaB{6B?&9(1JkZg_Ft4l<3=AC$2|*9)7tEFbAvJ~mj} zV!7xVH);&Zom$&by6DEGGzQlgtbew@=vkU+yx%#se)Qm?cZ1@q_72Rs6uT(A`_}Wp z)YSX$Js17QDbFKz4Lxfr;dc^-K&_2JKtix+R&2`I3eWF9~w+WhOQOfE3dqLhff z1Bw*q_e%%uy1}UYkA)bDK!%PQP=JmOM3lg#9Oc3KEM+2^*)NIQ=F@Pkf_6NK*#=Dv zO|Bue7QgZ4R*xwYGwbXK9~eTMWLrAUojMdnu@%p+e8rUuYs&OBgtA=cnTfcXQ=VNe zW&d)erHej^lTUY{im{y}E{o1?7KJj|Zs2DEBBe7j>vy6B%O^+&M);uh8>AIP%&L?L zv1Gs9pLH!UNczL`{|Z`5gipz`IR)%CIVWEdPE&w_vgn6y)wwKFksV3@UwxfvIMiLh zxMvt+#?0`W89Ukcbu8J*jD24ciELT&pln%+tjTW1l3hfl;t7!@F~eXi$%O2MBx@l` zQvROz|Kp;puXl2 zG*YoqO#vi!%4oX&j>O*>3_*~}Nwa?0RCs0y#zmdh#@~@vOMn|S^QPp#grRV;04{RY zjMG*bUndWob=Mp=6>e-}viHDmIZq=ac4}2}5e~L|JUQ1=K|fw!7uQLUM6|uUAXbh! z2fPyUaJ<3UYvsZA^VcGJ@J{A#IRLuI4+48I2(yOd#UYMm7&nxSYAu0l&q>tE6Gt4C zuL+LVIa&r)QsjyBRO1*|VJ_1o_M#|d1#+UKQp_5toXz8`Iqd|l~4Z^M?GO9InJ z(h`hVHc+b~EC^Y&LyWrL`^mif2gPyyrduW@LZZ8-?+R#l=6ABFwKMfZE!YK6Ef=re z^KzQ>eq7$Hu=r;u?gSjckQN8@{DOrT_9gx*+8-zGciG0)7OMS9K^9fUa{i2BT#D5d zwt*#Ms3wZ7A-q7U##~oRyhBb+*%8b)nz=9o5I4&E=>h{?2qz^jil@OE zQNwG%%6TUtVQ0k6u`EzLX4IC8IVx;i3@nc$GWvrL zxgjAxd`0Lvog{=TjEF|NrsgAET5r4-0#uhkcrCvd86b!nr#6TUBI}M7ea>>NajB>%(pDgr#0l8tmnJ8>_0yXWhle>DxMOD@p#FZu^wprV=Q!c%CWR2T+EJ*ND} zd;)8LR&JK^N}(~l$nrF$JChe!e2=z+aEva>LeF{7lJd7@KOe=8mFHoK-?H59cRKPVg0ULq@i-s~Tg)!k-r$8Jo38<=gq?I^fFdk|2tFXnn;&)VDW^vv+ z{It(^dS2bzUB}LOq|x;4pvlO>G^Fp|gSq?%h=fX>5D@R_=RPTb?jg6Gbb)<|b9I2w zOR6ewuS#rZJ97ybwS`F@aa_o&Mo}v3A^MD-l`=9Ib9%LP5}==so_RtrG6&+#fbW$x z(A^4~4UW2YAVsMvtOdg)^AJvwnqg32d3u2%)ZmI1;G=aqjLo8>=yCfa*AT^7&j=3E zU51kcY0p{AbbPrOQ}J!dN8IL*%>5rF{!{CQukLpMf=ir@l+R(7o@nnrv`a!4ln`QN zfH)Z-p`)gZ1xuu}GTcOGcxla&1RHF#|C#|@%dn}PXX#!5G%<<;jB3Xh-;+ic7X#1I z3H9m7=jq5sty7EcQ!MEjG$baQ5?MmQrQ&ZR6J#py-rBaU5=J8t;fneGY*9}N8`$e5 zRqMS6SxaP|O%FX8?>I%3S#B`b{;GT)LVEnW!+iW^J{a+g(Sj>ZNq_5t|K#M;jo^F- zDPUKhjX{WOgWLW2s^M#2-O706ecPt{9xNvQ2#MeDYj%vCbgfVNtY`9rXg91dCmBfL z->&QdjZ9UIC!P+1udte@;SCF{kv7&u7Hc+as%uLa4t~N|)!FUAP;)QtTJ=_RU(kYEV7oyjxLtwisEi_C}Qz^VV7jDD@SvS=mM$ev*5uHQ$2mAh^FkARSE*%Vgc24 zGsc8%{k~dCBr|l91qZquBH%zw2u6p3`R;K%XK<7Kvr5{{+K z0E1 z_c|O+-zXs zGskZK&cFFO>0g2zoz(#zT8{3tq^`-im2>uQ&R@3SrhPkh+t7LY;o$1mz_&98$zST; zE*!l1i*)7+MPa${5FS<@>Rn$YVRpEjUU9{sppQrCB~ zCdlZC74ZBG--Cr&|B2}^@KkfTQDfH34W+sEH-yGNbF6PD)$;RKsB@u|*?ubrn~U?q zS$Nu+dDfcXp+EC}$@7;fLBya1wBgLVlQ#<>|Cx)85jRmE6fV47{bS9n-nU+l|0s`l zNSWJS(Elcn-_!lb>hKXwrSxQe1ZqD1Mco5^#Rhzt?^xz`XyM#hoCLd>^~XEV7kNIA zsi?2`EqP@r6i3jdrOQ=JrfAyF*RuIx6a3a(mAZ?nRl$K)ILmT618GA1wl-6?rhFHm zX4Twz?-SwKr>W0N293*jm1Q*elhQQ~Nj-Mmh$a2JCD}_WJPsf9$3 z4htwTUZmTUlpcO=d!>>}5ms3J+{7TUAEbY6^?`RdbaeHf{m(K=eQT&Mp~(xls?~^W z?NCpoQAkp0S!$W{<_f=7q#EO6td&_|2&*^$6;P!^FXNr_MIDN%gtwykZnoQwgLWm*~AvC zYDLkZPtEfyOXCs}J%pot^&4LiLvP6lf7|)sE@tvoDu2s23v=`VJE?#XUB{e^au~;G zDI5g7y+-gWbCv_YP z5ci}{F1@HQF6(6P46{2vG1*?&;V%h63003!$gqmV<@39H4od4qX`9Pkq|ppZ3E0#fG8A*9ird52ch28I`u#JqJzB1O4RBFB&ml zst+fN)#C!Lz~cxNnSjq@O!0LfM;lvuj#m+5&xz)5?Bk|~4D+IoRCa&u7i`Y6pZ4hv zC52IEF$az#yN|*-XYF>fC+Uo{ibK8V-nQ;u*2qhvR*$QYuiVgDBw3d{{+5ak?{8bf zxADsYG7?j7r%vu`>IvvJrG8srGc|Mv&d2=tq^SH^QF$-s*ZOtS#kIfR6mc)JH01@S z*#BB~ThC>K_bVL!f|i(P{zt<7f05Gd4VV8TrT>#~iyI{{$=CgFQo81pl#cx?Hj}$( zQE8MVU{vC;Zl9T5q}Ni+Bx7Gi3$^O||D-fmkH}rQ5~n7<()@#Hj_ui^u<5QlE)(*U zhU?28`dl1>+`162gy;Hezj^fBK?$bF)-JkH-OAPehmPHFr{N~?N3 zVOH@M$ciYV1U~tXl-Axnd6f9lo3BFU=Z{kfw|Y}s>{B6`kFnaH!xL40z4@$GIu+xl z6R|!=g|igu-MB${j|lT)7If25UVP=B<2RdG>9@bV(9LX>wCjI(E{pQ?zWd2v3IghA zWUTZz{V1b!0D3CnX3A)?)K3Jt;s~dtbc527%&CMMH6WX#yagQ+PeGZ8H5y`XB~pYo zt-TvhCEP18@^_E_B;1V~J2)%k(3Y`a90b$L>U6AVDw^Xe70d@KHk?9@THNx4C-t-~R^dgg$!cq*1p!1VDW)5l1vanPy$EBZT#pIu-24Y(#U39S^MV}FP+!pFO%QO zCK$bUu8n9`o12c;r8OngTzJPC^x{&4kjQ`$SEDOmE@!-O1@})!*WwMO%eSOme!4Y} zPPV$ondCW1GoOgJd5m$tQ5WYVXs+eIL8cr^Ul(<=IG-3w&-3EtxwAcz%<%rAh(6k! zTU_1XU((zZr-sGnL>=R3(QGT32_cuOsm_);lF<5)S4j1* zF66x_WO{O+HTO$b-J_dNicwx+8f7me(7w54P;Kp#2G)GxK(67oEi8W3)Ti0U%X2e{ z7U3ch{pCjl7|+dD`=Qf}>LOm4l+7pd5A$2|w^jna^J5YmE&;l`QN(>4|9w4D>K8le|uvOdOUleyOWCU*EJ) zl-w_DqMOnc@chTJyN+JrgU9D!0x1zb)|%g5F$>-*I(%akyo)|sjb7-&L>|v78A~+Wp;ybuXIx#yDhniOux$Ciw3qb>eTp5cj+NK3F9jPImr$a~#X8 z{5O(#g4~cy#MA&1m{2?*Q5z{-H4Q(5$AiLamI1bAE$^t_BI7wh!B4dosKJxH zVq57?_(X1#YYqNMQ#IVk#Ug~I96EDEHB}W?V;uaWCQH=PTV$3;iRWE##ZRh(EJ}oC z`0uLzVdgY$yEZdHLy@orskLfq=Qi}RFC5)sO$18DishPxp4VKBs4J!ysZI#FuhilV zBZ=J*i5l@eDg4$9O}%;Ip<f12@B=}5tI^siNWgxA>pzZY~=H9nZ5HUT#^Tji4|S2+`h zwn3VjSdy;1X~N$@PMYI;(O}3EKNA%@y57po_thJ|y#}-I>}zW4?`$W^RrXlb&>ASF z?t$v;=NvpPw04&h<=2nMM$HB45Qu`YgVY$2#g=ao{?saO4ma&v-7vmz+F9Y8yMkkU z1xptU>%LW-mF@IU%^<+L)zfW9K&&|BMzRW}_tJC)qA>2VqVjAb>hE5p`o7Qgc+YX? z@7CL048{!spu2R4dX(zw3!|H7be8CgUt8F-kqJz4f^MGEz17mQ3Fj=iL9G%0d^@x2 zX)bpO0hqN(UmHo+9ri3J!S<)xIY-}+t>*j5t!#9qA?FVNh%gtA(lynS(A+^nl8sRH z;C-Q7uL2#PMSuf``IpR9lfBR zx#_9>9Wn}8pD&ZoLcUg5X`e;~+BF=lpQ7gzu6I)K@6(A^k}LHY+yB^fxdL`BTHK8a zv^us#>pL(lv8KRq%Uo2R&-0oYndq1H3K{IO*qW(og|o)jUZZ&ie&k!NetE{#G;?XQ zW^Vb>j#__DDhV)*hx(iRYtaZ!XcYN`NiR5&tL&U@L_LM$ z8aml#r3Z2MP@lcZULC$N&XuSf8;lOgR)kYEdtCEskBZvz((=QSI%8JPy3@K_E&1erA7{}tKI>;%hgGr}_QpC=hjstC`tW|n z`q^_oQ_U*AkJpq5rKcvC#AdTBPjjz1pWslAs=J(A>pJ(zZTY2oksap^J8oRp+TH1j zOkpQ}i(`&iWIA_v_pp2?s{8j6q9UqK{ljj~-Ix{ebJ0UiANC3dP8aWv9@Vy3E0;WN zw0HZ^b1H_MHLBL%%#{RUlW*@3TQ@QSGv8;3cYj!G-pX=4`RySpI^N+Fx|z033}XC9 z=~Og*m627}kb9#}HSOgtb5cyA)W`RE_iiWNx&KG$ydY2FFWsNF<|iXfK23b6ynnax zv*q=s8)8CrXal1AT*$xKc{vLG4{r&mzG&fHMv6I1KWCm3-qahjMKz7%AFVOwC!oq`9^(jRn7R-8gp>Cddw!A9WIEIK8Pin5Wz>*xEeDup zV2*>fj-D#4hXsCaOTPp}Esbg|k}@pSpdQ7aGurE!zFPNhLYirKWpQv_NgI{r7CY YE_I3T>`nGg?@Wz+RkNB?f=2uQ0oIBalK=n! literal 0 HcmV?d00001 diff --git a/docs/python_portfolio.md b/docs/python_portfolio.md new file mode 100644 index 00000000..32086e2f --- /dev/null +++ b/docs/python_portfolio.md @@ -0,0 +1,35 @@ +# Python Portfolio + +This gallery is the Python-facing showcase for the `pycddp` bindings. Each +demo is solved directly from Python, then rendered as an animation with +Matplotlib. + +## Regenerate the gallery + +```bash +source .venv/bin/activate +python examples/python_portfolio.py --demo all --output-dir docs/assets/python_portfolio +``` + +## Demos + +### Pendulum Swing-Up + +Torque-limited `CLDDP` solve for a damped pendulum. + +Pendulum swing-up animation + +### Cart-Pole Swing-Up + +Bounded-force `CLDDP` solve that swings the pole upright and settles near the +origin. + +Cart-pole swing-up animation + +### Unicycle Obstacle Avoidance + +`IPDDP` solve with a circular obstacle constraint, showing how the Python +bindings can be used for constrained trajectory visualization without building +the legacy C++ plotting stack. + +Unicycle obstacle avoidance animation diff --git a/examples/python_portfolio.py b/examples/python_portfolio.py new file mode 100644 index 00000000..8e4474d3 --- /dev/null +++ b/examples/python_portfolio.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python3 +"""Generate animated Python portfolio demos for the pycddp bindings.""" + +from __future__ import annotations + +import argparse +from pathlib import Path + +import python_portfolio_lib as portfolio + + +def parse_args() -> argparse.Namespace: + parser = argparse.ArgumentParser(description=__doc__) + parser.add_argument( + "--demo", + choices=["all", *sorted(portfolio.DEMO_BUILDERS)], + default="all", + help="Which demo to generate.", + ) + parser.add_argument( + "--output-dir", + type=Path, + default=Path("docs/assets/python_portfolio"), + help="Directory where GIFs will be written.", + ) + parser.add_argument( + "--fps", + type=int, + default=16, + help="Animation frame rate.", + ) + parser.add_argument( + "--dpi", + type=int, + default=110, + help="Output DPI for the generated GIFs.", + ) + parser.add_argument( + "--frame-step", + type=int, + default=2, + help="Use every Nth solver state as an animation frame.", + ) + return parser.parse_args() + + +def main() -> None: + args = parse_args() + demo_names = ( + sorted(portfolio.DEMO_BUILDERS) + if args.demo == "all" + else [args.demo] + ) + + args.output_dir.mkdir(parents=True, exist_ok=True) + + for name in demo_names: + result = portfolio.build_demo(name) + output_path = args.output_dir / f"{result.slug}.gif" + portfolio.save_animation( + result, + output_path, + fps=args.fps, + dpi=args.dpi, + frame_step=args.frame_step, + ) + print( + f"{result.title}: {output_path} " + f"(solver={result.solver_name}, final_error={result.final_error:.4f})" + ) + + +if __name__ == "__main__": + main() diff --git a/examples/python_portfolio_lib.py b/examples/python_portfolio_lib.py new file mode 100644 index 00000000..945e8f94 --- /dev/null +++ b/examples/python_portfolio_lib.py @@ -0,0 +1,698 @@ +"""Portfolio-quality Python demos and animations for pycddp.""" + +from __future__ import annotations + +from dataclasses import dataclass, field +from pathlib import Path +from typing import Any, Callable + +import matplotlib.pyplot as plt +import numpy as np +from matplotlib import animation +from matplotlib.patches import Circle, FancyArrowPatch, Rectangle +from matplotlib.transforms import Affine2D + +import pycddp + + +_BACKGROUND = "#f5efe3" +_PANEL = "#fffaf2" +_TEXT = "#1d2533" +_GRID = "#d8cdb8" +_ACCENT = "#1f6f8b" +_SECONDARY = "#d97706" +_TERTIARY = "#9c2f2f" +_SUCCESS = "#1f7a5c" +_MUTED = "#8d99a6" + + +@dataclass(slots=True) +class DemoResult: + slug: str + title: str + solver_name: str + solution: pycddp.CDDPSolution + states: np.ndarray + controls: np.ndarray + time_points: np.ndarray + target_state: np.ndarray + metadata: dict[str, Any] = field(default_factory=dict) + + @property + def final_error(self) -> float: + return float(np.linalg.norm(self.states[-1] - self.target_state)) + + +def _solution_arrays(solution: pycddp.CDDPSolution) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + states = np.vstack([np.asarray(x, dtype=float) for x in solution.state_trajectory]) + if solution.control_trajectory: + controls = np.vstack([np.asarray(u, dtype=float) for u in solution.control_trajectory]) + else: + controls = np.zeros((0, 0), dtype=float) + time_points = np.asarray(solution.time_points, dtype=float) + return states, controls, time_points + + +def _rollout_system( + model: pycddp.DynamicalSystem, + initial_state: np.ndarray, + controls: list[np.ndarray], +) -> tuple[list[np.ndarray], list[np.ndarray]]: + state = np.asarray(initial_state, dtype=float).copy() + states = [state.copy()] + rolled_controls: list[np.ndarray] = [] + for control in controls: + control_array = np.asarray(control, dtype=float).copy() + rolled_controls.append(control_array) + state = np.asarray(model.get_discrete_dynamics(state, control_array), dtype=float) + states.append(state.copy()) + return states, rolled_controls + + +def _default_options(max_iterations: int = 120) -> pycddp.CDDPOptions: + opts = pycddp.CDDPOptions() + opts.max_iterations = max_iterations + opts.verbose = False + opts.print_solver_header = False + opts.return_iteration_info = True + return opts + + +def _make_result( + slug: str, + title: str, + target_state: np.ndarray, + solution: pycddp.CDDPSolution, + **metadata: Any, +) -> DemoResult: + states, controls, time_points = _solution_arrays(solution) + return DemoResult( + slug=slug, + title=title, + solver_name=solution.solver_name, + solution=solution, + states=states, + controls=controls, + time_points=time_points, + target_state=np.asarray(target_state, dtype=float), + metadata=metadata, + ) + + +def solve_pendulum_demo() -> DemoResult: + dt = 0.05 + horizon = 120 + x0 = np.array([0.0, 0.0], dtype=float) + xref = np.array([np.pi, 0.0], dtype=float) + + opts = _default_options(max_iterations=150) + opts.tolerance = 1e-5 + opts.acceptable_tolerance = 1e-4 + opts.regularization.initial_value = 1e-6 + + model = pycddp.Pendulum(dt, length=0.5, mass=1.0, damping=0.01) + solver = pycddp.CDDP(x0, xref, horizon, dt, opts) + solver.set_dynamical_system(model) + solver.set_objective( + pycddp.QuadraticObjective( + 0.1 * np.eye(2), + 0.02 * np.eye(1), + 200.0 * np.eye(2), + xref, + [], + dt, + ) + ) + solver.add_constraint( + "control_limits", + pycddp.ControlConstraint(np.array([-30.0]), np.array([30.0])), + ) + seed_controls = [ + np.array([8.0], dtype=float) if index < 25 else np.zeros(1, dtype=float) + for index in range(horizon) + ] + seed_states, seed_controls = _rollout_system(model, x0, seed_controls) + solver.set_initial_trajectory(seed_states, seed_controls) + + solution = solver.solve(pycddp.SolverType.CLDDP) + return _make_result( + slug="pendulum_swing_up", + title="Pendulum Swing-Up", + target_state=xref, + solution=solution, + timestep=dt, + length=0.5, + subtitle="Seeded CLDDP swing-up from the hanging equilibrium", + ) + + +def solve_cartpole_demo() -> DemoResult: + dt = 0.05 + horizon = 100 + x0 = np.array([0.0, 0.0, 0.0, 0.0], dtype=float) + xref = np.array([0.0, np.pi, 0.0, 0.0], dtype=float) + + opts = _default_options(max_iterations=120) + opts.tolerance = 1e-6 + opts.acceptable_tolerance = 1e-5 + opts.regularization.initial_value = 1e-5 + + solver = pycddp.CDDP(x0, xref, horizon, dt, opts) + solver.set_dynamical_system(pycddp.CartPole(dt)) + solver.set_objective( + pycddp.QuadraticObjective( + np.zeros((4, 4)), + 0.1 * np.eye(1), + 80.0 * np.eye(4), + xref, + [], + dt, + ) + ) + solver.add_constraint( + "force_limits", + pycddp.ControlConstraint(np.array([-5.0]), np.array([5.0])), + ) + solver.set_initial_trajectory( + [x0.copy() for _ in range(horizon + 1)], + [np.zeros(1, dtype=float) for _ in range(horizon)], + ) + + solution = solver.solve(pycddp.SolverType.CLDDP) + return _make_result( + slug="cartpole_swing_up", + title="Cart-Pole Swing-Up", + target_state=xref, + solution=solution, + timestep=dt, + pole_length=0.5, + subtitle="Control-limited CLDDP solve", + ) + + +def solve_unicycle_demo() -> DemoResult: + dt = 0.03 + horizon = 100 + x0 = np.array([0.0, 0.0, np.pi / 4.0], dtype=float) + xref = np.array([2.0, 2.0, np.pi / 2.0], dtype=float) + obstacle_center = np.array([1.0, 1.0], dtype=float) + obstacle_radius = 0.4 + + opts = _default_options(max_iterations=100) + opts.tolerance = 1e-4 + + solver_objective = pycddp.QuadraticObjective( + np.zeros((3, 3)), + 0.05 * np.eye(2), + np.diag([100.0, 100.0, 50.0]), + xref, + [], + dt, + ) + control_limits = pycddp.ControlConstraint( + np.array([-1.1, -np.pi]), + np.array([1.1, np.pi]), + ) + initial_states = [x0.copy() for _ in range(horizon + 1)] + initial_controls = [np.zeros(2, dtype=float) for _ in range(horizon)] + + # Seed the constrained solve with the smoother unconstrained route so the + # obstacle-avoidance case is stable across repeated runs. + baseline = pycddp.CDDP(x0, xref, horizon, dt, opts) + baseline.set_dynamical_system(pycddp.Unicycle(dt)) + baseline.set_objective(solver_objective) + baseline.add_constraint("control_limits", control_limits) + baseline.set_initial_trajectory(initial_states, initial_controls) + baseline_solution = baseline.solve(pycddp.SolverType.CLDDP) + + best_solution: pycddp.CDDPSolution | None = None + best_score: tuple[float, float, float] | None = None + + for _ in range(4): + solver = pycddp.CDDP(x0, xref, horizon, dt, opts) + solver.set_dynamical_system(pycddp.Unicycle(dt)) + solver.set_objective( + pycddp.QuadraticObjective( + np.zeros((3, 3)), + 0.05 * np.eye(2), + np.diag([100.0, 100.0, 50.0]), + xref, + [], + dt, + ) + ) + solver.add_constraint( + "control_limits", + pycddp.ControlConstraint( + np.array([-1.1, -np.pi]), + np.array([1.1, np.pi]), + ), + ) + solver.add_constraint( + "obstacle", + pycddp.BallConstraint(obstacle_radius, obstacle_center), + ) + solver.set_initial_trajectory( + list(baseline_solution.state_trajectory), + list(baseline_solution.control_trajectory), + ) + + candidate = solver.solve(pycddp.SolverType.IPDDP) + candidate_error = float( + np.linalg.norm(np.asarray(candidate.state_trajectory[-1]) - xref) + ) + candidate_score = ( + float(candidate.final_primal_infeasibility), + candidate_error, + float(candidate.final_objective), + ) + if best_score is None or candidate_score < best_score: + best_score = candidate_score + best_solution = candidate + if candidate.final_primal_infeasibility < 1e-3 and candidate_error < 0.02: + break + + assert best_solution is not None + return _make_result( + slug="unicycle_obstacle_avoidance", + title="Unicycle Obstacle Avoidance", + target_state=xref, + solution=best_solution, + timestep=dt, + obstacle_center=obstacle_center, + obstacle_radius=obstacle_radius, + subtitle="IPDDP with a ball constraint", + ) + + +DEMO_BUILDERS: dict[str, Callable[[], DemoResult]] = { + "pendulum": solve_pendulum_demo, + "cartpole": solve_cartpole_demo, + "unicycle": solve_unicycle_demo, +} + + +def build_demo(name: str) -> DemoResult: + try: + return DEMO_BUILDERS[name]() + except KeyError as exc: + choices = ", ".join(sorted(DEMO_BUILDERS)) + raise ValueError(f"Unknown demo '{name}'. Expected one of: {choices}.") from exc + + +def _style_axes(ax: plt.Axes) -> None: + ax.set_facecolor(_PANEL) + for spine in ax.spines.values(): + spine.set_color(_GRID) + spine.set_linewidth(1.0) + ax.tick_params(colors=_TEXT, labelsize=9) + ax.grid(True, color=_GRID, alpha=0.55, linewidth=0.7) + + +def _style_scene_axes(ax: plt.Axes) -> None: + ax.set_facecolor(_PANEL) + for spine in ax.spines.values(): + spine.set_visible(False) + ax.set_xticks([]) + ax.set_yticks([]) + ax.grid(False) + + +def _metric_bounds(values: np.ndarray, minimum: float = 1.0) -> tuple[float, float]: + amplitude = max(float(np.max(np.abs(values))) * 1.15, minimum) + return -amplitude, amplitude + + +def _apply_title(fig: plt.Figure, result: DemoResult) -> None: + fig.suptitle(result.title, fontsize=18, fontweight="bold", color=_TEXT, y=0.965) + fig.subplots_adjust(top=0.81) + + +def save_animation( + result: DemoResult, + output_path: str | Path, + fps: int = 16, + dpi: int = 110, + frame_step: int = 2, +) -> Path: + output = Path(output_path) + output.parent.mkdir(parents=True, exist_ok=True) + + if result.slug == "pendulum_swing_up": + fig, anim = _animate_pendulum(result, fps=fps, frame_step=frame_step) + elif result.slug == "cartpole_swing_up": + fig, anim = _animate_cartpole(result, fps=fps, frame_step=frame_step) + elif result.slug == "unicycle_obstacle_avoidance": + fig, anim = _animate_unicycle(result, fps=fps, frame_step=frame_step) + else: + raise ValueError(f"No animation renderer for demo '{result.slug}'.") + + writer = animation.PillowWriter(fps=fps) + anim.save(output, writer=writer, dpi=dpi) + plt.close(fig) + return output + + +def _animate_pendulum( + result: DemoResult, + fps: int, + frame_step: int, +) -> tuple[plt.Figure, animation.FuncAnimation]: + states = result.states + controls = result.controls[:, 0] + time_points = result.time_points + pendulum_length = float(result.metadata["length"]) + frames = list(range(0, len(states), frame_step)) + if frames[-1] != len(states) - 1: + frames.append(len(states) - 1) + + fig = plt.figure(figsize=(9.2, 5.2), facecolor=_BACKGROUND) + gs = fig.add_gridspec( + 2, + 2, + width_ratios=[1.55, 1.0], + height_ratios=[1.0, 1.0], + wspace=0.16, + hspace=0.20, + ) + ax_main = fig.add_subplot(gs[:, 0]) + ax_phase = fig.add_subplot(gs[0, 1]) + ax_ctrl = fig.add_subplot(gs[1, 1]) + _apply_title(fig, result) + _style_scene_axes(ax_main) + _style_axes(ax_phase) + _style_axes(ax_ctrl) + + limit = pendulum_length * 1.45 + ax_main.set_xlim(-limit, limit) + ax_main.set_ylim(-limit, limit) + ax_main.set_aspect("equal") + ax_main.set_title("Swing-Up Motion", color=_TEXT, fontsize=11, pad=10) + orbit = Circle((0.0, 0.0), pendulum_length, facecolor="none", edgecolor=_GRID, linewidth=1.0, linestyle="--") + ax_main.add_patch(orbit) + ax_main.scatter([0.0], [0.0], s=35, color=_TEXT, zorder=4) + target_x = pendulum_length * np.sin(result.target_state[0]) + target_y = -pendulum_length * np.cos(result.target_state[0]) + ghost_rod, = ax_main.plot([0.0, target_x], [0.0, target_y], color=_MUTED, linewidth=2.0, linestyle="--") + ghost_bob = Circle((target_x, target_y), 0.06, facecolor="none", edgecolor=_MUTED, linewidth=1.6, linestyle="--") + ax_main.add_patch(ghost_bob) + + ax_phase.set_title("Phase Portrait", color=_TEXT, fontsize=11, pad=10) + ax_phase.set_xlabel("Angle [rad]", color=_TEXT) + ax_phase.set_ylabel("Angular rate [rad/s]", color=_TEXT) + theta_min = float(np.min(states[:, 0])) + theta_max = float(np.max(states[:, 0])) + omega_min = float(np.min(states[:, 1])) + omega_max = float(np.max(states[:, 1])) + theta_pad = max(0.2, 0.08 * max(abs(theta_min), abs(theta_max), 1.0)) + omega_pad = max(0.2, 0.12 * max(abs(omega_min), abs(omega_max), 1.0)) + ax_phase.set_xlim(theta_min - theta_pad, theta_max + theta_pad) + ax_phase.set_ylim(omega_min - omega_pad, omega_max + omega_pad) + ax_phase.axvline(result.target_state[0], color=_MUTED, linewidth=1.0, linestyle="--") + ax_phase.axhline(0.0, color=_GRID, linewidth=1.0) + + ax_ctrl.set_xlim(time_points[0], time_points[-2] if len(time_points) > 1 else 1.0) + ctrl_min, ctrl_max = _metric_bounds(controls) + ax_ctrl.set_ylim(ctrl_min, ctrl_max) + ax_ctrl.set_title("Control Torque", color=_TEXT, fontsize=11, pad=10) + ax_ctrl.set_xlabel("Time [s]", color=_TEXT) + ax_ctrl.set_ylabel("Torque", color=_TEXT) + + bob_trail, = ax_main.plot([], [], color=_SECONDARY, linewidth=2.2, alpha=0.7) + rod, = ax_main.plot([], [], color=_ACCENT, linewidth=3.2) + bob = Circle((0.0, 0.0), 0.07, color=_TERTIARY) + ax_main.add_patch(bob) + torque_text = ax_main.text( + 0.03, + 0.95, + "", + transform=ax_main.transAxes, + ha="left", + va="top", + fontsize=10, + color=_TEXT, + bbox={"boxstyle": "round,pad=0.35", "facecolor": "#fff7ea", "edgecolor": _GRID}, + ) + + phase_path, = ax_phase.plot(states[:, 0], states[:, 1], color=_GRID, linewidth=1.8) + phase_trace, = ax_phase.plot([], [], color=_ACCENT, linewidth=2.2) + phase_marker, = ax_phase.plot([], [], "o", color=_TERTIARY, markersize=7) + + control_history, = ax_ctrl.plot(time_points[:-1], controls, color=_ACCENT, linewidth=2.0) + control_marker, = ax_ctrl.plot([], [], "o", color=_SECONDARY, markersize=7) + + def update(frame_index: int) -> tuple[Any, ...]: + theta = states[frame_index, 0] + x = pendulum_length * np.sin(theta) + y = -pendulum_length * np.cos(theta) + trail_start = max(0, frame_index - 30) + trail_x = pendulum_length * np.sin(states[trail_start : frame_index + 1, 0]) + trail_y = -pendulum_length * np.cos(states[trail_start : frame_index + 1, 0]) + bob_trail.set_data(trail_x, trail_y) + rod.set_data([0.0, x], [0.0, y]) + bob.center = (x, y) + phase_trace.set_data(states[: frame_index + 1, 0], states[: frame_index + 1, 1]) + phase_marker.set_data([states[frame_index, 0]], [states[frame_index, 1]]) + control_idx = min(frame_index, len(controls) - 1) + control_marker.set_data([time_points[control_idx]], [controls[control_idx]]) + torque_text.set_text( + f"angle = {theta:+.2f} rad\nrate = {states[frame_index, 1]:+.2f} rad/s\ntorque = {controls[control_idx]:+.2f}" + ) + return ( + orbit, + ghost_rod, + ghost_bob, + bob_trail, + rod, + bob, + phase_path, + phase_trace, + phase_marker, + control_history, + control_marker, + torque_text, + ) + + return fig, animation.FuncAnimation( + fig, + update, + frames=frames, + interval=1000 / fps, + blit=False, + ) + + +def _animate_cartpole( + result: DemoResult, + fps: int, + frame_step: int, +) -> tuple[plt.Figure, animation.FuncAnimation]: + states = result.states + controls = result.controls[:, 0] + time_points = result.time_points + pole_length = float(result.metadata["pole_length"]) + frames = list(range(0, len(states), frame_step)) + if frames[-1] != len(states) - 1: + frames.append(len(states) - 1) + + fig = plt.figure(figsize=(8.8, 5.0), facecolor=_BACKGROUND) + gs = fig.add_gridspec(1, 2, width_ratios=[1.45, 1.0], wspace=0.18) + ax_main = fig.add_subplot(gs[0, 0]) + ax_force = fig.add_subplot(gs[0, 1]) + _apply_title(fig, result) + _style_scene_axes(ax_main) + _style_axes(ax_force) + + ax_main.set_xlim(-2.0, 2.0) + ax_main.set_ylim(-0.9, 1.2) + ax_main.set_title("Swing-Up Motion", color=_TEXT, fontsize=11, pad=10) + ax_main.axhline(0.0, color=_GRID, linewidth=2.0) + ghost_cart = Rectangle((-0.18, -0.1), 0.36, 0.2, facecolor="none", edgecolor=_MUTED, linewidth=1.4, linestyle="--") + ax_main.add_patch(ghost_cart) + ghost_pole, = ax_main.plot([0.0, 0.0], [0.1, -pole_length + 0.1], color=_MUTED, linewidth=2.0, linestyle="--") + + ax_force.set_xlim(time_points[0], time_points[-2] if len(time_points) > 1 else 1.0) + force_min, force_max = _metric_bounds(controls) + ax_force.set_ylim(force_min, force_max) + ax_force.set_title("Control Force", color=_TEXT, fontsize=11, pad=10) + ax_force.set_xlabel("Time [s]", color=_TEXT) + ax_force.set_ylabel("Force", color=_TEXT) + + cart = Rectangle((-0.18, -0.1), 0.36, 0.2, facecolor=_ACCENT, edgecolor=_TEXT, linewidth=1.2) + ax_main.add_patch(cart) + pole, = ax_main.plot([], [], color=_TERTIARY, linewidth=3.0) + bob = Circle((0.0, 0.0), 0.05, color=_SECONDARY) + ax_main.add_patch(bob) + path_line, = ax_main.plot([], [], color=_SUCCESS, linewidth=1.6, alpha=0.8) + state_text = ax_main.text( + 0.03, + 0.95, + "", + transform=ax_main.transAxes, + ha="left", + va="top", + fontsize=10, + color=_TEXT, + bbox={"boxstyle": "round,pad=0.35", "facecolor": "#fff7ea", "edgecolor": _GRID}, + ) + + force_line, = ax_force.plot(time_points[:-1], controls, color=_ACCENT, linewidth=2.0) + force_marker, = ax_force.plot([], [], "o", color=_SECONDARY, markersize=7) + + def update(frame_index: int) -> tuple[Any, ...]: + cart_x = states[frame_index, 0] + theta = states[frame_index, 1] + cart.set_x(cart_x - cart.get_width() / 2.0) + pivot = np.array([cart_x, cart.get_y() + cart.get_height() / 2.0]) + pole_tip = pivot + np.array([pole_length * np.sin(theta), -pole_length * np.cos(theta)]) + pole.set_data([pivot[0], pole_tip[0]], [pivot[1], pole_tip[1]]) + bob.center = tuple(pole_tip) + path_line.set_data(states[: frame_index + 1, 0], np.zeros(frame_index + 1)) + force_idx = min(frame_index, len(controls) - 1) + force_marker.set_data([time_points[force_idx]], [controls[force_idx]]) + state_text.set_text( + f"x = {cart_x:+.2f} m\nangle = {theta:+.2f} rad" + ) + return ( + ghost_cart, + ghost_pole, + cart, + pole, + bob, + path_line, + force_line, + force_marker, + state_text, + ) + + return fig, animation.FuncAnimation( + fig, + update, + frames=frames, + interval=1000 / fps, + blit=False, + ) + + +def _animate_unicycle( + result: DemoResult, + fps: int, + frame_step: int, +) -> tuple[plt.Figure, animation.FuncAnimation]: + states = result.states + controls = result.controls + time_points = result.time_points + obstacle_center = np.asarray(result.metadata["obstacle_center"], dtype=float) + obstacle_radius = float(result.metadata["obstacle_radius"]) + frames = list(range(0, len(states), frame_step)) + if frames[-1] != len(states) - 1: + frames.append(len(states) - 1) + + fig = plt.figure(figsize=(9.2, 5.2), facecolor=_BACKGROUND) + gs = fig.add_gridspec( + 2, + 2, + width_ratios=[1.45, 1.0], + height_ratios=[1.0, 1.0], + wspace=0.16, + hspace=0.20, + ) + ax_map = fig.add_subplot(gs[:, 0]) + ax_speed = fig.add_subplot(gs[0, 1]) + ax_turn = fig.add_subplot(gs[1, 1]) + _apply_title(fig, result) + _style_axes(ax_map) + _style_axes(ax_speed) + _style_axes(ax_turn) + + ax_map.set_xlim(-0.35, 2.35) + ax_map.set_ylim(-0.35, 2.35) + ax_map.set_aspect("equal") + ax_map.set_title("Trajectory", color=_TEXT, fontsize=11, pad=10) + ax_map.set_xlabel("x [m]", color=_TEXT) + ax_map.set_ylabel("y [m]", color=_TEXT) + ax_map.set_xticks([0.0, 1.0, 2.0]) + ax_map.set_yticks([0.0, 1.0, 2.0]) + + obstacle = Circle(obstacle_center, obstacle_radius, facecolor="#fbd38d", edgecolor=_SECONDARY, linewidth=2.0, alpha=0.55) + ax_map.add_patch(obstacle) + ax_map.scatter(states[0, 0], states[0, 1], color=_SUCCESS, s=55) + ax_map.scatter(result.target_state[0], result.target_state[1], color=_TERTIARY, s=55) + ax_map.annotate("start", (states[0, 0], states[0, 1]), xytext=(6, -14), textcoords="offset points", color=_SUCCESS, fontsize=9) + ax_map.annotate("goal", (result.target_state[0], result.target_state[1]), xytext=(6, 6), textcoords="offset points", color=_TERTIARY, fontsize=9) + full_path, = ax_map.plot(states[:, 0], states[:, 1], color=_GRID, linewidth=1.8, linestyle="--") + trail, = ax_map.plot([], [], color=_ACCENT, linewidth=2.4) + vehicle = Rectangle((-0.12, -0.05), 0.24, 0.10, facecolor=_ACCENT, edgecolor=_TEXT, linewidth=1.2) + ax_map.add_patch(vehicle) + heading = FancyArrowPatch((0.0, 0.0), (0.0, 0.0), arrowstyle="-|>", mutation_scale=12, color=_SECONDARY, linewidth=2.0) + ax_map.add_patch(heading) + + control_speed = controls[:, 0] + control_turn = controls[:, 1] + ax_speed.set_xlim(time_points[0], time_points[-2] if len(time_points) > 1 else 1.0) + speed_min, speed_max = _metric_bounds(control_speed) + ax_speed.set_ylim(speed_min, speed_max) + ax_speed.set_title("Linear Speed", color=_TEXT, fontsize=10, pad=8) + ax_speed.set_ylabel("m/s", color=_TEXT) + speed_line, = ax_speed.plot(time_points[:-1], control_speed, color=_ACCENT, linewidth=2.0) + speed_marker, = ax_speed.plot([], [], "o", color=_ACCENT, markersize=7) + + ax_turn.set_xlim(time_points[0], time_points[-2] if len(time_points) > 1 else 1.0) + turn_min, turn_max = _metric_bounds(control_turn) + ax_turn.set_ylim(turn_min, turn_max) + ax_turn.set_title("Turn Rate", color=_TEXT, fontsize=10, pad=8) + ax_turn.set_xlabel("Time [s]", color=_TEXT) + ax_turn.set_ylabel("rad/s", color=_TEXT) + turn_line, = ax_turn.plot(time_points[:-1], control_turn, color=_SECONDARY, linewidth=2.0) + turn_marker, = ax_turn.plot([], [], "o", color=_SECONDARY, markersize=7) + + status_text = ax_map.text( + 0.03, + 0.95, + "", + transform=ax_map.transAxes, + ha="left", + va="top", + fontsize=10, + color=_TEXT, + bbox={"boxstyle": "round,pad=0.35", "facecolor": "#fff7ea", "edgecolor": _GRID}, + ) + + def update(frame_index: int) -> tuple[Any, ...]: + x, y, theta = states[frame_index] + trail.set_data(states[: frame_index + 1, 0], states[: frame_index + 1, 1]) + vehicle.set_xy((x - vehicle.get_width() / 2.0, y - vehicle.get_height() / 2.0)) + vehicle.set_transform( + Affine2D().rotate_around(x, y, theta) + ax_map.transData + ) + arrow_length = 0.25 + heading.set_positions((x, y), (x + arrow_length * np.cos(theta), y + arrow_length * np.sin(theta))) + ctrl_idx = min(frame_index, len(control_speed) - 1) + speed_marker.set_data([time_points[ctrl_idx]], [control_speed[ctrl_idx]]) + turn_marker.set_data([time_points[ctrl_idx]], [control_turn[ctrl_idx]]) + obstacle_margin = np.min( + np.linalg.norm(states[: frame_index + 1, :2] - obstacle_center, axis=1) + ) - obstacle_radius + status_text.set_text( + f"heading = {theta:+.2f} rad\nclearance = {obstacle_margin:+.2f} m" + ) + return ( + obstacle, + full_path, + trail, + vehicle, + heading, + speed_line, + speed_marker, + turn_line, + turn_marker, + status_text, + ) + + return fig, animation.FuncAnimation( + fig, + update, + frames=frames, + interval=1000 / fps, + blit=False, + ) diff --git a/python/tests/test_portfolio.py b/python/tests/test_portfolio.py new file mode 100644 index 00000000..3de7ddad --- /dev/null +++ b/python/tests/test_portfolio.py @@ -0,0 +1,49 @@ +"""Regression tests for the Python portfolio demos.""" + +from __future__ import annotations + +import sys +from pathlib import Path + +import matplotlib + +matplotlib.use("Agg") + +sys.path.insert(0, str(Path(__file__).resolve().parents[2] / "examples")) + +import python_portfolio_lib as portfolio + + +def test_portfolio_demos_reach_targets(): + pendulum = portfolio.solve_pendulum_demo() + cartpole = portfolio.solve_cartpole_demo() + unicycle = portfolio.solve_unicycle_demo() + + assert pendulum.solver_name == "CLDDP" + assert pendulum.final_error < 1e-3 + assert pendulum.states[:, 0].max() > 3.0 + assert abs(pendulum.controls[:, 0]).max() > 1.0 + + assert cartpole.solver_name == "CLDDP" + assert cartpole.final_error < 0.05 + + assert unicycle.solver_name == "IPDDP" + assert unicycle.final_error < 0.02 + assert unicycle.solution.final_primal_infeasibility < 1e-3 + + +def test_portfolio_animation_writes_gif(tmp_path): + result = portfolio.solve_pendulum_demo() + + output_path = tmp_path / "pendulum.gif" + written = portfolio.save_animation( + result, + output_path, + fps=10, + dpi=72, + frame_step=6, + ) + + assert written == output_path + assert output_path.exists() + assert output_path.stat().st_size > 0 From 8486d44125f4c2b70a8bed6664e7ec3f4c9ad0c1 Mon Sep 17 00:00:00 2001 From: Tomo Sasaki Date: Thu, 2 Apr 2026 17:43:01 -0400 Subject: [PATCH 2/6] Trim C++ examples and remove ROE model Prune the old example inventory down to a small compiled reference set. Also remove the SpacecraftROE model from the core build, tests, and Python bindings. --- CMakeLists.txt | 1 - README.md | 23 +- examples/CMakeLists.txt | 16 +- examples/cddp_acrobot.cpp | 211 ------ examples/cddp_bicycle.cpp | 232 ------ examples/cddp_car.cpp | 329 --------- examples/cddp_car_ipddp.cpp | 279 ------- examples/cddp_cartpole.cpp | 255 ++----- examples/cddp_forklift_ipddp.cpp | 335 --------- examples/cddp_hcw.cpp | 228 ------ examples/cddp_lti_system.cpp | 172 ----- examples/cddp_manipulator.cpp | 242 +----- examples/cddp_pendulum.cpp | 249 ++----- examples/cddp_quadrotor_circle.cpp | 566 -------------- ...cddp_quadrotor_figure_eight_horizontal.cpp | 556 -------------- ...quadrotor_figure_eight_horizontal_safe.cpp | 625 ---------------- .../cddp_quadrotor_figure_eight_vertical.cpp | 555 -------------- examples/cddp_quadrotor_point.cpp | 536 ++------------ examples/cddp_spacecraft_linear_docking.cpp | 350 --------- examples/cddp_spacecraft_linear_rpo.cpp | 372 ---------- examples/cddp_spacecraft_nonlinear_rpo.cpp | 383 ---------- examples/cddp_spacecraft_roe_rpo.cpp | 478 ------------ examples/cddp_spacecraft_rpo.cpp | 372 ---------- examples/cddp_spacecraft_rpo_fuel.cpp | 390 ---------- examples/cddp_spacecraft_rpo_mc.cpp | 392 ---------- examples/cddp_unicycle.cpp | 230 ++---- examples/cddp_unicycle_mpc.cpp | 289 -------- examples/cddp_unicycle_safe.cpp | 219 ------ examples/cddp_unicycle_safe_ipddp.cpp | 406 ---------- examples/cddp_unicycle_safe_ipddp_v2.cpp | 193 ----- examples/cddp_unicycle_safe_ipddp_v3.cpp | 220 ------ examples/hessian_example.cpp | 182 ----- examples/ipopt_car.cpp | 364 --------- examples/ipopt_cartpole.cpp | 390 ---------- examples/ipopt_quadrotor.cpp | 694 ------------------ examples/ipopt_spacecrat_linear_fuel.cpp | 260 ------- examples/ipopt_spacecrat_rpo.cpp | 260 ------- examples/ipopt_unicycle.cpp | 459 ------------ examples/mpc_hcw.cpp | 386 ---------- examples/test_barrier_strategies.cpp | 147 ---- include/cddp-cpp/cddp.hpp | 1 - .../dynamics_model/spacecraft_roe.hpp | 188 ----- python/pycddp/__init__.py | 1 - python/src/bind_dynamics.cpp | 6 - python/src/bind_solver.cpp | 2 +- src/dynamics_model/spacecraft_roe.cpp | 344 --------- tests/CMakeLists.txt | 4 - tests/dynamics_model/test_spacecraft_roe.cpp | 248 ------- 48 files changed, 265 insertions(+), 13375 deletions(-) delete mode 100644 examples/cddp_acrobot.cpp delete mode 100644 examples/cddp_bicycle.cpp delete mode 100644 examples/cddp_car.cpp delete mode 100644 examples/cddp_car_ipddp.cpp delete mode 100644 examples/cddp_forklift_ipddp.cpp delete mode 100644 examples/cddp_hcw.cpp delete mode 100644 examples/cddp_lti_system.cpp delete mode 100644 examples/cddp_quadrotor_circle.cpp delete mode 100644 examples/cddp_quadrotor_figure_eight_horizontal.cpp delete mode 100644 examples/cddp_quadrotor_figure_eight_horizontal_safe.cpp delete mode 100644 examples/cddp_quadrotor_figure_eight_vertical.cpp delete mode 100644 examples/cddp_spacecraft_linear_docking.cpp delete mode 100644 examples/cddp_spacecraft_linear_rpo.cpp delete mode 100644 examples/cddp_spacecraft_nonlinear_rpo.cpp delete mode 100644 examples/cddp_spacecraft_roe_rpo.cpp delete mode 100644 examples/cddp_spacecraft_rpo.cpp delete mode 100644 examples/cddp_spacecraft_rpo_fuel.cpp delete mode 100644 examples/cddp_spacecraft_rpo_mc.cpp delete mode 100644 examples/cddp_unicycle_mpc.cpp delete mode 100644 examples/cddp_unicycle_safe.cpp delete mode 100644 examples/cddp_unicycle_safe_ipddp.cpp delete mode 100644 examples/cddp_unicycle_safe_ipddp_v2.cpp delete mode 100644 examples/cddp_unicycle_safe_ipddp_v3.cpp delete mode 100644 examples/hessian_example.cpp delete mode 100644 examples/ipopt_car.cpp delete mode 100644 examples/ipopt_cartpole.cpp delete mode 100644 examples/ipopt_quadrotor.cpp delete mode 100644 examples/ipopt_spacecrat_linear_fuel.cpp delete mode 100644 examples/ipopt_spacecrat_rpo.cpp delete mode 100644 examples/ipopt_unicycle.cpp delete mode 100644 examples/mpc_hcw.cpp delete mode 100644 examples/test_barrier_strategies.cpp delete mode 100644 include/cddp-cpp/dynamics_model/spacecraft_roe.hpp delete mode 100644 src/dynamics_model/spacecraft_roe.cpp delete mode 100644 tests/dynamics_model/test_spacecraft_roe.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 3356a3c5..943047c1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -157,7 +157,6 @@ set(dynamics_model_srcs src/dynamics_model/spacecraft_nonlinear.cpp src/dynamics_model/dreyfus_rocket.cpp src/dynamics_model/spacecraft_landing2d.cpp - src/dynamics_model/spacecraft_roe.cpp src/dynamics_model/lti_system.cpp src/dynamics_model/spacecraft_twobody.cpp src/dynamics_model/usv_3dof.cpp diff --git a/README.md b/README.md index dcd56fbc..95fff35b 100644 --- a/README.md +++ b/README.md @@ -29,15 +29,22 @@ $$ $$ ## Examples -The default C++ build currently includes a barrier-strategy comparison example: +The maintained example surface is now split: -```bash -./examples/test_barrier_strategies -``` +* a small C++ reference set in `examples/`, built when `CDDP_CPP_BUILD_EXAMPLES=ON` +* the Python portfolio for plotting, animation, and notebook workflows + +The kept C++ examples are: + +* `cddp_pendulum.cpp` +* `cddp_cartpole.cpp` +* `cddp_unicycle.cpp` +* `cddp_quadrotor_point.cpp` +* `cddp_manipulator.cpp` -Several visualization-focused C++ examples remain in the repository, but they -are not part of the default build. Use the Python bindings for plotting and -notebook workflows. +The wider historical C++ example inventory has been removed to keep the example +surface focused. The kept C++ examples are intentionally minimal and do not depend on +visualization libraries. ### Python Portfolio The Python bindings now ship with a small animation-focused portfolio built on @@ -96,8 +103,6 @@ If you want to use this library for ROS2 MPC node, please refer [CDDP MPC Packag ## References * Y. Tassa, N. Mansard and E. Todorov, "Control-limited differential dynamic programming," 2014 IEEE International Conference on Robotics and Automation (ICRA), 2014, pp. 1168-1175, doi: <10.1109/ICRA.2014.6907001>. * Pavlov, A., Shames, I., and Manzie, C., “Interior Point Differential Dynamic Programming,” IEEE Transactions on Control Systems Technology, Vol. 29, No. 6, 2021, pp. 2720–2727. -* Yuval Tassa's iLQG/DDP trajectory optimization: -* Andrei Pavlov's GitHub repository: ## Third Party Libraries diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f34c5263..6e4a576d 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -12,7 +12,17 @@ # See the License for the specific language governing permissions and # limitations under the License. -# Build only the maintained example used in the default C++ configuration. +# Curated native reference examples that are built with +# `CDDP_CPP_BUILD_EXAMPLES=ON`. These are compile-checked examples of the +# public C++ API, while the Python portfolio remains the visualization path. -add_executable(test_barrier_strategies test_barrier_strategies.cpp) -target_link_libraries(test_barrier_strategies cddp) +function(add_cddp_reference_example target_name source_name) + add_executable(${target_name} ${source_name}) + target_link_libraries(${target_name} PRIVATE cddp) +endfunction() + +add_cddp_reference_example(cddp_pendulum cddp_pendulum.cpp) +add_cddp_reference_example(cddp_cartpole cddp_cartpole.cpp) +add_cddp_reference_example(cddp_unicycle cddp_unicycle.cpp) +add_cddp_reference_example(cddp_quadrotor_point cddp_quadrotor_point.cpp) +add_cddp_reference_example(cddp_manipulator cddp_manipulator.cpp) diff --git a/examples/cddp_acrobot.cpp b/examples/cddp_acrobot.cpp deleted file mode 100644 index b1f00a75..00000000 --- a/examples/cddp_acrobot.cpp +++ /dev/null @@ -1,211 +0,0 @@ -/* - Copyright 2025 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "dynamics_model/acrobot.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -int main() { - int state_dim = 4; - int control_dim = 1; - int horizon = 100; - double timestep = 0.05; - double Tf = timestep * horizon; // Total time - - double l1 = 1.0; - double l2 = 1.0; - double m1 = 1.0; - double m2 = 1.0; - double J1 = 1.0; - double J2 = 1.0; - std::string integration_type = "rk4"; - - std::unique_ptr system = std::make_unique( - timestep, l1, l2, m1, m2, J1, J2, integration_type); - - // Cost matrices - Eigen::MatrixXd Q = 10.0 * Eigen::MatrixXd::Identity(state_dim, state_dim); - Eigen::MatrixXd R = 1e-2 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = 100.0 * Q; - - // Goal state - Eigen::VectorXd goal_state(state_dim); - goal_state << M_PI/2.0, 0.0, 0.0, 0.0; - - std::vector empty_reference_states; - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << -M_PI/2.0, 0.0, 0.0, 0.0; - - // Create objective - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Control constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -15.0; - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 15.0; - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 200; - options.tolerance = 1e-3; - options.regularization.initial_value = 1e-4; - options.use_ilqr = true; - options.enable_parallel = true; - options.num_threads = 10; - options.debug = false; - options.ipddp.barrier.mu_initial = 1e-1; - - // Create CDDP solver - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Add control constraint - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // Initial trajectory - std::vector X_init(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U_init(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Rollout initial trajectory - X_init[0] = initial_state; - auto acrobot = std::make_unique(timestep, l1, l2, m1, m2, J1, J2, integration_type); - for (int t = 0; t < horizon; ++t) { - X_init[t + 1] = acrobot->getDiscreteDynamics(X_init[t], U_init[t], t * timestep); - } - - cddp_solver.setInitialTrajectory(X_init, U_init); - - // Solve - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Create plot directory - const std::string plotDirectory = "../results/acrobot"; - cddp::example::ensurePlotDir(plotDirectory); - - // Extract solution data for animation - const auto& time_arr = t_sol; - auto theta1_arr = cddp::example::extractComponent(X_sol, 0); - auto theta2_arr = cddp::example::extractComponent(X_sol, 1); - - // --- Animation --- - auto fig = figure(); - auto ax = fig->current_axes(); - fig->size(800, 800); - - // Generate animation frames - for (size_t i = 0; i < X_sol.size(); i += 5) { - cla(ax); - hold(ax, true); - - // Current state - double theta1 = theta1_arr[i]; - double theta2 = theta2_arr[i]; - - // Link 1 endpoint - double x1 = l1 * std::sin(theta1); - double y1 = -l1 * std::cos(theta1); - - // Link 2 endpoint (relative to link 1) - double x2 = x1 + l2 * std::sin(theta1 + theta2); - double y2 = y1 - l2 * std::cos(theta1 + theta2); - - // Plot link 1 - std::vector link1_x = {0.0, x1}; - std::vector link1_y = {0.0, y1}; - auto link1 = plot(link1_x, link1_y); - link1->line_style("b-"); - link1->line_width(5); - - // Plot link 2 - std::vector link2_x = {x1, x2}; - std::vector link2_y = {y1, y2}; - auto link2 = plot(link2_x, link2_y); - link2->line_style("r-"); - link2->line_width(5); - - // Plot joints as circles - std::vector joint0_x = {0.0}; - std::vector joint0_y = {0.0}; - auto j0 = scatter(joint0_x, joint0_y); - j0->marker_size(10); - j0->marker_color("black"); - j0->marker_style("o"); - - std::vector joint1_x = {x1}; - std::vector joint1_y = {y1}; - auto j1 = scatter(joint1_x, joint1_y); - j1->marker_size(8); - j1->marker_color("gray"); - j1->marker_style("o"); - - std::vector joint2_x = {x2}; - std::vector joint2_y = {y2}; - auto j2 = scatter(joint2_x, joint2_y); - j2->marker_size(6); - j2->marker_color("red"); - j2->marker_style("o"); - - // Set axis properties - xlim({-2.5, 2.5}); - ylim({-2.5, 2.5}); - xlabel("x [m]"); - ylabel("y [m]"); - title("Acrobot Animation - Time: " + std::to_string(time_arr[i]) + " s"); - grid(true); - - // Save frame - std::string filename = plotDirectory + "/frame_" + std::to_string(i/5) + ".png"; - fig->save(filename); - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool - std::string command = "convert -delay 30 " + plotDirectory + "/frame_*.png " + plotDirectory + "/acrobot.gif"; - std::system(command.c_str()); - - // Clean up frame files - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as " << plotDirectory << "/acrobot.gif" << std::endl; - - // Print final state - std::cout << "\nFinal state:" << std::endl; - std::cout << "θ₁ = " << X_sol.back()(0) << " rad" << std::endl; - std::cout << "θ₂ = " << X_sol.back()(1) << " rad" << std::endl; - std::cout << "θ̇₁ = " << X_sol.back()(2) << " rad/s" << std::endl; - std::cout << "θ̇₂ = " << X_sol.back()(3) << " rad/s" << std::endl; - - return 0; -} \ No newline at end of file diff --git a/examples/cddp_bicycle.cpp b/examples/cddp_bicycle.cpp deleted file mode 100644 index 5d2c6a59..00000000 --- a/examples/cddp_bicycle.cpp +++ /dev/null @@ -1,232 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -int main() -{ - // Problem parameters - int state_dim = 4; // [x, y, theta, v] - int control_dim = 2; // [acceleration, steering_angle] - int horizon = 100; - double timestep = 0.05; - std::string integration_type = "euler"; - - // Create a bicycle instance - double wheelbase = 1.5; // wheelbase length in meters - std::unique_ptr system = std::make_unique(timestep, wheelbase, integration_type); - - // Create objective function - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 50.0, 0.0, 0.0, 0.0, - 0.0, 50.0, 0.0, 0.0, - 0.0, 0.0, 10.0, 0.0, - 0.0, 0.0, 0.0, 10.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 5.0, 5.0, M_PI / 2.0, 0.0; - - std::vector empty_reference_states; - auto objective = std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI / 4.0, 0.0; - - // Set solver options - cddp::CDDPOptions options; - options.max_iterations = 20; - - // Create CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Define and add control constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -10.0, -M_PI / 5; - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 10.0, M_PI / 5; - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); - auto constraint = cddp_solver.getConstraint("ControlConstraint"); - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - - // Extract solution - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void) std::system("mkdir -p frames"); - - // Extract trajectory data - auto x_arr = cddp::example::extractComponent(X_sol, 0); - auto y_arr = cddp::example::extractComponent(X_sol, 1); - auto theta_arr = cddp::example::extractComponent(X_sol, 2); - auto v_arr = cddp::example::extractComponent(X_sol, 3); - - // Extract control inputs - auto acc_arr = cddp::example::extractComponent(U_sol, 0); - auto steering_arr = cddp::example::extractComponent(U_sol, 1); - - // ----------------------------- - // Plot states and controls - // ----------------------------- - auto f1 = figure(); - f1->size(1200, 800); - - // First subplot: Position Trajectory - auto ax1 = subplot(2, 2, 0); - auto plot_handle = plot(ax1, x_arr, y_arr, "-b"); - plot_handle->line_width(3); - title(ax1, "Position Trajectory"); - xlabel(ax1, "x [m]"); - ylabel(ax1, "y [m]"); - - // Second subplot: Heading Angle vs Time - auto ax2 = subplot(2, 2, 1); - auto heading_plot_handle = plot(ax2, t_sol, theta_arr); - heading_plot_handle->line_width(3); - title(ax2, "Heading Angle"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "theta [rad]"); - - // Third subplot: Velocity vs Time - auto ax3 = subplot(2, 2, 2); - auto velocity_plot_handle = plot(ax3, t_sol, v_arr); - velocity_plot_handle->line_width(3); - title(ax3, "Velocity"); - xlabel(ax3, "Time [s]"); - ylabel(ax3, "v [m/s]"); - - // Fourth subplot: Control Inputs - auto ax4 = subplot(2, 2, 3); - auto p1 = plot(ax4, acc_arr, "--b"); - p1->line_width(3); - p1->display_name("Acceleration"); - - hold(ax4, true); - auto p2 = plot(ax4, steering_arr, "--r"); - p2->line_width(3); - p2->display_name("Steering"); - - title(ax4, "Control Inputs"); - xlabel(ax4, "Step"); - ylabel(ax4, "Control"); - matplot::legend(ax4); - - f1->draw(); - f1->save(plotDirectory + "/bicycle_cddp_results.png"); - - // ----------------------------- - // Animation: Bicycle Trajectory - // ----------------------------- - auto f2 = figure(); - f2->size(800, 600); - auto ax_anim = f2->current_axes(); - if (!ax_anim) - { - ax_anim = axes(); - } - - double car_length = 0.35; - double car_width = 0.15; - - for (size_t i = 0; i < X_sol.size(); ++i) - { - if (i % 10 == 0) - { - ax_anim->clear(); - hold(ax_anim, true); - - double x = x_arr[i]; - double y = y_arr[i]; - double theta = theta_arr[i]; - - // Compute bicycle rectangle corners - std::vector car_x(5), car_y(5); - car_x[0] = x + car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[0] = y + car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[1] = x + car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[1] = y + car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[2] = x - car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[2] = y - car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[3] = x - car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[3] = y - car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - auto car_line = plot(ax_anim, car_x, car_y); - car_line->color("black"); - car_line->line_style("solid"); - car_line->line_width(2); - car_line->display_name("Car"); - - // Plot the front wheel (steerable) - double wheel_length = car_width * 0.8; - double steering_angle = U_sol[std::min(i, U_sol.size() - 1)](1); - std::vector front_wheel_x = { - x + car_length / 2 * cos(theta), - x + car_length / 2 * cos(theta) + wheel_length * cos(theta + steering_angle)}; - std::vector front_wheel_y = { - y + car_length / 2 * sin(theta), - y + car_length / 2 * sin(theta) + wheel_length * sin(theta + steering_angle)}; - auto front_wheel_line = plot(ax_anim, front_wheel_x, front_wheel_y); - front_wheel_line->color("red"); - front_wheel_line->line_style("solid"); - front_wheel_line->line_width(2); - front_wheel_line->display_name(""); - - // Plot trajectory up to current frame - std::vector traj_x(x_arr.begin(), x_arr.begin() + i + 1); - std::vector traj_y(y_arr.begin(), y_arr.begin() + i + 1); - auto traj_line = plot(ax_anim, traj_x, traj_y); - traj_line->color("blue"); - traj_line->line_style("solid"); - traj_line->line_width(1.5); - traj_line->display_name("Trajectory"); - - title(ax_anim, "Bicycle Trajectory"); - xlabel(ax_anim, "x [m]"); - ylabel(ax_anim, "y [m]"); - xlim(ax_anim, {-1, 6}); - ylim(ax_anim, {-1, 6}); - // legend(ax_anim); - - std::string filename = plotDirectory + "/bicycle_frame_" + std::to_string(i) + ".png"; - f2->draw(); - f2->save(filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/bicycle_frame_*.png " + plotDirectory + "/bicycle.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/bicycle_frame_*.png"; - std::system(cleanup_command.c_str()); - - return 0; -} diff --git a/examples/cddp_car.cpp b/examples/cddp_car.cpp deleted file mode 100644 index 05b7151a..00000000 --- a/examples/cddp_car.cpp +++ /dev/null @@ -1,329 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -namespace cddp -{ - - class CarParkingObjective : public NonlinearObjective - { - public: - CarParkingObjective(const Eigen::VectorXd &goal_state, double timestep) - : NonlinearObjective(timestep), reference_state_(goal_state) - { - // Control cost coefficients: cu = 1e-2*[1 .01] - cu_ = Eigen::Vector2d(1e-2, 1e-4); - - // Final cost coefficients: cf = [.1 .1 1 .3] - cf_ = Eigen::Vector4d(0.1, 0.1, 1.0, 0.3); - - // Smoothness scales for final cost: pf = [.01 .01 .01 1] - pf_ = Eigen::Vector4d(0.01, 0.01, 0.01, 1.0); - - // Running cost coefficients: cx = 1e-3*[1 1] - cx_ = Eigen::Vector2d(1e-3, 1e-3); - - // Smoothness scales for running cost: px = [.1 .1] - px_ = Eigen::Vector2d(0.1, 0.1); - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int index) const override - { - // Control cost: lu = cu*u.^2 - double lu = cu_.dot(control.array().square().matrix()); - - // Running cost on distance from origin: lx = cx*sabs(x(1:2,:),px) - Eigen::VectorXd xy_state = state.head(2); - double lx = cx_.dot(sabs(xy_state, px_)); - - return lu + lx; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - // Final state cost: llf = cf*sabs(x(:,final),pf); - return cf_.dot(sabs(final_state, pf_)) + running_cost(final_state, Eigen::VectorXd::Zero(2), 0); - } - - private: - // Helper function for smooth absolute value (pseudo-Huber) - Eigen::VectorXd sabs(const Eigen::VectorXd &x, const Eigen::VectorXd &p) const - { - return ((x.array().square() / p.array().square() + 1.0).sqrt() * p.array() - p.array()).matrix(); - } - - Eigen::VectorXd reference_state_; - Eigen::Vector2d cu_; // Control cost coefficients - Eigen::Vector4d cf_; // Final cost coefficients - Eigen::Vector4d pf_; // Smoothness scales for final cost - Eigen::Vector2d cx_; // Running cost coefficients - Eigen::Vector2d px_; // Smoothness scales for running cost - }; -} // namespace cddp - -void plotCarBox(const Eigen::VectorXd &state, const Eigen::VectorXd &control, - double length, double width, const std::string &color, - axes_handle ax) -{ - double x = state(0); - double y = state(1); - double theta = state(2); - double steering = control(1); - - // Compute the car's four corners (and close the polygon) - std::vector car_x(5), car_y(5); - - // Front right - car_x[0] = x + length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[0] = y + length / 2 * sin(theta) + width / 2 * cos(theta); - - // Front left - car_x[1] = x + length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[1] = y + length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear left - car_x[2] = x - length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[2] = y - length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear right - car_x[3] = x - length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[3] = y - length / 2 * sin(theta) + width / 2 * cos(theta); - - // Close polygon - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - // Plot car body as a polygon line. - plot(ax, car_x, car_y, color + "-"); - - // Plot base point (center of rear axle) as a red circle. - plot(ax, std::vector{x}, std::vector{y}, "ro"); - - // Compute steering direction - double front_x = x + length / 2 * cos(theta); - double front_y = y + length / 2 * sin(theta); - double steering_length = width / 2; - double steering_angle = theta + steering; - double steering_end_x = front_x + steering_length * cos(steering_angle); - double steering_end_y = front_y + steering_length * sin(steering_angle); - - std::vector steer_x = {front_x, steering_end_x}; - std::vector steer_y = {front_y, steering_end_y}; - plot(ax, steer_x, steer_y, "g-"); -} - -int main() -{ - // Problem parameters - int state_dim = 4; // [x y theta v] - int control_dim = 2; // [wheel_angle acceleration] - int horizon = 500; - double timestep = 0.03; - std::string integration_type = "euler"; - - // Random number generator setup - std::random_device rd; - std::mt19937 gen(rd()); - std::normal_distribution d(0.0, 0.1); - - // Create car instance - double wheelbase = 2.0; - - // Initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << 1.0, 1.0, 1.5 * M_PI, 0.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, 0.0, 0.0; // NOT USED IN THIS EXAMPLE - - // Control constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -0.5, -2.0; // [steering_angle, acceleration] - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 0.5, 2.0; - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 500; - options.verbose = true; - options.tolerance = 1e-7; - options.acceptable_tolerance = 1e-4; - options.regularization.initial_value = 1e-7; - options.debug = false; - options.enable_parallel = true; - options.num_threads = 10; - - // Create CDDP solver with new API - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, wheelbase, integration_type), - std::make_unique(goal_state, timestep), - options - ); - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique( - control_lower_bound, control_upper_bound)); - - // Initialize with random controls - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Random initialization - for (auto &u : U) - { - // u(0) = d(gen); // Random steering - // u(1) = d(gen); // Random acceleration - u(0) = 0.01; - u(1) = 0.01; - } - - X[0] = initial_state; - - double J = 0.0; - - // Simulate initial trajectory - for (size_t t = 0; t < horizon; t++) - { - J += cddp_solver.getObjective().running_cost(X[t], U[t], t); - X[t + 1] = cddp_solver.getSystem().getDiscreteDynamics(X[t], U[t], t * timestep); - } - J += cddp_solver.getObjective().terminal_cost(X.back()); - std::cout << "Initial cost: " << J << std::endl; - std::cout << "Initial state: " << X[0].transpose() << std::endl; - std::cout << "Final state: " << X.back().transpose() << std::endl; - - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - // ======================================== - // CDDP Solution - // ======================================== - // Converged: Yes - // Iterations: 157 - // Solve Time: 5.507e+05 micro sec - // Final Cost: 1.90517 - // ======================================== - // cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::LogDDP); - // ======================================== - // CDDP Solution - // ======================================== - // Converged: Yes - // Iterations: 153 - // Solve Time: 5.441e+05 micro sec - // Final Cost: 1.90517 - // ======================================== - // ======================================== - // CDDP Solution - // ======================================== - // Converged: No - // Iterations: 53 - // Solve Time: 1.1538e+06 micro sec - // Final Cost: 1.910013e+00 - // ======================================== - - // Extract solution trajectories - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Prepare trajectory data - auto x_hist = cddp::example::extractComponent(X_sol, 0); - auto y_hist = cddp::example::extractComponent(X_sol, 1); - - // Car dimensions. - double car_length = 2.1; - double car_width = 0.9; - - // Create a figure and get current axes. - auto fig = figure(true); - auto ax = fig->current_axes(); - - Eigen::VectorXd empty_control = Eigen::VectorXd::Zero(2); - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void) std::system("mkdir -p frames"); - - // Animation loop: update plot for each time step and save frame. - for (size_t i = 0; i < X_sol.size(); ++i) - { - // Skip every 10th frame for smoother animation. - if (i % 10 == 0) - { - // Clear previous content. - cla(ax); - hold(ax, true); - - // Plot the full trajectory. - plot(ax, x_hist, y_hist, "b-"); - - // Plot goal configuration. - plotCarBox(goal_state, empty_control, car_length, car_width, "r", ax); - - // Plot current car state. - if (i < U_sol.size()) - plotCarBox(X_sol[i], U_sol[i], car_length, car_width, "k", ax); - else - plotCarBox(X_sol[i], empty_control, car_length, car_width, "k", ax); - - // Set grid and axis limits. - grid(ax, true); - xlim(ax, {-4, 4}); - ylim(ax, {-4, 4}); - - // Update drawing. - fig->draw(); - - // Save the frame to a PNG file. - std::string frame_filename = plotDirectory + "/frame_" + std::to_string(i) + ".png"; - fig->save(frame_filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 15 " + plotDirectory + "/frame_*.png " + plotDirectory + "/car_parking.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as car_parking.gif" << std::endl; - - return 0; -} - -// convert -delay 3 ../results/frames/frame_*.png ../results/animations/car_parking.gif diff --git a/examples/cddp_car_ipddp.cpp b/examples/cddp_car_ipddp.cpp deleted file mode 100644 index 044cbef5..00000000 --- a/examples/cddp_car_ipddp.cpp +++ /dev/null @@ -1,279 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -namespace cddp -{ - - class CarParkingObjective : public NonlinearObjective - { - public: - CarParkingObjective(const Eigen::VectorXd &goal_state, double timestep) - : NonlinearObjective(timestep), reference_state_(goal_state) - { - // Control cost coefficients: cu = 1e-2*[1 .01] - cu_ = Eigen::Vector2d(1e-2, 1e-4); - - // Final cost coefficients: cf = [.1 .1 1 .3] - cf_ = Eigen::Vector4d(0.1, 0.1, 1.0, 0.3); - - // Smoothness scales for final cost: pf = [.01 .01 .01 1] - pf_ = Eigen::Vector4d(0.01, 0.01, 0.01, 1.0); - - // Running cost coefficients: cx = 1e-3*[1 1] - cx_ = Eigen::Vector2d(1e-3, 1e-3); - - // Smoothness scales for running cost: px = [.1 .1] - px_ = Eigen::Vector2d(0.1, 0.1); - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int index) const override - { - // Control cost: lu = cu*u.^2 - double lu = cu_.dot(control.array().square().matrix()); - - // Running cost on distance from origin: lx = cx*sabs(x(1:2,:),px) - Eigen::VectorXd xy_state = state.head(2); - double lx = cx_.dot(sabs(xy_state, px_)); - - return lu + lx; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - // Final state cost: llf = cf*sabs(x(:,final),pf); - return cf_.dot(sabs(final_state, pf_)) + running_cost(final_state, Eigen::VectorXd::Zero(2), 0); - } - - private: - // Helper function for smooth absolute value (pseudo-Huber) - Eigen::VectorXd sabs(const Eigen::VectorXd &x, const Eigen::VectorXd &p) const - { - return ((x.array().square() / p.array().square() + 1.0).sqrt() * p.array() - p.array()).matrix(); - } - - Eigen::VectorXd reference_state_; - Eigen::Vector2d cu_; // Control cost coefficients - Eigen::Vector4d cf_; // Final cost coefficients - Eigen::Vector4d pf_; // Smoothness scales for final cost - Eigen::Vector2d cx_; // Running cost coefficients - Eigen::Vector2d px_; // Smoothness scales for running cost - }; -} // namespace cddp - -void plotCarBox(const Eigen::VectorXd &state, const Eigen::VectorXd &control, - double length, double width, const std::string &color, - axes_handle ax) -{ - double x = state(0); - double y = state(1); - double theta = state(2); - double steering = control(1); - - // Compute the car's four corners (and close the polygon) - std::vector car_x(5), car_y(5); - - // Front right - car_x[0] = x + length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[0] = y + length / 2 * sin(theta) + width / 2 * cos(theta); - - // Front left - car_x[1] = x + length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[1] = y + length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear left - car_x[2] = x - length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[2] = y - length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear right - car_x[3] = x - length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[3] = y - length / 2 * sin(theta) + width / 2 * cos(theta); - - // Close polygon - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - // Plot car body as a polygon line. - plot(ax, car_x, car_y, color + "-"); - - // Plot base point (center of rear axle) as a red circle. - plot(ax, std::vector{x}, std::vector{y}, "ro"); - - // Compute steering direction - double front_x = x + length / 2 * cos(theta); - double front_y = y + length / 2 * sin(theta); - double steering_length = width / 2; - double steering_angle = theta + steering; - double steering_end_x = front_x + steering_length * cos(steering_angle); - double steering_end_y = front_y + steering_length * sin(steering_angle); - - std::vector steer_x = {front_x, steering_end_x}; - std::vector steer_y = {front_y, steering_end_y}; - plot(ax, steer_x, steer_y, "g-"); -} - - -int main() { - // Problem parameters - const int state_dim = 4; // [x, y, theta, v] - const int control_dim = 2; // [wheel_angle, acceleration] - const int horizon = 500; - const double timestep = 0.03; - const std::string integration_type = "euler"; - - // Create a Car instance with given parameters - double wheelbase = 2.0; - std::unique_ptr system = - std::make_unique(timestep, wheelbase, integration_type); - - // Define initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << 1.0, 1.0, 1.5 * M_PI, 0.0; - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, 0.0, 0.0; // Desired parking state - - // Create the nonlinear objective for car parking - auto objective = std::make_unique(goal_state, timestep); - - // Set solver options - cddp::CDDPOptions options; - options.max_iterations = 600; - options.verbose = true; - options.tolerance = 1e-7; - options.acceptable_tolerance = 1e-4; - options.regularization.initial_value = 1e-7; - options.debug = false; - options.use_ilqr = true; - options.enable_parallel = false; - options.num_threads = 1; - options.msipddp.barrier.mu_initial = 1e-0; - options.msipddp.dual_var_init_scale = 1e-1; - options.msipddp.slack_var_init_scale = 1e-2; - options.msipddp.segment_length = horizon / 100; - options.msipddp.rollout_type = "nonlinear"; - - // Create CDDP solver for the car model with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Define control constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -0.5, -2.0; // [steering_angle, acceleration] - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 0.5, 2.0; - cddp_solver.addPathConstraint("ControlConstraint", std::make_unique(-control_upper_bound, control_upper_bound)); - - // Initialize the trajectory with zero controls - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - for (int i = 0; i < horizon; ++i) { - U[i](0) = 0.01; - U[i](1) = 0.01; - X[i + 1] = cddp_solver.getSystem().getDiscreteDynamics(X[i], U[i], i * timestep); - } - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem using MSIPDDP - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::MSIPDDP); - - // Extract solution trajectories - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Prepare trajectory data for plotting - auto x_hist = cddp::example::extractComponent(X_sol, 0); - auto y_hist = cddp::example::extractComponent(X_sol, 1); - // Car dimensions. - double car_length = 2.1; - double car_width = 0.9; - - // Create a figure and get current axes. - auto fig = figure(true); - auto ax = fig->current_axes(); - - Eigen::VectorXd empty_control = Eigen::VectorXd::Zero(2); - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void) std::system("mkdir -p frames"); - - // Animation loop: update plot for each time step and save frame. - for (size_t i = 0; i < X_sol.size(); ++i) - { - // Skip every 10th frame for smoother animation. - if (i % 10 == 0) - { - // Clear previous content. - cla(ax); - hold(ax, true); - - // Plot the full trajectory. - plot(ax, x_hist, y_hist, "b-"); - - // Plot goal configuration. - plotCarBox(goal_state, empty_control, car_length, car_width, "r", ax); - - // Plot current car state. - if (i < U_sol.size()) - plotCarBox(X_sol[i], U_sol[i], car_length, car_width, "k", ax); - else - plotCarBox(X_sol[i], empty_control, car_length, car_width, "k", ax); - - // Set grid and axis limits. - grid(ax, true); - xlim(ax, {-4, 4}); - ylim(ax, {-4, 4}); - - // Update drawing. - fig->draw(); - - // Save the frame to a PNG file. - std::string frame_filename = plotDirectory + "/frame_" + std::to_string(i) + ".png"; - fig->save(frame_filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 15 " + plotDirectory + "/frame_*.png " + plotDirectory + "/car_parking_ipddp.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as car_parking_ipddp.gif" << std::endl; - - return 0; -} diff --git a/examples/cddp_cartpole.cpp b/examples/cddp_cartpole.cpp index b459fccb..aca6b3f4 100644 --- a/examples/cddp_cartpole.cpp +++ b/examples/cddp_cartpole.cpp @@ -13,231 +13,68 @@ See the License for the specific language governing permissions and limitations under the License. */ + #include #include -#include -#include -#include -#include + #include "cddp.hpp" #include "cddp_example_utils.hpp" -#include "matplot/matplot.h" -#include - -using namespace matplot; -namespace fs = std::filesystem; int main() { - int state_dim = 4; - int control_dim = 1; - int horizon = 100; - double timestep = 0.05; + constexpr double kPi = 3.14159265358979323846; + constexpr int state_dim = 4; + constexpr int control_dim = 1; + constexpr int horizon = 100; + constexpr double timestep = 0.05; - // Create a CartPole instance with custom parameters. - double cart_mass = 1.0; - double pole_mass = 0.2; - double pole_length = 0.5; - double gravity = 9.81; - double damping = 0.0; // TODO: Implement damping term. - std::string integration_type = "rk4"; + Eigen::VectorXd initial_state(state_dim); + initial_state << 0.0, 0.0, 0.0, 0.0; - std::unique_ptr system = std::make_unique( - timestep, integration_type, cart_mass, pole_mass, pole_length, gravity, damping); + Eigen::VectorXd goal_state(state_dim); + goal_state << 0.0, kPi, 0.0, 0.0; - // Cost matrices. Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); Eigen::MatrixXd R = 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf(0,0) = 100.0; // Final cart position cost. - Qf(1,1) = 100.0; // Final cart velocity cost. - Qf(2,2) = 100.0; // Final pole angle cost. - Qf(3,3) = 100.0; // Final pole angular velocity cost. - - // Goal state: cart at origin, pole upright, zero velocities. - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state << 0.0, M_PI, 0.0, 0.0; - - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state (cart at rest, pole hanging down). - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, 0.0, 0.0; + Eigen::MatrixXd Qf = 100.0 * Eigen::MatrixXd::Identity(state_dim, state_dim); - // Solver options. cddp::CDDPOptions options; - options.max_iterations = 500; - options.tolerance = 1e-7; - options.acceptable_tolerance = 1e-6; + options.max_iterations = 80; + options.tolerance = 1e-6; + options.acceptable_tolerance = 1e-5; options.regularization.initial_value = 1e-5; - options.use_ilqr = true; - options.enable_parallel = true; - options.num_threads = 12; - options.debug = false; - options.ipddp.barrier.mu_initial = 1e-1; - options.msipddp.segment_length = horizon; - options.msipddp.rollout_type = "nonlinear"; - options.ipddp.barrier.mu_update_factor = 0.2; - options.ipddp.barrier.mu_update_power = 1.2; - - // Create CDDP solver with new API. - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Control constraints. - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -5.0; // Maximum negative force. - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 5.0; // Maximum positive force. - - // FIXME: For MSIPDDP - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // FIXME: For CLDDP - // cddp_solver.addPathConstraint("ControlConstraint", - // std::make_unique( control_lower_bound, control_upper_bound)); - - // Initial trajectory. - auto [X, U] = cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); - cddp_solver.setInitialTrajectory(X, U); - - // Solve. - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Create plot directory. - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void) std::system("mkdir -p frames"); - - // Extract solution data. - auto x_arr = cddp::example::extractComponent(X_sol, 0); - auto theta_arr = cddp::example::extractComponent(X_sol, 1); - auto x_dot_arr = cddp::example::extractComponent(X_sol, 2); - auto theta_dot_arr = cddp::example::extractComponent(X_sol, 3); - auto force_arr = cddp::example::extractComponent(U_sol, 0); - const auto& time_arr = t_sol; - std::vector time_arr2(t_sol.begin(), t_sol.begin() + U_sol.size()); - - // --- Plot static results (2x2 plots for state trajectories) --- - auto fig1 = figure(); - fig1->size(1200, 800); - auto ax1 = subplot(2, 2, 1); - title(ax1, "Cart Position"); - plot(ax1, time_arr, x_arr)->line_style("b-"); - xlabel(ax1, "Time [s]"); - ylabel(ax1, "Position [m]"); - grid(ax1, true); - - auto ax2 = subplot(2, 2, 2); - title(ax2, "Cart Velocity"); - plot(ax2, time_arr, x_dot_arr)->line_style("b-"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "Velocity [m/s]"); - grid(ax2, true); - - auto ax3 = subplot(2, 2, 3); - title(ax3, "Pole Angle"); - plot(ax3, time_arr, theta_arr)->line_style("b-"); - xlabel(ax3, "Time [s]"); - ylabel(ax3, "Angle [rad]"); - grid(ax3, true); - - auto ax4 = subplot(2, 2, 4); - title(ax4, "Pole Angular Velocity"); - plot(ax4, time_arr, theta_dot_arr)->line_style("b-"); - xlabel(ax4, "Time [s]"); - ylabel(ax4, "Angular Velocity [rad/s]"); - grid(ax4, true); - - fig1->save(plotDirectory + "/cartpole_results.png"); - - // --- Plot control inputs --- - auto fig2 = figure(); - fig2->size(800, 600); - title("Control Inputs"); - plot(time_arr2, force_arr)->line_style("b-"); - xlabel("Time [s]"); - ylabel("Force [N]"); - grid(true); - fig2->save(plotDirectory + "/cartpole_control_inputs.png"); - - // --- Animation --- - auto fig3 = figure(); - auto ax_fig3 = fig3->current_axes(); - fig3->size(800, 600); - title("CartPole Animation"); - xlabel("x"); - ylabel("y"); - - double cart_width = 0.3; - double cart_height = 0.2; - double pole_width = 0.05; - - // Loop over the solution states to generate animation frames. - for (size_t i = 0; i < X_sol.size(); ++i) { - if (i % 5 == 0) { - // Clear previous content. - cla(ax_fig3); - hold(ax_fig3, true); - - // Current state. - double x = x_arr[i]; - double theta = theta_arr[i]; - - // Plot the cart as a rectangle centered at (x, 0). - std::vector cart_x = { x - cart_width/2, x + cart_width/2, - x + cart_width/2, x - cart_width/2, - x - cart_width/2 }; - std::vector cart_y = { -cart_height/2, -cart_height/2, - cart_height/2, cart_height/2, - -cart_height/2 }; - plot(cart_x, cart_y)->line_style("k-"); - - // Plot the pole as a line from the top center of the cart. - double pole_end_x = x + pole_length * std::sin(theta); - double pole_end_y = cart_height/2 - pole_length * std::cos(theta); - std::vector pole_x = { x, pole_end_x }; - std::vector pole_y = { cart_height/2, pole_end_y }; - plot(pole_x, pole_y)->line_style("b-"); - - // Plot the pole bob as a circle. - std::vector circle_x, circle_y; - int num_points = 20; - for (int j = 0; j <= num_points; ++j) { - double t = 2 * M_PI * j / num_points; - circle_x.push_back(pole_end_x + pole_width * std::cos(t)); - circle_y.push_back(pole_end_y + pole_width * std::sin(t)); - } - plot(circle_x, circle_y)->line_style("b-"); - - // Set fixed axis limits for stable animation. - xlim({-2.0, 2.0}); - ylim({-1.5, 1.5}); - - // Save the frame. - std::string filename = plotDirectory + "/frame_" + std::to_string(i) + ".png"; - fig3->save(filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } + cddp::CDDP solver( + initial_state, + goal_state, + horizon, + timestep, + std::make_unique( + timestep, "rk4", 1.0, 0.2, 0.5, 9.81, 0.0), + std::make_unique( + Q, R, Qf, goal_state, std::vector{}, timestep), + options); + + Eigen::VectorXd lower(control_dim); + lower << -5.0; + Eigen::VectorXd upper(control_dim); + upper << 5.0; + solver.addPathConstraint("ControlConstraint", + std::make_unique(lower, upper)); + + auto [X, U] = + cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); + solver.setInitialTrajectory(X, U); + + const cddp::CDDPSolution solution = solver.solve(cddp::SolverType::IPDDP); + if (solution.state_trajectory.empty()) { + std::cerr << "Cart-pole example failed: empty trajectory" << std::endl; + return 1; } - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 30 " + plotDirectory + "/frame_*.png " + plotDirectory + "/cartpole.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as cartpole.gif" << std::endl; - - + const Eigen::VectorXd final_error = solution.state_trajectory.back() - goal_state; + std::cout << "Cart-pole example completed with status: " + << solution.status_message << '\n' + << "Final objective: " << solution.final_objective << '\n' + << "Final state error norm: " << final_error.norm() << std::endl; return 0; } diff --git a/examples/cddp_forklift_ipddp.cpp b/examples/cddp_forklift_ipddp.cpp deleted file mode 100644 index 17040836..00000000 --- a/examples/cddp_forklift_ipddp.cpp +++ /dev/null @@ -1,335 +0,0 @@ -/* - Copyright 2025 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "dynamics_model/forklift.hpp" -#include "matplot/matplot.h" -#include - -using namespace matplot; -namespace fs = std::filesystem; - -namespace cddp -{ - - class ForkliftParkingObjective : public NonlinearObjective - { - public: - ForkliftParkingObjective(const Eigen::VectorXd &goal_state, double timestep, int horizon) - : NonlinearObjective(timestep), reference_state_(goal_state), horizon_(horizon) - { - // Control cost coefficients - // R matrix: cu = [acceleration, steering_rate] - cu_ = Eigen::Vector2d(1.8, 11.0); - // Terminal cost coefficients: Qf = [x, y, theta, v, delta] - cf_ = Eigen::VectorXd(5); - cf_ << 1000.0, 1000.0, 5000.0, 16.0, 100.0; // From README Table 4 - - // Stage cost coefficients: Q = [x, y, theta, v, delta] - cx_full_ = Eigen::VectorXd(5); - cx_full_ << 1.0, 1.0, 10.0, 4.0, 6.0; // From README Table 4 - - // Time penalty weight - time_weight_ = 0.05; // From README - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int index) const override - { - // Control cost: 0.5 * u^T * R * u - double lu = 0.5 * cu_.dot(control.array().square().matrix()); - - // State cost: 0.5 * (x - x_tar)^T * Q * (x - x_tar) - Eigen::VectorXd state_error = state - reference_state_; - double lx = 0.5 * cx_full_.dot(state_error.array().square().matrix()); - - return lu + lx; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - // Terminal cost: 0.5 * (x - x_tar)^T * Qf * (x - x_tar) - Eigen::VectorXd state_error = final_state - reference_state_; - double terminal_cost = 0.5 * cf_.dot(state_error.array().square().matrix()); - - // Add time penalty: w_T * T (simplified as constant per timestep) - double time_cost = time_weight_ * horizon_ * timestep_; - - return terminal_cost + time_cost; - } - - private: - Eigen::VectorXd reference_state_; - Eigen::Vector2d cu_; // Control cost coefficients (R matrix) - Eigen::VectorXd cf_; // Terminal cost coefficients (Qf matrix) - Eigen::VectorXd cx_full_; // Stage cost coefficients (Q matrix) - double time_weight_; // Time penalty weight - int horizon_; // Total horizon length - }; -} // namespace cddp - -void plotForkliftBox(const Eigen::VectorXd &state, const Eigen::VectorXd &control, - double length, double width, bool rear_steer, - const std::string &color, axes_handle ax) -{ - double x = state(0); - double y = state(1); - double theta = state(2); - double steering = state(4); // Steering angle is now a state - - // Compute the forklift's four corners - std::vector forklift_x(5), forklift_y(5); - - // Front right - forklift_x[0] = x + length / 2 * cos(theta) - width / 2 * sin(theta); - forklift_y[0] = y + length / 2 * sin(theta) + width / 2 * cos(theta); - - // Front left - forklift_x[1] = x + length / 2 * cos(theta) + width / 2 * sin(theta); - forklift_y[1] = y + length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear left - forklift_x[2] = x - length / 2 * cos(theta) + width / 2 * sin(theta); - forklift_y[2] = y - length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear right - forklift_x[3] = x - length / 2 * cos(theta) - width / 2 * sin(theta); - forklift_y[3] = y - length / 2 * sin(theta) + width / 2 * cos(theta); - - // Close polygon - forklift_x[4] = forklift_x[0]; - forklift_y[4] = forklift_y[0]; - - // Plot forklift body as a polygon line - plot(ax, forklift_x, forklift_y, color + "-"); - - // Plot base point (center of rear axle) as a red circle - plot(ax, std::vector{x}, std::vector{y}, "ro"); - - // Plot fork position (front of forklift) - double fork_length = width * 0.8; - double fork_x_start = x + length / 2 * cos(theta); - double fork_y_start = y + length / 2 * sin(theta); - double fork_x_end = fork_x_start + fork_length * cos(theta); - double fork_y_end = fork_y_start + fork_length * sin(theta); - - plot(ax, std::vector{fork_x_start, fork_x_end}, - std::vector{fork_y_start, fork_y_end}, "m-"); - - // Plot steering direction - if (rear_steer) { - // For rear-steer, show steering at rear axle - double rear_x = x - length / 2 * cos(theta); - double rear_y = y - length / 2 * sin(theta); - double steering_length = width / 2; - double steering_angle = theta - steering; // Rear steer is opposite - double steering_end_x = rear_x + steering_length * cos(steering_angle); - double steering_end_y = rear_y + steering_length * sin(steering_angle); - - plot(ax, std::vector{rear_x, steering_end_x}, - std::vector{rear_y, steering_end_y}, "g-"); - } else { - // For front-steer, show steering at front axle - double front_x = x + length / 2 * cos(theta); - double front_y = y + length / 2 * sin(theta); - double steering_length = width / 2; - double steering_angle = theta + steering; - double steering_end_x = front_x + steering_length * cos(steering_angle); - double steering_end_y = front_y + steering_length * sin(steering_angle); - - plot(ax, std::vector{front_x, steering_end_x}, - std::vector{front_y, steering_end_y}, "g-"); - } -} - - -int main() { - // Problem parameters - const int state_dim = 5; // [x, y, theta, v, delta] - const int control_dim = 2; // [acceleration, steering_rate] - const int horizon = 600; - const double timestep = 0.03; - const std::string integration_type = "rk4"; - - // Create a Forklift instance - double wheelbase = 1.6; - bool rear_steer = true; - double max_steering_angle = 0.9; - - std::unique_ptr system = - std::make_unique(timestep, wheelbase, integration_type, - rear_steer, max_steering_angle); - - // Define initial and goal states for forklift back-in parking - Eigen::VectorXd initial_state(state_dim); - initial_state << 2.0, 0.5, M_PI, 0.0, 0.0; - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, M_PI/2, 0.0, 0.0; - - // Create the nonlinear objective for forklift parking - auto objective = std::make_unique(goal_state, timestep, horizon); - - // Set solver options for better convergence - cddp::CDDPOptions options; - options.max_iterations = 2000; - options.verbose = true; - options.tolerance = 1e-5; // Less strict tolerance - options.acceptable_tolerance = 1e-5; - options.regularization.initial_value = 1e-6; - options.debug = false; - options.use_ilqr = true; - options.enable_parallel = true; - options.num_threads = 10; - - options.msipddp.barrier.mu_initial = 1e-1; // Lower barrier parameter - options.msipddp.dual_var_init_scale = 1e-1; - options.msipddp.slack_var_init_scale = 1e-2; - options.msipddp.segment_length = horizon; // Longer segments - options.msipddp.rollout_type = "nonlinear"; - - // Create CDDP solver for the forklift model - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Define control constraints from README Table 1 - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -1.5, -0.4; // [acceleration, steering_rate] - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.5, 0.4; - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique( - control_lower_bound, control_upper_bound)); - - // State constraints - Eigen::VectorXd state_upper_bound(2); - state_upper_bound << 2.0, max_steering_angle; - cddp_solver.addPathConstraint("StateConstraint", - std::make_unique(-state_upper_bound, state_upper_bound)); - - // Initialize trajectory for back-in parking maneuver - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - - for (int i = 0; i < horizon; ++i) { - // Randomize controls - std::random_device rd; - std::mt19937 gen(rd()); - std::uniform_real_distribution<> dis(-0.01, 0.01); - U[i] << dis(gen), dis(gen); - X[i + 1] = cddp_solver.getSystem().getDiscreteDynamics(X[i], U[i], i * timestep); - } - - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem using MSIPDDP - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::MSIPDDP); - - // Extract solution trajectories - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - // Prepare trajectory data for plotting - auto x_hist = cddp::example::extractComponent(X_sol, 0); - auto y_hist = cddp::example::extractComponent(X_sol, 1); - - // Forklift dimensions - double forklift_length = 2.5; // Overall length - double forklift_width = 1.1; // Chassis width - - // Create a figure and get current axes - auto fig = figure(true); - auto ax = fig->current_axes(); - - Eigen::VectorXd empty_control = Eigen::VectorXd::Zero(2); - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Animation loop: update plot for each time step and save frame - for (size_t i = 0; i < X_sol.size(); ++i) - { - // Skip every 10th frame for smoother animation - if (i % 10 == 0) - { - // Clear previous content - cla(ax); - hold(ax, true); - - // Plot the full trajectory - plot(ax, x_hist, y_hist, "b--"); - - // Plot goal configuration - plotForkliftBox(goal_state, empty_control, forklift_length, - forklift_width, rear_steer, "r", ax); - - // Plot current forklift state - if (i < U_sol.size()) - plotForkliftBox(X_sol[i], U_sol[i], forklift_length, - forklift_width, rear_steer, "k", ax); - else - plotForkliftBox(X_sol[i], empty_control, forklift_length, - forklift_width, rear_steer, "k", ax); - - // Add labels and title - xlabel(ax, "X [m]"); - ylabel(ax, "Y [m]"); - title(ax, "Forklift Parking with IPDDP - Frame " + std::to_string(i)); - - // Set grid and axis limits - grid(ax, true); - xlim(ax, {-5, 5}); - ylim(ax, {-5, 5}); - - // Update drawing - fig->draw(); - - // Save the frame to a PNG file - std::string frame_filename = plotDirectory + "/forklift_frame_" + std::to_string(i) + ".png"; - fig->save(frame_filename); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool - std::string command = "convert -delay 10 " + plotDirectory + "/forklift_frame_*.png " - + plotDirectory + "/forklift_parking_ipddp.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/forklift_frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as forklift_parking_ipddp.gif" << std::endl; - - // Print final state - std::cout << "\nFinal state:" << std::endl; - std::cout << "Position: (" << X_sol.back()(0) << ", " << X_sol.back()(1) << ")" << std::endl; - std::cout << "Heading: " << X_sol.back()(2) * 180.0 / M_PI << " degrees" << std::endl; - std::cout << "Velocity: " << X_sol.back()(3) << " m/s" << std::endl; - std::cout << "Steering angle: " << X_sol.back()(4) * 180.0 / M_PI << " degrees" << std::endl; - - return 0; -} \ No newline at end of file diff --git a/examples/cddp_hcw.cpp b/examples/cddp_hcw.cpp deleted file mode 100644 index b9a05085..00000000 --- a/examples/cddp_hcw.cpp +++ /dev/null @@ -1,228 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * Example code demonstrating an HCW (Hill-Clohessy-Wiltshire) rendezvous problem with CDDP - */ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; -using namespace cddp; - -// ---------------------------------------------------------------------------------------- -// Main function demonstrating usage -// ---------------------------------------------------------------------------------------- -int main() { - // Random number generator for optional initial control sequence - std::random_device rd; - std::mt19937 gen(rd()); - std::normal_distribution d(0.0, 0.01); - - // HCW problem dimensions - const int STATE_DIM = 6; // [x, y, z, vx, vy, vz] - const int CONTROL_DIM = 3; // [Fx, Fy, Fz] - - // Set up the time horizon - int horizon = 50; // Number of steps - double timestep = 10.0; // Timestep in seconds (example) - std::string integration_type = "euler"; // or "rk4", etc. - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - - // Create the HCW dynamical system - // (this class is defined in your "spacecraft_linear.hpp") - std::unique_ptr system = - std::make_unique(timestep, mean_motion, mass, integration_type); - - // Initial state (for example, some offset and small velocity) - Eigen::VectorXd initial_state(STATE_DIM); - initial_state << 50.0, 14.0, 0.0, 0.0, 0.0, 0.0; - - // Goal state (origin in relative coordinates, zero velocity) - Eigen::VectorXd goal_state(STATE_DIM); - goal_state.setZero(); - - // Cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(STATE_DIM, STATE_DIM); - { - Q(0,0) = 1e3; Q(1,1) = 1e3; Q(2,2) = 1e3; - Q(3,3) = 1e1; Q(4,4) = 1e1; Q(5,5) = 1e1; - } - - Eigen::MatrixXd R = Eigen::MatrixXd::Zero(CONTROL_DIM, CONTROL_DIM); - { - R(0,0) = 1e2; R(1,1) = 1e2; R(2,2) = 1e2; - } - - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(STATE_DIM, STATE_DIM); - // { - // Qf(0,0) = 1e3; - // Qf(1,1) = 1e3; - // Qf(2,2) = 1e3; - // Qf(3,3) = 1e1; - // Qf(4,4) = 1e1; - // Qf(5,5) = 1e1; - // } - - std::vector empty_reference_states; - auto objective = std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Set solver options - cddp::CDDPOptions options; - options.max_iterations = 300; // Max number of CDDP iterations - options.verbose = true; // Print progress - options.tolerance = 1e-3; // Stop if improvement below this - options.acceptable_tolerance = 1e-3; // Stop if gradient below this - options.debug = false; - options.enable_parallel = true; - options.num_threads = 8; // Parallelization - - // Create the CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Optionally add control constraints (e.g., max thruster force) - Eigen::VectorXd umin(CONTROL_DIM); - Eigen::VectorXd umax(CONTROL_DIM); - // Suppose each axis force is limited to +/- 2 N - umin << -1.0, -1.0, -1.0; - umax << 1.0, 1.0, 1.0; - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(umin, umax)); - - // Initialize the trajectory (X,U) with something nontrivial - std::vector X(horizon + 1, Eigen::VectorXd::Zero(STATE_DIM)); - std::vector U(horizon, Eigen::VectorXd::Zero(CONTROL_DIM)); - - // Set the initial state - X[0] = initial_state; - - // Random or small constant initialization for control - for (auto& u : U) { - // u << d(gen), d(gen), d(gen); // small random thruster - u << 0.0, 0.0, 0.0; // zero thruster - } - - // Compute the initial cost by rolling out the initial controls - double J_init = 0.0; - for (int t = 0; t < horizon; t++) { - J_init += cddp_solver.getObjective().running_cost(X[t], U[t], t); - X[t+1] = cddp_solver.getSystem().getDiscreteDynamics(X[t], U[t], t * timestep); - } - J_init += cddp_solver.getObjective().terminal_cost(X[horizon]); - std::cout << "[Info] Initial cost: " << J_init << std::endl; - std::cout << "[Info] Initial final state: " << X[horizon].transpose() << std::endl; - - // Pass this initial guess to the solver - cddp_solver.setInitialTrajectory(X, U); - - // Solve - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - - // Extract solution and print result - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::cout << "\n[Result] CDDP solved." << std::endl; - std::cout << "[Result] Final cost: " << solution.final_objective << std::endl; - std::cout << "[Result] Final state: " - << X_sol.back().transpose() << std::endl; - - // Create plot directory - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Extract state data arrays - std::vector x_arr, y_arr, z_arr, vx_arr, vy_arr, vz_arr, time_arr; - for (size_t i = 0; i < X_sol.size(); ++i) { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - vx_arr.push_back(X_sol[i](3)); - vy_arr.push_back(X_sol[i](4)); - vz_arr.push_back(X_sol[i](5)); - } - - // Extract control data arrays (note: U_sol size is horizon, so use t_sol[i] for control time) - std::vector u1_arr, u2_arr, u3_arr, t_control; - for (size_t i = 0; i < U_sol.size(); ++i) { - u1_arr.push_back(U_sol[i](0)); - u2_arr.push_back(U_sol[i](1)); - u3_arr.push_back(U_sol[i](2)); - t_control.push_back(t_sol[i]); // assign control time to corresponding state time step - } - - // ------------------------------- - // Plot state history (position & velocity) - // ------------------------------- - auto fig1 = figure(true); - - // Position subplot - subplot(2,1,1); - plot(time_arr, x_arr, "-o")->line_width(2); - hold(on); - plot(time_arr, y_arr, "-o")->line_width(2); - plot(time_arr, z_arr, "-o")->line_width(2); - title("Position vs. Time"); - xlabel("Time [s]"); - ylabel("Position"); - matplot::legend({"x", "y", "z"}); - - // Velocity subplot - subplot(2,1,2); - plot(time_arr, vx_arr, "-o")->line_width(2); - hold(on); - plot(time_arr, vy_arr, "-o")->line_width(2); - plot(time_arr, vz_arr, "-o")->line_width(2); - title("Velocity vs. Time"); - xlabel("Time [s]"); - ylabel("Velocity"); - matplot::legend({"vx", "vy", "vz"}); - - // ------------------------------- - // Plot control history - // ------------------------------- - auto fig2 = figure(true); - plot(t_control, u1_arr, "-o")->line_width(2); - hold(on); - plot(t_control, u2_arr, "-o")->line_width(2); - plot(t_control, u3_arr, "-o")->line_width(2); - title("Control Inputs vs. Time"); - xlabel("Time [s]"); - ylabel("Control Input"); - matplot::legend({"u1", "u2", "u3"}); - - // Optionally save the figures - save(fig1, plotDirectory + "/hcw_state_history.png"); - save(fig2, plotDirectory + "/hcw_control_history.png"); - return 0; -} diff --git a/examples/cddp_lti_system.cpp b/examples/cddp_lti_system.cpp deleted file mode 100644 index 7844579a..00000000 --- a/examples/cddp_lti_system.cpp +++ /dev/null @@ -1,172 +0,0 @@ -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -#include "matplot/matplot.h" -using namespace matplot; -namespace fs = std::filesystem; - -namespace cddp { - -/** - * @brief Quadratic cost objective for LTI system - */ -class LTIObjective : public QuadraticObjective { -public: - LTIObjective(int state_dim, - int control_dim, - const Eigen::VectorXd& goal_state, - double timestep) - : QuadraticObjective( - 0.5 * timestep * Eigen::MatrixXd::Identity(state_dim, state_dim), // Q - 0.5 * 0.1 * timestep * Eigen::MatrixXd::Identity(control_dim, control_dim), // R - 0.5 * timestep * Eigen::MatrixXd::Identity(state_dim, state_dim), // Qf - goal_state) {} -}; - -} // namespace cddp - -template -void printVector(const std::string& label, const std::vector& vec) { - std::cout << label << ": ["; - for (size_t i = 0; i < vec.size(); ++i) { - if (i > 0) std::cout << ", "; - std::cout << vec[i]; - } - std::cout << "]\n"; -} - -void plotStateTrajectories(const std::vector& X_sol, - const std::string& plotDirectory) { - const int state_dim = X_sol[0].size(); - std::vector> state_histories(state_dim); - std::vector time_history; - - // Extract state histories (using the time index as sample number) - for (size_t t = 0; t < X_sol.size(); t++) { - time_history.push_back(static_cast(t)); - for (int i = 0; i < state_dim; i++) { - state_histories[i].push_back(X_sol[t](i)); - } - } - - // Create a new figure and set its size - auto fig = figure(true); - fig->size(1200, 800); - - // Create a subplot for each state variable - for (int i = 0; i < state_dim; i++) { - // Create subplot: (rows, columns, index) - subplot(state_dim, 1, i + 1); - plot(time_history, state_histories[i])->line_width(2); - title("State " + std::to_string(i + 1)); - grid(on); - } - - save(fig, plotDirectory + "/lti_states.png"); -} - -int main() { - // Problem parameters - int state_dim = 4; // State dimension - int control_dim = 2; // Control dimension - int horizon = 1000; // Time horizon - double timestep = 0.01; // Time step - std::string integration_type = "euler"; - - // Create LTI system instance - std::unique_ptr system = - std::make_unique(state_dim, control_dim, timestep, integration_type); - - // Initial and goal states - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state << 0.8378, 0.3794, 1.4796, 0.2382; - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - - // Create cost objective - Eigen::MatrixXd Q = 0.5 * Eigen::MatrixXd::Identity(state_dim, state_dim); // Q - Eigen::MatrixXd R = 0.5 * 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); // R - Eigen::MatrixXd Qf = 0.5 * timestep * Eigen::MatrixXd::Identity(state_dim, state_dim); // Qf - std::vector empty_reference_states; - auto objective = std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 10; - options.verbose = true; - options.regularization.initial_value = 0.0; - options.num_threads = 11; - options.enable_parallel = true; - options.debug = false; - - // Create CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Control constraints - Eigen::VectorXd control_lower_bound = -0.6 * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_upper_bound = 0.6 * Eigen::VectorXd::Ones(control_dim); - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique( - control_lower_bound, control_upper_bound)); - - // Initialize trajectories - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Random initial controls (here, a constant small control is used) - std::random_device rd; - std::mt19937 gen(rd()); - std::normal_distribution d(0.0, 0.1); - for (auto& u : U) { - u = 0.01 * Eigen::VectorXd::Ones(control_dim); - } - - X[0] = initial_state; - - // Simulate initial trajectory - double J = 0.0; - double cost = 0.0; - for (size_t t = 0; t < horizon; t++) { - cost = cddp_solver.getObjective().running_cost(X[t], U[t], t); - J += cost; - X[t + 1] = cddp_solver.getSystem().getDiscreteDynamics(X[t], U[t], t * timestep); - } - J += cddp_solver.getObjective().terminal_cost(X.back()); - std::cout << "Initial state: " << X[0].transpose() << std::endl; - std::cout << "Final state: " << X.back().transpose() << std::endl; - std::cout << "Initial cost: " << J << std::endl; - - cddp_solver.setInitialTrajectory(X, U); - - // Solve using the CDDP solver - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - // Alternatively: cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::LogDDP); - - // Extract solution trajectories - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - auto iterations = solution.iterations_completed; - bool converged = (solution.status_message == "OptimalSolutionFound" || solution.status_message == "AcceptableSolutionFound"); - - // Create directory for plots if it doesn't exist - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Plot state trajectories using the matplot API - plotStateTrajectories(X_sol, plotDirectory); - - // Print optimization statistics - std::cout << "\nOptimization Results:" << std::endl; - std::cout << "Iterations: " << iterations << std::endl; - std::cout << "Final cost: " << solution.final_objective << std::endl; - std::cout << "Converged: " << (converged ? "Yes" : "No") << std::endl; - std::cout << "Solve time: " << solution.solve_time_ms << " ms" << std::endl; - - return 0; -} diff --git a/examples/cddp_manipulator.cpp b/examples/cddp_manipulator.cpp index 24278b5f..3ad8b8eb 100644 --- a/examples/cddp_manipulator.cpp +++ b/examples/cddp_manipulator.cpp @@ -13,232 +13,70 @@ See the License for the specific language governing permissions and limitations under the License. */ + #include #include -#include -#include -#include -#include -#include // for sleep_for #include "cddp.hpp" -#include "cddp_example_utils.hpp" - -#include "matplot/matplot.h" -using namespace matplot; -namespace fs = std::filesystem; int main() { - // -------------------- System and Problem Setup -------------------- - // System dimensions: state = [q1, q2, q3, dq1, dq2, dq3], control = [tau1, tau2, tau3] - int state_dim = 6; - int control_dim = 3; - int horizon = 200; // Time horizon for optimization - double timestep = 0.01; + constexpr double kPi = 3.14159265358979323846; + constexpr int state_dim = 6; + constexpr int control_dim = 3; + constexpr int horizon = 160; + constexpr double timestep = 0.01; + + Eigen::VectorXd initial_state(state_dim); + initial_state << 0.0, -kPi / 2.0, kPi, 0.0, 0.0, 0.0; - // Create a manipulator instance (assumed to be defined in your CDDP framework) - auto system = std::make_unique(timestep, "rk4"); + Eigen::VectorXd goal_state(state_dim); + goal_state << kPi, -kPi / 6.0, -kPi / 3.0, 0.0, 0.0, 0.0; - // Cost matrices Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - // Cost on joint angles Q.diagonal().segment(0, 3) = Eigen::Vector3d::Ones(); - // Cost on joint velocities Q.diagonal().segment(3, 3) = 0.1 * Eigen::Vector3d::Ones(); - Eigen::MatrixXd R = 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = 100.0 * Q; // Terminal cost - - // Initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, -M_PI/2, M_PI, 0.0, 0.0, 0.0; - Eigen::VectorXd goal_state(state_dim); - goal_state << M_PI, -M_PI/6, -M_PI/3, 0.0, 0.0, 0.0; + Eigen::MatrixXd Qf = 100.0 * Q; - // Create quadratic objective (with no reference trajectory) - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Solver options cddp::CDDPOptions options; - options.max_iterations = 100; + options.max_iterations = 80; options.line_search.max_iterations = 20; - options.verbose = true; - - // Create and configure the CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - // Control constraints: joint torques limited to ±max_torque - double max_torque = 50.0; - Eigen::VectorXd control_lower_bound = -max_torque * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_upper_bound = max_torque * Eigen::VectorXd::Ones(control_dim); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); + cddp::CDDP solver( + initial_state, + goal_state, + horizon, + timestep, + std::make_unique(timestep, "rk4"), + std::make_unique( + Q, R, Qf, goal_state, std::vector{}, timestep), + options); + + const Eigen::VectorXd lower = + -50.0 * Eigen::VectorXd::Ones(control_dim); + const Eigen::VectorXd upper = + 50.0 * Eigen::VectorXd::Ones(control_dim); + solver.addPathConstraint("ControlConstraint", + std::make_unique(lower, upper)); - // Initialize trajectories: here we use linear interpolation between initial and goal state std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); for (int i = 0; i <= horizon; ++i) { - double alpha = static_cast(i) / horizon; + const double alpha = static_cast(i) / static_cast(horizon); X[i] = (1.0 - alpha) * initial_state + alpha * goal_state; } - cddp_solver.setInitialTrajectory(X, U); - - // Solve the optimal control problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - - // -------------------- Extract Trajectories for Static Plots -------------------- - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::vector time; // for state trajectories - std::vector time_ctrl; // for control trajectories - // For joint angles and velocities (each has 3 joints) - std::vector> joint_angles(3), joint_velocities(3); - std::vector> joint_torques(3); - - // Loop over the time sequence to extract states and controls - for (size_t i = 0; i < t_sol.size(); ++i) { - time.push_back(t_sol[i]); - if (i < X_sol.size()) { - for (int j = 0; j < 3; ++j) { - joint_angles[j].push_back(X_sol[i](j)); - joint_velocities[j].push_back(X_sol[i](j + 3)); - } - } - if (i < U_sol.size()) { - for (int j = 0; j < 3; ++j) { - joint_torques[j].push_back(U_sol[i](j)); - } - time_ctrl.push_back(t_sol[i]); - } - } - - // -------------------- Static Plot: Joint Angles, Velocities, and Torques -------------------- - auto fig1 = figure(true); - fig1->size(1200, 800); - - // Joint angles subplot - auto ax1_fig1 = subplot(3, 1, 1); - for (int j = 0; j < 3; ++j) { - auto plot_handle = plot(ax1_fig1, time, joint_angles[j], "-o"); - plot_handle->line_width(2); - plot_handle->display_name("Joint " + std::to_string(j + 1)); - } - title("Joint Angles"); - xlabel("Time [s]"); - ylabel("Angle [rad]"); - matplot::legend(ax1_fig1); - grid(on); - - // Joint velocities subplot - auto ax2_fig1 = subplot(3, 1, 2); - for (int j = 0; j < 3; ++j) { - auto plot_handle = plot(ax2_fig1, time, joint_velocities[j], "-o"); - plot_handle->line_width(2); - plot_handle->display_name("Joint " + std::to_string(j + 1)); - } - title("Joint Velocities"); - xlabel("Time [s]"); - ylabel("Velocity [rad/s]"); - matplot::legend(ax2_fig1); - grid(on); - - // Joint torques subplot - auto ax3_fig1 = subplot(3, 1, 3); - for (int j = 0; j < 3; ++j) { - auto plot_handle = plot(ax3_fig1, time_ctrl, joint_torques[j], "-o"); - plot_handle->line_width(2); - plot_handle->display_name("Joint " + std::to_string(j + 1)); - } - title("Joint Torques"); - xlabel("Time [s]"); - ylabel("Torque [Nm]"); - matplot::legend(ax3_fig1); - grid(on); - - // Create a directory for plots if it doesn't exist - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - save(fig1, plotDirectory + "/manipulator_cddp_results.png"); - - // Create a new figure for animation - auto fig2 = figure(true); - fig2->size(800, 600); - auto ax2_fig2 = fig2->current_axes(); - cddp::Manipulator manipulator(timestep, "rk4"); - - // Animate every 5th frame of the solution - for (size_t i = 0; i < X_sol.size(); i += 5) { - ax2_fig2->clear(); // clear current figure - ax2_fig2->hold(true); // hold the current plot - ax2_fig2->grid(true); // enable grid - - const auto& state = X_sol[i]; - - auto transforms = manipulator.getTransformationMatrices(state(0), state(1), state(2)); - Eigen::Matrix4d T01 = transforms[0]; - Eigen::Matrix4d T02 = T01 * transforms[1]; - Eigen::Matrix4d T03 = T02 * transforms[2]; - Eigen::Matrix4d T04 = T03 * transforms[3]; - - // Compute end-effector position. - Eigen::Vector4d r3; - r3 << manipulator.getLinkLength('c'), 0, manipulator.getLinkLength('b'), 1; - Eigen::Vector4d r0 = T03 * r3; // End-effector position in base frame - // Compute an intermediate (elbow) position - Eigen::Vector4d rm = T03 * Eigen::Vector4d(0, 0, manipulator.getLinkLength('b'), 1); - - // Prepare data for plotting: - std::vector x = {0, T03(0, 3), rm(0), r0(0)}; - std::vector y = {0, T03(1, 3), rm(1), r0(1)}; - std::vector z = {0, T03(2, 3), rm(2), r0(2)}; - auto link_line = plot3(x, y, z, "-o"); - link_line->line_width(2); - link_line->color("blue"); - - // Plot joints (using markers only) - std::vector joint_x = {0, T03(0, 3), rm(0)}; - std::vector joint_y = {0, T03(1, 3), rm(1)}; - std::vector joint_z = {0, T03(2, 3), rm(2)}; - auto joint_markers = plot3(joint_x, joint_y, joint_z, "o"); - joint_markers->color("red"); - - // Plot end-effector as a marker - std::vector ee_x = {r0(0)}; - std::vector ee_y = {r0(1)}; - std::vector ee_z = {r0(2)}; - auto ee_marker = plot3(ee_x, ee_y, ee_z, "o"); - ee_marker->color("red"); - - xlabel("X [m]"); - ylabel("Y [m]"); - zlabel("Z [m]"); - title("Manipulator CDDP Solution"); - xlim({-2, 2}); - ylim({-2, 2}); - zlim({-1, 3}); - view(30, -60); - - // Save each frame (e.g., "manipulator_frame_0.png", "manipulator_frame_1.png", …) - std::string filename = plotDirectory + "/manipulator_frame_" + std::to_string(i/5) + ".png"; - save(fig2, filename); + solver.setInitialTrajectory(X, U); - // Pause for 10 milliseconds between frames - std::this_thread::sleep_for(std::chrono::milliseconds(40)); + const cddp::CDDPSolution solution = solver.solve(cddp::SolverType::CLDDP); + if (solution.state_trajectory.empty()) { + std::cerr << "Manipulator example failed: empty trajectory" << std::endl; + return 1; } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 20 " + plotDirectory + "/manipulator_frame_*.png " + plotDirectory + "/manipulator.gif"; - std::system(gif_command.c_str()); - std::string cleanup_command = "rm " + plotDirectory + "/manipulator_frame_*.png"; - std::system(cleanup_command.c_str()); - + const Eigen::VectorXd final_error = solution.state_trajectory.back() - goal_state; + std::cout << "Manipulator example completed with status: " + << solution.status_message << '\n' + << "Final objective: " << solution.final_objective << '\n' + << "Final state error norm: " << final_error.norm() << std::endl; return 0; } diff --git a/examples/cddp_pendulum.cpp b/examples/cddp_pendulum.cpp index 19654f63..6972fb37 100644 --- a/examples/cddp_pendulum.cpp +++ b/examples/cddp_pendulum.cpp @@ -13,232 +13,67 @@ See the License for the specific language governing permissions and limitations under the License. */ + #include #include -#include -#include -#include -#include -#include + #include "cddp.hpp" #include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; int main() { - // -------------------- Problem Setup -------------------- - int state_dim = 2; - int control_dim = 1; - int horizon = 100; - double timestep = 0.02; - - // Create a pendulum instance - double mass = 1.0; - double length = 0.5; - double damping = 0.01; - std::string integration_type = "euler"; - - // Cost matrices + constexpr double kPi = 3.14159265358979323846; + constexpr int state_dim = 2; + constexpr int control_dim = 1; + constexpr int horizon = 100; + constexpr double timestep = 0.02; + + Eigen::VectorXd initial_state(state_dim); + initial_state << kPi, 0.0; + + Eigen::VectorXd goal_state(state_dim); + goal_state << 0.0, 0.0; + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); Eigen::MatrixXd R = 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 100.0, 0.0, - 0.0, 100.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0; // Upright position with zero velocity - - std::vector empty_reference_states; - - // Initial state (pendulum pointing down) - Eigen::VectorXd initial_state(state_dim); - initial_state << M_PI, 0.0; - - // Construct a zero control sequence and an initial trajectory (all at the initial state) - std::vector zero_control_sequence(horizon, Eigen::VectorXd::Zero(control_dim)); - std::vector X_init(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - for (int t = 0; t < horizon + 1; ++t) { - X_init[t] = initial_state; - } - - // (Optional) Calculate initial cost - auto temp_objective = std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep); - double J = 0.0; - for (int t = 0; t < horizon; ++t) { - J += temp_objective->running_cost(X_init[t], zero_control_sequence[t], t); - } - J += temp_objective->terminal_cost(X_init[horizon]); - - // Control constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -100.0; - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 100.0; - - // Solver options + Eigen::MatrixXd Qf = 100.0 * Eigen::MatrixXd::Identity(state_dim, state_dim); + cddp::CDDPOptions options; - options.max_iterations = 20; + options.max_iterations = 30; options.tolerance = 1e-4; options.acceptable_tolerance = 1e-5; - options.regularization.initial_value = 1e-7; - - // Create and configure the CDDP solver with new API - cddp::CDDP cddp_solver( + options.regularization.initial_value = 1e-6; + + cddp::CDDP solver( initial_state, goal_state, horizon, timestep, - std::make_unique(timestep, length, mass, damping, integration_type), - std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); - - // Set initial trajectory for the solver - auto [X, U] = cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); - cddp_solver.setInitialTrajectory(X, U); - - // Solve the optimal control problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - - // Create plot directory if it doesn't exist - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // -------------------- Data Extraction -------------------- - auto theta_arr = cddp::example::extractComponent(X_sol, 0); - auto theta_dot_arr = cddp::example::extractComponent(X_sol, 1); - auto torque_arr = cddp::example::extractComponent(U_sol, 0); - - // Build time vectors (state has horizon+1 points; control has horizon points) - auto time_state = cddp::example::makeTimeVector(X_sol.size(), timestep); - auto time_control = cddp::example::makeTimeVector(U_sol.size(), timestep); - - // -------------------- Static Plot -------------------- - auto fig1 = figure(true); - fig1->size(1200, 800); - - // Subplot for state trajectory (angle and angular velocity) - auto ax1 = subplot(2, 1, 0); - { - ax1->hold(true); - auto plot_handle1 = plot(ax1, time_state, theta_arr, "-o"); - plot_handle1->display_name("Angle"); - plot_handle1->line_width(2); - plot_handle1->color("b"); - - auto plot_handle2 = plot(ax1, time_state, theta_dot_arr, "-o"); - plot_handle2->display_name("Angular Velocity"); - plot_handle2->line_width(2); - plot_handle2->color("r"); - ax1->title("Pendulum State Trajectory"); - ax1->xlabel("Time [s]"); - ax1->ylabel("Value"); - ax1->legend(); - ax1->grid(true); - - } - // Subplot for control input (torque) - auto ax2 = subplot(2, 1, 1); - { - ax2->hold(true); - auto plot_handle3 = plot(ax2, time_control, torque_arr, "-o"); - plot_handle3->display_name("Torque"); - plot_handle3->line_width(2); - plot_handle3->color("g"); - - // Customize the plot - ax2->title("Control Input"); - ax2->xlabel("Time [s]"); - ax2->ylabel("Torque [Nm]"); - ax2->legend(); - ax2->grid(true); - } - - // Adjust layout if supported - // tight_layout(); // Uncomment if your matplot version supports it - save(fig1, plotDirectory + "/pendulum_cddp_test.png"); - - // --- Animation --- - auto fig3 = figure(); - auto ax_fig3 = fig3->current_axes(); - fig3->size(800, 600); - title("Pendulum Animation"); - double pendulum_length = length; - double bob_radius = 0.1; + std::make_unique(timestep, 0.5, 1.0, 0.01, "euler"), + std::make_unique( + Q, R, Qf, goal_state, std::vector{}, timestep), + options); + Eigen::VectorXd lower(control_dim); + lower << -20.0; + Eigen::VectorXd upper(control_dim); + upper << 20.0; + solver.addPathConstraint("ControlConstraint", + std::make_unique(lower, upper)); - for (int i = 0; i < X_sol.size(); ++i) { - // Animate every 5th frame - if (i % 5 == 0) { - // Clear previous content. - cla(ax_fig3); - hold(ax_fig3, true); - - double theta = theta_arr[i]; - // Calculate pendulum bob position (x, y) - double x = pendulum_length * std::sin(theta); - double y = pendulum_length * std::cos(theta); - - // Plot pendulum rod - std::vector rod_x = {0, x}; - std::vector rod_y = {0, y}; - auto rod_plot = plot(rod_x, rod_y); - rod_plot->line_style("k-"); - rod_plot->line_width(2); + auto [X, U] = + cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); + solver.setInitialTrajectory(X, U); - - // Plot pendulum bob as a circle - std::vector circle_x, circle_y; - int num_points = 50; - for (int j = 0; j <= num_points; ++j) { - double t = 2 * M_PI * j / num_points; - circle_x.push_back(x + bob_radius * std::cos(t)); - circle_y.push_back(y + bob_radius * std::sin(t)); - } - auto circle_plot = plot(circle_x, circle_y); - circle_plot->line_style("b-"); - circle_plot->line_width(2); - - - // Plot trajectory trace for the last 50 frames, if available - std::vector trace_x, trace_y; - int start = std::max(0, i - 50); - for (int j = start; j < i; ++j) { - trace_x.push_back(pendulum_length * std::sin(theta_arr[j])); - trace_y.push_back(pendulum_length * std::cos(theta_arr[j])); - } - if (!trace_x.empty()) { - auto trace_plot = plot(trace_x, trace_y); - trace_plot->line_style("r--"); - trace_plot->line_width(1); - } - // Set fixed axis limits for stable animation. - ax_fig3->xlim({-0.7, 0.7}); - ax_fig3->ylim({-0.7, 0.7}); - - // Save the current frame as an image file - std::string filename = plotDirectory + "/pendulum_frame_" + std::to_string(i) + ".png"; - save(fig3, filename); - - std::this_thread::sleep_for(std::chrono::milliseconds(30)); - } + const cddp::CDDPSolution solution = solver.solve(cddp::SolverType::IPDDP); + if (solution.state_trajectory.empty()) { + std::cerr << "Pendulum example failed: empty trajectory" << std::endl; + return 1; } - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 30 " + plotDirectory + "/pendulum_frame_*.png " + plotDirectory + "/pendulum.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/pendulum_frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as pendulum.gif" << std::endl; - + const Eigen::VectorXd final_error = solution.state_trajectory.back() - goal_state; + std::cout << "Pendulum example completed with status: " + << solution.status_message << '\n' + << "Final objective: " << solution.final_objective << '\n' + << "Final state error norm: " << final_error.norm() << std::endl; return 0; } diff --git a/examples/cddp_quadrotor_circle.cpp b/examples/cddp_quadrotor_circle.cpp deleted file mode 100644 index 22f7ec0b..00000000 --- a/examples/cddp_quadrotor_circle.cpp +++ /dev/null @@ -1,566 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -// Helper function: Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Helper function: Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - - return R; -} - -// Helper: Transform quadrotor frame points (motor positions) to world coordinates using quaternion. -std::vector> transformQuadrotorFrame( - const Eigen::Vector3d &position, - const Eigen::Vector4d &quat, // [qw, qx, qy, qz] - double arm_length) -{ - - // Define quadrotor motor positions in the body frame - std::vector body_points = { - Eigen::Vector3d(arm_length, 0, 0), // Front motor - Eigen::Vector3d(0, arm_length, 0), // Right motor - Eigen::Vector3d(-arm_length, 0, 0), // Back motor - Eigen::Vector3d(0, -arm_length, 0) // Left motor - }; - - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat[0], quat[1], quat[2], quat[3]); - - std::vector> world_points(3, std::vector()); - for (const auto &pt : body_points) - { - Eigen::Vector3d wp = position + R * pt; - world_points[0].push_back(wp.x()); - world_points[1].push_back(wp.y()); - world_points[2].push_back(wp.z()); - } - return world_points; -} - -int main() -{ - // For quaternion-based quadrotor, state_dim = 13: - // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - int state_dim = 13; - int control_dim = 4; // [f1, f2, f3, f4] - int horizon = 400; // Longer horizon for 3D maneuvers - double timestep = 0.02; - - // Quadrotor parameters - double mass = 1.0; // 1kg quadrotor - double arm_length = 0.2; // 20cm arm length - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 0.01; // Ixx - inertia_matrix(1, 1) = 0.01; // Iyy - inertia_matrix(2, 2) = 0.02; // Izz - - std::string integration_type = "rk4"; - - // Create the dynamical system (quadrotor) as a unique_ptr - std::unique_ptr system = - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type); - - // For propagation - cddp::Quadrotor quadrotor(timestep, mass, inertia_matrix, arm_length, integration_type); - - // Cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Q(0, 0) = 1.0; - Q(1, 1) = 1.0; - Q(2, 2) = 1.0; - Q(3, 3) = 1.0; - Q(4, 4) = 1.0; - Q(5, 5) = 1.0; - Q(6, 6) = 1.0; - - // Control cost matrix (penalize aggressive control inputs) - Eigen::MatrixXd R = 0.01 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - // Terminal cost matrix (important for stability) - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 1.0; - Qf(1, 1) = 1.0; - Qf(2, 2) = 1.0; - Qf(3, 3) = 1.0; - Qf(4, 4) = 1.0; - Qf(5, 5) = 1.0; - Qf(6, 6) = 1.0; - - // Parameters for the circular trajectory - double circle_radius = 3.0; // e.g., 3m radius - Eigen::Vector2d circle_center(0.0, 0.0); // center of the circle in the x-y plane - double constant_altitude = 2.0; // fixed altitude (z) - double total_time = horizon * timestep; // total duration - // omega is chosen so that the quadrotor completes one full circle over the time horizon - double omega = 2 * M_PI / total_time; - - std::vector circle_reference_states; - circle_reference_states.reserve(horizon + 1); - - for (int i = 0; i <= horizon; ++i) - { - double t = i * timestep; - double angle = omega * t; - - // Create a reference state of dimension state_dim (13) - Eigen::VectorXd ref_state = Eigen::VectorXd::Zero(state_dim); - - // Position (x, y, z) - ref_state(0) = circle_center(0) + circle_radius * std::cos(angle); - ref_state(1) = circle_center(1) + circle_radius * std::sin(angle); - ref_state(2) = constant_altitude; - - // Orientation: set to identity quaternion [1, 0, 0, 0] - ref_state(3) = 1.0; // qw - ref_state(4) = 0.0; // qx - ref_state(5) = 0.0; // qy - ref_state(6) = 0.0; // qz // z velocity - - circle_reference_states.push_back(ref_state); - } - - // Goal state: hover at position (3,0,2) with identity quaternion and zero velocities. - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state(0) = circle_center(0) + circle_radius; - goal_state(2) = constant_altitude; - goal_state(3) = 1.0; // Identity quaternion: qw = 1 - - auto objective = std::make_unique( - Q, R, Qf, goal_state, circle_reference_states, timestep); - - // Initial state (at origin with identity quaternion) - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state(0) = circle_center(0) + circle_radius; - initial_state(2) = constant_altitude; - initial_state(3) = 1.0; // Identity quaternion: qw = 1 - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 10000; - options.verbose = true; - options.debug = false; - options.enable_parallel = true; - options.num_threads = 10; - options.tolerance = 1e-3; - options.regularization.initial_value = 1e-4; - options.ipddp.barrier.mu_initial = 1e-1; - options.msipddp.segment_length = horizon / 10; - options.msipddp.rollout_type = "nonlinear"; - options.ipddp.barrier.mu_update_factor = 0.2; - options.ipddp.barrier.mu_update_power = 1.2; - - // Create the CDDP solver - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::move(system), - std::move(objective), - options); - - // Control constraints (motor thrust limits) - double min_force = 0.0; // Motors can only produce thrust upward - double max_force = 4.0; // Maximum thrust per motor - Eigen::VectorXd control_upper_bound = max_force * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_lower_bound = min_force * Eigen::VectorXd::Ones(control_dim); - // cddp_solver.addConstraint("ControlConstraint", - // std::make_unique(control_lower_bound, control_upper_bound)); - - // Initial trajectory: allocate state and control trajectories - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Initialize with hovering thrust (each motor provides mg/4) - double hover_thrust = mass * 9.81 / 4.0; - for (auto &u : U) - { - u = hover_thrust * Eigen::VectorXd::Ones(control_dim); - } - // Propagate initial trajectory using discrete dynamics - // for (size_t i = 0; i < static_cast(horizon); ++i) - // { - // X[i + 1] = quadrotor.getDiscreteDynamics(X[i], U[i]); - // } - - // Initialize state by the actual reference trajectory - X = circle_reference_states; - cddp_solver.setInitialTrajectory(X, U); - - // Solve the optimal control problem (LogDDP, IPDDP, MSIPDDP) - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::MSIPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::cout << "Final state: " << X_sol.back().transpose() << std::endl; - - // // Create plot directory if it doesn't exist - // const std::string plotDirectory = "../results/tests"; - // if (!fs::exists(plotDirectory)) - // { - // fs::create_directory(plotDirectory); - // } - // // Create a directory for frame images. - // (void)std::system("mkdir -p frames"); - - // // Extract trajectory data - // std::vector time_arr, x_arr, y_arr, z_arr; - // std::vector phi_arr, theta_arr, psi_arr; - // std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - // time_arr.reserve(X_sol.size()); - // x_arr.reserve(X_sol.size()); - // y_arr.reserve(X_sol.size()); - // z_arr.reserve(X_sol.size()); - // phi_arr.reserve(X_sol.size()); - // theta_arr.reserve(X_sol.size()); - // psi_arr.reserve(X_sol.size()); - - // qw_arr.reserve(X_sol.size()); - // qx_arr.reserve(X_sol.size()); - // qy_arr.reserve(X_sol.size()); - // qz_arr.reserve(X_sol.size()); - // q_norm_arr.reserve(X_sol.size()); - - // for (size_t i = 0; i < X_sol.size(); ++i) - // { - // time_arr.push_back(t_sol[i]); - // x_arr.push_back(X_sol[i](0)); - // y_arr.push_back(X_sol[i](1)); - // z_arr.push_back(X_sol[i](2)); - - // double qw = X_sol[i](3); - // double qx = X_sol[i](4); - // double qy = X_sol[i](5); - // double qz = X_sol[i](6); - - // // Euler angles - // Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - // phi_arr.push_back(euler(0)); - // theta_arr.push_back(euler(1)); - // psi_arr.push_back(euler(2)); - - // // Quaternion data - // qw_arr.push_back(qw); - // qx_arr.push_back(qx); - // qy_arr.push_back(qy); - // qz_arr.push_back(qz); - // q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - // } - - // // Control data - // std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - // std::vector f1_arr, f2_arr, f3_arr, f4_arr; - // f1_arr.reserve(U_sol.size()); - // f2_arr.reserve(U_sol.size()); - // f3_arr.reserve(U_sol.size()); - // f4_arr.reserve(U_sol.size()); - - // for (const auto &u : U_sol) - // { - // f1_arr.push_back(u(0)); - // f2_arr.push_back(u(1)); - // f3_arr.push_back(u(2)); - // f4_arr.push_back(u(3)); - // } - - // // Plotting - // auto f1 = figure(); - // f1->size(1200, 900); // Slightly bigger if you like - - // // (1) Position - // auto ax1_f1 = subplot(4, 1, 0); - // auto plot_handle1 = plot(ax1_f1, time_arr, x_arr, "-r"); - // plot_handle1->display_name("x"); - // plot_handle1->line_width(2); - // hold(ax1_f1, true); - // auto plot_handle2 = plot(ax1_f1, time_arr, y_arr, "-g"); - // plot_handle2->display_name("y"); - // plot_handle2->line_width(2); - // auto plot_handle3 = plot(ax1_f1, time_arr, z_arr, "-b"); - // plot_handle3->display_name("z"); - // plot_handle3->line_width(2); - - // title(ax1_f1, "Position Trajectories"); - // xlabel(ax1_f1, "Time [s]"); - // ylabel(ax1_f1, "Position [m]"); - // matplot::legend(ax1_f1); - // grid(ax1_f1, true); - - // // (2) Attitude (Euler angles) - // auto ax2_f1 = subplot(4, 1, 1); - // hold(ax2_f1, true); - // auto plot_handle4 = plot(ax2_f1, time_arr, phi_arr, "-r"); - // plot_handle4->display_name("roll"); - // plot_handle4->line_width(2); - // auto plot_handle5 = plot(ax2_f1, time_arr, theta_arr, "-g"); - // plot_handle5->display_name("pitch"); - // plot_handle5->line_width(2); - // auto plot_handle6 = plot(ax2_f1, time_arr, psi_arr, "-b"); - // plot_handle6->display_name("yaw"); - // plot_handle6->line_width(2); - - // title(ax2_f1, "Attitude Angles"); - // xlabel(ax2_f1, "Time [s]"); - // ylabel(ax2_f1, "Angle [rad]"); - // matplot::legend(ax2_f1); - // grid(ax2_f1, true); - - // // (3) Motor forces - // auto ax3_f1 = subplot(4, 1, 2); - // auto plot_handle7 = plot(ax3_f1, time_arr2, f1_arr, "-r"); - // plot_handle7->display_name("f1"); - // plot_handle7->line_width(2); - // hold(ax3_f1, true); - // auto plot_handle8 = plot(ax3_f1, time_arr2, f2_arr, "-g"); - // plot_handle8->display_name("f2"); - // plot_handle8->line_width(2); - // auto plot_handle9 = plot(ax3_f1, time_arr2, f3_arr, "-b"); - // plot_handle9->display_name("f3"); - // plot_handle9->line_width(2); - // auto plot_handle10 = plot(ax3_f1, time_arr2, f4_arr, "-k"); - // plot_handle10->display_name("f4"); - // plot_handle10->line_width(2); - - // title(ax3_f1, "Motor Forces"); - // xlabel(ax3_f1, "Time [s]"); - // ylabel(ax3_f1, "Force [N]"); - // matplot::legend(ax3_f1); - // grid(ax3_f1, true); - - // // (4) Quaternion trajectories and norm - // auto ax4_f1 = subplot(4, 1, 3); - // hold(ax4_f1, true); - - // auto qwh = plot(ax4_f1, time_arr, qw_arr, "-r"); - // qwh->display_name("q_w"); - // qwh->line_width(2); - - // auto qxh = plot(ax4_f1, time_arr, qx_arr, "-g"); - // qxh->display_name("q_x"); - // qxh->line_width(2); - - // auto qyh = plot(ax4_f1, time_arr, qy_arr, "-b"); - // qyh->display_name("q_y"); - // qyh->line_width(2); - - // auto qzh = plot(ax4_f1, time_arr, qz_arr, "-m"); - // qzh->display_name("q_z"); - // qzh->line_width(2); - - // // Norm in black - // auto qnorm_handle = plot(ax4_f1, time_arr, q_norm_arr, "-k"); - // qnorm_handle->display_name("|q|"); - - // title(ax4_f1, "Quaternion Components and Norm"); - // xlabel(ax4_f1, "Time [s]"); - // ylabel(ax4_f1, "Value"); - // matplot::legend(ax4_f1); - // grid(ax4_f1, true); - - // // Save figure 1 - // f1->draw(); - // f1->save(plotDirectory + "/quadrotor_circle_states.png"); - - // // 3D Trajectory - // auto f2 = figure(); - // f2->size(800, 600); - // auto ax2 = f2->current_axes(); - // hold(ax2, true); - // auto traj3d = plot3(ax2, x_arr, y_arr, z_arr); - // traj3d->display_name("Trajectory"); - // traj3d->line_style("-"); - // traj3d->line_width(2); - // traj3d->color("blue"); - // // Project trajectory onto x-y plane at z=0 - // auto proj_xy = plot3(ax2, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - // proj_xy->display_name("X-Y Projection"); - // proj_xy->line_style("--"); - // proj_xy->line_width(1); - // proj_xy->color("gray"); - // xlabel(ax2, "X [m]"); - // ylabel(ax2, "Y [m]"); - // zlabel(ax2, "Z [m]"); - // xlim(ax2, {-5, 5}); - // ylim(ax2, {-5, 5}); - // zlim(ax2, {0, 5}); - // title(ax2, "3D Trajectory (Figure-8)"); - // grid(ax2, true); - // f2->draw(); - // f2->save(plotDirectory + "/quadrotor_circle_3d.png"); - - // // Animation of the quadrotor frame - // auto f_anim = figure(); - // f_anim->size(800, 600); - // auto ax_anim = f_anim->current_axes(); - - // // For collecting the trajectory as we go - // std::vector anim_x, anim_y, anim_z; - // anim_x.reserve(X_sol.size()); - // anim_y.reserve(X_sol.size()); - // anim_z.reserve(X_sol.size()); - - // // Render every Nth frame to reduce #images - // int frame_stride = 15; - // double prop_radius = 0.03; // radius for small spheres at motor ends - - // for (size_t i = 0; i < X_sol.size(); i += frame_stride) - // { - // ax_anim->clear(); - // ax_anim->hold(true); - // ax_anim->grid(true); - - // // Current state - // double x = X_sol[i](0); - // double y = X_sol[i](1); - // double z = X_sol[i](2); - - // // Accumulate path - // anim_x.push_back(x); - // anim_y.push_back(y); - // anim_z.push_back(z); - - // // Plot the partial trajectory so far (in black dotted line) - // auto path_plot = plot3(anim_x, anim_y, anim_z); - // path_plot->line_width(1.5); - // path_plot->line_style("--"); - // path_plot->color("black"); - - // // Build rotation from quaternion - // Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - // Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // // Arm endpoints (front, right, back, left) - // std::vector arm_endpoints; - // arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // // Transform to world coords - // for (auto &pt : arm_endpoints) - // { - // pt = Eigen::Vector3d(x, y, z) + R * pt; - // } - - // // Front-back arm - // std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - // std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - // std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - // auto fb_arm = plot3(fx, fy, fz); - // fb_arm->line_width(2.0); - // fb_arm->color("blue"); - - // // Right-left arm - // std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - // std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - // std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - // auto rl_arm = plot3(rx, ry, rz); - // rl_arm->line_width(2.0); - // rl_arm->color("red"); - - // auto sphere_points = linspace(0, 2 * M_PI, 15); - // for (const auto &motor_pos : arm_endpoints) - // { - // std::vector circ_x, circ_y, circ_z; - // circ_x.reserve(sphere_points.size()); - // circ_y.reserve(sphere_points.size()); - // circ_z.reserve(sphere_points.size()); - // for (auto angle : sphere_points) - // { - // circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - // circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - // circ_z.push_back(motor_pos.z()); // keep the same z for a small ring - // } - // auto sphere_plot = plot3(circ_x, circ_y, circ_z); - // sphere_plot->line_style("solid"); - // sphere_plot->line_width(1.5); - // sphere_plot->color("cyan"); - // } - - // title(ax_anim, "Quadrotor Animation"); - // xlabel(ax_anim, "X [m]"); - // ylabel(ax_anim, "Y [m]"); - // zlabel(ax_anim, "Z [m]"); - // xlim(ax_anim, {-5, 5}); - // ylim(ax_anim, {-5, 5}); - // zlim(ax_anim, {0, 5}); - - // ax_anim->view(30, -30); - - // std::string frameFile = plotDirectory + "/quadrotor_anim_frame_" + std::to_string(i / frame_stride) + ".png"; - // f_anim->draw(); - // f_anim->save(frameFile); - // std::this_thread::sleep_for(std::chrono::milliseconds(80)); - // } - - // // ----------------------------- - // // Generate GIF from frames using ImageMagick - // // ----------------------------- - // std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_anim_frame_*.png " + plotDirectory + "/quadrotor_circle.gif"; - // std::system(gif_command.c_str()); - - // std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_anim_frame_*.png"; - // std::system(cleanup_command.c_str()); - return 0; -} - -// To create a gif from the saved frames, use ImageMagick (for example): -// convert -delay 5 ../results/tests/quadrotor_frame_*.png ../results/tests/quadrotor_circle.gif diff --git a/examples/cddp_quadrotor_figure_eight_horizontal.cpp b/examples/cddp_quadrotor_figure_eight_horizontal.cpp deleted file mode 100644 index 04c0771a..00000000 --- a/examples/cddp_quadrotor_figure_eight_horizontal.cpp +++ /dev/null @@ -1,556 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -// Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - return R; -} - -// Transform quadrotor frame points (motor positions) to world coordinates using quaternion -std::vector> transformQuadrotorFrame( - const Eigen::Vector3d &position, - const Eigen::Vector4d &quat, // [qw, qx, qy, qz] - double arm_length) -{ - // Motor positions in body frame - std::vector body_points = { - Eigen::Vector3d(arm_length, 0, 0), // Front - Eigen::Vector3d(0, arm_length, 0), // Right - Eigen::Vector3d(-arm_length, 0, 0), // Back - Eigen::Vector3d(0, -arm_length, 0) // Left - }; - - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat[0], quat[1], quat[2], quat[3]); - - // Prepare return container - std::vector> world_points(3, std::vector()); - for (const auto &pt : body_points) - { - Eigen::Vector3d wp = position + R * pt; - world_points[0].push_back(wp.x()); - world_points[1].push_back(wp.y()); - world_points[2].push_back(wp.z()); - } - return world_points; -} - -int main() -{ - // For quaternion-based quadrotor, state_dim = 13: - // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - int state_dim = 13; - int control_dim = 4; // [f1, f2, f3, f4] - int horizon = 400; - double timestep = 0.02; - - // Quadrotor parameters - double mass = 1.2; // 1 kg - double arm_length = 0.165; // 20 cm - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 7.782e-3; // Ixx - inertia_matrix(1, 1) = 7.782e-3; // Iyy - inertia_matrix(2, 2) = 1.439e-2; // Izz - - std::string integration_type = "rk4"; - - // Create the dynamical system - std::unique_ptr system = - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type); - - // For propagation, create a direct instance - cddp::Quadrotor quadrotor(timestep, mass, inertia_matrix, arm_length, integration_type); - - // Cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - // penalize [x, y, z, qw, qx, qy, qz] more (the orientation/quaternion part) - Q(0, 0) = 1.0; - Q(1, 1) = 1.0; - Q(2, 2) = 1.0; - Q(3, 3) = 1.0; - Q(4, 4) = 1.0; - Q(5, 5) = 1.0; - Q(6, 6) = 1.0; - - Eigen::MatrixXd R = 0.01 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 1.0; - Qf(1, 1) = 1.0; - Qf(2, 2) = 1.0; - Qf(3, 3) = 1.0; - Qf(4, 4) = 1.0; - Qf(5, 5) = 1.0; - Qf(6, 6) = 1.0; - - // Figure-8 trajectory parameters - double figure8_scale = 3.0; // 3m - double constant_altitude = 2.0; // 2m - double total_time = horizon * timestep; - double omega = 2.0 * M_PI / total_time; // completes 1 cycle over the horizon - - std::vector figure8_reference_states; - figure8_reference_states.reserve(horizon + 1); - - for (int i = 0; i <= horizon; ++i) - { - double t = i * timestep; - double angle = omega * t; - - // Lemniscate of Gerono for (x, y) - // x = A cos(angle) - // y = A sin(angle)*cos(angle) - Eigen::VectorXd ref_state = Eigen::VectorXd::Zero(state_dim); - ref_state(0) = figure8_scale * std::cos(angle); - ref_state(1) = figure8_scale * std::sin(angle) * std::cos(angle); - ref_state(2) = constant_altitude; - - // Identity quaternion: [1, 0, 0, 0] - ref_state(3) = 1.0; - ref_state(4) = 0.0; - ref_state(5) = 0.0; - ref_state(6) = 0.0; - - figure8_reference_states.push_back(ref_state); - } - - // Hover at the starting point of the figure-8 - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state(0) = figure8_scale; // x - goal_state(2) = constant_altitude; - goal_state(3) = 1.0; // qw - - // Create the objective - auto objective = std::make_unique( - Q, R, Qf, goal_state, figure8_reference_states, timestep); - - // Start the same figure-8 starting point - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state(0) = figure8_scale; - initial_state(2) = constant_altitude; - initial_state(3) = 1.0; - - // Create CDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 10000; - options.tolerance = 1e-6; - options.verbose = true; - options.debug = false; - options.enable_parallel = true; - options.num_threads = 10; - options.regularization.initial_value = 1e-4; - options.ipddp.barrier.mu_initial = 1e-1; - options.use_ilqr = true; - options.msipddp.segment_length = horizon / 10; - options.msipddp.rollout_type = "nonlinear"; - - // Instantiate CDDP solver - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::move(system), - std::move(objective), - options); - - // Control constraints - double min_force = 0.0; - double max_force = 4.0; - Eigen::VectorXd control_upper_bound = max_force * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_lower_bound = min_force * Eigen::VectorXd::Ones(control_dim); - // cddp_solver.addConstraint("ControlConstraint", std::make_unique(control_lower_bound, control_upper_bound)); - - // Initial trajectory guess - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - double hover_thrust = mass * 9.81 / 4.0; - for (auto &u : U) - { - u = hover_thrust * Eigen::VectorXd::Ones(control_dim); - } - - // X[0] = initial_state; - // for (int i = 0; i < horizon; ++i) - // { - // X[i + 1] = quadrotor.getDiscreteDynamics(X[i], U[i]); - // } - X = figure8_reference_states; - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::MSIPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::cout << "Final state = " << X_sol.back().transpose() << std::endl; - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void)std::system("mkdir -p frames"); - - // Extract trajectory data - std::vector time_arr, x_arr, y_arr, z_arr; - std::vector phi_arr, theta_arr, psi_arr; - std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - time_arr.reserve(X_sol.size()); - x_arr.reserve(X_sol.size()); - y_arr.reserve(X_sol.size()); - z_arr.reserve(X_sol.size()); - phi_arr.reserve(X_sol.size()); - theta_arr.reserve(X_sol.size()); - psi_arr.reserve(X_sol.size()); - - qw_arr.reserve(X_sol.size()); - qx_arr.reserve(X_sol.size()); - qy_arr.reserve(X_sol.size()); - qz_arr.reserve(X_sol.size()); - q_norm_arr.reserve(X_sol.size()); - - for (size_t i = 0; i < X_sol.size(); ++i) - { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - - double qw = X_sol[i](3); - double qx = X_sol[i](4); - double qy = X_sol[i](5); - double qz = X_sol[i](6); - - // Euler angles - Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - phi_arr.push_back(euler(0)); - theta_arr.push_back(euler(1)); - psi_arr.push_back(euler(2)); - - // Quaternion data - qw_arr.push_back(qw); - qx_arr.push_back(qx); - qy_arr.push_back(qy); - qz_arr.push_back(qz); - q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - } - - // Control data - std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - std::vector f1_arr, f2_arr, f3_arr, f4_arr; - f1_arr.reserve(U_sol.size()); - f2_arr.reserve(U_sol.size()); - f3_arr.reserve(U_sol.size()); - f4_arr.reserve(U_sol.size()); - - for (const auto &u : U_sol) - { - f1_arr.push_back(u(0)); - f2_arr.push_back(u(1)); - f3_arr.push_back(u(2)); - f4_arr.push_back(u(3)); - } - - // Plotting - auto f1 = figure(); - f1->size(1200, 900); // Slightly bigger if you like - - // (1) Position - auto ax1_f1 = subplot(4, 1, 0); - auto plot_handle1 = plot(ax1_f1, time_arr, x_arr, "-r"); - plot_handle1->display_name("x"); - plot_handle1->line_width(2); - hold(ax1_f1, true); - auto plot_handle2 = plot(ax1_f1, time_arr, y_arr, "-g"); - plot_handle2->display_name("y"); - plot_handle2->line_width(2); - auto plot_handle3 = plot(ax1_f1, time_arr, z_arr, "-b"); - plot_handle3->display_name("z"); - plot_handle3->line_width(2); - - title(ax1_f1, "Position Trajectories"); - xlabel(ax1_f1, "Time [s]"); - ylabel(ax1_f1, "Position [m]"); - matplot::legend(ax1_f1); - grid(ax1_f1, true); - - // (2) Attitude (Euler angles) - auto ax2_f1 = subplot(4, 1, 1); - hold(ax2_f1, true); - auto plot_handle4 = plot(ax2_f1, time_arr, phi_arr, "-r"); - plot_handle4->display_name("roll"); - plot_handle4->line_width(2); - auto plot_handle5 = plot(ax2_f1, time_arr, theta_arr, "-g"); - plot_handle5->display_name("pitch"); - plot_handle5->line_width(2); - auto plot_handle6 = plot(ax2_f1, time_arr, psi_arr, "-b"); - plot_handle6->display_name("yaw"); - plot_handle6->line_width(2); - - title(ax2_f1, "Attitude Angles"); - xlabel(ax2_f1, "Time [s]"); - ylabel(ax2_f1, "Angle [rad]"); - matplot::legend(ax2_f1); - grid(ax2_f1, true); - - // (3) Motor forces - auto ax3_f1 = subplot(4, 1, 2); - auto plot_handle7 = plot(ax3_f1, time_arr2, f1_arr, "-r"); - plot_handle7->display_name("f1"); - plot_handle7->line_width(2); - hold(ax3_f1, true); - auto plot_handle8 = plot(ax3_f1, time_arr2, f2_arr, "-g"); - plot_handle8->display_name("f2"); - plot_handle8->line_width(2); - auto plot_handle9 = plot(ax3_f1, time_arr2, f3_arr, "-b"); - plot_handle9->display_name("f3"); - plot_handle9->line_width(2); - auto plot_handle10 = plot(ax3_f1, time_arr2, f4_arr, "-k"); - plot_handle10->display_name("f4"); - plot_handle10->line_width(2); - - title(ax3_f1, "Motor Forces"); - xlabel(ax3_f1, "Time [s]"); - ylabel(ax3_f1, "Force [N]"); - matplot::legend(ax3_f1); - grid(ax3_f1, true); - - // (4) Quaternion trajectories and norm - auto ax4_f1 = subplot(4, 1, 3); - hold(ax4_f1, true); - - auto qwh = plot(ax4_f1, time_arr, qw_arr, "-r"); - qwh->display_name("q_w"); - qwh->line_width(2); - - auto qxh = plot(ax4_f1, time_arr, qx_arr, "-g"); - qxh->display_name("q_x"); - qxh->line_width(2); - - auto qyh = plot(ax4_f1, time_arr, qy_arr, "-b"); - qyh->display_name("q_y"); - qyh->line_width(2); - - auto qzh = plot(ax4_f1, time_arr, qz_arr, "-m"); - qzh->display_name("q_z"); - qzh->line_width(2); - - // Norm in black - auto qnorm_handle = plot(ax4_f1, time_arr, q_norm_arr, "-k"); - qnorm_handle->display_name("|q|"); - - title(ax4_f1, "Quaternion Components and Norm"); - xlabel(ax4_f1, "Time [s]"); - ylabel(ax4_f1, "Value"); - matplot::legend(ax4_f1); - grid(ax4_f1, true); - - // Save figure 1 - f1->draw(); - f1->save(plotDirectory + "/quadrotor_figure_eight_horizontal_states.png"); - - // 3D Trajectory - auto f2 = figure(); - f2->size(800, 600); - auto ax2 = f2->current_axes(); - hold(ax2, true); - auto traj3d = plot3(ax2, x_arr, y_arr, z_arr); - traj3d->display_name("Trajectory"); - traj3d->line_style("-"); - traj3d->line_width(2); - traj3d->color("blue"); - // Project trajectory onto x-y plane at z=0 - auto proj_xy = plot3(ax2, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - proj_xy->display_name("X-Y Projection"); - proj_xy->line_style("--"); - proj_xy->line_width(1); - proj_xy->color("gray"); - xlabel(ax2, "X [m]"); - ylabel(ax2, "Y [m]"); - zlabel(ax2, "Z [m]"); - xlim(ax2, {-5, 5}); - ylim(ax2, {-2, 2}); - zlim(ax2, {0, 5}); - title(ax2, "3D Trajectory (Figure-8)"); - grid(ax2, true); - f2->draw(); - f2->save(plotDirectory + "/quadrotor_figure_eight_horizontal_3d.png"); - - // Animation of the quadrotor frame - auto f_anim = figure(); - f_anim->size(800, 600); - auto ax_anim = f_anim->current_axes(); - - // For collecting the trajectory as we go - std::vector anim_x, anim_y, anim_z; - anim_x.reserve(X_sol.size()); - anim_y.reserve(X_sol.size()); - anim_z.reserve(X_sol.size()); - - // Render every Nth frame to reduce #images - int frame_stride = 15; - double prop_radius = 0.03; // radius for small spheres at motor ends - - for (size_t i = 0; i < X_sol.size(); i += frame_stride) - { - ax_anim->clear(); - ax_anim->hold(true); - ax_anim->grid(true); - - // Current state - double x = X_sol[i](0); - double y = X_sol[i](1); - double z = X_sol[i](2); - - // Accumulate path - anim_x.push_back(x); - anim_y.push_back(y); - anim_z.push_back(z); - - // Plot the partial trajectory so far (in black dotted line) - auto path_plot = plot3(anim_x, anim_y, anim_z); - path_plot->line_width(1.5); - path_plot->line_style("--"); - path_plot->color("black"); - - // Build rotation from quaternion - Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // Arm endpoints (front, right, back, left) - std::vector arm_endpoints; - arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // Transform to world coords - for (auto &pt : arm_endpoints) - { - pt = Eigen::Vector3d(x, y, z) + R * pt; - } - - // Front-back arm - std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - auto fb_arm = plot3(fx, fy, fz); - fb_arm->line_width(2.0); - fb_arm->color("blue"); - - // Right-left arm - std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - auto rl_arm = plot3(rx, ry, rz); - rl_arm->line_width(2.0); - rl_arm->color("red"); - - auto sphere_points = linspace(0, 2 * M_PI, 15); - for (const auto &motor_pos : arm_endpoints) - { - std::vector circ_x, circ_y, circ_z; - circ_x.reserve(sphere_points.size()); - circ_y.reserve(sphere_points.size()); - circ_z.reserve(sphere_points.size()); - for (auto angle : sphere_points) - { - circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - circ_z.push_back(motor_pos.z()); // keep the same z for a small ring - } - auto sphere_plot = plot3(circ_x, circ_y, circ_z); - sphere_plot->line_style("solid"); - sphere_plot->line_width(1.5); - sphere_plot->color("cyan"); - } - - title(ax_anim, "Quadrotor Animation"); - xlabel(ax_anim, "X [m]"); - ylabel(ax_anim, "Y [m]"); - zlabel(ax_anim, "Z [m]"); - xlim(ax_anim, {-5, 5}); - ylim(ax_anim, {-5, 5}); - zlim(ax_anim, {0, 5}); - - ax_anim->view(30, -30); - - std::string frameFile = plotDirectory + "/quadrotor_anim_frame_" + std::to_string(i / frame_stride) + ".png"; - f_anim->draw(); - f_anim->save(frameFile); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_anim_frame_*.png " + plotDirectory + "/quadrotor_figure_eight_horizontal.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_anim_frame_*.png"; - std::system(cleanup_command.c_str()); - - return 0; -} diff --git a/examples/cddp_quadrotor_figure_eight_horizontal_safe.cpp b/examples/cddp_quadrotor_figure_eight_horizontal_safe.cpp deleted file mode 100644 index f26ffee5..00000000 --- a/examples/cddp_quadrotor_figure_eight_horizontal_safe.cpp +++ /dev/null @@ -1,625 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -// Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - return R; -} - -// Transform quadrotor frame points (motor positions) to world coordinates using quaternion -std::vector> transformQuadrotorFrame( - const Eigen::Vector3d &position, - const Eigen::Vector4d &quat, // [qw, qx, qy, qz] - double arm_length) -{ - // Motor positions in body frame - std::vector body_points = { - Eigen::Vector3d(arm_length, 0, 0), // Front - Eigen::Vector3d(0, arm_length, 0), // Right - Eigen::Vector3d(-arm_length, 0, 0), // Back - Eigen::Vector3d(0, -arm_length, 0) // Left - }; - - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat[0], quat[1], quat[2], quat[3]); - - // Prepare return container - std::vector> world_points(3, std::vector()); - for (const auto &pt : body_points) - { - Eigen::Vector3d wp = position + R * pt; - world_points[0].push_back(wp.x()); - world_points[1].push_back(wp.y()); - world_points[2].push_back(wp.z()); - } - return world_points; -} - -int main() -{ - // For quaternion-based quadrotor, state_dim = 13: - // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - int state_dim = 13; - int control_dim = 4; // [f1, f2, f3, f4] - int horizon = 400; - double timestep = 0.02; - - // Quadrotor parameters - double mass = 1.2; // 1 kg - double arm_length = 0.165; // 20 cm - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 7.782e-3; // Ixx - inertia_matrix(1, 1) = 7.782e-3; // Iyy - inertia_matrix(2, 2) = 1.439e-2; // Izz - - std::string integration_type = "rk4"; - - // Create the dynamical system - std::unique_ptr system = - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type); - - // For propagation, create a direct instance - cddp::Quadrotor quadrotor(timestep, mass, inertia_matrix, arm_length, integration_type); - - // Cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - // penalize [x, y, z, qw, qx, qy, qz] more (the orientation/quaternion part) - Q(0, 0) = 1.0; - Q(1, 1) = 1.0; - Q(2, 2) = 1.0; - // Q(3, 3) = 1.0; - // Q(4, 4) = 1.0; - // Q(5, 5) = 1.0; - // Q(6, 6) = 1.0; - - Eigen::MatrixXd R = 0.01 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 1.0; - Qf(1, 1) = 1.0; - Qf(2, 2) = 1.0; - Qf(3, 3) = 1.0; - Qf(4, 4) = 1.0; - Qf(5, 5) = 1.0; - Qf(6, 6) = 1.0; - - // Figure-8 trajectory parameters - double figure8_scale = 3.0; // 3m - double constant_altitude = 2.0; // 2m - double total_time = horizon * timestep; - double omega = 2.0 * M_PI / total_time; // completes 1 cycle over the horizon - - std::vector figure8_reference_states; - figure8_reference_states.reserve(horizon + 1); - - for (int i = 0; i <= horizon; ++i) - { - double t = i * timestep; - double angle = omega * t; - - // Lemniscate of Gerono for (x, y) - // x = A cos(angle) - // y = A sin(angle)*cos(angle) - Eigen::VectorXd ref_state = Eigen::VectorXd::Zero(state_dim); - ref_state(0) = figure8_scale * std::cos(angle); - ref_state(1) = figure8_scale * std::sin(angle) * std::cos(angle); - ref_state(2) = constant_altitude; - - // Identity quaternion: [1, 0, 0, 0] - ref_state(3) = 1.0; - ref_state(4) = 0.0; - ref_state(5) = 0.0; - ref_state(6) = 0.0; - - figure8_reference_states.push_back(ref_state); - } - - // Hover at the starting point of the figure-8 - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state(0) = figure8_scale; // x - goal_state(2) = constant_altitude; - goal_state(3) = 1.0; // qw - - // Create the objective - auto objective = std::make_unique( - Q, R, Qf, goal_state, figure8_reference_states, timestep); - - // Start the same figure-8 starting point - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state(0) = figure8_scale; - initial_state(2) = constant_altitude; - initial_state(3) = 1.0; - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 100; - options.verbose = true; - options.debug = false; - options.tolerance = 1e-6; - options.acceptable_tolerance = 1e-7; - options.use_ilqr = true; - options.enable_parallel = false; - options.num_threads = 1; - - // Line search options - options.line_search.max_iterations = 10; - - // Regularization options - options.regularization.initial_value = 1e-3; - - // IPDDP-specific options - options.ipddp.barrier.mu_initial = 1e-1; - - // MSIPDDP-specific options - options.msipddp.barrier.mu_initial = 1e-1; - options.msipddp.segment_length = 2; - options.msipddp.rollout_type = "nonlinear"; - options.msipddp.use_controlled_rollout = false; - - // Instantiate CDDP solver - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::move(system), - std::move(objective), - options); - - // Control constraints - double min_force = 0.0; - double max_force = 4.0; - Eigen::VectorXd control_upper_bound = max_force * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_lower_bound = min_force * Eigen::VectorXd::Ones(control_dim); - cddp_solver.addPathConstraint("ControlConstraint", std::make_unique(control_lower_bound, control_upper_bound)); - - // Initial trajectory guess (use reference trajectory like benchmark) - double hover_thrust = mass * 9.81 / 4.0; - std::vector X_init = figure8_reference_states; // Use reference as initial guess - std::vector U_init(horizon, hover_thrust * Eigen::VectorXd::Ones(control_dim)); - cddp_solver.setInitialTrajectory(X_init, U_init); - - // Solve the problem - cddp::CDDPSolution solution = cddp_solver.solve("MSIPDDP"); - - options.max_iterations = 500; - options.warm_start = true; - - // Resolve problem with the ball constraint - cddp::CDDP solver_ball( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type), - std::make_unique( - Q, R, Qf, goal_state, figure8_reference_states, timestep), - options); - solver_ball.addPathConstraint("ControlConstraint", std::make_unique(control_lower_bound, control_upper_bound)); - - // Ball constraint - double ball_radius = 0.5; // 50 cm - Eigen::Vector3d ball_center(0.0, 0.0, constant_altitude); // Center of the ball - solver_ball.addPathConstraint("BallConstraint", std::make_unique(ball_radius, ball_center)); - - // Initial trajectory guess (extract from solution) - const auto& initial_X = solution.state_trajectory; - const auto& initial_U = solution.control_trajectory; - solver_ball.setInitialTrajectory(initial_X, initial_U); - - // Solve the problem (MSIPDDP, IPDDP) - cddp::CDDPSolution solution_ball = solver_ball.solve("MSIPDDP"); - - const auto& X_sol = solution_ball.state_trajectory; - const auto& U_sol = solution_ball.control_trajectory; - const auto& t_sol = solution_ball.time_points; - - std::cout << "Final state = " << X_sol.back().transpose() << std::endl; - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Create a directory for frame images. - (void)std::system("mkdir -p frames"); - - // Extract trajectory data - std::vector time_arr, x_arr, y_arr, z_arr; - std::vector phi_arr, theta_arr, psi_arr; - std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - time_arr.reserve(X_sol.size()); - x_arr.reserve(X_sol.size()); - y_arr.reserve(X_sol.size()); - z_arr.reserve(X_sol.size()); - phi_arr.reserve(X_sol.size()); - theta_arr.reserve(X_sol.size()); - psi_arr.reserve(X_sol.size()); - - qw_arr.reserve(X_sol.size()); - qx_arr.reserve(X_sol.size()); - qy_arr.reserve(X_sol.size()); - qz_arr.reserve(X_sol.size()); - q_norm_arr.reserve(X_sol.size()); - - for (size_t i = 0; i < X_sol.size(); ++i) - { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - - double qw = X_sol[i](3); - double qx = X_sol[i](4); - double qy = X_sol[i](5); - double qz = X_sol[i](6); - - // Euler angles - Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - phi_arr.push_back(euler(0)); - theta_arr.push_back(euler(1)); - psi_arr.push_back(euler(2)); - - // Quaternion data - qw_arr.push_back(qw); - qx_arr.push_back(qx); - qy_arr.push_back(qy); - qz_arr.push_back(qz); - q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - } - - // Control data - std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - std::vector f1_arr, f2_arr, f3_arr, f4_arr; - f1_arr.reserve(U_sol.size()); - f2_arr.reserve(U_sol.size()); - f3_arr.reserve(U_sol.size()); - f4_arr.reserve(U_sol.size()); - - for (const auto &u : U_sol) - { - f1_arr.push_back(u(0)); - f2_arr.push_back(u(1)); - f3_arr.push_back(u(2)); - f4_arr.push_back(u(3)); - } - - // Plotting - auto f1 = figure(); - f1->size(1200, 900); // Slightly bigger if you like - - // (1) Position - auto ax1_f1 = subplot(4, 1, 0); - auto plot_handle1 = plot(ax1_f1, time_arr, x_arr, "-r"); - plot_handle1->display_name("x"); - plot_handle1->line_width(2); - hold(ax1_f1, true); - auto plot_handle2 = plot(ax1_f1, time_arr, y_arr, "-g"); - plot_handle2->display_name("y"); - plot_handle2->line_width(2); - auto plot_handle3 = plot(ax1_f1, time_arr, z_arr, "-b"); - plot_handle3->display_name("z"); - plot_handle3->line_width(2); - - title(ax1_f1, "Position Trajectories"); - xlabel(ax1_f1, "Time [s]"); - ylabel(ax1_f1, "Position [m]"); - matplot::legend(ax1_f1); - grid(ax1_f1, true); - - // (2) Attitude (Euler angles) - auto ax2_f1 = subplot(4, 1, 1); - hold(ax2_f1, true); - auto plot_handle4 = plot(ax2_f1, time_arr, phi_arr, "-r"); - plot_handle4->display_name("roll"); - plot_handle4->line_width(2); - auto plot_handle5 = plot(ax2_f1, time_arr, theta_arr, "-g"); - plot_handle5->display_name("pitch"); - plot_handle5->line_width(2); - auto plot_handle6 = plot(ax2_f1, time_arr, psi_arr, "-b"); - plot_handle6->display_name("yaw"); - plot_handle6->line_width(2); - - title(ax2_f1, "Attitude Angles"); - xlabel(ax2_f1, "Time [s]"); - ylabel(ax2_f1, "Angle [rad]"); - matplot::legend(ax2_f1); - grid(ax2_f1, true); - - // (3) Motor forces - auto ax3_f1 = subplot(4, 1, 2); - auto plot_handle7 = plot(ax3_f1, time_arr2, f1_arr, "-r"); - plot_handle7->display_name("f1"); - plot_handle7->line_width(2); - hold(ax3_f1, true); - auto plot_handle8 = plot(ax3_f1, time_arr2, f2_arr, "-g"); - plot_handle8->display_name("f2"); - plot_handle8->line_width(2); - auto plot_handle9 = plot(ax3_f1, time_arr2, f3_arr, "-b"); - plot_handle9->display_name("f3"); - plot_handle9->line_width(2); - auto plot_handle10 = plot(ax3_f1, time_arr2, f4_arr, "-k"); - plot_handle10->display_name("f4"); - plot_handle10->line_width(2); - - title(ax3_f1, "Motor Forces"); - xlabel(ax3_f1, "Time [s]"); - ylabel(ax3_f1, "Force [N]"); - matplot::legend(ax3_f1); - grid(ax3_f1, true); - - // (4) Quaternion trajectories and norm - auto ax4_f1 = subplot(4, 1, 3); - hold(ax4_f1, true); - - auto qwh = plot(ax4_f1, time_arr, qw_arr, "-r"); - qwh->display_name("q_w"); - qwh->line_width(2); - - auto qxh = plot(ax4_f1, time_arr, qx_arr, "-g"); - qxh->display_name("q_x"); - qxh->line_width(2); - - auto qyh = plot(ax4_f1, time_arr, qy_arr, "-b"); - qyh->display_name("q_y"); - qyh->line_width(2); - - auto qzh = plot(ax4_f1, time_arr, qz_arr, "-m"); - qzh->display_name("q_z"); - qzh->line_width(2); - - // Norm in black - auto qnorm_handle = plot(ax4_f1, time_arr, q_norm_arr, "-k"); - qnorm_handle->display_name("|q|"); - - title(ax4_f1, "Quaternion Components and Norm"); - xlabel(ax4_f1, "Time [s]"); - ylabel(ax4_f1, "Value"); - matplot::legend(ax4_f1); - grid(ax4_f1, true); - - // Save figure 1 - f1->draw(); - f1->save(plotDirectory + "/quadrotor_figure_eight_horizontal_safe_states.png"); - - // 3D Trajectory - auto f2 = figure(); - f2->size(800, 600); - auto ax2 = f2->current_axes(); - hold(ax2, true); - auto traj3d = plot3(ax2, x_arr, y_arr, z_arr); - traj3d->display_name("Trajectory"); - traj3d->line_style("-"); - traj3d->line_width(2); - traj3d->color("blue"); - - // Project trajectory onto x-y plane at z=0 - auto proj_xy = plot3(ax2, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - proj_xy->display_name("X-Y Projection"); - proj_xy->line_style("--"); - proj_xy->line_width(1); - proj_xy->color("gray"); - - // Plot the ball constraint - int n_sphere = 30; - auto phi = linspace(0, M_PI, n_sphere); - auto theta = linspace(0, 2 * M_PI, n_sphere); - - std::vector> sx(n_sphere, std::vector(n_sphere)); - std::vector> sy(n_sphere, std::vector(n_sphere)); - std::vector> sz(n_sphere, std::vector(n_sphere)); - - for (int i = 0; i < n_sphere; i++) - { - for (int j = 0; j < n_sphere; j++) - { - sx[i][j] = ball_center(0) + ball_radius * std::sin(phi[i]) * std::cos(theta[j]); - sy[i][j] = ball_center(1) + ball_radius * std::sin(phi[i]) * std::sin(theta[j]); - sz[i][j] = ball_center(2) + ball_radius * std::cos(phi[i]); - } - } - auto sphere_surf = surf(ax2, sx, sy, sz); - sphere_surf->edge_color("red"); - - // Plot projection of the sphere onto the x-y plane - int n_points = 100; - std::vector circle_x(n_points), circle_y(n_points), circle_z(n_points); - for (int i = 0; i < n_points; i++) - { - double angle = 2.0 * M_PI * i / n_points; - circle_x[i] = ball_center(0) + ball_radius * std::cos(angle); - circle_y[i] = ball_center(1) + ball_radius * std::sin(angle); - circle_z[i] = 0.0; // Projection onto x-y plane - } - // Draw the circle perimeter - auto circle_plot = plot3(ax2, circle_x, circle_y, circle_z); - circle_plot->line_width(2).line_style("--").display_name("Ball x-y projection"); - circle_plot->color("black"); // For contrast - - - xlabel(ax2, "X [m]"); - ylabel(ax2, "Y [m]"); - zlabel(ax2, "Z [m]"); - xlim(ax2, {-5, 5}); - ylim(ax2, {-2, 2}); - zlim(ax2, {0, 5}); - title(ax2, "3D Trajectory (Figure-8)"); - grid(ax2, true); - f2->draw(); - f2->save(plotDirectory + "/quadrotor_figure_eight_horizontal_safe_3d.png"); - f2->show(); - - // // Animation of the quadrotor frame - // auto f_anim = figure(); - // f_anim->size(800, 600); - // auto ax_anim = f_anim->current_axes(); - - // // For collecting the trajectory as we go - // std::vector anim_x, anim_y, anim_z; - // anim_x.reserve(X_sol.size()); - // anim_y.reserve(X_sol.size()); - // anim_z.reserve(X_sol.size()); - - // // Render every Nth frame to reduce #images - // int frame_stride = 15; - // double prop_radius = 0.03; // radius for small spheres at motor ends - - // for (size_t i = 0; i < X_sol.size(); i += frame_stride) - // { - // ax_anim->clear(); - // ax_anim->hold(true); - // ax_anim->grid(true); - - // // Current state - // double x = X_sol[i](0); - // double y = X_sol[i](1); - // double z = X_sol[i](2); - - // // Accumulate path - // anim_x.push_back(x); - // anim_y.push_back(y); - // anim_z.push_back(z); - - // // Plot the partial trajectory so far (in black dotted line) - // auto path_plot = plot3(anim_x, anim_y, anim_z); - // path_plot->line_width(1.5); - // path_plot->line_style("--"); - // path_plot->color("black"); - - // // Build rotation from quaternion - // Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - // Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // // Arm endpoints (front, right, back, left) - // std::vector arm_endpoints; - // arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - // arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // // Transform to world coords - // for (auto &pt : arm_endpoints) - // { - // pt = Eigen::Vector3d(x, y, z) + R * pt; - // } - - // // Front-back arm - // std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - // std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - // std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - // auto fb_arm = plot3(fx, fy, fz); - // fb_arm->line_width(2.0); - // fb_arm->color("blue"); - - // // Right-left arm - // std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - // std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - // std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - // auto rl_arm = plot3(rx, ry, rz); - // rl_arm->line_width(2.0); - // rl_arm->color("red"); - - // auto sphere_points = linspace(0, 2 * M_PI, 15); - // for (const auto &motor_pos : arm_endpoints) - // { - // std::vector circ_x, circ_y, circ_z; - // circ_x.reserve(sphere_points.size()); - // circ_y.reserve(sphere_points.size()); - // circ_z.reserve(sphere_points.size()); - // for (auto angle : sphere_points) - // { - // circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - // circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - // circ_z.push_back(motor_pos.z()); // keep the same z for a small ring - // } - // auto sphere_plot = plot3(circ_x, circ_y, circ_z); - // sphere_plot->line_style("solid"); - // sphere_plot->line_width(1.5); - // sphere_plot->color("cyan"); - // } - - // title(ax_anim, "Quadrotor Animation"); - // xlabel(ax_anim, "X [m]"); - // ylabel(ax_anim, "Y [m]"); - // zlabel(ax_anim, "Z [m]"); - // xlim(ax_anim, {-5, 5}); - // ylim(ax_anim, {-5, 5}); - // zlim(ax_anim, {0, 5}); - - // ax_anim->view(30, -30); - - // std::string frameFile = plotDirectory + "/quadrotor_anim_frame_" + std::to_string(i / frame_stride) + ".png"; - // f_anim->draw(); - // f_anim->save(frameFile); - // std::this_thread::sleep_for(std::chrono::milliseconds(80)); - // } - - // // ----------------------------- - // // Generate GIF from frames using ImageMagick - // // ----------------------------- - // std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_anim_frame_*.png " + plotDirectory + "/quadrotor_figure_eight_horizontal_safe.gif"; - // std::system(gif_command.c_str()); - - // std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_anim_frame_*.png"; - // std::system(cleanup_command.c_str()); - - return 0; -} diff --git a/examples/cddp_quadrotor_figure_eight_vertical.cpp b/examples/cddp_quadrotor_figure_eight_vertical.cpp deleted file mode 100644 index ba288c05..00000000 --- a/examples/cddp_quadrotor_figure_eight_vertical.cpp +++ /dev/null @@ -1,555 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; -// Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - return R; -} - -// Transform quadrotor frame points (motor positions) to world coordinates using quaternion -std::vector> transformQuadrotorFrame( - const Eigen::Vector3d &position, - const Eigen::Vector4d &quat, // [qw, qx, qy, qz] - double arm_length) -{ - // Motor positions in body frame - std::vector body_points = { - Eigen::Vector3d(arm_length, 0, 0), // Front - Eigen::Vector3d(0, arm_length, 0), // Right - Eigen::Vector3d(-arm_length, 0, 0), // Back - Eigen::Vector3d(0, -arm_length, 0) // Left - }; - - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat[0], quat[1], quat[2], quat[3]); - - // Prepare return container - std::vector> world_points(3, std::vector()); - for (const auto &pt : body_points) - { - Eigen::Vector3d wp = position + R * pt; - world_points[0].push_back(wp.x()); - world_points[1].push_back(wp.y()); - world_points[2].push_back(wp.z()); - } - return world_points; -} - -int main() -{ - // For quaternion-based quadrotor, state_dim = 13: - // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - int state_dim = 13; - int control_dim = 4; // [f1, f2, f3, f4] - int horizon = 400; - double timestep = 0.02; - - // Quadrotor parameters - double mass = 1.2; // 1 kg - double arm_length = 0.165; // 20 cm - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 7.782e-3; // Ixx - inertia_matrix(1, 1) = 7.782e-3; // Iyy - inertia_matrix(2, 2) = 1.439e-2; // Izz - - std::string integration_type = "rk4"; - - // Create the dynamical system - std::unique_ptr system = - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type); - - // For propagation, create a direct instance - cddp::Quadrotor quadrotor(timestep, mass, inertia_matrix, arm_length, integration_type); - - // Cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - // penalize [x, y, z, qw, qx, qy, qz] more (the orientation/quaternion part) - Q(0, 0) = 1.0; - Q(1, 1) = 1.0; - Q(2, 2) = 1.0; - Q(3, 3) = 1.0; - Q(4, 4) = 1.0; - Q(5, 5) = 1.0; - Q(6, 6) = 1.0; - - Eigen::MatrixXd R = 0.01 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 1.0; - Qf(1, 1) = 1.0; - Qf(2, 2) = 1.0; - Qf(3, 3) = 1.0; - Qf(4, 4) = 1.0; - Qf(5, 5) = 1.0; - Qf(6, 6) = 1.0; - - // Figure-8 trajectory parameters - double figure8_scale = 3.0; - double constant_altitude = 2.0; - double constant_y = 2.0; - double total_time = horizon * timestep; - double omega = 2.0 * M_PI / total_time; // completes 1 cycle over the horizon - - std::vector figure8_reference_states; - figure8_reference_states.reserve(horizon + 1); - - - for (int i = 0; i <= horizon; ++i) - { - double t = i * timestep; - double angle = omega * t; - - // Create a reference state of dimension state_dim (13) - Eigen::VectorXd ref_state = Eigen::VectorXd::Zero(state_dim); - - // Position (x, y, z) using a vertical lemniscate of Gerono in the x–z plane: - // x = figure8_scale * cos(angle) - // y = constant_y (fixed) - // z = constant_altitude + figure8_scale * sin(angle) * cos(angle) - ref_state(0) = figure8_scale * std::cos(angle); - ref_state(1) = constant_y; - ref_state(2) = constant_altitude + figure8_scale * std::sin(angle) * std::cos(angle); - - // Orientation: set to identity quaternion [1, 0, 0, 0] - ref_state(3) = 1.0; // qw - ref_state(4) = 0.0; // qx - ref_state(5) = 0.0; // qy - ref_state(6) = 0.0; // qz - - figure8_reference_states.push_back(ref_state); - } - - // Goal state: hover at the starting point of the figure-8 (x = figure8_scale, y = constant_y, z = constant_altitude) - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state(0) = figure8_scale; - goal_state(1) = constant_y; - goal_state(2) = constant_altitude; - goal_state(3) = 1.0; // Identity quaternion: qw = 1 - - auto objective = std::make_unique( - Q, R, Qf, goal_state, figure8_reference_states, timestep); - - // Initial state (at the start of the figure-8) - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state(0) = figure8_scale; - initial_state(1) = constant_y; - initial_state(2) = constant_altitude; - initial_state(3) = 1.0; // Identity quaternion: qw = 1 - - // Solver options - cddp::CDDPOptions options; - options.max_iterations = 10000; - options.verbose = true; - options.debug = false; - options.enable_parallel = true; - options.num_threads = 10; - options.tolerance = 1e-3; - options.regularization.initial_value = 1e-4; - options.ipddp.barrier.mu_initial = 1e-3; - - // Create the CDDP solver - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::move(system), - std::move(objective), - options); - - // Control constraints (motor thrust limits) - double min_force = 0.0; // Motors can only produce upward thrust - double max_force = 4.0; // Maximum thrust per motor - Eigen::VectorXd control_upper_bound = max_force * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_lower_bound = min_force * Eigen::VectorXd::Ones(control_dim); - cddp_solver.addPathConstraint("ControlConstraint", std::make_unique(-control_upper_bound, control_upper_bound)); - - // Initial trajectory: allocate state and control trajectories - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Initialize with hovering thrust (each motor provides mg/4) - double hover_thrust = mass * 9.81 / 4.0; - for (auto &u : U) - { - u = hover_thrust * Eigen::VectorXd::Ones(control_dim); - } - // Propagate initial trajectory using discrete dynamics - for (size_t i = 0; i < static_cast(horizon); ++i) - { - X[i + 1] = quadrotor.getDiscreteDynamics(X[i], U[i], i * timestep); - } - cddp_solver.setInitialTrajectory(X, U); - - // Solve the optimal control problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::cout << "Final state: " << X_sol.back().transpose() << std::endl; - - // Create plot directory if it doesn't exist - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - // Create a directory for frame images. - (void)std::system("mkdir -p frames"); - - // Extract trajectory data - std::vector time_arr, x_arr, y_arr, z_arr; - std::vector phi_arr, theta_arr, psi_arr; - std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - time_arr.reserve(X_sol.size()); - x_arr.reserve(X_sol.size()); - y_arr.reserve(X_sol.size()); - z_arr.reserve(X_sol.size()); - phi_arr.reserve(X_sol.size()); - theta_arr.reserve(X_sol.size()); - psi_arr.reserve(X_sol.size()); - - qw_arr.reserve(X_sol.size()); - qx_arr.reserve(X_sol.size()); - qy_arr.reserve(X_sol.size()); - qz_arr.reserve(X_sol.size()); - q_norm_arr.reserve(X_sol.size()); - - for (size_t i = 0; i < X_sol.size(); ++i) - { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - - double qw = X_sol[i](3); - double qx = X_sol[i](4); - double qy = X_sol[i](5); - double qz = X_sol[i](6); - - // Euler angles - Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - phi_arr.push_back(euler(0)); - theta_arr.push_back(euler(1)); - psi_arr.push_back(euler(2)); - - // Quaternion data - qw_arr.push_back(qw); - qx_arr.push_back(qx); - qy_arr.push_back(qy); - qz_arr.push_back(qz); - q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - } - - // Control data - std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - std::vector f1_arr, f2_arr, f3_arr, f4_arr; - f1_arr.reserve(U_sol.size()); - f2_arr.reserve(U_sol.size()); - f3_arr.reserve(U_sol.size()); - f4_arr.reserve(U_sol.size()); - - for (const auto &u : U_sol) - { - f1_arr.push_back(u(0)); - f2_arr.push_back(u(1)); - f3_arr.push_back(u(2)); - f4_arr.push_back(u(3)); - } - - // Plotting - auto f1 = figure(); - f1->size(1200, 900); // Slightly bigger if you like - - // (1) Position - auto ax1_f1 = subplot(4, 1, 0); - auto plot_handle1 = plot(ax1_f1, time_arr, x_arr, "-r"); - plot_handle1->display_name("x"); - plot_handle1->line_width(2); - hold(ax1_f1, true); - auto plot_handle2 = plot(ax1_f1, time_arr, y_arr, "-g"); - plot_handle2->display_name("y"); - plot_handle2->line_width(2); - auto plot_handle3 = plot(ax1_f1, time_arr, z_arr, "-b"); - plot_handle3->display_name("z"); - plot_handle3->line_width(2); - - title(ax1_f1, "Position Trajectories"); - xlabel(ax1_f1, "Time [s]"); - ylabel(ax1_f1, "Position [m]"); - matplot::legend(ax1_f1); - grid(ax1_f1, true); - - // (2) Attitude (Euler angles) - auto ax2_f1 = subplot(4, 1, 1); - hold(ax2_f1, true); - auto plot_handle4 = plot(ax2_f1, time_arr, phi_arr, "-r"); - plot_handle4->display_name("roll"); - plot_handle4->line_width(2); - auto plot_handle5 = plot(ax2_f1, time_arr, theta_arr, "-g"); - plot_handle5->display_name("pitch"); - plot_handle5->line_width(2); - auto plot_handle6 = plot(ax2_f1, time_arr, psi_arr, "-b"); - plot_handle6->display_name("yaw"); - plot_handle6->line_width(2); - - title(ax2_f1, "Attitude Angles"); - xlabel(ax2_f1, "Time [s]"); - ylabel(ax2_f1, "Angle [rad]"); - matplot::legend(ax2_f1); - grid(ax2_f1, true); - - // (3) Motor forces - auto ax3_f1 = subplot(4, 1, 2); - auto plot_handle7 = plot(ax3_f1, time_arr2, f1_arr, "-r"); - plot_handle7->display_name("f1"); - plot_handle7->line_width(2); - hold(ax3_f1, true); - auto plot_handle8 = plot(ax3_f1, time_arr2, f2_arr, "-g"); - plot_handle8->display_name("f2"); - plot_handle8->line_width(2); - auto plot_handle9 = plot(ax3_f1, time_arr2, f3_arr, "-b"); - plot_handle9->display_name("f3"); - plot_handle9->line_width(2); - auto plot_handle10 = plot(ax3_f1, time_arr2, f4_arr, "-k"); - plot_handle10->display_name("f4"); - plot_handle10->line_width(2); - - title(ax3_f1, "Motor Forces"); - xlabel(ax3_f1, "Time [s]"); - ylabel(ax3_f1, "Force [N]"); - matplot::legend(ax3_f1); - grid(ax3_f1, true); - - // (4) Quaternion trajectories and norm - auto ax4_f1 = subplot(4, 1, 3); - hold(ax4_f1, true); - - auto qwh = plot(ax4_f1, time_arr, qw_arr, "-r"); - qwh->display_name("q_w"); - qwh->line_width(2); - - auto qxh = plot(ax4_f1, time_arr, qx_arr, "-g"); - qxh->display_name("q_x"); - qxh->line_width(2); - - auto qyh = plot(ax4_f1, time_arr, qy_arr, "-b"); - qyh->display_name("q_y"); - qyh->line_width(2); - - auto qzh = plot(ax4_f1, time_arr, qz_arr, "-m"); - qzh->display_name("q_z"); - qzh->line_width(2); - - // Norm in black - auto qnorm_handle = plot(ax4_f1, time_arr, q_norm_arr, "-k"); - qnorm_handle->display_name("|q|"); - - title(ax4_f1, "Quaternion Components and Norm"); - xlabel(ax4_f1, "Time [s]"); - ylabel(ax4_f1, "Value"); - matplot::legend(ax4_f1); - grid(ax4_f1, true); - - // Save figure 1 - f1->draw(); - f1->save(plotDirectory + "/quadrotor_figure_eight_vertical_states.png"); - - // 3D Trajectory - auto f2 = figure(); - f2->size(800, 600); - auto ax2 = f2->current_axes(); - hold(ax2, true); - auto traj3d = plot3(ax2, x_arr, y_arr, z_arr); - traj3d->display_name("Trajectory"); - traj3d->line_style("-"); - traj3d->line_width(2); - traj3d->color("blue"); - // Project trajectory onto x-y plane at z=0 - auto proj_xy = plot3(ax2, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - proj_xy->display_name("X-Y Projection"); - proj_xy->line_style("--"); - proj_xy->line_width(1); - proj_xy->color("gray"); - xlabel(ax2, "X [m]"); - ylabel(ax2, "Y [m]"); - zlabel(ax2, "Z [m]"); - xlim(ax2, {-5, 5}); - ylim(ax2, {0, 5}); - zlim(ax2, {-5, 5}); - title(ax2, "3D Trajectory (Figure-8)"); - grid(ax2, true); - f2->draw(); - f2->save(plotDirectory + "/quadrotor_figure_eight_vertical_3d.png"); - - // Animation of the quadrotor frame - auto f_anim = figure(); - f_anim->size(800, 600); - auto ax_anim = f_anim->current_axes(); - - // For collecting the trajectory as we go - std::vector anim_x, anim_y, anim_z; - anim_x.reserve(X_sol.size()); - anim_y.reserve(X_sol.size()); - anim_z.reserve(X_sol.size()); - - // Render every Nth frame to reduce #images - int frame_stride = 15; - double prop_radius = 0.03; // radius for small spheres at motor ends - - for (size_t i = 0; i < X_sol.size(); i += frame_stride) - { - ax_anim->clear(); - ax_anim->hold(true); - ax_anim->grid(true); - - // Current state - double x = X_sol[i](0); - double y = X_sol[i](1); - double z = X_sol[i](2); - - // Accumulate path - anim_x.push_back(x); - anim_y.push_back(y); - anim_z.push_back(z); - - // Plot the partial trajectory so far (in black dotted line) - auto path_plot = plot3(anim_x, anim_y, anim_z); - path_plot->line_width(1.5); - path_plot->line_style("--"); - path_plot->color("black"); - - // Build rotation from quaternion - Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // Arm endpoints (front, right, back, left) - std::vector arm_endpoints; - arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // Transform to world coords - for (auto &pt : arm_endpoints) - { - pt = Eigen::Vector3d(x, y, z) + R * pt; - } - - // Front-back arm - std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - auto fb_arm = plot3(fx, fy, fz); - fb_arm->line_width(2.0); - fb_arm->color("blue"); - - // Right-left arm - std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - auto rl_arm = plot3(rx, ry, rz); - rl_arm->line_width(2.0); - rl_arm->color("red"); - - auto sphere_points = linspace(0, 2 * M_PI, 15); - for (const auto &motor_pos : arm_endpoints) - { - std::vector circ_x, circ_y, circ_z; - circ_x.reserve(sphere_points.size()); - circ_y.reserve(sphere_points.size()); - circ_z.reserve(sphere_points.size()); - for (auto angle : sphere_points) - { - circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - circ_z.push_back(motor_pos.z()); // keep the same z for a small ring - } - auto sphere_plot = plot3(circ_x, circ_y, circ_z); - sphere_plot->line_style("solid"); - sphere_plot->line_width(1.5); - sphere_plot->color("cyan"); - } - - title(ax_anim, "Quadrotor Animation"); - xlabel(ax_anim, "X [m]"); - ylabel(ax_anim, "Y [m]"); - zlabel(ax_anim, "Z [m]"); - xlim(ax_anim, {-5, 5}); - ylim(ax_anim, {0, 5}); - - ax_anim->view(30, -30); - - std::string frameFile = plotDirectory + "/quadrotor_anim_frame_" + std::to_string(i / frame_stride) + ".png"; - f_anim->draw(); - f_anim->save(frameFile); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_anim_frame_*.png " + plotDirectory + "/quadrotor_figure_eight_vertical.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_anim_frame_*.png"; - std::system(cleanup_command.c_str()); - - return 0; -} diff --git a/examples/cddp_quadrotor_point.cpp b/examples/cddp_quadrotor_point.cpp index 42fb07dc..5346d977 100644 --- a/examples/cddp_quadrotor_point.cpp +++ b/examples/cddp_quadrotor_point.cpp @@ -13,507 +13,99 @@ See the License for the specific language governing permissions and limitations under the License. */ + #include #include -#include -#include -#include #include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -// Helper function: Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Helper function: Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - return R; -} - -// Helper: Transform quadrotor frame points (motor positions) to world coordinates using quaternion. -std::vector> transformQuadrotorFrame( - const Eigen::Vector3d &position, - const Eigen::Vector4d &quat, // [qw, qx, qy, qz] - double arm_length) -{ - - // Define quadrotor motor positions in the body frame - std::vector body_points = { - Eigen::Vector3d(arm_length, 0, 0), // Front motor - Eigen::Vector3d(0, arm_length, 0), // Right motor - Eigen::Vector3d(-arm_length, 0, 0), // Back motor - Eigen::Vector3d(0, -arm_length, 0) // Left motor - }; - - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat[0], quat[1], quat[2], quat[3]); - - std::vector> world_points(3, std::vector()); - for (const auto &pt : body_points) - { - Eigen::Vector3d wp = position + R * pt; - world_points[0].push_back(wp.x()); - world_points[1].push_back(wp.y()); - world_points[2].push_back(wp.z()); - } - return world_points; -} - -int main() -{ - // For quaternion-based quadrotor, state_dim = 13: - // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - int state_dim = 13; - int control_dim = 4; // [f1, f2, f3, f4] - int horizon = 200; // Longer horizon for 3D maneuvers - double timestep = 0.02; +int main() { + constexpr int state_dim = 13; + constexpr int control_dim = 4; + constexpr int horizon = 120; + constexpr double timestep = 0.02; - // Quadrotor parameters - double mass = 1.0; // 1kg quadrotor - double arm_length = 0.2; // 20cm arm length - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 0.01; // Ixx - inertia_matrix(1, 1) = 0.01; // Iyy - inertia_matrix(2, 2) = 0.02; // Izz + const double mass = 1.0; + const double arm_length = 0.2; + Eigen::Matrix3d inertia = Eigen::Matrix3d::Zero(); + inertia(0, 0) = 0.01; + inertia(1, 1) = 0.01; + inertia(2, 2) = 0.02; - std::string integration_type = "rk4"; - - // Create the dynamical system (quadrotor) as a unique_ptr - std::unique_ptr system = - std::make_unique(timestep, mass, inertia_matrix, arm_length, integration_type); + Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); + initial_state(3) = 1.0; - // For propagation (e.g., initial trajectory), also create an instance (if needed) - cddp::Quadrotor quadrotor(timestep, mass, inertia_matrix, arm_length, integration_type); + Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); + goal_state(0) = 3.0; + goal_state(2) = 2.0; + goal_state(3) = 1.0; - // Cost matrices (dimensions updated for state_dim = 13) Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); Q(4, 4) = 0.1; Q(5, 5) = 0.1; Q(6, 6) = 0.1; - // Control cost matrix (penalize aggressive control inputs) Eigen::MatrixXd R = 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); - // Terminal cost matrix (important for stability) Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 500.0; // x position - Qf(1, 1) = 500.0; // y position - Qf(2, 2) = 500.0; // z position - // For orientation (quaternion) we penalize deviation from identity quaternion - Qf(3, 3) = 1.0; // qw - Qf(4, 4) = 1.0; // qx - Qf(5, 5) = 1.0; // qy - Qf(6, 6) = 1.0; // qz - Qf(7, 7) = 10.0; // x velocity - Qf(8, 8) = 10.0; // y velocity - Qf(9, 9) = 10.0; // z velocity - // Qf(10, 10) = 0.1; // roll rate - // Qf(11, 11) = 0.1; // pitch rate - // Qf(12, 12) = 0.1; // yaw rate - - // Goal state: hover at position (3,0,2) with identity quaternion and zero velocities. - Eigen::VectorXd goal_state = Eigen::VectorXd::Zero(state_dim); - goal_state(0) = 3.0; // x - goal_state(2) = 2.0; // z - // Set identity quaternion [1, 0, 0, 0] - goal_state(3) = 1.0; - goal_state(4) = 0.0; - goal_state(5) = 0.0; - goal_state(6) = 0.0; + Qf(0, 0) = 500.0; + Qf(1, 1) = 500.0; + Qf(2, 2) = 500.0; + Qf(3, 3) = 1.0; + Qf(4, 4) = 1.0; + Qf(5, 5) = 1.0; + Qf(6, 6) = 1.0; + Qf(7, 7) = 10.0; + Qf(8, 8) = 10.0; + Qf(9, 9) = 10.0; - // No intermediate reference states (optional) - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state (at origin with identity quaternion) - Eigen::VectorXd initial_state = Eigen::VectorXd::Zero(state_dim); - initial_state(3) = 1.0; // Identity quaternion: qw = 1 - - // Solver options cddp::CDDPOptions options; - options.max_iterations = 2000; + options.max_iterations = 120; options.line_search.max_iterations = 15; options.regularization.initial_value = 1e-4; - // Create the CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Control constraints (motor thrust limits) - double min_force = 0.0; // Motors can only produce thrust upward - double max_force = 5.0; // Maximum thrust per motor - Eigen::VectorXd control_lower_bound = min_force * Eigen::VectorXd::Ones(control_dim); - Eigen::VectorXd control_upper_bound = max_force * Eigen::VectorXd::Ones(control_dim); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // Initial trajectory: allocate state and control trajectories + cddp::CDDP solver( + initial_state, + goal_state, + horizon, + timestep, + std::make_unique( + timestep, mass, inertia, arm_length, "rk4"), + std::make_unique( + Q, R, Qf, goal_state, std::vector{}, timestep), + options); + + const Eigen::VectorXd lower = + Eigen::VectorXd::Zero(control_dim); + const Eigen::VectorXd upper = + 5.0 * Eigen::VectorXd::Ones(control_dim); + solver.addPathConstraint("ControlConstraint", + std::make_unique(lower, upper)); + + cddp::Quadrotor propagation_model(timestep, mass, inertia, arm_length, "rk4"); std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - - // Initialize with hovering thrust (each motor provides mg/4) - double hover_thrust = mass * 9.81 / 4.0; - for (auto &u : U) - { + X[0] = initial_state; + const double hover_thrust = mass * 9.81 / 4.0; + for (auto &u : U) { u = hover_thrust * Eigen::VectorXd::Ones(control_dim); } - // Propagate initial trajectory using discrete dynamics - for (size_t i = 0; i < static_cast(horizon); ++i) - { - X[i + 1] = quadrotor.getDiscreteDynamics(X[i], U[i], i * timestep); - } - cddp_solver.setInitialTrajectory(X, U); - - // Solve the optimal control problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - const auto& X_sol = solution.state_trajectory; - const auto& U_sol = solution.control_trajectory; - const auto& t_sol = solution.time_points; - - std::cout << "Final state: " << X_sol.back().transpose() << std::endl; - - // Create plot directory if it doesn't exist - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - // Create a directory for frame images. - (void)std::system("mkdir -p frames"); - - // Extract trajectory data - std::vector time_arr, x_arr, y_arr, z_arr; - std::vector phi_arr, theta_arr, psi_arr; - std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - time_arr.reserve(X_sol.size()); - x_arr.reserve(X_sol.size()); - y_arr.reserve(X_sol.size()); - z_arr.reserve(X_sol.size()); - phi_arr.reserve(X_sol.size()); - theta_arr.reserve(X_sol.size()); - psi_arr.reserve(X_sol.size()); - - qw_arr.reserve(X_sol.size()); - qx_arr.reserve(X_sol.size()); - qy_arr.reserve(X_sol.size()); - qz_arr.reserve(X_sol.size()); - q_norm_arr.reserve(X_sol.size()); - - for (size_t i = 0; i < X_sol.size(); ++i) - { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - - double qw = X_sol[i](3); - double qx = X_sol[i](4); - double qy = X_sol[i](5); - double qz = X_sol[i](6); - - // Euler angles - Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - phi_arr.push_back(euler(0)); - theta_arr.push_back(euler(1)); - psi_arr.push_back(euler(2)); - - // Quaternion data - qw_arr.push_back(qw); - qx_arr.push_back(qx); - qy_arr.push_back(qy); - qz_arr.push_back(qz); - q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - } - - // Control data - std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - std::vector f1_arr, f2_arr, f3_arr, f4_arr; - f1_arr.reserve(U_sol.size()); - f2_arr.reserve(U_sol.size()); - f3_arr.reserve(U_sol.size()); - f4_arr.reserve(U_sol.size()); - - for (const auto &u : U_sol) - { - f1_arr.push_back(u(0)); - f2_arr.push_back(u(1)); - f3_arr.push_back(u(2)); - f4_arr.push_back(u(3)); + for (int i = 0; i < horizon; ++i) { + X[i + 1] = propagation_model.getDiscreteDynamics(X[i], U[i], i * timestep); } + solver.setInitialTrajectory(X, U); - // Plotting - auto f1 = figure(); - f1->size(1200, 900); // Slightly bigger if you like - - // (1) Position - auto ax1_f1 = subplot(4, 1, 0); - auto plot_handle1 = plot(ax1_f1, time_arr, x_arr, "-r"); - plot_handle1->display_name("x"); - plot_handle1->line_width(2); - hold(ax1_f1, true); - auto plot_handle2 = plot(ax1_f1, time_arr, y_arr, "-g"); - plot_handle2->display_name("y"); - plot_handle2->line_width(2); - auto plot_handle3 = plot(ax1_f1, time_arr, z_arr, "-b"); - plot_handle3->display_name("z"); - plot_handle3->line_width(2); - - title(ax1_f1, "Position Trajectories"); - xlabel(ax1_f1, "Time [s]"); - ylabel(ax1_f1, "Position [m]"); - matplot::legend(ax1_f1); - grid(ax1_f1, true); - - // (2) Attitude (Euler angles) - auto ax2_f1 = subplot(4, 1, 1); - hold(ax2_f1, true); - auto plot_handle4 = plot(ax2_f1, time_arr, phi_arr, "-r"); - plot_handle4->display_name("roll"); - plot_handle4->line_width(2); - auto plot_handle5 = plot(ax2_f1, time_arr, theta_arr, "-g"); - plot_handle5->display_name("pitch"); - plot_handle5->line_width(2); - auto plot_handle6 = plot(ax2_f1, time_arr, psi_arr, "-b"); - plot_handle6->display_name("yaw"); - plot_handle6->line_width(2); - - title(ax2_f1, "Attitude Angles"); - xlabel(ax2_f1, "Time [s]"); - ylabel(ax2_f1, "Angle [rad]"); - matplot::legend(ax2_f1); - grid(ax2_f1, true); - - // (3) Motor forces - auto ax3_f1 = subplot(4, 1, 2); - auto plot_handle7 = plot(ax3_f1, time_arr2, f1_arr, "-r"); - plot_handle7->display_name("f1"); - plot_handle7->line_width(2); - hold(ax3_f1, true); - auto plot_handle8 = plot(ax3_f1, time_arr2, f2_arr, "-g"); - plot_handle8->display_name("f2"); - plot_handle8->line_width(2); - auto plot_handle9 = plot(ax3_f1, time_arr2, f3_arr, "-b"); - plot_handle9->display_name("f3"); - plot_handle9->line_width(2); - auto plot_handle10 = plot(ax3_f1, time_arr2, f4_arr, "-k"); - plot_handle10->display_name("f4"); - plot_handle10->line_width(2); - - title(ax3_f1, "Motor Forces"); - xlabel(ax3_f1, "Time [s]"); - ylabel(ax3_f1, "Force [N]"); - matplot::legend(ax3_f1); - grid(ax3_f1, true); - - // (4) Quaternion trajectories and norm - auto ax4_f1 = subplot(4, 1, 3); - hold(ax4_f1, true); - - auto qwh = plot(ax4_f1, time_arr, qw_arr, "-r"); - qwh->display_name("q_w"); - qwh->line_width(2); - - auto qxh = plot(ax4_f1, time_arr, qx_arr, "-g"); - qxh->display_name("q_x"); - qxh->line_width(2); - - auto qyh = plot(ax4_f1, time_arr, qy_arr, "-b"); - qyh->display_name("q_y"); - qyh->line_width(2); - - auto qzh = plot(ax4_f1, time_arr, qz_arr, "-m"); - qzh->display_name("q_z"); - qzh->line_width(2); - - // Norm in black - auto qnorm_handle = plot(ax4_f1, time_arr, q_norm_arr, "-k"); - qnorm_handle->display_name("|q|"); - - title(ax4_f1, "Quaternion Components and Norm"); - xlabel(ax4_f1, "Time [s]"); - ylabel(ax4_f1, "Value"); - matplot::legend(ax4_f1); - grid(ax4_f1, true); - - // Save figure 1 - f1->draw(); - f1->save(plotDirectory + "/quadrotor_point_states.png"); - - // 3D Trajectory - auto f2 = figure(); - f2->size(800, 600); - auto ax2 = f2->current_axes(); - hold(ax2, true); - auto traj3d = plot3(ax2, x_arr, y_arr, z_arr); - traj3d->display_name("Trajectory"); - traj3d->line_style("-"); - traj3d->line_width(2); - traj3d->color("blue"); - // Project trajectory onto x-y plane at z=0 - auto proj_xy = plot3(ax2, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - proj_xy->display_name("X-Y Projection"); - proj_xy->line_style("--"); - proj_xy->line_width(1); - proj_xy->color("gray"); - xlabel(ax2, "X [m]"); - ylabel(ax2, "Y [m]"); - zlabel(ax2, "Z [m]"); - xlim(ax2, {0, 5}); - ylim(ax2, {-2, 2}); - zlim(ax2, {0, 5}); - title(ax2, "3D Trajectory (Figure-8)"); - grid(ax2, true); - f2->draw(); - f2->save(plotDirectory + "/quadrotor_point_3d.png"); - - // Animation of the quadrotor frame - auto f_anim = figure(); - f_anim->size(800, 600); - auto ax_anim = f_anim->current_axes(); - - // For collecting the trajectory as we go - std::vector anim_x, anim_y, anim_z; - anim_x.reserve(X_sol.size()); - anim_y.reserve(X_sol.size()); - anim_z.reserve(X_sol.size()); - - // Render every Nth frame to reduce #images - int frame_stride = 15; - double prop_radius = 0.03; // radius for small spheres at motor ends - - for (size_t i = 0; i < X_sol.size(); i += frame_stride) - { - ax_anim->clear(); - ax_anim->hold(true); - ax_anim->grid(true); - - // Current state - double x = X_sol[i](0); - double y = X_sol[i](1); - double z = X_sol[i](2); - - // Accumulate path - anim_x.push_back(x); - anim_y.push_back(y); - anim_z.push_back(z); - - // Plot the partial trajectory so far (in black dotted line) - auto path_plot = plot3(anim_x, anim_y, anim_z); - path_plot->line_width(1.5); - path_plot->line_style("--"); - path_plot->color("black"); - - // Build rotation from quaternion - Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // Arm endpoints (front, right, back, left) - std::vector arm_endpoints; - arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // Transform to world coords - for (auto &pt : arm_endpoints) - { - pt = Eigen::Vector3d(x, y, z) + R * pt; - } - - // Front-back arm - std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - auto fb_arm = plot3(fx, fy, fz); - fb_arm->line_width(2.0); - fb_arm->color("blue"); - - // Right-left arm - std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - auto rl_arm = plot3(rx, ry, rz); - rl_arm->line_width(2.0); - rl_arm->color("red"); - - auto sphere_points = linspace(0, 2 * M_PI, 15); - for (const auto &motor_pos : arm_endpoints) - { - std::vector circ_x, circ_y, circ_z; - circ_x.reserve(sphere_points.size()); - circ_y.reserve(sphere_points.size()); - circ_z.reserve(sphere_points.size()); - for (auto angle : sphere_points) - { - circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - circ_z.push_back(motor_pos.z()); // keep the same z for a small ring - } - auto sphere_plot = plot3(circ_x, circ_y, circ_z); - sphere_plot->line_style("solid"); - sphere_plot->line_width(1.5); - sphere_plot->color("cyan"); - } - - title(ax_anim, "Quadrotor Animation"); - xlabel(ax_anim, "X [m]"); - ylabel(ax_anim, "Y [m]"); - zlabel(ax_anim, "Z [m]"); - xlim(ax_anim, {0, 5}); - ylim(ax_anim, {-5, 5}); - zlim(ax_anim, {0, 5}); - - ax_anim->view(30, -30); - - std::string frameFile = plotDirectory + "/quadrotor_anim_frame_" + std::to_string(i / frame_stride) + ".png"; - f_anim->draw(); - f_anim->save(frameFile); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); + const cddp::CDDPSolution solution = solver.solve(cddp::SolverType::IPDDP); + if (solution.state_trajectory.empty()) { + std::cerr << "Quadrotor example failed: empty trajectory" << std::endl; + return 1; } - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_anim_frame_*.png " + plotDirectory + "/quadrotor_point.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_anim_frame_*.png"; - std::system(cleanup_command.c_str()); + const Eigen::VectorXd final_error = solution.state_trajectory.back() - goal_state; + std::cout << "Quadrotor example completed with status: " + << solution.status_message << '\n' + << "Final objective: " << solution.final_objective << '\n' + << "Final position error norm: " << final_error.head(3).norm() + << std::endl; return 0; } - -// To create a gif from the saved frames, use ImageMagick (for example): -// convert -delay 5 ../results/tests/quadrotor_frame_*.png ../results/tests/quadrotor.gif diff --git a/examples/cddp_spacecraft_linear_docking.cpp b/examples/cddp_spacecraft_linear_docking.cpp deleted file mode 100644 index 85addef8..00000000 --- a/examples/cddp_spacecraft_linear_docking.cpp +++ /dev/null @@ -1,350 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -namespace fs = std::filesystem; -using namespace cddp; - -int main() { - // ========================================================================= - // 1) Parameters for Trajectory Optimization - // ========================================================================= - - // Optimization horizon info - int N = 400; // Optimization horizon length - double time_horizon = 400.0; // Time horizon for optimization [s] - double dt = time_horizon / N; // Time step for optimization - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - - // Initial state - Eigen::VectorXd initial_state(6); - initial_state << 25.0, 25.0 / std::sqrt(3.0)-0.1, 0.0, 0.0, 0.0, 0.0; - - // Final (reference/goal) state - Eigen::VectorXd goal_state(6); - goal_state.setZero(); // Goal is the origin - - // Input constraints - double u_max = 1.0; // for each dimension - double u_min = -1.0; // for each dimension - - // Cost weighting - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(6,6); - Q.diagonal() << 1e+1, 1e+1, 1e+1, 1e-0, 1e-0, 1e-0; - - Eigen::MatrixXd R = Eigen::MatrixXd::Zero(3,3); - R.diagonal() << 1e-0, 1e-0, 1e-0; - - // Terminal cost - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(6,6); - // Qf.diagonal() << 1e3, 1e3, 1e3, 1e1, 1e1, 1e1; - - // ========================================================================= - // 2) Setup Solver and Solve the Optimization Problem Once - // ========================================================================= - - // Create the HCW system for optimization - std::unique_ptr hcw_system = - std::make_unique(dt, mean_motion, mass, "euler"); - - // Build cost objective - std::vector empty_reference; // No intermediate reference states needed - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference, dt - ); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 500; // May need more iterations for one-shot solve - options.line_search.max_iterations = 21; - options.tolerance = 1e-5; // Tighter tolerance for final solve - options.verbose = true; // Show solver progress - options.enable_parallel = false; - options.num_threads = 8; - options.regularization.initial_value = 1e-5; - options.ipddp.barrier.mu_initial = 1e-1; // Starting barrier coefficient - - // ========================================================================= - // 2.1) Solve Unconstrained Problem for Initial Guess - // ========================================================================= - std::cout << "Solving unconstrained problem for initial guess using iLQR..." << std::endl; - - // Create a separate system and objective for the initial solve (or clone) - std::unique_ptr hcw_system_init = - std::make_unique(dt, mean_motion, mass, "euler"); - std::vector empty_reference_init; // No intermediate reference states needed - auto objective_init = std::make_unique( - Q, R, Qf, goal_state, empty_reference_init, dt - ); - - // Use simpler options for the initial guess solve - cddp::CDDPOptions options_init = options; // Copy base options - options_init.max_iterations = 100; // Fewer iterations might suffice - options_init.tolerance = 1e-4; // Looser tolerance - options_init.verbose = false; // Less verbose for initial solve - options_init.regularization.initial_value = 1e-4; - - cddp::CDDP cddp_solver_init(/*initial_state=*/initial_state, - /*goal_state=*/goal_state, - /*horizon=*/N, - /*timestep=*/dt, - /*system=*/std::move(hcw_system_init), - /*objective=*/std::move(objective_init), - /*options=*/options_init); - - // Simple linear interpolation guess for the initial solve - std::vector X_linear_init(N + 1, Eigen::VectorXd::Zero(6)); - std::vector U_zero_init(N, Eigen::VectorXd::Zero(3)); - for (int k = 0; k < N + 1; ++k) { - X_linear_init[k] = initial_state + (goal_state - initial_state) * (double(k) / N); - } - cddp_solver_init.setInitialTrajectory(X_linear_init, U_zero_init); - - // Solve the unconstrained problem (e.g., using IPDDP) - cddp::CDDPSolution initial_solution = cddp_solver_init.solve("IPDDP"); - - const auto& initial_states = initial_solution.state_trajectory; - if (initial_states.empty()) { - std::cerr << "Failed to find an initial guess solution. Exiting." << std::endl; - return 1; - } - - // ========================================================================= - // 2.2) Setup Constrained Solver (IPDDP) and Solve - // ========================================================================= - std::cout << "Setting up and solving the constrained problem using IPDDP..." << std::endl; - - // Setup CDDP solver instance (using IPDDP) - cddp::CDDP cddp_solver(/*initial_state=*/initial_state, - /*goal_state=*/goal_state, // Pass goal state (used by objective) - /*horizon=*/N, - /*timestep=*/dt, - /*system=*/std::move(hcw_system), // System ownership transferred - /*objective=*/std::move(objective), // Objective ownership transferred - /*options=*/options); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // Add Linear Constraints for X-Y Plane Cone Boundary (|y| <= x * tan(fov) for x >= 0) - // Constraint 1: -tan(fov)*x + y <= 0 - // Constraint 2: -tan(fov)*x - y <= 0 - Eigen::Vector3d origin(0.0, 0.0, 0.0); - Eigen::Vector3d axis(1.0, 0.0, 0.0); // Opening along positive X-axis - double fov = M_PI / 3.0; // 30 degrees half-angle - double tan_fov = std::tan(fov); - // Eigen::MatrixXd A_cone_xy(2, 6); - // A_cone_xy << -tan_fov, 1.0, 0.0, 0.0, 0.0, 0.0, // Row 1 - // -tan_fov, -1.0, 0.0, 0.0, 0.0, 0.0; // Row 2 - // Eigen::VectorXd b_cone_xy = Eigen::VectorXd::Zero(2); - // cddp_solver.addConstraint("ConeXYLinearConstraint", - // std::make_unique(A_cone_xy, b_cone_xy)); - - // Add Second Order Cone Constraint - cddp_solver.addPathConstraint("SecondOrderConeConstraint", - std::make_unique(origin, axis, fov, 1e-6)); - - // Initialize trajectory guess - // Use the solution from the unconstrained solve as the initial guess - const auto& X_init = initial_solution.state_trajectory; - const auto& U_init = initial_solution.control_trajectory; - - // Assign the initial trajectory guess to the solver - cddp_solver.setInitialTrajectory(X_init, U_init); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - - - // ========================================================================= - // 3) Visualize the Trajectory - // ========================================================================= - const auto& solution_states = solution.state_trajectory; - if (!solution_states.empty()) { - namespace plt = matplot; - - std::vector x_traj, y_traj, z_traj; - for (const auto& state : solution_states) { - if (state.size() >= 3) { // Ensure state has at least 3 dimensions (x, y, z) - x_traj.push_back(state(0)); - y_traj.push_back(state(1)); - z_traj.push_back(state(2)); - } - } - - auto fig = plt::figure(); - plt::plot3(x_traj, y_traj, z_traj, "-o")->line_width(2).marker_size(4); - plt::hold(true); - - // Plot start and end points - plt::plot3(std::vector{initial_state(0)}, std::vector{initial_state(1)}, std::vector{initial_state(2)}, "go") - ->marker_size(10).display_name("Start"); - plt::plot3(std::vector{goal_state(0)}, std::vector{goal_state(1)}, std::vector{goal_state(2)}, "rx") - ->marker_size(10).display_name("Goal"); - - plt::xlabel("X [m]"); - plt::ylabel("Y [m]"); - plt::zlabel("Z [m]"); - plt::title("Spacecraft Docking Trajectory"); - - // --- Add Cone Visualization (3D) --- - // Generate cone surface points (opening along +X) - double cone_x_min_vis = -5.0; // Min x-extent for visualization - double cone_x_max_vis = goal_state(0) + 5.0; // Max x-extent (a bit beyond goal) - if (!y_traj.empty()) { - // Adjust max based on trajectory, but min should start at origin for +Y side visualization - cone_x_max_vis = std::max(cone_x_max_vis, *std::max_element(x_traj.begin(), x_traj.end()) + 5.0); - } - // Start cone visualization from the origin's x-coordinate (for +X side) - double cone_x_start = origin(0); - cone_x_max_vis = std::max(cone_x_max_vis, cone_x_start + 1.0); // Ensure some minimum length - - std::vector x_cone_vals = plt::linspace(cone_x_start, cone_x_max_vis, 30); - std::vector theta_vals = plt::linspace(0, 2 * M_PI, 50); - auto [X_cone_grid, THETA_cone] = plt::meshgrid(x_cone_vals, theta_vals); // Grid X values - - // Find orthogonal vectors u, v to the axis (now X-axis) - Eigen::Vector3d u = Eigen::Vector3d(0.0, 1.0, 0.0); // Y-direction - Eigen::Vector3d v_ortho = Eigen::Vector3d(0.0, 0.0, 1.0); // Z-direction - - // Calculate Y, Z coordinates for the cone surface - std::vector> Y_cone(X_cone_grid.size(), std::vector(X_cone_grid[0].size())); - std::vector> Z_cone(X_cone_grid.size(), std::vector(X_cone_grid[0].size())); - - for (size_t i = 0; i < X_cone_grid.size(); ++i) { - for (size_t j = 0; j < X_cone_grid[0].size(); ++j) { - // Cone opening along positive X: radius depends on displacement from origin along axis - double x_disp = X_cone_grid[i][j] - origin(0); // x_disp will be >= 0 due to linspace start - - // Radius calculation based on positive displacement along the axis - double radius = x_disp * tan_fov; // No abs needed since x_disp >= 0 - double theta = THETA_cone[i][j]; - Eigen::Vector3d point_on_circle = radius * (std::cos(theta) * u + std::sin(theta) * v_ortho); - Eigen::Vector3d point = origin + axis * x_disp + point_on_circle; // Point relative to origin based on x_disp - // X_cone_grid[i][j] already holds the x value - Y_cone[i][j] = point.y(); - Z_cone[i][j] = point.z(); - } - } - - // Plot the cone surface - plt::surf(X_cone_grid, Y_cone, Z_cone)->face_alpha(0.3).edge_color("none").display_name("FOV Cone (+X)"); - // --- End Cone Visualization (3D) --- - - plt::legend(); - plt::grid(true); - plt::axis("equal"); // Keep aspect ratio for better visualization - plt::hold(false); - plt::show(); - - // Define plot directory and create if it doesn't exist - std::string plotDirectory = "../results/tests"; // Assuming run from build dir - if (!fs::exists(plotDirectory)) { - try { - fs::create_directories(plotDirectory); - } catch (const std::filesystem::filesystem_error& e) { - std::cerr << "Error creating directory \"" << plotDirectory << "\": " << e.what() << std::endl; - // Optionally handle the error, e.g., save to current dir instead - plotDirectory = "."; // Fallback to current directory - } - } - - std::string filename = plotDirectory + "/docking_trajectory.png"; - try { - plt::save(filename); - std::cout << "Saved trajectory visualization to " << filename << std::endl; - } catch (const std::runtime_error& e) { - std::cerr << "Error saving plot to \"" << filename << "\": " << e.what() << std::endl; - } - - // ========================================================================= - // 4) Visualize the Trajectory (X-Y Plane) - // ========================================================================= - auto fig_xy = plt::figure(); - plt::plot(x_traj, y_traj, "-o")->line_width(2).marker_size(4); - plt::hold(true); - - // Plot start and end points (2D) - plt::plot({initial_state(0)}, {initial_state(1)}, "go")->marker_size(10).display_name("Start"); - plt::plot({goal_state(0)}, {goal_state(1)}, "rx")->marker_size(10).display_name("Goal"); - - plt::xlabel("X [m]"); - plt::ylabel("Y [m]"); - plt::title("Spacecraft Docking Trajectory (X-Y Plane)"); - - // --- Add Cone Visualization (2D - X/Y Slice at Z=0) --- - // For cone opening along X-axis: Boundary lines are y = oy +/- (x - ox) * tan_fov - auto current_xlim = plt::xlim(); - // Use only the positive side x >= ox for the lines, consistent with 3D plot - double x_line_start = std::max(current_xlim[0], origin(0)); - double x_line_end = current_xlim[1]; - if (x_line_end <= x_line_start) { // Ensure valid range if xlim is weird - x_line_end = x_line_start + 1.0; - } - std::vector x_line_vals = {x_line_start, x_line_end}; - - // Adjust x values relative to origin for radius calculation - std::vector x_rel_origin = {x_line_vals[0] - origin(0), x_line_vals[1] - origin(0)}; - - // Line 1: y = oy + (x - ox) * tan_fov - std::vector y_line1 = {origin(1) + x_rel_origin[0] * tan_fov, origin(1) + x_rel_origin[1] * tan_fov}; - // Line 2: y = oy - (x - ox) * tan_fov - std::vector y_line2 = {origin(1) - x_rel_origin[0] * tan_fov, origin(1) - x_rel_origin[1] * tan_fov}; - - plt::plot(x_line_vals, y_line1, "k--")->line_width(1.5).display_name("Cone Boundary (X-Y)"); - plt::plot(x_line_vals, y_line2, "k--")->line_width(1.5); - // Ensure plot limits encompass the lines if needed (axis equal might handle it) - plt::xlim(current_xlim); // Restore xlim just in case plot adjusted it - // --- End Cone Visualization (2D) --- - - plt::legend(); - plt::grid(true); - plt::axis("equal"); - plt::xlim({-10.0, 30.0}); - plt::ylim({-10.0, 30.0}); - plt::hold(false); - plt::show(); - - std::string filename_xy = plotDirectory + "/docking_trajectory_xy.png"; - try { - plt::save(fig_xy, filename_xy); // Save the specific figure - std::cout << "Saved X-Y trajectory visualization to " << filename_xy << std::endl; - } catch (const std::runtime_error& e) { - std::cerr << "Error saving X-Y plot to \"" << filename_xy << "\": " << e.what() << std::endl; - } - - } else { - std::cerr << "Solution trajectory is empty, cannot visualize." << std::endl; - } - - - std::cout << "Trajectory optimization finished." << std::endl; - return 0; -} \ No newline at end of file diff --git a/examples/cddp_spacecraft_linear_rpo.cpp b/examples/cddp_spacecraft_linear_rpo.cpp deleted file mode 100644 index 5cb94a60..00000000 --- a/examples/cddp_spacecraft_linear_rpo.cpp +++ /dev/null @@ -1,372 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -namespace cddp -{ - class SumOfTwoNormObjective : public NonlinearObjective - { - public: - SumOfTwoNormObjective(const Eigen::VectorXd &goal_state, - double weight_running_control, - double weight_terminal_state, - double timestep) - : NonlinearObjective(timestep), - goal_state_(goal_state), - weight_running_control_(weight_running_control), - weight_terminal_state_(weight_terminal_state) - { - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int /*index*/) const override - { - double control_squared = control.squaredNorm(); - double control_norm = std::sqrt(control_squared + epsilon_); - return weight_running_control_ * control_norm; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return weight_terminal_state_ * state_error.squaredNorm(); - } - - // Analytical Gradients - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state.size()); // Or handle error appropriately if size unknown - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - if (norm_u < 1e-8) - { - return Eigen::VectorXd::Zero(control.size()); - } - return weight_running_control_ * control / norm_u; - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return 2.0 * weight_terminal_state_ * state_error; - } - - // Analytical Hessians - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state.size(), state.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - int control_dim = control.size(); - if (norm_u < 1e-8) - { - return weight_running_control_ * Eigen::MatrixXd::Identity(control_dim, control_dim) / 1e-8; // or a small value like 1.0 - } - Eigen::MatrixXd I = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd u_ut = control * control.transpose(); - return weight_running_control_ * (I / norm_u - u_ut / (norm_u * norm_u * norm_u)); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd &state, const Eigen::VectorXd &control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd & /*final_state*/) const override - { - int state_dim = goal_state_.size(); - return 2.0 * weight_terminal_state_ * Eigen::MatrixXd::Identity(state_dim, state_dim); - } - - private: - Eigen::VectorXd goal_state_; - double weight_running_control_; - double weight_terminal_state_; - double epsilon_ = 1e-5; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Optimization horizon info - int horizon = 500; // Optimization horizon length - double time_horizon = 10000.0; // Time horizon for optimization [s] - double dt = time_horizon / horizon; // Time step for optimization - int state_dim = 6; - int control_dim = 3; - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - - // Initial state (v-bar hold at 1km) - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, -1000.0, 0.0, 0.0, 0.0, 0.0; - - // Final (reference/goal) state (r-bar ) - Eigen::VectorXd goal_state(state_dim); - goal_state << -100.0, 0.0, 0.0, 0.0, 2*mean_motion*100.0, 0.0; - - // Input constraints - double u_max = 0.05; // for each dimension - double u_min = -0.05; // for each dimension - double u_min_norm = 0.0; // Minimum thrust magnitude - double u_max_norm = 0.05; // Maximum thrust magnitude, consistent with previous u_max - - // Cost weighting for SumOfTwoNormObjective - double weight_running_control = 1.0; // Example value - double weight_terminal_state = 1000.0; // Example value - - // Create the HCW system for optimization - std::unique_ptr hcw_system = - std::make_unique(dt, mean_motion, mass, "euler"); - - // Build cost objective - auto objective = std::make_unique( - goal_state, - weight_running_control, - weight_terminal_state, - dt); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 1000; // May need more iterations for one-shot solve - options.line_search.max_iterations = 21; - options.tolerance = 1e-7; // Tighter tolerance for final solve - options.verbose = true; // Show solver progress - options.enable_parallel = false; - options.num_threads = 8; - // Regularization type is now implicit in new API - options.regularization.initial_value = 1e-3; - options.ipddp.barrier.mu_initial = 1e-0; // Starting barrier coefficient - options.use_ilqr = true; - options.debug = false; - options.msipddp.segment_length = horizon; - options.msipddp.rollout_type = "nonlinear"; - - // Initial trajectory. - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - // Generate initial trajectory by constant initial state - for (int i = 0; i < horizon; ++i) - { - // X[i + 1] = hcw_system->getDiscreteDynamics(X[i], U[i]); - X[i+1] = initial_state; - } - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - dt, - std::move(hcw_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // // Add Thrust Magnitude Constraint - // cddp_solver.addConstraint("MaxThrustMagnitudeConstraint", - // std::make_unique(u_max_norm)); - - // Add Ball Constraint (for keep-out zone) - double radius = 90.0; - Eigen::Vector2d center(0.0, 0.0); - // cddp_solver.addConstraint("BallConstraint", - // std::make_unique(radius, center, 0.1)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract the solution - const auto& X_solution = solution.state_trajectory; - const auto& U_solution = solution.control_trajectory; - - if (!X_solution.empty() && !U_solution.empty()) - { - namespace plt = matplot; - - // Create time vectors - std::vector t_states(horizon + 1); - for(int i = 0; i <= horizon; ++i) t_states[i] = i * dt; - - std::vector t_controls(horizon); - for(int i = 0; i < horizon; ++i) t_controls[i] = i * dt; - - // Extract individual state and control trajectories - std::vector x_pos(horizon + 1), y_pos(horizon + 1), z_pos(horizon + 1); - std::vector vx(horizon + 1), vy(horizon + 1), vz(horizon + 1); - - for (size_t i = 0; i < X_solution.size(); ++i) { - const auto& state = X_solution[i]; - if (state.size() >= state_dim) { // Ensure state has at least 8 dimensions - x_pos[i] = state(0); - y_pos[i] = state(1); - z_pos[i] = state(2); - vx[i] = state(3); - vy[i] = state(4); - vz[i] = state(5); - } - } - - std::vector ux(horizon), uy(horizon), uz(horizon); - std::vector thrust_magnitude(horizon); - - for (size_t i = 0; i < U_solution.size(); ++i) { - const auto& control = U_solution[i]; - if (control.size() >= control_dim) { // Ensure control has at least 3 dimensions - ux[i] = control(0); - uy[i] = control(1); - uz[i] = control(2); - thrust_magnitude[i] = control.norm(); - } - } - - // Circle data for plotting - std::vector circle_x, circle_y; - for (double theta = 0; theta <= 2*M_PI; theta += 0.01) { - circle_x.push_back(radius * std::cos(theta)); - circle_y.push_back(radius * std::sin(theta)); - } - - // --- Generate Plots --- - // plt::figure_size(1200, 800); // Removed due to compilation error - - // 1. Position Trajectories - plt::figure(); - plt::plot(t_states, x_pos)->line_width(2).display_name("x (pos)"); - plt::hold(true); - plt::plot(t_states, y_pos)->line_width(2).display_name("y (pos)"); - plt::plot(t_states, z_pos)->line_width(2).display_name("z (pos)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("Position vs. Time"); - - // 2. Velocity Trajectories - plt::figure(); - plt::plot(t_states, vx)->line_width(2).display_name("vx"); - plt::hold(true); - plt::plot(t_states, vy)->line_width(2).display_name("vy"); - plt::plot(t_states, vz)->line_width(2).display_name("vz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("Velocity vs. Time"); - - // 5. Control Inputs (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, ux)->line_width(2).display_name("ux"); - plt::hold(true); - plt::stairs(t_controls, uy)->line_width(2).display_name("uy"); - plt::stairs(t_controls, uz)->line_width(2).display_name("uz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Input"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time"); - - // 6. Thrust Magnitude (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, thrust_magnitude)->line_width(2).display_name("||Thrust|| (ZOH)"); - // Add norm constraint lines if available - // plt::hold(true); - // plt::plot(t_controls, std::vector(horizon, u_max_norm), "--r")->display_name("Max Norm"); - // if (u_min_norm > 0) plt::plot(t_controls, std::vector(horizon, u_min_norm), "--y")->display_name("Min Norm"); - // plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Thrust Magnitude"); - plt::legend(); - plt::title("Thrust Magnitude (ZOH) vs. Time"); - - // 7. X-Y plane trajectory (x-axis vertical to the top, y-axis horizontal to the left) - plt::figure(); - plt::plot(y_pos, x_pos)->line_width(2).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty() && !y_pos.empty()){ // Check if trajectories are not empty - plt::scatter(std::vector{y_pos.front()}, std::vector{x_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter(std::vector{y_pos.back()}, std::vector{x_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - // Plot Ball Constraint - plt::hold(true); - plt::plot(circle_x, circle_y)->line_width(2).display_name("Ball Constraint"); - plt::hold(false); - plt::xlabel("y (m)"); - plt::ylabel("x (m)"); - plt::legend(); - plt::title("X-Y Plane Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - plt::gca()->x_axis().reverse(true); // Make y-axis (horizontal on plot) increase to the left - - // 8. 3D Trajectory - plt::figure(); - plt::plot3(x_pos, y_pos, z_pos, "-o")->line_width(2).marker_size(4).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty()){ // Check if trajectories are not empty - plt::scatter3(std::vector{x_pos.front()}, std::vector{y_pos.front()}, std::vector{z_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter3(std::vector{x_pos.back()}, std::vector{y_pos.back()}, std::vector{z_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - plt::hold(false); - plt::xlabel("x (m)"); - plt::ylabel("y (m)"); - plt::zlabel("z (m)"); - plt::legend(); - plt::title("3D Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - - // Show all plots - plt::show(); - std::cout << "Plotting complete." << std::endl; - } - else - { - std::cout << "Solver did not find a solution, or solution variables are not available. Skipping plots." << std::endl; - } - return 0; - } \ No newline at end of file diff --git a/examples/cddp_spacecraft_nonlinear_rpo.cpp b/examples/cddp_spacecraft_nonlinear_rpo.cpp deleted file mode 100644 index e727519a..00000000 --- a/examples/cddp_spacecraft_nonlinear_rpo.cpp +++ /dev/null @@ -1,383 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -namespace cddp -{ - class SumOfTwoNormObjective : public NonlinearObjective - { - public: - SumOfTwoNormObjective(const Eigen::VectorXd &goal_state, - double weight_running_control, - double weight_terminal_state, - double timestep) - : NonlinearObjective(timestep), - goal_state_(goal_state), - weight_running_control_(weight_running_control), - weight_terminal_state_(weight_terminal_state) - { - Qf_ = Eigen::MatrixXd::Identity(goal_state.size(), goal_state.size()); - Qf_(6, 6) = 0.0; - Qf_(7, 7) = 0.0; - Qf_(8, 8) = 0.0; - Qf_(9, 9) = 0.0; - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int /*index*/) const override - { - double control_squared = control.squaredNorm(); - double control_norm = std::sqrt(control_squared + epsilon_); - return weight_running_control_ * control_norm; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return weight_terminal_state_ * state_error.transpose() * Qf_ * state_error; - } - - // Analytical Gradients - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state.size()); // Or handle error appropriately if size unknown - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - if (norm_u < 1e-8) - { - return Eigen::VectorXd::Zero(control.size()); - } - return weight_running_control_ * control / norm_u; - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return 2.0 * weight_terminal_state_ * Qf_ * state_error; - } - - // Analytical Hessians - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state.size(), state.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - int control_dim = control.size(); - if (norm_u < 1e-8) - { - return weight_running_control_ * Eigen::MatrixXd::Identity(control_dim, control_dim) / 1e-8; // or a small value like 1.0 - } - Eigen::MatrixXd I = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd u_ut = control * control.transpose(); - return weight_running_control_ * (I / norm_u - u_ut / (norm_u * norm_u * norm_u)); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd &state, const Eigen::VectorXd &control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd & /*final_state*/) const override - { - int state_dim = goal_state_.size(); - return 2.0 * weight_terminal_state_ * Qf_; - } - - private: - Eigen::VectorXd goal_state_; - double weight_running_control_; - double weight_terminal_state_; - double epsilon_ = 1e-5; - Eigen::MatrixXd Qf_; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Optimization horizon info - int horizon = 500; // Optimization horizon length - double time_horizon = 10000.0; // Time horizon for optimization [s] - double dt = time_horizon / horizon; // Time step for optimization - int state_dim = 10; - int control_dim = 3; - - // HCW parameters - double gravitational_parameter = 3.9860044e14; - double ref_radius = (6371.0 + 500.0) * 1e3; - double ref_period = 2 * M_PI * sqrt(pow(ref_radius, 3) / 3.9860044e14); - double ref_mean_motion = 2 * M_PI / ref_period; - double mass = 100.0; - double nominal_radius = 50.0; - std::string integration_type = "rk4"; - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, -1000.0, 0.0, 0.0, 0.0, 0.0, ref_radius, 0.0, 0.0, ref_mean_motion; - - // Final (reference/goal) state - Eigen::VectorXd goal_state(state_dim); - goal_state << -100.0, 0.0, 0.0, 0.0, 2*ref_mean_motion*100.0, 0.0, ref_radius, 0.0, 0.0, ref_mean_motion; - - // Input constraints - double u_max = 0.05; // for each dimension - double u_min = -0.05; // for each dimension - double u_min_norm = 0.0; // Minimum thrust magnitude - double u_max_norm = 0.05; // Maximum thrust magnitude, consistent with previous u_max - - // Cost weighting for SumOfTwoNormObjective - double weight_running_control = 1.0; // Example value - double weight_terminal_state = 1000.0; // Example value - - // Create the SpacecraftNonlinear system for optimization - std::unique_ptr spacecraft_system = - std::make_unique(dt, integration_type, mass, 1.0, 1.0, gravitational_parameter); - - // Build cost objective - auto objective = std::make_unique( - goal_state, - weight_running_control, - weight_terminal_state, - dt); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 100; // May need more iterations for one-shot solve - options.line_search.max_iterations = 21; - options.tolerance = 1e-7; // Tighter tolerance for final solve - options.verbose = true; // Show solver progress - options.enable_parallel = false; - options.num_threads = 8; - // Regularization type is now implicit in new API - options.regularization.initial_value = 1e-3; - options.ipddp.barrier.mu_initial = 1e-0; // Starting barrier coefficient - options.use_ilqr = true; - options.debug = false; - options.msipddp.segment_length = horizon; - options.msipddp.rollout_type = "nonlinear"; - - // Initial trajectory. - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - // Generate initial trajectory by constant initial state - for (int i = 0; i < horizon; ++i) - { - // X[i + 1] = hcw_system->getDiscreteDynamics(X[i], U[i]); - X[i+1] = initial_state; - } - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - dt, - std::move(spacecraft_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // // Add Thrust Magnitude Constraint - // cddp_solver.addConstraint("MaxThrustMagnitudeConstraint", - // std::make_unique(u_max_norm)); - - // Add Ball Constraint (for keep-out zone) - double radius = 90.0; - Eigen::Vector2d center(0.0, 0.0); - // cddp_solver.addConstraint("BallConstraint", - // std::make_unique(radius, center, 0.1)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract the solution - const auto& X_solution = solution.state_trajectory; - const auto& U_solution = solution.control_trajectory; - - if (!X_solution.empty() && !U_solution.empty()) - { - namespace plt = matplot; - - // Create time vectors - std::vector t_states(horizon + 1); - for(int i = 0; i <= horizon; ++i) t_states[i] = i * dt; - - std::vector t_controls(horizon); - for(int i = 0; i < horizon; ++i) t_controls[i] = i * dt; - - // Extract individual state and control trajectories - std::vector x_pos(horizon + 1), y_pos(horizon + 1), z_pos(horizon + 1); - std::vector vx(horizon + 1), vy(horizon + 1), vz(horizon + 1); - - for (size_t i = 0; i < X_solution.size(); ++i) { - const auto& state = X_solution[i]; - if (state.size() >= state_dim) { // Ensure state has at least 8 dimensions - x_pos[i] = state(0); - y_pos[i] = state(1); - z_pos[i] = state(2); - vx[i] = state(3); - vy[i] = state(4); - vz[i] = state(5); - } - } - - std::vector ux(horizon), uy(horizon), uz(horizon); - std::vector thrust_magnitude(horizon); - - for (size_t i = 0; i < U_solution.size(); ++i) { - const auto& control = U_solution[i]; - if (control.size() >= control_dim) { // Ensure control has at least 3 dimensions - ux[i] = control(0); - uy[i] = control(1); - uz[i] = control(2); - thrust_magnitude[i] = control.norm(); - } - } - - // Circle data for plotting - std::vector circle_x, circle_y; - for (double theta = 0; theta <= 2*M_PI; theta += 0.01) { - circle_x.push_back(radius * std::cos(theta)); - circle_y.push_back(radius * std::sin(theta)); - } - - // --- Generate Plots --- - // plt::figure_size(1200, 800); // Removed due to compilation error - - // 1. Position Trajectories - plt::figure(); - plt::plot(t_states, x_pos)->line_width(2).display_name("x (pos)"); - plt::hold(true); - plt::plot(t_states, y_pos)->line_width(2).display_name("y (pos)"); - plt::plot(t_states, z_pos)->line_width(2).display_name("z (pos)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("Position vs. Time"); - - // 2. Velocity Trajectories - plt::figure(); - plt::plot(t_states, vx)->line_width(2).display_name("vx"); - plt::hold(true); - plt::plot(t_states, vy)->line_width(2).display_name("vy"); - plt::plot(t_states, vz)->line_width(2).display_name("vz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("Velocity vs. Time"); - - // 5. Control Inputs (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, ux)->line_width(2).display_name("ux"); - plt::hold(true); - plt::stairs(t_controls, uy)->line_width(2).display_name("uy"); - plt::stairs(t_controls, uz)->line_width(2).display_name("uz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Input"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time"); - - // 6. Thrust Magnitude (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, thrust_magnitude)->line_width(2).display_name("||Thrust|| (ZOH)"); - // Add norm constraint lines if available - // plt::hold(true); - // plt::plot(t_controls, std::vector(horizon, u_max_norm), "--r")->display_name("Max Norm"); - // if (u_min_norm > 0) plt::plot(t_controls, std::vector(horizon, u_min_norm), "--y")->display_name("Min Norm"); - // plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Thrust Magnitude"); - plt::legend(); - plt::title("Thrust Magnitude (ZOH) vs. Time"); - - // 7. X-Y plane trajectory (x-axis vertical to the top, y-axis horizontal to the left) - plt::figure(); - plt::plot(y_pos, x_pos)->line_width(2).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty() && !y_pos.empty()){ // Check if trajectories are not empty - plt::scatter(std::vector{y_pos.front()}, std::vector{x_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter(std::vector{y_pos.back()}, std::vector{x_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - // Plot Ball Constraint - plt::hold(true); - plt::plot(circle_x, circle_y)->line_width(2).display_name("Ball Constraint"); - plt::hold(false); - plt::xlabel("y (m)"); - plt::ylabel("x (m)"); - plt::legend(); - plt::title("X-Y Plane Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - plt::gca()->x_axis().reverse(true); // Make y-axis (horizontal on plot) increase to the left - - // 8. 3D Trajectory - plt::figure(); - plt::plot3(x_pos, y_pos, z_pos, "-o")->line_width(2).marker_size(4).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty()){ // Check if trajectories are not empty - plt::scatter3(std::vector{x_pos.front()}, std::vector{y_pos.front()}, std::vector{z_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter3(std::vector{x_pos.back()}, std::vector{y_pos.back()}, std::vector{z_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - plt::hold(false); - plt::xlabel("x (m)"); - plt::ylabel("y (m)"); - plt::zlabel("z (m)"); - plt::legend(); - plt::title("3D Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - - // Show all plots - plt::show(); - std::cout << "Plotting complete." << std::endl; - } - else - { - std::cout << "Solver did not find a solution, or solution variables are not available. Skipping plots." << std::endl; - } - return 0; - } \ No newline at end of file diff --git a/examples/cddp_spacecraft_roe_rpo.cpp b/examples/cddp_spacecraft_roe_rpo.cpp deleted file mode 100644 index e35de013..00000000 --- a/examples/cddp_spacecraft_roe_rpo.cpp +++ /dev/null @@ -1,478 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "dynamics_model/spacecraft_roe.hpp" // Added for SpacecraftROE -namespace plt = matplot; - -namespace cddp -{ - class SumOfTwoNormObjective : public NonlinearObjective - { - public: - SumOfTwoNormObjective(const Eigen::VectorXd &goal_state_roe, // Renamed for clarity - double weight_running_control, - double weight_terminal_state, - double timestep, - double a_ref_m) - : NonlinearObjective(timestep), - goal_state_roe_(goal_state_roe), // Renamed for clarity - weight_running_control_(weight_running_control), - weight_terminal_state_(weight_terminal_state), - a_ref_m_(a_ref_m) - { - } - - double running_cost(const Eigen::VectorXd &state_roe, // Renamed for clarity - const Eigen::VectorXd &control, - int /*index*/) const override - { - double control_squared = control.squaredNorm(); - if (control_squared < 1e-10) - { - return 0.0; - } - double control_norm = std::sqrt(control_squared + epsilon_); - return weight_running_control_ * control_norm; - } - - double terminal_cost(const Eigen::VectorXd &final_state_roe) const override // Renamed for clarity - { - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(final_state_roe.size(), final_state_roe.size()); - Q(6, 6) = 0.0; - Eigen::VectorXd state_error = (final_state_roe - goal_state_roe_) * a_ref_m_; - return weight_terminal_state_ * state_error.transpose() * Q * state_error; - } - - // Analytical Gradients - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd &state_roe, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state_roe.size()); - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd & /*state_roe*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - if (norm_u < 1e-8) - { - return Eigen::VectorXd::Zero(control.size()); - } - return weight_running_control_ * control / norm_u; - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd &final_state_roe) const override - { - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(final_state_roe.size(), final_state_roe.size()); - Q(6, 6) = 0.0; - Eigen::VectorXd state_error = (final_state_roe - goal_state_roe_) * a_ref_m_; - return 2.0 * weight_terminal_state_ * Q * state_error; - } - - // Analytical Hessians - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd &state_roe, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state_roe.size(), state_roe.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd & /*state_roe*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - int control_dim = control.size(); - if (norm_u < 1e-8) - { - return weight_running_control_ * Eigen::MatrixXd::Identity(control_dim, control_dim) / 1e-8; // or a small value like 1.0 - } - Eigen::MatrixXd I = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd u_ut = control * control.transpose(); - return weight_running_control_ * (I / norm_u - u_ut / (norm_u * norm_u * norm_u)); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd &state_roe, const Eigen::VectorXd &control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state_roe.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd & /*final_state_roe*/) const override - { - int state_dim = goal_state_roe_.size(); - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(state_dim, state_dim); - Q(6, 6) = 0.0; - return 2.0 * weight_terminal_state_ * Q; - } - - private: - Eigen::VectorXd goal_state_roe_; // Stores goal state in ROE coordinates - double weight_running_control_; - double weight_terminal_state_; - double epsilon_ = 1e-6; - double a_ref_m_; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Optimization horizon info - int horizon = 500; // Optimization horizon length - double dt = 20.0; // Time step for optimization - int state_dim = SpacecraftROE::STATE_DIM; // Use consistent state dimension from SpacecraftROE - int control_dim = SpacecraftROE::CONTROL_DIM; // Use consistent control dimension - - // SpacecraftROE parameters - double a_ref_m = (6371.0 + 500.0) * 1e3; // Reference semi-major axis (m) e.g. LEO - double nu0_rad = 0.0; // Initial argument of latitude for ROE (rad) - double mass_kg = 1.0; // Mass in kg - double period = 2 * M_PI * sqrt(pow(a_ref_m, 3) / 3.9860044e14); // Orbital period (s) - double mean_motion = 2 * M_PI / period; - - // Input constraints - double u_force_max_N = 0.05; - - // Cost weighting for SumOfTwoNormObjective - double weight_running_control = 1.0; - double weight_terminal_state = 10.0; - - // Create the SpacecraftROE system for optimization - std::unique_ptr roe_system = - std::make_unique(dt, "euler", a_ref_m, nu0_rad); - - // Initial state - Eigen::VectorXd initial_state_roe(state_dim); - // initial_state_roe << 0.0, 1000.0, 0.0, 500.0, 0.0, 700.0, 0.0; // Time is the 7th element - // initial_state_roe /= a_ref_m; - // initial_state_roe(6) = 0.0; - Eigen::VectorXd initial_state_hcw(6); - initial_state_hcw << 0.0, -1000.0, 0.0, 0.0, 0.0, 0.0; - if (auto* roe_model = dynamic_cast(roe_system.get())) { - initial_state_roe = roe_model->transformHCWToROE(initial_state_hcw, 0.0); - } else { - std::cerr << "Error: roe_system is not a SpacecraftROE model at initial_state_roe." << std::endl; - return 1; // Or handle error appropriately - } - - // Final state - Eigen::VectorXd goal_state_roe(state_dim); - // goal_state_roe << 0.0, 100.0, 0.0, 300.0, 0.0, 400.0, 0.0; // Time is the 7th element, init to 0.0 - // goal_state_roe /= a_ref_m; - // goal_state_roe(6) = horizon * dt; // Set target time to the end of the horizon - Eigen::VectorXd goal_state_hcw(6); - goal_state_hcw << -100.0, 0.0, 0.0, 0.0, 200.0 * mean_motion, 0.0; - if (auto* roe_model = dynamic_cast(roe_system.get())) { - goal_state_roe = roe_model->transformHCWToROE(goal_state_hcw, horizon * dt); - } else { - std::cerr << "Error: roe_system is not a SpacecraftROE model at goal_state_roe." << std::endl; - return 1; // Or handle error appropriately - } - - // Build cost objective - auto objective = std::make_unique( - goal_state_roe, - weight_running_control, - weight_terminal_state, - dt, - a_ref_m); - - // ======= Initial and final trajectory ======= - int num_steps = static_cast(12.0 * period / dt); // Simulate for 3 orbits - // Initial and final trajectory - std::vector X_roe_initial(num_steps + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U_accel_initial(num_steps, Eigen::VectorXd::Zero(control_dim)); - X_roe_initial[0] = initial_state_roe; - for (int i = 0; i < num_steps; ++i) // Iterate up to num_steps - { - X_roe_initial[i + 1] = roe_system->getDiscreteDynamics(X_roe_initial[i], U_accel_initial[i], i * dt); - } - std::vector X_roe_final(num_steps + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U_accel_final(num_steps, Eigen::VectorXd::Zero(control_dim)); - X_roe_final[0] = goal_state_roe; - for (int i = 0; i < num_steps; ++i) // Iterate up to num_steps - { - X_roe_final[i + 1] = roe_system->getDiscreteDynamics(X_roe_final[i], U_accel_final[i], i * dt); - } - - // Convert initial and final trajectory to HCW coordinates vector of doubles - std::vector> X_hcw_initial(num_steps + 1); - std::vector> X_hcw_final(num_steps + 1); - for (int i = 0; i < num_steps + 1; ++i) - { - if (auto* roe_model = dynamic_cast(roe_system.get())) { - Eigen::VectorXd state_hcw_initial = roe_model->transformROEToHCW(X_roe_initial[i].head(6), X_roe_initial[i][6]); - Eigen::VectorXd state_hcw_final = roe_model->transformROEToHCW(X_roe_final[i].head(6), X_roe_final[i][6]); - X_hcw_initial[i] = {state_hcw_initial(0), state_hcw_initial(1), state_hcw_initial(2), state_hcw_initial(3), state_hcw_initial(4), state_hcw_initial(5)}; - X_hcw_final[i] = {state_hcw_final(0), state_hcw_final(1), state_hcw_final(2), state_hcw_final(3), state_hcw_final(4), state_hcw_final(5)}; - } else { - std::cerr << "Error: roe_system is not a SpacecraftROE model during trajectory conversion." << std::endl; - // Handle error appropriately, maybe clear X_hcw_initial[i] or return - } - } - - // Prepare data for 3D plotting - std::vector initial_x_hcw(num_steps + 1), initial_y_hcw(num_steps + 1), initial_z_hcw(num_steps + 1); - std::vector initial_t(num_steps + 1); - std::vector final_x_hcw(num_steps + 1), final_y_hcw(num_steps + 1), final_z_hcw(num_steps + 1); - std::vector final_t(num_steps + 1); - - for (int i = 0; i < num_steps + 1; ++i) { - if (X_hcw_initial[i].size() >= 3) { // Ensure there are enough elements - initial_x_hcw[i] = X_hcw_initial[i][0]; - initial_y_hcw[i] = X_hcw_initial[i][1]; - initial_z_hcw[i] = X_hcw_initial[i][2]; - initial_t[i] = X_roe_initial[i][6]; - } - if (X_hcw_final[i].size() >= 3) { // Ensure there are enough elements - final_x_hcw[i] = X_hcw_final[i][0]; - final_y_hcw[i] = X_hcw_final[i][1]; - final_z_hcw[i] = X_hcw_final[i][2]; - final_t[i] = X_roe_final[i][6]; - } - } - // ======= End of Initial and final trajectory ======= - - // // // Plot 3d initial and final trajectory - // plt::figure(); - // plt::plot3(initial_x_hcw, initial_y_hcw, initial_z_hcw, "-")->line_width(1).display_name("Initial Trajectory"); - // plt::hold(true); - // plt::plot3(final_x_hcw, final_y_hcw, final_z_hcw, "-")->line_width(1).display_name("Final Trajectory"); - // plt::hold(false); - // plt::xlabel("x_hcw (km)"); - // plt::ylabel("y_hcw (km)"); - // plt::zlabel("z_hcw (km)"); - // plt::legend(); - // plt::title("Initial and Final Trajectories (HCW)"); - // plt::axis(plt::equal); - - // // Plot time history - // plt::figure(); - // plt::plot(initial_t, initial_x_hcw, "-")->line_width(1).display_name("Initial Trajectory"); - // plt::hold(true); - // plt::plot(final_t, final_x_hcw, "-")->line_width(1).display_name("Final Trajectory"); - // plt::hold(false); - // plt::xlabel("Time (s)"); - // plt::show(); - - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - for (int i = 0; i < horizon; ++i) - { - X[i] = initial_state_roe; - U[i] = Eigen::VectorXd::Zero(control_dim); - } - X[horizon] = initial_state_roe; - - // Solver options. - cddp::CDDPOptions options; - options.max_iterations = 1000; - options.tolerance = 1e-6; - options.regularization.initial_value = 1e-5; - options.use_ilqr = true; - options.enable_parallel = true; - options.num_threads = 12; - options.debug = false; - options.ipddp.barrier.mu_initial = 1e-1; - options.msipddp.segment_length = horizon; - options.msipddp.rollout_type = "nonlinear"; - options.ipddp.barrier.mu_update_factor = 0.2; - options.ipddp.barrier.mu_update_power = 1.2; - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state_roe, - goal_state_roe, - horizon, - dt, - std::move(roe_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // goal_state^T * goal_state - std::cout << "initial_state^T * initial_state: " << initial_state_roe.transpose() * initial_state_roe << std::endl; - std::cout << "initial_state: " << initial_state_roe.transpose() << std::endl; - std::cout << "goal_state^T * goal_state: " << goal_state_roe.transpose() * goal_state_roe << std::endl; - std::cout << "goal_state: " << goal_state_roe.transpose() << std::endl; - - // // Add Control Constraint - // Eigen::VectorXd u_upper_accel = Eigen::VectorXd::Constant(control_dim, u_force_max_N); - // cddp_solver.addPathConstraint("ControlConstraint", - // std::make_unique(-u_upper_accel, u_upper_accel)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract the solution - const auto& X_solution_roe = solution.state_trajectory; - const auto& U_solution_accel = solution.control_trajectory; - - // Print the solution - // std::cout << "Solution: " << solution.cost << std::endl; - std::cout << "Solution: " << X_solution_roe.back().transpose() * a_ref_m << std::endl; - std::cout << "Solution: " << U_solution_accel.back().transpose() << std::endl; - - if (!X_solution_roe.empty() && !U_solution_accel.empty()) - { - namespace plt = matplot; - - // Create a new SpacecraftROE instance for transformations, - // as the original roe_system was moved into the solver. - SpacecraftROE roe_transformer_for_plotting(dt, "euler", a_ref_m, nu0_rad); - - // Create time vectors - std::vector t_states(horizon + 1); - for(int i = 0; i <= horizon; ++i) t_states[i] = i * dt; - - std::vector t_controls(horizon); - for(int i = 0; i < horizon; ++i) t_controls[i] = i * dt; - - // Transform ROE states to HCW states (m) for plotting - std::vector x_pos_m(horizon + 1), y_pos_m(horizon + 1), z_pos_m(horizon + 1); - std::vector vx_mps(horizon + 1), vy_mps(horizon + 1), vz_mps(horizon + 1); - - for (size_t i = 0; i < X_solution_roe.size(); ++i) { - const auto& state_roe_current = X_solution_roe[i]; - if (state_roe_current.size() == state_dim) { - double current_time = state_roe_current(6); - Eigen::VectorXd state_hcw_m = roe_transformer_for_plotting.transformROEToHCW(state_roe_current.head(6), current_time); - - x_pos_m[i] = state_hcw_m(0); - y_pos_m[i] = state_hcw_m(1); - z_pos_m[i] = state_hcw_m(2); - vx_mps[i] = state_hcw_m(3); - vy_mps[i] = state_hcw_m(4); - vz_mps[i] = state_hcw_m(5); - } - } - - std::vector ur_accel(horizon), ut_accel(horizon), un_accel(horizon); // Accelerations in km/s^2 - std::vector accel_magnitude_m_s2(horizon); - - for (size_t i = 0; i < U_solution_accel.size(); ++i) { - const auto& control_accel = U_solution_accel[i]; - if (control_accel.size() == control_dim) { - ur_accel[i] = control_accel(0); // m/s^2 - ut_accel[i] = control_accel(1); // m/s^2 - un_accel[i] = control_accel(2); // m/s^2 - accel_magnitude_m_s2[i] = control_accel.norm(); // m/s^2 - } - } - - // --- Generate Plots --- - // plt::figure_size(1200, 800); - - // 1. Position Trajectories (HCW in meters) - plt::figure(); - plt::plot(t_states, x_pos_m)->line_width(2).display_name("x_hcw (m)"); - plt::hold(true); - plt::plot(t_states, y_pos_m)->line_width(2).display_name("y_hcw (m)"); - plt::plot(t_states, z_pos_m)->line_width(2).display_name("z_hcw (m)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("HCW Position vs. Time"); - - // 2. Velocity Trajectories (HCW in m/s) - plt::figure(); - plt::plot(t_states, vx_mps)->line_width(2).display_name("vx_hcw (m/s)"); - plt::hold(true); - plt::plot(t_states, vy_mps)->line_width(2).display_name("vy_hcw (m/s)"); - plt::plot(t_states, vz_mps)->line_width(2).display_name("vz_hcw (m/s)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("HCW Velocity vs. Time"); - - // 5. Control Inputs (Accelerations in km/s^2, ZOH) - plt::figure(); - plt::stairs(t_controls, ur_accel)->line_width(2).display_name("u_r (km/s^2)"); - plt::hold(true); - plt::stairs(t_controls, ut_accel)->line_width(2).display_name("u_t (km/s^2)"); - plt::stairs(t_controls, un_accel)->line_width(2).display_name("u_n (km/s^2)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Acceleration (km/s^2)"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time"); - - // 6. Acceleration Magnitude (km/s^2, ZOH) - plt::figure(); - plt::stairs(t_controls, accel_magnitude_m_s2)->line_width(2).display_name("||Acceleration|| (m/s^2) (ZOH)"); - // plt::hold(true); - // plt::plot(t_controls, std::vector(horizon, u_max_norm_accel), "--r")->display_name("Max Norm Accel"); - // if (u_min_norm_accel > 0) plt::plot(t_controls, std::vector(horizon, u_min_norm_accel), "--y")->display_name("Min Norm Accel"); - // plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Acceleration Magnitude (m/s^2)"); - plt::legend(); - plt::title("Acceleration Magnitude (ZOH) vs. Time"); - - // 7. X-Y plane trajectory (HCW in meters, x-axis vertical, y-axis horizontal to the left) - plt::figure(); - plt::plot(y_pos_m, x_pos_m)->line_width(2).display_name("Trajectory (HCW)"); - plt::hold(true); - if (!x_pos_m.empty() && !y_pos_m.empty()){ - plt::scatter(std::vector{y_pos_m.front()}, std::vector{x_pos_m.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter(std::vector{y_pos_m.back()}, std::vector{x_pos_m.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - // plt::plot(circle_y_m, circle_x_m)->line_width(2).display_name("Ball Constraint (HCW)"); - plt::hold(false); - plt::xlabel("y_hcw (m)"); - plt::ylabel("x_hcw (m)"); - plt::legend(); - plt::title("X-Y Plane Trajectory (HCW)"); - plt::axis(plt::equal); - plt::gca()->x_axis().reverse(true); - - // 8. 3D Trajectory (HCW in meters) - plt::figure(); - plt::plot3(x_pos_m, y_pos_m, z_pos_m, "-o")->line_width(2).marker_size(4).display_name("Trajectory (HCW)"); - plt::hold(true); - if (!x_pos_m.empty()){ - plt::scatter3(std::vector{x_pos_m.front()}, std::vector{y_pos_m.front()}, std::vector{z_pos_m.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter3(std::vector{x_pos_m.back()}, std::vector{y_pos_m.back()}, std::vector{z_pos_m.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - // Could also plot the ball constraint here if it's a sphere. - plt::hold(false); - plt::xlabel("x_hcw (m)"); - plt::ylabel("y_hcw (m)"); - plt::zlabel("z_hcw (m)"); - plt::legend(); - plt::title("3D Trajectory (HCW)"); - plt::axis(plt::equal); - - plt::show(); - std::cout << "Plotting complete." << std::endl; - } - else - { - std::cout << "Solver did not find a solution, or solution variables are not available. Skipping plots." << std::endl; - } - return 0; -} diff --git a/examples/cddp_spacecraft_rpo.cpp b/examples/cddp_spacecraft_rpo.cpp deleted file mode 100644 index c2ab319c..00000000 --- a/examples/cddp_spacecraft_rpo.cpp +++ /dev/null @@ -1,372 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -namespace cddp -{ - class SumOfTwoNormObjective : public NonlinearObjective - { - public: - SumOfTwoNormObjective(const Eigen::VectorXd &goal_state, - double weight_running_control, - double weight_terminal_state, - double timestep) - : NonlinearObjective(timestep), - goal_state_(goal_state), - weight_running_control_(weight_running_control), - weight_terminal_state_(weight_terminal_state) - { - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int /*index*/) const override - { - double control_squared = control.squaredNorm(); - double control_norm = std::sqrt(control_squared + epsilon_); - return weight_running_control_ * control_norm; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return weight_terminal_state_ * state_error.squaredNorm(); - } - - // Analytical Gradients - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state.size()); // Or handle error appropriately if size unknown - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - if (norm_u < 1e-8) - { - return Eigen::VectorXd::Zero(control.size()); - } - return weight_running_control_ * control / norm_u; - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return 2.0 * weight_terminal_state_ * state_error; - } - - // Analytical Hessians - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd & state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state.size(), state.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - int control_dim = control.size(); - if (norm_u < 1e-8) - { - return weight_running_control_ * Eigen::MatrixXd::Identity(control_dim, control_dim) / 1e-8; // or a small value like 1.0 - } - Eigen::MatrixXd I = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd u_ut = control * control.transpose(); - return weight_running_control_ * (I / norm_u - u_ut / (norm_u * norm_u * norm_u)); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd &state, const Eigen::VectorXd &control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd & /*final_state*/) const override - { - int state_dim = goal_state_.size(); - return 2.0 * weight_terminal_state_ * Eigen::MatrixXd::Identity(state_dim, state_dim); - } - - private: - Eigen::VectorXd goal_state_; - double weight_running_control_; - double weight_terminal_state_; - double epsilon_ = 1e-5; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Optimization horizon info - int horizon = 500; // Optimization horizon length - double time_horizon = 10000.0; // Time horizon for optimization [s] - double dt = time_horizon / horizon; // Time step for optimization - int state_dim = 6; - int control_dim = 3; - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - - // Initial state (v-bar hold at 1km) - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, -1000.0, 0.0, 0.0, 0.0, 0.0; - - // Final (reference/goal) state (r-bar ) - Eigen::VectorXd goal_state(state_dim); - goal_state << -100.0, 0.0, 0.0, 0.0, 2*mean_motion*100.0, 0.0; - - // Input constraints - double u_max = 0.05; // for each dimension - double u_min = -0.05; // for each dimension - double u_min_norm = 0.0; // Minimum thrust magnitude - double u_max_norm = 0.05; // Maximum thrust magnitude, consistent with previous u_max - - // Cost weighting for SumOfTwoNormObjective - double weight_running_control = 1.0; // Example value - double weight_terminal_state = 2000.0; // Example value - - // Create the HCW system for optimization - std::unique_ptr hcw_system = - std::make_unique(dt, mean_motion, mass, "euler"); - - // Build cost objective - auto objective = std::make_unique( - goal_state, - weight_running_control, - weight_terminal_state, - dt); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 1000; // May need more iterations for one-shot solve - options.line_search.max_iterations = 21; - options.tolerance = 1e-7; // Tighter tolerance for final solve - options.verbose = true; // Show solver progress - options.enable_parallel = false; - options.num_threads = 8; - // Regularization type is now implicit in new API - options.regularization.initial_value = 1e-3; - options.ipddp.barrier.mu_initial = 1e-0; // Starting barrier coefficient - options.use_ilqr = true; - options.debug = false; - options.msipddp.segment_length = horizon; - options.msipddp.rollout_type = "nonlinear"; - - // Initial trajectory. - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - // Generate initial trajectory by constant initial state - for (int i = 0; i < horizon; ++i) - { - // X[i + 1] = hcw_system->getDiscreteDynamics(X[i], U[i]); - X[i+1] = initial_state; - } - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - dt, - std::move(hcw_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // // Add Thrust Magnitude Constraint - // cddp_solver.addConstraint("MaxThrustMagnitudeConstraint", - // std::make_unique(u_max_norm)); - - // Add Ball Constraint (for keep-out zone) - double radius = 90.0; - Eigen::Vector2d center(0.0, 0.0); - cddp_solver.addPathConstraint("BallConstraint", - std::make_unique(radius, center, 0.1)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract the solution - const auto& X_solution = solution.state_trajectory; - const auto& U_solution = solution.control_trajectory; - - if (!X_solution.empty() && !U_solution.empty()) - { - namespace plt = matplot; - - // Create time vectors - std::vector t_states(horizon + 1); - for(int i = 0; i <= horizon; ++i) t_states[i] = i * dt; - - std::vector t_controls(horizon); - for(int i = 0; i < horizon; ++i) t_controls[i] = i * dt; - - // Extract individual state and control trajectories - std::vector x_pos(horizon + 1), y_pos(horizon + 1), z_pos(horizon + 1); - std::vector vx(horizon + 1), vy(horizon + 1), vz(horizon + 1); - - for (size_t i = 0; i < X_solution.size(); ++i) { - const auto& state = X_solution[i]; - if (state.size() >= state_dim) { // Ensure state has at least 8 dimensions - x_pos[i] = state(0); - y_pos[i] = state(1); - z_pos[i] = state(2); - vx[i] = state(3); - vy[i] = state(4); - vz[i] = state(5); - } - } - - std::vector ux(horizon), uy(horizon), uz(horizon); - std::vector thrust_magnitude(horizon); - - for (size_t i = 0; i < U_solution.size(); ++i) { - const auto& control = U_solution[i]; - if (control.size() >= control_dim) { // Ensure control has at least 3 dimensions - ux[i] = control(0); - uy[i] = control(1); - uz[i] = control(2); - thrust_magnitude[i] = control.norm(); - } - } - - // Circle data for plotting - std::vector circle_x, circle_y; - for (double theta = 0; theta <= 2*M_PI; theta += 0.01) { - circle_x.push_back(radius * std::cos(theta)); - circle_y.push_back(radius * std::sin(theta)); - } - - // --- Generate Plots --- - // plt::figure_size(1200, 800); // Removed due to compilation error - - // 1. Position Trajectories - plt::figure(); - plt::plot(t_states, x_pos)->line_width(2).display_name("x (pos)"); - plt::hold(true); - plt::plot(t_states, y_pos)->line_width(2).display_name("y (pos)"); - plt::plot(t_states, z_pos)->line_width(2).display_name("z (pos)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("Position vs. Time"); - - // 2. Velocity Trajectories - plt::figure(); - plt::plot(t_states, vx)->line_width(2).display_name("vx"); - plt::hold(true); - plt::plot(t_states, vy)->line_width(2).display_name("vy"); - plt::plot(t_states, vz)->line_width(2).display_name("vz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("Velocity vs. Time"); - - // 5. Control Inputs (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, ux)->line_width(2).display_name("ux"); - plt::hold(true); - plt::stairs(t_controls, uy)->line_width(2).display_name("uy"); - plt::stairs(t_controls, uz)->line_width(2).display_name("uz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Input"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time"); - - // 6. Thrust Magnitude (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, thrust_magnitude)->line_width(2).display_name("||Thrust|| (ZOH)"); - // Add norm constraint lines if available - // plt::hold(true); - // plt::plot(t_controls, std::vector(horizon, u_max_norm), "--r")->display_name("Max Norm"); - // if (u_min_norm > 0) plt::plot(t_controls, std::vector(horizon, u_min_norm), "--y")->display_name("Min Norm"); - // plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Thrust Magnitude"); - plt::legend(); - plt::title("Thrust Magnitude (ZOH) vs. Time"); - - // 7. X-Y plane trajectory (x-axis vertical to the top, y-axis horizontal to the left) - plt::figure(); - plt::plot(y_pos, x_pos)->line_width(2).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty() && !y_pos.empty()){ // Check if trajectories are not empty - plt::scatter(std::vector{y_pos.front()}, std::vector{x_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter(std::vector{y_pos.back()}, std::vector{x_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - // Plot Ball Constraint - plt::hold(true); - plt::plot(circle_x, circle_y)->line_width(2).display_name("Ball Constraint"); - plt::hold(false); - plt::xlabel("y (m)"); - plt::ylabel("x (m)"); - plt::legend(); - plt::title("X-Y Plane Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - plt::gca()->x_axis().reverse(true); // Make y-axis (horizontal on plot) increase to the left - - // 8. 3D Trajectory - plt::figure(); - plt::plot3(x_pos, y_pos, z_pos, "-o")->line_width(2).marker_size(4).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty()){ // Check if trajectories are not empty - plt::scatter3(std::vector{x_pos.front()}, std::vector{y_pos.front()}, std::vector{z_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter3(std::vector{x_pos.back()}, std::vector{y_pos.back()}, std::vector{z_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - plt::hold(false); - plt::xlabel("x (m)"); - plt::ylabel("y (m)"); - plt::zlabel("z (m)"); - plt::legend(); - plt::title("3D Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - - // Show all plots - plt::show(); - std::cout << "Plotting complete." << std::endl; - } - else - { - std::cout << "Solver did not find a solution, or solution variables are not available. Skipping plots." << std::endl; - } - return 0; - } \ No newline at end of file diff --git a/examples/cddp_spacecraft_rpo_fuel.cpp b/examples/cddp_spacecraft_rpo_fuel.cpp deleted file mode 100644 index 23fb8ef0..00000000 --- a/examples/cddp_spacecraft_rpo_fuel.cpp +++ /dev/null @@ -1,390 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include -#include // For std::sqrt - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "cddp_core/cddp_core.hpp" -#include "cddp_core/objective.hpp" -#include "dynamics_model/spacecraft_linear_fuel.hpp" - -namespace cddp -{ - class MinimizeFuelObjective : public NonlinearObjective - { - public: - MinimizeFuelObjective( - double weight_terminal_fuel, - const Eigen::VectorXd& goal_state_pos_vel, // Should be size 6: [x,y,z,vx,vy,vz] - double weight_terminal_pos, - double weight_terminal_vel, - double timestep) - : NonlinearObjective(timestep), - goal_state_pos_vel_(goal_state_pos_vel), - weight_terminal_fuel_(weight_terminal_fuel), - weight_terminal_pos_(weight_terminal_pos), - weight_terminal_vel_(weight_terminal_vel) - { - } - - double running_cost(const Eigen::VectorXd& /*state*/, - const Eigen::VectorXd& /*control*/, - int /*index*/) const override - { - return 0.0; - } - - double terminal_cost(const Eigen::VectorXd& final_state) const override - { - - double cost = -weight_terminal_fuel_ * final_state(7) * final_state(7); - - // Position cost - for (int i = 0; i < 3; ++i) { - double error = final_state(i) - goal_state_pos_vel_(i); - cost += 0.5 * weight_terminal_pos_ * error * error; - } - - // Velocity cost - for (int i = 0; i < 3; ++i) { - double error = final_state(i + 3) - goal_state_pos_vel_(i + 3); - cost += 0.5 * weight_terminal_vel_ * error * error; - } - return cost; - } - - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd& state, const Eigen::VectorXd& /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state.size()); - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd& /*state*/, const Eigen::VectorXd& control, int /*index*/) const override - { - return Eigen::VectorXd::Zero(control.size()); - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd& final_state) const override - { - Eigen::VectorXd grad = Eigen::VectorXd::Zero(final_state.size()); - grad(7) = weight_terminal_fuel_ * 2.0 * final_state(7); - - // Position gradient - for (int i = 0; i < 3; ++i) { - grad(i) = weight_terminal_pos_ * (final_state(i) - goal_state_pos_vel_(i)); - } - - // Velocity gradient - for (int i = 0; i < 3; ++i) { - grad(i + 3) = weight_terminal_vel_ * (final_state(i + 3) - goal_state_pos_vel_(i + 3)); - } - return grad; - } - - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd& state, const Eigen::VectorXd& /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state.size(), state.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd& /*state*/, const Eigen::VectorXd& control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), control.size()); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd& state, const Eigen::VectorXd& control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd& final_state) const override - { - Eigen::MatrixXd hess = Eigen::MatrixXd::Zero(final_state.size(), final_state.size()); - // Hessian for fuel term is zero - - hess(7, 7) = -weight_terminal_fuel_; - - // Position Hessian - for (int i = 0; i < 3; ++i) { - hess(i, i) = weight_terminal_pos_; - } - - // Velocity Hessian - for (int i = 0; i < 3; ++i) { - hess(i + 3, i + 3) = weight_terminal_vel_; - } - return hess; - } - - private: - double weight_terminal_fuel_; - Eigen::VectorXd goal_state_pos_vel_; // For x, y, z, vx, vy, vz, mass, accumulated_control_effort - double weight_terminal_pos_; - double weight_terminal_vel_; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Optimization horizon info - int horizon = 200; // Optimization horizon length - double time_horizon = 200.0; // Time horizon for optimization [s] - double dt = time_horizon / horizon; // Time step for optimization - int state_dim = 8; - int control_dim = 3; - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - double isp = 300.0; - double g0 = 9.80665; - double nominal_radius = 50.0; - - // Initial state - Eigen::VectorXd initial_state(8); - initial_state << nominal_radius, 0.0, 0.0, 0.0, -2.0*mean_motion*nominal_radius, 0.0, mass, 0.0; - - // Final (reference/goal) state - Eigen::VectorXd goal_state(8); - goal_state << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, mass, 0.0; // Goal is the origin - - // Input constraints - double u_max = 1.0; // for each dimension - double u_min = -1.0; // for each dimension - double u_min_norm = 0.0; // Minimum thrust magnitude - double u_max_norm = 1.0; // Maximum thrust magnitude, consistent with previous u_max - - // Create the HCW system for optimization - std::unique_ptr hcw_system = - std::make_unique(dt, mean_motion, isp, g0, "euler"); - - // Cost weighting - double weight_terminal_fuel = 1.0; - double weight_terminal_pos = 1000.0; - double weight_terminal_vel = 1000.0; - - // Build cost objective - auto objective = std::make_unique( - weight_terminal_fuel, - goal_state, - weight_terminal_pos, - weight_terminal_vel, - dt); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 500; // May need more iterations for one-shot solve - options.line_search.max_iterations = 21; - options.tolerance = 1e-7; // Tighter tolerance for final solve - options.verbose = true; // Show solver progress - options.enable_parallel = false; - options.num_threads = 1; - options.regularization.initial_value = 1e-3; - options.ipddp.barrier.mu_initial = 1e-1; // Starting barrier coefficient - options.use_ilqr = true; - options.debug = true; - options.msipddp.segment_length = horizon / 10; - options.msipddp.rollout_type = "nonlinear"; - - // Initial trajectory. - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - // Generate initial trajectory by constant initial state - for (int i = 0; i < horizon; ++i) - { - X[i + 1] = hcw_system->getDiscreteDynamics(X[i], U[i], i * dt); - // X[i] = initial_state; - } - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - dt, - std::move(hcw_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - // Add Thrust Magnitude Constraint - cddp_solver.addPathConstraint("ThrustMagnitudeConstraint", - std::make_unique(u_min_norm, u_max_norm)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract the solution - const auto& X_solution = solution.state_trajectory; - const auto& U_solution = solution.control_trajectory; - - if (!X_solution.empty() && !U_solution.empty()) - { - namespace plt = matplot; - - // Create time vectors - std::vector t_states(horizon + 1); - for(int i = 0; i <= horizon; ++i) t_states[i] = i * dt; - - std::vector t_controls(horizon); - for(int i = 0; i < horizon; ++i) t_controls[i] = i * dt; - - // Extract individual state and control trajectories - std::vector x_pos(horizon + 1), y_pos(horizon + 1), z_pos(horizon + 1); - std::vector vx(horizon + 1), vy(horizon + 1), vz(horizon + 1); - std::vector mass_traj(horizon + 1), acc_effort_traj(horizon + 1); - - for (size_t i = 0; i < X_solution.size(); ++i) { - const auto& state = X_solution[i]; - if (state.size() >= 8) { // Ensure state has at least 8 dimensions - x_pos[i] = state(0); - y_pos[i] = state(1); - z_pos[i] = state(2); - vx[i] = state(3); - vy[i] = state(4); - vz[i] = state(5); - mass_traj[i] = state(6); - acc_effort_traj[i] = state(7); - } - } - - std::vector ux(horizon), uy(horizon), uz(horizon); - std::vector thrust_magnitude(horizon); - - for (size_t i = 0; i < U_solution.size(); ++i) { - const auto& control = U_solution[i]; - if (control.size() >= 3) { // Ensure control has at least 3 dimensions - ux[i] = control(0); - uy[i] = control(1); - uz[i] = control(2); - thrust_magnitude[i] = control.norm(); - } - } - - // --- Generate Plots --- - // plt::figure_size(1200, 800); // Removed due to compilation error - - // 1. Position Trajectories - plt::figure(); - plt::plot(t_states, x_pos)->line_width(2).display_name("x (pos)"); - plt::hold(true); - plt::plot(t_states, y_pos)->line_width(2).display_name("y (pos)"); - plt::plot(t_states, z_pos)->line_width(2).display_name("z (pos)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("Position vs. Time"); - - // 2. Velocity Trajectories - plt::figure(); - plt::plot(t_states, vx)->line_width(2).display_name("vx"); - plt::hold(true); - plt::plot(t_states, vy)->line_width(2).display_name("vy"); - plt::plot(t_states, vz)->line_width(2).display_name("vz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("Velocity vs. Time"); - - // 3. Mass Trajectory - plt::figure(); - plt::plot(t_states, mass_traj)->line_width(2).display_name("Mass (kg)"); - plt::xlabel("Time (s)"); - plt::ylabel("Mass (kg)"); - plt::legend(); - plt::title("Mass vs. Time"); - - // 4. Accumulated Control Effort - plt::figure(); - plt::plot(t_states, acc_effort_traj)->line_width(2).display_name("Accum. Effort"); - plt::xlabel("Time (s)"); - plt::ylabel("Effort"); - plt::legend(); - plt::title("Accumulated Control Effort vs. Time"); - - // 5. Control Inputs (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, ux)->line_width(2).display_name("ux"); - plt::hold(true); - plt::stairs(t_controls, uy)->line_width(2).display_name("uy"); - plt::stairs(t_controls, uz)->line_width(2).display_name("uz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Input"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time"); - - // 6. Thrust Magnitude (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, thrust_magnitude)->line_width(2).display_name("||Thrust|| (ZOH)"); - // Add norm constraint lines if available - // plt::hold(true); - // plt::plot(t_controls, std::vector(horizon, u_max_norm), "--r")->display_name("Max Norm"); - // if (u_min_norm > 0) plt::plot(t_controls, std::vector(horizon, u_min_norm), "--y")->display_name("Min Norm"); - // plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Thrust Magnitude"); - plt::legend(); - plt::title("Thrust Magnitude (ZOH) vs. Time"); - - // 7. 3D Trajectory - plt::figure(); - plt::plot3(x_pos, y_pos, z_pos, "-o")->line_width(2).marker_size(4).display_name("Trajectory"); - plt::hold(true); - // Plot Start and End points - if (!x_pos.empty()){ // Check if trajectories are not empty - plt::scatter3(std::vector{x_pos.front()}, std::vector{y_pos.front()}, std::vector{z_pos.front()}) - ->marker_color("g").marker_style("o").marker_size(10).display_name("Start"); - plt::scatter3(std::vector{x_pos.back()}, std::vector{y_pos.back()}, std::vector{z_pos.back()}) - ->marker_color("r").marker_style("x").marker_size(10).display_name("End"); - } - plt::hold(false); - plt::xlabel("x (m)"); - plt::ylabel("y (m)"); - plt::zlabel("z (m)"); - plt::legend(); - plt::title("3D Trajectory"); - plt::axis(plt::equal); // For aspect_ratio=:equal - - - // Show all plots - plt::show(); - std::cout << "Final mass: " << mass_traj.back() << std::endl; - std::cout << "Plotting complete." << std::endl; - } - else - { - std::cout << "Solver did not find a solution, or solution variables are not available. Skipping plots." << std::endl; - } - - return 0; -} \ No newline at end of file diff --git a/examples/cddp_spacecraft_rpo_mc.cpp b/examples/cddp_spacecraft_rpo_mc.cpp deleted file mode 100644 index b8ef0d98..00000000 --- a/examples/cddp_spacecraft_rpo_mc.cpp +++ /dev/null @@ -1,392 +0,0 @@ -/* - Copyright 2025 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -namespace cddp -{ - class SumOfTwoNormObjective : public NonlinearObjective - { - public: - SumOfTwoNormObjective(const Eigen::VectorXd &goal_state, - double weight_running_control, - double weight_terminal_state, - double timestep) - : NonlinearObjective(timestep), - goal_state_(goal_state), - weight_running_control_(weight_running_control), - weight_terminal_state_(weight_terminal_state) - { - } - - double running_cost(const Eigen::VectorXd &state, - const Eigen::VectorXd &control, - int /*index*/) const override - { - double control_squared = control.squaredNorm(); - double control_norm = std::sqrt(control_squared + epsilon_); - return weight_running_control_ * control_norm; - } - - double terminal_cost(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return weight_terminal_state_ * state_error.squaredNorm(); - } - - // Analytical Gradients - Eigen::VectorXd getRunningCostStateGradient(const Eigen::VectorXd &state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::VectorXd::Zero(state.size()); // Or handle error appropriately if size unknown - } - - Eigen::VectorXd getRunningCostControlGradient(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - if (norm_u < 1e-8) - { - return Eigen::VectorXd::Zero(control.size()); - } - return weight_running_control_ * control / norm_u; - } - - Eigen::VectorXd getFinalCostGradient(const Eigen::VectorXd &final_state) const override - { - Eigen::VectorXd state_error = final_state - goal_state_; - return 2.0 * weight_terminal_state_ * state_error; - } - - // Analytical Hessians - Eigen::MatrixXd getRunningCostStateHessian(const Eigen::VectorXd &state, const Eigen::VectorXd & /*control*/, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(state.size(), state.size()); - } - - Eigen::MatrixXd getRunningCostControlHessian(const Eigen::VectorXd & /*state*/, const Eigen::VectorXd &control, int /*index*/) const override - { - double norm_u = std::sqrt(control.squaredNorm() + epsilon_); - int control_dim = control.size(); - if (norm_u < 1e-8) - { - return weight_running_control_ * Eigen::MatrixXd::Identity(control_dim, control_dim) / 1e-8; // or a small value like 1.0 - } - Eigen::MatrixXd I = Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd u_ut = control * control.transpose(); - return weight_running_control_ * (I / norm_u - u_ut / (norm_u * norm_u * norm_u)); - } - - Eigen::MatrixXd getRunningCostCrossHessian(const Eigen::VectorXd &state, const Eigen::VectorXd &control, int /*index*/) const override - { - return Eigen::MatrixXd::Zero(control.size(), state.size()); - } - - Eigen::MatrixXd getFinalCostHessian(const Eigen::VectorXd & /*final_state*/) const override - { - int state_dim = goal_state_.size(); - return 2.0 * weight_terminal_state_ * Eigen::MatrixXd::Identity(state_dim, state_dim); - } - - private: - Eigen::VectorXd goal_state_; - double weight_running_control_; - double weight_terminal_state_; - double epsilon_ = 1e-5; - }; -} // namespace cddp - -namespace fs = std::filesystem; -using namespace cddp; - -int main() -{ - // Monte Carlo parameters - int num_mc_runs = 10; - int successful_runs = 0; - std::vector first_successful_X_solution; - std::vector first_successful_U_solution; - - // Setup random number generation for initial state perturbation - std::mt19937 gen(42); // Fixed seed for reproducibility - // Define distributions for perturbations - - std::normal_distribution<> pos_perturb_dist(0.0, 0.05); - std::normal_distribution<> vel_perturb_dist(0.0, 0.005); - - for (int mc_run = 0; mc_run < num_mc_runs; ++mc_run) - { - std::cout << "\n--- Monte Carlo Run: " << mc_run + 1 << "/" << num_mc_runs << " ---" << std::endl; - - // Optimization horizon info - int horizon = 200; // Optimization horizon length - double time_horizon = 200.0; // Time horizon for optimization [s] - double dt = time_horizon / horizon; // Time step for optimization - int state_dim = 6; - int control_dim = 3; - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - double nominal_radius = 50.0; - - // Initial state (nominal) - Eigen::VectorXd nominal_initial_state(state_dim); - nominal_initial_state << nominal_radius, 0.0, 0.0, 0.0, -2.0 * mean_motion * nominal_radius, 0.0; - - // Perturb initial state - Eigen::VectorXd initial_state = nominal_initial_state; - initial_state(0) += nominal_radius * pos_perturb_dist(gen); // Perturb x - initial_state(1) += nominal_radius * pos_perturb_dist(gen); // Perturb y - initial_state(2) += nominal_radius * pos_perturb_dist(gen); // Perturb z - initial_state(3) += std::abs(nominal_initial_state(4)) * vel_perturb_dist(gen); // Perturb vx (use initial vy magnitude for scaling) - initial_state(4) += std::abs(nominal_initial_state(4)) * vel_perturb_dist(gen); // Perturb vy - initial_state(5) += std::abs(nominal_initial_state(4)) * vel_perturb_dist(gen); // Perturb vz - - // Final (reference/goal) state - Eigen::VectorXd goal_state(state_dim); - goal_state.setZero(); // Goal is the origin - - // Input constraints - double u_max = 1.0; // for each dimension - double u_min = -1.0; // for each dimension - double u_min_norm = 0.0; // Minimum thrust magnitude - double u_max_norm = 1.0; // Maximum thrust magnitude, consistent with previous u_max - - // Cost weighting for SumOfTwoNormObjective - double weight_running_control = 1.0; // Example value - double weight_terminal_state = 1000.0; // Example value - - // Create the HCW system for optimization - std::unique_ptr hcw_system = - std::make_unique(dt, mean_motion, mass, "euler"); - - // Build cost objective - auto objective = std::make_unique( - goal_state, - weight_running_control, - weight_terminal_state, - dt); - - // Setup IPDDP solver options - cddp::CDDPOptions options; - options.max_iterations = 1000; - options.line_search.max_iterations = 21; - options.tolerance = 1e-7; - options.verbose = false; - options.debug = false; - options.print_solver_header = false; - options.enable_parallel = false; - options.num_threads = 1; - // Regularization type is now implicit in new API - options.regularization.initial_value = 1e-5; - options.ipddp.barrier.mu_initial = 1e-1; - options.use_ilqr = true; - options.msipddp.segment_length = horizon / 10; - options.msipddp.rollout_type = "nonlinear"; - - // Initial trajectory. - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - X[0] = initial_state; - for (int i = 0; i < horizon; ++i) - { - X[i + 1] = initial_state; - } - - // Create CDDP solver. - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - dt, - std::move(hcw_system), - std::move(objective), - options); - cddp_solver.setInitialTrajectory(X, U); - - // Add Control Constraint - Eigen::VectorXd u_upper = Eigen::VectorXd::Constant(3, u_max); - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // Solve the Trajectory Optimization Problem - cddp::CDDPSolution solution = cddp_solver.solve("MSIPDDP"); - - const auto& state_trajectory = solution.state_trajectory; - const auto& control_trajectory = solution.control_trajectory; - bool converged = (solution.status_message == "OptimalSolutionFound" || solution.status_message == "AcceptableSolutionFound"); - - if (!state_trajectory.empty() && !control_trajectory.empty() && converged) - { - std::cout << "Run " << mc_run + 1 << " converged." << std::endl; - successful_runs++; - if (first_successful_X_solution.empty()) - { - first_successful_X_solution = state_trajectory; - first_successful_U_solution = control_trajectory; - } - } - else - { - std::cout << "Run " << mc_run + 1 << " did NOT converge or solution is empty." << std::endl; - } - } - - std::cout << "\n--- Monte Carlo Simulation Summary ---" << std::endl; - std::cout << "Total runs: " << num_mc_runs << std::endl; - std::cout << "Successful runs: " << successful_runs << std::endl; - std::cout << "Success rate: " << (static_cast(successful_runs) / num_mc_runs) * 100.0 << "%" << std::endl; - - // Plotting results from the first successful run - if (!first_successful_X_solution.empty() && !first_successful_U_solution.empty()) - { - namespace plt = matplot; - - int horizon = first_successful_U_solution.size(); - double time_horizon = 200.0; // Assuming this is fixed from the problem setup - double dt = time_horizon / horizon; - int state_dim = first_successful_X_solution[0].size(); - int control_dim = first_successful_U_solution[0].size(); - - // Create time vectors - std::vector t_states(horizon + 1); - for (int i = 0; i <= horizon; ++i) - t_states[i] = i * dt; - - std::vector t_controls(horizon); - for (int i = 0; i < horizon; ++i) - t_controls[i] = i * dt; - - // Extract individual state and control trajectories - std::vector x_pos(horizon + 1), y_pos(horizon + 1), z_pos(horizon + 1); - std::vector vx(horizon + 1), vy(horizon + 1), vz(horizon + 1); - - for (size_t i = 0; i < first_successful_X_solution.size(); ++i) - { - const auto &state = first_successful_X_solution[i]; - if (state.size() >= state_dim) - { - x_pos[i] = state(0); - y_pos[i] = state(1); - z_pos[i] = state(2); - vx[i] = state(3); - vy[i] = state(4); - vz[i] = state(5); - } - } - - std::vector ux(horizon), uy(horizon), uz(horizon); - std::vector thrust_magnitude(horizon); - - for (size_t i = 0; i < first_successful_U_solution.size(); ++i) - { - const auto &control = first_successful_U_solution[i]; - if (control.size() >= control_dim) - { - ux[i] = control(0); - uy[i] = control(1); - uz[i] = control(2); - thrust_magnitude[i] = control.norm(); - } - } - - // --- Generate Plots --- - // 1. Position Trajectories - plt::figure(); - plt::plot(t_states, x_pos)->line_width(2).display_name("x (pos)"); - plt::hold(true); - plt::plot(t_states, y_pos)->line_width(2).display_name("y (pos)"); - plt::plot(t_states, z_pos)->line_width(2).display_name("z (pos)"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Position (m)"); - plt::legend(); - plt::title("Position vs. Time (First Successful Run)"); - - // 2. Velocity Trajectories - plt::figure(); - plt::plot(t_states, vx)->line_width(2).display_name("vx"); - plt::hold(true); - plt::plot(t_states, vy)->line_width(2).display_name("vy"); - plt::plot(t_states, vz)->line_width(2).display_name("vz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Velocity (m/s)"); - plt::legend(); - plt::title("Velocity vs. Time (First Successful Run)"); - - // 5. Control Inputs (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, ux)->line_width(2).display_name("ux"); - plt::hold(true); - plt::stairs(t_controls, uy)->line_width(2).display_name("uy"); - plt::stairs(t_controls, uz)->line_width(2).display_name("uz"); - plt::hold(false); - plt::xlabel("Time (s)"); - plt::ylabel("Control Input"); - plt::legend(); - plt::title("Control Inputs (ZOH) vs. Time (First Successful Run)"); - - // 6. Thrust Magnitude (Zeroth-Order Hold) - plt::figure(); - plt::stairs(t_controls, thrust_magnitude)->line_width(2).display_name("||Thrust|| (ZOH)"); - plt::xlabel("Time (s)"); - plt::ylabel("Thrust Magnitude"); - plt::legend(); - plt::title("Thrust Magnitude (ZOH) vs. Time (First Successful Run)"); - - // 7. 3D Trajectory - plt::figure(); - plt::plot3(x_pos, y_pos, z_pos, "-o")->line_width(2).marker_size(4).display_name("Trajectory"); - plt::hold(true); - if (!x_pos.empty()) - { - plt::scatter3(std::vector{x_pos.front()}, std::vector{y_pos.front()}, std::vector{z_pos.front()}) - ->marker_color("g") - .marker_style("o") - .marker_size(10) - .display_name("Start"); - plt::scatter3(std::vector{x_pos.back()}, std::vector{y_pos.back()}, std::vector{z_pos.back()}) - ->marker_color("r") - .marker_style("x") - .marker_size(10) - .display_name("End"); - } - plt::hold(false); - plt::xlabel("x (m)"); - plt::ylabel("y (m)"); - plt::zlabel("z (m)"); - plt::legend(); - plt::title("3D Trajectory (First Successful Run)"); - plt::axis(plt::equal); - - // Show all plots - plt::show(); - std::cout << "Plotting complete for the first successful run." << std::endl; - } - else - { - std::cout << "No successful run to plot, or solution variables are not available." << std::endl; - } - return 0; -} diff --git a/examples/cddp_unicycle.cpp b/examples/cddp_unicycle.cpp index df5969a2..7117e598 100644 --- a/examples/cddp_unicycle.cpp +++ b/examples/cddp_unicycle.cpp @@ -13,207 +13,67 @@ See the License for the specific language governing permissions and limitations under the License. */ + #include #include -#include #include "cddp.hpp" #include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; int main() { - // Problem parameters - int state_dim = 3; - int control_dim = 2; - int horizon = 100; - double timestep = 0.03; - std::string integration_type = "euler"; + constexpr double kPi = 3.14159265358979323846; + constexpr int state_dim = 3; + constexpr int control_dim = 2; + constexpr int horizon = 100; + constexpr double timestep = 0.03; - // Create a unicycle instance - std::unique_ptr system = std::make_unique(timestep, integration_type); // Create unique_ptr + Eigen::VectorXd initial_state(state_dim); + initial_state << 0.0, 0.0, kPi / 4.0; - // Create objective function - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.5 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 50.0, 0.0, 0.0, - 0.0, 50.0, 0.0, - 0.0, 0.0, 10.0; - Qf = 0.5 * Qf; Eigen::VectorXd goal_state(state_dim); - goal_state << 2.0, 2.0, M_PI/2.0; + goal_state << 2.0, 2.0, kPi / 2.0; - // Create an empty vector of Eigen::VectorXd - std::vector empty_reference_states; - auto objective = std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial and target states - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI/4.0; + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); + Eigen::MatrixXd R = 0.5 * Eigen::MatrixXd::Identity(control_dim, control_dim); + Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); + Qf.diagonal() << 25.0, 25.0, 5.0; - // Set options cddp::CDDPOptions options; - options.max_iterations = 10; + options.max_iterations = 20; options.ipddp.barrier.mu_initial = 1e-2; options.ipddp.barrier.mu_update_factor = 0.1; - // Create CDDP solver with new API - cddp::CDDP cddp_solver(initial_state, goal_state, horizon, timestep, - std::move(system), std::move(objective), options); - - // Define constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -1.0, -M_PI; - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.0, M_PI; - - // Add the constraint to the solver - cddp_solver.addPathConstraint(std::string("ControlConstraint"), std::make_unique(control_lower_bound, control_upper_bound)); - auto constraint = cddp_solver.getConstraint("ControlConstraint"); - - // Set initial trajectory - std::vector X(horizon + 1, Eigen::VectorXd::Zero(state_dim)); - std::vector U(horizon, Eigen::VectorXd::Zero(control_dim)); - cddp_solver.setInitialTrajectory(X, U); - - // Solve the problem - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::CLDDP); - - // Extract solution - const auto& X_sol = solution.state_trajectory; // size: horizon + 1 - const auto& U_sol = solution.control_trajectory; // size: horizon - const auto& t_sol = solution.time_points; // size: horizon + 1 - - // Create directory for saving plot (if it doesn't exist) - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Plot the solution (x-y plane) - auto x_arr = cddp::example::extractComponent(X_sol, 0); - auto y_arr = cddp::example::extractComponent(X_sol, 1); - auto theta_arr = cddp::example::extractComponent(X_sol, 2); - - // Plot the solution (control inputs) - auto v_arr = cddp::example::extractComponent(U_sol, 0); - auto omega_arr = cddp::example::extractComponent(U_sol, 1); - - // ----------------------------- - // Plot states and controls - // ----------------------------- - auto f1 = figure(); - f1->size(1200, 800); - - // First subplot: Position Trajectory - auto ax1 = subplot(3, 1, 0); - auto plot_handle = plot(ax1, x_arr, y_arr, "-b"); - plot_handle->line_width(3); - title(ax1, "Position Trajectory"); - xlabel(ax1, "x [m]"); - ylabel(ax1, "y [m]"); - - // Second subplot: Heading Angle vs Time - auto ax2 = subplot(3, 1, 1); - auto heading_plot_handle = plot(ax2, t_sol, theta_arr); - heading_plot_handle->line_width(3); - title(ax2, "Heading Angle"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "theta [rad]"); - - // Fourth subplot: Control Inputs - auto ax4 = subplot(3, 1, 2); - auto p1 = plot(ax4, v_arr, "--b"); - p1->line_width(3); - p1->display_name("Acceleration"); - - hold(ax4, true); - auto p2 = plot(ax4, omega_arr, "--r"); - p2->line_width(3); - p2->display_name("Steering"); - - title(ax4, "Control Inputs"); - xlabel(ax4, "Step"); - ylabel(ax4, "Control"); - matplot::legend(ax4); - - f1->draw(); - f1->save(plotDirectory + "/unicycle_cddp_results.png"); - - // ----------------------------- - // Animation: unicycle Trajectory - // ----------------------------- - auto f2 = figure(); - f2->size(800, 600); - auto ax_anim = f2->current_axes(); - if (!ax_anim) - { - ax_anim = axes(); + cddp::CDDP solver( + initial_state, + goal_state, + horizon, + timestep, + std::make_unique(timestep, "euler"), + std::make_unique( + Q, R, Qf, goal_state, std::vector{}, timestep), + options); + + Eigen::VectorXd lower(control_dim); + lower << -1.0, -kPi; + Eigen::VectorXd upper(control_dim); + upper << 1.0, kPi; + solver.addPathConstraint("ControlConstraint", + std::make_unique(lower, upper)); + + auto [X, U] = + cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); + solver.setInitialTrajectory(X, U); + + const cddp::CDDPSolution solution = solver.solve(cddp::SolverType::CLDDP); + if (solution.state_trajectory.empty()) { + std::cerr << "Unicycle example failed: empty trajectory" << std::endl; + return 1; } - double car_length = 0.35; - double car_width = 0.15; - - for (size_t i = 0; i < X_sol.size(); ++i) - { - if (i % 10 == 0) - { - ax_anim->clear(); - hold(ax_anim, true); - - double x = x_arr[i]; - double y = y_arr[i]; - double theta = theta_arr[i]; - - // Compute unicycle rectangle corners - std::vector car_x(5), car_y(5); - car_x[0] = x + car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[0] = y + car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[1] = x + car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[1] = y + car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[2] = x - car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[2] = y - car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[3] = x - car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[3] = y - car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - auto car_line = plot(ax_anim, car_x, car_y); - car_line->color("black"); - car_line->line_style("solid"); - car_line->line_width(2); - car_line->display_name("Car"); - - // Plot trajectory up to current frame - std::vector traj_x(x_arr.begin(), x_arr.begin() + i + 1); - std::vector traj_y(y_arr.begin(), y_arr.begin() + i + 1); - auto traj_line = plot(ax_anim, traj_x, traj_y); - traj_line->color("blue"); - traj_line->line_style("solid"); - traj_line->line_width(1.5); - traj_line->display_name("Trajectory"); - - title(ax_anim, "unicycle Trajectory"); - xlabel(ax_anim, "x [m]"); - ylabel(ax_anim, "y [m]"); - xlim(ax_anim, {-1, 2.2}); - ylim(ax_anim, {-1, 2.2}); - // legend(ax_anim); - - std::string filename = plotDirectory + "/unicycle_frame_" + std::to_string(i) + ".png"; - f2->draw(); - f2->save(filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/unicycle_frame_*.png " + plotDirectory + "/unicycle.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/unicycle_frame_*.png"; - std::system(cleanup_command.c_str()); + const Eigen::VectorXd final_error = solution.state_trajectory.back() - goal_state; + std::cout << "Unicycle example completed with status: " + << solution.status_message << '\n' + << "Final objective: " << solution.final_objective << '\n' + << "Final state error norm: " << final_error.norm() << std::endl; + return 0; } diff --git a/examples/cddp_unicycle_mpc.cpp b/examples/cddp_unicycle_mpc.cpp deleted file mode 100644 index e798d161..00000000 --- a/examples/cddp_unicycle_mpc.cpp +++ /dev/null @@ -1,289 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -// Helper function to create a circular reference trajectory -std::vector create_circular_trajectory( - double radius, double center_x, double center_y, - double total_time, double dt) -{ - int num_points = static_cast(total_time / dt) + 1; - std::vector trajectory; - trajectory.reserve(num_points); - double angular_velocity = 2.0 * M_PI / total_time; - - for (int i = 0; i < num_points; ++i) - { - double t = i * dt; - double angle = angular_velocity * t; - Eigen::VectorXd state(3); - state(0) = center_x + radius * cos(angle); - state(1) = center_y + radius * sin(angle); - state(2) = angle + M_PI / 2.0; // Tangent to the circle - trajectory.push_back(state); - } - return trajectory; -} - -int main() -{ - // -------------------------- - // 1. Problem and MPC Setup - // -------------------------- - const int state_dim = 3; // [x, y, theta] - const int control_dim = 2; // [v, omega] - const int mpc_horizon = 30; // N in the python notebook - const double mpc_timestep = 0.1; // dt in the python notebook - const std::string integration_type = "euler"; - - // Simulation parameters - const double sim_time = 10.0; - const double sim_dt = 0.1; // controller_dt in python notebook - - // Create a unicycle instance (will be reused) - auto dyn_system_template = std::make_unique(mpc_timestep, integration_type); - - // Quadratic cost matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Q.diagonal() << 30.0, 30.0, 0.1; - Eigen::MatrixXd R = Eigen::MatrixXd::Identity(control_dim, control_dim); - R.diagonal() << 1.0, 0.1; - Eigen::MatrixXd Qf = 30.0 * Q; // Terminal cost weight from python notebook - - // Create reference trajectory - auto reference_trajectory = create_circular_trajectory(1.0, 0.0, 0.0, sim_time, sim_dt); - - // Initial state - Eigen::VectorXd current_state(state_dim); - current_state << 0.0, -1.0, 0.0; - - // IPDDP Solver Options - cddp::CDDPOptions options_ipddp; - options_ipddp.max_iterations = 15; - options_ipddp.tolerance = 1e-4; - options_ipddp.verbose = false; // Keep it clean for the MPC loop - options_ipddp.debug = false; - options_ipddp.enable_parallel = false; // Can be true for performance - options_ipddp.num_threads = 1; - options_ipddp.regularization.initial_value = 1e-4; - options_ipddp.warm_start = true; - - // Constraint parameters - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.5, M_PI; - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << 0.0, -M_PI; - - // Obstacles (from python notebook) - // We will use the closest one at each step. - std::vector obstacles; - obstacles.push_back(Eigen::Vector3d(0.1, 1.3, 0.6)); - obstacles.push_back(Eigen::Vector3d(-0.85, -0.1, 0.2)); - obstacles.push_back(Eigen::Vector3d(-0.7, -0.75, 0.1)); - - // Simulation history storage - std::vector state_history; - std::vector control_history; - std::vector time_history; - state_history.push_back(current_state); - time_history.push_back(0.0); - - // Initial trajectory guess for the first MPC solve - std::vector X_guess(mpc_horizon + 1, current_state); - std::vector U_guess(mpc_horizon, Eigen::VectorXd::Zero(control_dim)); - - // -------------------------- - // 2. MPC Loop - // -------------------------- - std::cout << "Running IPDDP-based MPC for Unicycle Tracking..." << std::endl; - double current_time = 0.0; - int sim_steps = static_cast(sim_time / sim_dt); - - for (int k = 0; k < sim_steps; ++k) - { - // Get current reference trajectory slice for the MPC horizon - std::vector mpc_ref_traj; - int ref_start_idx = k; - for (int i = 0; i <= mpc_horizon; ++i) - { - int idx = std::min(ref_start_idx + i, (int)reference_trajectory.size() - 1); - mpc_ref_traj.push_back(reference_trajectory[idx]); - } - Eigen::VectorXd mpc_goal_state = mpc_ref_traj.back(); - - // Create objective for this MPC step - auto objective = std::make_unique(Q, R, Qf, mpc_goal_state, mpc_ref_traj, mpc_timestep); - - // Create CDDP solver instance for this MPC step - auto system = std::make_unique(mpc_timestep, integration_type); - cddp::CDDP cddp_solver(current_state, mpc_goal_state, mpc_horizon, mpc_timestep, - std::move(system), std::move(objective), options_ipddp); - - // Find closest obstacle and add constraint - Eigen::Vector2d current_pos = current_state.head(2); - double min_dist = std::numeric_limits::max(); - Eigen::Vector3d closest_obstacle; - for(const auto& obs : obstacles) - { - double dist = (current_pos - obs.head(2)).norm() - obs(2); - if(dist < min_dist) - { - min_dist = dist; - closest_obstacle = obs; - } - } - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); - cddp_solver.addPathConstraint("BallConstraint", - std::make_unique(closest_obstacle(2), closest_obstacle.head(2))); - - // Set initial trajectory (warm start) - cddp_solver.setInitialTrajectory(X_guess, U_guess); - - // Solve the OCP - cddp::CDDPSolution solution = cddp_solver.solve("IPDDP"); - - // Extract and apply the first control - const auto& status = solution.status_message; - if (status != "OptimalSolutionFound" && status != "AcceptableSolutionFound") - { - std::cerr << "Warning: Solver did not converge at step " << k << ". Status: " << status << std::endl; - // Handle non-convergence, e.g., by applying zero control or previous control - } - - const auto& U_sol = solution.control_trajectory; - Eigen::VectorXd control_to_apply = U_sol[0]; - - // Propagate system dynamics - current_state = dyn_system_template->getDiscreteDynamics(current_state, control_to_apply, 0.0); - - // Update history - state_history.push_back(current_state); - control_history.push_back(control_to_apply); - current_time += sim_dt; - time_history.push_back(current_time); - - // Warm start for the next iteration: shift the solution - const auto& X_sol = solution.state_trajectory; - for(int i = 0; i < mpc_horizon -1; ++i) - { - X_guess[i] = X_sol[i+1]; - U_guess[i] = U_sol[i+1]; - } - X_guess[mpc_horizon -1] = X_sol[mpc_horizon]; - X_guess[mpc_horizon] = X_sol[mpc_horizon]; // Extrapolate or use goal - U_guess[mpc_horizon -1] = U_sol[mpc_horizon-1]; // Hold last control - - std::cout << "MPC Step: " << k+1 << "/" << sim_steps <<", Time: " << current_time << "s, X: [" << current_state.transpose() << "], U: [" << control_to_apply.transpose() << "]" << std::endl; - } - std::cout << "Simulation finished." << std::endl; - - // -------------------------- - // 3. Plotting - // -------------------------- - // Convert trajectories to plottable vectors - std::vector x_hist, y_hist, theta_hist; - for(const auto& s : state_history) - { - x_hist.push_back(s(0)); - y_hist.push_back(s(1)); - theta_hist.push_back(s(2)); - } - std::vector v_hist, omega_hist; - for(const auto& u : control_history) - { - v_hist.push_back(u(0)); - omega_hist.push_back(u(1)); - } - std::vector x_ref, y_ref; - for(const auto& s : reference_trajectory) - { - x_ref.push_back(s(0)); - y_ref.push_back(s(1)); - } - - auto f = figure(true); - f->size(1200, 1000); - f->position(100, 100); - - // Trajectory plot - auto ax1 = subplot(2, 1, 1); - matplot::plot(ax1, x_hist, y_hist, "b-")->line_width(2).display_name("Actual Trajectory"); - matplot::hold(true); - matplot::plot(ax1, x_ref, y_ref, "r--")->line_width(2).display_name("Reference Trajectory"); - - // Plot obstacles - for(const auto& obs : obstacles) - { - std::vector circle_x, circle_y; - for (double theta = 0; theta <= 2*M_PI; theta += 0.01) { - circle_x.push_back(obs(0) + obs(2) * std::cos(theta)); - circle_y.push_back(obs(1) + obs(2) * std::sin(theta)); - } - matplot::plot(ax1, circle_x, circle_y, "k--")->line_width(2).display_name("Obstacle"); - } - - // Mark start and end - auto start_scatter = scatter(ax1, std::vector{x_hist.front()}, std::vector{y_hist.front()}); - start_scatter->marker_color("g").marker_size(100).display_name("Start"); - auto end_scatter = scatter(ax1, std::vector{x_hist.back()}, std::vector{y_hist.back()}); - end_scatter->marker_color("r").marker_size(100).display_name("End"); - - matplot::title(ax1, "Unicycle MPC-CBF Tracking"); - matplot::xlabel(ax1, "X [m]"); - matplot::ylabel(ax1, "Y [m]"); - matplot::legend(ax1, "show"); - matplot::grid(ax1, true); - matplot::axis(ax1, equal); - - // Control plot - auto ax2 = subplot(2, 1, 2); - std::vector control_time_hist = time_history; - control_time_hist.pop_back(); // control history is one step shorter - matplot::plot(ax2, control_time_hist, v_hist, "b-")->line_width(2).display_name("Linear Velocity (v)"); - hold(true); - matplot::plot(ax2, control_time_hist, omega_hist, "g-")->line_width(2).display_name("Angular Velocity (omega)"); - matplot::title(ax2, "Control Inputs vs. Time"); - matplot::xlabel(ax2, "Time [s]"); - matplot::ylabel(ax2, "Control Value"); - matplot::legend(ax2, "show"); - matplot::grid(ax2, true); - - // Save and show plot - const std::string plotDirectory = "../results/examples"; - cddp::example::ensurePlotDir(plotDirectory); - save(plotDirectory + "/unicycle_mpc_cbf.png"); - std::cout << "Saved plot to " << plotDirectory << "/unicycle_mpc_cbf.png" << std::endl; - show(); - - return 0; -} \ No newline at end of file diff --git a/examples/cddp_unicycle_safe.cpp b/examples/cddp_unicycle_safe.cpp deleted file mode 100644 index a8f24bc2..00000000 --- a/examples/cddp_unicycle_safe.cpp +++ /dev/null @@ -1,219 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -// Include matplot -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -int main() { - // ------------------------------------------------------- - // 1. Problem Setup - // ------------------------------------------------------- - int state_dim = 3; - int control_dim = 2; - int horizon = 100; - double timestep = 0.03; - std::string integration_type = "euler"; - - // Create a unicycle dynamical system instance - std::unique_ptr dyn_system = - std::make_unique(timestep, integration_type); - - // Create objective function - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.05 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 100.0, 0.0, 0.0, - 0.0, 100.0, 0.0, - 0.0, 0.0, 100.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 2.0, 2.0, M_PI / 2.0; - - // Empty reference states (if needed) - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep - ); - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI / 4.0; - - // CDDP options - cddp::CDDPOptions options; - options.max_iterations = 100; - options.verbose = true; - options.debug = false; - options.tolerance = 1e-5; - options.acceptable_tolerance = 1e-4; - options.regularization.initial_value = 1e-5; - - // Define control box constraints - Eigen::VectorXd control_lower_bound(control_dim); - control_lower_bound << -2.0, -M_PI; - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 2.0, M_PI; - - // ------------------------------------------------------- - // 2. Solve the CDDP Problem (No Ball Constraint) - // ------------------------------------------------------- - cddp::CDDP solver_baseline( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - - // Set constraints - solver_baseline.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); - - // Simple initial guess: states = initial_state, controls = zeros - std::vector X_baseline(horizon + 1, initial_state); - std::vector U_baseline(horizon, Eigen::VectorXd::Zero(control_dim)); - solver_baseline.setInitialTrajectory(X_baseline, U_baseline); - - // Solve - cddp::CDDPSolution solution_baseline = solver_baseline.solve(cddp::SolverType::IPDDP); - const auto& X_baseline_sol = solution_baseline.state_trajectory; // size horizon + 1 - - // ------------------------------------------------------- - // 3. Solve with BallConstraint - // ------------------------------------------------------- - cddp::CDDP solver_ball( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - solver_ball.addPathConstraint("ControlConstraint", - std::make_unique(control_lower_bound, control_upper_bound)); - - // Add the BallConstraint - double radius = 0.4; - Eigen::Vector2d center(1.0, 1.0); - solver_ball.addPathConstraint("BallConstraint", - std::make_unique(radius, center)); - - // Initial trajectory for the ball-constrained solver - std::vector X_ball(horizon + 1, initial_state); - std::vector U_ball(horizon, Eigen::VectorXd::Zero(control_dim)); - solver_ball.setInitialTrajectory(X_ball, U_ball); - - // Solve - cddp::CDDPSolution solution_ball = solver_ball.solve(cddp::SolverType::IPDDP); - const auto& X_ball_sol = solution_ball.state_trajectory; // horizon+1 - - // ------------------------------------------------------- - // 4. Prepare Data for Plotting - // ------------------------------------------------------- - std::vector x_baseline, y_baseline; - std::vector x_ball_vec, y_ball_vec; - x_baseline.reserve(X_baseline_sol.size()); - y_baseline.reserve(X_baseline_sol.size()); - x_ball_vec.reserve(X_ball_sol.size()); - y_ball_vec.reserve(X_ball_sol.size()); - - // Convert baseline solution states - for (const auto &state : X_baseline_sol) { - x_baseline.push_back(state(0)); - y_baseline.push_back(state(1)); - } - // Convert ball-constrained solution states - for (const auto &state : X_ball_sol) { - x_ball_vec.push_back(state(0)); - y_ball_vec.push_back(state(1)); - } - - // Prepare circle points for the ball constraint - std::vector x_circle, y_circle; - x_circle.reserve(630); // ~ (2*pi / 0.01) - y_circle.reserve(630); - - for (double t = 0.0; t < 2.0 * M_PI; t += 0.01) { - x_circle.push_back(center(0) + radius * std::cos(t)); - y_circle.push_back(center(1) + radius * std::sin(t)); - } - - // ------------------------------------------------------- - // 5. Plot with matplot - // ------------------------------------------------------- - // Create the figure window - auto f1 = figure(true); // 'true' => make it visible (depending on your system) - f1->size(800, 600); - - // Create an axes object - auto ax = f1->current_axes(); - - // Plot the baseline solution (blue) - auto h_baseline = plot(ax, x_baseline, y_baseline); - h_baseline->line_width(2); - h_baseline->display_name("Without Ball Constraint"); - h_baseline->color("blue"); - - // Plot the ball-constrained solution (red) - hold(ax, true); - auto h_ball = plot(ax, x_ball_vec, y_ball_vec); - h_ball->line_width(2); - h_ball->display_name("With Ball Constraint"); - h_ball->color("red"); - - // Plot the constraint circle (green, dashed) - auto h_circle = plot(ax, x_circle, y_circle); - h_circle->line_style("--"); - h_circle->line_width(2); - h_circle->color("green"); - h_circle->display_name("Ball Constraint Region"); - - // Add title, labels, legend - title(ax, "Trajectory Comparison: With vs. Without BallConstraint"); - xlabel(ax, "x"); - ylabel(ax, "y"); - xlim(ax, {-0.5, 2.5}); - ylim(ax, {-0.5, 2.5}); - matplot::legend(ax); - - // Create directory for saving (if not existing) - std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // Save figure - f1->draw(); - f1->save(plotDirectory + "/trajectory_comparison_matplot.png"); - std::cout << "Trajectory comparison saved to " - << plotDirectory + "/trajectory_comparison_matplot.png" << std::endl; - - return 0; -} diff --git a/examples/cddp_unicycle_safe_ipddp.cpp b/examples/cddp_unicycle_safe_ipddp.cpp deleted file mode 100644 index 7afcc951..00000000 --- a/examples/cddp_unicycle_safe_ipddp.cpp +++ /dev/null @@ -1,406 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -int main() { - // -------------------------- - // 1. Problem setup - // -------------------------- - int state_dim = 3; // [x, y, theta] - int control_dim = 2; // [v, omega] - int horizon = 100; - double timestep = 0.03; - std::string integration_type = "euler"; - - // Create a unicycle dynamical system instance - std::unique_ptr dyn_system = - std::make_unique(timestep, integration_type); - - // Objective weighting matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.05 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 100.0, 0.0, 0.0, - 0.0, 100.0, 0.0, - 0.0, 0.0, 100.0; - - // Goal state - Eigen::VectorXd goal_state(state_dim); - goal_state << 2.0, 2.0, M_PI/2.0; - - // Create an empty reference state vector - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI/4.0; - - // CDDP options - cddp::CDDPOptions options; - options.max_iterations = 100; - options.verbose = true; - options.debug = false; - options.enable_parallel = false; - options.num_threads = 1; - options.tolerance = 1e-4; - options.acceptable_tolerance = 1e-3; - options.regularization.initial_value = 1e-2; - options.ipddp.barrier.mu_initial = 1e-1; - - // Define control constraint - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.1, M_PI; // clamp velocity and steering - - // Ball constraint parameters - double radius = 0.4; - Eigen::Vector2d center(1.0, 1.0); - - // Create a directory for saving plots (if it doesn't exist) - const std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - // -------------------------- - // 2. Solve - NO Ball constraint - // -------------------------- - cddp::CDDP solver_baseline( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - // Solver with new API already set up with system and objective - - // Add a control constraint - solver_baseline.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // Naive initial trajectory - std::vector X_baseline_init(horizon + 1, initial_state); - std::vector U_baseline_init(horizon, Eigen::VectorXd::Zero(control_dim)); - solver_baseline.setInitialTrajectory(X_baseline_init, U_baseline_init); - - // Solve - cddp::CDDPSolution solution_baseline = solver_baseline.solve(cddp::SolverType::MSIPDDP); - const auto& X_baseline_sol = solution_baseline.state_trajectory; // horizon+1 - const auto& U_baseline_sol = solution_baseline.control_trajectory; // horizon - const auto& T_baseline_sol = solution_baseline.time_points; // horizon+1 - - // -------------------------- - // 3. Solve - WITH Ball constraint (naive init) - // -------------------------- - cddp::CDDP solver_ball( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - // Solver with new API already set up with system and objective - - // Add constraints - solver_ball.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - solver_ball.addPathConstraint("BallConstraint", - std::make_unique(radius, center)); - - // Naive initial trajectory - std::vector X_ball_init(horizon + 1, initial_state); - std::vector U_ball_init(horizon, Eigen::VectorXd::Zero(control_dim)); - solver_ball.setInitialTrajectory(X_ball_init, U_ball_init); - - // Solve - cddp::CDDPSolution solution_ball = solver_ball.solve(cddp::SolverType::MSIPDDP); - const auto& X_ball_sol = solution_ball.state_trajectory; - const auto& U_ball_sol = solution_ball.control_trajectory; - const auto& T_ball_sol = solution_ball.time_points; - - // -------------------------- - // 4. Solve - WITH Ball constraint (baseline init) - // -------------------------- - cddp::CDDP solver_ball_with_baseline( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - // Solver with new API already set up with system and objective - - // Add constraints - solver_ball_with_baseline.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - solver_ball_with_baseline.addPathConstraint("BallConstraint", - std::make_unique(radius, center)); - - // Use baseline solution as initialization - solver_ball_with_baseline.setInitialTrajectory(X_baseline_sol, U_baseline_sol); - - // Solve - cddp::CDDPSolution solution_ball_with_baseline = solver_ball_with_baseline.solve(cddp::SolverType::IPDDP); - const auto& X_ball_with_baseline_sol = solution_ball_with_baseline.state_trajectory; - const auto& U_ball_with_baseline_sol = solution_ball_with_baseline.control_trajectory; - const auto& T_ball_with_baseline_sol = solution_ball_with_baseline.time_points; - - // -------------------------- - // 5. Convert solutions to std::vectors for plotting - // We'll do: X vs Y, Theta vs time, Controls vs step - // -------------------------- - // Baseline - std::vector x_base, y_base, theta_base, t_base; - std::vector v_base, omega_base; - for (size_t i = 0; i < X_baseline_sol.size(); ++i) { - x_base.push_back(X_baseline_sol[i](0)); - y_base.push_back(X_baseline_sol[i](1)); - theta_base.push_back(X_baseline_sol[i](2)); - if (i < T_baseline_sol.size()) { - t_base.push_back(T_baseline_sol[i]); - } - } - for (size_t i = 0; i < U_baseline_sol.size(); ++i) { - v_base.push_back(U_baseline_sol[i](0)); - omega_base.push_back(U_baseline_sol[i](1)); - } - - // Ball (naive init) - std::vector x_ball, y_ball, theta_ball, t_ball; - std::vector v_ball, omega_ball; - for (size_t i = 0; i < X_ball_sol.size(); ++i) { - x_ball.push_back(X_ball_sol[i](0)); - y_ball.push_back(X_ball_sol[i](1)); - theta_ball.push_back(X_ball_sol[i](2)); - if (i < T_ball_sol.size()) { - t_ball.push_back(T_ball_sol[i]); - } - } - for (size_t i = 0; i < U_ball_sol.size(); ++i) { - v_ball.push_back(U_ball_sol[i](0)); - omega_ball.push_back(U_ball_sol[i](1)); - } - - // Ball with baseline init - std::vector x_ball_bl, y_ball_bl, theta_ball_bl, t_ball_bl; - std::vector v_ball_bl, omega_ball_bl; - for (size_t i = 0; i < X_ball_with_baseline_sol.size(); ++i) { - x_ball_bl.push_back(X_ball_with_baseline_sol[i](0)); - y_ball_bl.push_back(X_ball_with_baseline_sol[i](1)); - theta_ball_bl.push_back(X_ball_with_baseline_sol[i](2)); - if (i < T_ball_with_baseline_sol.size()) { - t_ball_bl.push_back(T_ball_with_baseline_sol[i]); - } - } - for (size_t i = 0; i < U_ball_with_baseline_sol.size(); ++i) { - v_ball_bl.push_back(U_ball_with_baseline_sol[i](0)); - omega_ball_bl.push_back(U_ball_with_baseline_sol[i](1)); - } - - // -------------------------- - // 6. Plot: Subplots for the three solutions - // -------------------------- - auto f1 = figure(true); - f1->size(1200, 800); - - // Subplot 1: XY Trajectories - auto ax1 = subplot(3, 1, 0); - plot(ax1, x_base, y_base, "-b")->display_name("No Ball"); - hold(ax1, true); - plot(ax1, x_ball, y_ball, "-r")->display_name("Ball (naive init)"); - plot(ax1, x_ball_bl, y_ball_bl, "-m")->display_name("Ball (baseline init)"); - - // Also plot the circular region for the ball constraint - std::vector circle_x, circle_y; - for (double th = 0.0; th <= 2.0 * M_PI; th += 0.01) { - circle_x.push_back(center(0) + radius * cos(th)); - circle_y.push_back(center(1) + radius * sin(th)); - } - plot(ax1, circle_x, circle_y, "--g")->display_name("Ball Constraint"); - - title(ax1, "Position Trajectory (X-Y plane)"); - xlabel(ax1, "x [m]"); - ylabel(ax1, "y [m]"); - matplot::legend(ax1); - - // Subplot 2: Heading Angle vs Time - auto ax2 = subplot(3, 1, 1); - plot(ax2, t_base, theta_base, "-b")->display_name("No Ball"); - hold(ax2, true); - plot(ax2, t_ball, theta_ball, "-r")->display_name("Ball (naive init)"); - plot(ax2, t_ball_bl, theta_ball_bl, "-m")->display_name("Ball (baseline init)"); - - title(ax2, "Heading Angle vs Time"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "Theta [rad]"); - matplot::legend(ax2); - - // Subplot 3: Control Inputs vs Step - auto ax3 = subplot(3, 1, 2); - // We'll overlay v and omega in the same subplot for each solution - // "No Ball" in blue - auto p1 = plot(ax3, v_base, "-b"); - p1->display_name("v - No Ball"); - hold(ax3, true); - auto p2 = plot(ax3, omega_base, "--b"); - p2->display_name("omega - No Ball"); - - // "Ball naive" in red - auto p3 = plot(ax3, v_ball, "-r"); - p3->display_name("v - Ball naive"); - auto p4 = plot(ax3, omega_ball, "--r"); - p4->display_name("omega - Ball naive"); - - // "Ball baseline init" in magenta - auto p5 = plot(ax3, v_ball_bl, "-m"); - p5->display_name("v - Ball baseline"); - auto p6 = plot(ax3, omega_ball_bl, "--m"); - p6->display_name("omega - Ball baseline"); - - title(ax3, "Control Inputs vs. Step"); - xlabel(ax3, "Step"); - ylabel(ax3, "Control value"); - matplot::legend(ax3); - - // Save the figure - f1->draw(); - f1->save(plotDirectory + "/trajectory_comparison_ipddp_matplot.png"); - - std::cout << "Saved comparison to " << (plotDirectory + "/trajectory_comparison_ipddp_matplot.png") << std::endl; - - // -------------------------- - // 7. (Optional) Animation for the final solution - // For demonstration, let's animate the "Ball (baseline init)" solution. - // -------------------------- - auto f2 = figure(true); - f2->size(800, 600); - auto ax_anim = f2->current_axes(); - if (!ax_anim) { - ax_anim = axes(); - } - - double unicycle_length = 0.35; - double unicycle_width = 0.15; - - // We'll sample frames every few steps to avoid too many images - for (size_t i = 0; i < X_ball_with_baseline_sol.size(); ++i) { - if (i % 5 == 0) { - ax_anim->clear(); - hold(ax_anim, true); - - double x = x_ball_bl[i]; - double y = y_ball_bl[i]; - double theta = theta_ball_bl[i]; - - // Compute corners of a rectangle representing the unicycle - std::vector car_x(5), car_y(5); - car_x[0] = x + unicycle_length / 2.0 * cos(theta) - - unicycle_width / 2.0 * sin(theta); - car_y[0] = y + unicycle_length / 2.0 * sin(theta) - + unicycle_width / 2.0 * cos(theta); - - car_x[1] = x + unicycle_length / 2.0 * cos(theta) - + unicycle_width / 2.0 * sin(theta); - car_y[1] = y + unicycle_length / 2.0 * sin(theta) - - unicycle_width / 2.0 * cos(theta); - - car_x[2] = x - unicycle_length / 2.0 * cos(theta) - + unicycle_width / 2.0 * sin(theta); - car_y[2] = y - unicycle_length / 2.0 * sin(theta) - - unicycle_width / 2.0 * cos(theta); - - car_x[3] = x - unicycle_length / 2.0 * cos(theta) - - unicycle_width / 2.0 * sin(theta); - car_y[3] = y - unicycle_length / 2.0 * sin(theta) - + unicycle_width / 2.0 * cos(theta); - - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - // Draw the unicycle rectangle - auto car_line = plot(ax_anim, car_x, car_y); - car_line->line_width(2); - - // Plot trajectory up to current frame - std::vector traj_x(x_ball_bl.begin(), x_ball_bl.begin() + i + 1); - std::vector traj_y(y_ball_bl.begin(), y_ball_bl.begin() + i + 1); - auto traj_line = plot(ax_anim, traj_x, traj_y); - traj_line->line_width(1.5); - - // Also show the ball constraint - std::vector circle_x_anim, circle_y_anim; - for (double th = 0.0; th <= 2.0 * M_PI; th += 0.01) { - circle_x_anim.push_back(center(0) + radius * cos(th)); - circle_y_anim.push_back(center(1) + radius * sin(th)); - } - plot(ax_anim, circle_x_anim, circle_y_anim, "--g"); - - title(ax_anim, "Unicycle Trajectory (Ball Constraint, baseline init)"); - xlabel(ax_anim, "x [m]"); - ylabel(ax_anim, "y [m]"); - xlim(ax_anim, {-0.5, 2.5}); - ylim(ax_anim, {-0.5, 2.5}); - - // Save each frame - std::string filename = plotDirectory + "/unicycle_safe_frame_" + std::to_string(i) + ".png"; - f2->draw(); - f2->save(filename); - - // Small pause so we can see the frames - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - } - - // ----------------------------- - // 8. Generate GIF from frames using ImageMagick (if installed) - // ----------------------------- - { - std::string gif_command = - "convert -delay 8 " + plotDirectory + "/unicycle_safe_frame_*.png " + - plotDirectory + "/unicycle_safe.gif"; - std::system(gif_command.c_str()); - - // Cleanup frames if you like - std::string cleanup_command = - "rm " + plotDirectory + "/unicycle_safe_frame_*.png"; - std::system(cleanup_command.c_str()); - } - - return 0; -} diff --git a/examples/cddp_unicycle_safe_ipddp_v2.cpp b/examples/cddp_unicycle_safe_ipddp_v2.cpp deleted file mode 100644 index 240fd970..00000000 --- a/examples/cddp_unicycle_safe_ipddp_v2.cpp +++ /dev/null @@ -1,193 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -// Include matplot -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -int main() { - // ------------------------------------------------- - // 1. Problem Setup - // ------------------------------------------------- - int state_dim = 3; - int control_dim = 2; - int horizon = 300; - double timestep = 0.03; - std::string integration_type = "euler"; - - // Create a unicycle dynamical system - auto dyn_system = std::make_unique(timestep, integration_type); - - // Create objective function - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.05 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 100.0, 0.0, 0.0, - 0.0, 100.0, 0.0, - 0.0, 0.0, 100.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 3.0, 3.0, M_PI / 2.0; - - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI / 4.0; - - // CDDP options - cddp::CDDPOptions options; - options.max_iterations = 1000; - options.verbose = true; - options.debug = false; - options.enable_parallel = false; - options.num_threads = 1; - options.tolerance = 1e-5; - options.acceptable_tolerance = 1e-4; - options.regularization.initial_value = 1e-2; - options.ipddp.barrier.mu_initial = 1e-1; - - // Control constraint - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.1, M_PI; - - // ------------------------------------------------- - // 2. Configure and Solve IPDDP with Two BallConstraints - // ------------------------------------------------- - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - - // Solver with new API already set up with system and objective - - // Add constraints - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // First ball constraint - double radius1 = 0.4; - Eigen::Vector2d center1(1.0, 1.0); - cddp_solver.addPathConstraint("BallConstraint", - std::make_unique(radius1, center1)); - - // Second ball constraint - double radius2 = 0.4; - Eigen::Vector2d center2(1.5, 2.5); - cddp_solver.addPathConstraint("BallConstraint2", - std::make_unique(radius2, center2)); - - // Initial trajectory guess - auto [X_sol, U_sol] = cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); - cddp_solver.setInitialTrajectory(X_sol, U_sol); - - // Solve - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - X_sol = solution.state_trajectory; - U_sol = solution.control_trajectory; - - // ------------------------------------------------- - // 3. Prepare Data for Plotting - // ------------------------------------------------- - std::vector x_sol_plot, y_sol_plot; - x_sol_plot.reserve(X_sol.size()); - y_sol_plot.reserve(X_sol.size()); - - for (const auto &state : X_sol) { - x_sol_plot.push_back(state(0)); - y_sol_plot.push_back(state(1)); - } - - // Create circle points for the two ball constraints - std::vector x_ball1, y_ball1; - std::vector x_ball2, y_ball2; - for (double t = 0.0; t < 2 * M_PI; t += 0.01) { - x_ball1.push_back(center1(0) + radius1 * std::cos(t)); - y_ball1.push_back(center1(1) + radius1 * std::sin(t)); - x_ball2.push_back(center2(0) + radius2 * std::cos(t)); - y_ball2.push_back(center2(1) + radius2 * std::sin(t)); - } - - // ------------------------------------------------- - // 4. Plot with matplot - // ------------------------------------------------- - auto f1 = figure(true); - f1->size(800, 600); - - auto ax = f1->current_axes(); - auto traj_line = plot(ax, x_sol_plot, y_sol_plot); - traj_line->color("blue"); - traj_line->line_width(2); - traj_line->display_name("IPDDP"); - - // We want multiple lines on same plot: - hold(ax, true); - - // Ball constraints (two circles) - auto ball1 = plot(ax, x_ball1, y_ball1); - ball1->line_style("--"); - ball1->line_width(2); - ball1->color("green"); - ball1->display_name("Ball Constraint 1"); - - auto ball2 = plot(ax, x_ball2, y_ball2); - ball2->line_style("--"); - ball2->line_width(2); - ball2->color("green"); - ball2->display_name("Ball Constraint 2"); - - // Turn on grid, label, etc. - grid(ax, true); - xlabel(ax, "x"); - ylabel(ax, "y"); - xlim(ax, {0.0, 4.0}); - ylim(ax, {0.0, 4.0}); - title(ax, "IPDDP Safe Trajectory with Two Ball Constraints"); - matplot::legend(ax); - - // ------------------------------------------------- - // 5. Save Plot - // ------------------------------------------------- - std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - f1->draw(); - f1->save(plotDirectory + "/trajectory_comparison_ipddp_v2_matplot.png"); - std::cout << "Trajectory comparison saved to " - << (plotDirectory + "/trajectory_comparison_ipddp_v2_matplot.png") - << std::endl; - - return 0; -} diff --git a/examples/cddp_unicycle_safe_ipddp_v3.cpp b/examples/cddp_unicycle_safe_ipddp_v3.cpp deleted file mode 100644 index 2eb6f6d4..00000000 --- a/examples/cddp_unicycle_safe_ipddp_v3.cpp +++ /dev/null @@ -1,220 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -// Include matplot -#include "matplot/matplot.h" - -namespace fs = std::filesystem; -using namespace matplot; - -int main() { - // ------------------------------------------------- - // 1. Problem Setup - // ------------------------------------------------- - int state_dim = 3; - int control_dim = 2; - int horizon = 300; - double timestep = 0.03; - std::string integration_type = "euler"; - - // Create a unicycle dynamical system - auto dyn_system = std::make_unique(timestep, integration_type); - - // Create objective function - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.05 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf << 100.0, 0.0, 0.0, - 0.0, 100.0, 0.0, - 0.0, 0.0, 100.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 3.0, 3.0, M_PI / 2.0; - - std::vector empty_reference_states; - auto objective = std::make_unique( - Q, R, Qf, goal_state, empty_reference_states, timestep); - - // Initial state - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI / 4.0; - - // CDDP options - cddp::CDDPOptions options; - options.max_iterations = 1000; - options.verbose = true; - options.debug = false; - options.enable_parallel = false; - options.num_threads = 1; - options.tolerance = 1e-5; - options.acceptable_tolerance = 1e-4; - options.regularization.initial_value = 1e-2; - options.ipddp.barrier.mu_initial = 1e-1; - - // Control constraint - Eigen::VectorXd control_upper_bound(control_dim); - control_upper_bound << 1.1, M_PI; - - // ------------------------------------------------- - // 2. Configure and Solve IPDDP with Multiple Constraints - // ------------------------------------------------- - cddp::CDDP cddp_solver( - initial_state, - goal_state, - horizon, - timestep, - std::make_unique(timestep, integration_type), - std::make_unique(Q, R, Qf, goal_state, empty_reference_states, timestep), - options - ); - - // Solver with new API already set up with system and objective - - // Add constraints - // Control constraint - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-control_upper_bound, control_upper_bound)); - - // First ball constraint - double radius1 = 0.4; - Eigen::Vector2d center1(1.0, 1.0); - cddp_solver.addPathConstraint("BallConstraint1", - std::make_unique(radius1, center1)); - - // Second ball constraint - double radius2 = 0.4; - Eigen::Vector2d center2(1.5, 2.5); - cddp_solver.addPathConstraint("BallConstraint2", - std::make_unique(radius2, center2)); - - // Linear constraint: y <= 1.0x + 0.5 - Eigen::MatrixXd A(1, state_dim); - A << -1.0, 1.0, 0.0; - Eigen::VectorXd b(1); - b << 0.5; - cddp_solver.addPathConstraint("LinearConstraint", - std::make_unique(A, b)); - - // Initial trajectory guess - auto [X_sol, U_sol] = cddp::example::makeInitialTrajectory(initial_state, horizon, control_dim); - cddp_solver.setInitialTrajectory(X_sol, U_sol); - - // Solve - cddp::CDDPSolution solution = cddp_solver.solve(cddp::SolverType::IPDDP); - X_sol = solution.state_trajectory; - U_sol = solution.control_trajectory; - - // Add this line to check the actual starting state in the solution - std::cout << "Actual starting state in solution: " << X_sol[0].transpose() << std::endl; - - // ------------------------------------------------- - // 3. Prepare Data for Plotting - // ------------------------------------------------- - std::vector x_sol_plot, y_sol_plot; - x_sol_plot.reserve(X_sol.size()); - y_sol_plot.reserve(X_sol.size()); - - for (const auto &state : X_sol) { - x_sol_plot.push_back(state(0)); - y_sol_plot.push_back(state(1)); - } - - // Create circle points for the two ball constraints - std::vector x_ball1, y_ball1; - std::vector x_ball2, y_ball2; - for (double t = 0.0; t < 2 * M_PI; t += 0.01) { - x_ball1.push_back(center1(0) + radius1 * std::cos(t)); - y_ball1.push_back(center1(1) + radius1 * std::sin(t)); - x_ball2.push_back(center2(0) + radius2 * std::cos(t)); - y_ball2.push_back(center2(1) + radius2 * std::sin(t)); - } - - // Create points for the linear constraint - std::vector x_linear, y_linear; - for (double x = -1.0; x <= 4.0; x += 0.1) { - double y = 1.0 * x + 0.5; - x_linear.push_back(x); - y_linear.push_back(y); - } - - // ------------------------------------------------- - // 4. Plot with matplot - // ------------------------------------------------- - auto f1 = figure(true); - f1->size(800, 600); - - auto ax = f1->current_axes(); - auto traj_line = plot(ax, x_sol_plot, y_sol_plot); - traj_line->color("blue"); - traj_line->line_width(2); - traj_line->display_name("IPDDP"); - - // We want multiple lines on same plot: - hold(ax, true); - - // Ball constraints (two circles) - auto ball1 = plot(ax, x_ball1, y_ball1); - ball1->line_style("--"); - ball1->line_width(2); - ball1->color("green"); - ball1->display_name("Ball Constraint 1"); - - auto ball2 = plot(ax, x_ball2, y_ball2); - ball2->line_style("--"); - ball2->line_width(2); - ball2->color("green"); - ball2->display_name("Ball Constraint 2"); - - // Linear constraint - auto linear_constraint = plot(ax, x_linear, y_linear); - linear_constraint->line_style("--"); - linear_constraint->line_width(2); - linear_constraint->color("red"); - linear_constraint->display_name("Linear Constraint"); - - // Turn on grid, label, etc. - grid(ax, true); - xlabel(ax, "x"); - ylabel(ax, "y"); - xlim(ax, {-1.0, 4.0}); - ylim(ax, {-1.0, 4.0}); - title(ax, "IPDDP Safe Trajectory with Linear Constraint"); - matplot::legend(ax); - - // ------------------------------------------------- - // 5. Save Plot - // ------------------------------------------------- - std::string plotDirectory = "../results/tests"; - cddp::example::ensurePlotDir(plotDirectory); - - f1->draw(); - f1->save(plotDirectory + "/trajectory_comparison_ipddp_v3_linear_matplot.png"); - std::cout << "Trajectory comparison saved to " - << (plotDirectory + "/trajectory_comparison_ipddp_v3_linear_matplot.png") - << std::endl; - - return 0; -} \ No newline at end of file diff --git a/examples/hessian_example.cpp b/examples/hessian_example.cpp deleted file mode 100644 index 107b9c46..00000000 --- a/examples/hessian_example.cpp +++ /dev/null @@ -1,182 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include - -#include "dynamics_model/pendulum.hpp" -#include "dynamics_model/dubins_car.hpp" - -using namespace cddp; - -// Helper function to print a matrix with a label -void printMatrix(const std::string& label, const Eigen::MatrixXd& matrix) { - std::cout << label << " (" << matrix.rows() << "x" << matrix.cols() << ")" << std::endl; - std::cout << std::fixed << std::setprecision(6) << matrix << std::endl << std::endl; -} - -// Helper function to print the Hessian tensor -void printHessianTensor(const std::string& label, const std::vector& hessian) { - std::cout << label << " (Tensor with " << hessian.size() << " matrices)" << std::endl; - - for (size_t i = 0; i < hessian.size(); ++i) { - std::cout << "Matrix for state dimension " << i << " (" - << hessian[i].rows() << "x" << hessian[i].cols() << "):" << std::endl; - std::cout << std::fixed << std::setprecision(6) << hessian[i] << std::endl; - } - std::cout << std::endl; -} - -// Function to demonstrate pendulum Hessian -void demonstratePendulumHessian() { - std::cout << "\n========== PENDULUM MODEL EXAMPLE ==========" << std::endl; - - // Create a pendulum model - double timestep = 0.01; - double length = 1.0; // Length of the pendulum [m] - double mass = 1.0; // Mass [kg] - double damping = 0.1; // Damping coefficient - std::string integration = "rk4"; - - Pendulum pendulum(timestep, length, mass, damping, integration); - - // Define a state and control - Eigen::VectorXd state = Eigen::VectorXd::Zero(2); - state << M_PI / 4.0, 0.0; // 45-degree angle, zero velocity - - Eigen::VectorXd control = Eigen::VectorXd::Zero(1); - control << 1.0; // Apply a torque of 1 Nm - - // Print system information - std::cout << "Pendulum parameters:" << std::endl; - std::cout << "Length: " << pendulum.getLength() << " m" << std::endl; - std::cout << "Mass: " << pendulum.getMass() << " kg" << std::endl; - std::cout << "Damping: " << pendulum.getDamping() << std::endl; - std::cout << "Gravity: " << pendulum.getGravity() << " m/s²" << std::endl; - std::cout << "Timestep: " << pendulum.getTimestep() << " s" << std::endl; - std::cout << "Integration: " << pendulum.getIntegrationType() << std::endl << std::endl; - - // Print state and control - std::cout << "State: [theta, theta_dot] = [" << state.transpose() << "]" << std::endl; - std::cout << "Control: [torque] = [" << control.transpose() << "]" << std::endl << std::endl; - - // Compute dynamics - Eigen::VectorXd xdot = pendulum.getContinuousDynamics(state, control, 0.0); - std::cout << "Continuous Dynamics (xdot): [" << xdot.transpose() << "]" << std::endl; - - Eigen::VectorXd next_state = pendulum.getDiscreteDynamics(state, control, 0.0); - std::cout << "Discrete Dynamics (next state): [" << next_state.transpose() << "]" << std::endl << std::endl; - - // Compute Jacobians - Eigen::MatrixXd A = pendulum.getStateJacobian(state, control, 0.0); - Eigen::MatrixXd B = pendulum.getControlJacobian(state, control, 0.0); - - printMatrix("State Jacobian (A)", A); - printMatrix("Control Jacobian (B)", B); - - // Compute Hessians - std::vector state_hessian = pendulum.getStateHessian(state, control, 0.0); - std::vector control_hessian = pendulum.getControlHessian(state, control, 0.0); - std::vector cross_hessian = pendulum.getCrossHessian(state, control, 0.0); - - printHessianTensor("State Hessian (d²f/dx²)", state_hessian); - printHessianTensor("Control Hessian (d²f/du²)", control_hessian); - printHessianTensor("Cross Hessian (d²f/dudx)", cross_hessian); - - // Demonstrate how to access specific elements of the Hessian - // For example, accessing d²theta_dot/dtheta² (second derivative of theta_dot with respect to theta) - int state_idx = 1; // theta_dot is state index 1 - int wrt_state_idx1 = 0; // first derivative with respect to theta (index 0) - int wrt_state_idx2 = 0; // second derivative with respect to theta (index 0) - - double d2f_dx2 = state_hessian[state_idx](wrt_state_idx1, wrt_state_idx2); - std::cout << "d²theta_dot/dtheta² = " << d2f_dx2 << std::endl; -} - -// Function to demonstrate Dubins car Hessian -void demonstrateDubinsCarHessian() { - std::cout << "\n========== DUBINS CAR MODEL EXAMPLE ==========" << std::endl; - - // Create a Dubins car model - double speed = 1.0; // Constant forward speed [m/s] - double timestep = 0.01; // Time step [s] - std::string integration = "rk4"; - - DubinsCar dubins_car(speed, timestep, integration); - - // Define a state and control - Eigen::VectorXd state = Eigen::VectorXd::Zero(3); - state << 0.0, 0.0, M_PI / 4.0; // (x, y, theta) = (0, 0, 45°) - - Eigen::VectorXd control = Eigen::VectorXd::Zero(1); - control << 0.5; // Turn rate of 0.5 rad/s - - // Print system information - std::cout << "Dubins Car parameters:" << std::endl; - std::cout << "Speed: " << speed << " m/s" << std::endl; - std::cout << "Timestep: " << dubins_car.getTimestep() << " s" << std::endl; - std::cout << "Integration: " << dubins_car.getIntegrationType() << std::endl << std::endl; - - // Print state and control - std::cout << "State: [x, y, theta] = [" << state.transpose() << "]" << std::endl; - std::cout << "Control: [omega] = [" << control.transpose() << "]" << std::endl << std::endl; - - // Compute dynamics - Eigen::VectorXd xdot = dubins_car.getContinuousDynamics(state, control, 0.0); - std::cout << "Continuous Dynamics (xdot): [" << xdot.transpose() << "]" << std::endl; - - Eigen::VectorXd next_state = dubins_car.getDiscreteDynamics(state, control, 0.0); - std::cout << "Discrete Dynamics (next state): [" << next_state.transpose() << "]" << std::endl << std::endl; - - // Compute Jacobians - Eigen::MatrixXd A = dubins_car.getStateJacobian(state, control, 0.0); - Eigen::MatrixXd B = dubins_car.getControlJacobian(state, control, 0.0); - - printMatrix("State Jacobian (A)", A); - printMatrix("Control Jacobian (B)", B); - - // Compute Hessians - std::vector state_hessian = dubins_car.getStateHessian(state, control, 0.0); - std::vector control_hessian = dubins_car.getControlHessian(state, control, 0.0); - std::vector cross_hessian = dubins_car.getCrossHessian(state, control, 0.0); - - printHessianTensor("State Hessian (d²f/dx²)", state_hessian); - printHessianTensor("Control Hessian (d²f/du²)", control_hessian); - printHessianTensor("Cross Hessian (d²f/dudx)", cross_hessian); - - // Demonstrate how to access specific elements of the Hessian - // For example, accessing d²x/dtheta² (second derivative of x with respect to theta) - int state_idx = 0; // x is state index 0 - int wrt_state_idx1 = 2; // first derivative with respect to theta (index 2) - int wrt_state_idx2 = 2; // second derivative with respect to theta (index 2) - - double d2f_dx2 = state_hessian[state_idx](wrt_state_idx1, wrt_state_idx2); - std::cout << "d²x/dtheta² = " << d2f_dx2 << std::endl; -} - -int main() { - std::cout << "Hessian Examples for Dynamical Systems" << std::endl; - std::cout << "=====================================" << std::endl; - - // Demonstrate pendulum Hessian - demonstratePendulumHessian(); - - // Demonstrate Dubins car Hessian - demonstrateDubinsCarHessian(); - return 0; -} \ No newline at end of file diff --git a/examples/ipopt_car.cpp b/examples/ipopt_car.cpp deleted file mode 100644 index 14cd3b3b..00000000 --- a/examples/ipopt_car.cpp +++ /dev/null @@ -1,364 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -void plotCarBox(const Eigen::VectorXd &state, const Eigen::VectorXd &control, - double length, double width, const std::string &color, - axes_handle ax) -{ - double x = state(0); - double y = state(1); - double theta = state(2); - double steering = control(1); - - // Compute the car's four corners (and close the polygon) - std::vector car_x(5), car_y(5); - - // Front right - car_x[0] = x + length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[0] = y + length / 2 * sin(theta) + width / 2 * cos(theta); - - // Front left - car_x[1] = x + length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[1] = y + length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear left - car_x[2] = x - length / 2 * cos(theta) + width / 2 * sin(theta); - car_y[2] = y - length / 2 * sin(theta) - width / 2 * cos(theta); - - // Rear right - car_x[3] = x - length / 2 * cos(theta) - width / 2 * sin(theta); - car_y[3] = y - length / 2 * sin(theta) + width / 2 * cos(theta); - - // Close polygon - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - // Plot car body as a polygon line. - plot(ax, car_x, car_y, color + "-"); - - // Plot base point (center of rear axle) as a red circle. - plot(ax, std::vector{x}, std::vector{y}, "ro"); - - // Compute steering direction - double front_x = x + length / 2 * cos(theta); - double front_y = y + length / 2 * sin(theta); - double steering_length = width / 2; - double steering_angle = theta + steering; - double steering_end_x = front_x + steering_length * cos(steering_angle); - double steering_end_y = front_y + steering_length * sin(steering_angle); - - std::vector steer_x = {front_x, steering_end_x}; - std::vector steer_y = {front_y, steering_end_y}; - plot(ax, steer_x, steer_y, "g-"); -} - -int main() -{ - // Problem parameters - int state_dim = 4; // [x y theta v] - int control_dim = 2; // [steering_angle acceleration] - int horizon = 500; // Same as CDDP example - double timestep = 0.03; - double wheelbase = 2.0; - - // Initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << 1.0, 1.0, 1.5 * M_PI, 0.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, 0.0, 0.0; - - // Define variables - casadi::MX x = casadi::MX::sym("x", state_dim); - casadi::MX u = casadi::MX::sym("u", control_dim); - - // Car dynamics - casadi::MX theta = x(2); - casadi::MX v = x(3); - casadi::MX delta = u(0); - casadi::MX a = u(1); - - // Continuous dynamics - casadi::MX dx = casadi::MX::zeros(state_dim); - using casadi::cos; - using casadi::sin; - using casadi::tan; - - dx(0) = v * cos(theta); - dx(1) = v * sin(theta); - dx(2) = v * tan(delta) / wheelbase; - dx(3) = a; - - // Discrete dynamics using Euler integration - casadi::MX f = x + timestep * dx; - casadi::Function F("F", {x, u}, {f}); - - // Decision variables - int n_states = (horizon + 1) * state_dim; - int n_controls = horizon * control_dim; - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Objective function terms - auto running_cost = [&](casadi::MX x, casadi::MX u) - { - casadi::MX u_cost = 1e-2 * u(0) * u(0) + 1e-4 * u(1) * u(1); - casadi::MX xy_norm = x(0) * x(0) + x(1) * x(1); - casadi::MX x_cost = 1e-3 * (casadi::MX::sqrt(xy_norm / 0.01 + 1) * 0.1 - 0.1); - return u_cost + x_cost; - }; - - auto terminal_cost = [&](casadi::MX x) - { - casadi::MX cost = 0; - casadi::MX d = x - casadi::DM(std::vector(goal_state.data(), goal_state.data() + state_dim)); - casadi::MX xy_err = d(0) * d(0) + d(1) * d(1); - cost += 0.1 * (casadi::MX::sqrt(xy_err / 0.01 + 1) * 0.1 - 0.1); - cost += 1.0 * (casadi::MX::sqrt(d(2) * d(2) / 0.01 + 1) * 0.1 - 0.1); - cost += 0.3 * (casadi::MX::sqrt(d(3) * d(3) / 1.0 + 1) * 1.0 - 1.0); - return cost; - }; - - // Build objective - casadi::MX J = 0; - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - J += running_cost(x_t, u_t); - } - J += terminal_cost(X(casadi::Slice(horizon * state_dim, (horizon + 1) * state_dim))); - - // Constraints - casadi::MX g; - - // Initial condition - g = casadi::MX::vertcat({g, X(casadi::Slice(0, state_dim)) - - casadi::DM(std::vector(initial_state.data(), initial_state.data() + state_dim))}); - - // Dynamics constraints - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - casadi::MX x_next = F(casadi::MXVector{x_t, u_t})[0]; - casadi::MX x_next_sym = X(casadi::Slice((t + 1) * state_dim, (t + 2) * state_dim)); - g = casadi::MX::vertcat({g, x_next_sym - x_next}); - } - - // NLP - casadi::MXDict nlp = { - {"x", z}, - {"f", J}, - {"g", g}}; - - // Solver options - casadi::Dict solver_opts; - solver_opts["ipopt.max_iter"] = 1000; - solver_opts["ipopt.print_level"] = 5; - solver_opts["print_time"] = true; - solver_opts["ipopt.tol"] = 1e-6; - - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Bounds - std::vector lbx(n_states + n_controls); - std::vector ubx(n_states + n_controls); - std::vector lbg(g.size1()); - std::vector ubg(g.size1()); - - // State bounds - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - lbx[t * state_dim + i] = -1e20; - ubx[t * state_dim + i] = 1e20; - } - } - - // Control bounds - for (int t = 0; t < horizon; t++) - { - // Steering angle bounds - lbx[n_states + t * control_dim] = -0.5; - ubx[n_states + t * control_dim] = 0.5; - // Acceleration bounds - lbx[n_states + t * control_dim + 1] = -2.0; - ubx[n_states + t * control_dim + 1] = 2.0; - } - - // Constraint bounds (all equality constraints) - for (int i = 0; i < g.size1(); i++) - { - lbg[i] = 0; - ubg[i] = 0; - } - - // Initial guess - std::vector x0(n_states + n_controls, 0.0); - - // Initial state - for (int i = 0; i < state_dim; i++) - { - x0[i] = initial_state(i); - } - - // Linear interpolation for states - for (int t = 1; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - x0[t * state_dim + i] = initial_state(i) + - (goal_state(i) - initial_state(i)) * t / horizon; - } - } - - // Call the solver - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(casadi::DMDict{ - {"x0", x0}, - {"lbx", lbx}, - {"ubx", ubx}, - {"lbg", lbg}, - {"ubg", ubg}}); - auto end_time = std::chrono::high_resolution_clock::now(); - auto duration = std::chrono::duration_cast(end_time - start_time); - - std::cout << "Solve time: " << duration.count() << " microseconds" << std::endl; - - // EXIT: Optimal Solution Found. - // solver : t_proc (avg) t_wall (avg) n_eval - // nlp_f | 23.27ms (217.46us) 23.44ms (219.05us) 107 - // nlp_g | 27.51ms (257.09us) 27.57ms (257.65us) 107 - // nlp_grad_f | 39.72ms (374.68us) 39.87ms (376.14us) 106 - // nlp_hess_l | 244.66ms ( 2.35ms) 245.20ms ( 2.36ms) 104 - // nlp_jac_g | 176.39ms ( 1.66ms) 176.76ms ( 1.67ms) 106 - // total | 1.49 s ( 1.49 s) 1.49 s ( 1.49 s) 1 - // Solve time: 1488881 microseconds - - // Extract solution - std::vector sol = std::vector(res.at("x")); - - // Convert to state and control trajectories - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - X_sol[t](i) = sol[t * state_dim + i]; - } - } - - for (int t = 0; t < horizon; t++) - { - for (int i = 0; i < control_dim; i++) - { - U_sol[t](i) = sol[n_states + t * control_dim + i]; - } - } - - // Prepare trajectory data - std::vector x_hist, y_hist; - for (const auto &x : X_sol) - { - x_hist.push_back(x(0)); - y_hist.push_back(x(1)); - } - - // Car dimensions. - double car_length = 2.1; - double car_width = 0.9; - - // Create a figure and get current axes. - auto fig = figure(true); - auto ax = fig->current_axes(); - - Eigen::VectorXd empty_control = Eigen::VectorXd::Zero(2); - - // Create directory for saving plots - const std::string plotDirectory = "../results/tests"; - if (!fs::exists(plotDirectory)) - { - fs::create_directory(plotDirectory); - } - - // Create a directory for frame images. - (void) std::system("mkdir -p frames"); - - // Animation loop: update plot for each time step and save frame. - for (size_t i = 0; i < X_sol.size(); ++i) - { - // Skip every 10th frame for smoother animation. - if (i % 10 == 0) - { - // Clear previous content. - cla(ax); - hold(ax, true); - - // Plot the full trajectory. - plot(ax, x_hist, y_hist, "b-"); - - // Plot goal configuration. - plotCarBox(goal_state, empty_control, car_length, car_width, "r", ax); - - // Plot current car state. - if (i < U_sol.size()) - plotCarBox(X_sol[i], U_sol[i], car_length, car_width, "k", ax); - else - plotCarBox(X_sol[i], empty_control, car_length, car_width, "k", ax); - - // Set grid and axis limits. - grid(ax, true); - xlim(ax, {-4, 4}); - ylim(ax, {-4, 4}); - - // Update drawing. - fig->draw(); - - // Save the frame to a PNG file. - std::string frame_filename = plotDirectory + "/frame_" + std::to_string(i) + ".png"; - fig->save(frame_filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 15 " + plotDirectory + "/frame_*.png " + plotDirectory + "/car_parking_ipopt.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as car_parking_ipopt.gif" << std::endl; - - return 0; -} \ No newline at end of file diff --git a/examples/ipopt_cartpole.cpp b/examples/ipopt_cartpole.cpp deleted file mode 100644 index 172aa9d8..00000000 --- a/examples/ipopt_cartpole.cpp +++ /dev/null @@ -1,390 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -int main() { - // Dimensions and time parameters - const int state_dim = 4; // [x, θ, x_dot, θ_dot] - const int control_dim = 1; // [force] - const int horizon = 100; // Number of time steps - const double timestep = 0.05; // Time discretization - - // Cartpole physical parameters - double cart_mass = 1.0; // mass of the cart (kg) - double pole_mass = 0.2; // mass of the pole (kg) - double pole_length = 0.5; // length of the pole (m) - double gravity = 9.81; // gravitational acceleration (m/s²) - - // Define initial and goal states. - // State order: [x, θ, x_dot, θ_dot] - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, 0.0, 0.0; // Cart at origin; pole hanging downward (θ = 0) - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, M_PI, 0.0, 0.0; // Cart at origin; pole upright (θ = π) - - // Cost weighting matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Eigen::MatrixXd R = 0.1 * Eigen::MatrixXd::Identity(control_dim, control_dim); - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf(0,0) = 100.0; // Cart position - Qf(1,1) = 100.0; // Pole angle - Qf(2,2) = 100.0; // Cart velocity - Qf(3,3) = 100.0; // Pole angular velocity - - // Convert Eigen matrices to CasADi DM using a nested loop conversion. - casadi::DM Q_dm(Q.rows(), Q.cols()); - for (int i = 0; i < Q.rows(); i++) { - for (int j = 0; j < Q.cols(); j++) { - Q_dm(i, j) = Q(i, j); - } - } - casadi::DM R_dm(R.rows(), R.cols()); - for (int i = 0; i < R.rows(); i++) { - for (int j = 0; j < R.cols(); j++) { - R_dm(i, j) = R(i, j); - } - } - casadi::DM Qf_dm(Qf.rows(), Qf.cols()); - for (int i = 0; i < Qf.rows(); i++) { - for (int j = 0; j < Qf.cols(); j++) { - Qf_dm(i, j) = Qf(i, j); - } - } - - // Control bounds (e.g., force limits) - Eigen::VectorXd control_lower_bound(control_dim); - Eigen::VectorXd control_upper_bound(control_dim); - control_lower_bound << -5.0; - control_upper_bound << 5.0; - - ////////// Decision Variables ////////// - const int n_states = (horizon + 1) * state_dim; - const int n_controls = horizon * control_dim; - const int n_dec = n_states + n_controls; - - // Define symbolic variables for states and controls - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Helper lambdas to extract the state and control at time step t - auto X_t = [=](int t) -> casadi::MX { - return X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - }; - auto U_t = [=](int t) -> casadi::MX { - return U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - }; - - auto cartpole_dynamics = [=](casadi::MX state, casadi::MX control) -> casadi::MX { - // Extract state components - casadi::MX pos = state(0); // cart position - casadi::MX theta = state(1); // pole angle - casadi::MX x_dot = state(2); - casadi::MX theta_dot = state(3); - casadi::MX force = control(0); - - // Use casadi's trigonometric functions - using casadi::cos; - using casadi::sin; - casadi::MX sin_theta = sin(theta); - casadi::MX cos_theta = cos(theta); - casadi::MX total_mass = cart_mass + pole_mass; - casadi::MX den = cart_mass + pole_mass * sin_theta * sin_theta; - - casadi::MX x_ddot = (force + pole_mass * sin_theta * (pole_length * theta_dot * theta_dot + gravity * cos_theta)) / den; - casadi::MX theta_ddot = (-force * cos_theta - - pole_mass * pole_length * theta_dot * theta_dot * cos_theta * sin_theta - - total_mass * gravity * sin_theta) / (pole_length * den); - - // Euler discretization: - casadi::MX next_state = casadi::MX::vertcat({ - pos + timestep * x_dot, - theta + timestep * theta_dot, - x_dot + timestep * x_ddot, - theta_dot + timestep * theta_ddot - }); - return next_state; - }; - - ////////// Constraints ////////// - casadi::MX g; - - // Initial state constraint: - casadi::DM init_state_dm(std::vector(initial_state.data(), initial_state.data() + state_dim)); - g = casadi::MX::vertcat({g, X_t(0) - init_state_dm}); - - // Dynamics constraints: - for (int t = 0; t < horizon; t++) { - casadi::MX x_next_expr = cartpole_dynamics(X_t(t), U_t(t)); - g = casadi::MX::vertcat({g, X_t(t + 1) - x_next_expr}); - } - - // --- Terminal Condition Constraint --- - casadi::DM goal_dm(std::vector(goal_state.data(), goal_state.data() + state_dim)); - casadi::MX terminal_constr = X_t(horizon) - goal_dm; - g = casadi::MX::vertcat({g, terminal_constr}); - - ////////// Cost Function ////////// - casadi::MX cost = casadi::MX::zeros(1, 1); - for (int t = 0; t < horizon; t++) { - casadi::MX x_diff = X_t(t) - goal_dm; - casadi::MX u_diff = U_t(t); - casadi::MX state_cost = casadi::MX::mtimes({x_diff.T(), Q_dm, x_diff}) * timestep; - casadi::MX control_cost = casadi::MX::mtimes({u_diff.T(), R_dm, u_diff}) * timestep; - cost = cost + state_cost + control_cost; - } - - // Terminal cost - casadi::MX x_diff_final = X_t(horizon) - goal_dm; - casadi::MX terminal_cost = casadi::MX::mtimes({x_diff_final.T(), Qf_dm, x_diff_final}); - cost = cost + terminal_cost; - - std::vector lbx(n_dec, -1e20), ubx(n_dec, 1e20); - // Apply control bounds to the control part of the decision vector. - for (int t = 0; t < horizon; t++) { - for (int i = 0; i < control_dim; i++) { - lbx[n_states + t * control_dim + i] = control_lower_bound(i); - ubx[n_states + t * control_dim + i] = control_upper_bound(i); - } - } - - // The complete set of constraints (g) must be equal to zero. - const int n_g = static_cast(g.size1()); - std::vector lbg(n_g, 0.0); - std::vector ubg(n_g, 0.0); - - // Provide an initial guess for the decision vector. - std::vector x0(n_dec, 0.0); - // Set the initial state portion. - for (int i = 0; i < state_dim; i++) { - x0[i] = initial_state(i); - } - // // Linearly interpolate the state trajectory from initial_state to goal_state. - // for (int t = 1; t <= horizon; t++) { - // for (int i = 0; i < state_dim; i++) { - // x0[t * state_dim + i] = initial_state(i) + (goal_state(i) - initial_state(i)) * (double)t / horizon; - // } - // } - - std::map nlp; - nlp["x"] = z; - nlp["f"] = cost; - nlp["g"] = g; - - casadi::Dict solver_opts; - solver_opts["print_time"] = true; - solver_opts["ipopt.print_level"] = 5; - solver_opts["ipopt.max_iter"] = 500; - solver_opts["ipopt.tol"] = 1e-6; - - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Convert initial guess and bounds into DM objects. - casadi::DM x0_dm = casadi::DM(x0); - casadi::DM lbx_dm = casadi::DM(lbx); - casadi::DM ubx_dm = casadi::DM(ubx); - casadi::DM lbg_dm = casadi::DM(lbg); - casadi::DM ubg_dm = casadi::DM(ubg); - - casadi::DMDict arg({ - {"x0", x0_dm}, - {"lbx", lbx_dm}, - {"ubx", ubx_dm}, - {"lbg", lbg_dm}, - {"ubg", ubg_dm} - }); - - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(arg); - auto end_time = std::chrono::high_resolution_clock::now(); - std::chrono::duration elapsed = end_time - start_time; - std::cout << "Solver elapsed time: " << elapsed.count() << " s" << std::endl; - - std::vector sol = std::vector(res.at("x")); - - // Recover state and control trajectories. - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - for (int t = 0; t <= horizon; t++) { - Eigen::VectorXd x_t(state_dim); - for (int i = 0; i < state_dim; i++) { - x_t(i) = sol[t * state_dim + i]; - } - X_sol[t] = x_t; - } - for (int t = 0; t < horizon; t++) { - Eigen::VectorXd u_t(control_dim); - for (int i = 0; i < control_dim; i++) { - u_t(i) = sol[n_states + t * control_dim + i]; - } - U_sol[t] = u_t; - } - - // Create plot directory. - const std::string plotDirectory = "../results/tests"; - if (!fs::exists(plotDirectory)) { - fs::create_directory(plotDirectory); - } - - // Create a time vector. - std::vector t_sol(horizon + 1); - for (int t = 0; t <= horizon; t++) { - t_sol[t] = t * timestep; - } - - // Extract solution data. - std::vector x_arr, x_dot_arr, theta_arr, theta_dot_arr, force_arr, time_arr, time_arr2; - for (size_t i = 0; i < X_sol.size(); ++i) { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - theta_arr.push_back(X_sol[i](1)); - x_dot_arr.push_back(X_sol[i](2)); - theta_dot_arr.push_back(X_sol[i](3)); - } - for (size_t i = 0; i < U_sol.size(); ++i) { - force_arr.push_back(U_sol[i](0)); - time_arr2.push_back(t_sol[i]); - } - - // --- Plot static results (2x2 plots for state trajectories) --- - auto fig1 = figure(); - fig1->size(1200, 800); - - auto ax1 = subplot(2, 2, 1); - title(ax1, "Cart Position"); - plot(ax1, time_arr, x_arr)->line_style("b-"); - xlabel(ax1, "Time [s]"); - ylabel(ax1, "Position [m]"); - grid(ax1, true); - - auto ax2 = subplot(2, 2, 2); - title(ax2, "Cart Velocity"); - plot(ax2, time_arr, x_dot_arr)->line_style("b-"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "Velocity [m/s]"); - grid(ax2, true); - - auto ax3 = subplot(2, 2, 3); - title(ax3, "Pole Angle"); - plot(ax3, time_arr, theta_arr)->line_style("b-"); - xlabel(ax3, "Time [s]"); - ylabel(ax3, "Angle [rad]"); - grid(ax3, true); - - auto ax4 = subplot(2, 2, 4); - title(ax4, "Pole Angular Velocity"); - plot(ax4, time_arr, theta_dot_arr)->line_style("b-"); - xlabel(ax4, "Time [s]"); - ylabel(ax4, "Angular Velocity [rad/s]"); - grid(ax4, true); - - fig1->save(plotDirectory + "/cartpole_ipopt_results.png"); - - // --- Plot control inputs --- - auto fig2 = figure(); - fig2->size(800, 600); - title("Control Inputs"); - plot(time_arr2, force_arr)->line_style("b-"); - xlabel("Time [s]"); - ylabel("Force [N]"); - grid(true); - fig2->save(plotDirectory + "/cartpole_ipopt_control_inputs.png"); - - // --- Animation --- - auto fig3 = figure(); - auto ax_fig3 = fig3->current_axes(); - fig3->size(800, 600); - title("CartPole Animation"); - xlabel("x"); - ylabel("y"); - - double cart_width = 0.3; - double cart_height = 0.2; - double pole_width = 0.05; - - // Loop over the solution states to generate animation frames. - for (size_t i = 0; i < X_sol.size(); ++i) { - if (i % 5 == 0) { - // Clear previous content. - cla(ax_fig3); - hold(ax_fig3, true); - - // Current state. - double x = x_arr[i]; - double theta = theta_arr[i]; - - // Plot the cart as a rectangle centered at (x, 0). - std::vector cart_x = { x - cart_width/2, x + cart_width/2, - x + cart_width/2, x - cart_width/2, - x - cart_width/2 }; - std::vector cart_y = { -cart_height/2, -cart_height/2, - cart_height/2, cart_height/2, - -cart_height/2 }; - plot(cart_x, cart_y)->line_style("k-"); - - // Plot the pole as a line from the top center of the cart. - double pole_end_x = x + pole_length * std::sin(theta); - double pole_end_y = cart_height/2 - pole_length * std::cos(theta); - std::vector pole_x = { x, pole_end_x }; - std::vector pole_y = { cart_height/2, pole_end_y }; - plot(pole_x, pole_y)->line_style("b-"); - - // Plot the pole bob as a circle. - std::vector circle_x, circle_y; - int num_points = 20; - for (int j = 0; j <= num_points; ++j) { - double t = 2 * M_PI * j / num_points; - circle_x.push_back(pole_end_x + pole_width * std::cos(t)); - circle_y.push_back(pole_end_y + pole_width * std::sin(t)); - } - plot(circle_x, circle_y)->line_style("b-"); - - // Set fixed axis limits for stable animation. - xlim({-2.0, 2.0}); - ylim({-1.5, 1.5}); - - // Save the frame. - std::string filename = plotDirectory + "/frame_" + std::to_string(i) + ".png"; - fig3->save(filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // Combine all saved frames into a GIF using ImageMagick's convert tool. - std::string command = "convert -delay 30 " + plotDirectory + "/frame_*.png " + plotDirectory + "/cartpole_ipopt.gif"; - std::system(command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "Animation saved as cartpole_ipopt.gif" << std::endl; - - return 0; -} diff --git a/examples/ipopt_quadrotor.cpp b/examples/ipopt_quadrotor.cpp deleted file mode 100644 index c6365eba..00000000 --- a/examples/ipopt_quadrotor.cpp +++ /dev/null @@ -1,694 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -// Convert quaternion [qw, qx, qy, qz] to Euler angles (roll, pitch, yaw) -Eigen::Vector3d quaternionToEuler(double qw, double qx, double qy, double qz) -{ - // Roll (phi) - double sinr_cosp = 2.0 * (qw * qx + qy * qz); - double cosr_cosp = 1.0 - 2.0 * (qx * qx + qy * qy); - double phi = std::atan2(sinr_cosp, cosr_cosp); - - // Pitch (theta) - double sinp = 2.0 * (qw * qy - qz * qx); - double theta = (std::abs(sinp) >= 1.0) ? std::copysign(M_PI / 2.0, sinp) : std::asin(sinp); - - // Yaw (psi) - double siny_cosp = 2.0 * (qw * qz + qx * qy); - double cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz); - double psi = std::atan2(siny_cosp, cosy_cosp); - - return Eigen::Vector3d(phi, theta, psi); -} - -// Compute rotation matrix from a unit quaternion [qw, qx, qy, qz] -Eigen::Matrix3d getRotationMatrixFromQuaternion(double qw, double qx, double qy, double qz) -{ - Eigen::Matrix3d R; - R(0, 0) = 1 - 2 * (qy * qy + qz * qz); - R(0, 1) = 2 * (qx * qy - qz * qw); - R(0, 2) = 2 * (qx * qz + qy * qw); - - R(1, 0) = 2 * (qx * qy + qz * qw); - R(1, 1) = 1 - 2 * (qx * qx + qz * qz); - R(1, 2) = 2 * (qy * qz - qx * qw); - - R(2, 0) = 2 * (qx * qz - qy * qw); - R(2, 1) = 2 * (qy * qz + qx * qw); - R(2, 2) = 1 - 2 * (qx * qx + qy * qy); - return R; -} - -int main() { - ////////// Problem Setup ////////// - const int state_dim = 13; // [x, y, z, qw, qx, qy, qz, vx, vy, vz, omega_x, omega_y, omega_z] - const int control_dim = 4; // [f1, f2, f3, f4] - const int horizon = 400; // Number of control intervals - const double timestep = 0.02; // Time step - - // Quadrotor parameters - const double mass = 1.2; // kg - const double arm_length = 0.165; // m - const double gravity = 9.81; // m/s^2 - - // Inertia matrix - Eigen::Matrix3d inertia_matrix = Eigen::Matrix3d::Zero(); - inertia_matrix(0, 0) = 7.782e-3; // Ixx - inertia_matrix(1, 1) = 7.782e-3; // Iyy - inertia_matrix(2, 2) = 1.439e-2; // Izz - - // Figure-8 trajectory parameters - double figure8_scale = 3.0; // 3m - double constant_altitude = 2.0; // 2m - double total_time = horizon * timestep; - double omega = 2.0 * M_PI / total_time; // completes 1 cycle over the horizon - - // Define initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << figure8_scale, 0.0, constant_altitude, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << figure8_scale, 0.0, constant_altitude, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; - - // Generate figure-8 reference trajectory - std::vector figure8_reference_states; - figure8_reference_states.reserve(horizon + 1); - - for (int i = 0; i <= horizon; ++i) { - double t = i * timestep; - double angle = omega * t; - - Eigen::VectorXd ref_state = Eigen::VectorXd::Zero(state_dim); - ref_state(0) = figure8_scale * std::cos(angle); // x - ref_state(1) = figure8_scale * std::sin(angle) * std::cos(angle); // y - ref_state(2) = constant_altitude; // z - ref_state(3) = 1.0; // qw (identity quaternion) - ref_state(4) = 0.0; // qx - ref_state(5) = 0.0; // qy - ref_state(6) = 0.0; // qz - - figure8_reference_states.push_back(ref_state); - } - - // Define cost weighting matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - Q(0, 0) = 1.0; // x position - Q(1, 1) = 1.0; // y position - Q(2, 2) = 1.0; // z position - - Eigen::MatrixXd R = 0.01 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - // Terminal cost weight - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(state_dim, state_dim); - Qf(0, 0) = 1.0; - Qf(1, 1) = 1.0; - Qf(2, 2) = 1.0; - Qf(3, 3) = 1.0; - Qf(4, 4) = 1.0; - Qf(5, 5) = 1.0; - Qf(6, 6) = 1.0; - - // Convert Eigen matrices to CasADi - casadi::DM Q_dm(Q.rows(), Q.cols()); - for (int i = 0; i < Q.rows(); i++) { - for (int j = 0; j < Q.cols(); j++) { - Q_dm(i, j) = Q(i, j) * timestep; - } - } - casadi::DM R_dm(R.rows(), R.cols()); - for (int i = 0; i < R.rows(); i++) { - for (int j = 0; j < R.cols(); j++) { - R_dm(i, j) = R(i, j) * timestep; - } - } - casadi::DM Qf_dm(Qf.rows(), Qf.cols()); - for (int i = 0; i < Qf.rows(); i++) { - for (int j = 0; j < Qf.cols(); j++) { - Qf_dm(i, j) = Qf(i, j); - } - } - - // Convert inertia matrix to CasADi - casadi::DM inertia_dm(3, 3); - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - inertia_dm(i, j) = inertia_matrix(i, j); - } - } - - // Define control bounds - Eigen::VectorXd u_min(control_dim), u_max(control_dim); - u_min << 0.0, 0.0, 0.0, 0.0; - u_max << 4.0, 4.0, 4.0, 4.0; - - const int n_states = (horizon + 1) * state_dim; - const int n_controls = horizon * control_dim; - const int n_dec = n_states + n_controls; - - // Define symbolic variables for states and controls - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Helper lambdas to extract the state and control at time step t - auto X_t = [=](int t) -> casadi::MX { - return X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - }; - auto U_t = [=](int t) -> casadi::MX { - return U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - }; - - // Quadrotor continuous dynamics function (computes derivatives) - auto quadrotor_derivatives = [=](casadi::MX x, casadi::MX u) -> casadi::MX { - casadi::MX x_dot = casadi::MX::zeros(state_dim, 1); - - // Extract states - casadi::MX pos = x(casadi::Slice(0, 3)); // [x, y, z] - casadi::MX quat = x(casadi::Slice(3, 7)); // [qw, qx, qy, qz] - casadi::MX vel = x(casadi::Slice(7, 10)); // [vx, vy, vz] - casadi::MX omega = x(casadi::Slice(10, 13)); // [omega_x, omega_y, omega_z] - - casadi::MX qw = quat(0), qx = quat(1), qy = quat(2), qz = quat(3); - casadi::MX omega_x = omega(0), omega_y = omega(1), omega_z = omega(2); - - // Normalize quaternion - casadi::MX q_norm = casadi::MX::sqrt(qw*qw + qx*qx + qy*qy + qz*qz); - qw = qw / q_norm; - qx = qx / q_norm; - qy = qy / q_norm; - qz = qz / q_norm; - - // Extract control inputs (motor forces) - casadi::MX f1 = u(0), f2 = u(1), f3 = u(2), f4 = u(3); - - // Compute total thrust and moments - casadi::MX thrust = f1 + f2 + f3 + f4; - casadi::MX tau_x = arm_length * (f1 - f3); - casadi::MX tau_y = arm_length * (f2 - f4); - casadi::MX tau_z = 0.1 * (f1 - f2 + f3 - f4); - - // Rotation matrix from quaternion - casadi::MX R11 = 1 - 2 * (qy * qy + qz * qz); - casadi::MX R12 = 2 * (qx * qy - qz * qw); - casadi::MX R13 = 2 * (qx * qz + qy * qw); - casadi::MX R21 = 2 * (qx * qy + qz * qw); - casadi::MX R22 = 1 - 2 * (qx * qx + qz * qz); - casadi::MX R23 = 2 * (qy * qz - qx * qw); - casadi::MX R31 = 2 * (qx * qz - qy * qw); - casadi::MX R32 = 2 * (qy * qz + qx * qw); - casadi::MX R33 = 1 - 2 * (qx * qx + qy * qy); - - // Position derivative = velocity - x_dot(casadi::Slice(0, 3)) = vel; - - // Quaternion derivative - x_dot(3) = -0.5 * (qx * omega_x + qy * omega_y + qz * omega_z); // qw_dot - x_dot(4) = 0.5 * (qw * omega_x + qy * omega_z - qz * omega_y); // qx_dot - x_dot(5) = 0.5 * (qw * omega_y - qx * omega_z + qz * omega_x); // qy_dot - x_dot(6) = 0.5 * (qw * omega_z + qx * omega_y - qy * omega_x); // qz_dot - - // Velocity derivative (thrust is applied along body z-axis) - casadi::MX thrust_world_x = R13 * thrust; - casadi::MX thrust_world_y = R23 * thrust; - casadi::MX thrust_world_z = R33 * thrust; - - x_dot(7) = thrust_world_x / mass; // vx_dot - x_dot(8) = thrust_world_y / mass; // vy_dot - x_dot(9) = thrust_world_z / mass - gravity; // vz_dot - - // Angular velocity derivative - casadi::MX inertia_inv = casadi::MX::inv(inertia_dm); - casadi::MX tau_vec = casadi::MX::vertcat({tau_x, tau_y, tau_z}); - casadi::MX gyroscopic = casadi::MX::cross(omega, casadi::MX::mtimes(inertia_dm, omega)); - casadi::MX angular_acc = casadi::MX::mtimes(inertia_inv, tau_vec - gyroscopic); - - x_dot(casadi::Slice(10, 13)) = angular_acc; - - return x_dot; - }; - - // RK4 integration function - auto quadrotor_dynamics = [=](casadi::MX x, casadi::MX u) -> casadi::MX { - // RK4 integration: k1, k2, k3, k4 - casadi::MX k1 = quadrotor_derivatives(x, u); - casadi::MX k2 = quadrotor_derivatives(x + timestep/2.0 * k1, u); - casadi::MX k3 = quadrotor_derivatives(x + timestep/2.0 * k2, u); - casadi::MX k4 = quadrotor_derivatives(x + timestep * k3, u); - - // RK4 final integration step - return x + timestep/6.0 * (k1 + 2.0*k2 + 2.0*k3 + k4); - }; - - casadi::MX g; - - // Initial state constraint: X₀ = initial_state - casadi::DM init_state_dm(std::vector(initial_state.data(), initial_state.data() + state_dim)); - g = casadi::MX::vertcat({g, X_t(0) - init_state_dm}); - - // Dynamics constraints - for (int t = 0; t < horizon; t++) { - casadi::MX x_next_expr = quadrotor_dynamics(X_t(t), U_t(t)); - g = casadi::MX::vertcat({g, X_t(t + 1) - x_next_expr}); - } - - ////////// Cost Function ////////// - casadi::MX cost = casadi::MX::zeros(1, 1); - - // Running cost - for (int t = 0; t < horizon; t++) { - // Convert reference state to CasADi - casadi::DM ref_dm(std::vector(figure8_reference_states[t].data(), - figure8_reference_states[t].data() + state_dim)); - - casadi::MX x_diff = X_t(t) - ref_dm; - casadi::MX u_diff = U_t(t); - - casadi::MX state_cost = casadi::MX::mtimes({x_diff.T(), Q_dm, x_diff}); - casadi::MX control_cost = casadi::MX::mtimes({u_diff.T(), R_dm, u_diff}); - cost = cost + state_cost + control_cost; - } - - // Terminal cost - casadi::DM goal_dm(std::vector(goal_state.data(), goal_state.data() + state_dim)); - casadi::MX x_diff_final = X_t(horizon) - goal_dm; - casadi::MX terminal_cost = casadi::MX::mtimes({x_diff_final.T(), Qf_dm, x_diff_final}); - cost = cost + terminal_cost; - - ////////// Variable Bounds and Initial Guess ////////// - std::vector lbx(n_dec, -1e20); - std::vector ubx(n_dec, 1e20); - - // Apply control bounds - for (int t = 0; t < horizon; t++) { - for (int i = 0; i < control_dim; i++) { - lbx[n_states + t * control_dim + i] = u_min(i); - ubx[n_states + t * control_dim + i] = u_max(i); - } - } - - // The complete set of constraints (g) must be equal to zero - const int n_g = static_cast(g.size1()); - std::vector lbg(n_g, 0.0); - std::vector ubg(n_g, 0.0); - - // Provide an initial guess for the decision vector - std::vector x0(n_dec, 0.0); - - // Set the initial state portion - for (int i = 0; i < state_dim; i++) { - - x0[i] = initial_state(i); - } - - // Use the reference trajectory as initial guess for states - for (int t = 1; t <= horizon; t++) { - for (int i = 0; i < state_dim; i++) { - x0[t * state_dim + i] = figure8_reference_states[t](i); - } - } - - // Initial guess for controls (hover thrust) - double hover_thrust = mass * gravity / 4.0; - for (int t = 0; t < horizon; t++) { - for (int i = 0; i < control_dim; i++) { - x0[n_states + t * control_dim + i] = hover_thrust; - } - } - - ////////// NLP Definition and IPOPT Solver Setup ////////// - std::map nlp; - nlp["x"] = z; - nlp["f"] = cost; - nlp["g"] = g; - - casadi::Dict solver_opts; - solver_opts["print_time"] = true; - solver_opts["ipopt.print_level"] = 5; - solver_opts["ipopt.max_iter"] = 1000; - solver_opts["ipopt.tol"] = 1e-6; - solver_opts["ipopt.acceptable_tol"] = 1e-4; - - // Create the NLP solver instance using IPOPT - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Convert the initial guess and bounds into DM objects - casadi::DM x0_dm = casadi::DM(x0); - casadi::DM lbx_dm = casadi::DM(lbx); - casadi::DM ubx_dm = casadi::DM(ubx); - casadi::DM lbg_dm = casadi::DM(lbg); - casadi::DM ubg_dm = casadi::DM(ubg); - - casadi::DMDict arg({ - {"x0", x0_dm}, - {"lbx", lbx_dm}, - {"ubx", ubx_dm}, - {"lbg", lbg_dm}, - {"ubg", ubg_dm} - }); - - ////////// Solve the NLP ////////// - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(arg); - auto end_time = std::chrono::high_resolution_clock::now(); - std::chrono::duration elapsed = end_time - start_time; - std::cout << "Solver elapsed time: " << elapsed.count() << " s" << std::endl; - - ////////// Extract and Display the Solution ////////// - std::vector sol = std::vector(res.at("x")); - - // Convert to state and control trajectories - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - std::vector t_sol(horizon + 1); - for (int t = 0; t <= horizon; t++) { - t_sol[t] = t * timestep; - } - - for (int t = 0; t <= horizon; t++) { - for (int i = 0; i < state_dim; i++) { - X_sol[t](i) = sol[t * state_dim + i]; - } - } - - for (int t = 0; t < horizon; t++) { - for (int i = 0; i < control_dim; i++) { - U_sol[t](i) = sol[n_states + t * control_dim + i]; - } - } - - // Create directory for saving plot (if it doesn't exist) - const std::string plotDirectory = "../results/tests"; - if (!fs::exists(plotDirectory)) { - fs::create_directory(plotDirectory); - } - - // Extract trajectory data for plotting - std::vector time_arr, x_arr, y_arr, z_arr; - std::vector phi_arr, theta_arr, psi_arr; - std::vector qw_arr, qx_arr, qy_arr, qz_arr, q_norm_arr; - - for (size_t i = 0; i < X_sol.size(); ++i) { - time_arr.push_back(t_sol[i]); - x_arr.push_back(X_sol[i](0)); - y_arr.push_back(X_sol[i](1)); - z_arr.push_back(X_sol[i](2)); - - double qw = X_sol[i](3); - double qx = X_sol[i](4); - double qy = X_sol[i](5); - double qz = X_sol[i](6); - - // Euler angles - Eigen::Vector3d euler = quaternionToEuler(qw, qx, qy, qz); - phi_arr.push_back(euler(0)); - theta_arr.push_back(euler(1)); - psi_arr.push_back(euler(2)); - - // Quaternion data - qw_arr.push_back(qw); - qx_arr.push_back(qx); - qy_arr.push_back(qy); - qz_arr.push_back(qz); - q_norm_arr.push_back(std::sqrt(qw*qw + qx*qx + qy*qy + qz*qz)); - } - - // Control data - std::vector time_arr2(time_arr.begin(), time_arr.end() - 1); - std::vector f1_arr, f2_arr, f3_arr, f4_arr; - for (const auto& u : U_sol) { - f1_arr.push_back(u(0)); - f2_arr.push_back(u(1)); - f3_arr.push_back(u(2)); - f4_arr.push_back(u(3)); - } - - // ----------------------------- - // Plot states and controls - // ----------------------------- - auto f1 = figure(); - f1->size(1200, 900); - - // Position trajectories - auto ax1 = subplot(4, 1, 0); - auto plot_handle1 = plot(ax1, time_arr, x_arr, "-r"); - plot_handle1->display_name("x"); - plot_handle1->line_width(2); - hold(ax1, true); - auto plot_handle2 = plot(ax1, time_arr, y_arr, "-g"); - plot_handle2->display_name("y"); - plot_handle2->line_width(2); - auto plot_handle3 = plot(ax1, time_arr, z_arr, "-b"); - plot_handle3->display_name("z"); - plot_handle3->line_width(2); - - title(ax1, "Position Trajectories"); - xlabel(ax1, "Time [s]"); - ylabel(ax1, "Position [m]"); - matplot::legend(ax1); - grid(ax1, true); - - // Attitude angles - auto ax2 = subplot(4, 1, 1); - hold(ax2, true); - auto plot_handle4 = plot(ax2, time_arr, phi_arr, "-r"); - plot_handle4->display_name("roll"); - plot_handle4->line_width(2); - auto plot_handle5 = plot(ax2, time_arr, theta_arr, "-g"); - plot_handle5->display_name("pitch"); - plot_handle5->line_width(2); - auto plot_handle6 = plot(ax2, time_arr, psi_arr, "-b"); - plot_handle6->display_name("yaw"); - plot_handle6->line_width(2); - - title(ax2, "Attitude Angles"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "Angle [rad]"); - matplot::legend(ax2); - grid(ax2, true); - - // Motor forces - auto ax3 = subplot(4, 1, 2); - auto plot_handle7 = plot(ax3, time_arr2, f1_arr, "-r"); - plot_handle7->display_name("f1"); - plot_handle7->line_width(2); - hold(ax3, true); - auto plot_handle8 = plot(ax3, time_arr2, f2_arr, "-g"); - plot_handle8->display_name("f2"); - plot_handle8->line_width(2); - auto plot_handle9 = plot(ax3, time_arr2, f3_arr, "-b"); - plot_handle9->display_name("f3"); - plot_handle9->line_width(2); - auto plot_handle10 = plot(ax3, time_arr2, f4_arr, "-k"); - plot_handle10->display_name("f4"); - plot_handle10->line_width(2); - - title(ax3, "Motor Forces"); - xlabel(ax3, "Time [s]"); - ylabel(ax3, "Force [N]"); - matplot::legend(ax3); - grid(ax3, true); - - // Quaternion components and norm - auto ax4 = subplot(4, 1, 3); - hold(ax4, true); - - auto qwh = plot(ax4, time_arr, qw_arr, "-r"); - qwh->display_name("q_w"); - qwh->line_width(2); - - auto qxh = plot(ax4, time_arr, qx_arr, "-g"); - qxh->display_name("q_x"); - qxh->line_width(2); - - auto qyh = plot(ax4, time_arr, qy_arr, "-b"); - qyh->display_name("q_y"); - qyh->line_width(2); - - auto qzh = plot(ax4, time_arr, qz_arr, "-m"); - qzh->display_name("q_z"); - qzh->line_width(2); - - auto qnorm_handle = plot(ax4, time_arr, q_norm_arr, "-k"); - qnorm_handle->display_name("|q|"); - - title(ax4, "Quaternion Components and Norm"); - xlabel(ax4, "Time [s]"); - ylabel(ax4, "Value"); - matplot::legend(ax4); - grid(ax4, true); - - f1->draw(); - f1->save(plotDirectory + "/quadrotor_ipopt_results.png"); - - // ----------------------------- - // 3D Trajectory Plot - // ----------------------------- - auto f2 = figure(); - f2->size(800, 600); - auto ax_3d = f2->current_axes(); - hold(ax_3d, true); - - auto traj3d = plot3(ax_3d, x_arr, y_arr, z_arr); - traj3d->display_name("Trajectory"); - traj3d->line_style("-"); - traj3d->line_width(2); - traj3d->color("blue"); - - // Project trajectory onto x-y plane at z=0 - auto proj_xy = plot3(ax_3d, x_arr, y_arr, std::vector(x_arr.size(), 0.0)); - proj_xy->display_name("X-Y Projection"); - proj_xy->line_style("--"); - proj_xy->line_width(1); - proj_xy->color("gray"); - - xlabel(ax_3d, "X [m]"); - ylabel(ax_3d, "Y [m]"); - zlabel(ax_3d, "Z [m]"); - xlim(ax_3d, {-5, 5}); - ylim(ax_3d, {-2, 2}); - zlim(ax_3d, {0, 5}); - title(ax_3d, "3D Trajectory (Figure-8) - IPOPT"); - grid(ax_3d, true); - - f2->draw(); - f2->save(plotDirectory + "/quadrotor_ipopt_3d.png"); - - // ----------------------------- - // Animation: Quadrotor Trajectory - // ----------------------------- - auto f_anim = figure(); - f_anim->size(800, 600); - auto ax_anim = f_anim->current_axes(); - - // For collecting the trajectory as we go - std::vector anim_x, anim_y, anim_z; - - // Render every Nth frame to reduce #images - int frame_stride = 15; - double prop_radius = 0.03; - - for (size_t i = 0; i < X_sol.size(); i += frame_stride) { - ax_anim->clear(); - ax_anim->hold(true); - ax_anim->grid(true); - - // Current state - double x = X_sol[i](0); - double y = X_sol[i](1); - double z = X_sol[i](2); - - // Accumulate path - anim_x.push_back(x); - anim_y.push_back(y); - anim_z.push_back(z); - - // Plot the partial trajectory so far - auto path_plot = plot3(anim_x, anim_y, anim_z); - path_plot->line_width(1.5); - path_plot->line_style("--"); - path_plot->color("black"); - - // Build rotation from quaternion - Eigen::Vector4d quat(X_sol[i](3), X_sol[i](4), X_sol[i](5), X_sol[i](6)); - Eigen::Matrix3d R = getRotationMatrixFromQuaternion(quat(0), quat(1), quat(2), quat(3)); - - // Arm endpoints (front, right, back, left) - std::vector arm_endpoints; - arm_endpoints.push_back(Eigen::Vector3d(arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, arm_length, 0)); - arm_endpoints.push_back(Eigen::Vector3d(-arm_length, 0, 0)); - arm_endpoints.push_back(Eigen::Vector3d(0, -arm_length, 0)); - - // Transform to world coords - for (auto& pt : arm_endpoints) { - pt = Eigen::Vector3d(x, y, z) + R * pt; - } - - // Front-back arm - std::vector fx = {arm_endpoints[0].x(), arm_endpoints[2].x()}; - std::vector fy = {arm_endpoints[0].y(), arm_endpoints[2].y()}; - std::vector fz = {arm_endpoints[0].z(), arm_endpoints[2].z()}; - auto fb_arm = plot3(fx, fy, fz); - fb_arm->line_width(2.0); - fb_arm->color("blue"); - - // Right-left arm - std::vector rx = {arm_endpoints[1].x(), arm_endpoints[3].x()}; - std::vector ry = {arm_endpoints[1].y(), arm_endpoints[3].y()}; - std::vector rz = {arm_endpoints[1].z(), arm_endpoints[3].z()}; - auto rl_arm = plot3(rx, ry, rz); - rl_arm->line_width(2.0); - rl_arm->color("red"); - - // Motor props as small circles - auto sphere_points = linspace(0, 2 * M_PI, 15); - for (const auto& motor_pos : arm_endpoints) { - std::vector circ_x, circ_y, circ_z; - for (auto angle : sphere_points) { - circ_x.push_back(motor_pos.x() + prop_radius * cos(angle)); - circ_y.push_back(motor_pos.y() + prop_radius * sin(angle)); - circ_z.push_back(motor_pos.z()); - } - auto sphere_plot = plot3(circ_x, circ_y, circ_z); - sphere_plot->line_style("solid"); - sphere_plot->line_width(1.5); - sphere_plot->color("cyan"); - } - - title(ax_anim, "Quadrotor Animation - IPOPT"); - xlabel(ax_anim, "X [m]"); - ylabel(ax_anim, "Y [m]"); - zlabel(ax_anim, "Z [m]"); - xlim(ax_anim, {-5, 5}); - ylim(ax_anim, {-5, 5}); - zlim(ax_anim, {0, 5}); - - ax_anim->view(30, -30); - - std::string frameFile = plotDirectory + "/quadrotor_ipopt_frame_" + std::to_string(i / frame_stride) + ".png"; - f_anim->draw(); - f_anim->save(frameFile); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/quadrotor_ipopt_frame_*.png " + plotDirectory + "/quadrotor_ipopt.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/quadrotor_ipopt_frame_*.png"; - std::system(cleanup_command.c_str()); - - std::cout << "GIF animation created successfully: " << plotDirectory + "/quadrotor_ipopt.gif" << std::endl; - std::cout << "Final state = " << X_sol.back().transpose() << std::endl; - - return 0; -} diff --git a/examples/ipopt_spacecrat_linear_fuel.cpp b/examples/ipopt_spacecrat_linear_fuel.cpp deleted file mode 100644 index 452b85c4..00000000 --- a/examples/ipopt_spacecrat_linear_fuel.cpp +++ /dev/null @@ -1,260 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -int main() -{ - // Problem parameters - int state_dim = 8; // [x y z vx vy vz mass accumulated_control_effort] - int control_dim = 3; // [ux uy uz] - int horizon = 400; - double time_horizon = 400.0; - double timestep = time_horizon / horizon; - - // HCW parameters - double mean_motion = 0.001107; - double initial_mass = 100.0; - double isp = 300.0; - double g0 = 9.80665; - double nominal_radius = 50.0; - double u_max = 10.0; - double u_min = -10.0; - double u_max_norm = 10.0; - double u_min_norm = 0.0; - - // Initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << nominal_radius, 0.0, 0.0, 0.0, -2.0*mean_motion*nominal_radius, 0.0, initial_mass, 0.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, initial_mass, 0.0; - - // Define variables - casadi::MX x = casadi::MX::sym("x", state_dim); - casadi::MX u = casadi::MX::sym("u", control_dim); - - - casadi::MX vx = x(3); - casadi::MX vy = x(4); - casadi::MX vz = x(5); - casadi::MX mass = x(6); - casadi::MX accumulated_control_effort = x(7); - casadi::MX ux = u(0); - casadi::MX uy = u(1); - casadi::MX uz = u(2); - - // Continuous dynamics (HCW) - casadi::MX dx = casadi::MX::zeros(state_dim); - - dx(0) = vx; - dx(1) = vy; - dx(2) = vz; - dx(3) = -2.0*mean_motion*vx + ux / mass; - dx(4) = -2.0*mean_motion*vy + uy / mass; - dx(5) = -2.0*mean_motion*vz + uz / mass; - dx(6) = -ux*ux - uy*uy - uz*uz / (mass*mass); - dx(7) = ux*ux + uy*uy + uz*uz; - - // Discrete dynamics using Euler integration - casadi::MX f = x + timestep * dx; - casadi::Function F("F", {x, u}, {f}); - - // Decision variables - int n_states = (horizon + 1) * state_dim; - int n_controls = horizon * control_dim; - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Objective function terms - auto running_cost = [&](casadi::MX x, casadi::MX u) - { - return 0.0; - }; - - auto terminal_cost = [&](casadi::MX x) - { - // Final cost is the terminal mass. - casadi::MX cost =-x(6); - return cost; - }; - - // Build objective (general) - casadi::MX J = 0; - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - J += running_cost(x_t, u_t); - } - J += terminal_cost(X(casadi::Slice(horizon * state_dim, (horizon + 1) * state_dim))); - - // Constraints - casadi::MX g; - - // Initial condition (general) - g = X(casadi::Slice(0, state_dim)) - - casadi::DM(std::vector(initial_state.data(), initial_state.data() + state_dim)); - - // Dynamics constraints (general) - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - casadi::MX x_next = F(casadi::MXVector{x_t, u_t})[0]; - casadi::MX x_next_sym = X(casadi::Slice((t + 1) * state_dim, (t + 2) * state_dim)); - g = casadi::MX::vertcat({g, x_next_sym - x_next}); - } - - // Terminal condition (HCW specific) - // x, y, z, vx, vy, vz are zero - casadi::MX x_T = X(casadi::Slice(horizon * state_dim, (horizon + 1) * state_dim)); - g = casadi::MX::vertcat({g, x_T(0)}); // x_terminal = 0 - g = casadi::MX::vertcat({g, x_T(1)}); // y_terminal = 0 - g = casadi::MX::vertcat({g, x_T(2)}); // z_terminal = 0 - g = casadi::MX::vertcat({g, x_T(3)}); // vx_terminal = 0 - g = casadi::MX::vertcat({g, x_T(4)}); // vy_terminal = 0 - g = casadi::MX::vertcat({g, x_T(5)}); // vz_terminal = 0 - - // Control constraints (HCW specific) - // ux, uy, uz are bounded by u_max and u_min (this is defined later) - // Also, the thrust magnitude is bounded by u_max_norm and u_min_norm - for (int t = 0; t < horizon; t++) - { - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - g = casadi::MX::vertcat({g, casadi::MX::norm_2(u_t) - u_max_norm}); - g = casadi::MX::vertcat({g, casadi::MX::norm_2(u_t) - u_min_norm}); - } - - // NLP - casadi::MXDict nlp = { - {"x", z}, - {"f", J}, - {"g", g}}; - - // Solver options - casadi::Dict solver_opts; - solver_opts["ipopt.max_iter"] = 1000; - solver_opts["ipopt.print_level"] = 5; - solver_opts["print_time"] = true; - solver_opts["ipopt.tol"] = 1e-6; - - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Bounds - std::vector lbx(n_states + n_controls); - std::vector ubx(n_states + n_controls); - std::vector lbg(g.size1()); - std::vector ubg(g.size1()); - - // State bounds - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - lbx[t * state_dim + i] = -1e20; - ubx[t * state_dim + i] = 1e20; - } - } - - // Control bounds - for (int t = 0; t < horizon; t++) - { - // Acceleration bounds - lbx[n_states + t * control_dim + 0] = -u_max; - ubx[n_states + t * control_dim + 0] = u_max; - lbx[n_states + t * control_dim + 1] = -u_max; - ubx[n_states + t * control_dim + 1] = u_max; - lbx[n_states + t * control_dim + 2] = -u_max; - ubx[n_states + t * control_dim + 2] = u_max; - } - - // Constraint bounds (all equality constraints) - for (int i = 0; i < g.size1(); i++) - { - lbg[i] = 0; - ubg[i] = 0; - } - - // Initial guess - std::vector x0(n_states + n_controls, 0.0); - - // Initial state - for (int i = 0; i < state_dim; i++) - { - x0[i] = initial_state(i); - } - - // Linear interpolation for states - for (int t = 1; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - x0[t * state_dim + i] = initial_state(i) + - (goal_state(i) - initial_state(i)) * t / horizon; - } - } - - // Call the solver - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(casadi::DMDict{ - {"x0", x0}, - {"lbx", lbx}, - {"ubx", ubx}, - {"lbg", lbg}, - {"ubg", ubg}}); - auto end_time = std::chrono::high_resolution_clock::now(); - auto duration = std::chrono::duration_cast(end_time - start_time); - - std::cout << "Solve time: " << duration.count() << " microseconds" << std::endl; - - // Extract solution - std::vector sol = std::vector(res.at("x")); - - // Convert to state and control trajectories - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - X_sol[t](i) = sol[t * state_dim + i]; - } - } - - for (int t = 0; t < horizon; t++) - { - for (int i = 0; i < control_dim; i++) - { - U_sol[t](i) = sol[n_states + t * control_dim + i]; - } - } - - - return 0; -} \ No newline at end of file diff --git a/examples/ipopt_spacecrat_rpo.cpp b/examples/ipopt_spacecrat_rpo.cpp deleted file mode 100644 index 452b85c4..00000000 --- a/examples/ipopt_spacecrat_rpo.cpp +++ /dev/null @@ -1,260 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ -#include -#include -#include -#include -#include -#include -#include -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -int main() -{ - // Problem parameters - int state_dim = 8; // [x y z vx vy vz mass accumulated_control_effort] - int control_dim = 3; // [ux uy uz] - int horizon = 400; - double time_horizon = 400.0; - double timestep = time_horizon / horizon; - - // HCW parameters - double mean_motion = 0.001107; - double initial_mass = 100.0; - double isp = 300.0; - double g0 = 9.80665; - double nominal_radius = 50.0; - double u_max = 10.0; - double u_min = -10.0; - double u_max_norm = 10.0; - double u_min_norm = 0.0; - - // Initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << nominal_radius, 0.0, 0.0, 0.0, -2.0*mean_motion*nominal_radius, 0.0, initial_mass, 0.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, initial_mass, 0.0; - - // Define variables - casadi::MX x = casadi::MX::sym("x", state_dim); - casadi::MX u = casadi::MX::sym("u", control_dim); - - - casadi::MX vx = x(3); - casadi::MX vy = x(4); - casadi::MX vz = x(5); - casadi::MX mass = x(6); - casadi::MX accumulated_control_effort = x(7); - casadi::MX ux = u(0); - casadi::MX uy = u(1); - casadi::MX uz = u(2); - - // Continuous dynamics (HCW) - casadi::MX dx = casadi::MX::zeros(state_dim); - - dx(0) = vx; - dx(1) = vy; - dx(2) = vz; - dx(3) = -2.0*mean_motion*vx + ux / mass; - dx(4) = -2.0*mean_motion*vy + uy / mass; - dx(5) = -2.0*mean_motion*vz + uz / mass; - dx(6) = -ux*ux - uy*uy - uz*uz / (mass*mass); - dx(7) = ux*ux + uy*uy + uz*uz; - - // Discrete dynamics using Euler integration - casadi::MX f = x + timestep * dx; - casadi::Function F("F", {x, u}, {f}); - - // Decision variables - int n_states = (horizon + 1) * state_dim; - int n_controls = horizon * control_dim; - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Objective function terms - auto running_cost = [&](casadi::MX x, casadi::MX u) - { - return 0.0; - }; - - auto terminal_cost = [&](casadi::MX x) - { - // Final cost is the terminal mass. - casadi::MX cost =-x(6); - return cost; - }; - - // Build objective (general) - casadi::MX J = 0; - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - J += running_cost(x_t, u_t); - } - J += terminal_cost(X(casadi::Slice(horizon * state_dim, (horizon + 1) * state_dim))); - - // Constraints - casadi::MX g; - - // Initial condition (general) - g = X(casadi::Slice(0, state_dim)) - - casadi::DM(std::vector(initial_state.data(), initial_state.data() + state_dim)); - - // Dynamics constraints (general) - for (int t = 0; t < horizon; t++) - { - casadi::MX x_t = X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - casadi::MX x_next = F(casadi::MXVector{x_t, u_t})[0]; - casadi::MX x_next_sym = X(casadi::Slice((t + 1) * state_dim, (t + 2) * state_dim)); - g = casadi::MX::vertcat({g, x_next_sym - x_next}); - } - - // Terminal condition (HCW specific) - // x, y, z, vx, vy, vz are zero - casadi::MX x_T = X(casadi::Slice(horizon * state_dim, (horizon + 1) * state_dim)); - g = casadi::MX::vertcat({g, x_T(0)}); // x_terminal = 0 - g = casadi::MX::vertcat({g, x_T(1)}); // y_terminal = 0 - g = casadi::MX::vertcat({g, x_T(2)}); // z_terminal = 0 - g = casadi::MX::vertcat({g, x_T(3)}); // vx_terminal = 0 - g = casadi::MX::vertcat({g, x_T(4)}); // vy_terminal = 0 - g = casadi::MX::vertcat({g, x_T(5)}); // vz_terminal = 0 - - // Control constraints (HCW specific) - // ux, uy, uz are bounded by u_max and u_min (this is defined later) - // Also, the thrust magnitude is bounded by u_max_norm and u_min_norm - for (int t = 0; t < horizon; t++) - { - casadi::MX u_t = U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - g = casadi::MX::vertcat({g, casadi::MX::norm_2(u_t) - u_max_norm}); - g = casadi::MX::vertcat({g, casadi::MX::norm_2(u_t) - u_min_norm}); - } - - // NLP - casadi::MXDict nlp = { - {"x", z}, - {"f", J}, - {"g", g}}; - - // Solver options - casadi::Dict solver_opts; - solver_opts["ipopt.max_iter"] = 1000; - solver_opts["ipopt.print_level"] = 5; - solver_opts["print_time"] = true; - solver_opts["ipopt.tol"] = 1e-6; - - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Bounds - std::vector lbx(n_states + n_controls); - std::vector ubx(n_states + n_controls); - std::vector lbg(g.size1()); - std::vector ubg(g.size1()); - - // State bounds - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - lbx[t * state_dim + i] = -1e20; - ubx[t * state_dim + i] = 1e20; - } - } - - // Control bounds - for (int t = 0; t < horizon; t++) - { - // Acceleration bounds - lbx[n_states + t * control_dim + 0] = -u_max; - ubx[n_states + t * control_dim + 0] = u_max; - lbx[n_states + t * control_dim + 1] = -u_max; - ubx[n_states + t * control_dim + 1] = u_max; - lbx[n_states + t * control_dim + 2] = -u_max; - ubx[n_states + t * control_dim + 2] = u_max; - } - - // Constraint bounds (all equality constraints) - for (int i = 0; i < g.size1(); i++) - { - lbg[i] = 0; - ubg[i] = 0; - } - - // Initial guess - std::vector x0(n_states + n_controls, 0.0); - - // Initial state - for (int i = 0; i < state_dim; i++) - { - x0[i] = initial_state(i); - } - - // Linear interpolation for states - for (int t = 1; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - x0[t * state_dim + i] = initial_state(i) + - (goal_state(i) - initial_state(i)) * t / horizon; - } - } - - // Call the solver - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(casadi::DMDict{ - {"x0", x0}, - {"lbx", lbx}, - {"ubx", ubx}, - {"lbg", lbg}, - {"ubg", ubg}}); - auto end_time = std::chrono::high_resolution_clock::now(); - auto duration = std::chrono::duration_cast(end_time - start_time); - - std::cout << "Solve time: " << duration.count() << " microseconds" << std::endl; - - // Extract solution - std::vector sol = std::vector(res.at("x")); - - // Convert to state and control trajectories - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - X_sol[t](i) = sol[t * state_dim + i]; - } - } - - for (int t = 0; t < horizon; t++) - { - for (int i = 0; i < control_dim; i++) - { - U_sol[t](i) = sol[n_states + t * control_dim + i]; - } - } - - - return 0; -} \ No newline at end of file diff --git a/examples/ipopt_unicycle.cpp b/examples/ipopt_unicycle.cpp deleted file mode 100644 index 0a20e171..00000000 --- a/examples/ipopt_unicycle.cpp +++ /dev/null @@ -1,459 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "matplot/matplot.h" - -using namespace matplot; -namespace fs = std::filesystem; - -int main() { - ////////// Problem Setup ////////// - const int state_dim = 3; // [x, y, theta] - const int control_dim = 2; // [v, omega] - const int horizon = 100; // Number of control intervals - const double timestep = 0.03; // Time step - - // Define initial and goal states - Eigen::VectorXd initial_state(state_dim); - initial_state << 0.0, 0.0, M_PI/4.0; - - Eigen::VectorXd goal_state(state_dim); - goal_state << 2.0, 2.0, M_PI/2.0; - // Define cost weighting matrices - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(state_dim, state_dim); - - Eigen::MatrixXd R = 0.5 * Eigen::MatrixXd::Identity(control_dim, control_dim); - - // Terminal cost weight (optional if using terminal constraint) - Eigen::MatrixXd Qf = Eigen::MatrixXd::Identity(state_dim, state_dim); - Qf(0, 0) = 100.0; // x position - Qf(1, 1) = 100.0; // y position - Qf(2, 2) = 100.0; // heading - - - casadi::DM Q_dm(Q.rows(), Q.cols()); - for (int i = 0; i < Q.rows(); i++) { - for (int j = 0; j < Q.cols(); j++) { - Q_dm(i, j) = Q(i, j); - } - } - casadi::DM R_dm(R.rows(), R.cols()); - for (int i = 0; i < R.rows(); i++) { - for (int j = 0; j < R.cols(); j++) { - R_dm(i, j) = R(i, j); - } - } - casadi::DM Qf_dm(Qf.rows(), Qf.cols()); - for (int i = 0; i < Qf.rows(); i++) { - for (int j = 0; j < Qf.cols(); j++) { - Qf_dm(i, j) = Qf(i, j); - } - } - - // Define control bounds (for example, v ∈ [-1, 1] and ω ∈ [-π, π]) - Eigen::VectorXd u_min(control_dim), u_max(control_dim); - u_min << -1.0, -M_PI; - u_max << 1.0, M_PI; - - const int n_states = (horizon + 1) * state_dim; - const int n_controls = horizon * control_dim; - const int n_dec = n_states + n_controls; - - // Define symbolic variables for states and controls - casadi::MX X = casadi::MX::sym("X", n_states); - casadi::MX U = casadi::MX::sym("U", n_controls); - casadi::MX z = casadi::MX::vertcat({X, U}); - - // Helper lambdas to extract the state and control at time step t - auto X_t = [=](int t) -> casadi::MX { - return X(casadi::Slice(t * state_dim, (t + 1) * state_dim)); - }; - auto U_t = [=](int t) -> casadi::MX { - return U(casadi::Slice(t * control_dim, (t + 1) * control_dim)); - }; - - auto unicycle_dynamics = [=](casadi::MX x, casadi::MX u) -> casadi::MX { - casadi::MX x_next = casadi::MX::zeros(state_dim, 1); - casadi::MX theta = x(2); - casadi::MX v = u(0); - casadi::MX omega = u(1); - - // Use casadi's trigonometric functions - using casadi::cos; - using casadi::sin; - casadi::MX ctheta = cos(theta); - casadi::MX stheta = sin(theta); - // Euler integration discretization - x_next(0) = x(0) + v * ctheta * timestep; - x_next(1) = x(1) + v * stheta * timestep; - x_next(2) = x(2) + omega * timestep; - return x_next; - }; - - casadi::MX g; - - // Initial state constraint: X₀ = initial_state - casadi::DM init_state_dm(std::vector(initial_state.data(), initial_state.data() + state_dim)); - g = casadi::MX::vertcat({g, X_t(0) - init_state_dm}); - - // Dynamics constraints: - for (int t = 0; t < horizon; t++) { - casadi::MX x_next_expr = unicycle_dynamics(X_t(t), U_t(t)); - g = casadi::MX::vertcat({g, X_t(t + 1) - x_next_expr}); - } - - // --- Terminal Condition Constraint --- - casadi::DM goal_dm(std::vector(goal_state.data(), goal_state.data() + state_dim)); - casadi::MX terminal_constr = X_t(horizon) - goal_dm; - g = casadi::MX::vertcat({g, terminal_constr}); - - ////////// Cost Function ////////// - casadi::MX cost = casadi::MX::zeros(1, 1); - for (int t = 0; t < horizon; t++) { - casadi::MX x_diff = X_t(t) - goal_dm; - casadi::MX u_diff = U_t(t); - casadi::MX state_cost = casadi::MX::mtimes({x_diff.T(), Q_dm, x_diff}); - casadi::MX control_cost = casadi::MX::mtimes({u_diff.T(), R_dm, u_diff}); - cost = cost + state_cost + control_cost; - } - // Terminal cost - casadi::MX x_diff_final = X_t(horizon) - goal_dm; - casadi::MX terminal_cost = casadi::MX::mtimes({x_diff_final.T(), Qf_dm, x_diff_final}); - cost = cost + terminal_cost; - - ////////// Variable Bounds and Initial Guess ////////// - std::vector lbx(n_dec, -1e20); - std::vector ubx(n_dec, 1e20); - // Apply control bounds for the control segments. - for (int t = 0; t < horizon; t++) { - for (int i = 0; i < control_dim; i++) { - lbx[n_states + t * control_dim + i] = u_min(i); - ubx[n_states + t * control_dim + i] = u_max(i); - } - } - - // The complete set of constraints (g) must be equal to zero. - const int n_g = static_cast(g.size1()); - std::vector lbg(n_g, 0.0); - std::vector ubg(n_g, 0.0); - - // Provide an initial guess for the decision vector. - std::vector x0(n_dec, 0.0); - // Set the initial state portion. - for (int i = 0; i < state_dim; i++) { - x0[i] = initial_state(i); - } - // Linearly interpolate the state trajectory from initial_state to goal_state. - for (int t = 1; t <= horizon; t++) { - for (int i = 0; i < state_dim; i++) { - x0[t * state_dim + i] = initial_state(i) + (goal_state(i) - initial_state(i)) * (double)t / horizon; - } - } - // The control part of the initial guess remains zero. - - ////////// NLP Definition and IPOPT Solver Setup ////////// - std::map nlp; - nlp["x"] = z; - nlp["f"] = cost; - nlp["g"] = g; - - casadi::Dict solver_opts; - solver_opts["print_time"] = true; - solver_opts["ipopt.print_level"] = 5; - solver_opts["ipopt.max_iter"] = 500; - solver_opts["ipopt.tol"] = 1e-6; - - // Create the NLP solver instance using IPOPT. - casadi::Function solver = casadi::nlpsol("solver", "ipopt", nlp, solver_opts); - - // Convert the initial guess and bounds into DM objects. - casadi::DM x0_dm = casadi::DM(x0); - casadi::DM lbx_dm = casadi::DM(lbx); - casadi::DM ubx_dm = casadi::DM(ubx); - casadi::DM lbg_dm = casadi::DM(lbg); - casadi::DM ubg_dm = casadi::DM(ubg); - - casadi::DMDict arg({ - {"x0", x0_dm}, - {"lbx", lbx_dm}, - {"ubx", ubx_dm}, - {"lbg", lbg_dm}, - {"ubg", ubg_dm} - }); - - ////////// Solve the NLP ////////// - auto start_time = std::chrono::high_resolution_clock::now(); - casadi::DMDict res = solver(arg); - auto end_time = std::chrono::high_resolution_clock::now(); - std::chrono::duration elapsed = end_time - start_time; - std::cout << "Solver elapsed time: " << elapsed.count() << " s" << std::endl; - - ////////// Extract and Display the Solution ////////// - // The result 'res["x"]' is a DM vector with the optimized decision variables. - std::vector sol = std::vector(res.at("x")); - - // Convert to state and control trajectories - std::vector X_sol(horizon + 1, Eigen::VectorXd(state_dim)); - std::vector U_sol(horizon, Eigen::VectorXd(control_dim)); - std::vector t_sol(horizon + 1); - for (int t = 0; t <= horizon; t++) { - t_sol[t] = t * timestep; - } - - for (int t = 0; t <= horizon; t++) - { - for (int i = 0; i < state_dim; i++) - { - X_sol[t](i) = sol[t * state_dim + i]; - } - } - - for (int t = 0; t < horizon; t++) - { - for (int i = 0; i < control_dim; i++) - { - U_sol[t](i) = sol[n_states + t * control_dim + i]; - } - } - - // Create directory for saving plot (if it doesn't exist) - const std::string plotDirectory = "../results/tests"; - if (!fs::exists(plotDirectory)) { - fs::create_directory(plotDirectory); - } - - // Plot the solution (x-y plane) - std::vector x_arr, y_arr, theta_arr; - for (const auto& x : X_sol) { - x_arr.push_back(x(0)); - y_arr.push_back(x(1)); - theta_arr.push_back(x(2)); - } - - // Plot the solution (control inputs) - std::vector v_arr, omega_arr; - for (const auto& u : U_sol) { - v_arr.push_back(u(0)); - omega_arr.push_back(u(1)); - } - - // ----------------------------- - // Plot states and controls - // ----------------------------- - auto f1 = figure(); - f1->size(1200, 800); - - // First subplot: Position Trajectory - auto ax1 = subplot(3, 1, 0); - auto plot_handle = plot(ax1, x_arr, y_arr, "-b"); - plot_handle->line_width(3); - title(ax1, "Position Trajectory"); - xlabel(ax1, "x [m]"); - ylabel(ax1, "y [m]"); - - // Second subplot: Heading Angle vs Time - auto ax2 = subplot(3, 1, 1); - auto heading_plot_handle = plot(ax2, t_sol, theta_arr); - heading_plot_handle->line_width(3); - title(ax2, "Heading Angle"); - xlabel(ax2, "Time [s]"); - ylabel(ax2, "theta [rad]"); - - // Fourth subplot: Control Inputs - auto ax4 = subplot(3, 1, 2); - auto p1 = plot(ax4, v_arr, "--b"); - p1->line_width(3); - p1->display_name("Acceleration"); - - hold(ax4, true); - auto p2 = plot(ax4, omega_arr, "--r"); - p2->line_width(3); - p2->display_name("Steering"); - - title(ax4, "Control Inputs"); - xlabel(ax4, "Step"); - ylabel(ax4, "Control"); - matplot::legend(ax4); - - f1->draw(); - f1->save(plotDirectory + "/unicycle_ipopt_results.png"); - - // ----------------------------- - // Animation: unicycle Trajectory - // ----------------------------- - auto f2 = figure(); - f2->size(800, 600); - auto ax_anim = f2->current_axes(); - if (!ax_anim) - { - ax_anim = axes(); - } - - double car_length = 0.35; - double car_width = 0.15; - - for (size_t i = 0; i < X_sol.size(); ++i) - { - if (i % 10 == 0) - { - ax_anim->clear(); - hold(ax_anim, true); - - double x = x_arr[i]; - double y = y_arr[i]; - double theta = theta_arr[i]; - - // Compute unicycle rectangle corners - std::vector car_x(5), car_y(5); - car_x[0] = x + car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[0] = y + car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[1] = x + car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[1] = y + car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[2] = x - car_length / 2 * cos(theta) + car_width / 2 * sin(theta); - car_y[2] = y - car_length / 2 * sin(theta) - car_width / 2 * cos(theta); - car_x[3] = x - car_length / 2 * cos(theta) - car_width / 2 * sin(theta); - car_y[3] = y - car_length / 2 * sin(theta) + car_width / 2 * cos(theta); - car_x[4] = car_x[0]; - car_y[4] = car_y[0]; - - auto car_line = plot(ax_anim, car_x, car_y); - car_line->color("black"); - car_line->line_style("solid"); - car_line->line_width(2); - car_line->display_name("Car"); - - // Plot trajectory up to current frame - std::vector traj_x(x_arr.begin(), x_arr.begin() + i + 1); - std::vector traj_y(y_arr.begin(), y_arr.begin() + i + 1); - auto traj_line = plot(ax_anim, traj_x, traj_y); - traj_line->color("blue"); - traj_line->line_style("solid"); - traj_line->line_width(1.5); - traj_line->display_name("Trajectory"); - - title(ax_anim, "unicycle Trajectory"); - xlabel(ax_anim, "x [m]"); - ylabel(ax_anim, "y [m]"); - xlim(ax_anim, {-1, 2.2}); - ylim(ax_anim, {-1, 2.2}); - // legend(ax_anim); - - std::string filename = plotDirectory + "/unicycle_frame_" + std::to_string(i) + ".png"; - f2->draw(); - f2->save(filename); - std::this_thread::sleep_for(std::chrono::milliseconds(80)); - } - } - - // ----------------------------- - // Generate GIF from frames using ImageMagick - // ----------------------------- - std::string gif_command = "convert -delay 30 " + plotDirectory + "/unicycle_frame_*.png " + plotDirectory + "/unicycle_ipopt.gif"; - std::system(gif_command.c_str()); - - std::string cleanup_command = "rm " + plotDirectory + "/unicycle_frame_*.png"; - std::system(cleanup_command.c_str()); - - - std::cout << "GIF animation created successfully: " << plotDirectory + "/unicycle_ipopt.gif" << std::endl; - - return 0; -} - -// :~/github/cddp-cpp/build$ ./examples/ipopt_unicycle - -// ****************************************************************************** -// This program contains Ipopt, a library for large-scale nonlinear optimization. -// Ipopt is released as open source code under the Eclipse Public License (EPL). -// For more information visit http://projects.coin-or.org/Ipopt -// ****************************************************************************** - -// This is Ipopt version 3.11.9, running with linear solver mumps. -// NOTE: Other linear solvers might be more efficient (see Ipopt documentation). - -// Number of nonzeros in equality constraint Jacobian...: 1106 -// Number of nonzeros in inequality constraint Jacobian.: 0 -// Number of nonzeros in Lagrangian Hessian.............: 506 - -// Total number of variables............................: 503 -// variables with only lower bounds: 0 -// variables with lower and upper bounds: 200 -// variables with only upper bounds: 0 -// Total number of equality constraints.................: 306 -// Total number of inequality constraints...............: 0 -// inequality constraints with only lower bounds: 0 -// inequality constraints with lower and upper bounds: 0 -// inequality constraints with only upper bounds: 0 - -// iter objective inf_pr inf_du lg(mu) ||d|| lg(rg) alpha_du alpha_pr ls -// 0 0.0000000e+00 2.00e-02 0.00e+00 -1.0 0.00e+00 - 0.00e+00 0.00e+00 0 -// 1 1.3213637e+01 1.45e-02 5.18e+00 -1.0 3.57e+00 - 2.22e-01 2.77e-01h 1 -// 2 4.8004394e+01 2.56e-02 3.60e+00 -1.0 2.64e+00 0.0 2.24e-01 3.65e-01h 1 -// 3 6.2828049e+01 2.00e-02 3.08e+00 -1.0 3.97e+00 - 1.91e-01 2.19e-01h 1 -// 4 5.3377401e+01 1.25e-02 1.56e+00 -1.0 1.01e+00 - 3.34e-01 3.98e-01f 1 -// 5 5.6693670e+01 3.61e-03 6.71e-01 -1.0 1.78e+00 - 9.31e-01 7.28e-01h 1 -// 6 6.0580150e+01 2.37e-04 4.35e-02 -1.7 1.95e-01 - 9.48e-01 1.00e+00h 1 -// 7 6.0448863e+01 2.28e-05 2.20e-01 -2.5 1.36e-01 - 6.39e-01 1.00e+00f 1 -// 8 6.0165740e+01 1.35e-05 6.29e-02 -2.5 1.28e-01 - 7.42e-01 1.00e+00f 1 -// 9 6.0066412e+01 4.10e-06 5.07e-04 -2.5 5.72e-02 - 1.00e+00 1.00e+00f 1 -// iter objective inf_pr inf_du lg(mu) ||d|| lg(rg) alpha_du alpha_pr ls -// 10 5.9914306e+01 9.25e-06 2.97e-02 -3.8 5.45e-02 - 6.88e-01 1.00e+00f 1 -// 11 5.9875609e+01 1.08e-06 3.38e-03 -3.8 2.49e-02 - 9.21e-01 1.00e+00f 1 -// 12 5.9869812e+01 6.18e-08 7.97e-06 -3.8 7.32e-03 - 1.00e+00 1.00e+00h 1 -// 13 5.9857746e+01 9.70e-08 5.52e-04 -5.7 5.35e-03 - 9.49e-01 1.00e+00f 1 -// 14 5.9857287e+01 2.38e-09 5.54e-07 -5.7 2.47e-03 - 1.00e+00 1.00e+00h 1 -// 15 5.9857127e+01 3.02e-10 6.60e-08 -7.0 9.07e-04 - 1.00e+00 1.00e+00h 1 -// 16 5.9857126e+01 1.05e-12 3.89e-10 -7.0 1.04e-04 - 1.00e+00 1.00e+00h 1 - -// Number of Iterations....: 16 - -// (scaled) (unscaled) -// Objective...............: 5.9857125548898239e+01 5.9857125548898239e+01 -// Dual infeasibility......: 3.8946268432482611e-10 3.8946268432482611e-10 -// Constraint violation....: 1.0502709812953981e-12 1.0502709812953981e-12 -// Complementarity.........: 1.0259906103085439e-07 1.0259906103085439e-07 -// Overall NLP error.......: 1.0259906103085439e-07 1.0259906103085439e-07 - - -// Number of objective function evaluations = 17 -// Number of objective gradient evaluations = 17 -// Number of equality constraint evaluations = 17 -// Number of inequality constraint evaluations = 0 -// Number of equality constraint Jacobian evaluations = 17 -// Number of inequality constraint Jacobian evaluations = 0 -// Number of Lagrangian Hessian evaluations = 16 -// Total CPU secs in IPOPT (w/o function evaluations) = 0.017 -// Total CPU secs in NLP function evaluations = 0.004 - -// EXIT: Optimal Solution Found. -// solver : t_proc (avg) t_wall (avg) n_eval -// nlp_f | 242.00us ( 14.24us) 241.34us ( 14.20us) 17 -// nlp_g | 503.00us ( 29.59us) 503.62us ( 29.62us) 17 -// nlp_grad_f | 493.00us ( 27.39us) 490.74us ( 27.26us) 18 -// nlp_hess_l | 1.71ms (106.69us) 1.71ms (106.86us) 16 -// nlp_jac_g | 1.85ms (102.56us) 1.85ms (102.81us) 18 -// total | 23.72ms ( 23.72ms) 23.73ms ( 23.73ms) 1 -// Solver elapsed time: 0.0238267 s -// GIF animation created successfully: ../results/tests/unicycle_ipopt.gif \ No newline at end of file diff --git a/examples/mpc_hcw.cpp b/examples/mpc_hcw.cpp deleted file mode 100644 index 2a49e457..00000000 --- a/examples/mpc_hcw.cpp +++ /dev/null @@ -1,386 +0,0 @@ -/* - Copyright 2024 Tomo Sasaki - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#include -#include -#include -#include -#include - -#include "cddp.hpp" -#include "cddp_example_utils.hpp" - -#include "matplot/matplot.h" -using namespace matplot; -namespace fs = std::filesystem; -using namespace cddp; - -int main() { - // ========================================================================= - // 1) Parameters - // ========================================================================= - - // Simulation times - double tf = 600.0; // final time for simulation - int tN = 6000; // number of total time steps for simulation - double dt_sim = tf / tN; // simulation time step (0.1 s) - double Ts = 2.5; // control update period [s] - - // HCW parameters - double mean_motion = 0.001107; - double mass = 100.0; - - HCW hcw_system(dt_sim, mean_motion, mass, "euler"); // HCW system - - // MPC horizon info - double time_horizon = 400.0; // time horizon for MPC [s] - int N = 40; // predictive horizon length - double dt_mpc = time_horizon / N; // MPC time step - - // Final (reference) state - Eigen::VectorXd x_ref(6); - x_ref << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; - - // Input constraints - double u_max = 1.0; // for each dimension - double u_min = -1.0; // for each dimension - - // Cost weighting - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(6,6); - { - Q(0,0) = 1e+1; Q(1,1) = 1e+1; Q(2,2) = 1e+1; - Q(3,3) = 1e-0; Q(4,4) = 1e-0; Q(5,5) = 1e-0; - } - - Eigen::MatrixXd R = Eigen::MatrixXd::Zero(3,3); - { - R(0,0) = 1e-0; R(1,1) = 1e-0; R(2,2) = 1e-0; - } - - // Terminal cost (can be zero or nonzero). - Eigen::MatrixXd Qf = Eigen::MatrixXd::Zero(6,6); - // { - // Qf(0,0) = 1e3; Qf(1,1) = 1e3; Qf(2,2) = 1e3; - // Qf(3,3) = 1e1; Qf(4,4) = 1e1; Qf(5,5) = 1e1; - // } - - // Sample initial conditions (24). - std::vector initial_conditions; - initial_conditions.reserve(24); - auto sqrt3 = std::sqrt(3.0); - - std::vector> ics_data = { - {25.0, 25.0/sqrt3, 0, 0, 0, 0}, - {25.0, 0, 0, 0, 0, 0}, - {25.0,-25.0/sqrt3, 0, 0, 0, 0}, - {50.0, 50.0/sqrt3, 0, 0, 0, 0}, - {50.0, -0, 0, 0, 0, 0}, - {50.0,-50.0/sqrt3, 0, 0, 0, 0}, - {75.0, 75.0/sqrt3, 0, 0, 0, 0}, - {75.0, 0, 0, 0, 0, 0}, - {75.0,-75.0/sqrt3, 0, 0, 0, 0}, - {100.0,100.0/sqrt3,0, 0, 0, 0}, - {100.0,0, 0, 0, 0, 0}, - {100.0,-100.0/sqrt3,0, 0, 0, 0}, - {75.0, 25.0/sqrt3, 0, 0, 0, 0}, - {75.0,-25.0/sqrt3, 0, 0, 0, 0}, - {100.0,25.0/sqrt3, 0, 0, 0, 0}, - {100.0,-25.0/sqrt3, 0, 0, 0, 0}, - {75.0, 50.0/sqrt3, 0, 0, 0, 0}, - {75.0,-50.0/sqrt3, 0, 0, 0, 0}, - {100.0,50.0/sqrt3, 0, 0, 0, 0}, - {100.0,-50.0/sqrt3, 0, 0, 0, 0}, - {75.0, 75.0/sqrt3, 0, 0, 0, 0}, - {75.0,-75.0/sqrt3, 0, 0, 0, 0}, - {100.0,75.0/sqrt3, 0, 0, 0, 0}, - {100.0,-75.0/sqrt3, 0, 0, 0, 0} - }; - - // std::vector> ics_data = { - // {25.0/sqrt3, 25.0, 0, 0, 0, 0}, - // {0, 25.0, 0, 0, 0, 0}, - // {-25.0/sqrt3, 25.0, 0, 0, 0, 0}, - // {50.0/sqrt3, 50.0, 0, 0, 0, 0}, - // {0, 50.0, 0, 0, 0, 0}, - // {-50.0/sqrt3, 50.0, 0, 0, 0, 0}, - // {75.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {0, 75.0, 0, 0, 0, 0}, - // {-75.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {100.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {0, 100.0, 0, 0, 0, 0}, - // {-100.0/sqrt3,100.0, 0, 0, 0, 0}, - // {25.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {-25.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {25.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {-25.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {50.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {-50.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {50.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {-50.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {75.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {-75.0/sqrt3, 75.0, 0, 0, 0, 0}, - // {75.0/sqrt3, 100.0, 0, 0, 0, 0}, - // {-75.0/sqrt3, 100.0, 0, 0, 0, 0} - // }; - - for (auto &data : ics_data) { - Eigen::VectorXd x0(6); - x0 << data[0], data[1], data[2], data[3], data[4], data[5]; - initial_conditions.push_back(x0); - } - - // For plotting/recording data (x, y, z vs time). - // X_data[ i_sample ][ time_index ] = 6D state - // U_data[ i_sample ][ time_index ] = 3D control - const int num_samples = static_cast(initial_conditions.size()); - std::vector> X_data(num_samples, - std::vector(tN)); - std::vector> U_data(num_samples, - std::vector(tN - 1)); - - // ========================================================================= - // 2) Loop over each initial condition, run an MPC-like closed-loop sim - // ========================================================================= - // Optional random generator for initial guess in each MPC solve - std::random_device rd; - std::mt19937 gen(rd()); - std::normal_distribution d(0.0, 0.01); - - for (int i = 0; i < num_samples; ++i) { - // --------------------------------------------------------------------- - // (A) Create a new instance of the HCW system - // --------------------------------------------------------------------- - std::unique_ptr mpc_system = - std::make_unique(dt_mpc, mean_motion, mass, "euler"); - - // --------------------------------------------------------------------- - // (B) Build cost objective - // --------------------------------------------------------------------- - std::vector empty_reference; - auto objective = std::make_unique( - Q, R, Qf, x_ref, empty_reference, dt_mpc - ); - - // Adjust solver options if desired (similar to cddp_hcw.cpp) - cddp::CDDPOptions options; - options.max_iterations = 50; - options.line_search.max_iterations = 21; - options.tolerance = 1e-2; - options.verbose = false; - options.enable_parallel = false; - options.num_threads = 8; - // Regularization - options.regularization.initial_value = 1e-5; - - // --------------------------------------------------------------------- - // (C) Setup CDDP solver - // --------------------------------------------------------------------- - cddp::CDDP cddp_solver(/*initial_state=*/initial_conditions[i], - /*goal_state=*/x_ref, - /*horizon=*/N, - /*timestep=*/dt_mpc, - /*system=*/std::move(mpc_system), - /*objective=*/std::move(objective), - /*options=*/options); - - // Control box constraints - Eigen::VectorXd u_lower(3), u_upper(3); - u_lower << u_min, u_min, u_min; - u_upper << u_max, u_max, u_max; - cddp_solver.addPathConstraint( - "ControlConstraint", - std::make_unique(u_lower, u_upper) - ); - - // --------------------------------------------------------------------- - // (D) Initialize storage for trajectory - // --------------------------------------------------------------------- - for (int k = 0; k < tN; ++k) { - X_data[i][k] = Eigen::VectorXd::Zero(6); - } - for (int k = 0; k < tN - 1; ++k) { - U_data[i][k] = Eigen::VectorXd::Zero(3); - } - X_data[i][0] = initial_conditions[i]; - - // --------------------------------------------------------------------- - // (E) Main time loop for simulation - // --------------------------------------------------------------------- - Eigen::VectorXd current_state = initial_conditions[i]; - Eigen::VectorXd current_u(3); - current_u.setZero(); - - std::vector X_init(N + 1, Eigen::VectorXd::Zero(6)); - std::vector U_init(N, Eigen::VectorXd::Zero(3)); - - X_init[0] = initial_conditions[i]; - - for (auto& u : U_init) { - u << d(gen), d(gen), d(gen); - // u << 0.0, 0.0, 0.0; // zero thruster - } - - // // Propagate the initial guess through the dynamics - for (int k = 0; k < N; ++k) { - X_init[k + 1] = hcw_system.getDiscreteDynamics(X_init[k], U_init[k], k * dt_mpc); - } - - // Assign them to the solver - cddp_solver.setInitialTrajectory(X_init, U_init); - - for (int k = 0; k < tN - 1; ++k) { - double t = k * dt_sim; - - // Check if the state is close to the goal - if (current_state.norm() < 1e-2) { - X_data[i][k + 1] = current_state; - current_u.setZero(); - U_data[i][k] = current_u; - continue; - } - - // Re-solve MPC every Ts seconds fmod - if (fmod(t, Ts) < dt_sim) { - // Update the solver’s current-state as the new “initial state” - cddp_solver.setInitialState(current_state); - - // Solve the MPC problem with horizon N - cddp::CDDPSolution sol = cddp_solver.solve(); - - // Extract the *first* control from that horizon - const auto& control_traj = sol.control_trajectory; - current_u = control_traj[0]; - - const auto& X_sequence = sol.state_trajectory; - const auto& U_sequence = sol.control_trajectory; - - cddp_solver.setInitialTrajectory(X_sequence, U_sequence); - } - - // ----------------------------------------------------------------- - // Advance the state by one simulation step dt_sim - // ----------------------------------------------------------------- - { - current_state = hcw_system.getDiscreteDynamics(current_state, current_u, k * dt_sim); - } - - // Save data - X_data[i][k + 1] = current_state; - U_data[i][k] = current_u; - } // end for k - } // end for i over samples - - // ========================================================================= - // 3) Plot the X-Y trajectories for all samples - // ========================================================================= - { - auto fig = figure(); - fig->size(800, 600); - title("HCW MPC Trajectories (x vs y)"); - for (int i = 0; i < num_samples; ++i) { - std::vector xvals, yvals; - xvals.reserve(tN); - yvals.reserve(tN); - for (int k = 0; k < tN; ++k) { - xvals.push_back(X_data[i][k](0)); // rx - yvals.push_back(X_data[i][k](1)); // ry - } - plot(xvals, yvals); - } - - // Plot the initial conditions - for (int i = 0; i < num_samples; ++i) { - std::vector xvals, yvals; - xvals.push_back(initial_conditions[i](0)); - yvals.push_back(initial_conditions[i](1)); - plot(xvals, yvals, "ro"); - } - - xlabel("x [m]"); - ylabel("y [m]"); - // axis limit - xlim({-10, 110}); - ylim({-100, 100}); - - // xlim(-100, 100); - // ylim(-10, 110); - grid(true); - - // Create results directory - const std::string plotDirectory = "../results/simulations"; - cddp::example::ensurePlotDir(plotDirectory); - std::string figPath = plotDirectory + "/hcw_mpc_cddp_xaxis_trajectories.png"; - save(figPath); - // show(); - } - - // Plot control - { - figure()->size(800, 600); - title("HCW MPC Control Inputs"); - for (int i = 0; i < num_samples; ++i) { - std::vector time_vals; - std::vector u1_vals, u2_vals, u3_vals, u_ub, u_lb; - time_vals.reserve(tN - 1); - u1_vals.reserve(tN - 1); - u2_vals.reserve(tN - 1); - u3_vals.reserve(tN - 1); - u_ub.reserve(tN - 1); - u_lb.reserve(tN - 1); - for (int k = 0; k < tN - 1; ++k) { - time_vals.push_back(k * dt_sim); - u1_vals.push_back(U_data[i][k](0)); - u2_vals.push_back(U_data[i][k](1)); - u3_vals.push_back(U_data[i][k](2)); - u_ub.push_back(u_max); - u_lb.push_back(u_min); - } - subplot(3, 1, 1); - plot(time_vals, u1_vals); - plot(time_vals, u_ub, "r--"); - plot(time_vals, u_lb, "r--"); - xlabel("Time [s]"); - ylabel("u1"); - grid(true); - - subplot(3, 1, 2); - plot(time_vals, u2_vals); - plot(time_vals, u_ub, "r--"); - plot(time_vals, u_lb, "r--"); - xlabel("Time [s]"); - ylabel("u2"); - grid(true); - - subplot(3, 1, 3); - plot(time_vals, u3_vals); - plot(time_vals, u_ub, "r--"); - plot(time_vals, u_lb, "r--"); - xlabel("Time [s]"); - ylabel("u3"); - grid(true); - } - // Create results directory - const std::string plotDirectory = "../results/simulations"; - cddp::example::ensurePlotDir(plotDirectory); - std::string figPath = plotDirectory + "/hcw_mpc_cddp_controls.png"; - save(figPath); - // show(); - } - - - std::cout << "MPC simulation for HCW completed successfully!\n"; - return 0; -} diff --git a/examples/test_barrier_strategies.cpp b/examples/test_barrier_strategies.cpp deleted file mode 100644 index 6ca19e3e..00000000 --- a/examples/test_barrier_strategies.cpp +++ /dev/null @@ -1,147 +0,0 @@ -/* - Example demonstrating the three barrier update strategies for IPDDP and MSIPDDP -*/ - -#include -#include -#include -#include - -#include "cddp.hpp" - -int main() -{ - // Problem setup - const int horizon = 50; - const double timestep = 0.05; - const int state_dim = 3; - const int control_dim = 2; - - // Initial and goal states - Eigen::VectorXd X0(state_dim); - X0 << 0.0, 0.0, 0.0; // x, y, theta - - Eigen::VectorXd Xg(state_dim); - Xg << 2.0, 2.0, 0.0; - - // Test each barrier strategy - std::vector solvers = {"IPDDP", "MSIPDDP"}; - std::vector strategies = { - cddp::BarrierStrategy::ADAPTIVE, - cddp::BarrierStrategy::MONOTONIC, - cddp::BarrierStrategy::IPOPT - }; - std::vector strategy_names = {"ADAPTIVE", "MONOTONIC", "IPOPT"}; - - for (const auto& solver_name : solvers) - { - std::cout << "\n========================================\n"; - std::cout << "Testing " << solver_name << " Solver\n"; - std::cout << "========================================\n"; - - for (size_t i = 0; i < strategies.size(); ++i) - { - std::cout << "\n--- Barrier Strategy: " << strategy_names[i] << " ---\n"; - - // Create CDDP solver first - cddp::CDDP cddp_solver(X0, Xg, horizon, timestep); - - // Create and set dynamics model - auto dynamics = std::make_unique(timestep); - cddp_solver.setDynamicalSystem(std::move(dynamics)); - - // Create and set objective - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(state_dim, state_dim); - Q(0, 0) = 10.0; // x - Q(1, 1) = 10.0; // y - Q(2, 2) = 1.0; // theta - - Eigen::MatrixXd R = Eigen::MatrixXd::Identity(control_dim, control_dim); - R(0, 0) = 0.1; // linear velocity - R(1, 1) = 0.1; // angular velocity - - Eigen::MatrixXd Qf = 100.0 * Q; - - std::vector empty_reference; - auto objective = std::make_unique( - Q, R, Qf, Xg, empty_reference, timestep); - cddp_solver.setObjective(std::move(objective)); - - // Add constraints - Eigen::VectorXd u_upper(control_dim); - u_upper << 1.0, 2.0; // max linear vel, max angular vel - - cddp_solver.addPathConstraint("ControlConstraint", - std::make_unique(-u_upper, u_upper)); - - // State bounds (keep robot in a region) - Eigen::VectorXd x_lower(state_dim), x_upper_state(state_dim); - x_lower << -0.5, -0.5, -M_PI; - x_upper_state << 2.5, 2.5, M_PI; - - cddp_solver.addPathConstraint("StateConstraint", - std::make_unique(x_lower, x_upper_state)); - - // Configure options - cddp::CDDPOptions opts; - opts.max_iterations = 100; - opts.tolerance = 1e-4; - opts.verbose = false; - opts.debug = true; // Enable debug output to see barrier updates - opts.return_iteration_info = true; - - // Set barrier strategy - if (solver_name == "IPDDP") { - opts.ipddp.barrier.strategy = strategies[i]; - opts.ipddp.barrier.mu_initial = 1.0; - opts.ipddp.barrier.mu_update_factor = 0.2; - opts.ipddp.barrier.mu_update_power = 1.5; - } else { - opts.msipddp.barrier.strategy = strategies[i]; - opts.msipddp.barrier.mu_initial = 1.0; - opts.msipddp.barrier.mu_update_factor = 0.2; - opts.msipddp.barrier.mu_update_power = 1.5; - } - - cddp_solver.setOptions(opts); - - // Initialize with straight line trajectory - std::vector X_init(horizon + 1); - std::vector U_init(horizon); - - for (int t = 0; t <= horizon; ++t) { - double alpha = static_cast(t) / horizon; - X_init[t] = (1.0 - alpha) * X0 + alpha * Xg; - } - - for (int t = 0; t < horizon; ++t) { - U_init[t] = Eigen::VectorXd::Zero(control_dim); - } - - cddp_solver.setInitialTrajectory(X_init, U_init); - - // Solve - cddp::CDDPSolution solution = cddp_solver.solve(solver_name); - - // Print results - const auto& status_message = solution.status_message; - auto iterations = solution.iterations_completed; - auto solve_time = solution.solve_time_ms; - auto final_cost = solution.final_objective; - - std::cout << "Status: " << status_message << "\n"; - std::cout << "Iterations: " << iterations << "\n"; - std::cout << "Final cost: " << final_cost << "\n"; - std::cout << "Solve time: " << solve_time << " ms\n"; - - // Extract final barrier parameter - std::cout << "Final barrier μ: " << solution.final_barrier_mu << "\n"; - } - } - - std::cout << "\n========================================\n"; - std::cout << "Test completed successfully!\n"; - std::cout << "========================================\n"; - - return 0; -} \ No newline at end of file diff --git a/include/cddp-cpp/cddp.hpp b/include/cddp-cpp/cddp.hpp index 27e6fccf..e1b2cf5d 100644 --- a/include/cddp-cpp/cddp.hpp +++ b/include/cddp-cpp/cddp.hpp @@ -51,7 +51,6 @@ #include "dynamics_model/spacecraft_landing2d.hpp" #include "dynamics_model/lti_system.hpp" #include "dynamics_model/dreyfus_rocket.hpp" -#include "dynamics_model/spacecraft_roe.hpp" #include "dynamics_model/usv_3dof.hpp" #include "dynamics_model/euler_attitude.hpp" #include "dynamics_model/quaternion_attitude.hpp" diff --git a/include/cddp-cpp/dynamics_model/spacecraft_roe.hpp b/include/cddp-cpp/dynamics_model/spacecraft_roe.hpp deleted file mode 100644 index 81893b26..00000000 --- a/include/cddp-cpp/dynamics_model/spacecraft_roe.hpp +++ /dev/null @@ -1,188 +0,0 @@ -/* - Copyright 2024 - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - https://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -#ifndef CDDP_SPACECRAFT_ROE_HPP -#define CDDP_SPACECRAFT_ROE_HPP - -#include "cddp_core/dynamical_system.hpp" -#include - -namespace cddp -{ - - /** - * @brief Spacecraft Relative Orbital Elements (ROE) Dynamics - * - * State vector (6 dimensions): - * x = [ da, dlambda, dex, dey, dix, diy] - * where: - * - da : Relative semi-major axis - * - dlambda : Relative mean longitude (or some variant of relative angle) - * - dex : Relative x-component of eccentricity vector - * - dey : Relative y-component of eccentricity vector - * - dix : Relative x-component of inclination vector - * - diy : Relative y-component of inclination vector - * - M : Mean anomaly [rad] - * - * Control vector (3 dimensions): - * u = [ ur, ut, un ] - * where: - * - ur : radial acceleration [m/s^2] - * - ut : tangential acceleration [m/s^2] - * - un : normal acceleration [m/s^2] - */ - class SpacecraftROE : public DynamicalSystem - { - public: - /** - * @brief Constructor - * @param timestep Integration timestep [s] - * @param integration_type Integration method (e.g. "rk4") - * @param a Semi-major axis of the reference orbit [m] - * @param u0 Initial mean argument of latitude [rad] - */ - SpacecraftROE( - double timestep, - const std::string &integration_type, - double a, - double u0 = 0.0, - double mass_kg = 1.0); - - // State indices - static constexpr int STATE_DA = 0; ///< Relative semi-major axis - static constexpr int STATE_DLAMBDA = 1; ///< Relative mean longitude - static constexpr int STATE_DEX = 2; ///< Relative eccentricity x-component - static constexpr int STATE_DEY = 3; ///< Relative eccentricity y-component - static constexpr int STATE_DIX = 4; ///< Relative inclination x-component - static constexpr int STATE_DIY = 5; ///< Relative inclination y-component - static constexpr int STATE_DIM = 6; ///< State dimension - - // Control indices - static constexpr int CONTROL_UR = 0; ///< Radial acceleration - static constexpr int CONTROL_UT = 1; ///< Tangential acceleration - static constexpr int CONTROL_UN = 2; ///< Normal acceleration - static constexpr int CONTROL_DIM = 3; ///< Control dimension - - /** - * @brief Compute continuous-time dynamics in ROE coordinates - * @param state Current ROE state vector - * @param control Current control vector [ur, ut, un] - * @param time Current time - * @return Derivative of the ROE state vector - */ - Eigen::VectorXd getContinuousDynamics( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const override; - - /** - * @brief Compute continuous-time dynamics in ROE coordinates using autodiff - * @param state Current ROE state vector - * @param control Current control vector [ur, ut, un] - * @param time Current time - * @return Derivative of the ROE state vector - */ - VectorXdual2nd getContinuousDynamicsAutodiff( - const VectorXdual2nd &state, - const VectorXdual2nd &control, double time) const override; - - /** - * @brief Compute state Jacobian matrix via numerical finite difference - * @param state Current ROE state vector - * @param control Current control vector - * @param time Current time - * @return State Jacobian matrix (d f / d state) - */ - Eigen::MatrixXd getStateJacobian( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const override; - - /** - * @brief Compute control Jacobian matrix via numerical finite difference - * @param state Current ROE state vector - * @param control Current control vector - * @param time Current time - * @return Control Jacobian matrix (d f / d control) - */ - Eigen::MatrixXd getControlJacobian( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const override; - - /** - * @brief Compute state Hessian tensor - * @param state Current state vector - * @param control Current control vector - * @param time Current time - * @return Vector of state Hessian matrices, one per state dimension - */ - std::vector getStateHessian( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const override; - - /** - * @brief Compute control Hessian tensor - * @param state Current state vector - * @param control Current control vector - * @param time Current time - * @return Vector of control Hessian matrices, one per state dimension - */ - std::vector getControlHessian( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const override; - - /** - * @brief Transform the QNS-ROE state to the local Hill/Clohessy-Wiltshire frame. - * - * The returned vector is [x, y, z, xdot, ydot, zdot], representing the relative - * position and velocity in the Hill frame. - * - * @param roe A 6D QNS-ROE state vector - * @param t Time since epoch [s] - * @return A 6D vector [x, y, z, xdot, ydot, zdot] in the HCW frame - */ - Eigen::VectorXd transformROEToHCW(const Eigen::VectorXd &roe, double time) const; - - /** - * @brief Transform a HCW state to the QNS-ROE state. - * - * Expects a 6D input [x, y, z, xdot, ydot, zdot], representing the relative - * position and velocity in the Hill/Clohessy‐Wiltshire frame. - * - * @param hcw A 6D Hill/CWH state vector - * @param t Time since epoch [s] (used for the orbit phase) - * @return A 6D QNS-ROE vector [da, dlambda, dex, dey, dix, diy] - */ - Eigen::VectorXd transformHCWToROE(const Eigen::VectorXd &hcw, double t) const; - - double getSemiMajorAxis() const { return a_; } - double getMeanMotion() const { return n_ref_; } - double getInitialMeanArgumentOfLatitude() const { return u0_; } - double getGravitationalParameter() const { return mu_; } - void setGravitationalParameter(double mu) { mu_ = mu; } - void setMeanMotion(double n) { n_ref_ = n; } - void setSemiMajorAxis(double a) { a_ = a; } - void setInitialMeanArgumentOfLatitude(double u0) { u0_ = u0; } - - private: - double a_; ///< Semi-major axis of the reference orbit [m] - double n_ref_; ///< Mean motion of the reference orbit [rad/s] - double u0_; ///< Initial mean argu- ment of latitude [rad] - double mu_ = 3.9860044e14; ///< Gravitational parameter [m^3/s^2] - double mass_kg_; ///< Mass in kg - }; - -} // namespace cddp - -#endif // CDDP_SPACECRAFT_ROE_HPP diff --git a/python/pycddp/__init__.py b/python/pycddp/__init__.py index 9ea7ddd4..afb4dd78 100644 --- a/python/pycddp/__init__.py +++ b/python/pycddp/__init__.py @@ -50,7 +50,6 @@ SpacecraftNonlinear, DreyfusRocket, SpacecraftLanding2D, - SpacecraftROE, SpacecraftTwobody, LTISystem, Usv3Dof, diff --git a/python/src/bind_dynamics.cpp b/python/src/bind_dynamics.cpp index 4efa7efd..fa1f277a 100644 --- a/python/src/bind_dynamics.cpp +++ b/python/src/bind_dynamics.cpp @@ -22,7 +22,6 @@ #include "dynamics_model/spacecraft_linear.hpp" #include "dynamics_model/spacecraft_linear_fuel.hpp" #include "dynamics_model/spacecraft_nonlinear.hpp" -#include "dynamics_model/spacecraft_roe.hpp" #include "dynamics_model/spacecraft_twobody.hpp" #include "dynamics_model/unicycle.hpp" #include "dynamics_model/usv_3dof.hpp" @@ -226,11 +225,6 @@ void bind_dynamics(py::module_ &m) { py::arg("max_thrust") = 2210000.0, py::arg("max_gimble") = 0.349066); - py::class_(m, "SpacecraftROE") - .def(py::init(), - py::arg("timestep"), py::arg("integration_type"), py::arg("a"), - py::arg("u0") = 0.0, py::arg("mass_kg") = 1.0); - py::class_( m, "SpacecraftTwobody") .def(py::init(), py::arg("timestep"), diff --git a/python/src/bind_solver.cpp b/python/src/bind_solver.cpp index 74b6b180..a653c4d4 100644 --- a/python/src/bind_solver.cpp +++ b/python/src/bind_solver.cpp @@ -47,7 +47,7 @@ bool nativeDynamicsCanSkipGil(const py::handle &object) { "QuadrotorRate", "Manipulator", "HCW", "SpacecraftLinearFuel", "SpacecraftNonlinear", "DreyfusRocket", "SpacecraftLanding2D", - "SpacecraftROE", "SpacecraftTwobody", + "SpacecraftTwobody", "LTISystem", "Usv3Dof", "EulerAttitude", "QuaternionAttitude", "MrpAttitude", }; diff --git a/src/dynamics_model/spacecraft_roe.cpp b/src/dynamics_model/spacecraft_roe.cpp deleted file mode 100644 index 71fe4704..00000000 --- a/src/dynamics_model/spacecraft_roe.cpp +++ /dev/null @@ -1,344 +0,0 @@ -/** - * @file cddp_spacecraft_roe.cpp - * @author ... - * @date 2024 - * @brief Implementation of SpacecraftROE for QNS-ROE dynamics. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - */ - -#include "dynamics_model/spacecraft_roe.hpp" - -#include -#include -#include -#include - -namespace cddp -{ - - SpacecraftROE::SpacecraftROE( - double timestep, - const std::string &integration_type, - double a, - double u0, - double mass_kg) - : DynamicalSystem(STATE_DIM, CONTROL_DIM, timestep, integration_type), - a_(a), - u0_(u0), - mass_kg_(mass_kg) - { - - n_ref_ = std::sqrt(mu_ / (a_ * a_ * a_)); // Mean motion of the reference orbit - } - - //----------------------------------------------------------------------------- - Eigen::VectorXd SpacecraftROE::getContinuousDynamics( - const Eigen::VectorXd &state, - const Eigen::VectorXd &control, double time) const - { - /** - * Based on the linear QNSROE model: - * ẋ = A x + B u - * - * x = [ da, dlambda, dex, dey, dix, diy] - * u = [ ur, ut, un ] - * - * A = [ 0 0 0 0 0 0 0 - * -3/2 * n_ref_ 0 0 0 0 0 - * 0 0 0 0 0 0 - * 0 0 0 0 0 0 - * 0 0 0 0 0 0 - * 0 0 0 0 0 0 ] - * - * B(t) = 1/(n_ref_*a_) * - * [ 0 2 0 - * -2 0 0 - * su 2cu 0 - * -cu 2su 0 - * 0 0 cu - * 0 0 su ] - */ - - // Create a zero derivative vector - Eigen::VectorXd xdot = Eigen::VectorXd::Zero(STATE_DIM); - - // Current argument of latitude - double nu = n_ref_ * time + u0_; - - // A*x portion: - double da = state(STATE_DA); - xdot(STATE_DLAMBDA) = -1.5 * n_ref_ * da; - - // B*u portion: - double ur = control(CONTROL_UR); - double ut = control(CONTROL_UT); - double un = control(CONTROL_UN); - - // Factor for scaling control - const double factor = 1.0 / (n_ref_ * a_ * mass_kg_); - - // Calculate su and cu based on initial argument of latitude: - double su = std::sin(nu); - double cu = std::cos(nu); - - // Return the control Jacobian matrix B - Eigen::MatrixXd B(STATE_DIM, CONTROL_DIM); - B.setZero(); - - B(STATE_DA, CONTROL_UT) = 2.0; - B(STATE_DLAMBDA, CONTROL_UR) = -2.0; - B(STATE_DEX, CONTROL_UR) = su; - B(STATE_DEX, CONTROL_UT) = 2.0 * cu; - B(STATE_DEY, CONTROL_UR) = -cu; - B(STATE_DEY, CONTROL_UT) = 2.0 * su; - B(STATE_DIX, CONTROL_UN) = cu; - B(STATE_DIY, CONTROL_UN) = su; - B *= factor; - - return xdot + B * control; - } - - VectorXdual2nd SpacecraftROE::getContinuousDynamicsAutodiff( - const VectorXdual2nd &state, const VectorXdual2nd &control, double time) const - { - VectorXdual2nd xdot = VectorXdual2nd::Zero(STATE_DIM); - - // Current argument of latitude - double nu = n_ref_ * time + u0_; - - // A*x portion: - autodiff::dual2nd da = state(STATE_DA); - xdot(STATE_DLAMBDA) = -1.5 * n_ref_ * da; - - // B*u portion: - autodiff::dual2nd ur = control(CONTROL_UR); - autodiff::dual2nd ut = control(CONTROL_UT); - autodiff::dual2nd un = control(CONTROL_UN); - - // Factor for scaling control - const double factor = 1.0 / (n_ref_ * a_ * mass_kg_); - - // Calculate su and cu based on initial argument of latitude: - double su = std::sin(nu); - double cu = std::cos(nu); - - // Return the control Jacobian matrix B - Eigen::MatrixXd B(STATE_DIM, CONTROL_DIM); - B.setZero(); - - B(STATE_DA, CONTROL_UT) = 2.0; - B(STATE_DLAMBDA, CONTROL_UR) = -2.0; - B(STATE_DEX, CONTROL_UR) = su; - B(STATE_DEX, CONTROL_UT) = 2.0 * cu; - B(STATE_DEY, CONTROL_UR) = -cu; - B(STATE_DEY, CONTROL_UT) = 2.0 * su; - B(STATE_DIX, CONTROL_UN) = cu; - B(STATE_DIY, CONTROL_UN) = su; - B *= factor; - - return xdot + B * control; - } - - //----------------------------------------------------------------------------- - Eigen::MatrixXd SpacecraftROE::getStateJacobian( - const Eigen::VectorXd &state, const Eigen::VectorXd &control, double time) const - { - - // Use autodiff to compute state Jacobian - VectorXdual2nd x = state; - VectorXdual2nd u = control; - - auto dynamics_wrt_x = [&](const VectorXdual2nd &x_ad) -> VectorXdual2nd - { - return this->getContinuousDynamicsAutodiff(x_ad, u, time); - }; - - return autodiff::jacobian(dynamics_wrt_x, wrt(x), at(x)); - } - - Eigen::MatrixXd SpacecraftROE::getControlJacobian( - const Eigen::VectorXd &state, const Eigen::VectorXd &control, double time) const - { - - // Use autodiff to compute control Jacobian - VectorXdual2nd x = state; - VectorXdual2nd u = control; - - auto dynamics_wrt_u = [&](const VectorXdual2nd &u_ad) -> VectorXdual2nd - { - return this->getContinuousDynamicsAutodiff(x, u_ad, time); - }; - - return autodiff::jacobian(dynamics_wrt_u, wrt(u), at(u)); - } - - //----------------------------------------------------------------------------- - std::vector SpacecraftROE::getStateHessian( - const Eigen::VectorXd & /*state*/, - const Eigen::VectorXd & /*control*/, double time) const - { - // For this linear(ish) model, second derivatives wrt state are zero. - auto hessians = makeZeroTensor(STATE_DIM, STATE_DIM, STATE_DIM); - return hessians; - } - - //----------------------------------------------------------------------------- - std::vector SpacecraftROE::getControlHessian( - const Eigen::VectorXd & /*state*/, - const Eigen::VectorXd & /*control*/, double time) const - { - // Similarly, second derivatives wrt control are zero for a linear system. - auto hessians = makeZeroTensor(STATE_DIM, CONTROL_DIM, CONTROL_DIM); - return hessians; - } - - //----------------------------------------------------------------------------- - Eigen::VectorXd SpacecraftROE::transformROEToHCW(const Eigen::VectorXd &roe, double t) const - { - // 1) Compute the angle for reference orbit at time t - double phi = n_ref_ * t + u0_; - double cn = std::cos(phi); - double sn = std::sin(phi); - - Eigen::Matrix T; - T.setZero(); - - // Fill row by row (0-based indexing). - // Position components - // Row 0: [1, 0, -cn, -sn, 0, 0] * a_ - T(0, 0) = 1.0; - T(0, 1) = 0.0; - T(0, 2) = -cn; - T(0, 3) = -sn; - T(0, 4) = 0.0; - T(0, 5) = 0.0; - - // Row 1: [0, 1, 2sn, -2cn, 0, 0] * a_ - T(1, 0) = 0.0; - T(1, 1) = 1.0; - T(1, 2) = 2.0 * sn; - T(1, 3) = -2.0 * cn; - T(1, 4) = 0.0; - T(1, 5) = 0.0; - - // Row 2: [0, 0, 0, 0, sn, -cn] * a_ - T(2, 0) = 0.0; - T(2, 1) = 0.0; - T(2, 2) = 0.0; - T(2, 3) = 0.0; - T(2, 4) = sn; - T(2, 5) = -cn; - - // Velocity components - // Row 3: [0, 0, n*sn, -n*cn, 0, 0] - T(3, 0) = 0.0; - T(3, 1) = 0.0; - T(3, 2) = n_ref_ * sn; - T(3, 3) = -n_ref_ * cn; - T(3, 4) = 0.0; - T(3, 5) = 0.0; - - // Row 4: [-3n/2, 0, 2n*cn, 2n*sn, 0, 0] - T(4, 0) = -1.5 * n_ref_; - T(4, 1) = 0.0; - T(4, 2) = 2.0 * n_ref_ * cn; - T(4, 3) = 2.0 * n_ref_ * sn; - T(4, 4) = 0.0; - T(4, 5) = 0.0; - - // Row 5: [0, 0, 0, 0, n*cn, n*sn] - T(5, 0) = 0.0; - T(5, 1) = 0.0; - T(5, 2) = 0.0; - T(5, 3) = 0.0; - T(5, 4) = n_ref_ * cn; - T(5, 5) = n_ref_ * sn; - - // Multiply entire matrix by 'a_' - T *= a_; - - // 3) Multiply T by the input ROE vector - Eigen::VectorXd hcw = T * roe; // hcw is [x, y, z, xdot, ydot, zdot] - - return hcw; - } - - Eigen::VectorXd SpacecraftROE::transformHCWToROE(const Eigen::VectorXd &hcw, double t) const - { - // 1) Compute the orbital phase for the reference orbit at time t - double phi = n_ref_ * t + u0_; - double cn = std::cos(phi); - double sn = std::sin(phi); - - // 2) Build the inverse transformation matrix Tinv (6x6) - // - // Tinv = [4 0 0 0 2/n 0 - // 0 1 0 -2/n 0 0 - // 3cn 0 0 sn/n 2cn/n 0 - // 3sn 0 0 -cn/n 2sn/n 0 - // 0 0 sn 0 0 cn/n - // 0 0 -cn 0 0 sn/n ] / a - // - - Eigen::Matrix Tinv; - Tinv.setZero(); - - // row 0 - Tinv(0, 0) = 4.0; - Tinv(0, 1) = 0.0; - Tinv(0, 2) = 0.0; - Tinv(0, 3) = 0.0; - Tinv(0, 4) = 2.0 / n_ref_; - Tinv(0, 5) = 0.0; - - // row 1 - Tinv(1, 0) = 0.0; - Tinv(1, 1) = 1.0; - Tinv(1, 2) = 0.0; - Tinv(1, 3) = -2.0 / n_ref_; - Tinv(1, 4) = 0.0; - Tinv(1, 5) = 0.0; - - // row 2 - Tinv(2, 0) = 3.0 * cn; - Tinv(2, 1) = 0.0; - Tinv(2, 2) = 0.0; - Tinv(2, 3) = sn / n_ref_; - Tinv(2, 4) = 2.0 * cn / n_ref_; - Tinv(2, 5) = 0.0; - - // row 3 - Tinv(3, 0) = 3.0 * sn; - Tinv(3, 1) = 0.0; - Tinv(3, 2) = 0.0; - Tinv(3, 3) = -cn / n_ref_; - Tinv(3, 4) = 2.0 * sn / n_ref_; - Tinv(3, 5) = 0.0; - - // row 4 - Tinv(4, 0) = 0.0; - Tinv(4, 1) = 0.0; - Tinv(4, 2) = sn; - Tinv(4, 3) = 0.0; - Tinv(4, 4) = 0.0; - Tinv(4, 5) = cn / n_ref_; - - // row 5 - Tinv(5, 0) = 0.0; - Tinv(5, 1) = 0.0; - Tinv(5, 2) = -cn; - Tinv(5, 3) = 0.0; - Tinv(5, 4) = 0.0; - Tinv(5, 5) = sn / n_ref_; - - // Divide entire matrix by a_ - Tinv /= a_; - - // 3) Multiply Tinv by the input HCW vector => QNS-ROE - Eigen::VectorXd roe_6dim = Tinv * hcw; - - return roe_6dim; - } - -} // namespace cddp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 68fb1003..265781ba 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -171,10 +171,6 @@ gtest_discover_tests(test_msipddp_solver) # target_link_libraries(test_ipddp_quadrotor gtest gmock gtest_main cddp) # gtest_discover_tests(test_ipddp_quadrotor) -# add_executable(test_spacecraft_roe dynamics_model/test_spacecraft_roe.cpp) -# target_link_libraries(test_spacecraft_roe gtest gmock gtest_main cddp) -# gtest_discover_tests(test_spacecraft_roe) - if (CDDP_CPP_CASADI) add_executable(test_casadi test_casadi_solver.cpp) target_link_libraries(test_casadi gtest gmock gtest_main cddp) diff --git a/tests/dynamics_model/test_spacecraft_roe.cpp b/tests/dynamics_model/test_spacecraft_roe.cpp deleted file mode 100644 index e724250d..00000000 --- a/tests/dynamics_model/test_spacecraft_roe.cpp +++ /dev/null @@ -1,248 +0,0 @@ -/** - * @file test_spacecraft_roe.cpp - * @brief GTest unit tests for the SpacecraftROE class (QNS-ROE dynamics). - * - * Copyright 2024 - * Licensed under the Apache License, Version 2.0 (the "License"); - * See the LICENSE file in the project root for more details. - */ - -#include -#include -#include -#include -#include - -#include "dynamics_model/spacecraft_roe.hpp" -#include "dynamics_model/spacecraft_linear.hpp" -using namespace cddp; - -TEST(TestSpacecraftROE, BasicQNSROEPropagation) -{ - // 1) Define problem parameters - double a = (6378.0 + 400.0) * 1e3; // semi-major axis [m] - double period = 2 * M_PI * sqrt(pow(a, 3) / 3.9860044e14); // orbital period [s] - - // 2) Create SpacecraftROE instance - double dt = 10.0; // time step - std::string integration_type = "euler"; - double u0 = 0.0; // initial argument of latitude - SpacecraftROE qnsRoeModel(dt, integration_type, a, u0); - - // 3) Create an initial relative state in the local RTN or Hill frame (6D) - Eigen::VectorXd x0_RV(6); - x0_RV << 495.08966689311296, -200.0, - 6.123233995736766e-15, -0.0, - -1.1230676194377847, -0.11314009527711179; - - // 4) Convert from R/V to QNSROE - Eigen::VectorXd x0_roe = qnsRoeModel.transformHCWToROE(x0_RV, 0.0); - - // 5) Integrate from t=0 to t=2*period - std::vector times; - std::vector states; - int num_steps = 2*period / dt; // 3 hours of simulation - - Eigen::VectorXd x_roe = x0_roe; - - for (int i = 0; i < num_steps; ++i) - { - double t = i * dt; - x_roe = qnsRoeModel.getDiscreteDynamics(x_roe, Eigen::VectorXd::Zero(SpacecraftROE::CONTROL_DIM), 0.0); - times.push_back(t); - states.push_back(x_roe); - } - - // 6) Print - std::cout << "[ INFO ] Initial QNS-ROE state:\n" - << x0_roe.transpose() * a << std::endl; - std::cout << "[ INFO ] Initial time: " << times.front() << " s" << std::endl; - std::cout << "[ INFO ] Final time: " << times.back() << " s" << std::endl; - std::cout << "[ INFO ] Final QNS-ROE state:\n" - << states.back().transpose() * a << std::endl; - - // 7) Basic sanity checks - - Eigen::VectorXd expected_x0_roe(6), expected_xf_roe(6); - expected_x0_roe << -4.910333106887314, -200.0, -500.0000000000003, 0.0, -100.0, -6.123233995736765e-15; - expected_xf_roe << -4.910333106887314, -107.44240150834467, -500.0000000000003, 0.0, -100.0, -6.123233995736765e-15; - Eigen::VectorXd obtained_x0_roe = states.front().head(6) * a; - Eigen::VectorXd obtained_xf_roe = states.back().head(6) * a; - ASSERT_EQ(states.front().size(), SpacecraftROE::STATE_DIM); - ASSERT_EQ(states.back().size(), SpacecraftROE::STATE_DIM); - ASSERT_NEAR(obtained_x0_roe.norm(), expected_x0_roe.norm(), 1e-1); - ASSERT_NEAR(obtained_xf_roe.norm(), expected_xf_roe.norm(), 1e-1); -} - -TEST(TestSpacecraftROE, RelativeTrajectory) -{ - // 1) Define problem parameters - double a = (6371.0 + 500.0) * 1e3; // semi-major axis [m] - double mean_motion = std::sqrt(3.986004418e14 / std::pow(a, 3)); // For 500km orbit - double period = 2 * M_PI / mean_motion; // orbital period [s] - - // 2) Create SpacecraftROE instance - double dt = 10.0; // time step - std::string integration_type = "euler"; - double u0 = 0.0; // initial argument of latitude - SpacecraftROE qnsRoeModel(dt, integration_type, a, u0); - - // 3) Initial HCW state - Eigen::VectorXd x0_hcw(6); - x0_hcw << -37.59664132226163, - 27.312455860666148, - 13.656227930333074, - 0.015161970413423813, - 0.08348413138390476, - 0.04174206569195238; - - // 4) Convert initial HCW to ROE - Eigen::VectorXd x0_roe = qnsRoeModel.transformHCWToROE(x0_hcw, 0.0); - - std::cout << "[ INFO ] Initial HCW state:\n" - << x0_hcw.transpose() << std::endl; - std::cout << "[ INFO ] Initial ROE state:\n" - << x0_roe.transpose() << std::endl; - - // 5) Simulate for a portion of an orbit - int num_steps = static_cast(3.0 * period / dt); // Simulate for 3 orbits - Eigen::VectorXd current_roe_state = x0_roe; - Eigen::VectorXd control = Eigen::VectorXd::Zero(SpacecraftROE::CONTROL_DIM); // No control - std::cout << "mean_motion: " << mean_motion << std::endl; - std::cout << "timestep: " << dt << std::endl; - std::cout << "period: " << period << std::endl; - std::cout << "num_steps: " << num_steps << std::endl; - std::vector roe_trajectory; - std::vector hcw_trajectory; - roe_trajectory.push_back(current_roe_state); - hcw_trajectory.push_back(qnsRoeModel.transformROEToHCW(current_roe_state.head(6), 0.0)); - - for (int i = 0; i < num_steps; ++i) { - double t = i * dt; - current_roe_state = qnsRoeModel.getDiscreteDynamics(current_roe_state, control, t); - roe_trajectory.push_back(current_roe_state); - hcw_trajectory.push_back(qnsRoeModel.transformROEToHCW(current_roe_state.head(6), t)); - } - - // Print the final HCW state - std::cout << "[ INFO ] Final HCW state:\n" - << hcw_trajectory.back().transpose() << std::endl; - std::cout << "[ INFO ] Final ROE state:\n" - << roe_trajectory.back().transpose() * a<< std::endl; - - // 6) Basic Assertions - ASSERT_EQ(roe_trajectory.size(), num_steps + 1); - ASSERT_EQ(hcw_trajectory.size(), num_steps + 1); - - // Check that the initial HCW state, when converted to ROE and back to HCW, is consistent. - Eigen::VectorXd x0_hcw_reconstructed = qnsRoeModel.transformROEToHCW(x0_roe.head(6), 0.0); - for (int i = 0; i < 6; ++i) { - ASSERT_NEAR(x0_hcw(i), x0_hcw_reconstructed(i), 1e-9); - } - - ASSERT_GT(hcw_trajectory.back().norm(), 1e-3); - -} - -TEST(TestSpacecraftROE, JacobianBasedPropagation) -{ - // 1) Define problem parameters - double a_param = (6378.0 + 400.0) * 1e3; // semi-major axis [m] - double dt = 1.0; // time step [s] - std::string integration_type = "euler"; - double u0_model_phase = 0.1; // initial argument of latitude for the model [rad] - double mass_kg = 1.0; // mass of spacecraft [kg] - - // 2) Create SpacecraftROE instance - cddp::SpacecraftROE qnsRoeModel(dt, integration_type, a_param, u0_model_phase, mass_kg); - ASSERT_EQ(qnsRoeModel.getStateDim(), cddp::SpacecraftROE::STATE_DIM); - ASSERT_EQ(qnsRoeModel.getControlDim(), cddp::SpacecraftROE::CONTROL_DIM); - - // 3) Define initial state (7D ROE state) - Eigen::VectorXd x0(cddp::SpacecraftROE::STATE_DIM); - x0.setZero(); - // Dimensionless ROE elements + initial true anomaly - x0(cddp::SpacecraftROE::STATE_DA) = 100.0 / a_param; - x0(cddp::SpacecraftROE::STATE_DLAMBDA) = 0.0001; // rad - x0(cddp::SpacecraftROE::STATE_DEX) = 50.0 / a_param; - x0(cddp::SpacecraftROE::STATE_DEY) = -50.0 / a_param; - x0(cddp::SpacecraftROE::STATE_DIX) = 20.0 / a_param; - x0(cddp::SpacecraftROE::STATE_DIY) = -20.0 / a_param; - - // --- Test with Zero Control --- - Eigen::VectorXd u_zero_control(cddp::SpacecraftROE::CONTROL_DIM); - u_zero_control.setZero(); - - - // 6) Simulate trajectories - int num_steps = 20; - std::vector x_trajectory_dyn_zero_u; - std::vector x_trajectory_lin_zero_u; - - Eigen::VectorXd x_curr_dyn_zero_u = x0; - Eigen::VectorXd x_curr_lin_zero_u = x0; - - x_trajectory_dyn_zero_u.push_back(x_curr_dyn_zero_u); - x_trajectory_lin_zero_u.push_back(x_curr_lin_zero_u); - - for (int k = 0; k < num_steps; ++k) - { - x_curr_dyn_zero_u = qnsRoeModel.getDiscreteDynamics(x_curr_dyn_zero_u, u_zero_control, k * dt); - x_trajectory_dyn_zero_u.push_back(x_curr_dyn_zero_u); - - Eigen::MatrixXd A = qnsRoeModel.getStateJacobian(x_curr_lin_zero_u, u_zero_control, k * dt); - Eigen::MatrixXd B = qnsRoeModel.getControlJacobian(x_curr_lin_zero_u, u_zero_control, k * dt); - x_curr_lin_zero_u = x_curr_lin_zero_u + dt * (A * x_curr_lin_zero_u + B * u_zero_control); - x_trajectory_lin_zero_u.push_back(x_curr_lin_zero_u); - } - - ASSERT_EQ(x_trajectory_dyn_zero_u.size(), num_steps + 1); - ASSERT_EQ(x_trajectory_lin_zero_u.size(), num_steps + 1); - - for (int j = 0; j < cddp::SpacecraftROE::STATE_DIM; ++j) { - ASSERT_NEAR(x_trajectory_dyn_zero_u[1](j), x_trajectory_lin_zero_u[1](j), 1e-2); - } - Eigen::VectorXd diff_final_zero_u = x_trajectory_dyn_zero_u.back() - x_trajectory_lin_zero_u.back(); - EXPECT_LT(diff_final_zero_u.norm(), 1e-2); - - - // --- Test with Non-Zero Control --- - Eigen::VectorXd u_nonzero_control(cddp::SpacecraftROE::CONTROL_DIM); - u_nonzero_control << 1e-5, -2e-5, 1.5e-5; // Small accelerations in m/s^2 - - - std::vector x_trajectory_dyn_nonzero_u; - std::vector x_trajectory_lin_nonzero_u; - - Eigen::VectorXd x_curr_dyn_nonzero_u = x0; - Eigen::VectorXd x_curr_lin_nonzero_u = x0; - - x_trajectory_dyn_nonzero_u.push_back(x_curr_dyn_nonzero_u); - x_trajectory_lin_nonzero_u.push_back(x_curr_lin_nonzero_u); - - for (int k = 0; k < num_steps; ++k) - { - x_curr_dyn_nonzero_u = qnsRoeModel.getDiscreteDynamics(x_curr_dyn_nonzero_u, u_nonzero_control, k * dt); - x_trajectory_dyn_nonzero_u.push_back(x_curr_dyn_nonzero_u); - - Eigen::MatrixXd A = qnsRoeModel.getStateJacobian(x_curr_lin_nonzero_u, u_nonzero_control, k * dt); - Eigen::MatrixXd B = qnsRoeModel.getControlJacobian(x_curr_lin_nonzero_u, u_nonzero_control, k * dt); - x_curr_lin_nonzero_u = x_curr_lin_nonzero_u + dt * (A * x_curr_lin_nonzero_u + B * u_nonzero_control); - x_trajectory_lin_nonzero_u.push_back(x_curr_lin_nonzero_u); - } - - ASSERT_EQ(x_trajectory_dyn_nonzero_u.size(), num_steps + 1); - ASSERT_EQ(x_trajectory_lin_nonzero_u.size(), num_steps + 1); - - for (int j = 0; j < cddp::SpacecraftROE::STATE_DIM; ++j) { - ASSERT_NEAR(x_trajectory_dyn_nonzero_u[1](j), x_trajectory_lin_nonzero_u[1](j), 1e-12); - } - Eigen::VectorXd diff_final_nonzero_u = x_trajectory_dyn_nonzero_u.back() - x_trajectory_lin_nonzero_u.back(); - EXPECT_LT(diff_final_nonzero_u.norm(), 1e-4 * num_steps); -} - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} From 394f04a8812f1e97e801cee38e7f46386e38ab0a Mon Sep 17 00:00:00 2001 From: Tomo Sasaki Date: Thu, 2 Apr 2026 17:48:15 -0400 Subject: [PATCH 3/6] Add GitHub templates and contribution docs Add standard issue and pull request templates, contributor guidance, and lightweight community policies. Also move the PR template to GitHub's standard location and link the new docs from the README. --- .github/ISSUE_TEMPLATE/bug_report.yml | 55 +++++++++++++++++ .github/ISSUE_TEMPLATE/config.yml | 5 ++ .github/ISSUE_TEMPLATE/feature_request.yml | 36 +++++++++++ .github/PULL_REQUEST_TEMPLATE.md | 16 +++++ .../PR_TEMPLATE/pull_request_template.md | 14 ----- CODE_OF_CONDUCT.md | 27 +++++++++ CONTRIBUTING.md | 59 +++++++++++++++++++ README.md | 16 +++-- SECURITY.md | 26 ++++++++ 9 files changed, 231 insertions(+), 23 deletions(-) create mode 100644 .github/ISSUE_TEMPLATE/bug_report.yml create mode 100644 .github/ISSUE_TEMPLATE/config.yml create mode 100644 .github/ISSUE_TEMPLATE/feature_request.yml create mode 100644 .github/PULL_REQUEST_TEMPLATE.md delete mode 100644 .github/workflows/PR_TEMPLATE/pull_request_template.md create mode 100644 CODE_OF_CONDUCT.md create mode 100644 CONTRIBUTING.md create mode 100644 SECURITY.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml new file mode 100644 index 00000000..f68b3b9d --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -0,0 +1,55 @@ +name: Bug report +description: Report a reproducible defect in the solver, bindings, build, or docs +title: "[bug] " +labels: + - bug +body: + - type: markdown + attributes: + value: | + Thanks for taking the time to report a problem. + + Please include a minimal reproduction and the exact commands you ran. + - type: textarea + id: summary + attributes: + label: Summary + description: What happened, and what did you expect to happen instead? + placeholder: A concise description of the bug and expected behavior. + validations: + required: true + - type: textarea + id: reproduction + attributes: + label: Reproduction + description: Provide the smallest reproduction you can, including commands and inputs. + placeholder: | + 1. Configure with ... + 2. Run ... + 3. Observe ... + validations: + required: true + - type: textarea + id: logs + attributes: + label: Logs and output + description: Paste the relevant error message, stack trace, or failing test output. + render: text + - type: textarea + id: environment + attributes: + label: Environment + description: Share the platform and toolchain details relevant to the bug. + placeholder: | + OS: + Compiler: + CMake: + Python: + Build flags: + validations: + required: true + - type: textarea + id: context + attributes: + label: Additional context + description: Add anything else that might help debug the issue. diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 00000000..e504119a --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,5 @@ +blank_issues_enabled: true +contact_links: + - name: Security policy + url: https://github.com/astomodynamics/cddp-cpp/blob/master/SECURITY.md + about: Read the security reporting guidance before disclosing a vulnerability. diff --git a/.github/ISSUE_TEMPLATE/feature_request.yml b/.github/ISSUE_TEMPLATE/feature_request.yml new file mode 100644 index 00000000..b59af5ac --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature_request.yml @@ -0,0 +1,36 @@ +name: Feature request +description: Propose an improvement to the solver, examples, bindings, or docs +title: "[feature] " +labels: + - enhancement +body: + - type: markdown + attributes: + value: | + Please describe the problem first, then the change you want. + - type: textarea + id: problem + attributes: + label: Problem or use case + description: What limitation, missing capability, or workflow pain does this address? + placeholder: I am trying to ... + validations: + required: true + - type: textarea + id: proposal + attributes: + label: Proposed change + description: Describe the API, behavior, or workflow you would like to see. + placeholder: Add support for ... + validations: + required: true + - type: textarea + id: alternatives + attributes: + label: Alternatives considered + description: What workarounds or alternative designs have you considered? + - type: textarea + id: context + attributes: + label: Additional context + description: Benchmarks, references, examples, or prior art that help clarify the request. diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md new file mode 100644 index 00000000..fbfb40b7 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -0,0 +1,16 @@ +## Summary +- Describe the change and why it is needed. + +## Changes +- List the concrete code, API, testing, or documentation updates. + +## Validation +- [ ] `...` + +## Checklist +- [ ] I ran the relevant tests or explained why they were not run. +- [ ] I updated documentation when behavior or public interfaces changed. +- [ ] I kept the change focused and avoided unrelated cleanup. + +## Notes +- Add reviewer context only when it is needed. diff --git a/.github/workflows/PR_TEMPLATE/pull_request_template.md b/.github/workflows/PR_TEMPLATE/pull_request_template.md deleted file mode 100644 index 9ea67c13..00000000 --- a/.github/workflows/PR_TEMPLATE/pull_request_template.md +++ /dev/null @@ -1,14 +0,0 @@ -## Summary - -- - -## Changes - -- - -## Test Plan - -- [ ] - -## Notes - diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md new file mode 100644 index 00000000..a86031d3 --- /dev/null +++ b/CODE_OF_CONDUCT.md @@ -0,0 +1,27 @@ +# Code of Conduct + +## Our standard + +This project expects respectful, technical, and constructive collaboration. + +Examples of expected behavior: + +- focusing feedback on the code, design, and evidence +- being clear, patient, and specific in reviews and discussions +- assuming good intent while still challenging weak technical arguments +- helping other contributors understand project constraints and expectations + +Examples of unacceptable behavior: + +- personal attacks, harassment, or discriminatory language +- hostile or deliberately dismissive review behavior +- repeated bad-faith argumentation or thread derailment +- publishing private or sensitive information without permission + +## Enforcement + +Project maintainers may remove, edit, or reject comments, issues, pull requests, code, and other contributions that violate this code of conduct. + +## Reporting + +If you experience or witness unacceptable behavior, contact the maintainers through the repository owners' preferred contact path. For security-sensitive matters, use the process described in [SECURITY.md](SECURITY.md). diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000..8099370e --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,59 @@ +# Contributing + +Thanks for contributing to `cddp-cpp`. + +## Scope + +This project contains: + +- the core C++ trajectory optimization library +- a curated set of C++ reference examples +- optional Python bindings and portfolio demos + +Keep changes focused. Avoid mixing bug fixes, refactors, formatting churn, and documentation cleanup in one pull request unless they are tightly coupled. + +## Development setup + +### C++ build + +```bash +cmake -S . -B build +cmake --build build -j4 +ctest --test-dir build --output-on-failure +``` + +### C++ examples + +```bash +cmake -S . -B build -DCDDP_CPP_BUILD_EXAMPLES=ON +cmake --build build --target cddp_pendulum cddp_cartpole cddp_unicycle cddp_quadrotor_point cddp_manipulator -j4 +``` + +### Python bindings + +This repository uses `uv` for Python environment management. + +```bash +uv venv .venv --python 3.12 +uv sync +source .venv/bin/activate +pytest -q python/tests +``` + +## Pull requests + +Before opening a pull request: + +1. Make the smallest reasonable change for the problem you are solving. +2. Add or update tests when behavior changes. +3. Run the relevant build and test commands for the area you touched. +4. Update documentation when user-facing behavior, examples, or public APIs change. +5. Write a clear commit message and PR description. + +PRs that include a minimal reproduction, exact validation commands, and a concise explanation of the design tradeoffs are much easier to review. + +## Issues + +- Use bug reports for reproducible defects. +- Use feature requests for API additions, solver improvements, or workflow changes. +- For sensitive security issues, follow [SECURITY.md](SECURITY.md) instead of opening a detailed public issue. diff --git a/README.md b/README.md index 95fff35b..50b5091a 100644 --- a/README.md +++ b/README.md @@ -125,15 +125,13 @@ This project is licensed under the Apache License 2.0 - see the [LICENSE](LICENS ## Collaboration Contributions are welcome. -If you'd like to contribute: -1. Fork the repository. -2. Create a branch for your change, for example `feature/your-feature-name` or `fix/your-bug-fix`. -3. Make the change and add or update tests as needed. -4. Commit with a descriptive message. -5. Push the branch. -6. Open a pull request against `master`. - -Use GitHub issues for bug reports, questions, or proposed changes. +Start with: + +- [CONTRIBUTING.md](CONTRIBUTING.md) for setup, validation, and PR expectations +- [CODE_OF_CONDUCT.md](CODE_OF_CONDUCT.md) for community standards +- [SECURITY.md](SECURITY.md) for vulnerability reporting guidance + +Use GitHub issues for bug reports and feature requests, and open pull requests against `master`. ## TODO * improve python binding ergonomics diff --git a/SECURITY.md b/SECURITY.md new file mode 100644 index 00000000..c47348ba --- /dev/null +++ b/SECURITY.md @@ -0,0 +1,26 @@ +# Security Policy + +## Supported versions + +Security fixes are best-effort and are typically made against the current `master` branch. + +## Reporting a vulnerability + +Please do not publish vulnerability details in a public issue. + +Preferred process: + +1. Use GitHub's private vulnerability reporting flow for this repository if it is enabled. +2. If private reporting is not available, open a minimal public issue requesting a secure reporting path, without including exploit details, secrets, or full reproduction steps. + +When reporting an issue, include: + +- affected version or commit +- impact and attack surface +- reproduction steps +- proof-of-concept details only through a private channel +- any suggested mitigation or patch direction + +## Disclosure + +Please allow maintainers reasonable time to investigate and prepare a fix before public disclosure. From 4e591eb0a10f221cf48c10053fb807182f637cc9 Mon Sep 17 00:00:00 2001 From: Tomo Sasaki Date: Thu, 2 Apr 2026 17:51:05 -0400 Subject: [PATCH 4/6] Remove tracked result artifacts Drop generated images and GIFs from the repository and ignore the results directory going forward. This keeps the repo focused on source, tests, and doc assets that are still referenced. --- .gitignore | 2 +- results/acrobot/acrobot.gif | Bin 254215 -> 0 bytes results/animations/car_parking.gif | Bin 2653276 -> 0 bytes results/animations/car_parking_acado.gif | Bin 2639949 -> 0 bytes results/animations/car_parking_ipopt.gif | Bin 2682497 -> 0 bytes .../quadrotor_computation_time_comparison.png | Bin 18582 -> 0 bytes .../quadrotor_lemniscate_3d_comparison.png | Bin 368319 -> 0 bytes ...cycle_baseline_trajectories_comparison.png | Bin 83492 -> 0 bytes .../unicycle_computation_time_comparison.png | Bin 18843 -> 0 bytes results/simulations/hcw_mpc_cddp_controls.png | Bin 75012 -> 0 bytes .../simulations/hcw_mpc_cddp_trajectories.png | Bin 68156 -> 0 bytes .../hcw_mpc_cddp_xaxis_trajectories.png | Bin 68570 -> 0 bytes .../hcw_mpc_cddp_yaxis_trajectories.png | Bin 73030 -> 0 bytes results/tests/bicycle.gif | Bin 79640 -> 0 bytes results/tests/bicycle_cddp_results.png | Bin 63833 -> 0 bytes results/tests/car_parking.gif | Bin 508426 -> 0 bytes results/tests/car_parking_ipddp.gif | Bin 509828 -> 0 bytes results/tests/car_parking_ipopt.gif | Bin 504979 -> 0 bytes results/tests/cartpole.gif | Bin 112438 -> 0 bytes results/tests/cartpole_control_inputs.png | Bin 20930 -> 0 bytes results/tests/cartpole_ipopt.gif | Bin 112827 -> 0 bytes results/tests/cartpole_results.png | Bin 60887 -> 0 bytes results/tests/docking_trajectory.png | Bin 106024 -> 0 bytes results/tests/docking_trajectory_xy.png | Bin 23537 -> 0 bytes results/tests/dubincs_car_cddp_test.png | Bin 29856 -> 0 bytes results/tests/dubincs_car_clcddp_test.png | Bin 30096 -> 0 bytes results/tests/dubincs_car_ipddp_test.png | Bin 30885 -> 0 bytes results/tests/dubincs_car_logcddp_test.png | Bin 31151 -> 0 bytes results/tests/dubins_car.gif | Bin 180689 -> 0 bytes results/tests/dubins_car_sqp_test.png | Bin 37130 -> 0 bytes results/tests/forklift_parking_ipddp.gif | Bin 553543 -> 0 bytes results/tests/hcw_control_history.png | Bin 25177 -> 0 bytes results/tests/hcw_control_inputs.png | Bin 32452 -> 0 bytes results/tests/hcw_results.png | Bin 67058 -> 0 bytes results/tests/hcw_state_history.png | Bin 36431 -> 0 bytes results/tests/lti_states.png | Bin 55909 -> 0 bytes results/tests/manipulator.gif | Bin 965154 -> 0 bytes results/tests/manipulator_cddp_results.png | Bin 47562 -> 0 bytes results/tests/manipulator_pose.png | Bin 52146 -> 0 bytes results/tests/pendulum.gif | Bin 169189 -> 0 bytes results/tests/pendulum_cddp_test.png | Bin 58186 -> 0 bytes results/tests/quadrotor_circle.gif | Bin 493778 -> 0 bytes results/tests/quadrotor_circle_3d.png | Bin 54442 -> 0 bytes results/tests/quadrotor_circle_history.png | Bin 97450 -> 0 bytes results/tests/quadrotor_circle_states.png | Bin 96625 -> 0 bytes results/tests/quadrotor_discrete_dynamics.png | Bin 34198 -> 0 bytes .../quadrotor_figure_eight_horizontal.gif | Bin 491451 -> 0 bytes .../quadrotor_figure_eight_horizontal_3d.png | Bin 63859 -> 0 bytes ...drotor_figure_eight_horizontal_safe_3d.png | Bin 76762 -> 0 bytes ...or_figure_eight_horizontal_safe_states.png | Bin 130650 -> 0 bytes ...adrotor_figure_eight_horizontal_states.png | Bin 105394 -> 0 bytes .../tests/quadrotor_figure_eight_vertical.gif | Bin 536671 -> 0 bytes .../quadrotor_figure_eight_vertical_3d.png | Bin 52333 -> 0 bytes ...quadrotor_figure_eight_vertical_states.png | Bin 101866 -> 0 bytes results/tests/quadrotor_figure_eight_xy.png | Bin 28605 -> 0 bytes results/tests/quadrotor_figure_eight_xz.png | Bin 29008 -> 0 bytes results/tests/quadrotor_point.gif | Bin 248708 -> 0 bytes results/tests/quadrotor_point_3d.png | Bin 49776 -> 0 bytes results/tests/quadrotor_point_history.png | Bin 85965 -> 0 bytes results/tests/quadrotor_point_states.png | Bin 78323 -> 0 bytes results/tests/trajectory_comparison_ipddp.png | Bin 55136 -> 0 bytes .../trajectory_comparison_ipddp_matplot.png | Bin 71924 -> 0 bytes .../tests/trajectory_comparison_ipddp_v2.png | Bin 32302 -> 0 bytes ...trajectory_comparison_ipddp_v2_matplot.png | Bin 28584 -> 0 bytes ...ory_comparison_ipddp_v3_linear_matplot.png | Bin 30063 -> 0 bytes .../tests/trajectory_comparison_matplot.png | Bin 29816 -> 0 bytes results/tests/unicycle.gif | Bin 83899 -> 0 bytes results/tests/unicycle_ascddp_test.png | Bin 28700 -> 0 bytes results/tests/unicycle_cddp_results.png | Bin 53535 -> 0 bytes results/tests/unicycle_ipopt.gif | Bin 84089 -> 0 bytes results/tests/unicycle_ipopt_results.png | Bin 51180 -> 0 bytes results/tests/unicycle_safe.gif | Bin 209935 -> 0 bytes .../unicycle_six_trajectories_comparison.png | Bin 60156 -> 0 bytes .../tests/unicycle_trajectory_comparison.png | Bin 45082 -> 0 bytes 74 files changed, 1 insertion(+), 1 deletion(-) delete mode 100644 results/acrobot/acrobot.gif delete mode 100644 results/animations/car_parking.gif delete mode 100644 results/animations/car_parking_acado.gif delete mode 100644 results/animations/car_parking_ipopt.gif delete mode 100644 results/benchmark/quadrotor_computation_time_comparison.png delete mode 100644 results/benchmark/quadrotor_lemniscate_3d_comparison.png delete mode 100644 results/benchmark/unicycle_baseline_trajectories_comparison.png delete mode 100644 results/benchmark/unicycle_computation_time_comparison.png delete mode 100644 results/simulations/hcw_mpc_cddp_controls.png delete mode 100644 results/simulations/hcw_mpc_cddp_trajectories.png delete mode 100644 results/simulations/hcw_mpc_cddp_xaxis_trajectories.png delete mode 100644 results/simulations/hcw_mpc_cddp_yaxis_trajectories.png delete mode 100644 results/tests/bicycle.gif delete mode 100644 results/tests/bicycle_cddp_results.png delete mode 100644 results/tests/car_parking.gif delete mode 100644 results/tests/car_parking_ipddp.gif delete mode 100644 results/tests/car_parking_ipopt.gif delete mode 100644 results/tests/cartpole.gif delete mode 100644 results/tests/cartpole_control_inputs.png delete mode 100644 results/tests/cartpole_ipopt.gif delete mode 100644 results/tests/cartpole_results.png delete mode 100644 results/tests/docking_trajectory.png delete mode 100644 results/tests/docking_trajectory_xy.png delete mode 100644 results/tests/dubincs_car_cddp_test.png delete mode 100644 results/tests/dubincs_car_clcddp_test.png delete mode 100644 results/tests/dubincs_car_ipddp_test.png delete mode 100644 results/tests/dubincs_car_logcddp_test.png delete mode 100644 results/tests/dubins_car.gif delete mode 100644 results/tests/dubins_car_sqp_test.png delete mode 100644 results/tests/forklift_parking_ipddp.gif delete mode 100644 results/tests/hcw_control_history.png delete mode 100644 results/tests/hcw_control_inputs.png delete mode 100644 results/tests/hcw_results.png delete mode 100644 results/tests/hcw_state_history.png delete mode 100644 results/tests/lti_states.png delete mode 100644 results/tests/manipulator.gif delete mode 100644 results/tests/manipulator_cddp_results.png delete mode 100644 results/tests/manipulator_pose.png delete mode 100644 results/tests/pendulum.gif delete mode 100644 results/tests/pendulum_cddp_test.png delete mode 100644 results/tests/quadrotor_circle.gif delete mode 100644 results/tests/quadrotor_circle_3d.png delete mode 100644 results/tests/quadrotor_circle_history.png delete mode 100644 results/tests/quadrotor_circle_states.png delete mode 100644 results/tests/quadrotor_discrete_dynamics.png delete mode 100644 results/tests/quadrotor_figure_eight_horizontal.gif delete mode 100644 results/tests/quadrotor_figure_eight_horizontal_3d.png delete mode 100644 results/tests/quadrotor_figure_eight_horizontal_safe_3d.png delete mode 100644 results/tests/quadrotor_figure_eight_horizontal_safe_states.png delete mode 100644 results/tests/quadrotor_figure_eight_horizontal_states.png delete mode 100644 results/tests/quadrotor_figure_eight_vertical.gif delete mode 100644 results/tests/quadrotor_figure_eight_vertical_3d.png delete mode 100644 results/tests/quadrotor_figure_eight_vertical_states.png delete mode 100644 results/tests/quadrotor_figure_eight_xy.png delete mode 100644 results/tests/quadrotor_figure_eight_xz.png delete mode 100644 results/tests/quadrotor_point.gif delete mode 100644 results/tests/quadrotor_point_3d.png delete mode 100644 results/tests/quadrotor_point_history.png delete mode 100644 results/tests/quadrotor_point_states.png delete mode 100644 results/tests/trajectory_comparison_ipddp.png delete mode 100644 results/tests/trajectory_comparison_ipddp_matplot.png delete mode 100644 results/tests/trajectory_comparison_ipddp_v2.png delete mode 100644 results/tests/trajectory_comparison_ipddp_v2_matplot.png delete mode 100644 results/tests/trajectory_comparison_ipddp_v3_linear_matplot.png delete mode 100644 results/tests/trajectory_comparison_matplot.png delete mode 100644 results/tests/unicycle.gif delete mode 100644 results/tests/unicycle_ascddp_test.png delete mode 100644 results/tests/unicycle_cddp_results.png delete mode 100644 results/tests/unicycle_ipopt.gif delete mode 100644 results/tests/unicycle_ipopt_results.png delete mode 100644 results/tests/unicycle_safe.gif delete mode 100644 results/tests/unicycle_six_trajectories_comparison.png delete mode 100644 results/tests/unicycle_trajectory_comparison.png diff --git a/.gitignore b/.gitignore index a5716e3c..243ac7e0 100644 --- a/.gitignore +++ b/.gitignore @@ -6,7 +6,7 @@ build/ # Output plots/ -results/frames/ +results/ # Models models/ diff --git a/results/acrobot/acrobot.gif b/results/acrobot/acrobot.gif deleted file mode 100644 index aea32c7f9986212da0e311fe5f585cb7adcc9f08..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 254215 zcmd?w^-~-{|1bK%f@?^EJHa(1I3bD?qBw*Y?(T~(?(Qy&JG+a!yDsjwi#sfb=RV(a z>eT%YZr%Q|XFgpsJyl)P?|F@!!bdT2112mctn>H4Ln9y{U;u!p06qZFQc_aV($ccC zv-9xqh=_>1e*M}60IdIWmKFe*0f5!Jckh&xl)irbs-vUx=g%KgQ&T%TJ6Bg%1OVIv zz&U`ACLmYklV~zO=8+e#~fcc(K^~1NX@7}0=5at)e!g%Q7 z{m-rZ=P?1eXwZ9aA74NJ0B~SXa7buactm7WbWChqd_rPUa!P7idPZhec1~_yenDXo zq`0KCth}PKs=B7OuD$^ZgEuxcx3spkcXW1j_w@Gl4-5_skBp9uPfSit&&8u#J%Ef= zF-5*2t23DDg~@zRMRs>M)4L!#h02`XXwI)iI=z*-{qcgo`%)CD@&=Q|YvNEQ$#_@$vQOhv&0ur{%SgI=+r$pCEn z^Ox^+aCFpUW29w&rjU5gWXNJj{kmcWgn2g;!=$D}|3q;(T!L|KKX05KhUQ4K*f_(b>@j<;G11GDF&K0P7;Q1s0ZqJ(m~h6&Sf*7rWFao=220;XsmQI* zo)}nv#rz3WR;5XFlme&R{~+~RvK^!;IAJaJ0KJGLLC0=NP`5imUDCmdz|ksUz8alIxW0J?mV$i~Pkh54qW{QU_ry$(LFtBkl6^ zS@SY?hb)`!Q~|`~lrA4LE3GUO5v85P(Q+kT@U}KsQ4Md@+esR1Adzw#Zy+LuVg)J& zrFa1deUtdVbq2y*CNmSI_u7Z3pBUI3808|H(vJ+FXxoM&R-@WIk>}dDH z9nQV5gh@Z%kn&kPo|Ljfii4aOAL{Yhhx$UeD!vK=CS4`t=ndd`{;%IGBcT9lN^pQ8JkE9(U;2ts&X|o9&A~B12E?Yp-^mT)=9vcB$yRdMl)AIf`NGJUQfhyO z1a^N}e!RsZo?)I}a=x;3dY4@!=e+op3CcKwCN$&@z?+Aod+L*-+KW?-)NC>cpZ5 zDVkuZy&lE_6YRtQxzVJ_mltJk<+}lrJ!-Ee>Y+n1NXk0)Cy6T7)PEHxDa#dqtXW3d z8C{OkvPU-f`Z=%(667)Lf3f`g`7IAN(u4VRcOdwe9TzPX6Y!YQR|eVfNzb3e^bdBz zORf<`AOEcgl1-Cf6L?4Dg}Iyq`q{Tdo$^#R zQ|u*3RcLKI^PDn8)-U9)CpV9}4dzR6OTGssV3h(@>K zRAtgxv5^WyYr1c$7J61<6$;VWQk;g)os~KbLi8^Brkk$ML@3liKXH|2+Gx(p!79bS zp7qakNt{RomEuavu1Y%8_Uo0jv{sR!+t1h$BOy5 zZ*@;c|H?T`R_LNs)t^o4DmWRAF4)Cf&~1GFsXE;~eW&Xu;bnDfDmvWrkKRw<`e<#+dNxvvPH&jdiut#hHsaC`zH*f--*q%- z8M{7$KcpCF*@>}nsCI(ODppOZXFA!_J_NlMUi%79pb?Gx7-moRTXUkG^)-KIShmo* zA?0k3bl8Uo(aQDDbhFf-9(|5lApa{TBF?H#@*y_9V&jk9Z2wn}4{-v*o1fgMsSRI! zOq!(orykS5Vu|WV3KrTjn3x?hxA>64QMsiuuSws^O1Qah8CgjttKVqr2Vg z(Xc!V4`&Qx#n;f0%?)IZaj@~3-t~A?oO#aCXJg%%xrtQO4_S9Yi$0I; z`cFV9%DO(3npc?W4PR5%>B*OKjGFGFyP!4QU1bG)sb*;OTvN}2NKtZ$wu!prgfMk2 zTaXH&#WU0_dh)bV+#KoTbc5K4tEe_ewb=5eZCM>UFNoyZbAUoGgE2N@goRk)1L6VrO6q|K+FH!$MFVt7(Tf}(YqgI@5 z92U=+8iL+1*hIH?tcI#x^<4}e+4ItDVzpke{0SpSOK#hGZRpHl$3T|Ffw}#*w81g9 zi6HyFeJ4Oxf-8rgph#VJI|bzOy1GfMI67fxyS|~@o!H^Zc&$70T9{yX@ zVYc7Eo-bYcvCfj*BJO8LwNv!MV^7@M1)+)yH%bp}pKj~bC*hXPWp_v}{acZaG)o7V z^s#L|tUor`2Jw$!E?&KMt(V@#&{JkUR9$k1`QU22UGhxe0KTKSbUh|1hFXY|inMQb zov}q9osu*i3ZqDD3mf$ww@~M^M8@V#Y`2(nr`xSXRvUy@oFfr|(BR-+(%j zcK{YX@ZMh#G-YT(+4J`{9z-sP@%tU#mjt)zSAO4&yy%6n$y=nhalLTx{JZ{w(#n0e zBiN+Xp2@0d>w?`JoC5l~^`4Vs;f@5jgQdLH0-VLbzGALc({7C2{!Bmo`UKsJ)ZO(G z{7sxJJ1<-z&jJnPK~V((V0nk6djE91pa6OIIMG1bXF)MyLE#!f37kPC+d)}%K|=vS z`9?uCJ%Kr5!L>%VA$b3O6;OB^ft@%*+6xTo<@6ezh*0_X{RKwqoO(tHfn^Cn<9LJ? z8l$S_{WC|+=f26&DtxXUqcK|b^VFTBnw^fV%LJ|XO~ zKJ3IPWcz6tyZ{`08H}5dY76fLw9IfWDT)Hp&cFro__*~1wf zEgEL_Jc83JYC9pCt1!xCGm02Dreh=|VL7JsM;Ml~+pbg0cjH)mu3*C6NLH>W1CH2t z#?d^zvAPOzML(mCWn*v(qs;0`Xq zzxd~w=s0Gsc-x)WqRn`6j)XDX1TTeXUV{YJoj7yN7|X&~>%w^F-o(`2usF_0^@g~3 zg``Ei_+@ZHMt%|`FgPhODNQr3f-5=WD)O6iM1p2g0DfdIA55S)|HmKoOTGLrw1lC;HN5fB~WiA%*v%N?j+3?2CpZk;09&X;HM1~ zrmu0O6Szc<%|>Gqcsw!5ToO;*c20%vq}))amWih>1ZLtFId3XZTqdR=sME;^9+o?C zn+R$mHDml2L8d>Q<5y-guXZv>xigs+Gg&39gt)UswGwEdY3y35JV`MfS5eRUegZTZ z)C8g8ed!F`DHbJ@klK+M~$C{fWJt!wXs3`v0GT=HsIp|;TE@7BP zVe(Z`f(yh}(bRd)wn-vS0-Bvz2r2J{uoV^eD;DOO6b=yNy7uLJO2l^16rsDcilY^a z`ni$}lS*a?N|}O+S!f_d5+zi%MV#l5=Sf9lyQS$Pg{YAtJDQRMlhRdDNN8Z`Y(!z? zav9-t0cT&SqGCa|Nx8B_W@lg-Zco`Ace%}Vfe%e7BBj<0#hOWFZ&2k~QRR+SiNQ`Ku2O|CVIh5f+5JvA zZ(aqh=`Si;yBftXrT%J(;OuGc0s+D*8P_<4WIGil!;g^E`MwM}?HcmylGVBNw}jc6 zh!}0tqM^AGo&E|@(<)0u4Igcd?89rEWQ~er&DZ!^4xU;ErCNeLbPg+R#Cz@PT>^?z znp&acN-M(Rzx}y>lF>d&^?A835mi6;>b-&sBKw`v38As3CHlz?p1}=yt`*^s zJU8tskDDqjDAYxwfws4tSQ0Af+TcW6XVDLn=Yh4k)J7`6YWgdGX+iA?VX!?IgHoxi z2~1oG?tfGLv9Ibk3?2ll55|X6^T0t<&{Ef8woxoXC;ur|Xi_q?kGA^x3Kh{~KWsus zD57*s$%%s;3m*g=@PLjaGfuS28~YpBn6YK8FmC$&?r2FUI7tbM8)p%4HfHI-jAr^v zF9opAwQVa6yj8NNmEpGad5;g1R2xHxFPmE%jaeHfdf)q)n}ouw37XtgkPP2TE`NU1 zb{^j{NYipk*!V78o@R4p0&O^nE>TPJUZ+01F;xkYDVg9p z&|Obh(<9kFW7;jn+cgiVcE3$nylFJvC%4`2@+0bvB-V9^X51#RkRwNJoOCJ7FFi<}?0;U}vbseRW9`1A-cI_W0Rp}{K?)|9J zB~Lu?(QMp5Xgp$X40Su9WXamnU7X9Q;;=X-C^z^RsbYuRw&mgfjws6M1IS zpyDaF)M=NJ2{PWHk)+WoqFMXYJ|UIag^)3ZyHTUY!7SpDxYU{05@-lL+#4BO!H2k; zAMkISE^3?$P#Jk*-j%{P{C=TNK4gxqaU$n#GC{g3X`zl|u&bGPeib&qVmeQAH~)rj zwmD=v-hC+7ecnKKga`Ss1D|CMT|lSIfkP1ujSIoZX>s!@AL6AW_c=P<`32;BtNGlf zIbv>bZV$P1AKH!5om_RFtTKm`50HoR&QItrT=5ZD7n2Z{E|H>^2Sf8!%zJSeVrYj} zYIJAr8WH=0%fw+TW$1-Q`mkEv(8W^eWu4U3cJ1Xy=#|5i2@Cq=-PA=&zJ;ge3r0k1 zLQP9dL#wQ)g%aI$GK&EZ^{xh;l}q{s*2Y;?k_Gm~*^Jbw^U(SEk`3*L5f|2Tbm1ZaK-eiOiB2|2DJU4olejQ@u@ni;>W<5oMCimZq&Pk6jJ; zc8JXUnaUoz&th*tW>H;req?BaGHthC4>^q9nXy>UCPulZZhJ~24b4$oLr6!Jb!*h# z9|ojW@%q0X`zxU+(^6D4{mu#+wZxBthwitPBE$6d#=;I}2T_e_hXliWn5w7)_q}T3 zBl7gU*XC=wO$WF9yOl1hVBV$2ulGCBmX#k(AW*v%iw9SIN0<9YcotiZsx#(IdzN8G zKll&XxemPJck;rHsqd#qJ}sY@7DzOoxajRlTbwW-94F9iKY6|VEPU<7rxSDV$)f0~ zo5eAE^X?Q1NprtS zN1q)nl9jT)^0>eFh4nS==Y_ez4w2`j?GPD-Aa%&mvtUnr-=z~Z%k7x7OVUVTf~YIk zgHuz>%g?W`z(Zu0K2*s9CoxMXC&pcwVKN**_;2{RXxaI!>fz6W^RJ}jIOTr1;fLV+ z(~PAnNHf_J!On`|tE&66M&6?!vXw3XdjS(;HbwN^1mBCu zYZy6!6AJ2kX0|WuIlq!&v0+nw6~t=jo!z;*;>4Cv)G|rpbSVldDBry%fM{i)*YNEk zxHFw+Xk1;eDlu%vm2`->>||T9Cf-?_646Wdd>wg_F!!~bb&xN0j+o(&o}^dFBP@-| zRxmre>i0WD0oI#Ko7SWur<0YhQ5b?5Ene7!G*V!}%r-wFYGDn)3Ok6BgrT?|ER@|9 zN+;=Zizl4Z6G=~-(6a5V7J`4R}bKkg(!f_RF`|eOWQwzjks9jG&5nWAc54P8t4d#s$7H zCfr4ZNhU!>ogsZi++W)+35w0TB!VDGyHK9e28mr$F*VEx5D|Q?kGL$Jn~DhC%$@!@F2?eCV_!Yb8k1BHP?vo1f#IM)_BOa)f{YIwIE3+2}v#Y6%Tn zb`64G^RxI8kz=dL;=Gyw-e4dsRxO2Yudm8e$(3#eSRaRvS#=&`sFh3k5McoDv_JFx zon}dH&-=JcLkg>T%YMCyGU=r&)8P(wu8I}kyA@_ZOU92^nX`pcS8IPrcM%y==-xga zvzpyM9e$-KZ9kzRsXIPWuBO5|&E|4fGr9FkH)bj}$X#THqG*8$p%|6QI-vyPV_2}y zCT5ryOGE}OEL^$ME_76mJ$Fa8F-R%YX_3hCo5Z3!86xk&gPHC7|jcvveQ;!V( zs}T_01fw?KBuy3t@#)E4KAZ?>)iN&kX5%#=Opj|*FFEuT(8<96{p=le(2(~MONNXa z6({9px&DiZXJj1T+wmE!z})jI#QpZ~*<1uIm3{s2!du&oKSa`Lv&E7@z!fZc0)ez_ zzfmpqK|D$QAs+{_o;HKKA_K{TKIQzT7od`3k%$caz5biAFhTBXfwjH`(T``X);-$p zf)Orky3FpeJ%6O5XnjO<+4)}eYJ3>ecI;qa#S!neHn-7BoM5ASy#rRlERKQf{vrJo zsQ9s<@^7i{6sLk_|52xKh-*p~q5G8*dJjoq-58_CPu#2cd*F*@|EZ?1xP8B*bTri< zoA%342W6cP;|AmVoi9_*RdTOB$1LbPJpzO%` z1`D}-Tt3N?*guoD&;J~LJwe3(GF7~gb2N+K%Wr<`B417u`B?B|Ow-pay~$nmR+k^W z)-TgKiTkwB_ z{GnLqiR5hYP+Tp{o!;a-Vy=7YJUrqFua!B^{9@Qso94k14PC--+XOWYl^cA9u`sR8 zkLUFrofcNnFwq&C>99O@OXnjaovqF9Pz9Va%R0zn0@Sf#v6I=J-g!2<@>x~j#;((y zv!2hU`V&IFIZqtApWx?WbT}k)UQeWSPKGW*c1lq80wD(1{ufOpw1OSVMfxMFQ*AW- z6@gVeV+3oC&CF?sjx~@~k}9;5T5QdJ2rcy*!ddLoOB5~Gnr`m$<8)^a`?0Zj@fz*P zWj7=0;2UGeXI3S#wryhJz|ScLyoTcC@;|o1xX%9yE=@JR&HEPq-TI%%iv~(!6m^Vr z(K>rTV*Fv_ac~K2gQb0@k4H~X_3n0S^;okDO*n%iKTnP(f;=(Zglt2L>rx0{T$U<|0!WJEqc&0$vlt4Qe5 z5jA8VV;QHDz9G-)N|Zn47jzeF^C%8fF*)(~dyaS2b8A*=7kMnTfM%8x;kkE#hx~&yhi*>&yIc{~5TF*DGDl`It9?!Ba zD4X}UVWUgpO_evFWQ)hkX&uH*(=N|Ah-5Q2j;2)EZwWTnHHMPd1roTIqvKvS8Mxbp zP9@E>3^`7gq?vtqys&k@={($9VpjBeVN5;1Wvo4H*QzXj0qI{0X-+NpJUp~u^o48g zjf!JR2^5v+w*_(Ub7#Cn?@MF@;mc5hly&o{Qegc&TA6>2E_{9S-%QZsr%#T)M{-&hka2N8XdljMeE~z~t^W|1SOM z*IzuTmU+2ouK#jQv=^nN|7u&k?3P}Laa={Nb{f{?R7l%=oNyp@lu3HCr2cwlR$Xek zrtxl6uGth`*0^a{>B0^h*2w8q2b2CSAbuTF&Dj)}x`$gKyQPaonR$ z)ZTd7eVN1UU9Bm43v^cJKyLKUJwWy7LWior7%=jz$9+wh;MSw=eNgv>&dKX(y*KZr z7E3)7TaO1W7(^qc%q`}2Tj#lv|5Z>!mVwGqSj=Yy*RzGgP?pM9ME=`FoxRqk?7>jG-FMS^`)GHWt>G-6=FKx$G-+gAJ@l8ZpZc~M6x-@xbMW< z8V9>6B$yc`kS5xn&43@$SF4@S@W9yfo>*ezm=NPc^T5QD`q&KWq&~bvLasy*+9|1k zIw99NDyA?giwg`6jQly95MGxk#~JZ5G5(Kp^5IN!-m7G3@wi6Act`wLC|B%5yer<2 zGF}tE4UV_KPbe>RZ`F)%-|?t1PB!F7sBTE8FHH5DO(efc^rTMK5>KkUifyA#TfRy~ zahdHory_TfORti0oD(Ax6Roe}&Z!Cg@`YYCq~7$Vj|Zlw6{b&!M>T849L=WgU!@69 zr;aI*09rzr+-Ye1P;!El#P`{9Nd zewrAKq}&Gam|o3{k0u%Kf{*hMiV^@@@f%ci!v5+*%=b7&i7tObnqBOEZbwjJ}l0-IOa4Y%(hh*>Ws=GDc-w zh;Cud=cIy8+)t7qz?2-zDbqITI&Viar_CiJ9UFW65nZ2z-GEE}^)Fion!GF;HJAyO zvzOJg3@bJ{8cM^`ojz;U{8Hq#)&6ej(KXFGpzPSB4B}OKVS=W5O2hM?Z#ZgLfrqrs zb7hH1IrCbXhrTx4xY!S0a#+?NGjk=gLFGS_$|+uAlOJMAZRE!86sAiQOD2AL6#+;C z*c^MzFin>z?#%qYvdl^nT&61A7K(nC@?jcCby3!Dt-@4j!QoX!2u*$fO@Ra=CqAgq z1gg%B$d;GPdcEhbs8IAsyPEkXH-w|+OGl*wVPPae&I|5}A;k)@(B z$=Qam>^FqfYLbQTf^)z$#eZGvoFHk^+IiYH)ux1%qcl09h~lTF^&`+aXM#+3m%MM< zHQt1^zLK@kN)3-)b9_weo*?r4TTC<^woh@(ivy~y#`(v=poE4*Q972qL~G2$s}wIg;bN8HC>uEQ1jNt z(>5eZwlEMjt?cFWD3p&QV9(v!n0uOZI$HKQTc6#gKj&(Bl+r|V3(c%+(_61U-D|ER zY$)Mrcm;3Rb#3pEC_*COu*){~;x;rM5p)$1sI(8Abnf7Vx7TPlpWn2zNp-%1x4zx) z+}rDrr)$%JK#y+V^mL6P#Se>HTXBEqo7>J0A#K~H9eFn$hIFl8c)K-{+rblU0xq2z z%5@k6?H902h2jp9eaFZ9a0?>1rm~Z;TMw68lY>t8f@HIANROma2hKpN?0&0RN^g!% zUnX65_HA#cX&<&*OUhgwfpV)FU1tc~D@>}XQmWr&0Q6g#1Oq10;wI82HK6)#fEAu+ zY=EKKZu6#UKG6R#RfBUxLFv_Mv-2-j2ZSFITGih}ektAr zEknrtp#!4fBi`W?3=H4x58o4w9EAX6WFt7{BeXsHqW!4YEQ z2u|Y&Dc|U0mC^l>;V06g<+-D@gQN7wQAXl1X1+02m9dA=mLqhGt7MF4aEuQ*CO|wc z#5evzW&EZ2xM=9O_~3U)5`e#4B*$tV{}n^-?F;G06Cc{gONz$*y&-SQA&u95_*g~EyPr#uQ&XtfJlM>$F7Tf2-wE*Lr-xe;PMY*@>5pmb$w`ZmdAfBQ5J>!dfjwUEq@R?c5n(>J! z4oMY>avz9LVI@TOQxM;j^J2~MTnINA%zgMe>xC>Q+nZIffqYvPf!y(-DyE7SW;Q4g zWyt4jrj-Ls(J8Wsr6^|FG3F$CktX-b*cOC7MHMax=mpI~UQEcpoo$fjALgri`M~;+ z3roa{D}0M9ARkCz5xO9hH^2QN< zz;!`P7?R}k_o2(%Y}gwHw(rWZfbtT2{+08_<k%37fYhF-0nxJ9rvxjsBx^^~7-sut^|jcJW|&GSe~Pa*B`UM(NwTFavu&rklexGMvWO?u!jKiVTc)xbBDhhA+V!Ph z#!AD(@z^c1*b`r1C6-~U8`^6`?KP9^xAO0|tL}GN?01Ll_m=MW5A6@4_J>K3qx{Hm zRpg`vaykq-TZ%*sAs0}{B@)yMKWa@CwPAtU3PbIbqV|SRNEGUTA}s=!5!-0p5zci;1KK6A&%uCZulX7*&*TZA@RW>Dd`cpz|rGRM^7w|o`oM# zmmSd#AJHEiF_IoL3mmh4I%XFb_j+KY|HDcDj~(@YFr@zlzPPy00D$hlz?bvUBQi3s z|C{;#$Myn%zJS0#p@(_adi`4ezuuRR&-lOOS58jzzv|aUUtdYd`u}Brk^c|>y(c8R zr=+~6p+U2=-*a=LMMUl;B`fj1hXYpkzkXdfI^J7Z-FtchK-9NyF#v#|pcwhD0Dh=@ z{P>~n0SqHqSRP6r%-zssyW9B~XnC-^h7Wd^O^$@&KX!Kv>woMn zPQ=!@cN6$VxMf^@m_v$zi0be#ek73yhv1JGtGvQ5Aca{8b*OHKIp%%(K268vrAbYB ziS!#@j;}gc5hQYNL|~TYAMq(EOLJU5G2jr;x%Ndcy}FWJ`xPzPzVZnmhDD5@{$NTE$6pR%?vDOoHfa4)$l$=} zG=&R3rY0taV0m)rQ{fS22ByP$S#Rqn=$7}G(Omg*kr;GbJqGUf8sJc18E=(A_G5)? zc;?IJ0Xj^SKLI?$f_xB_H@HF;LmKsw9Z(^9P8IXTW;Q+^L!*V7jZsPr@3%*&rfi~N z9yNQiYmZmrKhL2!S!OX8CVAX@^0D_o9EzM1&()~b7grVU%TDfnDik+QSr9`uzqqK+ zg!y-YItV9Ztbj*A#VlYWo#@XqGr;iY6+P%~VeV;x^_vTJfV!R|-UR>=d~jmCEi5c^ zzYF|p=WZ>>$?*I9jNUF0pHohokSG|Ja_O&0VXD($R?cr80+GRd8eyRF?J72v`$HH2Fdk2PCL4G zufOgm?y{TGeq<&_nD`||9DRyc0F}*~`F*-U2d9tPhJY^6L4gSzdHW5B+Qw1-!uJ~- z!5^Du7}T3t($+wyyy(jHbG8Py*Xeu0Bkiv?SV+_>jMVg-Os35{k?^0x>7Vk zzso5lvxJG{A3VS?mByw5()xQMi>_`d9A|aw8_Gc zyl_@9tQ@Res&nPa(2jfl>?Z)Fx3PXM&FVo0#_I#)opDKbk6$&6Hr9PCwBFs*{G?eJ zT^ChU0EAtZ9b51ZRtIAjUS_~PdkfYxn^bIrm7-zLBRTr|FH_jeQq>=r`K@U64zbT9 zS943qp4<`{b_LXxY#5lLux6KpV?fVSRwT{1hw3Gqs5p7c{5DuSZpYN|VB}ds3f>GD z7t6HD#x3|NM&6GJ?C{k8T79?U_N8lz_G%_W3XouWJ^4K8EA*=(1gK|$41l?KsLSxF zjR=9#SFIAItAdZjhHc|y+hKpg{9M(NM$l8mU+9TNyw{T~rHt?bQuFz!e=}!J#09W5 z3H)seOk=4*2h>6uBLoAb{>;A;Q;>~}cq*S1c7WZ`>-aiuMg}H_HV9os3kRg3ufyA;w-a4t+zAcSA%p@SHA6L42399eZ?i zYep`YF*e-kM-cP222+^rK%T0c!SI_Hhz9*KdFk;7JeDJQ3}q|jC>f9-DQ9=VXT=eQ z(kEzu1(liaeYr!*u>%Kt7xUSSyu-~J$KL-FQKU+xY>-g|N+N%mo(I=fzqVw?H>);HPm@2{C#SD5#nAEp zZFl9A=EjoFs|!?0Ow{}5rl99F<)I~JhDwOJx%1lk!4eC{e#GMSd0h)}sa1f|{3^{w zeR(f{71uw%DRI#-5?X4Pue7kMbpf3jEOn^sUqHEBz?O;2oVt}3kCQIo+bU%))3ka? zf*H^1`{mpY9_%hEyQ$vkK=~9#csteJd;(a34iJRsu8x)lvT`X(B2x4t(S#Pb?4c5y z8zF9UdmFOF%AXldNKn_&UNa&n`M#KhB0ixV3LGhZyOp3sw0G=)ge3l?5IoKA=&H!5 z5Vun%VYry-ys{T?^HL^d3~%pQl|AOPa-(?O{I+))R4JMx^_K-N#`S9ZLVjpT~qm}5gNA}>T5jTPG4#;7suImH@@zHqcp6H-masV0X2zky&gM_R;Cn6+2K!je^bJ7VLJqi=5spqW46ZPhC@FG0-V#4!LMmtj2j9?&HzWb?p(_VTD&-~?0Fk(^@ zCv4GdUi0Rd@tM!?j*~Sz@D)st1RNfx$E22&%v+4Y1#fz&NMC1dV{$guv(m|1A)%QaNBZA^*+EK%VMfeh+?{ z28oRo291^2*KIdLu$N?yPr4|D%TJ7;XgrAr!K)E0rvYMKVK-EJW^awx2=?o%4>1z6 zVyj@=vZm?L2m%>;w;F{8OnEWI2ce+>p?RDkdvc+1xFO%SgMY}m-*<&}Y=urb1wY~p z9*_^-bPCm+aWj$&LxRJv68z`DHoHc|iUropRQM1o(%zX6f`afhjqn4f@RQ5X{rZSo zaG1nJ_|~&X)^i`x=V8==k$YqjF)hA#oVHk+tn9{7%SK*@;D}?Ya6W1e)~i1pnkFw4 zqPY~j>8>K5I!6)&I#UMPGibWJ;ff(@aOX*k;J*qc6*m?#wv|lud|61uauuB<8dGT) ztF9Td;uIq=8>?3sGh`J0YbH8PF7B^*WY<=Nf@YX$Z=9e)EXidIHaJ!?FOt(bLcTXj zUm@IxD{j&-?#0vCLWgL+9(3%_#CR9y1UkHU2Ko5@t%UHxSnk5Oz@0d-b0Ses0s=2_ zha=vWD^bii!R-OxHpI^sB%*r~SAeMJ90@^c5r?4oyoPXd{KyQ=gqXm@Y=xxS*?3~{ zI3=#g8ii!b#JCpm6#Bv>h;h71T(n_taz|mZ>r{-)Rw9d0>hw<7$He3+u9T6T)L`Qj zPwJFj{0BUoz|EW-)R4B{ki4=Jzf+JR#F>8LoV>G>@;)$SLm^FuEA7ZQ%|0+S(m#!s zD=Bv;Z2>%WiW|ml1S{nN_{?;rNEh~8JDH0nKc}k-F}{B_%yrmUyhth z)}V0)8+R(zb&hgjrm%RnPhoa}Ms_Aw)-#$^d}zACRq`5s4mUIlo}cr0H=DOFU0gBm zsa%etTyBMbPKRJD5kZXET;h*Dmw$8F%6+-oyZN3_6ANy8D;J_-F8lxjTPZ~fN`hPh zi7b`tw4c}MCQ0ePB=VXXQbl)jK)VIuNtyOqv5wFbKa+xBt$#*ZdD)6Z&QSdFE0R!} z!ic%TN|&%qn)niE7=#<-+E-9WlNf)U-Kyy7BjI3^WY!&2+!$2keqC5YQ=q4nayXj- z)B2msosHHAN=}~3ebZN1eQn&S{RhS@ATx61tQAcZ)x}KteT3NRuGYq(WwB zN!4!o{9FlPP-#|CS&KvIS@PbDjDdC_4J zs->Llrb;%sGJ~M9Ua>+lsJ!)K71K)9+neGeXyut=`9)tP+@u0WL0{eRQgRjU9Z0g6_mwESVPZKZVjvAhZ+63sbzpw+$mH)hSi!R*Lu>T zYpD0iND1p~d5XPFvwdCbk-K$XlI1?ya;`WsG*pf;wElH{ZcL}=q4EH^o~=BB#A6jpar zVMtpEB7~Lo!*6LC@`GVup2qQD_?O_?0z^&!9z2i-9t^32Aj(zxp}pGGgGx|@YjxFL z?cr|qs%ic5jhVfvqr7RUV{jd$r3%?neW(QQ+-tTYtexblRnu%ff1s~aNtc!b4>>~&8XzoE5cT=V{<#K^^If>CQ&wpPAwB%+cG+c!mz~;+|s-v z*+l0ChbmDNMGB9Dn?;CPCTW}L%_x-10enzi$Kzm$&J&_}YEfX%2Y)1vS75UTu zOtzB*UeiiQ@hAq50KjBq3P_m&dr)=#(dh~^>M}~{a=rwc%y${V11;#f{}6TC(1EXM zNwja<2y|+;5G@l*#hj7d;=G;0Iz9gL&1t3--Z~u*aqkPa4taQo7g47#&`u-OCgj$0 zEZGaM?+)KkCim$dIzkxy>s~No{tm7&e8@+;kU0 zIvRD_ry+3lfo^wRn7L~!cSvvPZC_|||6+1OQ%EO~*#KJ8tui#FcP3>pp0}V%xu8ZW zV~J>}+b!=SQGZr(V>>Saq?n|HsCVGDzl*0oy&u*|1RqZ!{zp5o={j7WGL%jpc6yTZYaABBxCn zhrLt=)k7yIm0=R@L)dpS5$@A5cN3Dt!*TAjxX20ol9>$YncbW5fw@WYyP@E_+1>rt z?6|fRp-biJxeQ>6e zc%~aUZn!X_-8kl4GCxN&wLm{!Cp|u0GWpkhN+onUHg%r)ZUG`aCLB7kVc!3c4Mz_) zAqE%I9TXAF8sDmpaR%I@4i3 zV?(^qle)^SHj6{lv$V7TW1Yh)+63n zAzu1QvP{pv$u~54(YT~rI_)01@)C{s9ya_`b=^#6;eqK|p_dIAS}64TDD`shRW>t2 z7nMpkaZ&5M4BOcJTRKgf!9&}qyA2|lO)mOP5dXTj$4aQ)w({b-UfRk}{vF2aE%Jx| zy=zD1QS-wk8)DO=t8-h{L0bZ^Px*{)izhv{w#*w7@6IM zv^nRr&8E^FUvx_`x)NO;w&P#AHa57{<-S*_x;i1VHD$3T2{WHSO!u?k`I1E9&k?TdXSbBa{a$0*GQmBH zfMn+j$?h4+5xM0dG;RL{$pKdL!4bp8W7UHv3`h*peY)W-hJ&qh)%{D0O}y}7OTL%gyk_s^U1DW)jq?i#=*Af{oJrcoxCT~ zyzIg#eOp2QM8NV)ope$A{?P8zhO7QXoD7*0nP_42bv1K7ITgMppL&ETwH3YLQxM8P;<0;*LPiJGv-srRi4Inx;8v&k>AmU6wpb zZ?5A!eZBlv!XoOz=OtyMC+%4gmE3+#v;=N9Wzc`Ow5yl4Ws=Yh6z=YYvxQRZOzMl) zXbpJ9VyQj2%x(=izL#uu9fAaTViQ&*=lErD`h&jYus+3*NjcD}>sd;U=Zqu=?LtWy zZ265N6nvjoe)^Ipp#f`d;b*RbGo9C&z;d_elsr*Lhl?`_B0CWiC&K!U<8OBSHBTrQ zjX}~`ake(M-;5d1=>t<`r9aQ!aG$i;f(RMXHQVJ+Km~tEu-w9Ep;=Qdam^n8aFs_1 zoivzCZYl{u6^9A_sfXo;v;DEE_geRv3Zeut4Jncz+wF_-K-{0bmN z>KRwM33WYmJqXYt<#Iwow_9UzET!tPgvYDnt!n;G7EolQp}^pNvs+}26GuTu+Oqbw z^*-bif4l=iJ$@$^^bwP1K{VR#G9;X`w5=JK74u5?U1$MB>+W$5zM3s zGC5qgCs3N(@Fpb45mX}<{30GkTQO)9&e#qzj-U}HH;!Z~AQgp=sB`c`Fkb|Hj}ZpC zi4lGy3jH1@)lMxNX62+P@`+Q1ixi-;YzK)?vt0WT~QE`*e@i2 zahk7rK}rUMAa8N`{IWA7{En%RX!++NMO&*cBFG`_JcdwTWL&?Y7#0l>4{$_R6Pb7y^1;u7+hE>ws zFG+ydj8XIF{0o=`&6@L7E`F8JfMg4@Yw_G50NWnNs9zgm(4@aF#wv|qEbTje%~!5Z z#;gP2r}M|ZJbe1-!PsJ#1}tTK1Xq28=m)QCvlg5_zgcv_-x%WPAcEM zDQ{72dtAAC_-wFpZiL6()(K2ZE|eST-!Exk%MU(E9x;)Cv%cEsbW2Tb^OiqSiV*MV#~yiR~>#)1N9k6F+X+yQhS|f41C0FvckoafpfdrSttW zPZJ#fba!;mOaQ8LLrXrptVc?#0S2ErvVu`8zl9G3{4F~lz7ZL+f&0#)&7>%pnc(tk zc`q@QVH2|E58?QhqCE!Rd;X-xSTCVTzfB9}(QQKX)a zG1urXwUTohFAa(ZqNiBKKwjJAK=mk8e_#BTJiJ^p9#qR3eGyPdV8S6^6S4_F$?_wr zB7uN9%nB@dCG!Bn$NI|s&H55b#bwQn0n3(!NtZMUMSUsV8EBY9+Vs122aTQr0a1O|(3w1vZ?L*cXDWr5Tpeo%2kk@WB}hSMe{O&okE1vMR2Cys zr6meXVRhsIq9bM(3doXSCneRCIxv(Dt2gr1+Y>JTB7jh59fXBb_Lgf|2e(oS{8?XLWId~AIlHp07TcOGFXiC=cRGcm zv6!L4Kzu}f3tqlyC#Kwy6n1S{>!?8`%j(Pe zISYAfMqcITi5HGX3z>FXSzFthQtka_v<~aL3-2wSO(;5?#xZs~hSPA++b^+BL_KB! z5-TypZ$Ta3_UwW~Pc{|J8d1>d2?K-Oja-5nG04X=gZ)*vU-H38S#&?X_~1($Ot)*W zvDbg`ql+*?kaua|%Mb~NMKx|3!*P}b2Retp_TW=-4ou}&3uVg)(t*`v8$cQi@ zw_GYwL%xig!r!NU=Nh!Kxrq@<+n0~h)YU0iPlkit=SsC1C&prN8R3m0cT|{chPq8? zlPTssaYGHLs7d!d-520=opR8-NqrmrE+UXP{fECId+60%K|W#mMW&(oCf=6OVfqn;#2*2;uR zdl}K(`6`RyREFv6)YwmsdUDxy<=p0#e(-%&7vZ_J?J{`j9#~(WD|=>T8^3mTe_LBu zdM-|rvc8YZ(R@X3qpP9q`sUTpI^%gkH{;?ZnJN})as2S;OYfAp6yxFvI%N< z?7Jyn4;8>)V1{v%{^Dg2J5#&;9_2EkTVeDkacYgw+wBi2ky&!3M;mpA*@P$ZL8v3a zCRb+l(BIOV~h#`r?oUMCRq?L|ksEvyhdx3u$}i=W-E zN3T4)9PnFPPKqi|k2j3i1zc)-j zB#;knqaU1v4?maZw?$L7MNdAB0DNi}u#kpFzo|cSh^mAHkCX&ni@J@NnXiI|>sM+I ze$>eUF7L7^FgzIhs9Y%pO_5+L|X z2ogIob0DP|FuX=0T+#tXRw=xxDBQF7Zgq&8K4|#>lhikXE`BZpBoZF@o}>_$ycL4vLZW}7bi;oFd#EAEa%b7gUkCw z!&52AGvLwVh%5Sf(Ng9y>RAIEbcqvPJ`fFtjX^#P?q!S8bct$qiP>ZgwYdrMG70MI z@^in9F~W+Co{N!Dj7^)2%~lD`qx2gz4GTW>{Sh3r?i!c=7`ch#cvlpvPW_wJEsPrO zH!XK0eN!BdrX|f%^dnB-2M^Zdiowu`5pRqoz>Q1eh}(9Jm*9>)Q;+9*jCa@gqb3>8 zFBv0zTDbMzC;0%%01iLr{FT zPeeF*!qZ>^qj`de>u&+vq|a_iABib%smXf2M zl9FhQ>YDya(YtI6S5JT zvs;q05TCLQadQY#a%g{L(YWNG;pPrC<+$QzBXVW$xn(~l=PGID;&JCVEM`+e1i>%m z<~RMulFB&c$^#c`=7G5LRho10aDKDHrL&pG@wsKpJmuBk78qIlZhOjM;VH;{$|W@| zkcLk($4j*w&NM5|7NX5jJ&s}ENj8-Vbsd%x*UGeY%-qq;*3n8ZX-?Bz&X-%x3rcZy z3d{KkpUWARYx9)v%#-^}QwXvswk|0OZqC=jE3rN(=Hf1~ZYo|d&&an(vV+e{E-4Oo z`>?B}^v8u##f8~Jg@2AqDpN|BK*b!i#b(Q;0mu1e&B+}liNnoh)nR2@LuEWXWxZiV zP|w9h%SAcEMFS~C1-)0!zx5 zamqw2z!jf=apl*buH_&;Qh!`Ycx*k zo$%}MTPg?<>P=4m{tB=E0J+wwg}f(dlFuniZWQ%}zKZd+``c-hJteFw zHAu>*f1{~Kv5amBr=N_zIxV43QIL#yGK|_Ng54oJFk;YLDI#=quzqncdX>VpYA{A- zC@3QQPb-;k37uOO6aoM`!~mji1nU=Kzd%}-Afn0eV1zpfEOr(Id3?VZeV?mG=SRE2 zT&+*4(=11(h25&h>NPkX3mU-=#=&58tb63zz30(#WU4R(4lp*k8o`y&G$#DoBCJ6T7k+C2&n zUaPs&I#J$waoc7V%cl5s>jd9g<=$qMBbuwrCf&85oYj+ExEr0sUz;_y9{Z&`6J|Xb;kg*pwv>i65eIH-HIbdP=9?uw>w4qu ziq~BViFDebpKy(waa>z;Mq2i6nQtRlW0VvzTKi_(_-XQ1S!jRj(wcf_f*r4%RO&{Ba zT;E_~+~)Awfdg+LAa7tsY%^!9_UJBt0j~;V>`=( zmp1M4?(NGg^Oe>K>wU`P{bq13V8p-AF0wCjws(CA!JZe^S+mc2yH9{|U`n|4>C3^R z<3acDgYKFA&Y1(0ic++{2R8iQyxY0_qj*9XSNHk>k>`ie$Vah^N5AEc{(uj$3?SeQ zj#9^u($9}Fk&m+(kKhd;a%_$ZqmGNgM=2G@<>wz{_qYuCq(<(fZv8OX=A@R$x#j=T z?xH95O0Pl@I0es$GVPG@Zbb>K*+9rtotXc*^|roXzx1hAj*LJUU#% z#mkX*O10rkFJGP=-s$naD7xn8;y_0N5mUFoXa=(ADd-JUCVW78(GA5Ik>S0s$uR zh+_clzHiO?;Jb@Qc>utTNcc+)tQRSW1OUQvcXtH*a5n`w`v0GFa*JdDxY2>8{s2XP z5^R6hppdYt|EZIkYYHJh7uC_=4lrtIbMFWa4WHiI2md>i+mA@-E(5*mU*Fj5PU08P z8G6}?|L;&PPGl&AuRGSLaXgYbr`HB;l<~hqxkvQG6nyTZ03V6}8p>@N|DNx|_FqG} z9RRbUcnF`W%>NAK9@TKWYDjfM&K3W!L%AioBlYDg4R$-j>Cz1qYb~xf$7>@El^Y#C zkO)LFja6GcA?S2^qm6%e24cviGh{wC{Ej5CTCR^a)f`M@eG4a&ZLU3{ z-q!MPvDp(&EZ^SxbaOaUsz1@*_VRGKGmq zMOiNYE3+Q_VW;6?VgF(4u&_WN-hY~PS_lXLfDRs>@xN#5|5EAzfagEnT8EEM696#( zC|3XPGS$-`>Kp+0(CT;p0oL!3kp5-X2?*Xle}1Q@2mdEL|Mu-4a;~iWuB{C=Hh#CV zdUteu_wWD!e1O2;06>NpM*|Qz0RVjX^^ftk0D$v<;@5zG2K#{Q`1tR1bhqT>AFuy{ z?4CkB|2d?J%Eyo&<6V4=YH9iI?ELQO`R+qk@^8rgKc}w)0^TDc-s9rlQ&Xo43T{8p zdVc;*Ma6qr**~tmwY98lrLAr9gSLl-y~oGDr>DOc7w_cd{quQU-F0p4$5;NP+gAn$ z|3%w-doMpE`^WP`x38>BPHy$~zK@K&FO6RR#~c4mw|~I)-QD-o)Bn)zw;zuW-2Ol4 z_J6MW|Nr=Z`U-%+0Cc$jFM8Ym?@lBC+gSws?`b5Q^D_Vd8R-PT@d1HiNCQsSIC-Hy z`rKi6YXii95RYC#Z_xdM59u4>H7X%ChC(N_6V7K*Kfq{g2q`{}K_|?+{UK=xF!a$d zgfK(HDC~2|L5`{#2}nZh3KKBpt3iTc?9Iv;FbG7z&_Im}eQosdCo-(^0YU>vI^%E& zfO#Sx6m}$U>t5GQiK}MLqzeT^tYqVsxq#L-c2r4*>BpMIus#`jRv*_@n7k1$&Qe zE>zL|oFUi%?*k24s}>^R?*mW}goVbLgdoJ?g$ow6V^#o^A8;T5FcF^)pmPx5W5qH|5-#IFMu&|d-UO{-$6U&FBhr^N#jy&=MT8;&5H{$!IgsJFYBK@| z5W`E|&kRXo(%BmpZZTn)*O-OAYEQD(y+NZ;rM&+PKUoCgOzwL4)N&U84$_IGfyKO6 zCz+Gx)U5>r;9HOPzXenBD0s{5q!jM zz3KsW6JP+`+0a8^%8VN)opEh!NKjE}v-quG2KT=7q6sL%yhmVTJK zK2XqcT}Voket=Gr8PN4tNEHcqyi1}}H7@ik2m`Tq_lfsBv6vhoM$~t79Wpt|Oi@P|%f6J*rjqgv(&H2*{*6GVzf*^45n?Q?>RCODqW=;XDk1A>HW7V7>Rqe$}o z5aa-2U^IZlGs^yKSj~!Pek_dVGye*O)=zj(!#|Er4)D|H5P78+7v0UHP!$zp;;`2S z+Z$ti;%?ob@qu>=QEq8Y0(CoI3#u2X;lkzkszZ}RLTx1??>L9xwV^uquxi4T2tw1U zbjgDtMADdJ1TF65NYGyODGh(J*e9Io?tiAjoNi+IiB}n<(kbW;uxpcCcBF^`D+6MH zb=1(S!H^J#f^_KFyn|0wuCXlI*Q<%3t+vVEiv%G%3Ad#vlsRT51TiyNk4?1K;YMrz zMd+y-lZJIvDCH5@Z%##unm=y?-ytD>4K32+UGuHwn246R=JS+Cjl$w;I3f zbE;sqDTLc~TxloLP+$QCN+66dWKH#w=-4rn$gU^WyoXndb83J2x@&d*ygOpU3bResGrfuozh9(zcT|AvUmY@?+<_EO9J z4O1W8#%g)&V~+Y8VJfqOxANG}HU2lsWpsz=<#9j|xjH6TW|s{AX;9)PDhyudF6Gy! zA%&>w_(GXITJ5J{jq&P)hS5Dn_oop9uK`q>YcW>RCCzT3p;ogtkC9eI#(i^~z*Ka{msZPv)PJQcVvnWM{Up33{okZ2=a zz)pCSu9EVxuVScRiN&JspWgPoWRYr(MRFPsLnXg-nMwL_S}h)XL(ov!ShZ#K?eaq1 z{7tI+^~qn1uk-_AKdWrxEN9qOD28C9Yui|?Etpm)Cn#m>HI>dPoZRU)U>@o$tF5Qv zwJEmdrJDa%+x(19r96ORy!4ZN~aJHmYMxBeVeJ0 zz9=7DmmN%aP&T8*q(0D`*VO*I%EfbB@4dNj==`8IvG3HxfBoV>*Agb zS_^Cc1xA;<9F#YDH+IGa1w^Y61`}$J_OFYWg_mX1p2rZbcFM#|$$j={*Ekh0bEfy; zzAm9#YXm=~>L*V_m5rF0ljd8OptdR+rk_It>-P=n>?^PvZsrf`55|RWOZJ}*H@qqC zTGVT=+S)w!VKXP{INMIc1w5^&-Y@4&oo<@IejZx`d@uI)Z_>S=&dS{dE_w?Qp0umI zY*LAzdlJ2#=Q`e^s=SyV^d(-@tKZ{qH{S0CP@k}IAd^tu#cemSy&xJLVGrA#2>mb-$BAD+nNPs$+#ViDjF%X<29#q~P61f-{zwd8f6nqOCLTec0>>K39 z6&f#L7PE+#vKZ>v7@EfA?mXz8FlZTdXrK9r>&QmaZG@7o5t6478Uk`CoB|L6K=z#g zLQ0exjj#{7pFtgxg9>ZdC&?p<(!~`~D-oe(7Lg4BQe#F@tcrll)-FoI#u39_JB*kx zvn-hkM`cGr=!77cgy;%TI$ex9e~kKA<+l*!-6#d*7{kj-^A;AX5i2-uQ zKs7}JG-E)?G4M;#khL+$PcbM3Ji(qOQOPY#+buk=AiK(@ z3eL(u8P5(kAo3{bPpG`vkXtkjmeC?=`jDf+Qlf_IAJw8n7VMNPjU>mT_)y7YkK`1u zr4%2@lziOe#)6az+&^`0$seclA8u-yWC`+6R?6vu+Y3SpBeMzhQ<&2xcltw9Cf2X) z(xJ?sLrHLWA%w@-noZd&PuUjYITUy~hvvb@a5*B}8JG20dk>l0l)0=tSq+-mxMA5% zO*u(RndXwYnyA^hqv{cv~gs|nM%XSNXJ=XQdwNh zxr;+Vg2O({!(N&tP9_!w^~vGT@CB4onbtfm#>ZZU7Ph8%7-~s5DnofTC57%5VXnUt zZ7r;vkDb8g$5xij8ImP=XHPkD&#CG>X}+{Yfm(RKoAUI-ib6}0RG)LB@zP_%@_(0D z2M_1$g=Trc7e+3pIUf7^TR3a~%9Z$4Y$lY4EmZ3AP-3y1pP*G@^;}GD80)B59G;RJ zW>MmG9Q1d%H1DIgU6SoRoLxv;oPJzP9acu0Qrt3JRufhlR8rb=oL}8sp3Q^TZBe%T zD`zn*ycj-n#=^RExMat|CYQFNU8?+O_+#^?cR5exAzlRyM45wPMcc2+{a+Q-5LNc1 zRY?|A)=L#6zEyVFRbyIZkkVD~%@v5x6|{#{*OK`YJULVFB?JgrS9o}6(v_ri)pvMk zC@)|vs+CGcslN#B8S^QHSYQ9Lgx91z|5aWP@s3z^W=JVHT z_T#_o2u1u?&@>+)@)BCwy@m&&g6(VVPzt)C9njehfr%8dhz@9o(o%-d+(Xw~C0!tj3fVyiGw9wTl+uz*=PP~%ERqHqgGma< zPi)*iQkx@Kt@!8+3T-Y~m2%-ND_;Yq5bPxEL3BRN6h5#v+U*nW?Q%)&SdHzpo9%8{ zjZ4ynw{)m$Em#|L=)p0-B1@p3VDlS7<#o94J%XRq7f?z|6BRRPdZiN_-bMD<$vueS z$J`Ya4wL|PA(Yv^YX=du`pd+^Qus8}GI!JJbmPt`+#lQfDpkz zECS|mcyrfDvcPMIYee@Cf({j-wxW^NtfxW2)j?#`PKz&{{9C{|{05YgA$`eV#I7Op ztsy>p5dCKR4qbNA>7YO2P|#_UYFGO?LdQ3YVR!Bk6yIU9>|uVzPT1BCQM{3|kWnOv zQB%@Ue$uWY?XH2-k!qb*;A5{}1g4)|b80vc%cFF-4C5Css@7@Uf(52q=UCKB_omF) z(CPR{#F$horfXJDR0~j&{#UC<$_wxB>(N17#a{8WiSmUBApAt(>qO!zrm;b9>Iu-D zV7$$0%m{Djbp=x|qS?U84d%=-u&mah71KPT*>ZFWZES+-3_O8V-l;D%5M?>=oHh+B zJB8djjZJ{1dD&8jKLg^Mst7NsYi%}&9ZYqvhh~@|TALy;pE;Jsif?U77)9B!nwBWf zr=YX-Ld48!ZTd_y{9HII3_CwsG?}Y|RYu>g#4!K!c}jb=#@Kfx^`%{3cg|3D!FX); z!4fMtrX$r7*dKwSjD+gTuxMpH&hau&jWPy@xM(3;^pipHJJN_5#Ms*F7|fSNWZ$J^ z-NjrX*trmt@l%YIh-R9YiInvD$g>i4KHT6ch@zX{n!1?u5zUVtOT}mCACnVD39fP{ z0RD1W`mOGJY){ch55ePN)Y=Su*QgLYh!C(!jk}@-CY}7Gi?TtDy(WHT*K2sy*HGu~*z?D~$mUnP~N(6^k*w8QXaUlBjk- z3J;%X4TTZQM`sp$e32|;o9`DMmDfUdIhM#-qu%8bpacLg- zxdW}imoUUvqZyau6>HvlOVATlxNMQOEgk)bU(-y@I7L;SzGI z>BcQr=0gwBG~&v`-ulJscrO_FPRHY1o)Cy?2QVTxz+Js}ZhO=szT>t<*+KxqZUTsy zfx1}`2+Y1p$iBEl8Soot2wm+cmw?B0So|zi_0~$GiRxJXvCLl}$V-TGWM~0Fn49d! zP=Ov$v38C<|W;h)b;%X4Hookt&TwWjeli` zD%Sep)O@8wb0h!PYsVA%1ry~P$uD8n&->ceonVaKXrXv8f*l8_*deA39+#&_5K6Ws zrWLvG1*H*mmRePfYU>Y=G#0jqQj1dR9@~t=O?%ZlZZSJ9ww5FHjg<_3OJN`-04kiB zAe2ps<+EgpJrXhSMX?q)In|+&mX*h0sJU9?Sn9IEVP~j1h@@APLG+rXfsJPSTBc#S z*L-ZL1QE>2Ogfw=GY+*zPcO;u=+D|Az}6-r4cesV@oDN*iz{CNesg?!W0+)G z*z8P;15%iii!VRV>gb8rxvUoD{?tjRSTywBY4O3Kl2w`3 z@}ClR9dI@j4JhjzA1>7kBd>ons$?N@Fm47U~89HOE+6_3-T!~9AurR0mU0)jds5NS_8&g^!ZCO_8 zu&n00g&@O!I=KIET%#zht@aT_p@*xY+2zq`I@m8iSEd+eu7X_fPu=W*m>9BRd!dx+ z>(oHRcjz6qUnQaHJf3;Ywzuwmu6K33&r1UdZ+3nHk%ONYU{pZw;56v+ z`$MK*hv-=nAQ1KqUy$~?QC1c$s3cP~=I7+jrtRxqnXCDww-;mvY-R&L#&ZG61w3MB zTwRxxvqB(US`s7;YeH~xSWsN`7E%*zHy(em332Kc+)jcpX$e!XK)@*KNH?ytkiCMC zm60SR4lNyjff-L}4jPks2R(9Zpmg3i_DD5rWayWlGW5Anp&*fKk#c%v>16y&m@ckr z^QZ`664BQAdJbS!AjB!TWc?v7;dqd>$yDmt?I14~Wt^CIYmO(pdP0wNdALV+4h552 z|Cb!o-=f^z>#YxxoPkR5c$%L}D4z(1{scNi8}B9SJV{0LRx{Li$ej#>(en4%;-dcS znuvOE(-}XDC5e(2oH-Qd>r$dy=Xn_WM2N?KEk;iIBvQamQ9T+0g=UYs{Nqy$)tGG% zbJ}(U2FHUd*>NP38?@CA$_+UACWCAF{o9b2;pviBSx3paT~mQQNlARTT516wV(1mk zUQbFDN-z{fEQSUK@oQK(Iv*u2!|_1ik7x<+!+D^9g#;U!L*7oW8C{~25E{#LmW1%3 z^a!T1uEkN{WgLaHv?fQo-c2Zp=qFMFtR8)M_Eg67bW$KHs95SxiTa-sGB+t%&MRhS z6m&KI_o0Dsh|V%oQ93Q8FK7-ycLk%dMv6KGr48^jg))$W1cy~%_4fNe$bdyz?V~W2 z7XvX?6&)n+Qxodiz zX!5#V9_I`)*-Q*zj2a-RzM88%o-q76eJqSU_d{erunEGJi5=9o$uc;@Xks<|9cf^J zW}HD34E~gG>ybsPu!7RNv_OHai@GWZTjH*=(0mjx!cE}vw69B0@CgN|-~-Lbyn(Pd z-@HjM=jI+Gb(a#-#=yFk~QvrLMxtz=LOlA}tVHv!IQsVM#VSy6>Fcn0_&^6@)0+g8W zS!%i9&D8ZfS2%kf>Fz9#&kc2klApv32}2=hpR*i;(9NjTOFldU6mf2CFa#bq6s zLvndPuk&}(lV^5=kT(n9Lnl&B5k76iodFi-F>UpaHR+`|2<_*ZwoWR68(e z(?=7US*Ki&HxG{UXg-jtQ&3?G$glyxDr4R>3?DrAIpqn7SZ@SzY{uTZ>_MpIB zM=KO1_PYDca@Lf@nuM^GWVg zrTof9`aRW%XS%v=?mTDJEpu2KyD8Ik(gV?zzB>3)UgedmE#r1le*b!ARN>%;=z(>C zf8}QVt&fcFam%*lap2v(;x$F<@PPj&bpkvHmAP*`^VKGrDRUGJ zH@-*INraRBo0NzMUwm(FjfgP42t%(3j}^+-S~Ok)CbHEwsncH8)n2yOUS+GEZ@VI- zx4jZjqAwxBNsXd9pGA`-dX^AMa3X{-RcgMJiDp@f$P$S4=ZdOF zh<>l_HzwfzktZe=A-0I#SCA}btkQ2uAnuUY1@kIu>mg=vDt1II#;+qTXeB;>BA_QF z?k3a68Q(|fAzm0R{tNut&(y{5ZY6d*D2f3m!CpL|-Yo9(Djw`Hs3bDrciSA2)~@?n zVHYsq);buF7afR^AM}|&It@L-isuD=D5_Qhz$OVe5r5T|r20I>hbs}3C(-BL8=E#1 zHzVP_E0M4|L{dBy(<(WGFf7k4Man8_57p%%B3jtmn-MUS$=01v){|YE7Y{X@6hD-< z+m}c{SXnllcN)=xM^jE9UC}D_mv`ufPHNY9q(VjdWm>ENQP}aLtxM1yx+-QEFl;e9 zqFFW)86ev6Ds8jdn*VvUC!oKZZPY|XCeumgXPV4#o?z82VM)C7*s4rJ_-JvNjK}xU z{#Kb{#E~W^G4QO+SnsZM3tO+}?7(+k@punuaQH~w$6;CcGD8Hi&ZA>th$892BjW*M zh4kY^tFn`)vQxZrodmVJyt3nnqSc=hDDt|O1B8#$u+GxH&5Vvt21p#G$(>+`oVNC? z5KL^ulV5xf_ZN}4W0N{x?U~mZ-S?1L8XY-!9X*7SPZyEbh8ikkn^1h6m^+mZ%^Pd~ zEc@yq`?A{d_By_YI030TwCPd2)hi3XCiRHHcb`U#JSO*)hg~M~8BtaqNmd#~^ef0( zz7$FUl~BPhU>xMEFjA(7&psBsxRk zJPUQEs2ZUnX`(_!Hbb{J^*pO2LpURzKc&Dfr_48JbvnyUG0S1Cs%|1H4L#QxA*)rc z`u2J5v*%p&>#Sys0_EX6i^tUI_z+^==f*e#iTEhWyy+RErS&vM>Vf+noU>BC0#u$e>rDODLGv;)kGM&PqA!Ft7>l` zm#?Eccf2phEI3FTD^&4Ugd1Xh(gPmLVHkjjc-kNy?ix&Mp-XVH~UmK4qitseHDda zy@o=53sG-hR&S3`FOpBMC{kwvX|3{2b!l!X+j{aef2EPV^T2bh&wA~MPqS2ZWo&MJ zIbV0RT(6#8e>ifT^G$ayReS&Y#(kS^9O1@mzS7@1-HSKPbCYH8+xi>QhN9|566U6Q zn*KB9Mn$?V2&^-yYTz=uHm*h_JA^f=>p%~bJ%FC#bLU)(K z@CC_8Bi(?wf2(|K6R>XByktOLuw^f4)M#P=*{=04W=KtGK!as?dbTZUy(%QSb@*b) z4Ws`Sxl@U_bH}rdS7AgqzJ1+lY%^xeq-M+1N_6M$ z&1h`xyIjx)+5L_f(UbtpE^ERrq|FY*j~&&YJ2F2vMecW{)b`Z)_t+9lh}ysNA{(j` zZE>ru3i5AJ%x_E9@5*7V@xkaQ+%qXr?uaw$8dB~uM46~D{xDAH7meDY!_reE+T*$J z5EfI@2b!$N{Wo^s`+7lTy!_QQ!TX z;#Yx@M}mPL;~`Ph52K8|z#oSXclwlKCT{&E-;qs~gUqz$OoGSFA{jTe=D)k{Z$xGs zO0*wFx9_nR?EY5!ZgS6Q^Yb8OZ0~!9(TT|q@e1?Q`yYNDM`CRTNd;z!r#mJ;&CU6L zSi($a*_eBuo963Tc#hAc7a058>lRRMCnxCpGa44J|1h&L%|Skj$1;y6(so2PDG@U= zB{B;*w+P%nw17FPEZB?lGWio_T9sh7`~B#;$=pk9ICWfG(omN*>L~2oe4x%kjN?R! z@wDitMep8;2ChY=oZgk!UE{w-NJp62!J6vd#Hc z<%0|e;4%QjkY6Hi+-z2d2X1A8 zAE>cyqaSXtn4G>5KMjLjzJXn1E8SW#%~FDH^yP1~2AoC3Z~PA&ehavb|8Yp?bRZVL zO%2XZ6TeLKzMgJ(W`+GP?A>Kh91XkR{T^g+C&=JQa1BWa9v~!0AV3871b2e#;O_43 z?hb=HOmNo(*94bgC(nKMsoknmr_OG@-`=H)PfYcPVXA4mumAPC5lwK>54b7pu!!!k zQ#Z1zc(~zyeN$j`?@MwJHRx)dse2Lh}a03@09K$`YRXjN-5Yzq$GH{?I3I;KU@d63xT$8Q{{O?Z|1V%StXqh7^q>H2$726^_x2@>djLupp9LKWtlEjC(<89nA-18Rp_P!(+t;^ zs^uC7n0Hht8aS8_CkXAARMR@>Tbr#r``6_bw$=H1?(?M_=ASSGm} z{}x;>$X8fExL-j|KgCvfmUuee&(1?hPPga1QW>w1Hw7f7b$MQI!%tZCE4%ME2w!{;rt&I>4CbX{-Y(uIsVTg`p)#>oIb7{gbFLYDV`WUD zO~1~K*UR6HN?ogRW=^+u5n%pgA3T+x;<9D(E!9obc;=BN)6LK9P`2iRthd*c#2A_m z^ago}wn?n2G4I%-3g~Q1e-?^pv;8Vkh)@1fm~r!MrdX(tZL_pi9lNMRtt z#VuSdht0QKt*1jm+->IzuH5a{doA1@_cyoPFc6L~526#D%8jQBi@lYn8&Bwtr-$hM z5*a;&2M#<^n9%DD_cDh8U>oC+(}+hp!o59id~guG4UeK<6jkm}Hkcat*o)%dBU}?2 zpbD!V<|!C4pvIwo3@3%0@uQ<+pNufjV}JAYg1_QzgH5uKi6~CI`HqD-7$lix*KcPR zS?6bcM~c2c0oHd|r0^Dj&uNeE@{+x)cF%c4Vcq7nVq-Qcw&L(UD3BEA#lq$a@5SiL z`B0qjEQXIfm5u8x>Qyil%BLs;=#=nv{_S*}DgF>uRk6#Tq}lCHcCw8Sx#LQ1*DgU& z4j%hyp^Y*9!b zhPOGE~>vHag=W0tgqtr1X&#%Fq0tb3CE_qe{vS=ze*W z>O-(jABkUz&j`bF*n0Erh}0=qo7cDD-++7YYG3kXDKT^hUnY_gm~4zQ?}3y>2ZI&_n~;4w(Z6& zyvaK5JW-Q=(aJ3Pr)b>$cTEQ3j#&(q4emu;n+X8K~cxY*Z8kn z7%w8CfAW?8XjcH>5)Btwu*_mSc|alz92^fXUp|P4_yH~t5)yxN7%Qu5I~QaE0|0*$ z7%3nK0FVjHA_m6a{^b#{_wNJ-X+R)*8dlcLe$89WPeR)2=88E5?0dE8RN+}MFpv*;vhdM@G)}BK@EJMmz zUOzX-DX%#aCr&~rrQ?eeG6ur|6)74VK=)l>f0XfK=YDz&;(Pp<;UKvmVgSCXVZc|5 zfoTv3Y-jC{J|4w@Nr^`YNx0j<)D-p2ttkSULRx(${$2mI*MEL;M>pnNvWk`Il|rX@fjwi$y# zr3@53Vqu4!TcMHsX&C;13KDTZn@@+H9xlWe*qom;0u-1N94UYkn;!_UCfuR#ROd0z z2&xO9OAm}+Q~_d$=H6-GQNIr$Wpr_s((%_qE)sV{qZA9e6+vNOa9<|kbl8W$mn`h8 z&BUv~tu_I9!H81FVg?&6Y!kz22R3O8fM@-bhTf6Kc97ZVJtoblmNkb(M_=fBHfi)5gcIROLC4HA9q3>L^D6rAL<0dmNXo<-dMI{L3uy1>OeH_mQ>e2<5eD zV&dE$N3`%)`rmpurK=QoL@{j?t>#q@T+THdSAa@9=&Ja4^&1)s8BH(-Ss;ekLQfWZ zD?OqK-Ng8hZ{@;luiuiqwVnYneOtj4xkbCa)8;uHDi3)V8ED{g?Pky zR8|)K-bdrye?Yh;DUt_nwm}lY#Li+Z_R4=)2X*mNpExzXKsc4}R`J^a;)} zg>0YAY(lkZYzfsLGvc}@a(!W|bRp{@1D0yj!I64$<2Xj3sX=aMGF)PrP`y8i(%n~W zS$dm63LxWdsxUkWZ1*2eP*b7IkUA-EBjb>m=my#!2L-ts&I&R#@pP!UwS;0gF!Z08 zK&jfF{A~CHJtCe1&p1$pOEW2!?}mcO7I_gg2iWewL3kEt*XzHVcggajBy7Duujy*~_Ui8dZdX{&Xkp}sw zG-V7&D?gzCg&1mMjt^Ke$7_P)qB7jT{2PN=AWILHj8spN;j7{K|4YANRu={ukT17Q z`0x4+=UnpC@Q}`p?zRi4mD?r5sz#+F)8+D8_uVQT=d;<4v%|L@UwPLw?_SYjcu09a zqSi%dlU^|rwD)>1KhtygJlBP{^43?QdR<-9iH7cjRN&iGJuN#YMrIGKpzV?fqMYvD zB551hZ`3#xDcyZPVK(6^p*WC?p8g8>DZei@{$ui_{tGQD*C=6vCqCVSt59ARs3tL6 zgT&A>>^EO+s{zw&*U%HtAGXF)Jl?O}BSsgzoITXUd-@vI zBZnvYzI)uWzJ}v$iAW*=1^z?q>^W(hv3P$MoXYErh2jubc6HzfDOqK-v)=Ce?VQPB zppI9v4O7ObXDW;SCGTeoT;&GHWQExI+i&++D&*ZW-7x!dy+dqum7du&cpZ-~9AFrv~{Z__AQw z{j2<@%HpDSL+y6i`gf|tWubh>*8O`++x?W@-}sF|hhZUhIk&68>Lu*9%+ibbjuza} z&_L;7?fZv(^?Iv8t~@L#kbG%_9OF6xi%TywqBqZCOG|g({7i~?Y4R1-#A7oY_E!@#h{YV12?F$ zSG8N-=cRi)L&WPK?Itqt#j1Z^YyErtw(uc6{%y=Mp1tQQ8klv&ZO{ISwI3Z~dH3V0 zkXH`Ev2}I%M1ih#`CdDsPDkx1i={>U=`m)1P1o;YnA;Y^YlDW%)IUq`yA<(btRa$~ zvrs}2w$E1BGY#oyX<}_+-zqR?=>(7WDn(cq($69`5xte%&zBz|-+|}tr=6>4hoEXV z$sLc04h)a8(dFA%I*;u^g_Ac;s-)Q zjNB*^z5E(%r!Q^Mooq=Gjk{kFTV#SxtLgm-q4&hzVHaNXSDy6i01bji054LlBL*tJ z%(lbz|ks|a4Km8g@%WaIa!>+@0S^Nw2c*@1(VGT*=9$2?YYyMVnt*Y(43a;t~= z?kj@v;L<)YAY&3F@${9UlfQAIziFet`JBJ)6ADX;09*cmfBXiML=LCM0JpgS57hvd ztAM|LgHwS2r@%m@-{9mQ&=}}9;I|`&ArA-m;*dXdqN4aNJ?G5y1B^^40^j&16b7j$ z`lMW8MXKW4>w<87G2a&Yj_UfR(}#5OdHO43JxJ9#If~fYPohy$*j7 ze5Mkdm>A@<DU8-?zm zLA`U#h->5EheGTF3W6j4sNBX#-0R3$iYS_*C@R+I@i{Lmm8heDXx8~K6d6D8d?+_o z%#Cq$#%$z_SV$@~W|S|2P#_XRCW=}hj5bK0o;CKVNraS%{jKWPdkRze-PjrFSW&Fl zHI^tDO0)M^4t#?iY-;#Fub|k@aZ4=mU+2H71vzN!dTNU`^jNNh`FDI$28zNJ`(w z%B03jr)9}dyGSh|OPdc$&!fyl#u){>>FOq#Spk{-Cvjw|sVFy@2b9qktXak~SzU!0 z+C`b$MOlB>e+9=5C1p(_2GcHsGT5)P&|IRQ3VtKIF+IEfdZCua1Ic-98dd1*EFg<( zH*fRSG>HBt{zT10rrAu$lo)}PMGMKjmdP1b%Y1c{#H*gIq;4SMk~c7)Mzdh{M$k|J zf-B{MW#;moNj(F1DEpx)i+v&erFzU`^)Tn+g6^hF7Pf-V>Um#fEsUC-_@C7C7fte>FJ!M=6@;4>B|wTKnsbYq3heNkud_3gi;$tl zYEmBGLLR?MVc<>PQ>7xig`#xiaRycT5)DOvWyh)gDPRW-opHMIDa4D<7F0-jG{0PY}Z!QsK zE6w96I)awiV;8L!mkhHNOYW8C#25A(mgs>i<^;>PWGkNcmzFSBw!`zG>y;M^_*cQD zO+yverum5Ad;lknX1{9wraWw@>^EEfo_YmtixIwAWp{H$2xWQLV7aDR`7g?9UBT)b z_3G2&nu~<$ipwhU=4y_RYAUlrUZF%xjT(2C?7oGvKQ7fXH^q~XbnKE^8KDe5*OE6> zb;66)AE=6XZqucN@Ce!Mi1%w6Flq$_>%Z-nziKHHaIJc}SSLwUPa<2hqF5i3*`U5% zuO3n}WQwS=rE0i0ZD0s)z$mUaYpJ!yZtx1J@=mE5^sjGWt_|NW(|PaiKb&j6m>ihW zsHRZ~4QcYZZHzQ4s0=R15Xx3bY4BigP8cppYN^S4U-)*hGz|yOjS8#9%%Osv_>pU~ zFMCt2Mq?3s`InHolHuk;^+fsi4OlpJKiKPbWXlHkn}c1=Iu;EzgxcWyZL5nuu{iGY zIC)JaEsIn>%Vu>G!|jJu&YL(M@wcsY>@80mTktg6yZJiKG@?_4iid^5?^4RAQi{=p zTePX#hg{3S=55C~%^(gK8cyqe3yc7_vn(X|G{qEEu8v$Yi)5rN$E@T0ww9};irEIN zfY=Fs6xv2aT{b%$#H55l1-x#X>!P^p94YBe<*8a-L&K{C_)2rD%(}1-y130fm`}kL zaL^k~%+5u8Repj`p)f4-Rz{Fm5DZ{?;~#z%V13oAFWd)}?lW}jGouJJZtXK%3N*j# z(?96577h@_#aAEcdSc$gXkN`M+{9wj|0=cL&8(GAjh!FKqbaN--r{fT+ z#xTNZ__0Qh&&Y5o$4IvMh(40+xg8uX9ks$4DQ_J+5FTOS7<0rKB@P`O4<7Rz9*rv< zZjo!94DDbu8y%nNq}7Ctxx##@N0skJa5drh9HYwzqu7VT6DDv%y!J;HKM*+M0qo;E z<^weH@D8~jcXx0kozg1G4(=ZTzt8n>ySukX-uYU+$FU4ecA-?;S^ij#0W>%)zUD& z#e{NM6J)eW;jl@|J!bcIVr-;N$fA?BtVblR{&iX=f7+yo`D6_X0$$ZTt;zYrqj>B{ zvz0MzJTi6KQ)G4!caF}zqsqM2B&^-}en!84woY~4*J4f@uigj`X2v=7HEfRic0N~l z{xoQzs144r41agnp2ImqkE~agry?vC8^Wd~%ces)7b@@;BP|xHOBd>?7urQKyEy0j z?h}Vcm%K-7A1}}6%1?jMT3~6LtD^bQ=DyTC3YXJrk+XlQsoC4)K37e%G+WmE?HY_5 z2{IJJFw6wuLSx!)G0(M}EjXuLXy!s-pcE7gpGr`%ch6|q%=mI+iq^8XE}#rYVI;&b z1<*8fl``)ZZABJ+XqLl5!2mtV6CM;KI4f9*`t!|NIO1^n0=EUrW7-D_MlQ?8KmsHm zQ1~NJUq%A&crcjSmlf})i>YTy4>ssTQHTK0n|2gIG0>w-)Yp~ZN8yVsV+*zS%hbVO z4xXQMv?v%S0KG2Cb9xY#HL4)bh8E!@^Vp1%mhtWV4~g(!Z@7?Y!BcESkO0q?L;9wh z`daMarX}7_qU9}1#5%Jg`aKC)NO#*|1=R$$I$yR-fxleW76ql<@$tYkCqxSr-4d!q z`^C9Di8nkL)^f_XYpJ~(q>CXFx%>44n&8Tu@X^wn!{yddo!szW`D2)RFx2Amo${3( z>*eJ#`Cmth`)@>d?k6#A>CuYIQBzkod$g7i7~#W^a{L~y9p4XF?<)`9&|_2{?MtQ2 zwS+BqBR0G&4-+Hzi^ovE>aJCc9Yut%O={y$i=r@#p{GP145y>HA`a#`eo@lyZu1;B zjA3b29!S6r;VVbCN5_#|2b=UKU+A&FX6`4Aq3TDTtl%#Vq^%5u;G-y@8}ngEMjqdL zY_)~21edLV6p&!>0lO-;mi0~&Et)xDWpdkw;pl0VKu_9)LWi#7UK0rs@&h%2(slaFw->w$d>J z^TChPcZC4(g6p4C{5`?fV=LAd#uMciQ8)1jm2^o|DcI3*l*) zn29d^pTL!$g&gPNDO=RfrpF?$kbwQgJ+^tpp3oY4FxzDS!BI8Wk*w!0=kcrdTWkkw zG*7xK<%h!_^P5i5{fW$L%du;BDx8Rlz1Nvwg8kV-f`d=tx8s?&s_j>nY&d2BTBgpH zf#*6IS9ex=M_|QG@c0dp5KdwHfm8a~Hr}s9#r{3$b$8}nZ~3{s8cs*XZmZ~Js@6=B z=4>1l-rmD{>nfrS28JJBK;ibU{-@u-f7N&O*Kd$f3)(S8`VE6JLGxJ6JA|_8rY^z7 z{K@J!gE!5AeY^+>4UG_6`#tRUCJDKy)TM7;^qV!ArIu<2wjPWu-rY5_X<4|-yWdlk zjk22Igr^KGyOZ}l!Ci_`wv=AM@1S|DbG?!-pHVR$SYg!>u|w6U(WH9c!o(~sNFx+G zB7{ju+Y|VUNqt}H*`{#l8OIR`zcpI9V5P9^ezjshp#bqq!xy^~lyXMYUl(GPpRdR{ z(PIQZum3*Z;2};TsYVCi>PqoPdG69@B7wn!RCCE21HW1D z^F!z11_NAph)D@ARoe-HHy@dZ($p+Xr{h&xwk|*B7)7ZnF~4o%!K5;Y(Ruy{?~was z-G^@xQTX`h_CjhBuXf{;k(!n6BGd-_A^y|a1!q*r7)|G;dZlebnIOrni~N0iEUV+@ zTRZof{!g5X22w}MYU?Ro2naNFU^_z|t(r{1JPH(@3QzK4vq{ zKQ~mfK@_7H>gYgTFa;{Dyf9+by<-_6Fl|&b67h4XUe8io9$ex5cJq`mBdH98W~bd) zVEoiwqHdQV)KE4iu}>KCAy>v;Hkd{__nYLiuU^<##nJU(_D>o5LpVj&Nkg%vxpz%) zf&)cW_9yM>Nyb%>Uf{L;%ML{7<{rKu&>V4vd5z~~RhKh9Cx7duS$mI6N zyIu>H_FPHakTq@IV}_NPmeRs3O&jm>y4=X#sBXNtF~PSRw^UtWPfJeT-FQc%KpcHl z*bENiyWZ7x9aQ!(ksr^U&|LbLMl|*$e?*Z{|9r6FBAZ+Lk%>;~#h<|1=#ih@X_CUy zP6)$%<>##WnV%|^{Q0PBU*m2rg$>Rp+oEF|Pl><9;zGluqtfD>dX_C6Aj~^?%FoH& z#1gBkVI{&WVwfxL zRj|nm!!o;&+!f+qj5TAJ;B*p+3Hm{*hwJ4+Zj|jqr#oMcspu3yTCJ$F+NM<6U2c3xGdn4RNsdI5mm{Pdc#waLbP=!D zM~7W*p8JBvpz)XM$BG-M(UF)+qFt%nj~hxR!GeV1AU126FV!<~WPDx6zZ5(zFkvVh z)?O6a^iaOVwJhwwbW#IFDk1Z+P)H#*s#_(hB${3+9~{7qWgw!7od zAYNVYRi3rEn4Baq5Q&9no{6Vu3_E?XDPnL=NEVCjj|(RBfmmnZePDr+Fd28dzj*c@ z418r=s08G60qnrJ%^$xLS-d#`d0a1{m|(&v)Q>EwFDrsZ%}u|jEFsS{_uHe^!QWGVauf)RCyhQQ#7{dg zFA!Rtmj@a_SORcyqS9Ueh0gC8cL&S@ox9`6O+lHfPmRU!in4H1pE>(07Cz1=98w}f z$%>I?qKz|v@+H2(w50carZ>+Mf*+Aoo{}bGRuIU?BNpj<7RzmhE~otshD9;;i=DOU zt&?J{SY2tJG)|TmK3p6d&$#acbAYsJToyn`I!`|)29@#Wir4(M^+2k^-(wI*WCs@` z&XbiTVtS;k$Rb9vaN_@bsw$74ri3HOBs8ZlxHyUT4Hy@>U<{$Fl;k%3L^FnAcJjQg z%!jd5=V2%W1_>#z3@&o9HGS37E>YF-m7|b4B(qEXcLlDl#3u#u`Cajg>Uc)Z8?He# zFaQI6;D2vCsG|N>PnohN4$jNyit*e|7X&nlk$RX0%}$urCKX$R1(x8gcLm^64`>26 z{f!BHWKGp!oP5@|U=~gK3aUg2Qfghm-%z6IsM0bkwB&Jv@_7aRS~+qN1_t2f&^qz5 z%hViS&s`1KZfqymClO9dlSYCw!QFP#7gjF^sCY4FUv$`iNANd;xGF<*O10C*=17U(>4n?4 zeZ56k_hTwULW6ua-k}RLNpjhWM#~k_pl(o|&@@mR##63Jh(X(Wlh^c!PShrF6*mQ9e6|U zTeJ`H6jFlP5VbWK76)&vG^T>v>+43{k4D2=5DC*{zq32qo|;so%rDn}Z`?$Jqhl$H zhqTXIqf(E1j#8F?9sOw$Sl(qLNF^M7*I0IpXRT<}vW_9u(88WhAUzwhK}PVrCx-LX zQ%Z|_Aq;zKN};$8{D(-l8pGh#0a->3TEfQ z^OWx{my18&GP_L9vY(~-v~HKTUw?}!Kl2t^-qBobZvG^C=1WI2_qoGmqC5Ps`gVKU z07q~x&++Zv*m`RRrgQ(8em{d@x4j*vZIU;Du<#kLMyM7Y?oS zSRL2KZ&rTWMF<~#;dYv(5=zxi(7E&)PX9f@?0HSMbh%XFewltO!lp}5ep<0|D|{>*F?oD!Hs@b$LQJF z;Aw;5(JtkVwdJvR>Z~3Oy<~P?nswEWxx(-w3G||DbW?0_pMC{Ro%Ni~GVdmX zjvKkpGJ9!VKxq@bS$6EX2fUIKJXak(P_DfAFI~wSy@=+#xhQ-#3Or7#pl+QW*!P4<{h3q)HfH=3F8nR${M{0r#rS;;8~yfY19a;BwJE&YpZQ8& z`DGe-DF(WImi97XF;^Jy55o-b3w)U+N6-;yJ_{fTrr> zz#j;n^Ga|EF0Tp<_#DC!A7J|=xUev&o+6-lCO9l1ge*GP-#94nDp=JiU_{j`pfI2V z^F@DSkf(I8mvlhYRZv@CXv-DhlyT?;e^_duZ=SL5l4@8lh4COo*bc?t9X>wWVZ~3v zIX^{Q7>E7g3#Fe6^)5t&g=2=b7KUH(N1_$E^A`I2Kq|YK5&QfRos*H^`H1#$1-%7&enM3kCO zi$Y0cLeWj0b@G2TB1HeW6~!~?i$fXwo8Qd-L|jrWT6i!*kuvU)fY}E)fJ3jO_azoG z7yZsTmMzHG3J#Y187mYN>#>7W1!CEmWDVxSO|U5V1h8zeUYW7#TO?uP!ay`)@?dlY z;8%hdYvM!g2Os1DpCEZ?P-2KlV(?&Mgo$D}R?^>x599-U8Lx=z~?z}s<-Ixq=7!(u)PGCFArLn?xG^I?-o=~si1H>}Ke z*M^9s46sWkz-G-W6Y(1>Z6zqRi8XYC)tgj3i`pff7&{7ci0elYANHOB?oB32ayVhI z4}misZF2_MLYC}&RIOSXvvV4@OdOg^1{)-T!!-3pbF@ZKnxIP#zq;Q|VV3c3=H`5E zPGK&hZ9Ya}DEG5q=1bW$fuZCwwcKY#X(Vjf6OVITpZRb4XMb?X1tsSb-Q+P~=bmEa zJi|^mY|gE}&bNl-rw!&TCKVJ&WD_^#sH$g*3WnPxXHq~+jheIE_X@tMXVBkdhnkYu z1$~ZY`yOd38o$8l8JzN6(8j(w+gH6XIoX~oxyW%LQyEh1C78=soTuKH{|PHzsX4iF zDDT}(vFTiXRB$mXTQOsBVN!nK7f6ZtLJ59jNkMV(>*mstq2gK95@V;5iut_Bh5}ue z(h%8Vh*EwATVAzbnZ`|&3?zNkw6p`euovP1m(6VyEI;0hYc?&0)Rt|jr_W>O{emFM zs3^nyR{gf@Z z2rd{EEGBU^0PVkdykAPhUiBod^vtxH0jCY|03 zE|Uzmg$6Z^nkUIM#{xCXRQ1v>4Q$f&j3IR<8jXprl{7*PV^{U*w@n5PjdKW>Ci3P+ zeMn9AWurV5@*~nP4%8++u6?0V;q|^Tg}p&>zoO!OL+h<^PD*Xka6_J1v*vBBwonsp zOG`U@bK+2S&-;8=q1F!}l>@`ArVB_TwxQUpr9HXr6LuS&dXqU-yGBZ5uvzQ0Yt^7o z-O&(obx*^JUVW%*bDMs)GG9yNZTs+k@`+j95L@dHp^meZ_SBLVhec#nRtMa6j8nl( zZEC#j+grC<4KzAxY&$75VNGUjSemuBAuy*!7@1}Z#$D$u&iBod22}G7j-{@m#h~So z{8gOtsFbc#Av&(oP7=-5M~ij)Azd$VyO=q;2tpcvxfW6i7hNuXLtGCx^WnA=+!eBM zbjY?A3AT2d3U$S^_sVE?F}c;glWW#;t5cbVdRh=A-RUE^OIE`uS^~J42Z>alv+cQhDO@9k%~3P$kIs4 z=hW_*(Ei-e@qL%pqSmpURygkHaA<26+UU5F`S=8-sm0ot(q1c)<)NefaXO(9s4@l_ z9Atrf)Cp4t;r0Dqg5Tf$IDTc$oF@DMkS}hU7+snmwHV=PGn0_PlvA9nDT33|B&RM7 zW(u1zi=hAL0lBKl$Lz}Qp-q3HQH++ER&oEJ95$`N`N1x8S`%+(>FKmyn0%E6y#ovl zj~+cp7qmc4nV&RCBR`cCYLt+aa=kTya~X) zsD=+6&l+q&KmYF6OmfLwf9oWm7KZ}^aMtFN5k(U%)N^~nvw0R}^|-J{?gQNJEzcGJYd#aO z(PPFjPBfBQ73Y$-#loTM!WqX z0J_L(73X57d-s|Md_!yew@7Vy8ocswWVdW3hi0@wYh)#@e>$w0s&!=NaAGNJ5hxG2 zqv=PcTDU7~1=Q==qbu00E00%JutitMJjQRzCePBcE@;-+xMnfO#!%AMBZUVb?dx9` zhx-|S5Vvpev=8*ickx*+{|svv6<$N&;QtJ<_!&RC5j3=9F|rN|TfG(>e8ag34j+6n z29r1%WBIU*pFS*I-j4QRJyGP>rN}rFV%3CeOj7$NiuRVQ_AgWIHTCp08IKK1{Be8B zZJ)!HHQcR5_bub{O$tQ6etPei`>5~IM#Jb&x0P+j_Eqhb0eP-p(dipz<=YnRKmCuk zxjlB`X@Bq^Ehf`$(YB9^(r!Mb-6+?t%cWhh7TpSN-`TQQEL~a7LTuHq%n7Ay=W8$d zeApr2+`pIKUrs$3qMb-f-)wE)jYVvxif+3ic5B@a=RO>&SZ-;4SWpY!evW^D!*uZG zXn*i#zm?@W;{d7}rjr z_DWCsi2_%tl6L>F$3C`Ixm0w;Sd&ev5hlrDJV~1yz zGk7(>F(-d>(eZLe{4Pu-peE#16X51s8$*W6E*L6(ZQRSyte5zH4_+{!_5Ybeqjb$595 z@>d_hxVoSEjv-|PQ~7q_Z$+G$XOl{vYRlY+%n9%t0ZcjA`?+H(*)X0KEVi-OyL}z* z69TTIaYTt8hJ5A>_Sc7C6ig)wN8b++UnIg6@^8PvQH~}qDLExIEy7M7?_+vyUVcGg zQE^FWnG!B8rK1HorBPX9Q(Q$=U_vvjGwc&tdt%qXpl`>}D6F=AY+`b1dZyT(OwN9G zId5cTJ<X5mUl^nZ};F0}FDh~xP>lqyq`Kbpe-Km7(V zA8Z=g+QJ_>|M(3>lLd-7vT3q)#s6);p$s{02~CLLxyq|)`0FYAR-w}1VHND=@yd%zJ`a+LD$g)^spLwU!t?mLr81dxIxv!rb<)(dn@ zfinySzo+rWkJ<6ft)t>XRi){DLU3K*Cjc^{R` z?4W9ZspOz~gm3?#2L6uyuy#t>?67Xmu;j3Q$zlJnVa=cYsPSjK*-_I@e#ueuLH+(w z%SrGfOn~7U4WLDi?{gr(0eVz=)W5z34ges>`T>CIAKZcq03M^^y#!wTuegOK0BG^^ z0|3&r_}@SaX=!t1W$SO>zL}Ys+1c5-y1GLDB~hIH%e45%ptwK|;3FA|e-Gdb3ws$F zK1fO;-oJnN{2759!2cIOab#=zU}yK>>Iwj{l0dv25F!b*prDK)$NJgX7Xe_C4A?{- z6$=Z=S|A{h2VUMIWE${q)&hAvWEb$|%Y&8{0(p1~iw9)K=jiz0;qmYfXaR*r$Hc_^ z=cWZxt4K|K$j$vzRP=xx@&6Z95fO3j<@JCZ?vIZ@``7UQLs7y;e*PaMdx3mOef{s2 zmfzLY|H-UBa?<}~cJ^U%5(!!?EF6!Gopg8qhj6jH{CE0)YwP&$^#A7O!~XuSUk`_e z4}Xw@|7U0C=l|98|KDHP|NHv?`W-;}7C8UUxA@ECgpfZ4U?^c$03o!|Xq+DDTL_^6 zVv)T!h(}#IP#R9ys@GlHt2HSrMMVHa(yA9pPeB?9Lr2qA6a!J9Nw53UV4tn~QF`y_ z`B4)Wt^|L6YqLg6*{cFbfN{W5MG6?3$h=nS@g^g;>kJ1VsbFL{EU{qGy}p z-|LNxWL)EYK>%qia=qZS41XlmXKd0us!+jemh882Y9`+_hNt`v z^J6d;W+gN%2YU^Sitseegcf`DNdcr-*3yxswbY(|sQIIJr+ z)fk{9Aq29r`2__CsUXHF8Nqql^l)^0rdI22K=b%jW}>NWs!^pT@;D3O0il?>rWVv5ip4j>pm z<*BEYL<*Ou&f{I~^xOIds22*R#0%iv@ID><&_FS8@=M1xJkt*!&BE>TA7+@3Dh{s! z8aFvy3c&z+g7!8+j`YlO%+HwqYz>979JJww3PaoUf6ZmL5umWbzy6q(ReXde|3Kh_ z*2262iJu}vhM12j&jGp>W|zO48)+8{;10v{8;fuMAa+pGPs<{n)gW`zekZRaSgYTC z_>SRwdxIUFg&d(1gH*lJKstPnR%po`*Q|9HMe@vYQ4F8I?tGL)!L`?7oU)PLl3HGI zx`E`y&Y2wao(pj!#HEO!m|J~-IdmZBOrU-P8S`L&W~`U%C^NUIXhzj9u)Z9KJo=MV zc~#RO@ifd0tdDw$_Pd&;(u)4|&2rThY7P$eQ>}G&x~9Ijt=FU*S~%te$Gn7IPe3pi z#Or7kh7UXJfTEu2V{bBXioOgMYF`VqXREuGn0#J4kwKUfYZ7xjc`;hywsMNp6uone zJnCGw-y}CF@1+Rom;h9w)J$rfkI&FfxAE|wU{>q%OFBit1D~|g0&+Y360NwJ?_NmL z9I|97Ge&9Z=OlOZRfcS8071NuWRlNTGw3dX^lCkj=ctGfY3MTIQ(lpvPlu z#_X_86u@YiUU|=~9jiC#ms0ubUhP;~)%ZkV;{`D@sKwYx$7YFvzm>?Shx;5OqA8Y; z3$-@GhV6gPFH+g%-=ID$iE!at| zeui;z4ni@bx>K)2Xm?Fp%+ykLF7mlfzsOPP$LK^%sR$F1RR)ByMn7E}@z^-4da}MN zHZ&iAlRNay=#zevVIFjS9{VjVYBcy`9#mH;3wgrH6MK5wCG;__^kXf8VY4>)8R#j1 zt@3e>RFMk38e6|s2BIxIy+`OfR`XgVjgvix5#;$+nx2bzF59K?v(Yk)0E;kNyL^=9F+{c5zr<8pWvadX)L;8#L1 zwnj`K#peU#xm24ypKHQ z{r31cZ-D>0$~?A|~>8-eUHPg6-mbNb*sM73(9@?`H` zCBtQq|LakUkjV!0P9*rB$rD;YKD3}s>VoQ2Bt=Z+7kegi#b3UcUVfx()jM6mXD|Pm z6QW*%HlyD8QrWJ}Ol`7fCKJRb>*W4OU!`}h|KeQE_mI*s1#SMbSN-Q)5etLip83>H zKAA$AN0zU97gy^Y)f{Vl%V`;(dA&yXX^_jsJ9UtCsyMp8omR8OUDiM$RPpm}Z=a+kXO z%F`Jx|Ix1RMcQMjahWMAUi)J1wxvx%g@_08 zBf6d&W{{^$&ufoEvz}XbaZmAq4vPcN`TI@2w%PR#!<$*1gAT{GlTTI;0=J@kd(0eL zMvo3&5u-a`>;A7+Omo4FMFy})O=q--v z-)-b4!R&9g?H_08f9UW3HQ(Rj%1{%mGoRbYPCd5LK5#8d1a9#o=T>3qF7J!ip`UDqgzY2j-gm&?V_Na!o&k6P=h7L7`j?9IQU4?dHeundh zO{s>>%!N)kg)KCOEnS6rM}{p^gm3VNyPt&pqzDfRB=d%&;jAfuiGpkSeNR~;@|}W- z#X!H`5S|S9pEU;jX*4e&0!_vc-tI(zog?#DoN}``sK3xv{RuBm^nJMU$ZoXCKSfiE zj{2DsK_nA}Br&ik{XZu<$0V9CnnbH7`oE)y_En8S7zLCmAtE`jqHC_A0Dqev%c>wV_N%kMCqc$@T8<b3)OAQJ&=DYazP>ttHz_yChQ4deJ$%9L)I z)QH``42GOqNr8UYZc4dY>M=OrJ9BcCf7(2vDS6x^*-s{IGAY45Fs8OBRns{I zJt3uZH?55|y{{>;#xTt>ARSLC<9s)@=vm_GZh8l68rQP~o2-mOtc=R}4D6uPsND>a zqD&l@%+Bj1T$l8PB(uHww3fk)ACy_dLuuDoX~jiZA2G98K*(#n%wx68b(zex>&!vc z>^PHjD(qA?=PWjtY?kCKe8HTqpe(w*Y;Lv`O!aiph18LtXx`++7tKki>N$MP*@DOHpETk@!N9Z*gH}vU&D` ziTOgYWpGZZsn0h-|2n}(Z=H#{P3;~nWJRbKdl#3qKngk_0YTV_KiJAVi&L~siwoKE zhnszE*<3>)q`m4y>)7`Fdxc)j8KVpN|AW1|3Ti8U8+{+#-5rXQ; z0>Ry_NQ=9>JHg%Eg1fti&Huc6-r48OzBqF(&ehIcCNo(#naP^LUddl@idvrWlv{zCY$aPcbX1AHQq_i98gf*D zAP~~URCXO+iuPOuh^WGga9NWD5sUT*Hxso66jEq(o(G7TJZZF2WCo`K9gZ7MNK0|88*;;% z>QbtR1)AUZTcvcHi;r4LnOba8TS_9DhfAABkDI?o)C@tb%SUwE2d&%Y1u|r;Tm8vO zHkmu(tSc%<+E?V759M0d1q!!y{m;=lcT1~!L2b;X?Z?(}^~W9H=hlwnPCe50?1;{L z>*g@)maK@D8MNj%xtea~`W9XAL2Bn3na}fac_S$J(z;qqfYey-eWt&Al&Pvst_njw zo20DkTA*#ev;$YLi}uAj5ajhq&#qawlONPY-P-kGr4xYOzR27TFJD)4+`U@TBdFVB z;@-nL+ClHx__3`~wyl>!&)Qn9{hMAJhiC6;M3>-by?k2x=g3~2=e`iKz8^1OuZSL} z);`ITep>#XO`?7{8*o=^cgiJVF=HssOTUgyFVy>_H;)sU*q0A`X(0DMW%d?DcT%M) z0IJbomRny$+2Dlr5G_oDQ5O;@3nu=(-l#`d^APT=H?V+4`ZEDL&QrAAEqXpQvVwf1 zCNip4Z=^vma>H$;MQ~)VX{3W?r2S=Nv}ovO+_2|p{|EBHyXS5~Pttx*Y%1~|`_;C; ztAj?V+;!{;9v>M$J;AvwBfQp|Tp1mM z6YAG*>p_X?ey1KV0XY$Z)9P94a6EGFVv|C$0jMoI0{*3KOJJMJunr$gf zRI55UDbd;(Uil=e!j$8SO@7$~4#w15Ta$5GA9wmFaeFH>M&CD#8G*4G&eO^4$UX+I zX?ThO)3gTF$W$}id8^U6W%&t}^eLan36!!~Muk~9uK{EhFe>@H!Ry@4=oH^+AA5Si zd*9->!nC{4tfk;0`s+;B-K4Aj0#tCJ@AvHP@A>aj_1Jz(4hxeSt8+#ebGBpie5+G3 zt1~VZ%Z2T8>Fx8XYs(d^v)=l1$mw(Bk;~kpie2%NH`EHc*6@F$|XB*gCN=H}RnB^yO1Tit9t^5Qp~lJB7s))(r%< z=6Tk+WrZ#J@r~8f4c3Y|s@$IfTrZ4IcyLzM5NSK(9n7E?Kdg<^9=Vb6?mOU-+c7`m*Lv7;q0Z@;n|c?7Yr zT@@Z*t`gdLP2YwRsqBP@t{#-{;{rD+(e{Jn_LESueg(TAcHho3qQ3Jlgu$B!7J7YHaf;Gu_ouUmV^2ik1Q z3+cytZJTDRoArvvbHOWPhzB6b!wkqF$>#nqhaFkUWt-@oC%NTL%H0`^lP=-IMuWqc zvmga^!g}zj*=Z`6iCS7bM(XKWDw$~=Ho|BwK^<( zOg+*4LFtC`?e=*5CZ}TWEaT*7<#u+*Y3}%)!TFt5<{dWr4GQ~>ZRPzx!Miu}Tl~%& zr_Ph$PQOsB2W9s6;Q4hT#s!Jyo%zIp8~Z&m)}1WX!Akofh0k4<;!}R*BhADqJ=INo z=DB_6qhjZStKHL5^pjQPlPCM3i_g=~jH9%U=l$p#nYSZ+%)J`nXE4fHL(wi0yd?Ml<

    Jdhsd9HSbN%7S1|syz&_3JI_o?C&oegia~>SNXsD7RJ5)c&rBh>09)LlL>jl zll=H86-STvnd9G&UD;UwryB>7YcqK;1)4lSv$zo>*a*hl}=EXC91 z(%EdE)Q-lBRH-0!DeBhZ0R49FR~?rR^W|85N#Dq-!DIoJ&IeVT8>i7!;^EXVCguv1 zqL#0pU&)BKwY!3Fa24g|FScR<%Wdx43|FRuK)~!x(ISU&zXc3Alup9rJ0`$RA(Oj3 zR|@-sR8pi$K%w1!Mw(?|y;rLZusp@(&6^j-Nn(@A3vCa>^KhBygP>qC4biRhQL$#D zHwCESDsre<;1;TH=~g_@m&r~yIOcIjKlVl+BW#9<&YB@21;~E#h8C&Ak#vVRFE98;(xx)DNz5$rL78?L6kHu^eJS9Peuk(5V3fy_V zJsdqT#tAAtE7WCE9I$L|a12zec~Sl3A8~i!;b1w800$)Nu_aJwg8?~`_?0Iy zNPsA?T&17^y8IvwE3T7#*sv*z)R$Ksw2xnZ>pB%bXFNmUK8WAAeIEYgw*ez3Qkpwb z!FCU;%EYy8bD%6q^n)v(hiD8H4r8?q`$vZK-&(Yovr(ro+EC=25D_Vb>WbE@>FC1m ztY0nEHS`G%RWve}C4AvO#8PXb_@1E8f7ARsgPMd41CRB!{{ml4MdrQJdZM#BPHRY% zPB>-tCAFRd5j9o~&hBGAasUE@MF5RycFDy@uZR|$k^xT17fIF@)Mid*^D29=c7?UQbP~2^hZI7I$ieZ5R4xKLiZ==DF zdUOsHPUP8KY(`|aoM_=Y3x5D3A?BxT8kdd(<1|eu6ZmK3ow6@h07IxTO=jkncE8x( zjS==*xX>LMT`0D{%a~e%|zOxe|yvc*Y#$58HtR(p#>lO%CryrHMDz49Eb;X6JY1>gD3^ zwROvP-R9Lys33ti>jLhmshz`^l3quLtbfUeqhNY$`3K=&a0h%c_|W0D9U~>|zMK59 zLuxNGMA+l7u(0E4TmSDLgyY8jj_2LSD!8c6ZPHtzG~ahBxn?}5Gq3<{AtK(7jlaFU zpU(%V9-po=-<(!ya{#CKxZq&rE+Ar8>NFHc3x4}5iRQ#4wgYh~GYtxNDS+udMx6vp zI&geI$B%py9K;@w?hpLKx%o^g&Xr35Yl(_JjZF0csVK@GRuK%B&~ zhwY8m8h8BF?28D`8H6DDEl>u>IQR+MpRcbg07wncMOBI8!3Nt%Mj8ipBgcKjb%^k{ zN0FcW`~9o1B=**aj2(<%QE=!3FTu ziw47f@&&+hb4XzR5Kc-L>ogb#t6X28F zq0Hsv54)0CLS|;|P^{4~Owl^}-~Q0zw4bDbe=e z@E`E--)jki+475OGGAR(V~Ivl5NFcpzp94GMK+1Sp#Xg0a{%IzzO_b&z1?ZbzKROr zwf~w;3#H)W{3?)rrMMqIe%j{vh;vb!c$60=5(6@c}+ zH053KB?~7E{4K~FTMQr?K^A8r^L?2)Ai+pc5Brm(9O={_19&)Q1!QHsBxUCsBSrPW zVyWLPLm5x>1t0!>GGTHI;wz>umh)m%N)1mcEE&tS-&j)mn&(?f0GRpmOQ^MepB}T-lWLWs6WYq@FL*8Y zY34uGmqm_+n|#Gx=yo$meV<^h;NhSWdDX6v9dqJu# zY5CnL7{)HyfR-7Ua4pPEZ1257_7|R~z8h1!${#l#!RxzL5*~CUNQr5Sn!y#*3Dz%! zf)p}BN!<0iYozMoo(YZR=ICkKEceqNm5&c6O1Y0Kh;nM%x;*>)L&)5LCekC*36-Q7 z9#|cxDQ^6|k2~{TMl3RfWu8%PNrl7pvpAtgW^iybSQ4=)xiiv~kqq9-wr?$J>ccPI zL(MUo>?>)vh~j69BOhl7YF7Q$ia;vegs;0Jjjs#U&sX=6(0Zrr>OON6TDqEve>Q1U z?GP@xlw2+aF0Jz!PN|PiJwCV2WnjIdz_MH6^78bosd~$b0@8`n`5W=8r?mF|lzE-# zx^hskwIO?N)%_>^3NducT~xAy-XwkXl2{>)%zq=_T3bC=YX+bTCM zV10dYjb~olb%5&bOp2s&cnKM;8?&d*@B{C$8>7qvueYK; z*Y>4(HVXE5g3yFdybPbIv)d*Zk1@_ba-LgHZ1?|Wp3}5|dTXowcLP&8m-fu2{S%M7 zJ*VYc*rj?Oka*~OGf5QwG`g>SYHT*jrf8|Gbo#DBOm$96kEo1F>lJ&Kks}L85|K(HYs8jS~F#T7PF6*tzNki=EZm(^;}^>(2br&RaZiZ8e5_F3bZs#cPeh|09MIDHsDMa;MrIs4UPxCVDO)ddmzI z_(&%n^iaKz{P`ufdu_XQu173w2;m{p$8Semu6HV7%YTE zEGTjUUefI?udzM=Vv@bD(uK^*nJpro&9;O39o&=HLrv1q#leGQ=U8z(wX>prSq)2e6 zH&d9VcErs%ZMWbcK=tDm}ktKEpo$H4Gp%0V@4u@8? z?t@!%c4RmN+jP}rt)@c3+r8D1GF4o1&609Wb;$irf{k<|b@D@i6S;4J$XX{o4hhob zFVcz6vNq14(*d37RJlG2g(L(l{Mfk`geQAyds zG&$>~P%Sk-rVUsTMwwuIg^@aO>t0DI&rn5CS-@*oAaUTGs1-qsL`kwX@^i3Gz4c6Y5+OodV-Cqa(Lv5|xo- zyqm(4?n)1I3X5E0VepE#rbAb1iuZMjudA|tEb`cNlb2kR@}`O~uT4C$u-V5-1D?ti z=*o9$d@|XS*S(W9@RM2c9 z(@eJ0Y+e~YrevR#0SE`#;*8Vyr|2GzQ*S?2Njzq7!e?mKRPYr9n}?OqY*pK5r~Kt+ z1WwD=Y`%+8%o0Q# z;UuKFA+BLpuR`;xZjvY~ov-ekzu?h6C9FPaYP+BX#n8OUQ|(Dx0C_DqyDXR_YFZG? z`K@Vy=;wg#^FJ}>)YKRIbrwQi=R?gj{9NX>ziEZhYkBw0+5c2Ku3RfgUnhBPKBay(t$xw#n|3yZPNIueY5Ss$!eXlJ;;;0jvc%;g3|*kQ zZo1h@G&)!K5dSyi5ye6PZ4V6SfToNnXma!0;a z1-))%y>1SHUP-=QUb{{{t8VS+=j685Wbc54T^PwadnK~pXd6+#7UbAb%yf!hPSLg z%P1DGI}E=JtzS-VVxAd}y%>^4Lk-X?)><(P=LjGlzw3S+-yo{^g4r-ccV;X>pnp`p zf!1OCnOln$lZ(ATj(q$l$KBXekTD*m$ro?^8(Sl4%AbVe+oa#O#Z*m}Ot-%xuA?Y! z9@QI<+HQ7J=rU#e6zbn%6yE+8Y={N45G*O{6LqXgX z&)7z0Gm+9TMKm`>(lC?k*kMUBg)1#Txw(GBo=Jh3X2uTFnfWiM5ha5$ zmBGF};V)C}T^>S{AKvC}P|E$2-CZ(7bFsT!BZIAJn=SKfwqk;JV;O!02(R059~wvROAuO8 zj+h1=o4%A=rn;KE1#L%Z99mLZdIei}Lx1@s9b|GZdqK9c?@aRzj(qnf{Jamtlgu)c zEb|n%75Wdo8LY6Q_dZbmp$*PSn-*43T zh2VNb8GPi)cF@#eEg`4hB5a*|X5H=jv-HlSjMBQ#;6$llUm0joKW>qLXcYrI{?l+A zuy>qjejMt0oWXDa?XEb=Qas8@vH=O7y3ZeaM4$YwI3C?QY3{H|hS-!S+D2%Y*JjvE zMq70XTTORZmG7DML#=AYZMz`0>x8E(XBJ5rrwbaumG@X>lI=vl4W#09QrKog(Pnep zs(=zW&`>YbWw zaEaSUiOX||A44f7>Ok=O5-W3>$R{igBb`Cn_mfd5+_H7UKYLhq`{liD8(P&btbszY z093b6Fu$O-sK3r{3AZK*8jy`(%boVAs7@FrfPp|BCM{o{#Q=7@Y$T~OISbqbL5giwkfXszw+umn<6HcGmoh-(A zEP>}NznzDnwj*~=2mOxHhQP!u2P$Ldk0LkoXU?nMHfrB*xbNOa_>Wy74x;-vN}6`U z=O+RS=dzl&>V~!dIs~`IajGz_^$K})&xH+=ar7%Os>eg+ld~0kZcx{+O&jfd=XZXv z1C6j;w=r*@?`~uZoVD#-&%9kPfHrn-cdF+{Oarb$3wLJwcECbQOCnn1brLH>+d*?j zekhg8528Kc5SK57_txz9{2y;*c$~#}?!Az1-H2Sgkq)#(?rE=G3LNf9aa`5i-F~B; zh*P;~++TVt?OBD`2R8l|9B^xf-g~||nHjqI+ns5$+XnqQi&S!EeLD_Z_?=4R9!=#GvwoCa_&D5upQ!2KS9zbOdE+YKDre_xF7+GU z?kNq)Jxa=>IOH+Y@Jgfcsgxb0+2~Zr{#eH2p7YBi?HrgsaT}KDnn`4lwQ!<6@bo9M zCLHM@BIK#k&Z@$|xf0^uoC(S>Yz`h!vJmm?4RLcL0=a(#wTnErQ`yRVe6%rqg0?k! zmWMn8&!3X99>DAmLn06VupYCBo{Fg&OWr&ilD#?xoIBTFrayXtd0rEgKo!3p=k8w` z&Ou}vpm8Lq-1=+k`D+u^>pTy1dmT8&?!Efk`>4{}hsPr#=IJ8%rG?0DHu-Uw$oqf? zG->EP_4c|``8XbP8kgz4Ht~A8@9n_u=@{cP_t8fO$!2REm7Jaa4JlOo|IxSDO!!~= z7Ceq8ZXCG-v4|w0ES6VvvVZ7QgGa&deT#5XHo{)bY{a-^=sTo z>d*UQS+1km63trR>C@Mf#hPC;6}HdZXR9s0ug^}Oc`i1(L-5#vFT7Vf!^vOl&R+O# z4yFs=Z^>Wz?@pE*ozBl*1s*Q82L32D?RUTTx@tP(ezao+Bj7Gq{q}kFeEPV1-)Wll zQ;7^s(vJesO6<27B1p2@ml~dwG2I7%I!F~nU!M&YRnjwB!$YIHFmeLXfkQ;`(6#hK zP<JlJ^bKL!RUp`>L^8#7#cS)#_QFzY-|sl9v}l>R`r9AoCs~rx1;L^!D-V+4Dqnp6Yun+TmpG_` z0~6)WhE(7J8k8wa31Y*C!CQqPU86+3QP~PJd@3f-3D!x$CO~Vu?5DJgbz94s($Dgv zR%N+hEc$a)d`MaD?Qxi|M8|Pl#;rlbB7^`E|l$205u(h>o-=G_z!Tg(62w_uK=exKvF5yx9x*=T$3Ti8+o>bfeS z;{J6ofRZ<+Hv4***3C&W0QTtnJ&rDa5FoHbTDd(C7Vr%QR4p z6~lMIC_=%NM!qzXdp$}3LI$TMtRgz+;Il@z7P{_rx1A1(UcrOEXa#i0`v^56dNL^T zLNZ&SEx@ENb-X9_E0nt6z;WpHY5TLcPW%1mJiEzGG9N)5FXZkfF@MIG9Ko9@IT4}T zIb9#2yCv&Rq5Cz^+k1;LLPYp+H`Pb@>9F+wOW&dkeEGRUm^P4XWyU-=d}}h|QA*-Gs4+OrwfsJkX&M^Kn39pX~Fa-eYVPU-` zBqZeI{=^z{B$k@0RP-m?mC0KhXm@_$4IF77+Wn1^9nME~+eOZz_s1wVf! zKzUL^;@xH3E2#gMqj(P^ya9nX?=IurQFwa7z(fN8@c=-!As|Z%(Da^UMMIkg0G9Xw z{Q$rg0B{Nb+`eDu{R((^{}X)tx6ZJ$TYrx(yn_!_)&GDGE30c$)BiFWckkcrW6`#1UCRmjb~uB`m;0K@wy85#f48UNe* z!o{O9NO z|L5!fKnyCSj<)}T81IJ>a8XY0quzrdG5>)WJaq5?@N4+(+5i2l;Nnm--dw zYKokMSQ&umNz8?Wh#=1!BC0`$3=a0UG4h2Ws*UI!uo2;3qp;VeH>fXN|jleGv}U1)&e%Uh|6 zZZ)Je%3)o%p{}kEwB>c8kRMA_Y3PM3RLQF5TIPMHoEvr2y7qjoP?}eQ#ripN{CMtF zdvW;UJh)p;>3PFDBHutKv@J6Pd9q0PYGpOjnjQ6hW3 zVt^jRLd+HlWi5mNXQ#bfZg8)Vu``>M$86uzF z>C+wu>vTl~Q2xE-b%n@|QSR!a<9i10U%)hq=^E@was1==;5UYN*K)K!#6(pvWLp>U z?C*&=;aM6C=Lk=6HR9JM>`Z`Ow6`oi{mhkmr@zIt1lbQ-m?by1x7ljv@SV&8eBU5G zdrO0;AFCvXjR;KRHBrd^CSvf?v4}z=(YtT}D$^uC79$umZQfb24POK@ai&1H&45{s z3#x-xq#qPUSs&el5nT3c49|9!2(~_b0S2L=5koDo0KFkY-W5Bdh{~#koJe(@j~nr>VzOErHQ)Q69MrNSj&nGl2}D&K zZ<0#4*T-wXFjQjpu@qL|Fig54WXvsDfL0+2j3~dDy$o6{ZlKD*-`V_O8Xr_;tJ0Js z`Wp;WG;(Yzno0OCJ|6XSKs;PHB2f_pUJR=&eB?QFK+~(jkb&Nx7=-2PZtkxeF~C}a zCXJG*=PtE4{n@-Z07oS^=LSZ-v+}}T%eRi2Df^r4Y|<=T!lJ#QLvyj3H`sYt zf2q~44bHxBR$9MdQrr8qsU?WPYJ2D(LQtzlV5vPAj|2m2c(^tkNO|+Axi~&xl!bO7 z+Fx{2vuxt2@S4I+`M3X7Ut9C|e+w~2w<(_=21GGyVngJ2K9D^QN@w68l7e>_1RjT! zqiYfh<#(BMABVNZYmypAciBLXBSx6De+T6EKBqp8S}4{+Qx-Q+_H_Hq4 z^Vg}MtK({X0hWR9u2pvN)-zly^zVB>>e@fsTCuM%OfV=kX#Y5^a0W52Bi`3r*Vs-a z=+bY_%eGY409|8J8TJts+Ek{`N@rV{?)&dse|@%_xLKilERY4~f428O*JXIylkb-K zaZ$we@(C;Cq06MkeoRe|4(GRQ|GyfCXeDw6q5=6qsMz$S-eLZZteE=`wTjp{-Tqz5 zpN}f02KXrpFWc;Xd}huS^l6oSdy+6u%7Kd58FKvxq%|5 z-Xn)#{t|kjld{a0W24O4?A8vvG7ts3IeY88rnt*M-P#Asd#A;z4%fuCbk5&}(yLB2 z_o+8)=PpVz5P~mmVJ~abPMuC$K|-nBQacx4{X8+@CXTClG8Pk%?zUiT-GxoOuLBXi z4ulk3n=Go7U)yPVDzCGS;SjApL$6MW7)bzm5eEt+YR~G|1|gUt*y@v$O}Jg$KSg5tbJ2 zmqB}CY0D25{shDUpWOn=v;9PO{I>f2&1k$(Lfs@8L4v##Fk;IGKum-uKyN2)jvh(yZe1}5Axy-PvA|e z(?~M^n>bLI#5x$|%o~b|oSgD2`S)WOja!msb0SGtGJRLPb9I8_P-2kf-;c=QO2~hG z-TwL%C##Tzdp{;cF8vK_PX5sxmD2prf-gB-CN$A9RPoSW)15Ss@81MZit5hSS@p(({fNx;G6w#9$#hp88LiBp9sq*7^p#i_*(DQS=VzyZixbBmBL>3~+rs`H7H2?6 z(wxHrvr)p{I}ov-!py5p14QOyP`N= z%BGji)jGQaspJ%BTZwtKtdtnu%yayV0~tDdTpitCM2EA>|@H9++% z!*y$@6)MLK=FC0=;Xp$&XZO-Z1W<;ET%)OOgS9oTDl?HfS)FJ^Qy5y2?r~MXaZLwg8_eoEpwA!M8%)f2EFHIo6;s9wzt-7y)>RIzRgMCU zUq^})B5KQzbKlDlDQIQ1sZ|i!)(q>`oa3fa=H_&PHbziu8EG?rYMs$aZLUL85osG3 zYTf=dpur7i;0UMttJ}Ohb&LK?C&}(n=K6A4n>hvEL#wwv>0e^*UyWA+2ei`kemGAv3-v=Em>D3JB zl|k>`WbU>{?+;%ch}3OMJZ>Yl8EA`W=@@DDUhPPZ9Ey7B=uZWgp$)~A^<{D*O%ng{ zcp1uw94?l}MUy8Ctb(b_O(+!X6)zjAw`nYJKtRs|RC~tVTZ8QcJG#oM^QVwJCt=$4 zux(xlm!*lu+J+lOtMY$Jqf`SZz%aWHu>g{o<<&6=dF(p*_||ANEZ_JZ`8cNg_|fXv zVcYo4;;^aMSi#E(r{E~qX5z(~^onKVhP?OTWa7=UyQq4iBXY3&r7zNRMAefNzI?Qn zd<;2#FoN8rcxtkLaYCuB)v9EQ*|Ha#aS-dZD}EH`;)HO7eCi<;I`n~c7~gvGQ~9I{ z`dAao0KVXK!tfN&S}R9s%V&xiCW>MH_P!+aExe8v}L~4p@wDehk^-K=a zoa)&02Z31*uK|Uqsc-0mZmn~Adb8}TpF6iT!xCV{W>D6C`Ak*!&2eE|xK32ieM&ojYmGs5jdiK8>&<#X@cMFXSp=j(zL z#lpYziP6&8Afchi_Qesh#Y3{?EQ+Og{mu~2CERz2VLQ9OvZSKF04uQ6rn5xaw&01r z^0$47QDxfJVcH&JvUO|)|8(w?%?d7P!8K}yW^}nU^2R@&D2ojX3#=GxaFCTAh1H)nYfh1C>!qtBwi`C5 z(mplpVPIP?n>^TdY~xUW>myq|r9!}0;XxzYP1pNv zZr+_;)=hS{h2yo&SBzZgj2#Zljce8o!RRf`v+Y5z9_orZO6X>Z(3YgZgn;6n8Fb~l zaFE#9>`ME_LGqqD@veHs&OOEY4#kEuWb0008_EOi;lrFFG1y?KzyXgDzRzW8dvAss z?C5&;I##TMD)!%4*JBmeJt4aWY+JmFTjrDpAkRHm{dvF0L!SGCMBu&$>uy%X#yi9y zgY0~L-63Q-u2tOBEI&f2*eUbA(b^&s> zoqptYc52&kyyv}oaCR^N>3+k!_}Ou2a(1GHc{&lj7X_VyF&sSVIJ-62+{(Df%s6hN zTD=5!JMGk)p??13D zOWR$@VjY{OpCqi^D2nV#cAn}RUTS2Xw^y8E0dI`h?o1}GH-&GRD(~LsZ1y{Dek$E5 zLoP5oPZVDE*D>!M&hK#@uB_s&_S0{o&L2LV-7!Nh#YL`_Gf&wKZ<5xpQYRi&)~|Km zu5CK+^kN==z1^i7u3#DVyRDK$RvyHh-&Ru{d5RpB`mBW7ol0cha=efBDLy8?J-VD< z6B<4Qzui-bJdAZ*S;pM|hOW=Oj$bq?Rr%U&TPs}Py}b}+-mkpfa!=fV4exS9o^Rn=l%-lUCSOoMS4Tj9|7Y(5F@)w z7>z2;*deJtqm?Du$?r>W+`!%Z!(-ur2(2x~XHqmfaOnNV|)~fW>za)@vyCDVx z{`W`k@rn;XjK|K@_8@jR)2I`oP0=cPN}Fw080L2;CJx)TK)FKE`gC}*5@2{pDfCk8 zwKv!mvkvlj3Vlvaz-j_`kzwbaLqS8RO9m@gWv~t)?0RH+$;s+!%rfPCSgyYkwKE)} ztP;7BI~Lv3^7t6vLPhBu=-~FW!uncuR;By;ZQA1cr`Tqz3o-aZ<2or-$vzi+h!ULs zMENHzECzsI1cv>@YQe$AK-+y;#Zuq)qlmsWa>|!VfErI4!fgbA<1NC)l@DsDLyJa7 z2SCBT==08hS_Ic$9F^i>-QZ|3xHo9g5c`>>`!`$<71-)$YK0YV^>1ja%SZ<7_E!tLkItv(ztHRKqiY( zzqq*AFNixLFb6QB4#A-&R15-C%{N;#vebU-$BKp2fsL}5xp^&C{?+KCt(Bs01VqsU z#u`%#ql58Pl%~FFYDa)6kkK$Ob$sP98;Z(|0wD>*JKh5<0g(A7bKc%v@iIb&n)rdxSLtBVQ_OzlF4^I!|z{2>jVSr6+YHP*FG#eptLB!%Q;(PTP+BucD9uwPtdzPC6AGES&RpaU%HFL9K@lxj1Pf}KYb}BfjMn_s6}%Vo%P*3XW@dq zqn}5Q7^JZ=rfmcdxX;JFMCIENgAwVUHhNIyA~d)ihjNcrIvZQ*;KTF3?QO#HpC-WF zEVYKexCHvn{f8VlckG4a{Zvpwh4VzS z;CAoI$o-n(QZ?B5!;i^`{LJY-B2D~}X4a_4tFecOO0pyi0N~m{ZSgY8tr-VKmBk|1PJF2t}GL&MxctuNVy(LYTT_yh5x&~$7k(Ous z@u&3X7U}a07-=v2k5C!SoMJPcV)Rvf(^LRXLNYww^7NlZNm3cwX9F+uQng4!tVg|~Vevt~ZNq*03FiBCSsOT`bT`ro4K)7bWto%J`BlpzN1~+Y+tQ=Lw=)K888;(%p%fMS4yC*)I?D{=qgcU%D_0rb9oe6j z-;z7Hq>0xoO;+>UZik}t=@GJ&*ioCZDEm|7$Y8mnmeukcRf`!^EOLcQ2pr;P(k?m8 zlf^ye9yxBkqn3Jbq_vc)fa+2v^vuL2I1$7v0=@EX>d6EoWQISMORHjk#`X?yEc6@b;luB1c}6_rI#OxmD{K17H=RrXBgQ0#*tiy+hZ;GkGu_N1&mr(vCDC+ zG?iHn?7pSeo0&$$dHU7mPoy4t@LkEhHD**1a208h>i#~+^ zPc1*q?4oJ0TQiy<`qu}eq8yyok_0E^jgw*_vgUS~X4=3dS#v?MCRSs%%XD2Gd|$S) zp2MfBu%1YZD))b5*fN~-)dYtOn(hN$dtA~Mf}d4@Pt(VjHxd6{=Ci6C2P@JdGTX_H z6n>-(lvb1}eRrENNa3GQ%cv`_53-)TGaZpT{#;?9e`172He1L&sG3}0-a5$7IL`nq zS(mq2*vgB1il{KGV%3-UXf~1JaaZ{T_aGno?XTRVw^FTb`kA9o-W08gKknOSU<*rY zTsLKH{+un&v-r)I7xPoFC5rtUQ%eaGN&R5(9WH@f64#n8#CJHnRuLVH3518NBhQ=bnLGapaq$6mcTVN1mWsc%cEyzfGk{0VyjkFLt- z`-UH&-EQeeM#&!EKNyAz0N!A*C%s>`ef-ZrUFg3#A{P3}1 z5Y)s@nLCKGU^taKswO+RzlhXJbXI`E1UTS0V*Lnt{RrU2x4sDPM0DBUHJ6(Ra*l{T zZG{Oi!m)?KP@#8I?+BmcLE$c1TS->iNCP{_BwOiME3if=E*!2!pumPH%L&-=o~=iE_G+=c52gFh)jVADm! zA};r%EuU6W9ZzU26^(*L?2}C|JWI#6T*t01BTtzC+lh$8YUczo{Kr6X#gpELQgL=h zxR>i{8FT>(lO}rn>iHsx&!at>qa9rE0i0RimQBR<;Cc1oxlfQKI61`d;rk!9dlsH0 zPz9SWo7?@AzjH`ni!6%anf6+Yc1Q(^sqB0=nXR=!Z$~*1z?tf$q=RuFAE1#J*1+rK z8}7GF;9?+w=e&U>hAR8v#13qd`Qb~#a7uTASSnX$1{6&a3<6;+BEREg1>jM`k=K3O z8J1GZ6H~J4|Mk*GAn7Nb6@U+xb{1rG=@p7z?T)^7(aeL1=Ne*Hlg65sN%E9PAV=n)_G8Nm2$z)386C`A9+XQE&i^0m-BoN{Tf3m^ zGBY#AcFY_zL(I&~F*7qWGcz+Y#2hm-W6W&F7{@Mmt+oE%fA4d8w{$LA=Vs4~l15Ew zT$MCtsp|P&Lf9`t1HrOmm8y{lCMmg7?DaV!$~mO2m@;NRq{GQ4$wg#J=!e^6hl_@4 zs!T@bzl+OG$vE>$SHB77*ho|-m$pC1AeD6XyvckzpZvZg1DZfF+R{Ia+0jZU(|IXr z;=<99!#~6(J2oXXXfjm|DcgN0TLh31l$rz%7f(&-%GrZYj}ywx$H=V{%6<=-UeFy` zQI*?-=vgWe-F}nX3#nXv0uF-t889U)Cb;^j*>qbYEW*AsD6}AEx?SMtqc;=nMf+0Q`Jod1%wl z<1P6k@-IuI7;s3_*Dh07J#%B2tj5Cgn>BMICQ1mQ@W3TBT(JnKy#Qof+^oBdOt1w~ ziiL>G;0c-qay8{(v;_)RWis0Zs#KtIM&tsG9xmZK3WH_Lg@9{Di`Zd(lONb1c+hT>lN_qRnrtC@LzFl8_wRCZYnTnhaO& z6WTIg_4xq{EW@KQmc~9lw?rS(D3UXa;p- z+m&YWB^3S@!5%eT*SV7HrQbD6+uf={;0l($D`?v*dv8lSx+@6?8jiWkhOaBnva68O zYMR^2TvO_8m+Ia<8X49aa=>W~8KTt(`qg{BRUuyukJ=R`C^ftul?`1DrS~Zd*Hyox z7613y08lX0S0##nCX9XBS8O@Bw$0;l*^@yu##AnrK_T+J-3W>)QEWA+R6VJ6NU?M- z)KoLuR3nXnITcDXWm+L~n! zLhRNCgEn7}o-@?WY^tv9k)Flyb|-~ykgxvfqnzPUYp_^6qYWO z%C@z$)|sBZVeQ6`)a^x6-A&uwmfN-d*d2*0{Tp_%onNzi6g$th8{xM4zk7B>Y78X5 zuhduTgXI~#BJENT7<|^aRPWitW#4&J+qvA<+g@IUrfdhKX`?e5 zO>7&69__A|Zol`;zg%tIi>YJuPCXFmA&+RF3TWY_(V<sdMtugmpG3Xi zYV?fz1B|YH4WZ<}Ies@-n=rV<+5t`P8QD&P(TJLFg z*skBqprhYe9OGG9on?ytSr3$zow!l@%3(3~w=%nPdgAkZGxO9HOa3xT)3&o5#-kz* ztBMh;qB<+(k+WLt^ZK;&6l~KL`HSkA%^J#!_OOe_9m^o`qgZhR(AcArxbxDy^HyZ* z#%s;I8Q$PB<9q?@Hg$vcw2L}*Yu2apHfZZweVdWv^Aya>8CIKb*VcVNi_(?L5wm09 z#EhwXnuXxV1s?WUqP*Fdz-6EK@wA)G0<`59H>>Gd+fC3+qPWYBGMiOD+w~`#Sb1A3 z=wqLa@#oXd3~>D}4dmV2aB@{coi|gQvd~1Z>(K18wK8ubbo(%EKwPQ8V9&!la=MJ&ffT)joM#}(dlK*6~SDZE7!%&@^u6s`b= zUIP!Q2=JwhfjGIo5qCI|XJj~17H9}Sd?EWIf4y^TOM>Dw*~WZV7qruLQ~m_Bb2ht) z7jlH$2Zzpp5GZi!4Rm}DvwWMe54oz>*8&|j_f~gzSMs-b=1yzG@?CyM@6ekJ8g1YL zg2Hw;lqVK!t79i=W|?+Z`1W>Wqt1?bc0$N5!tMLJa!!mhP80^eP}QCN&F)3Z?z;s} zdVrT=mqE1~*~uFQ!aSNqrtseV#e(j_FJui62K( zZNGC-+*8s$CBuJbq(AADKgsVt2bjAT8h8{5dWoGpm5+Mlt-hqL{z}pC)G6O_L2;|y zeJ!e&@vgVd?{hkTI-)X9vL*IzEPstV>2&{Ola%h&;qLk^-_2{*Gyd5v(A~Y+z_}&e z+3Do93EfA6%BO+Tr)hUK6#4fL4YyH2kF4E4X6~;#Bi^phUO=h5m$Do0K9u)P1s{+0 zKk2(~4KU9Y67R07KCAxkihXYd=3evdFPnX@h4$}N@xGlfJ{33aVfnA!pZtCryzljS zuL(Z(wZG~yzISoHq{sT5X?Ps&`tHWt9vJ}pVLVUu-)2D&(EQxWmZ z#hsp|zk;X#i$>Z@ya(k9JhCFTz$3=nE*8)L>pw#b7!J+TThgHjbSmW3}o2qa5^b-mH7)| zIEX_Xa$wGyDxPqHtL4{)QMyR4O2d!E!v61%eotzgbV`ivGVr427fOKw${_ z;S&qE9dif>M29ksPuGO6SjRsDIZpdwkb~)mIQbrH10nM15g?JMh6>;9zhX@lYX}1S zWKYq^=CJT#-Ju}h_u2_Q!9S3qLIc6V3xa+OH1-QYfp-|mEFr0e2Chuc4+M4fII3V# zT(68q(6X%Qk&-xZ8OxkH3hPDz`z-^7!wB|Hi|jcTxJ;yiRR{X9hmT%1pbtGtM7SzrE3^~=lwrJj4M%J03e_W&ghoG zcMAkDT7v)piB5PpP?78?#Cb@Esqg(~ml)uMac&3L0}d7t3I?XyKMDW3M=+n9cWazX8PgT&H> z1pplz97$ij=qqU!N&H% z$M<0(v?(I;udIfS4iH2vY-~OpzTJ6wJvlpnczges%3>oVl<_e*I5;^uIXb!y;ufo`>zkXK zcY}i;|53fz+UoDW1Fimc7r=kq#m({Y&!2y1FhB*2%geu882_y={`v_1-@ZW50`I?z z7k@(w1@gb3g&P1j0GE1>>@R2`3xXEIuaU4z1_8uh=5_<$+50~MAl*zPpkZ(Wgh`;) z0!aWauq6XvFg8MlWP}c5145BD4gui!Y#m17pTa!)BhH6Cu&`m2Bb0n#giQ9ZVNI2c zMc}FD_C$GEk|YyIj0*a}p#da933$vwB@!XjdplqNdcy>003==sQH#fJ!07CZ1^!2Ki-9 zNZ7@NCLz^DwJU&3`I}}Xc)FLBWqGFAI8B***#;)*yVgsd5RihFLqf@jK2K4kLh=8Qs8t2|OTBNVsoHe_q>gU6=@3PsywWuw{Lb{JuPX6R6IE zM+)GEULb}5O`D6rR(CTT4Fcov74{}#ZgO376-YS+7J8 zAlP9H8x73o@UG48VB@RvpGe!34ZZ`=jwU&`lH%)o9tMoNE%FkmzK-@llVSiehFPF= zNl=|EX0g$s1ZV*T5WlTR09>fTfm{s`h%I{%bYl?+j4?KbRYA}rCtc_>kk*)kYu?Ol zY(Z<%jxi1RyNHOlkKtc|>fWhsd*BmDmTIy?u+b}Tf8NAA2a9nnUJ+K>_?&`szHFb!Tpe^BYrD+5(LReiwOzT*r?X;#~9p7c8*g_N&W*Arxs z1E}4;NIk?A1Y0BpEwVFxIY$h|cBc02r(zD7bq9NFt$a!@{d!gkXJGdYIIabXNWAn$ z0-rUB6h#QM2~@Mc@`GNJHc;px;HW4be_Rt3p~6Nc3D9Nv*#a(gt~t4($XbL2z+C80 z?zU{Icw9+~?60+fY7+Z-&XDXY6XN(MO1D_A-w?M0Cl*s2l}EEc2d6{bzaKLk8rBYi zS#~H&8M6Af-&pVC5vp%&$Zn9yzHZMiTg(4r@d9_IA&m3CEMAPlLLfyn#+b_<;BUT+ zaLqKvx&ObRg?v*|`qaOm#jiw5R+_wiW+shZnY7mKbcTbHi6*dS`EFetmf7Jc^J^!d z!Vn?>#{uNDQy{DEA)h(>{m^vXK(pNG8@53E@T`B^z5K%z{?|pwIUC^?ZOk4E;ftZU zs=yXm++1wwd{FVi%|)I(7GM4c*E%Cx4DIBRRr+~XjgTI!Z#dbj>|kvcDYfXv*2C+Xfo?5{au{a8BOBC-PiifC zSa$B&8>|Cu=0mpV_A0|$%EInl0}L2W&Li98O75zM@0ebz+1phWgr zPX@3~6V*DjWQ5@(p+L_mB>{O=oy=p4#NP@o*BH6Yge-!iu(K+)>4m%9r`B!12<8X+MElUM zbax*qazWe~Cdm5%Gd?|`zNA{2+|#1?=HuaSugt~7=MC}vE5+BZ#goA6N{#p2&br6t z-HqqI-S;zF!9SY^J1>pLzH80~=Et1=a}x@@x9(SO0*eA1c^a^1*+4ztb{j#8+EL&| zv;y##v(`(iz1K4azwfz-|I4|AU)JiZ-$Qi%%L(Vl-DAGbi@P4M3nl>U#bUnQ{Av_y zH{BNI6m1;_7byZ2&I27y6CFb`5Md1sbFJ3`8j{d+V*GQ&c(PD3O+f|Vpg<+wukIf7lwLrw1jKL>`ryM@#%1x=*{ z?V5#|kA-=z1c`8YIpButu7$bbhJnO|(~F16i@PTmmK82KFg(M-1r|RLG}C-g4r)Ja zNiE_6JEFQRB7Yu093X^9VwklQ9zY#7OBMCo4Bx4M0_Q*yk~GpyB=Y_^s=gzr5Div~ z8CA6)3SwSMBLfFj1*hjU+&{yniWCO1Kmno=fO-g~-7oM@@nQ})78HJ;df`~|h+WJ0 zyLhn{I}59}^LO#$up@R)^KWRe7E9jxR}KDlE#?Y0{$ec3IuTZ_A5e@HSwI~+02@{) z8Bm4>3kvH3Oi*hwB0d!+5Dg?C!9}AR#akMI?Ioka!6kl#CF0RU7kpuGQv`L!_+Z!L z0a{6vzk@T@@YMGx6rE6UEF)R^xHHqNBGcc?gTGU!J&vaN(wK-r9=kTtcUvIWyk)`E~(6pqRAZooz*a&LnD!$ zI+}?G@)TNGu9Z2xXF2^qsT?Sn+*a{i@%;o+m^`AB+|2N7b<#Y7!aRobjNGu?>9dqy zky+mBSwAXsxh3*GpX8M{W>nH-KXB(So8=XT=XqJ={I<;f4wv=OnYERftHza)$(^MW zQGi7ooM9ON?Pd2Wg_(z!+1;6jf}ao06NV=pjEQeWj1HYgLt`JE(N<=zBLOW8-s)TnV|CYO$ z+pAC~%NP1{N;s+51CO!&OS^Bmnk z3J2I(Zq-%h1)mB;uPSt&@G_z;GuOuVpD6jVQRd=RYT;EL{8|wtT@+%KA3{?+YFS9D zU7p-kB3D(K;1yXgQDM1JSsGR0$b;s~gA>bB6$oF^oK-p4Sy_#rl4n)Q_L^DeS=mZk zJz!N78dU`Pqj&g3RZ>({N>pWH7QgiXoobu!&m9 z%6k6xig((oS=yRi_y+x`I{VC;?W}4nggW-uYE*(sXzzwM9{k3Q1~T3zW}b$9?S@|y z)il*j3tqsck*=n(jmGQMYLbZt3WO4H?`FlST4m`*;)`ZMndUOfW-gf~G3%DE6U}Gv zEvDmj1ZQ<52=!pmEveG2K34Vcr!DF<&2k8>la#Ib6Rofn_4Twkq}9!8(QTIBn<4)+ zVe>XK6Ev@Hv~A+Iv(mIV)3mIf)gMQd6HGQbUo^S?Y14~tpDk-pnruh8Xt=X#|E$#J z=-4K~+nI9F-j>z)tW_5)(-BJ0kr7>;#oMa>r@on{v30z~xVly6qO&)v(?7a4C%a3Z z06)pPvv{+;&AKU{uCCF$qbfS%)1TI;@16As-wXe^Y0?G4@^%+hw`o{+&Hw(6Le;a# z`+XG%-A1p|?S9cg2G;4I^xc}E_vb}T*Jf8ib&v35&)H_v_vogc@0m+FxhvU`YX}{q z1Z`n-LE}1hlQJ!x7u~aPJ-c{)`|Ewc%`|YIyo&7hbA)vkfz9%|R)V)iZxAAv% z5W-YHif%K0cJqf$=K(=Kj!zd}P9F5z07OWPSj;J7PAwZRk3b zWQPf-e(?Kr@?5rk^Jx^&9TxH#{@Ojfo;}h;_k+=^U(RNTgKr2{cW@rz2R{9gty!+)(?-#@o+z9;Wez0=Zq!`^XcAwD@`iL^4zxYJzRD8Pb zKsJ4QTn(BeA$AZdEHUatwPv63U9>alWEkHVoe#cO3M#@L7*RpYgJ#^y%j6*6)Uo8$ zh|ko#N8DKV)Cgbv)Z5hH<^_U zrSTU?b7qN=76}7qtP6)WYZhO0M?GtnaHp0!&lUw^I|g-T^=hYerkBws7Y((S=xG=I z-{x6;=85DcO8I7Rr$;1_=DmDZJ$hD2Y*%fF)&guNT=++o<(9+r)?#fJuB=DY`B%Ql ztq16?`ueVYAkJ~hjWG87NZuYzW!OlsT?^q~*3aFrMp`%J>&U4cDU{oYBw8+?UW*{w zRM=kdd0*htTL%4*F6FymbhRW&yE=@t>=w1sU%Q?iyNMIHY*n~y1=L$;^WDtr*(`Y9 zjMv-t-yTl9+L+OscOY6FBdUt7-B^mhzwU)^WeVcW)A=-GMl-Q@ixw77edZN5uK47)m zfUw)6i~C8lv%;$nifMHr%>M5IZ5lEDv?D$_ zIbU(`I=0F?Hm#jo<(&wTKNPF`Nw0q#*?W}x`@oy=M4$205O`J~a3;C4!w1|MwLLG_ z-*6^A3MC$`xIV1fIdc&>>(E=Y$J+Z{U4f6Sz?~bBf%1JhO8=XLovJcfEvsbjWxnZg+8I zcUe+*IKFe*BY%U^+c4mF@onb%M*plcuk{hwl96{7C*PN#fBBwwn-aHo7k9aLeeiwe z;yJGaP2h6S?hdEVlc6^Z?PK3#<|NVPtc&;-74)1-A$Vt=djsEh<4SxL?sv)0f3pv~ zrDD3S?!9LCxLdgXrQW-{mwUxGdxH>v!EApF!PF-a|G>d?G0XTsuW-3Ba~3FYaoxMM z8h5qncO)Zs-*5d(*KR<}|BQv{78HbU6nK=&zu&#SvPOAA`gE_WaI3%jNZmIF^Xc)V z?q0)xnIJwQYv*dx?nWm5i3{aXxcB-Tc zN2<@!%=Q`U(^z9pc(^RL5&!{4L#0S$TbTL;Wui`$v9*D?yZB za??*GeSgkpUgYENUV#sn(^onuZ+)L$Sb-lGFV|;y@z1fJ-p=YydOltvZ~jczzsMTA zsKvi6D!i`>UJrpXp|kI4Nbi{Of4bs!bn^{?W^??z(~w2&hv^aK?z66y7NOES=phhtc6ceXMj zP)T$7-JfI+8!6@EL}O=CJXI~nOJs7}eDJZVmO?}-^iaUeZVP(vAlc6P{$T2&3UBYh&k3i2qk+a@F!tYq-)($j z?nPeygDMIq0^it-mT$EefW&8*C>8;`9}tLeC`3J2EKQFhadJ4e2LK?C1&m-YEzEb3 z(KR_rCP7C0C_>_bg+zd6`%Eo$p0ag1wq3_n5G4c)Hv|vS(9crF5?M1j!OG54AQc6! zC4?HtOafdaVYgpc=;TvLJ^=7SCMBcsBBMIVg+C!8D@9zhrI68K_LCt?QTS3LBS04w z3GrT8tCER{O!h}LLN}2G%TMz@cCo4W(r_OUPJ9&!tXbP55nnaNTGmD2Awd-f{Qg`j zguJ#)LL1F~sxp|+LyLe2-Sss%7~8NBg28Q&L&vuLs7=SdZ}^GVVU(g>*LhZqbK7=U ztzFN3H}qKt07)7WNfJcz6^;`Ujb7jX18Pmz4T7@6FxVac#n9j0)U5z9j{S5$q^(1> zK-RVv;b$10(n^y)9{0~3?|oc1<2X4+N#jP`9o+g}{UNYLbVM^nS7T2naiLNix7KRl}itFjDY#&sxGj>~dT%>KOnQ zflMTN&z=@$3-?C!7zUeTDwN433Mmw#?})uV+*pJJHI{6M9<5O`0CfX3$767h#*s#L z3HEuZNUUm1!Q_FLtjW(}m?Enolt2XntlVP+DJhX!Q&a_)_YtyC%qUhswurzSeDq}N zi<%6oHvSv+2;cb~g-;DE&UDdO1*Wit53Wh$h{YIx7Fs+KM9>^G+PI!vQc`#eIeI3P zSRz_rV%WZkD(cyYnlx2FrC0D=f`jxz3A$K*ixeHd=_E^`u!VfVk+}!ZQ%qMKJ%CFT zn@B7y%uu;Bvz^A|%PxlWR~8w#uhu_UF<50MBr#G(mx!7oNLmaXo0ak&j@bsJhV|eW zV58?K?WeRxT<{};>Mxf*g@}jL>^EmUSC{j*b1A^J3R_5@Qn6rVVe8R07BZ1l1pCl5 zQIWIdAjs(osr{M@A6ld#&W*$f34@MqS}ZZ$r-o6fqVvaxhx_U+BDKDzTv?Oi!yyMN z`RPZEV-zAPOAoo6TIKwKl1kE;cE~C=n5q)|W11*bf)Z~ey&!BYtaYSC<{X?FMy+#M zCriaxT7Vk2d~2-kJFNVo$_h)aumzUsx!{*5#C}; zn7QULH~5AUy(L2}wYAg+VGCoZD-9+YjkOiUHh%`}Gf_&YmAt14^Q&6XrKqHuYl-?s zx@)_^IdF^)5=4%|tJH+-tu-&TmU4K!Z^ai`%nbmPsD229I)voQpNFkmYFX~t6ST*X zm#7DFNC=9Guz`C6P#r9Ga{IiAN0il_&v!LrAwsC}JBE;-Jp##a3t=$;9_`fx%;J9D zRZnRpDEG#C=U7p6CXkr;>9c29%W(nhEz8ze39q3&V96Y_AZT zj>+&k>&8#g6758X>xRh?YXZzL_k>xLft0BPNyo^>?i!ChtG@d+Y0MdbDW<)fTw_^T z{u|F9b<@kwpaX!Bwg}pgcp%cf>(q|Ji!@%qysq1Wi5Xd&-rE8!LxChL{^vS{r8r)` zo?af_Zgl`h+a#{jmI=$v7i39Bf`5FhAE;3AunGu3K0&PBRWS- zE=)|jy8`!9#7J>ZK3mk~%4V5#AxiFPl>HlJ14rfrgb$hNPIL)Mc~t2aTL|ZmjCSf( z!V0A2lX$~F`nCXWHN`7ib)23tT=A}%+FEjns7n;3_z7IZ?L+Jro_#YY>V;%Kx51`~ zTp6e?6{i48^YEF&^Qo?d)uD&j)8>>ZUun{B%#IG9!)~r3k6T*vZZKTm^gqG;Q5w6w zrfeobiT&=ay4>qg{QN6DKw|<2uwxP^0X)9dkn!GG7uZydbjd8Bk{+VU3!cpJbBx5{ zIH`{-wT_}MOKguE%k}|JS{1m@Rr#|~D_|h<_@Hk9BOq(CVU3RswHZ z%b^s46c*QV5ex|mBKbAW9zJ{DVLUO>gdnIQnO`)3FE6=eF`E>cdqaC%<_lc__PtXZP&W8oj- z5o}rzO?u?HYrKE=z#zi87dKDJr2LYhdt3a@`eh&@1N43+3L+eHf6D@E9Fc6^h;q-7 ziXi=&K;k$}Y63rVanC99;FT~?m|sPB&nji9E4}(vAZaa_8}yC8_$z@=&E=$U?K$Qq zdNmb&PBHSHBGrmwftxx_{Q#<`(1JV|qz(d4Kwjf%g zpt1BUGA0s0baf#@w0)#PSI$?CbR5*p^_iy8{KR}=)$rQ zkl)jx=!PS2n<5FCp*@Fati=>V*hKaRNi=J*L8324iAYm%O9K=Bcu4;jIY`N{hgy4| zu`7ZkZ3J*DHc4@=Van?7*{b6j&XVo@QbSyAB$6!7-NR^8!y391Pf`;}ywV3_EVk9+ z#wD!0ivv~U4b?T=W?OMCI-F6M5!R5+xCPwoQxlH7Tpoz6?CYE-N)cs35=1JaJs2`a zWHPEzliP+JBn}9)`Q9Pd zaO?1<1RAzQzl{NB5R3ZBxkh8+@(_YdL{jZo#|L$US9QnZw#F$4(aI6P>!vERYP#iQ zr)x2ob0Oun*y8G(S;PCmZ0H;DaJejUhN`*x!U`u#b&}gvA}W@?pdZTR4e^XUjBTnW z4Y~-1j0I!8Oq`d@+$~KXs!qQ+bdv;h2Tx6*dk3C{j6IutS;^r%dWfAz1g8>;kb!9K zy_|J`Wcjrv_aTb9_QoBgC`-f&Hj<+-^Dr_yBn`G5yW`yz)Gy0S_kB)xl&+-d@?nz2 zv6m!3AdpLrs5nsQP7%_R3DIU8V_x#w1ajj|-oblZ^i>8)WCnR!@xf5g2Q6Z}S&H3Q z@tIE^nE^QYnE?fe03PxhM4Ho2!j6Hl%twPYg)fH$jR;Piz*QN;J3==D9jow}edg_y z`;*};Wi=}<;w*120sx7VsV7EsEf5m)x3mZVT0w8S2`68Pa_}N6?^w_at%7JO>Q}`8 zxIHjj(2PH!095KPMJkg}dW*#fO<0agFuuxQX8}krftb{dFdhMDTwsV-s&^@B7bPrz znUXn7tK?Zu(|8DG2ol9WbcjH(wJFWvMdkNd5{wWbheZ7G`50Anuonm#NpN%zW;8&6 zDw{g&(F!$EQ?%pC*wPH?9Y!E(F!KR8)M*7NgD@r%y#qfi^l5-+4|Zr^dPw7{&$5OS zun{76ZPhU^B##zN2{+8>7if;u3S+e^O&2?5H&Sf0t8}&R7ga1awB@I?iw`BM zu~xB=bka>UNG~>QU$xb2blQnFzjkXA_-+zPZJK&+F!SqJ)NWpN%wy*0fbB2noo{l} zYZEf)6m9GDVySdHD;9(<!IDMVfq7CvunV za@S3ccJ>~34#f;Q#J;ZgY>kDg-uLL|x$aya8NB8ifN|`&FKydCY?F2CNI>lHw{9OT z@4naSKBj7oKdK`1?k(FG*8A?A$?f4EZY_)HHxe0wpoM;n0Zg4ipPu0_g#9fdqn0Z} zl)Qa{EyK22qd)vcM5Q}mpAEog44-Tb(n}4;kbX{W8;$hrex&XKIDke}em~&^b{-ja zK8t^&7B_nH)u&hgNxrky!M=xkyid4d#3(*N5Y~ppq07>?i9@^#5w=I_XOQqH%K*Ix zTlbA_W(WL9;>-0nz8PcgI%7(8Bc`%V6gv&hI(@D(BM|`;4m(LUJ9bgZeryh;J3SLY z;5P|uT^Zz6%wt1#c|8SWB-tk;abyGOIukWBL&XszrE5J&{R0ZdpX*SE{Jo~SVYAvZ z2K?6stUD$jM@I}ZM+S^$#ydweb%t=*CT4bK;?75G$A{adrZ~_C0%bqxo=i>rj^(3| zrP7Wx!%Q8q%}hCd+O3$n$eU}Ynv9Sf4SJe;s2{4V9L_{Y-=HJcS>yBR$%$<%8 zwnR)DrcdOrPZZh?C^cdmGPczR9J2l1r_B?D@+}r0ia_SgoSu=C)gnSTzeHO}SmGfkl>t~uRZ(7FD z6L(w}pJr4GZInT&T%yj_u@gH$q1&adQ!Q`R;)hhKZ&iM+Td#f=nRXsEqtcUS-Ck$i zcWqsuZ(V3-JgjfiiyaXqhTTSNJg#rrJ)+Y|$vWL;2Ao5-ts60`Kt3Fdvsxm)NMf|k z>$O~7IX1brT8y)8th3#;+cD}jF0!+p?=@+aXPg2W?_Aq9w;9d4F^#nGPH^z;T{G+> zn>9dNR{6=Uq?xVSnH*4_h9lc-q@8kyUEL7V4gqbh;%s)G%(X!k5z6a*JNxG_gQi}) zvl*L*V~bH_yD>APnKGfHw##pUc0PVLr)4)=OSYlJw^Lirg+`%OlxorB+9i`gBv`xfqr zIi`X=(yYTZ_C5@X^&qy>E#=S0Yt!>Odtw-%V?WUG255!huSd~70e^Fg@BV9m_?NK2 zZ5pEkc=)e$^_z78^Q{plGEQd(PN#3cU#l}tKNy|9nA?+w+k=`GY~lBx%kN3-@0a}U z7l`j~>zp|SosrZXKk3|G=G``%IpIS8I)i=?I=R1Ne4uXrCAfRPC~zqy(JdVhVr|Y+ zpBjYb0MHEprTJxf{|AM9D}{Qy>m~pSEF`yK0FSUX0nEMV?lq%19NH%|ZcTu4A~vqX zqYTcCn!;lh@}oEwEDG$Cw*AA;os2Z12g!El>!e49j5N>30Iyt4hqF~X828}BH3zC^ z7rbXD33n%{5NCyFx92o__h;MvM^a#A5Y!wF6Y-`9=upEgHc$e$fsyfC2@ zJrm_T*xNnA{XH`bED8IpXm+i1Kb?oWJ49)?THQS7&st{fS`+oz7cspuKRYKrKbM+& z6&PGG?4E_WJ7)KJ()2o~o4Y2bzg7zV=4^Y+%X7r%^fFSo-;VRF+kK_Jd6ivxj{fAC z^znR^YL8d`DoXsPO#C&s{h{6emxzQ*wSre@{GTX6@0Qiy=fxoE72NlByBa| zgbUqTr9q_|Qg%y?R-wfrwBBS}`DTIf?m`bYj@4Ed@1wx<m={<1R=L`^_P{HxN+$Hu#Bk0R#{vJK-C{+k2)@yg2oAFhy-+q5|zg_1I+wJi6 z*|_JKOgBT>c=vu_ZJdm+5ukdT`OS25VzA5V`$6iqYXPplWMBeIX<=xggEqFOf^rSD zF9OeEwjYYAj$07sB1Mf677rtdY2R`ymoOy=wAcl?Ss2~=2Mw4c2 z$A_FkW*~GITu%`_#Uz&WC{>NJO)cFh zRq8n1@+WnfCa=J6${d-XakFfTk+XwLw~2AmT**+&oGgjs%H;yh>2-4ze{^@M_)z^L zYAqi!+VpI1ZLi9LB>9cxA~H**qjH%rTH1;%J8fJ|BGohD1xH+Hxldku&od3B`7Zr8WoWU=w*>4|6RP0sfEI(Z}@ld;tCu)=R4!~ zt1g-A_L~V1w73}2Ve0*TPFLIh=NN&Z9}Izy88`q%;KMu!N7v2#1Bv&Ic?eC0?+d7S z;qzq#&$|1|D3SNumod_4K9+HcY#){hbeJMA2qfLc5+bcbNmv*}T_Kn$mOmX%lj2v zcC!Vjf{`!BAFED%3;fe2B6tstXh<@ebew-G@CH9ND*%9??gv9}2!Q4z0mrE5hhk|6 zMD`(p{7n6SEM6G(!-CorZz!a=nxspLpyGuY6&fHx1Q9C0j005sM3=-j;t0CcM;`=pBVcdQQ@cvK2VIAVFu7Ftap>-VJicv8?ATt7hIt?EW zEPxAk2;zG*EWp7`l$@n0InO2%3&7l21u%?CF$sZTBta#x`W2V&LqRY24F=34Fs+3A zCplfEw0Ofpv}+6nbFfw-w8u0&G?x@P*dCXvzH&k~CM8>OB`O^uNf_c70i~noglZj2 zvYToN+mFtENtVOt984;n#mMpf)cf>vpK>nSv9Dp>bE&u8RBUjG5zhGJXs<(5LJ+ib zf#@v-(EQY2F{Zux&Br>m6cfKwON!7gBqp_#Q1a7A zt5hwdHno&8`qIc6(=KK%w1A$QXyl!%7IS~KlncDmCpU1>~etuf=L(_XAvX>Dq)wezip{@)TA zFfcG!05~W|0&0xKX44F6mkZ@{&y^dp8g*Y6AVz;BNzDqwMb-TfhsD0nV5ehi;D}WLIMIYU%n)P zDkR2$95Fx_007!`3j+hBZvKjo{KH}h2!Pz5&$zg*K+FcTD=+WUKR!m9eEsiTK^2m} zcK!D4!`k}8*%|2T`(Mf!(2b9nn2+S-hnyT>R@PrKrn>qs8S@=<&4E}9=w^QYzgSFV z<1+bZTi?GGX{NdHY_{w6Y?$N~M}v5p`jvt~Z~cZ-DZFCru0xMeQs5AN3T zSBqp6;19qYQzFE{RSbag#w-yAz=8J%kSd$NhLZ+cfLbK@u((BFa3+d|(4W(&=OW2@ zKrIp#wZB^=8lV=*x4&B?9g5&^W4KE3Bp?0D!2zVMG$~@5BIaXh4FHuoCJz zIRFdSNf@9{i5gCdX^|-eFv3?3%rb;ep-coQl9XrJEL5DRV)McEW8w{S?utkfFPVD> zq^Vj+;R8r0q&TEAcQav-k^%sq7;lM%9V}?(QXO2nj#2<2=QNdNaq#DPH5^AUVL&1~ z_#)_Z#=YWC3WEaxED|S&O7O^YNilG8^uuZZ0=bu=e>e66Euay3X*5}ro&*48&SEh} z48ZIM#YY@aVW7aN=fZ?+=@kP2h%X(N`4F$G*0quH1VXKs%CB?KamXbM?K?qqjGYKM z){>vFF_}r@)N^Q(+Sw3~;XejA}TZIq+1>U121SLk`B$h^S%8NRK zc}kBur}$)U-o5!GVdf7mNxj>4W%+tYqM@tB9{kKL7nn?dJNTIDD!z0IECzpcZ&~wz zF?{j~Hjx6Gg?=!S{85ZADwd^0f(ereE|*QR_=ax_3j+{M>=erJMh-a6alZY1oQuI0 zk&JaqAMlf7G;T3Fpv?0N_BMP<=Mf&{ns|GZJAS~YJFtH1JBK%Yp<4iC!AlWjsTOZb z>a%+&X$K5|EO3lq;l$h5@HCtNThuNh*$!8^Vt0a7u={BBfKf>F?H3YfJD}v_ec=7K z(XV3Ps4bE`L-ru*0?%odF{l_SR8H~$a9@Yu&mA%JQI6J(gX}7M;@A_ zFTy@5k_1hntp0F@5-?hZn9?v^Gk0jN-h_IeAf&pM&<>;E<^tfg#>POi_e1~@BH@bS zsJhb%B$UM^q#j{VCEK?`LYL{Ntr=pUunrTaMdmW;f0OlXGr8MfmXI=$XG8#!9@6&f(9z>_-Sxj&${s((^6%=>7;CZ|W?h@Qd2yP)H z!QDMraCdi?#v6y=?(XjH?(XjH)-3OP&YYUFGc~of7kjmr|C_$*YN_Y>{JtNs3S^<> ziF@Ab!8)*r7=_+wGQ441ycA->{x(%3&U@x6?3;=LG`yuQ^JY1mzkOI4Yef(mz_b_y z&}h(ZvDPjDK;MVpe%hB_J{L@1UqH%lao?F}(fb;;Yt_LXn6KaBlA=Ggb1Svn5K*N; z@gGd)3=Dlal8W)T9>-sX19B&X`YA4SU~iL>OPaz7!m_8eVLOi?GLOmuDtroHAQXNg zVHH?g`^JF~in7a0NtGvfIiD5kT~ueuVTeG3n326u4Gbt>ERx*URO+{&c}*f*qag-p z@~h|2z4(K%nW#;tVu$|3Q8X*L0j$edzGfin+T*K9&`1W7M`!sqP)R(?vNEwr*@V)H zlBDD?Z9s&{{Z`c{ToRxo&odEp5r}qAxv3q;Ka)0m##cyJfIzIFO#2-Mwh+zwj^_JB z1{t4}C>Z;YrANJ?>qQF$17< zUNASQE>%YJm`fDio)THhRmQ@ou9Sg>QaL75#&rs+^znT+*$&Jmv-YYKiP91UTbz&7_ z)#h=8&9vid;x)OcCrK=7Eb~f(HMLb1CHBk9vw325eBUf%+@ERo%fy>ziOv#ZmcO0< z7;GwJwkn)iUOSBwYhkOl`m@48^X4hu0iAZ9aHIAO7H6;{waPk=Wn~jOP^|0gH=9UK zcWN9N@xJfGm+=ZK%p~P<{owg3o1B;zDoPR20qSbo@SGMZMiTK61MaK18g=HM^8+LP zRdyLSEBoJ##Ky?J*@wQoP>Q_&;THl3hCY|E(1x$iiYJdj6nhh)lG7L}MWHezs+QVVzNC;4?rn|qRwj9IsQ>P5DQ#}V7< zZ4*!0dyB+lRw~_Lc9`u>YtjAqG1SfYe(k>6>H6@i%+oTC)?)Mc^X2P{TiHR{ot~Db zI`13C5n}V70-T2L1R$$tN@Jn|qwacFM|AJcnLY?Op2W^R)T}`gj}!x*qtq z1P1De_#^H6fGLavtRDg_2S5Y$fxZucBF3OHACT-qfbjvyQ5a<4gzpv!f!G0HkVkVU z2y&tdif#zl>4QM80iaT#gMy_+1F|+@)cwVh1koxRKvk?Ec?Xtx=&(vmXum2# zATw2!A3|(&$ioIgyAtp%wP|590i-<;zc*l)8p2i zWeow{6M{78*9jMevgn_~2eB88*7^|oiS17!E-3pKy$!Ft8-N3`5JVmng~tZ=EjqxH zm!+V#MI%%BL-6>A2`?(Lz`cgmKZVNdTO&T(VkD&#l|dW%K{K^Pe38XyvBD?|6KlOgXQME_(L*yE6BoN6b8qSdr@;W1#duI+g85-Q&tVK7TY!X02t^`D95<2wF(L9W+6OKs zE-_K3F(INMF?=!66qK0DmguaKh?*Fj7lbXU98mO_XgL_4K^+%n66<^D?qFgYXPi*^ z826_!sU#?=tueHUI=VD5FbO{Sy{!~imrOOETv{2Yd6+Vum`waD(jLs0TCI}2rji;; zoz#$+;txuliHj?mi(Q3Js~JqIqfXN|NmD_OCE`nGpiKRfmo`A1(&>_7?UH;cmL^D@ z0V$p`U6|f|m=0f*L3|&d1e?kPn~5HrmfxBBJeV;rmf^Oakx7}pv6o4rngHvXuzW9Ylumw>Mz@r8j2Cu69giOz_f0&T+B61kDgE>@i}NY{D?-9|@p#f;%ZH$B+NEsv zrfdrQw2{HUoWmpxam;eD#L>bWv7!WqqiiYsAeo{R%A-U{@m%SlbSm*YgP|zhp{ED%8X;vBb|yD$46?Drzc9_E5#g zMkr|)FP&Y=C_u<5QcW9oO>4m~YNIKxq$%4*$c|=DiXAFlE-D)qD>+yyIYB7DEGp@3 zEF5qx30Ez9QYu(;Diqx>f5R^wfhq11FM~F#xale12rLG`R&YlZ-VT-AAC(-dW}G&a z^s-l8CzZpRm7TGtVIjt%NL0Wlm)0+pUb9tYsTS`efU6EoE3Xi$Z`iXo#fyPYRm>bE zxX)$poMYa#+6uoCZ@4lQzv>fhMfTUyYSp42h&A7a3v7Zb9-gY7igHN^GK6W}sFJHh zLoCSEYQBb;0g6-YGHawIYKcN}7EFtYnra1yDv+0JGj-||n`lpazZ29U<%u3}r zY8_3hERt)3#T)$HD*1=21rZyh)auQatCT~kMULyNo=eM{svMIWlicdg;TsES8h;=( zWfIh|5Y&bxmxK&AJkvBdBh)JzH>3wQ#Yg$d4oR{l8-I~4-v;?rXl;XE8s!wId^yoh-L(Ew`^rbaJ@0E=jb)mvj(wbVY@< z;ktLyySJbacA&Mi;&Ec3CAY(Ic1Is~tsNB|1~rnLbn?;l{K&63%daAOX~Q6F-!bci zdg-D=>OC6nL`CYNYUu%U^v0`IE01)1G4I+|>-2r@;gak#Xz5f->DdTrW^d_clI&$R z??spF`Iu5KTw)=r-m7ua3q#n=M%NE!8R=e8%CUawcjN3Am+Y5R$M1prvo_psfz$_V z$t=i(Nb-%2aPJLj88mAd$odM67zv0!kxdL85EvQEr|Zi6MMB6lL_gSTwHf+OWGKyt z97FNlV$cw@*%w$N--%2c;YgQyM7R1#A5!?8^ZO9!$cM&}F~X72myv^ldc&w;n%_g- zguU;Zr=R#n4Rl5mka{-N`nM&=_~Y?6B!{-l$5dL{>(qN1PKK}>$IRUa&PT>px0Oa;s-9ob;`@w?jz9 zmTlb?~jUEHU}+~#(Z=ayUMzOMHBOU}?} zbO>3@7@y3!t`15P&FiO*J9zYHSj0Pp&5I#h>4Yr+>F4z5C!{$0*rld2>6a|RCK*;2 zeuhnZr#8Ev_GDWuzFQo4izUR-1tqR|gVy=E<}S~$naZ#UEv|}uk7euA1#|iZ3Znj^ zcOo;oQqsC?yt)zq)>xQM?V4DfpK2|Rm1?P8ovPJXDO_DFCh99iUTPh!ZAZ3=U&WKB zpWh%_Yd~H^r(ZlQ#k^}ozc01(OIZn^TN{&FUDB8eE?ohSP6Ep2#>2Y(UT0v&Hjvwz zuEYAHN0UEFZ>}QGb)T;7rYzTmVf=hj?uI>G!5^)H>egj&S`tBczljUw7*BXcBHrLqh*Ru^)%enc}rG2R-Zt%9zSwCXh zwuR=d{@Ebd%5u#ve2uzn>v+^kFm0cld+T=^2FVyUndb^G%7MtKm$)>L)^i_PbB8{B zPYrw!OK{MLuxF=spaI^GJln;oJTRL)F!VeO@H|i^+T_w$k0Cm=mELx=+)e@S)~p?V zkY2V*J#Y)(Edx77Gg!rjADeR@4RGzomF^+G1+R8+?{$Xn zlv|#wo*wdfoGhR1sfMqbO7CBvT_BVnBAuW5jGbYloQcyP-JG3lgD*IU7BMU@rNS>v zq`_+*;ag9dmoQ!zzHN9#V~a$@7a-~Ring6k?Ps)BEiVi!VB+%x;%k7+2`R}j8|n&m z`Bf|UYzBNzzdW;mNWgf>+G6G>(q|1kIL%EjAY+L>+WUs#Fp_~ z8ue1v>P|o6u0{I6zx`x-Y%ApLUhVBph2hd#`Y77!A=BznJmL{J{-A++ol0^Wwf>OH z@HDBplq<8FxPFve{)8rVf1`186n3w>eg&6*8SeE|p!NJM>TDAOD#_EOS{U^cY zRj=3ct<@VD*_#R9+v58D8P5wq=U+r-0`0#cGCcn?k?Aq1G?Wfvb^$9KemszkP;YWL zuJb^^u~N@+dj#J+#~W#Pvcg}xt0`CV0xY+BydhO=cUS>17Lp^5HcO*P92{V-7Z(HL zltiKKT5A;@(-Bu0#xJkz`sRy5X7~PPPd}FUtli&G3JLBkGirj=SUg*FZFi;S5v<1S z#R1I#pXPAOXcx!8<;I^kU@jf!*oj_9`be_yxzjzHbR#ihFz@4a`x0sr!TWBFjZzay z5%)8cUqr`;`)`B1kpRJoFUYJ9sLe1I$rZT>^ext(p?P$fy8k?(kwPHQkXHH}&n;av zV^*t0388+UITz|da*l)~Aafr;MaC}ZK=xxNl^y#f@YzrxhPBXGq+jslqgHABi5Im# zqQ~4MRW{KO0;1CB1}U`p%0_Te8}v_go4<)nyT-Y?!@R-YMCSJjYejIqrrUXM{R-ge zB0GXP_#iWo>%B#?uxkI&@O^Y?(j#G0yRa1~;ioJBhbRO60ZX}oE^jVU7m;Hw zlJkQw9pbH$y?{TyLLYCP14?s2 z1M15|ByvLqsc?cXS-W}kFm!RGd^^p(^UtB>-+%UKt3_iF5V>o_LMi`Utw(J_*XE>NkePKO;><+XK z!T}kGW-r-CA0DImD4_i;=N z41@;JIIyAdg-RpK9OcmMcl7A0UMDruWilf}aKsEsi~50fDVsB-<&vf;7VJ^j_Nma; z@sORF5%wqp#l{OZzD2@>f#8R;WUEQZU8$1SLR!$IxQ(kb?o#0SAq{@XQTHOr2xq+vru<+G51^~u z`Q~rn2hyG}Q<*f5cm<7FFr*6*C&~Tff=q_KYkGj7baL%*? zqMCIC(D+Th!461@!~}wQ zRN2%va-_p_<}-aT(zY0rZo8C^{smNa8N5T@53)LM6+}3_k}M0|gU_EUO1( z;(&ch+_uKkC5BkV_d|Nf$|_o)^;L!-q+Q}p(NZZT&o@y*D&@=0% zSQ`o#tt#kAk&;emR7B(vqZN2EpMm0#Y_|;g#U3WDYK5Q1*JDIeuV-4rvf381PrVna zCW--fD)INKg%;Rrd9-NFvZF~YA;@zIihPWvWO?X})zW2=whYeg*Pdi2VRO#l++DlX z$aw&#+Gke+h_~Ipk^}(J7f5o<|Fa6*5p=`biZrjcYx6OTK@N#i+vgC*pc-e=%tjrNm#pd5o zOv7|_HHmAh^XGmMs-%W`%V@#w_54$*EW%b@zm}ip)w->PvOqLkwJ76w=Swtxu!J@5 z(4qzUAupt&*vbq$KZJAo6qmCG-E~>g?C}|R2Jx|LYFP$+cNW&3zm>RlJ-Ee%oc+08 zKE>>A?-rbzo22Ew%oTqB3$|oNI@9g5h`Q^@KGAKc3`fUL=40S&67{)-zPpUi4ZyD`MI@Tr8?6CI){y?-3wX}?w2c2`M+3O2 zzj&^R)aH)4OiwRhfp-f!?&eOD~a{9V%hYo#ydSXk}mn~FP?%V+p3T55LDCVK@A;~qgHd-hnW4&n#zNU(CB z@D#1ZO}o@b;cotxMVGGLmvl*{`3)*h;r5Rt0}-!#dL+> zwhFU1zlw_@5e(|2h)UVRGYR5-s{k$NBQ*Ohux8e9Npoi z1rw=!Kp*vU?gR$9ID5Lu2YXUF5-ZxZT;VqKa_|I3%E^Nbv*XHc_$P1Rz=rq@ff>WX zx*fxUqoLK3T|JWAenEOj2~)q|_~9glpV}sn_$*_@97iOFLgBtJC7nvZ4Ip`ARt#)} z4sIt8!u;ytuYtD_O!Q)hV?%<#VC{de%FCrlU4%+4rvy2*@c5DP&y!1E?-aG{4Aya? zemWE(r3KNL=g_*3QTVlA&PZ(Mh$TB$0ULRJa0M_i)6;qc-a^M)k)l&bJAsR$J{!{P zlCqD2Ob-g;fZVYZUNKYx&@G{0TY>a(3B{rLxRaf%cf}xa$DpWrj#$eC)^2qkxy->0 zUka)C4MZ;*S})%21T@jutA6)%3Vb0F?ze_o;i`$vUlRjWlW$1i@wn%p3M5=|Qfgs- zRtyihU_!YJIvK3dpy*9+cwQiY6$lG}5KhYPqWVRrz>oPwuDoY58tnrV2!I9fMll9L zJ^;<_QyIR)PlaMnV|G%%!XZTh2_DE{fxw6qX(&Fjve21VXL*htc*q3^LR@d*D*%eE zJm2aNmBj>UtwIJIa2UY{OPibl4mjGNAgS2IQljtznk5{8hjjLxO@hD$`9c8|f29h^ zt;z~IaHcH)wa7rU@JdJq;>bc0^0l*DvOq+j?^**e)kFzD7mnWpTcB6eBn-qiKnx)Z zqyj3CepkZwo6BxcR7aNoiZ%bspq{nDC#+bpAZ11UMhciTo=CC7|J!{Or#ui`@<7*(N`IW ztgT`dgzK)75FfjkXc6y{xtQF$XcM%Uvb&hPx|jyN1bSS|;KH#gMWdAkn!aKNta4Nq zq=)6kw;0QYAEz{IQ^K1!|+GNnivb^DCFOu+O~4V zVMc@DvM<;TyWwJA=8PSdt?ZSs__}i;e?zb=Kh~&yF`JJkSGy-)4D^tJp`YswTj*3A zXkTsY7@ch0Rcms9%XYvT#v1BTRG;wZ>!xo5w>h9sb7|B-uat7BjUdYohN-a;sTEkL z&7V%N<|+nqDJ{p&bfsptIQ(8$40m!MoO#ulqDR@}LfJaynVe>lQeS9Q8&YH& zSCm}iQrwX3m(*O!eCFdIV2>x%{(OAZ^$^qa?An}brDH7c7yLYh8EI`?6l zYpvQJ$Fv_#H!gRzh?F)U7`A-4ww61<%S14P=)#)>YjY~S+E2L~#CJOMWh1D0qa=0O zG@7B5(px(gx{FNO7lWJ8{#)NTx0^ilSkpGIN_EySW5wYQ(C&PjC z+D~)Ol>kkHptOUJw0izy1_7GJVP`TRux2pBuCK73WB9wUF?9DdaxVL2_v2So+Fuw4 zPHB%3=FnZ~aQBOeBY`n`nMtzn;mhs8YpqfAo!zOv6?Wgx8KLJq;@QOe~dj@)=ADh>Z%%^y^U; zL!^(=xJ~LT&5Y+vvQW%g*UUPlH!?Igsw}m;P)>Tf&3+P_HiC`v&g%Ql40_MZ20h>1 z%=?>9w;XIbjG_&W3z+WTGpZ3b-`qKpg*k1aIGrNa7~(c+Cf3V7+e=w9@A#oR(xg<@z}#2UYA4S$$MNLKaq1Xl2BQ7+gVVvQ(mCY%%6*;*!u}z^=sXbR95i<^Hg=9& ze*hjkMsu=6v^qN3tJy=*$11mgO*fk4=3iQ~*wi%Z`*8_vb&h3p0b^t%WOpgGXASjs zshVS>atgl0?YAkWI759i#`Lnm9Y4ADJi3`Xe}l26=HY@aH)r56WJ0~JsXHgcxo*_7 zrKrDZ=(EL`zoKKfLcG6Pu)IPdu|Z!qSSLRHyl#0QZCAN^$=H5P9brdOe$Ll+EYp3{|Dy@L>m zqllFa$^zt1WdJvX)q|tMwCA1D_%)XuB=kiI^+4R(+^xl%x$;kI)bT2=hTq}T_vZC> z_Fx>0Vuw3R5~;9iN4g2@xLrW}7gf8;MIhyaAKsFWh_f@>gP+lZ1D>D1)dPqz-aFpe zy7C4o>H~Dc2fu}cANOc(_m1xKyOixrIf_eM1wh0|GCM0rW1Pp|5qHWm-w;4P*>?|^ zzwhD4A9Z$F=#+u13%(g5m@bUB@%wjfB2Nb+%o1Y2JQ<+#{E}?Bv1_@t0<68t&okY0 z3%q?fxOvOM^exTxCnzs_=ULa|vTGO0M`o+XNGF$U9@ktWH;cgMqV>nZH^-8E%gUct zZRc)|>29?$t~wF#m1X-{OSi6aw`N9n*V$|Q{U`4H^J>Z`MV|X!C%dBYs}>P=a1+T( z)H{)he^!@qpZx9q4rgj9J;uGB=bSw1Nj!!bJrYDbILlud=G@-eJfz#7E8cEtQ5~mo zz?=CVv+*8tfv?l3uUjIgV>mDKl;D!JS3wGg*)xyyI#=;Gj~}R>dorH8fu0e__Uy2? z$woJQ`;Yyge^UXU~MUQqnFA&P3FUGI1X zbuck~<&E5QkyesWtLl+id!@m+;i2m8-cp90{G7$|z05|Ze{_pS!h`vmX;cIY%F3hN zUIeU!R%wfcL&SuG)qYy5o>Rnp`!o@1{7c_Ol(7p z=A~3&?-wxp;M2SxiXXk7wb!v9=c>g%(FoN0#M6WpBTy78H@q*^NVe1+m?;cU1msn) zp*K%r$p|;^)Xazvn^%A5DxQRqv7OMb-{8ixtXMp%IThNWC_IZ?4_?k`-c2(5*o0ll zvD3=lm%P&^yeDzgGRDmGpNNcgC#Gx$p!;7$rVBw9_&1TU=|%JXi^$l~RSi-Xw_J6g zR+rdzd>!WeHu`sxS@$U_ELod9lPyC#*v7j3-2}5Rs}F z)|iX5+SkVQf}+`~2Q2sdQ{w!=S{Z4;XiVE7-f z-&MlGM$3SDfBkBZb|EY+wqQTXrZi#278@$d#=>SQ^FFWc9%w!j5U=E|6#z?v^)51T z+IL8Yf2P0qDp6&0KnL{v>V&r8ZTGnUz{U6(8xzUiGvXu~rR`y1T9gk{t|>xy7tesZ zHR@)#{4+K-S|IBQ8A|-OsaM$;2o$6(1VmYEIgEuY0ERWH8|%g!4U0dNb);{hS^6dJ z4s4amhWX2~IxJU0CstL3KZ83NlHNO!nW_l*(L#n|SI|v#RT0SjPGo$kddM&;LBgD$ zFro{3zA#q?NxOf-%m%UWykAJ~QUgI3!SPYsR)(P9K>=1S>ivIMW5fKC;YX4at|o}G{Hcm#tN8#p zgBJdY{|R7$1_w*?KHuMf9&TIng*kdKiduP+G=>EV;AsNVM$nJX$jN1{UhHCp>p)m- zf&U7H^=+E@#;Mve$5vX+>!SJAtJ-qUS6XdI+J#Pxx{3fUI^B=O3%$&BmEj(A z`k!eR2j%Lj;#%npYw^(j`}z#R2grZW8ffUhXbmwoHUR;_yRLzR{BLxPH7x8qumJ!x z{-Z_X;Q>(mM}S69Q1f36ntuz>KtcUyWAncQ8!oO&fb>6f%|9K?-@4{d$LZe5>FwRv zxVb??hXVlrG&WFBlK{XH0I>CstPK+2`X9^&6Y~uZ`-Onu9oXExGaFjkf8d=rLBW5f zY}C}=tgO!8U;A%k^DcM(M`IHb0)9`+Bqv|z=Dr)7>-YLhQPEpf)q8*@H+Q|d`kw)s zn3%unGygC)4GmX+2WtMwZ2oC%{sY#$tD4Elt^f4&m$CVmuKEADnSb*x{|_JDX$|WC zr!{}m8p^-xGxh*N;6Z-`*iB>x$Ffbv z&S0G`f=`#h3ju(u*oNUld7Q+0b%{0Jw1W5CD!3*514dj*q)!YL1Ct64f=? z3=>R?4)zrA$>Dji7>6i716YVLjoj?xZniyf9RM9Ll&`-4e~2(yVB-UDvj6})I+~np zz(i%ihcIq-5%&Z+eCq5NRaJw$*ftYWc`qoYd{2tMx-(!FFa$5aj>TFifaKlHKq|pO zZDS!Qv*wUBo-G}d!QMI1@fDUmrSVoFR6s+PPeJH=1w26TLXcoucfi`KXXyI{_H^<> zlusql0e+)Rr2|PChG=W5rPVA1iILbNo53c-@AaABVL+p&v2_8=9PuBaSlC|)eoe zOBAyRDThzR@U#FBvc>0Q3fMrti9qAa0$BKubyA$He z+JMMJP2aYGegl>CTOE)Wfj2XhLFbbykdYQ%OLkuE&q{0y8jOKsqiIUC6=s z2NWA#XoMVZfbzyR`vxyeUa1dS4CxBYR5PSe0`Jl_2dX+i48TN!`X~fP zgrF~6g#bW@kVOl*g+)ZpCTU06Wb`%<57Ly3L_+p~PE|qk&K@Sj;-wT}PqGZpKTaXK zP3VWi=t1+_mV*@(?c#5P5{ExRB_i+hCQ+3kRXW+k4!G-r+>P}7As>$lKh-W6M-!sf z66d9@-#6_c!~Hv>JNDB}eyh+GuPUzYYg0iH060ndsQS51G*M8#X=2;w}S%&u=K-)C{Xs&+BCsv`HHOIZ|A`xtjZPJioxA*CG4iqkjy6}|AmwE$RkN|&X*G`H**kO4zVZKc58p-{U+ z96wvF@M$)JuD_wq)1o*AZ+E?sQPKYgfCdfTDglC z5Sh;uK&J0wBTt_6;b$JbBAi*s7j?Z|-<(12xvE%t(OZUzQ7Qb}YSO5MYABx>9_tQ8 zdWjP3d&Lsy8+c*j2e2w^fFQ`3+C)W-6$r4zo165!EsP-i{KU}IxPj*bY1jNA7QYaB zRad9{!glsUiFJDA8S*C=tO4us;K?s(kyf~@%3YZ8k&qO13Vs{B{;Yscx5U6!B3nlH zZ{+KDW%F(4y=Z(@)@2%(*fju@3gG``eMT|I8>ZpE(3=0DK9e|5W5O$=nSevH-aGVr z4KdE<)9#|Z3#D3_M8ZC^A+uQ{rB=8UILS`Vu(1Y@!7AW7(WPo{e&&(F##16~xyp!p z+=bG~QYyo2%BT)gl|E4TCf$MgV3x&|B1l>yXPntYoROU}LRudSdR70 zD@^cCMmri9P9nW)GM!Fso39wIR(*#xQ+wQq~zDoDDIFF?<<&H^sc2d(hV~ z0<`+JNTOKfSS&Haol>^wI-L!`f@|mzIK4Xpd@e(L+|u^GiMw%gAw&MmcAib@l;2^+ z$2_X+(z-dnkf%#d{G76r|NXe1CVV}*7;67(xaE)n&s9GsEh;Pj`B0hXsj=1EzI40y zh;f`fJ3jnl#kTs1iZDlEqo+e{HvUnO68m!Z*=^1I>X}~p^Wv(dVcR{?gns|Gm2O?f zyl0Ii?|QM#Vb6yKI?W5Uc;wlySI)gZHOJy326u?6T|yMnCK8>7_f4v<$G-L5VB&G* z2%HUnn{royC83{n5|I#2U9#!;zAUlJqNzi8Vpzv@U|Zv67KK%jIz~hy!}UKjQ8{mjxid# zC$8QIQYy%dw#zs3vp1h)FBF5qNJ5lWBK5(jvh#u87MgKwk_hPjtlZp z_B6})cboSICj^3m5}X1+ZoUO>&Iy5@toWWC5c<`0&^Cd=RIYXnR$`(SBpa}{9e_6j zJD@1Y3MZ)NE-0N0RsvdVI3`E}E+|4Yq*l~7cN6xn3=LWcl+MpU5YCeWPB$pHkjgLr zYjCgNUr7Su3y8`a?)Uo4jB?oA-}RaEYL2CU(Hhq9*@kaB|DZLv;d>2#*JoJ6AuuCu zl;8Ks!>*kpE|mj~`Tok#Z0MsUIfrOA1f>iFr*FdIRzN_KhvX0V!7RF>Kf31Xz~NNz z!henIQ;vihj7l)XpXP_X-GtT2i$YtB3ZD-`>x?kafkwFa!`KKG&U>$0B>pKHFpnz|2ODi47yi_yx7v79O( zCA?4xlNceFNRh(m-;J^2kFnbDF<}e7Qb8WSsAKgG@hME=yl~<$20KMmHZ1)265ETbD>Uc4+1mD9b)u50-6BqeHAB)2{xI^P8u|yxX zM9H9dph{dObz;_Iw3k?%rb=RlOHzSJqRU`hkXVd=VL}A8aXMR4*<(_riMh<6iB%zH zn3zlVAQ~Mtjvah*%loxzcwpzDdt#w)KbuWzA^z}V@;G=fWf?w&FDNlt%zKkMEoU&v z^)SUGDD4nFbsf)bo7%V5B)J$q(Yr9UC^6}nIyrYS>EST`^)UU(B(26Jx$9@@j7w@# zUGlw2I^s}95>D!zQO2=SDnWd5NmOdvVk%xy<{C`ql1L^AW#-4=i~{dW!lZN*nz&uD z^t{BZ0GKQ?{P-r7bb{cl@21&AOKGc=SxOIS7lm=vK?zVpiQM>3d2U1b%uy*eo4Gnqd0=Dl9L4tz%~Ni0Q-QCljV*$gW0S4D zYQFlA+51?n#ZlhXU|RfPn!k9OfN6m=O$L8aT0&Cc%42>+k$IH3UFlI#tT?_;aFMcW zQJrZ5A3|EXDt506dh3ykb8u>WQ*QH6aXEW*<56KILQ$S;akzM%EL$O@Qwcjx34BsP zSW;f^Q}(qK@|o?mC~R}JdPp=#N3S|a0%&f!KGp4OJG$Gd^z`iMb_71hUM~?p=!W! zDIIMk*r(ZXO1kwazEkjV4z_snz5Yc-AlH7ALpZAvU!Xx6U+|FVMCg z54Rl**B;T<_&zr-x>ZOcwyZY?cha_OniV!4H}0yn-xOmcKVzqwwZWxyd?+ajAjo`1 zwCJWSe5EbkK5m0F@5BkkfIh*7ZRv<3X!yNKV*+JJLn}l7ak^ ziB5>wu8RIW#dWTz>8-ef@uhR$tljjug_5pulA|5zrP<}VBPp@{iMESfy^+*CZ}qq} zdbyIXxP^`OO;c~1mw-B-?harX?1lRiDVHja}{Rmol< z^-43O!f)!OZX^94Un;1+ApJDqDFQ2#tKFTie3iSO2)`L$Fw)cYFfH{-Nz1EhN+S8A0*LI z3CHaThYF5|Fpc;;LXO#nAA;~RSlZ}st@x@&2q0! zKq1W%HVlYcOzVZsd_L(V2%CFVpL|Q1v2PuxES>UrZNnjIH_@23UhT1c?Xj}xbAO%p zwV34_X~iI#i=tn|w&=xOU2xQxPh6e+%{8Mt+AgRuqi(+F<1rs|I-g8bP3KXm=3!-- zx)AWPfQ~#T!nIhdvFPftnCG!v5H=5#TGCow&exa?P0i+~?=F=p94uYY*O+3_SP4m8 z@&}Is&55kbOP7;QmwAyUAD$P3>1O4L@{75uhgU0hE!IZ4rVURgjObT`M;EJBSL=x8 zucg)-xaJp#RzK3ObhoZ*()YZ0Os~DJGQZYuwyr0ft`#G#uY?Uiw)LQ*Y-Xn}=ccZ{ zwl254E@Kj}^pvjRGHiSdU&kt2$Fbb}GPd!CyjX+0MLV|TLcc|rwgJcR-kMoS4O_`1 znr1884wUMvSY7*WxrKMOenGHJV!3b|wsRl0;I=wr`Z|50(a=BI$041I&afnLwk^fI zN~W=^M7$-Lwl2Lk&EmOL#I@_{zDAwAld-yO+p;Fzx}hh%_k(yHWo%EwbN6%V8W;w= zfYN2cWe*h=|=_&Es6+6ZrGf=kP5d%?pFEGlKC;2kC>f*9%UDtIz4+-MhA3Ow=7d z@PYQg3Ddy|mDc40!zm)k6|&66CCUZGd3$Wxd4KrH7m`a#t7GQ#Yo7Eg1k@{5@Oc6M zk?`30_x2m|x80u+*Op_~_i5+tnm58);|y8>(&bxCX$O$)2QuSV`s+2g^5L{T&b5H_x%{tVky@w#M6KP=M$jG;dJRs4LXBjy{+%v?eItIjZ|OwWtI`U zbDciG&V)Ci3NsNP2%bS{IH7!RBqdQ5d{=@|BQ=t_Xgc6F5y?B_x)}aL3d8XvrzT{q zt`+^~$W-GfIPs&p^T3*@({r0MVWZ&ga5DS&qPl_2fkZJ>10wL@_z2WI9RnuHeMs1p zlA}DY2EekbtXj#KalgLPn&ahjJPM&8OdZ{ISoqdQM|NO%EYyoxM=Ss{q7%jiVcU-x zp%4=Kjo)tKJ9O&NhA(8}@#MI&e{gh|28ld#G(0K z)&6#n6HD<|xh9-`i?lA2l>rwNOalR3`8zX3${3RNf3bI0v2lIxVur`e6f;B2nAk~d z$IQ&k3}d!qW@bBP#+aFznVFfHnJ1m!`JYy&?Wt5%YOgw)tGQTLTU&e9UhnrDa~Veo zlrIA`V=dw!mM|e}P^2^KO~RPZ#}}e=8J)3)!%?NJlh&;dsEz@A$5Nl+DQ`J^H~m4L zCrH{-&7axrKmT0Ni?5y5Cu88?F!!V5nTBMDU>W2vief)(Hi}rg<1mgDqi!*dmzzw9 zE|WKHF-g|DumCqFt^nj!hp5k0H=V+xv8|LmdlwiHSesQPXYkK1}etaGP z3e8?9l*|=RKZGnvUVHNuQ3GNL8!>FXdzquW8Xb1&1=aj=>;2a)gn z%U&>q13Ka3fQCPW8kXIZSNR6b-!Ht^B~c!zsHpJUzR23RT%pv4A*#I0cHbe;juZX@ zJvU;16Z%Ywx(A%DKJl)U7$XZY1cZSoi}_Ru!_P9t6m!lgRLnw1>xQV*{_?R$8p^Jn>l47OP z?${PUD$f<+1@GB^>qeZg-B$cP(an#u z?i@=S4)4#yE#65V3TsAJ1iPs@gYm>Z7zt(x9WekN?X^NdDhkY!0z!x<;$?gA<%(3* zLhi_Jp+A@}5%JLZ6B=WJV2J?UI3@X3n;f0RfffEheM<4uFW*?V;lexv#i2&${p1h= z(ZMqwBjMe66zPQ#>6H6Q?Ld9h+D-=i@yJvy-11}oUzCz}1B_U(KLue`lB?7Ki7Lrl zq`&swGPUI|QTDjO)8@yZWcbUFYwB}-k*rPMM3!U~pqR8rj3t*9Hy|W~Ne7G8+K7VG z+`lQNR)sM=ZGeI>K{-g)?NJy-Dxe}TZjLv)wuC`O5GDkDAx(21rumgZRj*_r%?|rB*9C?s z6>Dg9qbqh$OlK{&#mq3C3B=R7;jPyp}8qaPLyVM4SDa&jKg>p>ux_0Q#m6oa5pUGk!52ccv zvmw0=Xb1yNM}n^!bXf0o^5PGdjyYOl3xgk_cun@AyIz zSe(dO8k#P(3yPC}=A1n+kl4;KNdLMM--(ZSQ7*ZKF_+Sv{QXO~)TeI5PuJdXBP1Rh zNIMjSZoPNl`N!2pH4F()y8cgg*uJQX zCY5^mHWoD#I)&G+1(~~zMXO3w58z18ygbDM2AvWUH_%NP`d7?=4-(!Q0v73_=FJud zRcsv>>L5dn!K`2jP6pS>>3kG5tG8dZD?G6_Q%FOnm0|5`L-G^t%QCFZc2G|fqAp7K zt1J@5QV6nm~d(=&a-D>4^BP4Miz%(5QbTR#j+1PuuA z2&bpK>3k%+hKlb3JlojNLL|m@2$WlV>lI_6Ulm<-`wF)Dm+-g3$h}V$YYPid$(-kM zb+Yaf>oOMp2D{H^OFq;C1g&lU^nk~TI>Odwdg@O(%OfkO)oeI17C6r#d4f{4T{7cP zx=fob1=VU;AL;5vEy*7@lR8~CF0?VZTSP;amlO+@Y2cQ2qvoCy`FI&E#J(%Ql55ux zgCH8EZhE_8Dqr%tm#z?QxX)}c-O{0#TK&}}@zq}*^FI&V#YgZQQ(a-5s-hz_vy6sZ z$)K-b4m?!B?JRlxw#vuaYJa7>uW2cCLU&Ckcb#b5S@6)!FIwTBtgn6KdBu0W}8{UiRjIM;G^fmW&n z!2$C=n!uiFq`n$J!(;3>mDLX3HKBsjzOJ{v=7_#h-|scC4N=wXtF2#g_IpL3yD|FN zTEz1?ci}ITDiNjnGoCw|SA?aCXE4g>R5|J!iVrX@H7f}vlz z;?mDb?W`Dne-rh97O(pfScBP8N*KyT2_fEEoV?!`lF(^!-annfRr6;=@K^j-+Ts}H ze&D-!!>mLd8F!muxg=Yh6xV3sH<6^kVSh*ARrJ7#PlOc5PzvAT4n`%i$At^5BrLy) zO&v?ty!auC`vUlV;qf3orw){UlLA`x`Du?C?Mp7*`a!1vknkYT?Eui|5D9N_!RO-O z@pk!GJqJ0J2q^&K;siKfKtcx1;JQTp_-I9f_}noRGTl z>wgSDlb>vN96t0MKM3q2)9_^@59D0-ZEulXw(4cx9}7JnTPB01R|h~e=YAKY+tilW z^89f*F7kRlSsF7`C?QvIKlTtP8&oG}XCxCdKlMJ(LGvy*jWxZjELX`eo!ut~T_KM| zC4ccg0cA3ZbTN&*F;?(i20b8u$32EFGnVZskFBH7AuNY6!GK1r@Clo7Xv}xB^>No zu7Noc$GM64Ig}l~Y>xRX`PrW$N@Z{fdz{uFf&nF33OqL z$_N%^POf_d9+f#;5C z02S~){c@0#y07(e$U_R~J`Q{^`brwd=ApMHX39w>F}eUZCJ{H5SkYxcon3fQTSm>v zL__P_%C8O;6P1<3i&@$Y4$li!$A{&wCJP@{OS&jZ+9>VfFpCBsU9L=;xx}mP3%LT; zJlp;ASt`@^iL(hhnk7sMsROg}52|t%8dV>fxD~6F6^ltQYIO}OYz>-O3#(-Vs{~G~ zE1y^I4K>}qYx0U{x_fCcsI2~gQG%+_>e$edI+&6`S#6A3?UY&1KG4h*S*!KZ9(K~m zfmwGm`BJQ-t!urWlBm)svOeCSI$AK@BclWwuvYo$#jlRNG{vJcCd1ZOp*_o_vUI>w zdNI>pptX{zvynL8?8H0%urm3eJwdEBgren)tvjv5wM?utm#KN=r8~%^J6W(|%d@s; zJ>F%lyBM{(Z>_VYqE)M-11@JyWwd0l_4YSbcE0P$XX@%5==20_mQ!u6>1Z7cY^Lhy z9b#=zpscS)>AfWCzRBo)Oz1Ub>NPLu{w>(RdD8g{#to*n2{ zGp&HUln^hgTY~hFMfFfFw{NJnE>Sing7lDZ76HsVuM_&G8(X&>21KSp2%^f{CObqR zFqpHAZle$LX$M1eBd=rY>R^+M7o^_>V<5<5_?g*|9(D_}ac5XXkF0PD$9tJQ(;i=OG9QHBTQMH^^SGA#@(-tYV5j3+_FX-(MIIayG15O zl%jil&I?OQ8%*AY@7DXT-;4ww_by|1xMU66bqt9&x3R!N4YfYj>@T zlr`NKvzgF|M&;KvQI<6k_;IkjVANKzk636##jFqAc%X%9_Tq18ycvN@CiId92L8k(URdtV+Yf()$&P3#K~J$Sc_3(dq#O`#smU~mq% zg3N?@k6b$U)f$X!n9YL+&1x2oG$)VU8_lA4&23>#6iE&&Y>w9rbzwITjV4X4Q4cLQ zH|;k!l4Vy@P>)kV=0UpVcBUqQ%)o?8V2tdEQX+Vu+zI|BFl*9Glh;Irde4vg*vb1C z!PzW8;;5wYFhkU$gjuHwbec_l;R8R@pOE@6#CS(^``AHeL$~n-f>lv(7A&KJdQRqVWLrxu*3w zoA)`*+*!xt8K_y-oI3hE{qW3`=_pO!NVn6X9AxFK1ssyKkg~DvmN4$p+8pYJIS#D3-?EJVg5w$&4wLQl<-8Qu?-MnmgN3yr?~@@BJEX%0(zahG)UqH8N|bIE&o$w_Gc z3GM2h2~!3p&?B}d(7#G1_ImIm&+Fw?GV z^2)H%4r$7c$<~f#$cmNaZd2y2-R2i&m&35G1D5SAXO|5c>1{=(!=>)8a9#(>F6*H+ z2j0I9AQHzxT@F4n5*q&{jwK6zwEKa@OE0!Sq-OwM3>55gdQ_CHz|p--lMP6R1FX!{ zxuuXw-~6PxWS(;LHD%}fqFUyclEL$!Oo|m(U`xJqUP<`CG_2-Tfft5??{D&G#-0`$ z^avCquxNTrCWi)gJz78EnH@PtBHRhmLDTC4nD|3WSFV3zJc_GbqxqOR*QrN7Kp}&c zeYII1G?p9<;heo_9G%}B>3zE#L+-s?Y+c}fb*(|d<^&umU}^llGaz;K|NZQ})u^Wd zfa!j=x^eOhd8VCm@lL*v_I3?;dX8p!0fDTeY1}yfKKrwrCy=^1+ukH)KgXz@{q=TC zVt30FbEB?0XJfyBA3Ej@u}w^Ni?Mym^Le5uy5Y`_CwRJKH*=I$yUjRqE8u&chy6{- z{;RC(0Vd>^AD^3Y@^cM~bL?NYDi+%uH1|JGH+p(b`D#u-haS?eEOL(=w5nb!L_IQ! zoS^@DbXS2x7>|yt*Y2iU#%%YRuGd;y&ms0x!J#XjNkEJ4qptG?=+wH=420aI4^EEZ~EQWKGOG{ zCy$FJ@A9e_S-y`YcFz%6uLT!yt8+7PdB0sRGaH7Gc@u^ z-vT}zaMaT(Mu^3;eym^_Ocf~>2}Vjf(Jhoi)>veMMjOiJtMt>uMJ${cH4Dx93SqPw znWmfUyhbz2>X@e+oSz2grIJ{*x}|RrZ6unnNBe$$P}sD`+A9u3i%4d@*VLNirS3%s zwZHrloD%sOP$}M8-#=HJSs7i@T5!CWV+7~Lq?LQI2KVdi$8Z~a&lWWh%2qnV#y+9f zkHswO-S{qMDEltcJK25YxT(Q*NVcW!X<_k~L$Z$dgWLU%Kw%e$H;-%6_4g@KjjaQ( zH~p=n>`^^aj{=zI6<=tuX5|S-@tAFiD66b*iY|JrZ-JnwzM=j}voP0)$k~-#nB-?a zS*V+d`mQwXZsBe?BL(HIAZ4q1e5Bw+^I8-Lrbm4_+W!GwCE9!;MLnhmyJaC(ocd)? zK!{o+E`FM4Bwt5am9rp7ju*Q?LUr=ML`y$7?7&-7alpjc7>CYO)9TLvb(*OmmYKLs zmTP|IEmLYihUrGwQI;R1rfIg!3_=`^9JTxYpGf*qvs?k<*H}0??-=8P6y8*zTD+*{ zf_erHokesqHSjbxKkEgkm}QfH8dcp&dsdz#IC^S`a@@*L)$#huP~C%g#sJkv-~mot z=-U|Ux|r<*>SiRt`phV=7E|Mj1>r@*n)@45a~m`IWm9vS2Y6?o^xyQEH|F-6fApD$ zRgZu4nKqWLkJmSr|4g5;)AY8JFUJ;}jU9;caqRYmbx@DAkNKp8Y@dzdxgA1;tgm1U zS6n;n2j{I{10ZK?JO4wDn~`xlO39a6OAe{gBM`0nC8v9W>NOW2L2%EVH-ki3@rMWr z`CI*zoGv#ywy>G>5S)@8-jIxPD9SFWem2S<^dROE?MwF z28+p;eX&Dnk!gv-=s%=L-#+f6>gt}|&m?Sm0L0$#*)%Gx$-_Nxf#yAc8zubTpxvt; zw5>O=FJspMnS7UdGe}JO;u*GRR0TMmPxs+{Jt^zreYe;Zu;#-DdO7Rj z`}^_sm+wE(XEffR008;UKyxzxiC<)}Z19-yqq(L?c9a%{UZ`VIDqza zAhTz#Ks}i+mLwAgK->UOZU=zS?nWb~<%gg*4aJT|4+f_-nm^=!(le4dLz4HS1i%7d z`pHq@;Je|DyCE=041<`2De%~yLm)l*0VH(>h!E3tsI>fK4EcTNEqLIx<|~~Bz_&Dq z1I`aXh6?!tfNg~I<#Dfx4(866EeH6vpMZ{oJ@5C(0WbXm&I-|??Ud9qf^ZP}0stFK zN>p;X5uxLnIK6R7`nx6Hj+1LD+WpVlyz;F={4p_%(p1d9=rF*0`2ol&WLR^wqx`e8 zvBLALUjn^2pNg1rqyikahUZ>8s7k`3qQ?(bMw+D>KH%!2d3S`B$z2 zZdCw)M*srYn)z1;b4^U~O7i(H71duRrhkeRZtezvBwk{?`uX;olbicfm$Q<*$y; zUsKb+Ha35qoxw}~uREB~(0g#<5*G*VU{>4P|FLE&D*mx%+S^l8kHfD(hP5qmj z`%fEFUl0EIe`;UG#;(Ae%C?r>F@tLKK?Io=HG~!!^3|Hn1h4=!I!ze|Np+s zKbPbGo6r9*U`XXU+y7O-U;%ugq8$FgWs3e)z)=2!%e)4{&+GY;a87UeeeiUX0-*i# zMR08KD8*o5@qGP=Aa(r60QN+Jp>XhI+Yka|tla_uM1jW;ex#+vn-S_jdwo*;2Xazj zSZBX!95z;CaVTUgLxpG()^30}J{}OvSmBlQkc);Vi1?7=^#cH+qqsS+>I5TzU|dIp zZWzd*R4Q1LaEU{5Q{5KoNITI)hE%cMEbxrn}{P%k~kxTw(AfZ(8eGx#bpJYN93gEl%p z6b8v{FchqKSze73$!s=%)1hQJ|Bp-ji+T(<`D6aza?3o36`Qq-vYkhPTnK!9SNPu< zIM5WiDxVTW01=-Md&!~ocKmSg>FLqooGgZW2AvEcx`#sSB7=q_RwK&!?OZLpVRq8! z+2mMtbINy$}I{pwm7YFF`2 z0M;iKKn!cDd6rkb7+riIHwyne5^S;Kv?Zy()3WVP;o{s7hpz%dfFg5p|09;U|J>*Yp)-Ng3hH6t*viD z#$R+7e7a-(upyZchVnfSkGF0*F+W0T=cY*bJDw2xzmwlYSACG*fXHiefBDOa6Dbmg zLQU^C2NOg8LLq}D0$+B#-3AgmWLVFrI~-`@@?py24bVsKOai@0-jkcT>oDCv@)@ zzxp8;yXS5gcsSo144?p8BFf$i^OQk_kJ0q)@;IW+kl zU!b=eQji4%BFbf^}FAZ#3zfnhBxMljg2(YsHPsSfnglw=~ zpk~N_zOP@+5IY_q{<%M~v6@csxIUcc14wj@FP96Os0_8!3-|43kx0p13DwOJ|F?O- z?N@y>hiCIy$F=0YXX6`YUFLs6hz?f3H8$>K(%eH;b^5 zB<8l@n?`R1opfFW;lsIwtfSyV1GxbxiR~?31+^K`G~SxFE%2dY8A6Gd406#%X8~aB z1XlN!56F!PdCEExtDxc-PF96Jqkf}9l6=F%jVXia+zfB-)G5{{RuuJo7_tn>v@!J4 zQ1!=`7DZr#C&s0O8@Dz$v~}&?;vf?e%!h}dFOjDyI-ta{EL zE|Vh}2eoF+_bXFQhZ0$OY{%*EFH9jeQh%_Ck2A4azyGcr`Ln_bY*1dEjarn*SF1Zo z)&9wp%_~(bl6jKh`15;F^hohUtwnA9>Oz6)U2-3hWotVam%#y_^o={6yMLu>gO#f8 zV6`$_TBYt{mZ{ZJJg@xb!7vs4SYugxKBMeGHM1z$SW|0lBbQFSgeudlG<#8&&_;hG z`qX5`dO219MtM>w*t3ZreRV0_DW!N-eE&xG7xuZssP<|C%aanqMY1=w)-D*0 zh#GE6x?gDaxyGSFnez%$ zKj&839oxBeX!PLT!0$fphY~(043_E^J9wQFGCIE6R*A3Lv$~|uZ(LgQNvz}6J%z37 z%v$pO+BTVRDn{E}bPH+7DPw-@n_Id0z13><${gD@*MG~}<9Udw_i6O=;2ru*dnx&p z*kT4qNVq5=16+2HAewFhq)aqkXGIv%RvuooX$&4~f`-0Du`7W;BQ?-JZ zkp7g_o|5Jxg#t)FzYG1auK$(3$NMoCMEdCzZtx9ZhPNfN3+E;;|9Jba)GL~yw`)A< z+?5{9#mS_X+0qs$0@r(Qh{y;0d@J9>?$&OG`&aBAT;}Nr<7^2RNgW+7)b1n1={?y8 z(%cpE*aJ7zFYSjn zBaOL@)^HF-aRBAAhapGsk5Er>ykHaYU}=s(_ShizonT0XAQJKrB7qR6Xai1Y`F^GzJ4lOJsumdo_%>YQRA;`L6 z&XoQGE~6gZI`{9m%s&N8XtajY@7Lzv@5{gMQ+|W+VjwwV9-rl*-D2QVV-C$@5G7(d zQ*Z+9U{G@uU}M8aQzC}pJ@se_yuivIIzNm-?22n7{s|79IRWk$0R-|m;Bp*uOYoXH zh+tY!>0yTp8yGqA92e^vyKPFKzD*_TfX;{zFRYQkg&!}_?8BWJ|Fa~DpCdq$Gfo%*J5b}_-PU&sfrTGWg}^F2*HBOX+uk?IVGvp_=z$SarGMB zwqXQ`si^@cX+6N?KP!H}Pl5_Loe0B%qBzrAO44gb>|IveV@vE7fSF?_$u*#tj9$8w zP0p}^7XJ}Czc#nDMz`QK&WwhUOt3Fg!kKn(;5#Q|_Eku=K}nC67NXhq5$->-3MJWPt!;E}g}vcuw4|k^&|ALL5>j7K;K3#5@!F{O{q3BJN?9rIrss0)wA<-mgV`qc%dTo*4Tqf`SveyfT6!JNK;d)RNM0@ZhB~#MZKg)`CvS@&U;_GmE?$#PHvvg>|Qe z?O<7EwPY?lcf_J-EZk?Mw4%H`RGjONHl2<<)C>%Fps&k`;qLD_cu54>hY>=qsNji8gB97 z=z8?HMf4SjZPnY7&avUv*iu-SgczR*-3u(N?^pBRSF4&!L7%|(6~0vU>1x>!eetVg z=Cx!tXIUM9t7?Y6?pd==K>D4ntYWet7kkMO7q0%_ooAKNxj_Wi^Cv^>9)- zkX&{AT=ghY8E9=)@?#ZDT2<7el~S6G(WQ-+gyqtNe~=>@>=~M}2pT!k>o=Y2#oOvN z)2pGh8dTq!7Q-9OM;j-9HX4Jc?WiGjcVVzO_^!HW9BimXx)cd9+?wG`p8JiPJaiCe@ZRG$*&U#<eNFBBGoqG)Jv|KF{>7A!%?d~)kN4T}DVx7!lZ8<&d8y;QH zXDt_Jtw786fw68B?WRkH#%sa`0AnrWxlO-EGirGcAyG%WRQ_UF-YrtgVMIZiR2_^} z_Zn9-qINSeQ5U9k&plTIK2h6euv|~%^?v4!UH%L7*2SjX_L$!L;?aF>S?9dgM$Tx< zciwkP-$FywoF385AYD%?T`Xml&vV`{z}@}*z3S_DxxqWe=o=2ScE6HmKk(d{3)xre z{Fg2AkWOTeP~;%3biea^2NO}N5qE3rSPuxjeQ0NGNK$GzD6)mRyu^U{m-@+w#xyeq z2z7d6B0G_EW}qs1&*+D*()$b}L9=ulBL|4H?d{|AnazwJja7tm-Wem96+_9|bED^@ zRnooV?=vYGQw8sH9NcpeT=VG}b2u{7%xi=1i~SDeGsML6(}>fuQB&YB<+tZT?E1Vb zgm_Jd1{z3!0hTu@}AZnM>XuOC*sq z>e36L*7K^d`52x}#WJONQ46Y8tEOJdHx_G6nae31%lZ@3X&ozd8>^D%PdSwo$Irs8|z6R;?+MqLpCz2lO6NYA8RCB%X1NH+*0cUUMsu|YX%!DV-xE? zQ8u`v=Coxt*sVv-nN}_{H&#)Wvv{_0bhh%4w?ZQ4j|ev+J2o;ZHc>xTJgw&bPHcUA ztbdc)N|af7`q)Ixn!h04Szy{+25!6tFWqErLd(vceQdu)?U17GK1cQUX3h-iEFgAn z-^%PFTyF7y>{dsvA7rk;WbMxKY+#dYTd05y|J^*vrj9#BRq+5x{hOpyx!Td$IZJdtGlbnyrXBcrR=>=BeN$- za>y>bDPO)vF}VRc-q<7idT6C^_}gpKi+8(CYRwB}6BT#OU3M{4cA22_IGp*UHFK|h z;)q=K7}k4+!F!b{x+qrmgd^)HIr`A<^2o+!|CMJ?D(f^j>kzKRUV5+FTnzy~tEsLN`C#K)n>HJmd%MZ+6ZukzB4-E<@T}21H-#XKk_a zo;{%MSzn&kfUXv8j+}U}A3=MQSy!{(r&XI*_PQ6tB-buk=i`&t>&#b|-ZwZ`H!>tw zR=iixe?iyide@edr|?&2xt&dUyqAYwm!`~jY=7rBH@eQjDy+|KM%Gzh=EYvrjr4o} zm#yP(Ea%i$2bi|k*j=~ySNC#PS9ECC@>jcpwhsiquP!?84l1wSbfUMqAyA!uP<(9jUt~wiweo$d~Qe?TMueyemyQR8%RPwoYMZ5JudzRXIk|BLYsCxRR zzv+6=?K-ilx-SJi@{vB}pxz5)Ka5N~OUPaQ(t9zJ>)W4v3H=M6oZiJg)n_92XjJve z^7~P=>M^?ODE;rzDac>ra>s4!h7jV|663ta=iZX#&C~Wt+4h;y_JvUQB>(dIH_K}t zxPZCteEzBTI>-FJcy*kqyH@6dW!d4WG5Kb(^VSb~sQ&w=pZyWm`Ed~OzO(U~ll{0) z`u@K8I4FB#=ku@%y7}&XmCE-~m;L-d7BIxr?|1UM!r`BW>N#c%r3b<=IK9iC0sH?H zFj>MH^2U-$A>56D_;veIso$-C=DR5!P5N`XtrGPa%I0!1{usS~ncI;pkjdnw8pfjU z%U7!KE_YWs>nqplU_O6MG>pJAfS$BhU@KQGG2H0XS$@3GY&JYu+;GROQtj|STBXBq zoy--anSV_@Q@dI0cg6)*Q0hSA5k9&%;$IYYVOW0CB%sZ;=G$YTK+yYF8QSj_i}}KV1Xq^p-Vj7$S==o)yPgq8V3WbcF@CNC(tXF{S9qQ{ zh7u_XAexBNet77stu89y(7Pf4?uEo#DYw&!;J`S{6bhPd zS3$EdzFmqmSIS>^nMbfKv+<_^}D* z2YmE*1MYrwPV_HH+t?qHaeP?gzLydq2EG0eOq<&&d%>H{;55cmg>E|nO;Ys-N;Tdw z8c(!56cUOoHLXeT=(1efSA)D{(>Qm~eQYk%4{UfOG}O~1n)Ga~R#xa&^A!Y&Q2t&( zHq2^cC6PtFflwAxr+X}+_(vZdiYqE1jFu`M1}hn1y`N@778ag76AuS_h-Xbx7$r z=you_Ms^UPmjxg(mjk)yBb=9G@dha18xg`yeCkrkUP&-R^iias?7u)0MCSAk3hcOS zS)_SC??JMf*m8WA-h}Hb>>J%TMpq)+oe$@S5fZip>K4ZaV+jou^UpA`V|{|(NlxJL zWr_I0r8;W5Pg}lawU2>9A9~$0G_SOza_SD+Tj{d67)d`O3izc(tuLvh#YtS1_Aptod?4ea4SLA! zeCDli8eikBg*^ZQ3IOtjU?Thdx$_>}`i`LU@{>mh)9T^Q_0!-vL?hRpn9y+whN2PC z0F)e}u&N%#?5QcyWLys+i&n6xEQ(-CcB$wZG|>5sA)p{!Rd5@(OYMFtc+%%&!qEPEsnr*v4Pbzg3&TWG!z^QAz>GREmhe_Me1dWh2^1=upP5qj8=Upy zo-znvq$wh$wQr*)u)(wCVlX?;UYg5sHNtRoYQFf`iko-sq;ApG82^LPpxh*iM&eTm zF%CCQ>FUFkF~mCm%c5}TRG=V@7#p#?g;>JRQtLpTZw7t{&4!XKe+&pimTw_%Ki4kE zqUK;3f-o48`hi68=z3{$8GmYTEK94~EhXEiD4b5Wf4L-8FB3ICGS zcZqrrJ8&BAVvae{cQBdTajwSPo0@kB(X%G~pA{Ngpk#&3+4#n~JQTvfB;&*AU+(`XbiEDloFkqT#KiT9l2Uu5+0OUV-_{x zbMMGFM=0&WxlSyu%gwtLf4>|^lA>OF2tu%DH(EE$WHO*aDze5#d82>gp5ydw`U^Ys zU}uZKZI{ElqGFezb@oHdA6elO`uwF|?0p?KUN3W6q~yD5*hj>UbHR7_WQz;3i8EbA zjb~Mi(MuEnX8ec>J z_#PbzAL{$*xc;Jtw|Ki7fnJdOo}VZ^VUYnqN(PCyjEo`ft18s}ZUloTq@&*3o+k^|6t7g z(a*CF)ci(2fjMSzILk#^_NS9aZ34bd;EEU5Pq0Q*diG2?r>(kGC?%cvYGP9&JY zg(JvO01zkKM-s`q6;ABqk(3r`^cYap7%-RRwnvg8)?I2U%K6!ZKhrsX(P1X>o!UJi?by5}&u^P76A94&7cQ#Js&){?&ABGHU2+bc3J0FUvCwKeC5qVD;EiIAw zjVT^HQiyxl$8pejUMwN-M{3}Jsq#Qt{*X)m$oiW^lY>M$GJEFuNKT|!*8X5hxp<+K zq!`g?*1Jglxp-22m~Vb+vZG||x@2XbWP!10X}d%XkyKi{cu9tYe}Z^bJz_aGeuc1T z1La7=_)wkpXtVK{yXRb1egFN49i?}G=Kva-yg_QVSJ#Ad#94w1}kzKk#B z4`C{shdFAY2)!-X}QaGx%Y2l zclC0Ufm6@#Qv>tT_xDpJ<5SFT-`9*L0oD_@krP(?au?ci58U#+mQx4!G9S?LP)zdY z<#GrW)A#|>s2{RV$Wv$K1=5Zg>Insgh7SH2 zMJk@z7tcvJl-c?|NH~2!97GCJg(L;j>;+N6++6@~XyR9%89EUq-V3GI`i`aC0iF*< zSSDp5FU3sE`2ag#G&|)+4B`=lO!0zwN#cy|ntADk`S#R#nTL6~j{sSi1%(P_1*(Ns z`>}5;{;<`;vG#MoawH=|MZH*+w33DRmIYy%77;Hc)(1s;5oP@cu+_W3>OZ%CuE2bu zsKLmq8>E7(qiT|=LTEBWNj1-gqRNK7m`Nm061B*Ys1$cAE*~+=`k`bsq51`Twu(c# zKSLhzL&5Yy6+KD~_%KJW(sxcY>kfiZ^S)U6)Szmfx#;tu>Mt|r`>^OIvS|E$89!(i zSw#M4lzLburI(4?=K|Saon;HJWuph#pbhmH>k+gKwJ4J*JD3{#pn8W76>F!JUnWQq z8{d6C)MI&8KGqf7ziagMFGn6MYZz-}cPu#$EUi+mL=>oF$Y>UHOoRXV=JF`h5w9Bj zGt5N8wL`P~V?_m7(;`#zSC9s=h%SopqDwP zhl#pIX=7mXVPJy6%++J#Hsy{Rx{+%)Jt*ug5? z#m?Gh0V>IXrT6}iql8zuj!AGu}>+-rAo>@mKx@PW+#-AR|jBHHJqD_@MO?-8YoJ@CYFHOjJkL_g- zCnb-6$sXu99|xP7lSZ4HqM90KnTHRqxF;RQ!0v@p$3QdjaTl7%;+Upv=KVf2OblkS zr#{hCJq9kC*le1s1e?dho_Guz|6xA$N;>pzG-b6p2w5~t0~w{`FqdSV#*vt-ivj~l zfaZ-B-kZjpKaR^6Eiwm>gKR8vcrEJ-HH&{3JLm!h7R~)0E&O#)ePqv?QBTVj4_i?! z^FaFs%$VTwYc!kb zwBC%i%HISQP+Ju~9=4HajAdEZOagZ|t-Dp_H%KgZNNmn4t!5|rn}QkFn2#d7tsGIU zr%BHD4=YW)ZB8bwRx7Q4kz7T}UMywVzLLm3L|Z&{0Bn{C;oadxL-gSlaZu6P3CjAp4~( zd$J}YgR=leY0C6Fc9KA3#~o#tYUXlUl+ca-F0c) z{RsKhK^_Pma`Uq&ovrDvNnuN<#UFMXGSHm(g%^wIuRYC{1Apv5TjJ*$%*Y9H4lFEB<6J(RGb_Xz>_*3GZWj1F{uhzZYC`Qgwbnsk+uuvy@}G(J8vtg?s$?aWSWB z9C>$+Z1ymPdYk&=y0P-{P0*Sk#Mva-8D{CxTF%94@ytc_Y4h@Nm*my}wB=~r^yKl^ zQO)LQThxX8_tVJ_8;m9=BfSS9J(q>(EB7fE?V@`#IHz}5myb#dXgNEK&8PmX$FQdd zz3it`SUVebS05i2+pg!aOBYvCH@7BN-L112wU-3A=V;rL-+ZnrEUu<}R+l)!VOv($ zNp|axu7-ThA$qRCEG~X}&i=MeX6&yaE|*YS&)0`9Sx;9vYOa55U;o%T7cITS?Ab<5 zxmG8?pwwSJM!T03Jztof*@4_k(Om4i9{tChV~1WK%w99}-e$AhEp0uTvi}QvcNG+8 zw=Vj=8+Qoq?iNBqa7%CxL4rdP+zGCYySux)ySux)y9C!}_a}3n`K{XP;+#{p_s!~y zuIiVr(M1&(yrakO`CI+6d}yL`aP4;v2iw}i_X{OLFP?xQ`N;>+E9^6w=Q+TD@`-S#Zc%GMx&D-Sz67 zS1s>L^TCik>-=!XiTvBveV4QH=i+hKi+R`P{l}K`v!4Du>$moB@Xs5n;7pI#$1|Ia z{}eE=uk>br3mCDV62B??LI~fhuN*)GOeo3cC}!iSje%%#vI4WiOBxwp<{v>h##gjb zDLm$RD~DG<$J0Lv!;v^!D$x~`MR}@SaAZ1FGN<|dSmVB#LSp_H6Fw9rzb*kSm zsuV6(f1WPF8LBHCuNN5XDt(GBQ);w#Iy+sOKVL6!w%bBAOE_HY^!H?yD{6Q**dGy? z#=`f&E;=kt^J8wH@#J3iCdrX9h{0x|1D3Jro-*Veq|6t>vE;ZN4F0gyKo!pa-O)2lVCx%2q$r^i zb(ADyBXzVa&jWSL7b$Lr5nm9F+Mw)mn=Lebuy&!JdMExWu+9czmM%rZarU%*- z>!CpnGU9-M-Y6S0>m4#uE)bB|=`8VQs>9gBE;RZ5Z$D^t`a@wKOq&Z~GIcJYfG9E% zsh?SH9g_!{nq8e8Lf@=F)VOGD6~Ar_K$gwJCVba$>2a39phcViF*pb z$Rk+zB%CwMd8b>$qg7r55V3wT+D?Ii087?&fA0SSB49l9fI{`iz>bGIe-Ox1$b%E? zcyoB%-Y#wfQ_=gn($5Fzv2?%DSUUvux5KhqF`#qd;G(caodE$Fmsn&Eq=s#9HWl6< zJE5Rp_5mr8<1QQ7>l7z<&CgDdxXcHMJ7TXU)HX<524?7qoV}X}5|^QP&{!q*s-JnN z2oR%2r7%M17Nq|j@Mm0xzL!C#s7=1NUX z#V{zTSQQlq5isuy2W4%lqSKzK=|4l_GEr4Ad3-dCUkitntEytlTxpnpFbu0rRmIh{ zKm<(Tu-0W&eB1Nx+yBmsAR{9~ya+rz1d9+siYYiaWPf3i|4xehJD2ho6OoWm|4WLv zD=27c{((jQEk%|AfH4egNG=7!ME*7+#KbcIrW-oCSBU0dW(I%w@XE`(BrN)@^NG0X6smaT0F)ZxH-~a#ld3E*9Us428QE6`e-$;?ynHfkW<*!7_!otPuEacTc zDk(cVuSZ9(mzS5X*O15m7?J-oKIFfC3dD=R|4%XHPcH(G4XGrBS^=;@1>)%Be-u-& zAztJq=w=mCO!54ym@*F_e?g>F#8Ilzi@-*Ny67VZSy^=eiJ#*){Ya3mGogr{=>q(S zoddoH9Mu}d;vgJBXa~HIEjcbi=R$f23PXjEC(bID1UWMEMus@vpV<_c3~D$pY{VUL zrR#Z5VSIo>PLvhOC(k%!fRLvUHq1sgBobE$0N~^}?Ima@5zwZv&JoPQ%0jXAh5%;n zBO>587uV8gfI}0JxYhsw9Np;`Kr}Iaj}SC$D-ZR5NtrPK6;LD#WaY4p zNPrUP%^+ClT6+QsZ|8x1VIbrVMm!N&f=hx31zUkBYz#^W)*FoKRZ=yAMtNGhC^plX z1>K1(Q4i}%bk;DORNN06uARXcf<&CN*`|t%-2tm;rQj>{6@YO_9waBc*++EnP$@(q z9|<9z;d~N|VG_S!_zw}3MV$Td#bsitUv z0|l2cr^75mR?29cixH~PiuIZ6G##mT2)J%M1xD~w765p1^MU&NNf+YL<4G$RosO+I zsEUS67&pnMnoB8{-cwnmnY&56t%tOl4jl~N7MZ4Z0TIwpTYeYryq5g8z=PrPfR$Ur zwmUCSt9YNwHn#w|RmGAJ{sirys2RD1f)MQW1{|%Pp3XLr50HW$W6&Dpg*k%{N5|EK zG-XcS$tx6}Qvtl{g?N$3xDfW+v=Ek1@+tKd@_SApK#iv()TA1Y(E>A|V%Q%H_hl31 z=4<`EUV$a_P`WD&)H}}_Lu-oz0Biyb;0ke2hmS8EJy%o^fKC1Lr7=PHdhTrlFeH%7 zl@cGTrrujA(~y8qH$$wxam1}GEH4;}R5V|FW_2>0ggAga&z=EI6TvsYN3xF*2Ee6Y z1U)%K+P9Z4%G^T-VCS1aV<@a9+bSRrE>VbYa1?oKF)V0EEOPKz4Zp$wLb5`L_5sY+ zGm{=5H5_f>y`k>&Iw=mdga(oO`1XyQ(*MK-qDdc1NsE^$@6r(_Wjppy zk1ZZDKZCPCF)C9aHf=;72MPsTj(Pmj1fbJe$PWaWLnuW}`9cb6$G?0Fx@y)zN4yt= zsr=LwXSXu@|HF$|Ou`cWzx5)1ihTdYi|AJy{KJb7e01phhZoU$Z}bl@lEe|7_YW@u z88-P3FG9$X@AnTc;&ORZIm5$T-)C218D%nky+qUaw--5wcoACJDz*RgB4(3H8vpPj zaIy_w{?m(CjMpsx!;9?6v`PM_7qJ}0*8J0pXmD87Gp|s<_sjGMU;gby93fuBdf0a5 zpI#(iW{CSgy@<`=jOIVQh`-FlyT81MAbf4AA<14&wEA0d@urN#w&(&*w-GsyrtHGA zy^{FeBjvkCNxw7vDh-$ut$v=FUJK0X_kE|>!Y*<<0`6OB{pBgvdKIs`$ohVxOSWvmhT{#oI3N1N^X#5}e@L*^p8bRNFp)V<#jnk1 zrax`@wmQ$r^Ixg1^QCCK#`fiFkJmWZpV_@SPxh}}cc6n4UC4+Acz3Se3cE|kv_G%9 z^xXS+3Vco&Kbiiu_CONZrdtCp$2cnQd13&1+*gjjIfL$dMtCFGSSsjpOZ5c#S6MK9 zFdb*PTj1m}Jou4F)FU)w{p~BB$crJ)6TBsKz#HHI9wNeLczR3J15l5@VK%30mxJ3w zzs1F!173g;d=fxu7$;{FONx-!bQpW!!o173-(h$T^;CpXC=&TD1{RXxMpTF)N z7r`E{w;>=}!n|k`4rM|HrV>Ch0VD-UyD0o!Oj&9OU0De2g+^Gz58L7j+xhl~7g;=b zf6x$ivJiImE$rw%?2;?|+A$2E6n>u&{^%Hb*ARYlA7lbVQ0xF4{=`Ue^r!HQAj^zE zMhrp$Mi^znMB+l>(Xbg#p!K zka|5hGQ=+``5i2hRWv7}4D|1)CN5t#f@mu)$ahB3?YJ;WsaX`Qgi?gJ?3 zqh%hVOXBr>V##Y6}5YopPbw-fS#~@5b z{_2c2EVNa6uv2Lyv`>sHa*TI83=qSQb$1E|J;b>T8h0N=`yV+e>HbhJ6N2}~q(YfKE`PK;qlP!5RINDL`QOpZW|{kf1>Xq;T% z7#E3{WO0~KHJI2Wnf$phsqSNv$nO|$wd8`r#Nok|7Tka+gA^XR)M=;0eCwq4#NtXV0VoG;lvJQP(lR;`*T;e%m+O}~zm2kX`XDWVU z>eyoX_(S3(VtTE3s<3BDsc{-OFzx=(d8g37>>+-CFyk!HW`f)4urUc$J>yc1@VPJ! zK$u0|l!jQ8f*cfw6_f>RN`_9#j62MFD;2k99EVesMM;=Ut)52foZaD+^|2@fDkzg^ z$c0Tkg`~*rS~63BFyZs#n@0jXvY>25o?J}Al#_>4j-ed2qFfdAtkcA-0LcvE#|+iN z48Ejb*&!T+qHLX}oFncmD7k@-&Jt<&p4Qma@UtL-}q) zk-v_d;7n|ThYFlb%q1VQ{nQJ5ka8fUK@as$KhN_np@Dz?66}CK- zVOA8*rKd6}o?0h| z+EMs=ET+0!vAXm(wGP2`3nukK`Sr8?^*@lSD46Oyi)uxKt4)&YVEh}_<7+=P*K#gb zjt`ZGFqOG4dxx2peqd@$=56pnE{F>@Pgu_L(`XPsu1!#{eMi)!P?*$is zq*283)P&00Sg~BoY+BVCT&zn}*Ph&5mfXZB-CVoeBK*{n1Rieg;%$i?uKQNp;PKR$ zA>F#8-n8J-x@+2Iy4*-++H7>tx}IFz5!|xqQa3@=$`n*no!m0Q)Y^tzvyI%?Q{0*_ z-54+gIi=f1HQX-f(q4sJIy_v6RMGk!N=N=;k2U0QgFI&qde zNl_Zk#OkMu+n?JVk z#%<|SF(q`#fG6!3f}!X(whpoD9F9ooK#?JIj`^dNH6;-WUI=TC9vN8~*~1SXBOaX! z357&c=1xXl97mT%Mj&Kldtp%L-AG(WzoO>Y-bo*)8R3>IM$<{JZAd=I?9Ijr&N1=O zPRN+n$=JE3JH(5Wmh@GojN_vW6PAoMv_xkycP8@<}p5a@iZO5cEjwr-iAOkETyofBIb z2@te^a_#Bz z*6Q+3=|m^XioMKgKmUw^>tYhiQdsItcj(e}=&CsXQuykc9m-OuxgA#qi$Y!ZL<%h>$jsDuOzF`Xd6In zNX2D!=yZy)Z3`K^jEc624&FSI-T0Wcg;us9h_-WJz7kiu%_6WZ%fFhVF=xEG`Q~gV zg?P*UepMiBo11l0DP%p0WmRKrmoIItm}G}{Y|H+1>q2X1adk(*efPy}-E4LD1MA)o z?QLC)4KeLK32>WKTQ8WcZ0{ZGw#`|NVwgYG*}SjCfi-HO=ji5~+bU_;uIXqej&`a{ z>Hc}^j@#KmF7bgl>6(bZnsM1-vc)bM{{f=pt~%?6r2C;O>3S&IK@NEFGkB{EydMHS zs&L=pPdoaFHXki_sQGeuL~)u>2c5KUfqDOjM?Y8fDc32a(XUcj! zBeyc{ewvYX`fKcPR^ZqWeA+j*z8`k>mH3eR`B=c=pgi>ek7+rz?X*pM3paEbzx9ML z^jzBlvJG_XE^qx!TJ8)OetHPr zAw$1BK3gAS1)tra?Gu$B+qrLJzn(j-b-SP~$guw2WIdfmJEVTyD?+=XZ$HvOJGGZP zX=J_ryuL@Tefd%FjOF}tPW!AI?Ti!s=1cjiTG>^r#g>T2Nqy=`W9h|5)bpIgO*rv$ zskb*bZP$3eCk!h$-{_pwxgS%V?-8tD@wH#spn@xEo=;P3*jNZNG~Te{c%EP(8g-EBzg0c~4?_mNdRcA$Y`y ze$AYIV}5=Mt23KYKA$!|pF#HE`1UIC?6Il+NmTykWNfuo@S$4%sU++PO8)Ar&SM_g zojBP&EqMGszy0}8Qn*;yFRGyd6yr}XVg+O_-o z3pwf280syq1(<6SmVph5VFPyhZl0O{ss;TH@a~_*6cVJBKfMSJi!;L{jRG;Y7Oq$g ze${vA$UnSDqN2WV6q6QYz?b6QNc217wVuNX14uCi`Rtk?hBDy|r6xj1_Ez>pq)e)S zFJpzilAlnacC8T(q(Z0JsyOpFONWO|ITDoco_-=A_q$q?FA?YFOoQHTP_0Y6sdlTz z!!7@!p>$xi;SUt4B^6e!j!-Ob53{JY|r3KG^xUk25?%xf%&U zHS=Ilu&FqnGvjRmOq*bU%g|w*tSxLbPtQpebkMva2cI#}G2gMWDjF&HywS~|VnP)6 zkq%lmn#K^qH)i}TmSBsG)+1CyULuTXu<^MS&uOO!gt}1?(uP_&^rfF(FC}USQC_-K z7`q0cCx=nq8FMfL4fG?At?&`E=L4N)^eA++##t+Ng9Ny6G-3=pnhuSRZMu)|_!(@T9(ZOA4?`c+$Ao_Px!8L--?8$knS|Mnv1 z2A7tde|iygaZO7udg&JHelq_S%kwj_&!(loiWPXOz6L6raY6Xj^N!DSTIX*?WGj8y zr0862=Y&;V%)QwrKAw0ze?|z7g5`NIZtaUp&4?qZcFv$>UiSnH$CGU#@)441Q@mA@ zh*T>8IWXOBz&C~Qp0`R%gu~vRa_%`QRkk5yOvo8-=5wf=Z?nO{ZqwydX`}U*Smc) z?MX`9QhF@zTca@bYphR~x^Pqp*6xB5UW9yHS#iCcu-RS_21Q)rB{P$14n99WgERc7 z?>oX1-+v-_*3B&jc{&e!30K=RNQf!+M&^B|CT--14z~ctNGF6yBzD&uNg5jC?G1Y@^$OZL@GXc)QeNQ^AM4Mh-eKM{{;Tv&7 zybu5g()}2eeXv|eX|32pO&*yjJ<^S4j2XZhqp$Yz!)Ph#F#=7bmfWJ2QK<50G9{!k zq(Wr-r7Q>>B>*r^`f$+g_^oNKU`I(oWrR^XCCZ=uIx-Q2O)dWwQ+_W)7kQ3vOc(J9 zyBjm8j5%b8IzD1d+GGqRc_&ng7-_Og0z1iMm05{LBifo0mkE}i{=L4WG+HWkZejGe z=LaH<%#k?NbX4u@s74tB9xPv4VMcmU2F*Oo_%Ih)R-4N2a<=ThQVoSzIz$xbG%>51 z=5S~shn*H?hH?X>9ckXNLu#H%W9M);_W$kSq2YzNP) zsr1n18&{~+`7E+9sg1p^>;`r6W$jYVn3^P@+r+&8&XdbD<}Zer+UmO>wieLL`f=MK zxF~{u;-3FwUwY=d(4x2Sqhm@UQ!aO|gA@@IeK3I*-V(be%H>NGNw>d1yf1W6yy}RA z--H0T5uRAo%EK*wrRCGhJ0~_g3L&vJm`)KOgbe@^xfKBF6G*3{tbTq<8=<0q3&fxw@kT^72WPpAmG&(brze-aGZ?jjned!5(~Uz%=wRkI<sLl^Gm)+J%ubdF^HwHDX-R3VppIXaauk4oHwf?v|a~R^jW)1tT z_w;fe5NEb|JZ2xW{Blte#v2Y#W|bfP{F@7vueDEZeejt0*g?Fxgi+ps?h5S2l&QmX zq?3I=^}g-gqWyX5z2)H;a@%c6XzK}8yV3Mj+nwqcH)-$m>gD{V`#uNPvuS>po$9um zvDcxCQwBH8(6--Y@ve)pkgZfK@I$aa7^nW#bkD)`%IJxIw^qdp#}ar z9^oVw(JW*8efzizFN`ZWdQ1n>bt`g@5WFf#;Cg>4_ z;u9u45gs1y^u*{)cqdGBEsR&vP7V`JP}53e_KB{CpGLEb1f>Iy7~H|=Bg_C9=tuvF z(C5?AuMX^$E)t4P)RRwdefU{sgt(YKzc>4whW{Br_!;e_d6)dw1elurO`A>^LV zA7DPwq;$WZ;rqng!`9Ow?AndaF2W|$hOZ<7$0s70B7!~ADN)mXXWGMy(nH?UBUmD$ zfYK}1(!;_0LCUsA1|^6~BwfCzYu-il8#c1a3aRQzH(86Q=Ex`E529isqH-gm8`Isw z6{1Yn-QW27)QJ1Ow|x2`BW7rpqkqy%{nU%DDUy=WyP+qhW+rAN(ghVGMoTPe`Qg*g z5HbFhKEs_pi=X0FBK^iF*gPXyvNe6;*q99qEsYN9|3=nPiV=4^@IQ0j? z^x2OL_@_u{D-Ak755)c){FO7{aWY^%BAF`lDWPXDiCNt9dLW{uKVhaP%Jy@PPj@JB zZZx%IE}y82Oi!c;rcVu3!L?|itB`-sK-u+B2K9jA2dQW!(JJQQv;ncjO{t0yiFh+f zJ(86>1h8>9vVu{w3;dthON|~X=7|G5P@fI_w5>1JGS1D<1$&R0&A+^^5 zk-_AV;U;3K%pJ*gZ0SZ<$n<)d@fykWl9BNdnJMPciDzl>nC);mjO<(tOWsOTb%@kr z%IF8|(e9j4w-MRZn$a2J(b*d54HUVC9GMmBkq$n&9qOS%+mWRnnFv?8S1;LK#Sw(; z{_Gj4SB>Ghow2i)kqR@JSzFnI70JsJ$z5+~rUc}o8o5Eff#d7Inh&_b3(+@bV@B+sM2b0mkK$F5ph$enSXu*WyA$EK+j4u7_<8Mi;}j2;k=1dnth zqE2{y1EF1jnw&_+tyAA{Ok(k;^a@Yn=znQvn8fv+#C4m*&;5dxI!X9K^ze+u^bJ(- zJ`qh>xbcFnEhnBri--z`$S>wS(hUi6=*Y9J9106~(?2xX(r{bFDs*T`d@i= zr!Pk)1a78g-8P z`{~FGC%>{%=%@F&atf_)id%*RQ%9CVls@;$e~|rp(J~`UqsYChbn#Jny z%>0KDz0+B~StVUjr9Gt?rPw)R{yF8`S(Vt?-X3Kkt+7&=X;mC$D^%4KX%(~8xjSOj zt4|`9c2lml%GPeGHu|&jqjN<*^1DiXHo5b^z_ThpZj||bm44mK%i_pMrB0cy&U@Oa z_-ZYx7G664 z&K%M@SFsOOiKbaFU{UecTI7BD78v?1jYj$Qy>gQIx9_csk+F+WvTEKeOZu@B{ZFG5~$)=t0`5Bk=0n=QHE@Fw2>@{T^S(JG=UkI<~#pDg5~YK=p@Na?p( zx0S)!)m4ZQS^YZvqC9H8+EuF*g}SnlyU=T=+M+DbdaAWXqrIag)flVghqE^9w$}cl z)kCwibEsx?!)cHBBV zskJ<9z8ujyy9~QD2CLSP%UTht@mk6akkf^6XW1L&-{;V2A6-KhSQy$}gWS}gl*pjJH~Q;$H=Fl%-ia_k?kB(BPfoE-N!A~IsoTS+^^vy@naKfn~6Ty|$whrbiIBv5>u? zJf?48VSq>b^9}88F{}agnI13hw&Br#LfVZ=4&9elea*3z!xw`b zJ6>f!Md9?tN6I z_@X}=4fbv)*&~s}5+;=$K&mG(2K$t7h6%VOex$~FXxp@V26nf`DRXP;eMUNch7o9o zVQmNDV+Vy}CZ*b2IkX0W_D9KQ#y@3^ep4PDE$Dq`H;HC49n(0-g4hui#oTS>#G1C3U8mNs*dn)ak^L9`)Ut#)lc_eB|ZN z$bSyPE-&%tuU;M;Qm z9kCF=3dm`Nr=J4dPc-KqBNPAy*8t_Skh<|P?q8N|| z!kxquQ*q$|-0ck(qZZZ@sh7CnO=+wgc z+}#>a9(<`awxjKLN|S$~TgwAj_O+C`!xOLBv=`OT}l%3N9;hiNu`>V|bt;L7=i(wTro_ehb zw9~RagKL#bcFwC$4wfRXW}=2>D+UMstma7PXY`im2XVi9+HBv-n|~Fw!(O+MkGJ_8 zZ;Lr^$fs%~>tM#ee%08^mMj%mZsOHcN+aR4)do!$bRdu+i9==wocdOKDYKtzp^r{a!qe{*I_UzKYD)# zf%A5o_BX;FCfZ>~wuZM7ua30-Ms(qZq2u?S`S;58_X_QfAr4Nhw04%Nj;8JolM+qh z=#KdLcg`N>%5)AYh7TEdkMGNE!}`s_IUnL*uNfTf(>)y>J)8^B%_crOCf)t&SaX1@ zwRdZO)C+e`4tMZKcCg)lh=9Mjuy96tb`DZ^sY`#vC~*dzIhU6^z2STm5xff=cWJ$Q z@P6yi_Vy_U&o1)rD8TO~RnWDk{=fqLw(-uP-@}#b&LxBHF}M9LEq}N9tzC}z1Gp95 z;YayBm7t4@pi{5qZGz>qC7#2qj+@22Yog)3m*I=pxr=_-6KA;FV)_G_{1eZJbK$Go z2B+il>(lsKr_TCkIjuW2|K|Wpm&z^MSpQ&zbgCl<^5b@Qu`ci?o>A)oKVfW7&*cG7e?3L?Saf==HTIadv?)t?-Dvc9FwA+@NxmO{7J&(XgM!CoHo741 z@C=te8f;a|tP?up3U5K)eW~nBs7G za(G2Ik@3kNlf~qkekw;Qp56TDnqj6uF<-INllyl&15tEe%gi3w z_ePR9f1RB;RivS!7P`hE_DdZKyKu2JY|wIyOjl_6S#arpJgY_JJFxD~K(at1RkS?F z$RC0d>h$l%74fXM+-S^?hNORXV^Ayd*%Uffs!3s8G_@nNlb*cJb61%i6H|GfE2^}_ zCexhJiP4X^>y0nihul*)^ViLsGsM!}ely(1T7KJr(=}Gn+#rQVhf7fRMmA|sCjY`_ zC2E1;PMhh1m`A&129o%_>Bl0a-wTDT%N9V2qYLN{0KXfPSoclT6YlijxAFUK!m)Nh z8TFML57t%0Ca)iA8&xsQx0)r9I_`^JCxF=b0O%i6!9BPLM+&fk%=b*A&oR)jKg>;1 z8&aFWMp`h=56lg1Tr??dRoS(7SZdr(@g;Po&kAI0qR$THd8E&Yl;UB?ja7GM$V)V7 zV#rT*eq<=f4B}xd%uRA;EGjH&Vk|CgdSooA9O7XrtzB|v`tAZbhMdWvRZ(oyfW*sO z$q$4A5p^!X1P}pw)R=1~af_M4xH~sXY8FkFk8prW$)qwfO)wqU@GwH2q{P??9p+w| z#V2*YhnN`Qgv2U4?B0?f_uB!9C&Y;00UJOtF%ckRrFML*nXNnS>pHVQD}A`221lMja>w&rb5>Ck?FGjDp8$u)XYC@Z)mnaFe2LB$DqFU$k30Q&!S{MD0I0XJ zAPF??y+qSC?)_93F!w=bumI0tZn8ViQDJc#&v9upnCGN&Sb!H&ka6cdYdmg)Y=u67 zc`rJV1^IsW5_#}l4l=d#U5)a-s_|V-!7WA^WUwyyz<{~1`7&2?EZf# zrl7f!!%z*hg8%@E2N=K~Z4Kr>j**i?lSBIh0lfJlhZRX zF@5;(K~PZ83;?hK0E}^PtlzzZhE@jv%y4iZv+}JdDQ*58+t5)~hV(Z6i=X&IPN1Ot zQP&_K0RO9i0WlM=kf?@?%!`T&SWD~F((>;DhMgUxfB^*+?M9sT1yJ^vmLP-M`%7QE zc>`JFm6GyrEy2h4#~QM-;Qvf$czFEnB>r0@;p1}?9{vhxX~e}riW%1_DX%Fh-H?g~ z1WZ7>8GmYsmX?Y7`sK8=QxFL9#@F=pYe-rnDe3RDMsxEes)6>(-%gev} z`d?N|!apSK# zh+_}|@VOD702Oc2^HQoj3!%J)5QT^myqt?tOFs6Bdw>bmmnh&P*+JXIsq7W`KH11yM%wGrynQy2)NOHM_>LurKp4|}jI z{OOUFLZM62s>4T!P@u^(jRg6+5|aXp-DZ#qFQ=~o=9_{=G25L;E^LFruuvW+`~+N? z!I`AN@TrrKgzJmiAH9tiK32ddUOfn%*x;QQ;h0X&NVNTk&_TX(>u(1@fYt?2xYX1O zjd^l)8qaufNd!!t%7&N%Ql=2UWI@-q+JWbFZ{csFe!ySWz;fbsz*DgCXkz5ak^?)k z;oQ_KeDN`|$|rmr0RYT+Pw& z0vrH_Sk4wSingjl)O;t0kOv^vrWZEpLId@BZydo;RKt@iczD|KQ=}n_gu4;qlM4@! zOUuzyd-`CXyLh-t$n!_PIUGK}e?iRRr&x&|ZNq#*^2xvVH1eK-sRFTbTYQIqnCe5w zgoDx4MK}32g>_9M@QEu78XJ26_})mk!1@9Nv#15+it#~}DX^nYK`i^((|&hRZUfUf zyNS@*{y;&G+Kx3anxN3_iD2vmR)Gc}-+T@*PAw3;h6aHV$T0#DbNKzgeuihRpaCSH z1GuK*FkK{sn757sq^Jk_AFG9sZY;@fwsEmo`fKQDEklr!(uET;s?jJb$WJIbG7&Cm zsAJ@8-OaKO_%6gpVKIOCQ4f$81pv@e*nA^g5nq{Y8BxtM$i=V`@ECl1?_qTP5Vkf6 z5Us22^d`xpR}|hvE>KV(v4C1kv&a`Yd106{Q4JX5BWgYd$Wjg0|I}gK)*PTqMe@R6rC%x_WO#sC!>ZE5AwWC zVUN1dMD#)dfjDdF5Np9L=&h=dki52d4Z&%-?DbPsHtK?I_T44gYmkFNXKIK6% zn|~L920+L4l$U9fTbSF757W~1c#0fn>ro%F!y@)dvYy76d>0~IyZQK#f@4yQlFde8 zBjahLlvve6j165$lQ1MMhAKS(3*F52p1%t9lmhq7>`xF&W?*%itZByyoO(0rPskw% zAzmO`YeAC=^&}y9Kd*}`qU?_~?C3^A11CS1Pn;~J|Bb6BB7VcX~z zLaU1Km)W5tdKi$9tBQ&r*`eiq7*q(WipiJRWz={W`ZiV-S3k1L>hdtGoQDeSY@^c> zv&d>Fb_Ld+a*cjB-Z#pt_g-s<8INb)X_Vjdm)Ug+7H@y=xFygw``1X&ZG%mVOvvbEiCc!-YMfw+dPU=EUEIoX~vzJq?;_`niw9M3_01NA2ue{HA&3n zezgVGRY%h^k2IB}(q-LMrrP68qu*(-%J-*CE3luK`r!skrK?ZksGFI_*Q9E4`A?EQ zxO|w`9;~UYGB2@RUY^a9to!`_EXMVTalcHeX_n+HG3M$0xwcX>yzG%vKlNH_r-S62 zERMT$@A_*Ur_6OLfmb-p#uwrHuh?x?p6xvwiJp!U_-EKb?|ZlK92%sl-3h`xV78@! zPKsa=0h`eJp6ys+Cvk}|>^P#{-M5_F(n%X{`BfzD!%tk_x5 zy$9lVjZ!{f{5&0)LqX4`ieuRu3HW3>#q_4cSa;k4-qv?I@EG&MQFbNaFVuQEGD~!d zw_K`j$Cl%ROIYvk0&2AA9Qq~KZrtsoXI|JmJOuj*4 z+u}?b#f-n?y%xLsrDZ$SI-blUj-tDvq0ZBJdgB$78@Qw5 zeYY1nFZu*8>I9I#y%!U{7vndlVneSycyD$tFHU*~GA=hPBOC%FOu+_A<^w{!duILt z3rNx<9)L?Wenfb!%+lYe+oo|56TSiU)Td;)BrH@J_jxM2M+{j z1q7sI!l~p+ZYW`-eG|!Au!_Q!4U*_=$%9jh_Jir=M^PHhqI2Spg`W4eYrO8fq|V#D4=w z#C5R(60!-wSO@zdVB#FU!3&H;MtpXy1PRs$ap8vvgZXht zkqI`H2|f@iu^8=4km%}^P_mE^Vr(uEXc|ZG%W=@0K9DepAu04eUg|zE5I@OCA}M(= zQ8m$DZ86cLGlm$L!a1K*N1GVSko+?~3Bfbb`gc-2chUqwvi@MQ;bHPmwWLV~tPwCG z-dJGrcw(w=U_!pJdoiNLu5nsTAt5BT0qJCX<4Q#`N=XY$osvvn;!ZnrNE0YX;TBKH zt4zB=Oa?M$+)2h?=ch{?q=msJ)^aDn6eTwh~5#~U>I;Ugs=@dSVe z%`O*X-|(d0Hii%(#gXtNGYw@m6QtK2rn2*7pDenRy19+MH0GI)<1 z?gKrZ7k>#m`yUpX2qtCXI%m@HScw*SNU8^N7iGVd%4{XbrB%1UzFv_$eEz~* zPM%m%?od8YVE!Il@fY#p+N1ok!6H(Ve4(Qv6oz8VgW|I9#R6Zv^op`tmWsM~N*dHt z!g%u2)$>yye{~djCM3lNBo#;}6^~05L=qNwsTafqWiJNhP8XFdAC=%R7G?~UojS*4 z5eCc;B@OdLCm|&rBbB8cl}$P4^(W=+I!E0Q+7vMo+8mWm5SD5km9r(4uP0SJH&tZv zl=&x>G@Df7A?KkE7uph*JvNnJNL6O@lp}CeNUK%sBIY zQDw3p9jaMdYw6MrKm<_Kyhh~MiZfQ<3LkW{6f=8e}nZ>O`vI0V{vmhe!UKT zjj3s4I#E?2Z&i(Sc@R^M+ET%1>4tFRCQIJNk>vUb-WFZ(amz=>Cc)&EuaULbo2_R1 z^%s84B}~oL!_8Ecsg}S7$cFXlaU0QovmRIdi)8yvb4}=S%Q*-_HaLgi zxu~wWDCM}5g1HfkxT%-735Ktl#;l8|q-^H6QKGp+%B5R#xf8O32Ak3Wshlafbm73a zATXD`YiZ?Mspt4#?A>Kh+hM%u`QYyEUR>G&#ogUq+Cp(JQYh~3#ogTYx})je13|2q}$6vwt&bn+0MiC;eGuPirmic z9}!7?c@cU#U0!=CI!0IIiREelh`yunx&uyYqs|#)@hrriH3)&U@mZ+&!#V_gsH52m z!@1kiNV$L<@hI?9^w!h(tiZ&T%*3MS1c)$ZxdSp_HfHU0V)kreOCY*{1%GsHq^Y7i z&!AmqJg(GnvXpe(E@LR^Y*-?k_{w0+v0`#ip#Q-Dd!H2luT8{_LZ33~!1*gC6dFE^ zU>uy`l)vX#OUGEG&9G_3@SDKYx5#Q<(i!vDUhKCnDbj9)%8t{>N|GpWv&q?v&g)ce z^97;vZcVgVQP%lafranDS*^^4A5jaqhQo;&Gnf;z ztm{K=8FR`})5hz-ol~N+@x@SsInIfG#mY9PiOJuB-4Uouzr2>!SeJ)9=iJUAJjR@R z<w(%@Q8jQkLy>SY=OYRG*dNqKo2^pWO zyzJW`{L6Hx*Gfb=NV#<&Bos8TI)KmGOJmzpSQ*g^OzOz2I|i>U29Sd4GDjj6R~Fxv z*~nI^$X26(>q&+yyR0i)mFw%3Gu^hc7L_Zd6D#wE>&L9W`)%Wf$u@2kSBu~J(rp*Z z1wl7xt1D=rzi*&Zw8e;tnalIdO2N4R)-7bVxeD7kIJ>R$s8wwAtxUu1HMH%InQO%4 zo8n|!qre4PvIW7&9mcFJ3bs|!&YeB9-2=g`!SbCHuPx8aUZCLmJK837=Qg?00?Ngr zh|o4J`JQFwcG>!t6nKlyXqhW|w}^FL-Fy30aIe8@Pw`@1=3+zcVpoBDN4RRBNw9qI z97NW+PhC50b-hH}x%UnI@Udf!_H|9`_vX|3J|X%J*y&>L`^K)C-a(Jmp)+W0^1Saa zXj4Myz;|-1QSngP_Gn!0D5!HYEPCG_{lKy6_@~{@xb1Ea>v2N#kp}8~RMx&8_%P<; z*oEz+{rsfb?zph(sAO{As%k^a``Gy6sC47dJ9-^!@-PE@+NX3@jk^CyVLt@@B$w^f zLE$uY@)T%vcC5ci5poE7vDFkk*mJS78hyHBxUs3YJ3_wu#qQ!zXm>s9u-SWk9=xIq zUR900I3v6GBy@2ay|G!fIof%~!nW7mc~oq43PL|)oxCU$I-j*Wqn<5Qy1b9R zM5w+zx7&U|UwF^j>+QU{%DO_{yc)jf$IJ%rCVF=jfX`Bdb|lenP?dXPy+QQ$eRTFW zj9t4$oyX9^S2NycH%1pkn`duX{d{ceyfGu>@7JA1=l*t;HR$Wg826LWx6_k1kyW?+ zT_-eC3tYzgqU?9ALZ{4|H<#!a?44LPS@?E#_X1N7w$+do{2g)oYQxKWT#PHS?0YKZ zD>;gzkM;+j*#}f98YJJFE!ZvyVy?}V{T8d@%qMqsrXKIs?|5FGq`Mvk*>8lEZ+=po zW?ugNR(%7-{`Vs5&aC=STj)8p>$&3cL9gqt!TVn|_Lq8!XAR*8?U=t+F?T{f8!K5) zp%||{Q|EZ^FKnBSMN^ke_IH}f4zs%3$)i2aDQ=Ns2f2&F7WNms{{X7W@0H&m-yOd2jXg+U6U{<-WT;7$EvT^%JOn zIRgn*A>IZaflxz=>aJ8YI={EZ@c-~ONExu{WFnajI}?|&4;0eiek}I$-a`5b2Db-; z66_is3MIZ}vv~xcQPsA%*ya zIsb1kIC5?@l)!%@v7{I8r$q%|zQK=7-<1TAhE(Nkm3}Y1-u~s`p%UwtLy%)l3kQ@~ zD}|W7Ldl0oyny|H09d82ahG3rMQbp>-_easC|EgE0#&k%{^E=Ii-{0a|4}C4zCR7< zpK$*DTJp;K@{Z9Rq>w-jhcz$GA;_4<3?&4Wt>#}hd^L9=n($EXK#BSp*P^d?r{;SQ zHa4v)5LZdww)~Z+Aj}tSwFRXQPt>HA27|Q&YX~(;yh?&%j$~V8z=_3jkl2tZ2Q4vD z<5Y$u^A&BB;qR>p3L)z2j5L;tuPDj^B6U3NheFyg7>uNfScQn*yO;^?o`3*ktol1} zEi6GzC=DaRLV;xr0JCNbT9iF!npue1>2s$99-310u2N3D1h!V}PE;uV#OZVz3q!X8 zhLB)Al@O247Bm+oF%E-5k3JU<7bgS27n<{{xO%9bOIQapMkH~njxx!SPeJlm53#q&&h4vb6y z-S7ty01avi&#+KYS2(0 zX8(B`vo&8SX~lxLCn7NNetkwwoOTEyu?wYwCif7sdwAEhTtQ;&cQRO4W(jhsq~X40Ii*YJU6qrN|=JAm``uc8m>l;jyC;#U5Bsr^IT-s1AFW1#(go8W z!x{7Qt>&~pyZ9!=dleECQ1;`c!c6iGsUrBr_~rL1xn#;N3-k>VeKdvM2(nV19jt8Nrp{CgkQ z%mAAcl7!)nd8~-dS13ZB6sYnh0oJx4BsdxWrq$_6Xkt@L50O5?NXkHp7Su2wRM0Z# zuO@Wj6WVAesDct6My8IQ09^?xf^4zAKMjr?NeU<=oL>O|LSHSMRui&OKrj^`7l8+0 z%H)_6Kn~kuW8Tt7lMah*7=~%lg`A|%Q7R>?6cjIQl8+_`h7IM<5RH+T7iCgU4M=6h zGM`-?ZYd&ccGmr7s2pj^9(OaAaCXDGp)i(rkupSsnj2H1@d0~An_Fzu={p{jDs`!j zWT@`R=dH7FZu(X!;Py`zMv{ICUl}>|yw91^rkTtG-4Y@-u+)u#`h5&5 z(6KqR311s%@!?Qp(Ej3z>`}#t-}zBsc=Vu_#dw9vA^K@;@mp=kqF>M?3DNt*!U24t zJHC=T8l7}QGUWe>9;VlC4%N4(ifOCMnm*a^YL3RoaulcJ&zw0 zoI|n1^e72i9UgPj!Z6u6huqH_k*ZNr0Gbgu%)X}xz`2eZf5CKhjyn*l{7(%T!}rn*v%3a;9v9bHCL6Yss~C5v06JD$e_o z(zexUgFplDbNqt?&8DhhzGBL*R5cd&y!s^w?Lt-rfiDnQ0q{py1`3fJ0JYC#3q(2? z@n3;kL3mV$BHn@~&&u(Gif=KbBo7Y_QU`(0j94%Q(0sSPN7P{SEi>HSJ47AJ?`Ayn z(0`gl4E#*9NBNnENrt;lBnMTU{x)Tpj?F32^3#uS23{7;rcWu!y+0@tQklMcCnqb1 znl)MI_J|0jrj0oLAfTC;5cam=sO>o9JH4FL5567PQ^*&x{xarc6qd>^X)b=NJH;+_ zCy(pJEQOIev325D5P^HdL9jX-T{T*;!hBNh+cr`p)R@VYX`%FDJuT_ZRl$5drdiK7 z73JMftbTr|mmN62J=>UL4m?$PTwSUZ;wak{IHMz6su*Eyo z6BML>WW8{tcm}Ps-WUG_+8KavpV!F#HfA+=G1y@gZj^~#wKE5wTQch}-=f!c zZckj=!el5v1{bx$bzVB-fVMG=n|cY@^!=@ow_iRzIo%369%^N55Yf*Ke7vxY{w%OY z84^G2n0J$A+O|h#|EoXX&EDrT-3A|!S4@XIE7h&-(8Swa(kc3rlQhXbsDsHtYstfXkuE9UDG&cbxE&})J5h6n*?qt`U zkF+sfLgtshq1?$+s_b2_x;j1fnm4Ye*xPTCg*`!EGM@&91lL@;`cAt_Up5drZ<_62 z?Yy&v_qtRbfI{A@n;Wl@Z325M@7@_&o6nFK`t@A+*Ygs^{p?cL$XFBj7Cl)W2rvaY zfrP<*UCZL#2kIhFq}}iWA`{|maBBk44Q$7Kw;mOJ-rdzR)zX#{%rXnLpx1hEPP zkRogG#|1Dd+DR+GV$1>p=%!+%9inV!V(AIJtj?VuoO_X8g|AP0h-G`?bi}zcdT3Dk zI9WOHy-J}UHnr0rw(Y^O`?n~dn$vgm8b6B(cDW4;rYH0Wo6?G_o273*i? z&*&3R6qb1vWZ@K7j1(g;=%r`rn?;e#=@u`Sl~A$iS0t6hzmqtSA6N|#({cX7+TY(x z+#l}I_r+TBBw`?@ePEqKM503SEMG$Obs&^MvXEC&Q$kG2MoLaa!RaGdjCdg5qC2Bf8sqqG@CJsY03mc1I2t3;Kj zdL1mm9VvyCvxZn21tb2PqiL_Q@f~srYjT91BN*YrF|VVy?PC*LvheDVLr%t1K|Yp6 z!5+4Q+XA`_B>z+{->xtcCnLp01pE2hc&@Wtv#0!ogj}JzKb(l~X{t~~;Mn+{LY2V? zI3ARw+^SG7F;?%XxQsfQLz22^GZrN=QCrbB@7cO4fe3d5z@Q}EtIgb{n%tF`oSMnl zGo3uBAl-GIJW8DG^P4)563R5F>tu=SBCUmz#6fxcgbFN3iJS^ikb^2zhBs6h-c$S*sEjM9;Owb@a6iq( ztTGfi10I*Jwo%0sR3-3ICC(Vj#8o9fSEZ&?Z5p4#9hf0*oPlxa9>m2!Qv}yham^y5 z&7%BJd*7XwxtmHRQ6OZUeM6n&_nfAUQb86}=QNZr37n=_SD-VT#VZ_w)s$bUQ0G7I zXMUSzVHIJ*o1^)m{@F!+E^tmRQ60E8Bdj>bpQ)0!r4;yAEx=})XMNT@UG?osUA$7` z*V*V=fEsJ2h9a4|{+v27P!$@|Pq@q?D`?1}X=;)!ptEW!z^U4lY3iSAoWINq?W-G| zFQ9eIL%sp+M>SO8G+=G#%1kx5G_|Bz)p5KQ6xKBU7--@bs`vG)_ma*(OK6GOYT3SN zIlT2@)rqatq0Q9x z{xfeursMKMGZaoeab3s1ab6d1(fE((Z?s}I)>aw3m4E$2)RGh2A|6)w6~UIM9&s}*l+-FOB8 zc;nMt`b%(96F}}s$c!4U^+L#+>L2adAD|CE))!rtJty@0@AZbG3=B04#|jPI=hxTo z4Rhc&wrxR&K}MbnnqCksgKlGsjAw1&%e0`;zM_!`&SqerQHO!?1M9{)>n2vCKBRRR zBwP1|Ggi4bIyO{488AM@+js+RJPPVuoUiY5ZFUx}9-Obe-Y?AV8@IlKQXwV8fnlX0 zsP@emDth*aY^%sir}bWU@U5~72n@DS(SV-?9`L{jA9j>IWxJLTygFDZKyN-<}-IZJD z+&eT6AfckKc#~@)!Miw%JGg_p2;6((!G?vu*T}MVxy?*I8Sccr>fR9hp_kF zO67Ov#SQ3aV*|5&&1jQ@%&mp{ecgi{wxWGZsUPM_KQy)03?Gc8vJUX1O!c!AIjc4t zf=zXb%+v?XoV?BCCim6gcfYtE5?&nq0$*%ca~p{snDKW0Fk>_K5IVF1f7Qi5ltFKk zg}3(p+`_f<$YbN6$m|3%b|eS{^ZB{7@U!K-<}o|`L9|wzXbk{k8HP*8mycMv zaM8+k@}w248?6olr;^^~uAJ3m>M68UKe$&43K+meqy><^_FJ_H;ojrg7#^5Z|2(Bf z%s@w+?43~>(VZMWINKecoP<9IPyRid{%}5u6ga~MSys)M&^qt`c1(i>OREE*7ePF^ zJ|%XviFVa=PO476Rk~UWK$-SEQ9CP>I!+L>+j}sJR=1`_?5J%r69ij#Z>*L6_J^|w z5S+dsieF#)b5c5Z-1(pYs{(-Kut&qRkGwE%pR_2JvKC7^s005v`EbetJ}^qUbWyr^ zZaOK@x-6`+u5!KXDLRJ#a1sZ$Tl59Fa$gK7SsriLzFce%*j)l*EKz(;pxJk>K4_I~ z?0~h*TJarFv+dSDXrdK=&wsdpoiYl1n7x3v#}66l@v?PrJjSMQ80L1=mAuwYa%6aL za7c3a3BG!Z{`wqkhq(#1#Ok_2roTqic9IQtgu`%p4Zgw&xl99J4_SO?+Pwk*?Y|3M z;Zgkjv}FEXbahXDO}}(qRkaTyvvfBPpq7S`^_ z;C6-Z#mS-mwuJ2`)6lH|g_9rKjkxv&Px7q{!VjL!>+UA!`sg!`kUM5+XSr(UZ}9g| z_%2GD&YEsN;j{0QvM)8+@3p$D6cMZd=0Dwy?5GKDG_vnWm+qCb9rO`gwb)%vwD;7P zZlvrT@xJ_2@VV7azNb~blaILx%(^i%ceUMo=+M6l^}hS@{!`@eXRg$}6~Z2Smo~xF zicPkoIsK!f^xzBl+{HQOUVrGm{lJB}+3oFv3pndgA=%Z__~)RjlUMSc$NM8qwyV|V zec<6^Q1gTLquaMlw~xt>ZXs^c=5Bp1Zja}#u^4|3gRLC2ADiKhW7*t(Jl?)m9mNqi zXC^rvnLU}j-&bnw#M`$fZr(;N{VG7eemA@H6n@IfJ{H=%ih6fXkv@o~zl%X|f`Av< z=Ap#wNn-XtGcGMFee8b{xFu`5m&JI*XZ;0DJ{wTD=tzIbJmf8S4Z%jVeOx&YQJSN`#FHbeh5`{iv;`fZ;54Nm24(d}(1Tn%7#=xuH3 zZ9T>dbojQ30Nxt%+9Uw)d;#wgc)^Ky?j8<6`hhGx&4}e6|EWKZH!; z0be4#UlF`t)4$(*dB2r@zteudH-F!Hv08M?*;iF~rpDux%l&Jd^@wr$aEJl_)w&rT z@k1c|fAtdtpZ<9p66oZVY88-*YA~3D@9bM1rOM#Hfrp$7wX~y&OnB&ZTi;^R;Gnht ztDmqOB;`~Y3C@J{6KZvU9*I0T>kH9tbIRaU`QkFpGD^mU3c3XbN-(0vfA$k}%SA|{ zw4!5mhQq~C2o<)6=n8$5l?H9jn}Z9dZd>FHFbiN-o2QzM6lKgQ$@pZ)#SerXPQK%d zwfn8%pa1m}1v#`R8J_47tqp1;MoW2F9&PvYB6+fXRkrDlIB>|En5#cU#nVB&KQ9NF z1rBjg24gNgCrFF!x2B5K2|(CkQzyKc*7U8?J?dhr?Mr(~S$p@lCrfjlbvYARPrsM* zIhDJ1;4%C%SP*@T3%uS{_sBi3|I$Ta?;&TTFqTd;15+u+-`Uoa)ZbZBmh1}nz7k1P&t86P&zdT z2ymD=uv7uCe8su{`Uy>9hLC<~xSo|@WdLQY6fqp^mM94c0HBuh%in{!sx_})8j2h? zmMS0ciqx$@>MSXfQ({-fTtC65uZjb3cEHTA;Yk}5A!m>tPFY-hW@*_D*T)4U5Y01C z0lvzIA`qZzu-4T_^Rol9o3H>lP>52~rAua~Y*bg?`t0{TaEBuzKjd&7DBA!mgBMNf zgVyCec>11&y;f{jU%QU0Ko{+RU(A;Sbm?bwZD?qopT=0#Q$L9_w?p~~xn5l}af^6^ z&r^aJBhr)^A8-+;h5q-v4aYITFY7KKuP+*ejsmLG}`&vp=rH_uKOb0^Pk z6hD|}FHT;FcmI#R_y2xBQA~#U{}4Ao{!{)hZh(S(v=AKPU*7gw+X1|UbrcT>}M8=J?UKi?r&Pfq|Ko|iWo($g3K z@}U3_B4YKwh=_l0jDqs7ogg9k=S?s(|ECi1u7uJ3-*0JX`2OPu_&>b~Z}0d2?jF+8 z(hB~sI7C3edql*0Lc(22%6oeHdtu>idHH)q#e04IH4yj?1O^1GW@gSphzLmW@L##Z z9fXL0JgcVWU-19|CVG2&$HvAWxx?JtCZu@ymphD&{evPvps}&tjg8CyY#rw2AP@Xk z=m23N&d&bh=08G*+uQ%&iuiYY{eNW%D1m5P+`D*)jgi&oMfFzkmIh^@we8G-{w$O{Q2#r_sbktLJo z!J_p8&fmurHya9*EEGkgN{3Y1RYZ+J5-ozMo3W<3r~qq91C4z`6tsu z7lK1T&2B<)h{6^T0Q%ZdSqZvIZ7xDRH;08MoJwtXpcMHIgbsgVn)Z7;){89%bn{JD z>TrsbCkJyrg?K{tjeHTDQ$_%!&^Kf=Y3&M+Sil@S;i zB=b?I8-W}6W(I+M$00a`>cv??O$4WlCs_wU&aZp`10-(v+DUF3 zHf==3p8$RB)e!8~iEw^Fq~bjs??{Qg=Nr^N!%rOr50JT=L%>w+^sq0n_1QM}L0tB= zsd&sxBoLEc2puNa$Han*#-c?>>F%c3fsE}!RH1}B>xMxZu0_I+g~89zgXb5)+#u?f zS6dc&(vj{>HMKRlTv?t)gk~L}67zxK#U%Bn$IR4(3Lb;@ZF9E3v=~4P0_){xy#iG7 z{!Y;Q{uGz^jY|-MZtztWfM^{16eNCqjHySlLn2DMm>o$(YyaYr-US=aj?VPa-9SO* z6}66cLXnN?)jIz$k5YPM=GxM(gJ$ncXXp$19;RA3HiDE+uUMz43E`)OAnq#`s!kPS z-hMI9`Q$zlF>EY8&~_BEzYMB7QiM3Jn$I&G#iyMa+mZBj=rR$6k8!8Up5;4!RSxAW z*p3m1H+j2kVWZ-JvBcQ9xPDF*I3|@`B4t49yAFy!e z+Eb5TljT)uD-V@;rNa(D@)b_3wO4J}iGr7y@@A_|$_+$(1rIlWWNYvkq0z=MUyu=IuC5NtmX|Ck-A1=U!RI#{Xmrr1OAM&T+Keqi)7$c35Z4@??Q znJh|zwJB@IgsEr&Wc?kF3(bj#+8gZ2Z#9?ouqK9IHId@r5;222odOmF%>?AdCrY2K zVPhTpK3q*#I1J+hNNKg|W)(y2ybuZD^0eRo+~k|XN^DonHxL3#9O0l60tfGwvSxAx z`(|U(K9JB05lt%k=bxDg^Xtu^o4P`^0C=Gsl#1K9X=jPSh|8W$e!2r^)y=P%)qDGt zUtL5TNIBG~T+3PfzCz-LX*%lf%&{v?f9&^eOAHd+LeVn9kTt%W&d2NP{F(@ds_m;} z-E;v@Te!v_gD!?R(orb?i;NqEg5n~Ii_LRgmh8cepe|x(Oh92L1Bko5& zluL3l9@~QFf9ip3F8{xe8&V{R9DJkQ#&^kIp8nV3hFpbox$FKQcc@##et`pEED^m? zk|H?G#p$4}!JW-MxIXoFo!Rm{5xrxQeAafIxzJQ9y_>6Ij_vGWGj1Deh}2!S+b4@f z&a@9cp+Op z^y#!_es!_BbEH(U-a2`Wn5FAMt|lncI{hwm6eZNEs=<$PI%f zvmBG1Gd|HD4i87v-Q+f`?bF%Ij?#Vp8P#FH@C89`(uMqI(md%W;i2J4NIIwcxHjh; zeV-h|W(CAuKl0UjR?6zU3vMY-3W9g7@J1$AsiImy9z}RFru6~ zEPH>q>i&^MY$$$s6G6!uWF7Q6^Ua6QqaxF6FNytOlW)5iDl5E#o^X&&-A z6@B-ZeE~oI*zmF;y^Njg>VIMt^}hLeiM4|>_!m{RvrfL+{lE?O*}tb#tN`4FeNo*1 zve_&o-GD)OLj(J|Q{;WNV1Kr{l=A_^urD$CH}H91pG&il8AVBL%$ygg08;=g}Vk;Vg>5e2O)+8Tgn7S zy9TK}`RbGeV|)w#B^shz67-cY*j>g~In?8O3%=VjmS2gJW@sQ8A!M;KB~$^?+RNg% zkA-CnVwm4ykP2dmhecSjg-6jf0*MG?z;{enh7er(@ciN6vjZrUc>s!*xLrzE#8bGV zMR*1lf_mY{aShB|!Z3@Ep(H&K+}fep*9cl1n5qsD<8$GTs#I>dk%~{j)G5S{(|{2P zOjJryauNB{g#QsYY&=D6wFtH0{0|)BC?)!2I7+BK`r;}2iZJGAIr>H?=HXY&$&v6= zOU&zX%xXytI5ft&1wV)q4sBYmB{b5zDFkIC7TS&2#}|qiAOaf~fzBHYi5sS5h(jEp zU=lI$!@|%Q<7rC63RGF0RVaL>&8Su)pQOX(X23!DAK_3`61ZBWU}oaOk0ROr#@D3~ z^C3l4F(ir~2PPhc5Fv$fggFXZS|Nw|(<1#*MZ$rxBoHNvP%n)Ww6v!obeCle(`B^m zUJeeCNu+B{5Eu!SJ`Obwb8c&iFli;$PEFDwN|IYiEdH1**_!NmoRDzj^Fue;VkOy} z(J$)B+ZHL=KFoy#DaF_#*)BCD{BJVpQ;NQ9P(-PfW2vQbSZXX$YIZ5MrY?cUadPr; zYA)p5CQDGLo8ruv5-<{C9hOqM;v$dal#Y~`S^CH9IIWt|)=<|y_1LOUHY3q8$nS4@ zk$YN)WlFuJZ+vO$fUI@vapH(=srUp?) zhFdx6Od45C?1qS>%zSwv;IABM8BhH?zHBZ#Q-#I!Trk#fKC=8&{ySRJSQDam9k z%iCN@`SUmL6LCI#Tb@B!4lQEd^g+JxNscLF4li*ocG<5FtC>q9d2p)*qm1cn;fd1E z+3IqIABYNVbPLhS3iUk-xtIz$kkh^~6|p`S>hcvuh80=r6%ET4D2*1_BNum%M}FCJ0mR9fO3f(C$6aQC~uJ~A3Z7RUagputMrpA?$xchF0BNm zRft=aFFaS2K9?`?RS1q&)=QWEDJ#xst;i&<+BvDn4zE0SufQ*<;t46u_shK=&6P?k z-$g2$Gq3&-T6N5noqAHWI9h=+Rzpl*vmR0{AYB7@TKT)IhHtgz61n=;s>%hqM(d<} z54q6nxs1BK^d>xC>bUF$30#L@U1Nw`xw%@t8(v3RUib5)b_JqgKyZlD!eY64Mo}AN!+S3)>^9Hx_#U#chVN~(pDqi()-+SNZdGV)!y7**TCN~$lT~-9oW`h zk~7u>&5^z1*~=e=zDNF zI$xN&*V2Kjzng8!yRcX~PsY05B5DXofheSHdCcwW5v?CkI^oWG**kh?!hzkOZib4U zIOLuLxgN!jO*q?qzY)5#bGw-$`-p7%-I|+^hx(9*`W0<@%&dDQ4f?oQfPeKn`O`aT zPhN`M#_6 zHV)D{aJ}_l{L7Hl%b){k$B1=j;99Gz=g=a5m!|+w)3f)BLS2C7GYX#fhxC=%m9#@R@{!WiUttM3&8IbaM=cl3Ktqzlw| zDQdHd4UuyqCTchD5@GBOPxScf__RRGjKIYFS=61*#InEyAa!ExbsV%danLeq;y9jm zHuf>He;YK6Pc`{nbP}O<#B^<_$aB;>nfO9sw2pKtlVwQDpsmPps#c*3-C*PwI< z4{y7iJi5F;zT|1W@S}3j&~T7NV3@#bGSqOzf1QZ&ZT=-=K09*Q-=IB1aH$#%3+7VM+h`2ARPI zMaG6Q<8DjXj}#&hv9S zw2Q&${nD!Sef0Is%8T{MbA`_1bkVb8p$oU@i?X$S_{aTwqx1R6)q|`pXYWgtsjFY$ zt&8ZhA)(`4)--7L0OG7_qU!5sC5KG#CA{$U9NQ@~Ie2lEZGL>?YWlHAz~-$9`5hhlZCch13&Kj#+qD$?HTC=L zh|$fc*NwOL@l^D#%leHF`!S91J-+d=0`OX6?2csPI<@DL()gC!_-@zjTEOB#Li!3W z=88}FQ2g@B;r)R(`_N%BWY_`)Zr~UhQ&L%V#@+0=F3* zEA{=C($ulv#YqCjrN8pN(>oUPAsnL!G{Y90OZB~A#%Wdff=sA^D)qB@$Ue? z|0!-jBSVM1Q~4J+u&PD=`WH8lVVK@Lm?raJr6HZzJ#iD|a;4%xmL&7E zjZU5Fd29)v7z(Jt1*@?!0?*#4_;+U2KFKn}R+aak;4uE)2<<+9KW^7o94FJPgb?ha z3|>03%A_DyaF~3a(zgi@`E;T6X12rmO7^2&Kj*6^cI#yBkAtnmPghGW zJ};hFkAXRp{dD|3=)gLM;|084E!(Bo@D`>teIIvH0rBhIY_%`;6oeqZHOzfFsYhx0NszdzBGghrc7&gNc6oiaaBM=Q2DQ0{GED#rWO%T6y==XV{3#cp@H8vsC^ z27GfMnv5_BYDEK}M{sX##V`>P*5|~i?mSTu?1=gC=5-Y2`7(k5dl-z!CErb)`oNOb z`zC0Zsd>Wq!wdmg(rpcmDQyWUOFW)<3^aVG(}b%@>FCeq(M22(a$>9d`&sZ-3xu42 z)k-~`FA6_p%51uj3t+_jmX9b1pC$%lf9$GlQ2hm&5Xat@1R zj%aOVrHrBT1>}YKff>3%iO1_M4p|k$zL#j|-vL|bRXH54E9Q{60c1ZU=&Jei5a_n) zbNLq0-va3TwH^goYTZv}C-JV94YB)gjQcQt5mW@4-`2c@OF zwSJASdcdj%Bb~4QC{E7F>;k31zT_45ajYWHzx+*}Q0f|OXaUpbiC761*@6w1Sz zQl_!ioYDss*rW5W00BTR<~$`PA1g$k*aoty@b5dfuA&30E7uJ z$7>8cJXUlO?Q!T8$aez*Xy1Q&!1m%G#!IxJ)>#Mjk5YN5XYzFyG7T^x(YeJ3A0A&L zdOamk`ZP%>466E1kEj~-V#;y+r9z5Dg(j}68||sB`-A#T1lJqvf~^Q$%6C*8M`2Fg?*EZ8U_sm*z#pOD^BTwib37^?jLGrLE?;)TvZ;|s zDgezdTg(AGn+(~KkGdD$H{m#b5yaG@8M^uSHP zSELLAbaUtu^W37AGyRM^_FANbl_B=Sh=8_KLTQ-`a_%mMYb{G=&?D>bm(&*is9UI5yZND)S_jrV<%#^zv|{ctT{=WnKvmlq?J`3_mTmUOdjvZKQ{h(;j#jwtV%B|Tl^3h(i+F1p;Zgmpu9bRrxN7N+OMN%p2jhv) z!Tl`oW!+fiwLMZoQ6A^ zU&(t;7`7FB)xXqSIlv)zmcBtfQ_GaGb7|R|0s^nE*7g>)IfM(=?WE%)VQ7@fp?$9) z;^xqdQOaD268vLAri|Of@`*`NBo%Yo%q>#1#xfo$LkH$dtKn`TPLpY>%1}mbqKQE7 zZ?C)!7)EzSfzA&ZA)a)mvw^TTX+d$^US$~}nKMVXs znti=Z;sWi9^6R#I_0TnSvrHDmq{_7Ul@Nv!xhSXKHtk+#p=t9ywh}83iL(hi2aoPZ zO<7_RLn_gxve&8|mndFxIUqD`?1$P?+BA~cJehzjP64zc3+F-=k<}Wbtj}ZXU}r+G zkHmV5PP3H-6&xsPTpc|BAeFDjW?zqj>%+H;f*EJJ zr)9J(`oL_m2!-M~e{(UVEQJgoycmTAcTTt5tJlC_Wx8e_0UV4j(?NL265w!_Qxr(> z+pl8vGE3;)#Bov&uHwio6T^!VO0c&>QOK9(uXNBUd8S7uEFMSn_I7{t!Cq1!Npmq) z@q2QDTzME=+Y44N!8u?M-INT{-C+y_aGX@zY<|~iw?G?7 zXfaWxuM^@FC_kDy`W=Kno8ARwng(%tB&Hj&LK%YzVb}a=*LSf0M&Mr83%ux;WTzvI zeGA1_ns5!t{Qj=@-lBQ)CI{!vtWa zAYn~IQEov&BSJHLjnnAJVBbSJ-6ddx#pyx>EHXpUZe>saeAOc{jXRJmSUxI{iYWH; z25|Tia`^Gfz))gBe^T+Kh?9DO8qCC$vacP?mk&kX0XGKa9X2W$+D?~g zERhN67{+p!At~=rI2-mg7$AI=N#c>V`#3DFF=XvLk^z#5rWHGmkV)(qDbSI%upB`N zl+At}DM%m5ViD7c90?%pkD`@J7Z_nskcFk`FEpqtmKcb94a*e3FC`T%tB|PD2urQ# zj3y|TWl?RTG$tRAD zL6&x4M}VAIZJa~B6(f+r2ObjRWF`vYrepaHlNL2uWDzN9_o#S{H z1&R+EO3xY}pJ>s*cfx-&l;P}()o9OECt-8@YJce=5X$3+d5{R`qkE_C)O)w zCTC~=mdrgzs`EBZRlKMs*rI^c9s@9bWnR^iUwvCN4_e&G4WJKSv})7>IWAf+ELu-2 z+TJgkpD)@^kinm0Fn{&+(n!~Ik*w`59^?Gux{vp30?*w`(L{5JszcMzMVkQ}wQx+^ zY4Sr825;KSWx-oez8z-SWnjioQ$5&r8IDz>{IiZ|rcStvJRzQr|AKbZx(;N9Qx9mK zynp)EV1Bb>epX>#m1yPBa}F78pF@oa^iOedOEJ+yL#wQ?CdQ?CrT%rUW4JTP9VsRBK)jP<6g$f}pmx^ga{ z8|S5)VyIi9FjKDyYM4-JS!ixD)T6A_%R~bqMd=AlfL;akejKY8zRX>o>397BfnQgH zY*(xH^}K9qM&`aWZ{{34@6NzTpYI(ag0FG{Z4P12B)^8nd9`{JL&J zltC|0KSyz$1!xdfX^_ookO8MYHL*N6u&~;=z9u<0g=aWOXEYSFI_t7BAqiUc>gqOZ z?P*+{LHj@0yQ`o$`ghUygAVTQkl+#^2@rw|?u6iO!QEX3cL^3GXbA4^?he7--5mnM znY{1%%UWlzQ@c*>+E=SDrfR0EdaC+ndb)p~=c~F?JG#CCy~(oD+q+8GyLj|ocXd?v z;6`n`c45g``Otf*N^X2MO85L^{zL`E;RbKNS8L5!^Q3g{6k%x&U+ap0ZLD_nxmIrw zf9>~;=CjH&ES>({jAl%_PORA4vyrZV+@hz^+GFpUKlwTqtzO~E`mM441i$_Y{yLh^ z+8Mfm(uscC&YFR>0in+_KzU=>8HbTkJ7t_(H9^DbW-B#o>7IxlVC*57s(lUY= zsIYD6a%r=w>Hwm5aCCRYPEBlG*7bb0butVc*i6;?j1|kEvp9?`Awwp4TvpNBrokrC zZR1}c!3Hj~#*Sr%7N}6&V z;(MQycFw)cjPrH^5;s6?W*_tReo;vZrhkbf*tf(mDaAE4l{YiAF;5{d&agIX<~Iw> zIM^iBOkOpQkKXlD-3l|=N}N6TN_P;Xx|k-gqX9AdK4zA-x=)dJSY)%FeQO#JZC0>q zQAV*5tGn}kcc;we@a>8TzxYOts%3tkMMarOmHbxi?tYzsa)|! zx+C&6JBX^ocJSVPfNf*3)dK0o-p{k#XglN=JN(L4!2%i^-c92A3tGKB_VU%JkAbM? zV8PG;L@X=_R$wR!qA$Nj9i zEBPxF!R8PButsvK^Vn*uDYNoG=QHFv1^Sy~#v3Km3}GT?Wz(DGhilb*@(1IuBBB0& zvKacA(BEk(TRXaZC*U}@qu88a2LK(bNC@*%ckfj1&ROPD19uE;Hmf~Fj8kIS?UU{Y z7BlF*mH?Y?*=+Q73^A9l>y?_*prFy!>5kMW3R?Tbbv8+Tab5W*E?&OyC@{wEeHNi zZr@9(cdyBJ=~R0l3psBKvG1xs{(80%^Y&%-v%Q;X_4??R@$B1Xk+!Ba3UxKrwVZ{D-`?@Ji~($= zDkWyWFqMi;2AbZh&a>&2zlMgLPI78&NtZ`Gv(DCF15oMZIqU6u2SP~pRvwGyf4d%2cj`^E36woF?{SpxNm5+@9=l-7v&C#YdK!Lsb+%{gd*%Hi zrm83R{J|v45Q&aqT?_@WcO6_Hr2aL)U&U-AkO(0;TOa{f5{WK^nZ=SRl5Bk&uLL@2fa=jxa@_9Lcs{ z0=$^U4oJ-~EHp`jztLFQ&{<5MCW1eO>$D7d`(66E>?(a z#Yc;_ZqdQgx&*`RT!IW;*^d@z326`l`YLyVsIM29x2aEIan2wu$4w+>)Ua}uehEtN zDmvPkA(bF;V!X)QZZy%7FJx#$Iqcnt^@k^*&w-Jzshr#@I701^@DYY-@>)2X_Gk>N z1}gg^5R%wmnTsL9$#n{ibG$S-j+K$nh`~wI95{Xjp?W*SE2wE8{gS6&$;C%w&w`=x z)z5+<|Llog2U2|r?M0v^WzAWX441o|EunA_!b1)qc8&67SGed^X&>EK`8>VCM1VeV z0fa)tUe_p6H-!Owbe=K%ZC<)Ix2=%+552J2A<=aSDZ?ymjasQ~H2XPkKuvr9dvOTJ ze~Lpe>mdOE9nlJiD|%)84?9W-NC5lmW(8_{Kt~een2o?bJbAyga zhX>%OG4wDh+A}EuKoeGm-LRKv*m7hTcq++VOmUTweAyy^A}l}}|3$FObq+4JUmL^j zc%)0q4;eC04ct&5I1~UPY!3~675+8Ijc@xZPXT=Mei`6G&azI*Kf(3E<{~7tzf^S;j1mg~K|RRo~j4 zXxRf8M+|VPll%DSIO7XPj5(`Q#=Pj>{a_q5SFBE*ZK30;E*!OXs7_mbqT}gi9J7zB z{=Umc&-<%z%(<#M{nU$|Z;Nrq0GlQfE)700vnp`@5MrkFcD)9d@&jAC2 z@)u$O00@CV3aDVg$0vp&7G?l|frJE#SpJJ(5dn}v`HDDz2L(m@Z^82Ke8oyl?cehp zP{HyqyMl)YwJWOt>Nxt_CmRhFivCMOsFc$J=> zmywb4si~L0gi3Gk(eUu`-(=;lWXFF)R&H*tu3n(q{}rHm3uh13_a#8P>rxr~tqLv=w4;`PeGJFe(^vFaU9j1%m`W*w_s!0srG(*ei7@2TVg9X)85v@z(y=%@`~ifM2z)BPtZnC%WY7@}Ha z#0ofqND?6%S1<;@0o=MwI+CeF?PF`ckJPJyQZ(++$J%j_IRgo*Jskoe2E1fnx2CVY zkubUVxHlvqRIMI`D%QKx8ta7PI|;8o3>yr<3q&$OWp*nJP~K35z=DLBW+~wawr$`J z7N^3Acwe7JM<7{b3h}vq=qC>3N8rH|YTJhAvMGx;?)grBlPtlF@fu6s2mlo3feMyf zA40{MU@nDNbM&6z;VMHf_zq#XnF$|Q=&V_X`7Y5SCYxVyIdxcEeUQYjZsl4ayk*c& z7mZ18FxcoG078&}{YqtaO(QhVjU~j+ARzi~XVXQ!5>1jC<#Vim6qcf(c-*lLqW$OJ zZg-TZ?pZ0+5wKjDg>nF%YNMr+V1;Wg zM0w@}O}`haWtwF-ugU~}+3#k^>DRd6~B-9Dw@oDZ@2I6&Sv_@+Zunu^AGhC!Tqn}0ssP@`r)+9*J zsM{r!9i_$ox_uZEHPurVU}K4;Kgz^V>oyz$#!l)uE+D?cYGBg97w7R;7n;J$<~Fxf zQKrcyU3|;(TvJ$SYRK}9bC|vpIj}NgML&*BU*3u7riLbL7UWYOg066A?1>LqX(0jx zA;MI{A+iI2!8Od%lP**$JYaxRq2}O?X^|k=jwUXXtlw)6EYf5xyqunae00~+04(_O z1Z6D+I_?A_>rAYjSM#rNPGB3YlR;Q&SRgAZVbX^2FZ@GYjvqh(;5-0z1$7OlmAf5s zQXUE+)eDfN))}0lwICe%|1DU`k>D@}pm~n}ZNYLGZ@vZ2m?nIqS0|I)+wzTLEqAzD z=n5h~B1_0M+&gN^=J;uvjFfi|e$2k}O6$7C^utxpSUJqK-2E|uaCPrQ$nBLp{0fQq z9Q>rEpOfZmesi&-p2_0QcgU=ACanr2teNs*c}i~&lLHr7^66xXR7TCeCp^9@_Zcku z55ZC@@b+8l_oK!?f(0U7A%t@@h1X2meJWj5Uu9)-*F@J(Ay=a|WmT$73KcB3)#jWh z6HXs#7uuv7iaBi@Y(44LAhJ!L6m5!Xw3yCw@-}RG|?%0 zE&Y3t> z-esIcVtTHtt(k6ii{6F{wTYU&!QJidc^IdBmQ08tIuwC_tm5*~s(_ru&AIB{EXLGa z`#s;Rx3ApUW3=BR+xoPhk>9mb3j97|@w(5ae7*w;JdeLXn(QbSwg_=%O^M+4v0nOd zfCV_n1z;FStF=83^Z|TSBpd8~Yy?Rn!T~JYP#jV-9P)iX{CR9*2BKF5Sd^i*hxr8b zk~pjRp0VHjvk3fWRegT%`CQKVLg)iXKl_6_1CT2H;ei1h41sEU{;46pCHVo1T)q_> z0YI2Q8kis|>L8_pK;n%+Z@-`@qo7^!K;8a8KULokp@CBSLG;-{o_@hoT|uXP!PZE@ zW!b^%Tfvtm!QuJ7aty&2+|c|17rS{5_lq$LwroGZh^AdD$v zrAY?S&4qW(hGAcXn`Hx)))i~r_zD>aKPeLS4}|cT;kGppSWEzhm9fykLKF%zo_7Dr zb3g^lG<@_X&p!l9Llj?p^zr;3!Lr*Bea;hetsb*qAb6V`^Vkrx5E}Dj7Bd=306vFD zU*`kbN3_i2HSA-fGCC$Oka*a^5O)Z|`^7dDSRoh2Vj`3H>BGFlV-YZhhPiwtA`Z{^ z%xa@R>7j2z-5B{$A3Br_!G+NvP{^X?D*Pi@*bBp7Gy0J(nDsJv(0qs!DRjhC_Y^yD zk}6DaBMJ^32sLg<5HSmtHxE!a2!UFcGM9wWZ(nit67|gEQV0@0L-`70qS(BTUvi?c zd6H&|r$wWuRal}8V}deqh>_Gc4);V4wicS9sDlNm?nAfUDo`2 z2V=apxrKfTUIXO7ZNc1rj@Y}VF|b_9vS}e@NF%*f<9jlr!&-{>2BXc&p#4tD_wJPB zqlNF&2M#9--WSLYXULfYVI&z+->uyu7jLo%aBtdnX_A%#kiP7T9nhjmyINu zEn1mQxbdTaI}Prhqd7EJ zY0_WwFj;}unQ!rjFp8z9NA4HtJY8vQMHE71%^wcD`P{szz8a~PC@IE64lv<)?=QC39RJEZz?Zuy*(wTINxjf++@r#}e7mEsPEu8H`0>b7>#^Gvy=3)chv|i1$HxZ8BhXrqs%2AlBNKk8F zm}{s%=6q(Z?I5X{bg$;%t<}(~{p4Buez-<3q6|~I3OS;Rez;hmIY)IVM}#>;Q^rSP zxafCkos(Amux2SaYNZ}?rS(yr_V0?Mrg~-OhJcTCO`3IP%ylxu^}ynCTFtj4hG9RkBiup~>=RFK4rY>%GHrX7ZFR+UOP(z& zmL=-H8%L7cj_cZ_NSg|d!U1UhYsKlXd>y849Sq4Gm&l#i$IT8O+qy|x<58Q?Wm`Wo zb>cU*KQ%XoEH(Ccb`q7;ybN~+A9ga-cXa&z-X~K`C0oO?++}ZBiH25p*W6tl(ZP8P21?58iX|WS)mOv2o34MAfQ(O3QEF?T6&x!iyN){@+*NJ>oB!e5%o{_gFJ-2R)gV@ z^*=sKAa?>Xm7-pdVk~h-r?p4-7-D9>k1m!(K?@zLR-=&n(M{RW4Zg8$q+$Kek#xQh z=i`Bx<1rk+F}>`uLaTv6mLX5=4%lRpYpdZ~vY|4*f%D~vC$bUz!Lg>1{^F6L&zcid zVH2yCeXY!sMAYNv8-u0G-QS)D?@=30nugyZ4SEgr1j+W0dQUNUL&gn824-X?=TN7p z<)-4F#y>}nCq|9{jwWG?drtT!*q8@hWq-k<|9W@)3)5iI%x{uW=NDJ&1hZVPgzPjf z>x@!quQ^%&c+R~+pZ)UOr$shk%{T3}GG`f8;eRsAJvza}I;XHQz{c7`Bj@PC5{?x$ zYbQ7FGdgTo(iU%B<7_>rIyxIR+D&G?n6J|kvoaN=(^q=3_#Tti4!NI;Y#bgiXE>2VwmsWIYwdy4+p55Q4ru z5;eH`yi#~lGd9{{UXZy@Uh;nHpr@0EG}G9R+QJ?{k$))gC)wa*R9CUQ%)&(m9_ z?K>x7*>d)Yr8d_((=cr7xBS?W-UQMotLy2LC+WW$Tj$br){r5;rb}06y_az1m(S!j zzJFY*D_t>-S}-D?f4#cI-@3lrx`EiX`mD1o&p%JfH^?R( zi#AM{6GZj(AhzSijJ+zG9UkUg6{2HupW`8nwGl|i7^KsmZ81xJM?2$K-{x@9W|;@0 zr$l~z6>`EIeR%0}ilTj%lX1}6cF+Vlh{iY$w6UF)KYwgH+i4ryg7iO8?0K$kmI)k0 zMW1-tToArFu){dQ_T6odKF4jpNT4{<5P+Nyl3rGgUQ|aP9Iu|9N1uJ+J41PM^)}{m z8U2F!?DU8HVT;cmzTV+N+Z9Xu@dd>d^2>27`Y+onoe-#UHcYS z`wmZgr6w4b1`Ml-bsEBU4TU0?Q9fFBu(nu8wt!pK%zeX`q2-K-_;0Yb>{zz3u(pD? z_P%GS6f?KuK#LgD(U12lU5V8gLUfXu03ht)u!Djd(6#G6Tojv}HS-v+#$iRfF)w?7* z1DCIz+}9&yw8OS%UL>;lJC4ULLAZb!g0O>cE+~Dmdvpo<BuTiJQ`%d;l5(1Sc<^TKHlMUm|`Kule@~1>UV8S%^MPe?Jkg{7(C8zJS)v|%LN&lNiZf(Udy=FT@W!W(H!WD_<}aA2Ncfb_Hc*>(zRY@cUmhXUxnk<=xZR~5U?$oM zlp*DM9nz1yX#q5nPW<={(K-fYq4cno;l*ykc9y@s4i!3JS(X$+Ihu;4M~ja*LddO{ zkIll2`e@&PM}Jt+Q=|EPOl*y$3bv5YXauRB*m)$HmB`%+DVF~ht7?EcYI|QIRkeqe zjV)FaMuN^ZO|g!NQV~Zo2(Vry^QIO4wMbK$5o_6pSQ;T|)-+9}4^358zo-Dyc90+P zAJ3fN0E_EhVY0tAQ3BiJ9%CmzO`@Tre-65jbfiM-;zKGGqQJjm6?;F7ijcd?Q1dyM ztrcxLfaoTH3N#CPKQr0KqLSUB31W(n*AkOd?z3VIomS1fj~iBD{aLFTVhCai)(GIo z)CjPnm7G&Vp9f*mB?F`T4<7-}-{&7K})Fi(db1Qkm;< z>-Rui;rVdBuC2N^TA5uX&5Nq*(^)E`?ZZ7K0!CnI$l5?Hl8adPCOs_9ZI@0Un)h4d zBYFkI=$M21dSx6FfXJ>8kQ26rA6XU060Z=2h5mefWgg(Kuj{y1wRmENMKmlV+4az`jG%RPb&1Hy$au>xorIN3>$JT8(7 z)bxl`VFUcK*1=ZYjxG%RU~E2644?mbXN2E1J4oY))E%~CIxi(dI8?QOwlNBbINdfv z=%EjAVb`?x(YH3Bl)sZ))w{ zcWc}k-uFxOgac@iNi|u&af^iQy3&3QAD7+60ux^g-*5mhA$|279B9Irzyh*%c%r1o z3p07QuB;5493Wz#wH0C^l|9QI7ItEw=xJv+yhR0w5}q0}AXyt8)0KP4TFS9Cl}d%MHNq@-q!q?^~F*q8@0mu_0 zCOo9;Xm7st=fm66x*ADl#R@Z=AjJgF%*5Lf+KIxABT$PPq}I$ zE;c(B9|l8PiUn63Hz3XH;zolSk~O4K7w6*UWh_htS%KDrC708$fwRKr+Yc=NC2n&G6-^ugjEXjsjA<_y*qg?V{D+5zWCW+T&3t8 zaZy_M5LV4sQR@*uaR=5>uP2xg`+U@##>abUXo3d{aQwW59lwBT4o4d`P z8P$G{ojrR^1hzZX6dIw8c(a2+I2U`g4E#`u$;^Acw=^jxgsZW(e%9810mxn#XZjY-BAwJx0#M`Unm-bi>c3<)R0EI zK6Y*ILQ~U5> zGu>)0|7lQ0-A zb*-Qomva*$gUw7|*c!24BKKo|cOA&etZ&oYh>5lkbx=+ji| zinEWej&3Twjq1>~o59Rs zeyBpoWSNvyoj5HWqn5n+N}X_#4Pi^6f<*q<#|jo8!#xo-@tcM z;fj>0gPaG2s9BJTs(C~8MYsdIc}A*0Bg~vud?9HfVMNVX3?Buox)+-R{0Cbf=lPl5 zbv-SGHpYkYne`yR`bz|g;wtmuZP$M6X%E6`37rt-zV7+d(|w{PAWR0Y7%2>0P%|hJ zI%6-w*O4R{iTT;+y#}9XSm;|GJ0xwRY^sS~9r)hqD=|4Z@eeJbAkUQG4!Dbr9wX&G z)#G-w<7QJl(J;4~4Xsd%cl1Ur_`2FLQpe(N(Zpf~{MU&jEXgPd!_hDzqm7SQ)UUUaRr$(1F_OYxe+)VL z)BT(lXWs71GLkTP3QZpFs;C*_>>NU!l&0Gnx)DLn{s@;s;@|B*{8P5S@w&1}^j$($ z6RAE^+wpJ}Uw3s+XU%kLLaZMW2n+xLkoWx%aG06HWcC0L7%II{*W# zE;o8D6KEx!0mhbPv0!8gN##keL+gl<_(1+#V5&1K`3Nuh z@(B67>rf0Na(}2KS|7XlK6rcFa`z-NuMbZ9kch^R`Wt?%e|r3O>(ky75~zU=#tc9a zC-d|)cy?WJPS&MAEs3^MIv?2!Z#=G;D~Cmn5-&=Cs?ugVqF|OQg7N;dn&@Q0^n}hY z3Cz(?*tBCBfhaiWNdzn6WI;njqn`T8>UnTr+SYSq4zq_@yDn~ zhiHO6(eH$Du_kg`OYl2Sa-dJ~^8Z3jSK^HNrSeLd9bb7uR#}8xMEF{%7Jiz-dz$}Q z5tKV6LN3i0RsPy|TFzQoLQaW!begI}nWuFcMBXDdqa3`g{GMDz-9bfJM}@UjMcZ3U zs`eL>oQevoiYCI08orWxl!{`MGUs)CZORV{SY59u?stV%U3)42FE7C&cI zqh`;prZK%$O?r4t}{1AlX(!@Kz7q5%5`p zoz-hr)cUNKbyQUSR6cdkPT4)bY17ee^;T;*QLYUdi=0vE4pN@%RfdePY7Lia549@w zIY|$SVOR5Ojh03!ooMx+e43Wi>5S5zU{x>o)*5?${i_x<6Q$EbzEW`_(A=uCq@%kl zhumb1yOXHCHKV%LySPHTJeH^v^>cLre^t9%M~`-OQ)lu_tnpMC`&w=dP6aflvv!fL zeQ#ac>Acict9!Dtng(8d|5ew1bZxbDZCz#gSK`{LvL2kt8lICLJexkEjlO5j%E-y; z1ntV`&tEVUx_ju$FV3nfa;pe7IP+0@=q?qQyDJzO`Y0IsO7GWxzuK7b)@RC|Ks;JQ zFVjD5HF%EFhxIYII5D6M*2W#v)rivkt+Nr(y9&iHWQglD6cA-J#5E$5Q8XcgO+1@Yf>RK-j~-)&Au~jb#YCP%UiO_07lVKvyURKyo!+)_8_Adso4CQpVAaP& zRX!hWfzz!^<1d7}`VK)`*ch81xVAV{zf@@(*<5XUP8*8cZZ-37(~ub&@f${yZ+lH| zEv^_zXKe458cDYpv7zrA@b3(xZ@-D&o^#&frZ9fXYAk26`LS$=PkxiXZAWm-C_a5o zf?`k=V@ue@c=mZ&?xsIvFTlstbId$_)dbq_h!5UBB;Rjz-epiVbJ8_W znl*zbH@9Xp_s6g}`)QUaVDYWYqS(aD@!7n<=g=tQ;HcHyGTH*4;xOdYTw~Ru{MIB@ z*Rq1(0QzvTZg;Ote%Z}uH$G`QJ!7}pX1|8ZvMK4H+{dt)%OVzH)-q< z%u+p`wYG4zvFazVf}uO+A}~=GKQ{C^hzhoZPO3Vnq_eaivl2SB8k;@hZQHBAJ?gMI znk=&_6tGs6KkPl1d+IRbVzwArRI=_7~|)&*Z<{=$@4%SzWN5%_p5Tw&`D& zncbQgJ&oDk2|!`Y@k6lH<>_W2m(6qZ;D)Nvxy{<3xbc+D=KgHh^9&BJfEBRb7`1<= zV)b-p)ez$hn$tboZ98obKELm?I%%`S{A2~wes02Mvm$<89BEIicZd*j2IM{iyt#m> zw=Lp2#x%8e*|kl+J=@DWBkMnX6o*`N?b?*sIMCOd@AjFa(I1f8UL4P!WTJPR7r0D1p4Y?RSJ*5OX zuzYhk>~mz(yLz#?5?VWF%|Cvp=J@vRfIY;9f4}kd{84`bF$*@Z0xW8R?!D(~yLRWZR+X!x$=?7* zLt^suz0$M26XCuzH?6gBg_Uq|dGqZdCB)@mx0cBaz&#O=1El$yf1yBlqZ<<%#f{l& z07i)Q7?QfPIdh7~yi1jESE6@H<-Uk(_ju!NulwoLZs7!8@AU22W9Ey8p{XZ1g=Z=0 z&4)Lh)%0IXMLiVH9$Ncc-5^fW!B;`Ejy04H6RLN0n7@1aozv8Qi=BC93c8n=dX>3) zxt5=|nw~J&K6%zZK|psNJ@khSYR!$@rg<-?HThm+FHfevo@AJ}y#hBgd+sCcUW9AT zjoi<-6wpTzPt!3E{d>R1?w;m+&$?ZoOY~ef$`h6-pO-&*{8Y0*D8EV{cU+`|3}AZi zs`2j4c^<`lSvtFb^}XSt^u2uJEF1GYo9Vrd>7%OVG^6%%c;}<;`ZD_By~F*|LHM*P z@lxCG^92|x^q&Qb!g|KP2^MhR?ncABr2HJ;IZ_)z3Ok zl4SK@xKs6Q&IW^|(Xn?ti#}X8#r@r3K>pVxdFyFs-T6x6vs~HVb%)iZ_G{a%4)wO7 zohq=DjUEl#Tfz~)O`?|`9JlGReU;hLE1a{Y&22+gR({{~)pa+ItzI=-UKh-i(__Z* zi(Q?r4UHpHUO$gM+>GBftQmMe2jQ<rT&y$g!)%-^!2+pW-i|DER$Ed7IR06~d1vM}2eWbdFQ730k3*Yk$)C$))S^>sfAi+5DL z31r(#n~3E5)Ch3k>*u=&Kc4kY3XdzfyLb;E4Hh0L9CaUa*_7sJC4F`*JTkH~ zNb>KLT+>C;#IiDxOb-iaHkG zHStvWtKX;JFpa2K)&mFK&3);n;NS!ZdCzysg<+h!UcyC#5F3Or3A|Jl(9Cks-2hm) zJyZ(sl5?08Cj31B2Ji;3K?oIgFbAF#i_?8v%wZFv%vKw)+uyp#FDpU>o}hw-p@$l$ zGE|(81}DCthnBN4Ox}wI?*~IKqhe*aY6}fPbwMwyLuG{S6Ae)}gLnwEy9<~w5N6jG z?~baBve_P`0AwL@F~MV5K)uFVK|epn>*zDfP*MO$LI9^KRy*4t0FmVNzlVIL0)%$K z!0W^C+jRgCsI;hHQzS$j;=+j=GI5DOAiso3^mw=q*s0jyKl;XI9!v$y9+aP|O0wht z1K}sQ#9`NC0B&SJBC1$WDram!4J~K4EX2DdluefT##MY-rkSO}@Z0qe1}FbT&?HY=JmGlVW_)^iR&(LV0f{ zMDZySqyQD=X*KpDx3@X-DCAG4cye(cB zb*QV(cxEvZVP2e!tE2Qf`(-Ndig6Pa}C}8N9Ft{Ec1Wr4HVsw z{|~zP3*G3w1_0oq+@a`3GIWCG54th>2fCpIM0xf6$;R||fDwXwg2;iaRh=+Et8>a% zxT^P=fq0tGYzzrXpg{+#G8&cr z5*rbf0a}cK-A{&z751M-0FaS6!2nPg{&ZqA0N`kVI@Lsiw#Pwel9+DFP7Q9PfH>9PAKs;ao#40Wn zB)YB}9ONcSKknzCXiFcY<#HKI`fBdqZ6Kl`O>{&;@=@$0;GDRoI$>eiJ50TRcG+MU z(su&`rHz;F`o7vkPE3HpHhP5;efD(=3c=fcB&7%%YYU*eXF*f zAS%&V0#L1ch|LPbn9dwmxC^=Ys`bXd27(Ymq96JS`PDQ`0^-6_^{W6^{RU9jn`j<@ z2G6S7WF#T$hn;&0_s%))s^bSarK!T71kvE^+Spr%iV{S37DXTc0dI342S9Y`Sf#RO z06g~n1*y-3H)rInj%KeqCj9w|abj6TglNxyxG7qQpqCOkI|h!e$`i)-#cJSU5Ebid ztNq8gv)bnm<$5#0R`%tu>=kX1D5MGB-FL$+$h5xF02Q`_p0_$)?!Q&SAWncG0b~GV z?$|kEu%_k&AW%S}Glgf=`^-Lb0;#H`{X>`c&PP0=7W!BbXP7{^3+(d@L@Hdv(B&amd=YsVdah(uK0km&QtX$1x>V%8%O$5%+bkH3NfI?(k@x|7h!H+aa| zID~d&2A>|?lb<<)*8j1dZ1$Ko}+L*)PmSmCXZMMPR&|?-(frJd- zW6>aD1701+05P4q?mh?y`hNc`bZ91FLH;=yP>|%i`BtnSdCCc8U6^7DkBx71GzRzx zOG&K}%gj}27wi;R%iu0DvJh%WvMx+$R45r_W&ag0vDM$OE}-L3@{Mo_mfiKkh~Dm{ z;ov3}A^QXcfXX&{0$PQ^$O4epN}wjUU_!5({3LicotGU0^DJCH`rQCAF`kxqv}(FU zhVmsF6xUx}sqpPCgoT$utf(=3UHCz>Z{yaFGcY8i#yyA~K)WSI0_Yo+Y{KnWpf+OG~Zxv$U*R|TYF-`D}%BL_fzIa0skl}jB9 zH9IKr&)=sp+EOWTb|5U`{w#vYf{_TdSstB%1A*!c5TjT4wMJgnS@UrBEX zUcGCGzT(Rii6PLC7e*bN0x2mp5)+>B+aALrF;f|uAd&KFv_uuoc@0DZl+dx}z?FIs ze!-*yE1~38!8SsyH1}pz#aocdq9>?dz3bp&la-2*u(Z}%O4OXPCkRXTMtYbJo$*wy zbP;F^dyzeFu_!h5vtpZobo?y<6|5!l(?Dkln;dyYFF; zuMAfk*(7Mb?`4m!j5L+qB3Zic;~D!Wx_O@`2j{Wb*@E}LCLw;Q8y6W*J>EC?(ZE3` z_y1wa0WTtvWj+wtRHJOfkfr3?DMKlKa4X@nD0Ts18uA8G1p-_fE}_-{NDUW+A`l zPTI5*OZV5nQg_o=IR`@E&tmB1AHq(m37wV(Q~k@?zV}ioa#-dv1FK6;O|k_Wc-G0# zYl;vL%KiM-Rzv-3>B0|^!xxxNUj{a=I5=hJGx6Mlp*LlEoRw}nZCtziH>=8F}$$;63@ZwCM_XUNY z3h(l65{Fi1`OI9$HJENhOz;jBtDZCrvwo)~;~nwrxK4Xo8)i}ik99cQGy<|5@*eO` zxD4FpGph{Cemsvb4TaBJ)j3wtzfn+m%Pup|-tlO8j_PraEaTVThb3fE*(6J?A7tIf zHF&Z*XAiIAd)~_~Wm33)m)$0>b56nBqzsmL-4aB;V`m1_hkD=bePesW#}BiK7BNDn*Mo+c#11Q?J50oLuKhP4Z}!VL*fH}_h$A{2si z0s*eSqDF-H@h^u&wfN>6eBz-*)yk29i49G62`d>6;*Je45r)%cLDdin>wyZf`$Ozv z5T20|9Q%lus4fFt3xJ%5$h+n5SC1HUi5O0a7;TBzn&TONjF`raoaKs~SC1S@`Lvkw zZ#G6Ua(Ov&8#ij#G!pG=)S*k%v3kToO4QzPm}xDXCI~Rq5YhnWo|Y1(o8ng}42Kf~ zai<)1*J2zE=lc5?^->)>LLcHK9<`_>4CN{2sU@rkjS*dySZOf^4L;U9C49{osHH$j zk}8&h8#5mq+{P7?^AO|^9H-qAjJp$O*bELY@r}g~js9vDUsmj=JQUYB7|(waYAWgX zkP-`A34P}B>lliqG>f~ZiRC$Q5eW5yNws0aGpBemmZgnR9Py$Xan_RZ)@V(Tz)O(g zPTCFhGL!+c7Obq#WL^$ut?accEeH3PDnB}AmAWV_l$mAa%#`6P#?n!Bc0 zh9+scrU6Y;G+WX{Pm&u>QhyBjx{aiTm!`KrCAXNRN{1#^;rS($rnPdXH;ttC!lyfh zq@by%72#z>!lz(!WpKh}DhvD0gK2}7@vP%qF;}0`>1i^jRx&p=GHP8j8sU?NQ!~0k z6F@7;W>Q%Psc9#8*||??H{99sv{}4nnc}8d>LFPZwCQInX}6(i<4?h`r&%b^Ij^qi z*W6hzp*dLQx#-eKkEI!RsX5Q7xrtJ_Pf{5GV9vcp&MAB@?r1LIYBt7mHqo;mq^33W zXbvqf_aZc(do^|qKA6%x@QZm6wRt{%TYjf&4*hc$kS>qmIaltqKpL3G;+8umRj7)P zH>gn{=~nn%IuEf7m|2=nmsX&~lL>}T6yympD=X4#Go38WAwMltYqQO#brlBMIENK~ zLnyLADE#GC;B8*S999Hob<4B>V()O5_-d3;jg~~7=E?9B+L@O`@tA!bEk>p*N^2`U zhY#X!iwl;Hag|O?J}pXJEzOWF`iQ<{pC;y}ndg^bh5}0ic#3U#N)r%Dl{Cv+%uA~g z%H7S&IK#^NH7m-VEgj2TxA5%7Mk@+=;yvk#b?EZDM?FT`EG9JVYBiI45Gsq^Dz<@D zK4BG=JjrVaSu16g8|H~yJXO1+h2lImOQ)_!X|{Lf)n}urA0DU4t$Z#F{Sz&YfqBKX zW>F4a^1*Y;gES_K85;7LQ~HYeOIrE+b4h2J(_eEp#PX^{gn}o!+6&E^($lJ|(K3^^ zk~g|atg~{fQ*dRUW*rzAQU!*8HJt7ROk zVwS10hDEKIMT0Z1y<)n%Dn90C88q*5XWn!R$FVw`@CMp)bO?ML{;`Hn z>CI+i`Fdyhzv#;x*H9w&bz4 z6`nOLfGs-nR+^kv+ni}TFxxxA%`+@s58)KS##QvyO8mS}__Z~xy?->vb3y zu4lmgb-+V=7+n^KYtQwGbl8Ef*I#xxm;tB-0wClJ-sV?BK1 zGt1q-W=4Ir2d&4uw$8@&lYyfh!{ZgBrQ_{OmX#%}6UhWaF|Whh9U}_u6M3?z5wd+5 zuj7sc6Z_*a3lS635j}q_ot?)$<<2K|A||OTdUn$%h%@@H&%2Hh`%dYn&Mc?Dj!$8( z4?=iOKc@GzxAg$tI$UK(ofrm}HD?CXC(q7G&CZ*62rPk}GkdQyYxuJpXW*%KhG}M` z?!T6Ube(k3}@zcb?&R=ycqu+Khpej#vB*_P-e#* zp4B`Q-GXxD{M^fAEypa`_zW)nJWysqBy5%zd8YJi76o|@LvDu8W8rJ$wD#LHbL1e$ zdIwVGf~MRwJMR)K!y+8gqQOP4t?aC9WzgTTGVZ%`2cQN1iwkS!k2I61qwOUS-TXwCSrtMfuTUo6FU(948&z3T-W+Sf} zzIDyXt<-ofnp&+h;jaf}OpVK}+h446B5inPZV0@!u~*I?$*uKuuAd_Z$$WKOrft%pT!EFtf7^KT9_ZZ}));1G=%ZEQ5jZGS)> zn9c38w{5bCEjROpXvQrfqHSD(Ez+)?(8}$S$ZdG}4cM+Fw8^#Yw+$qey*9aBp34os z&2=)bZ6Tr!D*3W}LaV~gS&_>%i72$;b?l?_UB<3mhN_))!ad%uZNjJnx3dK$`VB#* zy)RuGP*#iIH%CSk;Q8@pOvDS`;z;;;H@h!ulNBaKy>Y*y~@=)Z`G4eqS(~jxpEP=qO z?gzTjon7#pb==&nWjc$S1OdPkA-X3?StpNg3t8YLKd<>5`JFuLt@yWtuh%Beswd~Ls`p8mZ~8va&Ar$4bJPuO_Vw800oeNVn&^ts<}4xV z4A1&6XZ0L0@dEkQ3C8z7Up}`tcb%PsZ&G?!c5Np2?R0NZs{hDLC8p{2 zyLMg6RbRer-gtN2K@k5nh`!a`x_a6?C5*lf&$^vMxfZgyV0ZhIVQ@Smf2$;Tr?z$W zYw{$1ya?tsw7bYa^VS1mWdjRbGpP(Ck zs8B3Mbasb-voUBN*%+k)5FV*)kOHec$v@~O?0=%0g8x0b`DS#(Z59_XmM5O+X8Ejg zI#8kv4{k_PrI)DCVs(Q#t1(v({Ti3$!kuKP-e}R;l)1Wav0h`}(_6^WjtfGK zPr6#~^bf}7Fkia}6qtp52P`a7pGO}+ZNQwtC)?!yYlC%2J^y7s@52RoijdJQ3 ziRivpP#W9qCz$)f7R&>PPR_v$8#`UkC=D$5Ndi8VEjw?3n+#d*SI$S~QU5(GKsq}| z$qp9DpA?4INl^TPUl@uCfmyQ+DZ>n!trW3aQz^uaGZ$u)8~`@v%H!|Ws{{jCwx>{Z zVdm$NaX}!I0HuQym3fCd)9CKWoRcUdBml?<=~Ce?-*C&_ekBRIq>l`lgQOrFhK>R5 zhhipw$WoLv4{c#;3yTn<2okAbI8@8FQ=!u*%X^(@q!2YS5ljHQKNHHVnxZRV0CH); zXv#QO8Eu{c+KocU8of=@f*!7j#;qpTqETLT%ccyelNA-gHzSQ3BT2 zzmSp5C3%0?5XE&j(g!Jyl$iy~G#vR6jHRKQMt(zI%4*8v6C;{HBNFKg$Gxp%DG{|~ zoYMi)&tYWeGWGqz{rHo!c8IFovVKaO*Q&N$rQPbI`^{_Jdc?&0dEJr1^)v~EqsjMWcb4CfL- zmC#M{{JBS6*G86MMk#&<2@v)B29b$`l0%MbW{LCd76K?mU}8ZP$ls9$0Oo)gE0hlT*X)*NeE&=IjS~{ z90j?dC^X+DO8`<|e0x7fvIGYNPKQaz=6wn;5uQlckzqCy#mqK==57fO{Xv0<9^dH0 zKvF?zZio&z>&EM~Ck@)}g@K-?WAX4+O_`CT;bt45WDw2QZ^lkp!p747VA-G#L7{F z#Qv=}NabTOB8uapz&D*=k@HIlwO$pi@mvWjsdr^?E?pDGP8fU>x zu~4U3ouTx6);#-nVI4$rwcl|BA;W-4w z`qTch89aJ*@ndjqOh0L&ZKMTnp!rDKDr}|F!5A*Mw=b%{2Tm|TL?N%NtQ0$m$~mz@ zyLq=iei}q>?{fZ^EM23gt*#;|bJBn|9fz3;MwTG;o2k}AfcUm!U11r6In=;p^lV@h zRV}#$fOM^Q=Dw_%P}SP;MSNj5iOJ+qhMbdaotPuHX=vfx{G?6$@W!b|pY}jX8x$)< zklVI2U~M+SqjGuKlytvZ-cH!qdn0%w4aEt&?om}x%!*r zv-Nt<(QbEA?VX;k-P|!p@uy*!B<8vgCLFyrM#(zBlg$9N9Y&jK#8`~|^&2INOPcG( zm6;e4DHxs8+|=t4QJg+51X=Jqd}t1G1X}wB-quYg3M``ZcYDZ0aYHi(So;`3%U?0r zu9*_xDpk}!$siR`G?_=8hIpX(75x5 zB2$o=(P}==x=+?&a}vsleGW4W+b|GSP(QsfSRH56z01t9l9EdJ z=JnL4|9rL`wAj$QG;xh9^RaK$Yna1(dBSSNeFlE11%h|uDoLFS+SqoO&s%*e3%cbC z6|?!M;(#^ppVNLCyAbj0A%&dfSJteg(XN3~hkKGtDlYj^C0w%GMYPUi`EKVy$1Yn2 za(5b!FYxhrbwNp8AqOUPe;2EJe>Z$TK-Kyxm5enzcVy5*E53xVDHU(k_$zuZ)k!*C z?kA)qaRIVC4C>)j;;UU<0|=m63$|!7p!xTtB4pzvU1Fwt(+k zRj0#uYa{I&-MeygaNwUsbli5aA!@c1`KzBcotM_WJdpX`Nda9@heVvN(r_@2T&M0Q z1P7K#S$2elEME8ex{lgy`2WUVVG@eqlg@c(*_C_SIeh8*<8|d$?+R%hAF@VL`?iB& zEf22PdwxCEYrW&Xxr~==CYeVTyajguQWmT}?xf%mvJvSDe{4q0!SDxw7HgRxv_Le9 zUFYt60Z?ILJfR`vAtYMN{cn_|pCNo3PY#XXGO{)ZZSW@E)4EVhT%MjQLjbbuc-41zd7G zkMA}s&6rRGzDRD3NIG609YS9updA&JmnopWR~V9Jy!%Us0G(_r8vz+@1zdPoyRSk3 z2LmMQ7-DBVg0L(<&pa0|h3Ln^svbn&G1L%d#CldlQNDG7Zz^1(1)?D_9jME+k_GH1 zJ=wAiLg(#0%naS>l63JTou8gX`y~6v`+C!BzPa{@0uA9-zQEs-e3kyv*yA$LjxjLb zCb-knqc|T5!vimv(#U!$riV00S=&R$FbG@^Jt~JVh$kcc8KKACuHI2$Kq0PNA((nB z5P$4%29@`7ZP0`w&a|S>EI>SSyW;+v1ph3OH6M~w0*kFf$E`(6D%gc1-WJl{AJ?-3 z&6!Ws#d0Y9u@cn>g0`&1om~=Fcvwbdn8+0sg&m$GhieWr#F082n=;^BDrTbshmGWm zc`O-?B!yf$>_IQZ?GQr99!l&&6o(iY-NB>f!0hD^kU{~9dE~})Axc|IOiGAJR^iN% zZH%(zCNANT7aoOGl(zaMU5yy(&lZYK;@4|ex-vbImOjeKdh`%( zOdC&z{O?FP11M5G07dd2O#=sjKtCQWCW~rj;7(<)sAHG0)8<=M_d&V_pgsaV3Hcz< zK#u<&Ye|SMQ{iZP9g5lZL2mIaaPfi986Vx3il7iP6O{#%A%*%2Lt%5lBaryqp~{9M zN>}2JIL(YloxuTosCZl;&{7})F>+(`v2z|n^YfjtTq(XOP;?;w68Pv9_LkKO(mp;} z?|HeX<8i-b01EEptf-7kz({?8WFkwzK!^XwF#pz*e0+q&A8qLyzSw*903mb$$1}xp zjQnqM+4j20b?A;FBn61Zu(f?`Kp#^n1ehWaz1z2!&V&g?-Cr_&^1uiG)^< z>4JHMG75S5JqhRqAy`I547oOhfk}wUv2)9rQ+8Q&m~W8$ia@y;+zSO%$EmNT4OZkgOhO5KezAKx89W^&7{?hHIdBuP&J47tB7LV4T%RIIrU>cRLBfq8 zstHB36Ge2=StAT(CPrcA!a+7wGCF=GN;z2yx!G0LSsI7Ad&9X0hTchhQqGYpxE+=(S3k;*g!O0SQT3+Ke-l)uTTd_S0%S8e=ZrJ|uap*FEVOE{y#IH^QAr^-01fF+{SsbJuV zu_s#3ckLIjJkK3D|7~C)Lxx-Y5yRw8^@H1}XR5Kzw=(JjU;wGM0Sn&?7ih$O;4W}E zxMEqV&PlH;6Tzsp&U4M|v}y4#NyvSm8`Y(R`lYHJ9~1!om`27Z>9W6=dTVWZfYEZ0 z9KOHfa)_gPNaAuBzj|1sdL!#J)gM0?b=hdVABp7QuZD^yq#CN+D@sx;_zSJxls`N+ zeppZZ@JgIdLSFF-Sc!|&NZnW|URLL|(}=}daKTc^W7MPyRF?j_`oyPv3>w#VU(~r+ z{FS-Hd9mP3I9v9nT8X7-8?m~ttyv_drqDK*`*o27SxZ)IwVZKD; zd9Jlrt`vOL5`$T5xKns+7`2R?tfiEzB2?2-U9G=R>i)XWc&FJTr`8v#JwmDVGgELt zM|lu=Q9wta;!SCMLVNn|`xrkDxHnOHj$dbT0Mrz?SSqG9lQ>YvsMb}eIRT@xz$mtu zxSE=%wrQl%nYm#Vxz^UW){(i^U%0U(r+WaS+P|T-W2LjCqdi18SY5eskg0plD0_sg zdlL9#O;r^%Av^4-IS(^dwD5Iyg7;QV=XzsR`A&JtO8H?y?buOuyHoq(qhQ0R{dl3h zaiR6Lq4&(M{mQ5Vw$fXE(>`5Lxw+7T(A9^-7QdX(dqLKRKU99#(P_KT>A2AU4Bq&- z1h^v9hsn}Ip4374*t%kD@VinKN>}eMzcgN!!Md0npi39AOP|mhX{AyhJxZU*SQqMc z2a0O@rqCb>Q?JBv8zc+f%`n^weq1rE-6RcKJHFG&X57UU-~Q{l>!-b|TE2S@vrEFX z2OqQp(XT)E`g77nlht|`8v7@kz^~MlpQ?C!)0w~cH}_@=^~pI5T={=eH0|v58_>fV z;B@^om)jGL`1$5xD2cKsH@0`B^NZthS9Rs**UMjDCUE?b zgb~wudN$Oa2z=D85=ekh4&i? z9~#w8>}UEL{faWCtTMI`-@#Wi5TnwyzBDdw*;7(HPy-t?I2{mW9g1`qv*?;QO&WjO zG*-Aj{LEw`j=ggU#yTW0KEN>6SFt+O@G@>hK1S|5BAzr6l{a)<+;vdvcM>oP_BwX% zI`~$!_gnnf&C5uy$XN6KXGj*Fk&$uO;huk&sT<0HxSB~+l3}!(aVW}(3x`R>qKO8I za)PyKVwFM06TuS>)LG*wZ-^2^{w7BacE$Upa$#mh; zYAZ==z{|p(<76_*Y!B;lF6(3qe6oJY6xnn(L$tmebkTHpw$pUcf^B*PKHbdu(|t)!BAaca$MaG+MHxrpP{S|h}#@~ zSfHrW{mrWds>|K1BUJHgG_~t)jO5p zAMo*tc>U_&HL8sr&eg~h)1PN-D`2%98PT~%f%ONv!Kl_o|7<~AZG>ra^165k{eF$} z9c)ke`SR50G;z}w8OJ^Z?&xE;!FrILPnJC`_?)EK4k6lpR^F2O=nuZ0J;T(^k+oGX z%HMaYn{qWf`gVK9DO=Wedlc%wh!TGTqHOk>j!-y{zYtpp6W>zVY_nZm@l@-HG3(Frq&Xs0f0euO@Vj$+~r`yac7t6z^EWM|%OMjLoUGj*Z1D9MmY}}lgo=J;uLoe?%yPYS%cgquY zG3$R^mmIQf9E7sXYol*VlAq-sOlp2SB@o*-Q=8T$TQ(5ev{k?Oe|9V3bkC>0Yv#Od z>~_-+cK<^B3N`f?#C+Xb{nYtgFKNj=!{)R!`Bz7>`=)^FLy%2n^IhL}C$ONz)7a4K z%fw58v+Ii5b7ApW)z-+IiF^0fvyF;p?WYNU;6JmS^LY*(%PTrO#eF z&3naDp6$%```^7rk34)oc~(rh$r9TYJh&}>@}i;!<5s_3sd;r~y`3$A4>_OCZCrwv zJU-#P3we9>{P6G>e4eQW&sJMMWxtnspG-!Brv=|%tLgTly*EF>N&FYOA!6^pChZUT z$i@^L*N_cH06FD5hX3UE!jee*n~f2PrIB*`CmSP{!e+u`DfRbIE}hG{Yknj?cQjih z_y$S3;c%va#FNenA+~g`1R+*cYZM-DLT1Hiqz@Y)qa_ zVN+!Lf3h)?>ti@YdKtgp(RI0(&9-}~G3bp~me2PZj6O?LX~(h|j)~w|Ob)kx8Jx=b z6*j>4+^|%arzmK&v2_a_Pm8p4dzJ~0WKR%KEZ#E{Io$fAxWHt-i>673}$#)pHij@NVsm zwexA!2O3sV^T#_OO`;z+BaNbOni$QFKbjn_qCXZ@qJbrl>|jTQ#EXVZ1V^NwG?X`& zODn9s(PbeVHWhazLTCUt+Z@aZS-fY4uZX2DNM^rHPZQ8w3@SkWX* zBO7^0vxCGrDGjW|aD&plc#pu;r4(q#R!RvIwuggAqrn3zZCjo^sx-VA?zjxogHZf* ztD7IiO3q%%lqsHrG{reS(g`K5K}{{x*#Y(gC3&9}%VuyyjYs#2GR&V%3at|dAYut0 zB~MF5^V0N7@T1DgqKgI*%9AR?=oZU(4uN}B9Z3jfm2?~||64ZZycUV&e`aII+I?Ua z&D$B9H{`=Bn|H!^tD3gs+?m==(A$05j$vPzI{u9EGI!psx-)k@owhS~zdgS&gCG$3 zSin6n_#Q0(g>KMf_*e(9v^?xU0jApwIDCgY1K~lIAONhB3(`#_khdLX(3E2ug4Bs+ zIxq@}qX!@>3G^xblF zpAgz|`@0;1jpzW}+oFX<;aH8qzuY0yWVvqHC2^|-LE>?V48!2Z|)a z9AMRf$xe!#tMaEcB)NG%);DF|g?GfKyj<}4^#~CK(AW&mCUuv9g+GOR^Z*Lf;F)*- zj4FgsL^Y-#C2!Nsi zL7><8!19qmVw8Yj*lK)HJV>C)X?i}gF}mR&bLY#+s7U(LCRnc|aGk&40Lwl82pR!| z0EJG}x|%>@JW?VOzfV|gH9;H{<2cZ^JQB7a9w{W38~_T0f&)PYEc-wpfY>C)rvo@Y z&`o=s?~;+QnE*5y08=5D2UiF{IP4D#*sjN`VhJ;T%^^jahJZ*J59WpTnc>I*`0non z%VO@~{Vf^FcYy$Owvk|;k;I^A>vI8G`UuBbhQ!#wwuk`Kb=7lRQDGjx7|2!acuWUE-zPDmKzII&Ko1T}c5Yp3X-$M!*p9(=`bc zyX2@8%8g?bt^w7b;V~n&zqEj5(r@-F<7P@<;-Afj`mY zMTf~ox&L3v#+1z_)-@C|dD6=MqMJ*dZ7AaCq?P|&HkWzx-{^+){~p~y!9xFEC>R8U zkH!qnKhz25L&1Cy7+L^;1?lsD6Bs!FK=0qu%x?&oPXOirmM>cJ^8bxr;sJns03eo> zbPWLb&|6dR@R$E3R5?H;51^9@FpdRShX9;?0NyF6&czrOqd2lF zlrk@TLOo1B{}D7IBJYZdZ<^Zg#>Ow^*6+^F@7~`3sn{?xM~MQmoB<&=fEZ&yswYa! z4?u|=pk5TZ+ZeF`0GJm5^soUYxL_wJA=a1xGx&ggbil=juYmx3Jo`U_2MB!sz%@)v z?<_3;;2IXj*Kgc+GBWR~svmDL@2aAgCbIj+#_!hu%iq2`eP2!$%*hn@&rzudDa9VU z#)iuG2LuE}L`1~L$NwKYI3XeLK|${^G4E+b94Vha0Uk6M@DuwH{U;+H=CR511BKR``Fm~ zMBm-w;`_?V``*CL2fFzXHl{WAgtin12;aFcts=8JPjV z^hu$^V)#eF1i%1<7{c#1aAdseJR1I0FaU3GD6}NiCp!^g2p9!WsE{WG94N3xU*87; zXPr|f7?uJxPpH<#6aY&W2bULeI-s6N0#_8L=m9I_Ktc*Pvz#4?M42Pxi*>;j&VWF3 zoh^Y$5%UqDf!;QRsilzGm+%F|_zKs4RB#|+0s0_MEI^J=JiIoIZvs3ti?0xd$H_r@ zy(9@W03EKODBgPX_(%m)6dpv(8CFUT;3L8`bq`1~H2fx`82|ymN(q2~db83%CDofm zAM^DYulp#`Slt*g=s?zlmcqN79+ZKLCwD2SEAn{GvRgO`rMP1{-1%ViqkIIj#HhMFl$WF@*v zA*6!2G%5*%J_%|sa9k;u7#EsMp_**Uz9)wP@%Dz;8!&w{&f3mrDx6xO;RB6+M92Q! zXM3fxCxyz#43Ob)Mw#miUe_J@$k8wZFhR6iX@CSi$rL=?*V>sky!Fb2w*y)kZw&Hd zqXbM~nzTD21M(P&ZcwKa*xydN(x~MvH_}8jUX2H}?exA_C;Tf!!j zgoj_yvxTsNC%Fq}ELSI#{=oXoP?+7-3R~tZhsvNJU&9{rZOJP>Ghp>(h#>=by;Xqc z;0{4uqfeH7pjxivSfcv-rw2q*I)cwZGg!5H-W1 zkW?{YvO=M#aLQW@Yze+nW-wG`+CEDFDt*9}J0MJNBd~) z&$Uhcoxxc6I>EAS6-Yo2JoChuBvM!)6$DENRZ(38bm}i4VqLfI{;Woo=zg@Wny(N5 z64h5SLFCdjM#Uu*l1wQpgsRXtO+(4V=elV8o>D$@1_`j`vC;&ahajYo!w<1dL~+y_ z2bCD|eG?pa;K>#;s=@c!wWcC%lxv3QXr$Vl1878ZwL&EXiIReJn#~ZyJ@5mP1k1KU z6Q{MA)0=2MtSjQUM`)#+hDw>FW?X}W4U~U<5=%0l0YlA28cvrRPl7iJWayxPQ|tLz ztbI$Xz=_rk{d%h^f;{&K%NBxU%ZzPgPQqWz6W2deWsJa*H=8%leuYdS54*jZRCY*2 zgI8sPVH#a@j>+mrA#b?_NkAnQ#`TopfUTB5u>@dY=4Az7Ag04;F3|m8LyszO4~G%^ zZZa?op%3X`TzQ3rWl~69Rb6(?e4Sy(6>kaYgn|_M%DyS%kCg(J@(>G)&y~m@1VFp{y$VO z1mp-T+e1Pqbuq!R`(*e}!;0k3Q=_l#j*!F`!Md{%@vKvW6TAk$b@usic$Qoz_BADE|wa5PsT z#862eSTOW;tPtBUW{po>bcnrEcVNWUjSg5ShPapUK*s**KCnDA*eDmE12k@iUeWQr zS1aJRGFs|i$?v(BE~&(_{xz_+)x;s!KnS!ihFB*vzn<;;Ahj%q!$URW^nu1t@M5_^|j zXm|f^GQ^Vvm@5i14u4>u`k_TeR2MJF8TvrX_esG};CEtk|3Q4ulej4pW){@Ikzg~o zi~|u~o(c4^pzw3$UEXb>#OflSncI9S)2-4G-l<*HvqnLdV;K(cjAzGfxzpOXvKV;o z$>FZipXF5N47}hna9`i3GHzRXo{%33U$?4r?kazy5cihdW}bbJUh|yv<{a6^uYU}~ z%%X};mfENMSmw*_#hRQwyszc?sQn|0BK5oMF?pS9O2Q^(vBcYvH}ZpMHJHBC`~K`3 z+jHMMn6%bJ>Qc4NeRGP4qM2Ft8h`fXw=;Nhh}ik;E$da7bL;8*(93-GRnl&L|MTCj zw%c~F?){~^-qmXI#5JCuXM937#gWAOl^~l}PlF!mi5}NodAC<|2QkZogygGOop;Rb z*8ANO+S3sZlqu>vr~TgtQ}`D9F%uWW7PHTAzBANbu0Nc&aeUPt9M?FVa9bQ9maTT0 zO|ZDkKN>WYA?Pr}IJ7R`h;gl{TbxMY@ac!;8B?skn)(AJediuLDIWdmll;kA{BgJf zL`{8dntiQ?{6miX+p+zFIs9bQ1NchonqZtgNeJB`B z7c_Mj9DSD{WyK)gp&+c-Ag9_OZFNiA6dNHLe}!XLmEmAd7b|2qS7$gZ>k_m;7YDE| zmzjHrhZ1gJWQ(OQuDK(eyT4>e=rGXXG1$&71h*$Nz&SL#Da4y2G(j>9ams zfsGA~<_asqwaQtx0V)V10t|#G!qRcWwRb|XeI4vwuv24HQ*Y&9cEZHD0;}P|F}Q%G zBydnOp9UpSUC9ERYxSLcBS%vroP&X>HGo-BRD>7^yc~#5L&4*esMD6H|DJL0#K5LT@BEHIXpKQije=i^`Ggl?3W4ZV1Gt$F zYlHJ#KMui%4=svCz)*ldaEQQbHSJKhq8>p**TAkNfdD3;4!3|K325WLXap9qGG!tO!yQpQ|ckf5P2+PaOndT7|>uh`bNm^X%| zm!_sSX{0vLrVO-ZjHf1DHKi9lq@yjRcX6kOm1In|rlo*WQ!7GKs_@d2sWRu_Q$}1< zCq^>YT2qNuQl(tdb7-^ha575l(vDLzS6#EFo>EXAQ_+vJuFNu1xH5J|vftpdkV>-s zBr{zkbMPdymdvv5r7|8%vwT8w;)ZjmLUQrKGCn_N4sz!JpUrRZEFqt>!5TTlZaL@h ziKNf|jHh`7z?|jKG&H*0uVs0aD_O8%c_*&fSZ#T_PkA~eIf%ggT(0~(seDfJJn=H% ztyHd5S%Feowh%%pwVU~MDJBRmvoEQT@~BV`Ax8osSNSyG$h=4;EuX=y@I%n>wPl$D z3oPmKM1i*C=D_b^MQ&}yLnkS!ZP~vO{2k3h!9Pz6D4&Z=R*PxferuPx`6FaRBb1`h zH{(q+XT166IwB0%h1DYTI?SLapB;L-A4guF^~*Yq-X{WSXq zV0Iu~hGbf44?@M(bAAm%Nvm}6P*}x;G|&}Tl`>k~SC&37ntr4i_E)-EZnQG-wDM}S z>Vn5^q0MRu_#1-0W{oF%il=;zr{K;l><=(=W!3I8Vr{N@$;N4wtY+1rTQ#g!?W=h$ zPJ20>Vw!Dj)eBuE?uQwY$s^FJBgO|;G9nf?(-l*%1)$*3?^(Cj}Wux_hy!Gtv_4sEEgfFc*ysh5!&4a}){3gxC z;mwm}&9UXxdFibiX00s<&FK~`P9<%pqfIn2?TzKFITCG4!EM4OZKY$aa_RL&t8G=h zExW+_+R^r7=?-DV20{1SCUCmtEN{nPdUMuGn@xCY%~eN)y=GtzChQhpHH0gcoc zaMm?J-_B;yeSg|M)86@h1{#xTB|PuBHV2`UgFHh)@aNsFV{Ihoom($m`Qa@9-flXi zo)In3o<%3FM-O&I-|kt*ep}z6OfTg)h|sN-iJ|9fM=vo>_aSx1F@4_`f;!n(8~Jk# zQ$(~M5$-35z?ky>(U%5x?N(&VezcBuA%cFIjwZ#3eqw?_D~16UzGjj2AXUo&Edra{ z@*3{(J_&**GLHuEZ|ws2h)!TeFW_~6!E*2-+)uf}OJTf6pP-9Hre~^s_}pS7nQ!D5 zUwcZ$kblIWC;>175D7OkU`@~l^*ZRK4W#vx@2Vr#y9*#XOfq zE|#PDdm`SJ#N~$lbTSp+S}?6vdTId%9-ljhmnub~}RTK8rR?<6mteh_m-*B!*>a4PPu4cNgg+#2iTCFlg&a!}! zS4K8g{${M4rcZ@L&PYwHg4fsV`PLK|H}@*nhtgNqJ2y@$H&Hw1xhyvjk+%NGEzioW zwj*yOPOQvq%pLPDZFFw7F%I5&u0QB(JRy(1Sj~A{Y@F*Xsvvjg$_)(4t;}0(^Hpxo zMXo=4Zd+$=+fJ+-ziojTcTGL}o?cei8Mm|v7vHGX33YcQCbm1Qc0Wbz{zcxy_u3)e z+(MCGnta>qIbXV(*vYEg^{?D3>D&fb?*Oy*;`p~QH$OIb?!n1#y;km%Z*EUb?1v*C ze3L(*w%p?c@Bhf!fg#$HnLL2hJ-lb!dqh4oxZIJlKD4enG>baCVBDv+-Um0lt$}pb z(keF~vJNy+_EAwb@#Qw%E{+=Mj>abTv@Z8eqK+spH{Ip;mnx6Lvj%;MmIR1)DTq#x z!jH)&jx~YneqP<|0=;SAqav?UpRA3n%~gKzNlukZ|Aco5%I@dQGxg3>pY_wosFPId z&GoS}d!4h7kMCQ^=bDU%5=;lm@`t#aht9eOwz~Ujx);#8M+r=)%kmezQ3vC?#}ih^ z%(AC0jOVM*r|4rRby4R{S?34Vm%*3k=ExT*6PFh#SK8;hc3Bq#lSg(bXE@DgF;SPd zUel*ctCwDwdU9T>+EbRSi(^&Sf4i=^%ul|`UmsljA@07|lRsJ#0AIv2omfm>D0)a$iI_^lN4&2Q@qrT1Hf_ru+;yA9nN2;wDR z2LpUyRed3ubx*Q3+Tqc8C(i{MHU@e`EbU-r+>Kf7<3h%d{!pHsaz z%>^IB2w&>1p3|70Eux>2zrPr4z1RspXHGp0>7B58-%2yDse_4c8okej-X9C9|2Sk{ za$T)`nEQ#V*C^|kbeq@qt0&O=Jze&5+xyc#^Xnn;^T7Mdc{cbo`>4eG#JGDmF&fNi zbK3)cO}~5xu*z%;`N1F)iKZy*hy>NEeEmqz>$JQsa5aaMj*jU*IzJ{JW#Ln@F5X^J& z>!@InLKLCC7+FeUAz|l`U<8C_fkHJPA1HwmkQ_HoUVXLDXTQHwA&?;G zd_)#W${3go`jY8AB)RxmKU6$lCn?4Fw|>DHM7mO(L{-o{);a zLZsPro8?9s7P&ZTF2rYXntn8VWVLzg#=ZEh1760hy|kTGdp?V z%!;pVrFkr-IIe*|>hM?6ATj9Yd`OcXRYYCiv^x$T07pHJ4*-ZB;Ag^0(x7D%|CJq^ za+vam&uH^L#(x**Hi{)wX*EjL z3*t6THDOAP?=~IeHpz6xUO~e`1ykVw&|FY|MX*w#X>evG8@HLIXgKkhmlo@$o|Z5( zH9|_}elg_J`s#I)y$F^c-kk0pJ;u4}-nVOvxo+0Qo@>p|?;Fkjf;gr0ZA&*A zilvpVhA|6?qtjJpNL9mhU#+JVjtLzDZ;47h95yq+8<9gVy-2t9vdY6=`gxZipbf4? z5JCf5(|~4NMp%0b4}mt&5xo>g1OdDbrx#Hga;GrBSQ)tPV209p)ZGKXkA4a@(5xNj zQ0;6JSF-`R+XMd1<-cBW^Wu5^^OGdmKEkXD7bAA=m zQpnDwJW@{CEKJ)+pIUrGHbO@iKiANX_IoeR6X=FI`I@xchuN@i66Y{Dzxy1q;0gW! zwJG_XF|c_>@Hc&k`6a>dc#KGe zf>H<>gF+~Bg(z^Jw*?tw;pK;gf?EmS$vK1$C4iw9w`_lDo#_*B6o!z@3?Siu6xy_$ z=F6=Xx^n`A4gKE62tX%$zEbb|(M1OFWHn_ds8I$J28nhA@$01wCsNvU+OM;qKo82PgfaXtTq}s6~Xq_y)EEV)!BRzo7h9xMrKnL3vje z#dP9dtVFSMol@W+J&}#;fG%`GKNfPq>;l6Zk9k8VrDg{l*B(uxtiS+%+Br zHbTpUJ2JcX!H+!ZT{i_GmN_LB&Cp}DW@(WU zEVxo@<28)!;;~1H`g9rHaw!lTh@jO=%<-P}7dvk7LQWamAByEume-c#z+x0Pac_uy z=+>p=o%?FJ6?heI<iU&Bt%o|V zyA$Ezn@(dqTO^$5FSZEQtE*NN_5IsNYGt_XL|rk+e7KB?`Kv@bSlDT{Q0Ob-oT>~< za~Nf`mD)(w>#7G0S*mdKt1bqU1xg&v$OO!u!%u}*2ZetHd4z-p9h8q379}>5nC*_~ z*D`azd0`PkFeb3*UZJN^56*uc>U!QNc$;=ru0Em0KHJ0tqKokeQ)FX^sopRW%`9_8!bBL|iahUYFZwIGw z;~Vee@RhIgkNP#^s=ajbN3kV1gT}Dv4b2jL*Td{*n*&yDlh3%5hYZ${WcNaGaI7GD zpW~4qnn4S)(z=69;BIC;5L{1-mk$-klM_I zrZBYC<=Aw+cFy#4l23R*{cDU!a;t?dm-8^VWNMi&`{Am_2$tM~XG+f?yenh<|>FQhLQ+mYA;1Ir{q(O}{ai)D5g zVa5XJ%tADa0sx9@dJld2A5E)&&LB&bV5z%;TmA~1dD9IW3#^KC?nB@NqC%;BT2aBa zyH}(Y9>I%Qx-f-M$kG5{Kq#;@Ks~bSH3J1=P5^Q&z9}G-Uyu*#DEJ#V9~^5-)=WoW zZP&^Q4=;HaOokBN9MAeqH!&~s`*L@iOaneE2RUz#D86v^X*UTkD@h0onU*jWgD{N` zNSL}!m^4%P$G7g2FWpO{-C0xI_R9hk6z$ADZEv*=EOk8;eZm}bJ+vmh9K5|>F}|_! zHgH7?b61Fbud8RA6Ctn>;lvQ7)ael%>k(BE6*eIeJQFSy5t*#*&35X;BVZCx>5!VM z74Z=T{N;~-5>*K4j>Hi$7ZMe}-ylVK3l zloixJ{66Pf@ctNXcGxf5_f9jj!ESMS?56a+CG-!^=mJM647oEkD5Z6ao|C*@f;=*=Ll ziy`eUI$Yp0m}CN;Z+A@^5opV2qhM{o+&7?fU4wu|03<3t8HMcR*;v=vh3kcx%eM*7yQXtdSg0WY5&*Y+8@E((^1)@Yq&fXDY4Vu@ z_n~m|HA()pZ}Pnk?|n}`*%1gpgM?B5xTC?|taVg52wf%pgd)U*smFlDlnoS7AUc~k zF&R09lszP9gcqBbG8xxLR74XS(!QPgn-1(loS4BFhg2NvbC4Z@6~nhur1n-Mm>nIg zP~4RntA(7#ya$pX%{1)EoYcuduPacDciFn_b0xF&T_>lb0NvQ-AyyHDNACg2yM?M-px+;DQ#7#Z0pSN+|S_b%`hQJ3j^hl z7-wZnr{#TT73N3wWmQ#ur7J{Lx$9N-O;oQ%XUDzfw5MkUU1xDc$2D~46_ZtKA?JxH z=Sh*&Rw{^>BrRrvX&SsRcD-*JicjYwl2($EieNY)qNHtU=^elHGD!<{ehaY zgbRV^>Mlr{nXIZ2n6skw%NhN0e_T}kDmBtfHRKr;&v`T>-xueiHM64C+|Sk0`Lvod zHS^w=5^|(fim5>$w*8t5&YBW{&SF z&_)wTsEui>wSuVCX02@p)J~{eeWlTEXI~`Xn0?Y1U#<2SEs)%~cG>!xX4?|TYE5cYqpDJ82B_2cPk=^u z0;pAiq&xMlv%#mc+`dM^H@D5EBIc`8bgmo!sbJo9D^|7Z*L636x@k0;BA$Ake7b*i zH&klZg!`8@DK{>4XUc)I!|SsPuIu&h)u&?X`Kp?t?_=|>e~wHyj#by%TsLOMWnL;b zS5Q!&&RYA!s)8m`V``WKXx*tUw6Ji@@{o1gxTLDFym;E|Vm>X9y`hWoqum-ie z`OWrEuX4`oDOG|tP%n$a`ePMhFvI z>=VZP>CUO^hwBr1{9VRkit6%KsI4=w& z?UYsZOofp@yN|mfRHm!@3cy%nc{|hZDSBCArVFlnir%^gYMTIK{d3j52Poq;Qxn!x zBaHzg*@Z>4gJlycEvu>n4!r|u<9)D!eI0S*Emt#+Ff&IY^B?;L`Wt50a^|jX`|ue1 zN)v0L^ZNn3htKC`cA)G-P^IZNzb#|874LyV`;J`)ITLGfLw~AOy@o@d1H+JP1HFj@ zC2KS3Y*SAx3v#L>#f~iorX$}Jvs$(zK6cZDha=YP1CI`~*o7mchJ6)i3#WHe!v^E% z;-i?Vy(n=_n<{f$y+iwqqhAXWp$EsQ565X#2tP7s2nO`R8??j179xu4vl|TanXIJz zOmk!RD;7@7v!}8Sj0*I&<;_k;UA6?=tQ_Bue-^9$u`~HyW!&g@>eeyjUTm5iW}akc zkO#7A@-r#Rwo*W@R%r@=QXs>bIBI1&OinRPQLEF42Ovp?%4z_5gcOU!&04Fh$J7qA zf7(<%L&W}70971VWpr51=>2dE9uGW%nDW!0COX}ZSICsJ+^uIHrV5E24!A{3|4_lr z*goHk#ruG~*v`h?rn=a5!`1j|w`XRTbbWq6m3}ggs(BO)g##H9A5c9Jy`*<`v0=ry zPy@#Jc^Ekqt`wjOZ(A>SHl}C)aABq5e8#U4VFdbo+qRo{QSu?-QBl|hRXA?)R8 zt@vqrw#hxy`Q^nCa-$ZS{t?WgIrgGqvz%2+!x7jY$1l{&H5(>GB|05U*FWSOkw312 z2QG`KK>v7_WjzBzb*Bh3Ycpu;QFb%jPNsG{YxGo0(n}}&OJ({$mlU06mia;Z*In@(&3`Z9ypA5gAzk2lituBtH3Qtfxe zel8kut~CozDkXOS;(L`;J1$xmO@TZ599L@}XBdc`qc_*Dws699Rwc03<&&2_?yOA$wy;6l z)Sw*>(5?h%kJt|`9ss2PIt&LLrGk!2Kqnl2Q1O6I{BnK>y2$Z6djwr!e_Sv69a4YX zN_^ZA``xPh-#iX{x}vAlkLQw)m&T9R!H>7akN3k5(BsDkOoZltQ!p$xNB^Z@DlD%5 zRWMFx|4GmMt6(TblIYZHY>saz$37LzOoinw)kG$@`_0+$?LX<6aCAniJDQn7=~Ncm zlRMhEkl#!U1^^m5X}O^4SQSvHAy}xa4$z8F#>r}4z-+O`bXZWNOcnvW9x75uL^l?j zr4YUlptceFmt_m7?OO_DlhZMt-C0`xng;lXj)%|nWDsO1ql|2_V6q^5G?#o|MY>DB zEIhQ5`1y;gW}q)!XIN>}&#>`&Y$Kzu)o~Z=2=<3qps(|4%XKl|Q5aGcZo|3?$T36% z*`QAlO03PF+IXHyYF-#{Fo;MWZx=L~1wMG1UNx)VlH%-%OG%*M>Bgkl^1!Jt_8T|7 zuhGba0w2c{vwcBer6eH&qze)uaM_2r7PS%3q`?E{Q@4_Cbut!(e4Jf=W zmLYK3l|~~E@)V2wXb|bi(+n}((~+_F^>k^LxTJ)GX6hW@muKqS zKzMGNJcZABEdV(>QLy{~%om!%gn>eMKssj`DnmLTzMwG6>%~$c33>^Y8lVGDSN6M1 zdWr-PT^3-M4-eTz3=K&lM2CZ+5TNxpY2>)98~)V-3icsEP$=AqOcMZY5EKapu;?0w zDxSDGtzNd`DW!w5KmU2)mOb(oj07fl$VeIObn*-GGH+PR5hfW2t^M@ zuS{KFgU>J^z#=9q6JTmQzZ(*KK7*+mT!z;%EfbPtsDHSH+qwgRgMkS~a#j-Xx=1n{^f#?r|qv zG;zi{uNv%bk&pO|yJlY3n=p&6S{BI6fadSZzG7M4&c15f`p&-QILgPd?z-yBvEg~z z&avtH`p&Txh``Ue9g6SAxf4m>!MPj51LE9Ekm2XrPuBM1I!L$f;5y9m25}wb{ov<5 zF3RxZKKWhV!F^iU3gSNdJIc>9P0I-I-Op?L^F1tEck(^1dw=jfZT}GP69EJJUm6G^008}SLj%D5p9bQ;0|-3; zm<<5n@QGjmT8N06e0-Mw-9Y?z0O9BADktaIM#lLGAi4l}=bvE?z-ON0ANp_sK)Xi9 z|M>FdgMi=;jbI)?*9YMF_=FDh^#5c)cz9X?q6Gk*Pu4KRVfP^>_77$FmlaHi*uVd4 z3LZZx!@rsV9Q@~}VE8P7NCKL^0Vc=*>j1zm7U1|l84yIkEgISfF77{4;XiBh@`6M~ zKmG?(csDiu4^a4LJ%9g?XtAbgm$)do-c*C3|0|mCFFm;b?12;%{Noa8YOXsvKHDFi zF}-nd_y3b7SYhfvKw)NLVqjqPzl=g}@73hw$N2a^Mqzbz zW8-pY==wiZklERf_4R+MAfG;AclYu?RgnGt&os#Y=YYaLPu&0J-=~3~{QnKazXrnp zbIcZajL)Zmh=83Y|JOkLpCyn4pTd6(L}M5EyAYWYwg*9-SPqlRvD}NKwF1Y~_CPhk$?h zL#_!_JOsrQxBVg2pr^E{e0RTQaQG&%8 z7igO$ztoOsOEa^z%2M4MMpVc^@4zR$C~OkcE^y8sye=XH7t&#J+@&(Xylc!UC~$lt zI4S5)eDRNbIJ6e31}8ZcYzfQjs?-yoAtAdl{cM8ZUKyH!yTiJKgF~%F8P@?^x^w-p zSx!yzmhD;rfhkl&LF>Wx zK>@H~>u9jQgfU2^Py{oeju2;j(nb19O;jQ?EE1ufs)I3QY-6=ix}ovDFa5E`ab999?vMvLj;TMn(*wlRfbW%Wo4ylH9r^coh%;M*@y=4%eGMK@G>K zF|3bKw*~c;1{KNav$4Rc3&U8#B;aX@fE9syuEzQEkM9{D@ee$qGAJ%7NCy&_mfmYf za9ZXyR4ov|Lmd@Ki4nIQ)n?iqsK6i`%9Te61l z+l%!~UJ6oaH3fw~^U2ED`)W42wE+$a8iQqx6b<*J<`}Sg2och84T@ertY_CvFusLw zDyu`=pw!&mQVM*N1L8?5o1&Fyel=y6%Wh{7a>E9|#eV@D+LT#|I8_Fw#aLifgXYIy z%0@AuPW6!Ku%J=h1IfW;G(u;xz`&U)liz_|ux^#qGx5g|%j^9StemHz#v zvE%VP-d~e7p1FEdvtPIJe^mnce_$Z66b-=sTM6X<-axpq*wXd?#5?F8b^k1ZJd&AZ zI%u++FGzvXPiqdE>z2n&E~I`LemBo-(`0fFlgYj(FwdS_X7g_t&fa7>YQR{T^4*Zi z)vUGnMevI;PEDqeGRq>1Rf{b(Ww>y*=D5~nWj1+2s#x*6RhrKVLkX2knJS^xcl&1Q zaw3_EUKVSu#uut0c3_pRl6Cdn3VkQ^L#1tv^$bP^W%q@2O=FFX8A>bFAQrGrb;hPr z1)qL#;Gx!%#dgXCpK`fFx~ZJS&dJ`JYV$$11*l|KR;NvO8TQz0T4OgcmqBqIE8US( zWA8V~L-n{I+a)$*UxM+b`r-CDZk)wojFo@_L0`J>CyQeg^&2HhqwD~ml4GIE8Vxbb zb3aJ8#&IMmlbn=UdL+EYDJ8Crk~&p(jBUm#Z;pV5WAJ%Ylf`-Hj)0u&Lu$&f-C1t* zd0v-^yY!yLCI1!on8(s(~VkjS+%XYVi;tW~V(lS6!8KczzBF`kn{ zt2yjD=Lqy(o7O{bpdYwEPiW1ZoN%wz_ht8pi`cMcdBU2}We`GnGsO6a@4?@=^l)q| zjzjh+5!ql$jFUP50zFx^`EPt-e2>Ip?i-0W7C#NdEWN<}Xf4;hzLd}LIik1e;>JVy zqtB_>$hfgtHRP!9Tq zd(I0%H@`t&9O`AT_RAj$fxqSg?)SU6Z<+~wr>z&DrnC==M|1bX;E(6cSHGA0aJ#cc zcQ8qds}kET3G;WDfR9was&H!vNe>tc%x86U%n19}l7QAje}bhzL<>u_Ba1HTMV4Fm$62^Em!dnRVMSa)LF7TzYw$I~Vndo?4@N}%!HFyhgn{ppg-rOY ztAXJ<$lN%`Ed8ehvJ|sHBhYgjv%?v?r}1wIq%=nK=YJW9gQnR37>FYc!H2ZCm!`O- zh`2Y4xb{-4xN0c)c&!GFh^nC|xZm-z8h8<3!7v>JA+IA_BdqdEF|;}H;z__Tl29?y z!>M2sN#TNu@)&&-h$F6ep|2BChRiW76RMj)xH{F8thf>o-H9?o@wQ8ecUVDj)QN_$ zNkUSIi9_MS$KlwPj^CuL`Z*IvntpN(+wyaHG7np+S|*Q`2I>y|RPso!VUI9gO41!p zHkL}k;Yj|Knk0c1f#03N3X@_T5kHEP+;o&offnx?_)}gpRU$G;#uLx0Ii6`bHC{65 zjXG6%3IBCRDYStTNkdpI@vI5kNsLR%_Tt~oU=GE!_fBGJ+{T{A7; zGc615SI+OW%H{YnuE=c7lv=5bD9&H!>c75zmOw1iv}iLbEHkQTGpnC7#65pmY^UJn zWeUQimZPOP<7W1yr=d1QG)HC@Yi5Xm(tiy|{aRYiSb?*gh_p0n&g!+yK3q;)kP2vv zOx}dcZp6(P#LX_H%{tP|Om6;lteNvVobxoC-nE=F{5!>(EBiNC)?9inyjQwcM8?^3 z_Jvdq2+lTE(+9H52|Fs!|F`u%ZT2~C-ox)~WV*n3TyI=y4BX|cMcOCVJ9EH*AF3OFuQY)RvWFaE$y(K#vBhtF|+ zaaFO6w1$~JKeHwOOL+xcdG*?IWtLX$)k@XHNaf#_+Rc$_ zVuTvO)+(^mT8FYanIC_?XB6;SmvfAkHqzOmtkzK@)Y6pKgiG7zo_w*;LNi=-+l?w$ zw=R+W(O~(b1STV8TRKQtra~1Tk1?Z4k-lC`rc(FS*Z$N_AECk2x}MUyQADPWln0$2 z0o%2;5?rSG8-la9x1aBiV1Mrho7KN|_>DW<%}G3s8)nUXr%l@B^&L^oale}}G@64E znr*#XJhh97}mTyQvGmbJ@ENKwq~b({d&AhZno~3Ao!nXtK?`We)R7L@6Out+P2po(u!{Au^-?S{v6Q`iVXc+ZN(Sf zUBKx2Z*Axsr&wF7y&|%GYxwB8Ygqaf{bQqj&P zV&FLTi(%A=cPzVYpfMV6Pj=+MrY|dcz^!efWP0K+@6ZimFK^~VoXuDpZ^9+Rprg+4 zk?h~!hLi1Y-LGTA*Pm-63={E81rQ8etxZaf4MN$Dl<-b_5%fvPPD3KikgiX^zE0=x zj^b8=rc->T?^~yxUI!f3y0LY-PBJH7cqip}d+mINU}0yqaGG53r^wf*=(1+Q%4WSz zW;w@Z`Nlhf&PF*1=ani4u-XS1-v^n;=Q4N(2cjmC&$}8v6$Y@CieZ|jVt#&feh+?L zC1#d=ePMrfKq_W|PIl21sgE*dnrwWU?R~)paXQ_4k-cJ0CT5XHc2+d2QzL6WjBhr2 zZBeX!(MNZlsB)3ocS5{!DX^j!{(K?9cR3B1CmB=vyCNxM9fNjc#`Js!XuDv(z9hfC zY{0mX{l45^v69fXq|LY#d_I>MvxH!~8dj;}1XMpv}7%`5zemYE~{rP(=aaoVVwPov{nyX%hjDWj#)*ES>Lc-Uv6I> zXIxbVj`g1RJOBrukQSdSH@khC=X^Uhb-Q6=x2oS)q^!kV-JM&;O)jDh zcH~`7WmOGH%n4e(WQUh&&_e<592-34#7WdnuzE~2w*kb88P~~3-;Sp`FXYFw# zAMwWSxL57C@E`8$9v;8%d-)xCe12s>-V6k8@(}ID%k}v39|vwUkHjPhzBlWQA1E-L z6!^^zoY(8<<^HZZv9fK*>o}ArI@OTdO4nP@*jP={JMJeu;K@35_dRXm-}^FgRCI9^ zW_MU&`QzF8}`JD7dcNVwx?cP#RLgvN9xBX?F4yS>eH;a_=XG;!7q zIt<#_v|u{7(mNa4II`nkDcv~M?KmMbZ_g6ipJTdQm^ddU-M8$%yym~~d%sACJ^xj8 zF&=wyJaI8Su?H=G@>%lOXF6_}xI&5B>*POjV>$!~EYELjv&n&uNCa-ytFH0?9Etkf z*vj3|0S_D`lk+_7|?9&CK}N@ky`@+z5{*m7>wW3MpnPulnwk(nR(E^nvg zZZBeQvHm>FB7Y9JSIarW={z(1v-M;0iKz1^)b2_9@=|W{ zFw*}bCT>Mp{(cd(qZxOk;RsDn0#0uLZOZvT^Kv}QbN5pK%Pbe%3;^e=@Zweb%s+9{ zOZ1#1kNM*(G#LP#l?2td3%ow=g$esE7LF?J>u_%)k9i z|4N1Q72sF^3Hxav&@sS*LUE-M(f>6NqEVRt!$6=ByFubA?MWu$2&9NMI|@msFzR-M zNI98~rBPdM^rg?3$z?Nuohvvh&_rPJfCJZ-m5-I8q|*6yPcX^`(v>Uq`tkl+Ekr9d z`w<>vR?LVQsUh-NfJ+enFdFPQhgY|gY&341=+D63U2k)}pSXWbrJ!J8oWf&J6angV z$B;t1yX{c*DR`hMw(*!i&ne_4|2r+gZh0!dK)8`{$-zWAP~ z&QAE6rjNF#91FL%dQ-Y7urigkFJ2TL=rSyf_*40s4g=rkFSX^TRTm7p=_z8Y`r z;IEh4gmMXVDU%`6AEHh}Nm_Mu10R`%mK=CT5Qfm(4hT+t47x!z6jY5iaDZ=v6hFr# zauHBvQ(9c4Vm6LWFIuygY(Q}ncV~#lGHi1v9c{t~?`}?q2<((f#+!rR)Y8Wm#P@RkZ>QN~6NBFX*EQ?H0h5lvR_~qTc|7 zC&`<3&E#JTO)jKd1>)0^-_I*u>@(CGylAafn*>mgWS*!%IdF)O(x@N^IiZp=&RrkVpz7u3IawNATG-10_`Ad39+xjz)?ZrEAPLGfNlxmAdCET z`8Wx@$+!@KNw5zAiaR;tn7H39Q3ORy#^&2#%U1&gQFI}bAK)$3Pp45IPOaJyBgk-Q zko@^w2tF_?`VUAWDb$Ho!pkZ2pe=ApNiST2@p1;CX97Yw zq<1`>5x0(^n-a{D6XUS{3PKZsK|^uw$08)^Nt#gvk8GDxcAu`{M=yrpsm-MR5=5X+!`8#(et#iN zibjq*9x+2zrd!PMBCr%i(Jb zXAkOybuanhpXQEm7uWN!bF-;O+V)#9D{B+nQBs%RZm4DyE@d^cx0LSGVEk5dN3^oGuaa_5OEqG z83Y`xAULZ+STms+B=b|C7Jd3GwL)NtD<`CaBbB%p~=kYBJ0qcQvFri8WWjf-cZp>NZvEB8f}UuOB5Sp&s& zt(3^w21`1m%AgjGjZN_w8Wynp3@b4-nQdl$i(M=A+pW{?@MyaaFsqvL&k)d(m->i`M#_*qgKy&wqeiGgf9}7w+aN7cH<) z*D9PITQT`AQ>$Mshl=OhuaPd3ZZbA@Hg0SOfft7OI#l;^ZXLTwSIj(XrazOL>foxb zeYJU29@ahjzE3zRd#}l$qC5?q10Bns@XeU8IaQ1%lG0~0_mv%+`wjeVrRH^%NC%}S za2uSHOWKaaKN^MwVjXi=pN{0@TV{x39n{o6XBEgb&V37YDy8S$)@y87ke73<;PBjj zVQOCD5xy&K963DN;VPYHLT|`;KiO#TUOHsbso8x$`{K_%@i^fgf4F|>kL|hu)5%)Z z%6Ik4>opUvl}3b=Pn*b3=dc;WxJDmA?Gz3bFrVbEo&wte#KeJO4wk z`p>h!eLf330xtpT{8t5XzLgsO@++NiFSEq%GCw zZ=elkp7+(x!`9l@UV+gsf>-68efXUp-#gEK2s|4L?0oM!`OXKmCs3#@ScS?R3MP02 z(Tz$VxKZAPLLh|3%LnfB1Nki-2J+|gY69#Sx+lF5c2d_>D?ct`BYYC%7ujxrtRSKe zAJLr<=^Ov2fe6~|CaUYkof9Gs?8dPXe54nKMg$4dw+SQb2vfBQGN^PDL;ka+W>RUV zU=aDvT1HvX^IcSk0#O86xt9ttk!CLuE=2Hxyq!&li-1>vNA%M`^nymasz!TQDTKK~ zdZ_!p3S=S)iuQ@^_3}jb2}Fyqto0(biOM2!OVo)9y$N&Jh*0wO$<1{MVRT5@^hu8i zC}Ri!8N|M^b_x23vEKE`WAuO15z`*)6Rr?LkM5VyLE{dg6hj;sx8^rsKr@mRH$CH! z8xzx_5LL73KPDH@j25?O6Su+ORTUMqJQFeVLB)F$QyLpkFcEQP71cQt|Ez&>%nb-R z54ida5{QaX_lZo@4k+*SYi15U?212u$_GUuC2+nCT!;*O!5soa8!*i5vEm(akR75n z?8`I|@*N)BckXu*9R$7&vi=x)*BDBE8TyOgZ|*V}vp4vYp({4JHWFhfz(?w%peLL{ zGA%?jgSRO$Ng^3iBx!C4Gg=~GOfs54I=@i-q;<&BWYFzy*mh1TZ%x8CTKad07z~9( z+1a3dpOl5M)Hu#Cx8rac@5qjfv{$Bd!JRm~k96Fcbi|u?k(kXhxD$c$;+Hn6wmwbn~dpADd4tAv??~TUaO+`X+O8B-0T! z+MgjaKp@*QHdc@DIRaX?r9uW&OE9|eDm%>!oI@N}@fqXB2P)By8J)?7?*=npwfEJ@ zWSG~bOl;N39T2p4?`Gt2O=QW+%|`>h zZHAhA$p&tLS30tbK0v+l_8VCe#32B*78$8h{&U^rD+MW9&*Ue7Kq{LAK~4dHAs-l1 z;O+9@YzhcvLk!PBkfkgu2@?==2;a*mEb^von-vfkC5xOVkMAbn?|WL`hR<}`kdqZ= zWr0(OlU!>GKfh1k@W?O8PU2_Erf5vrSpxBZikO&+C5W;Zx{AGPiuXF>#?gvIx)Z2b zict)}_6o(9mT^-8kbF&>Y^0A8O(ihdLTN}xo{&(9xpE|(SBdOgv0rC~@J*5WTdv+?Lavyx zP|O+QY}xawnd6!+j2b@sGI>zAp1Lji?^A}R(uuxW=$Oh;lnZ6`D~b1FVYXV~?JK4G zE775gImydjP%F9h>f}XQ74H+up&GG>tES2;=3*-=;F|ScmIF)|1Mf8i?lqgTw6h|$ zoB6akf!cr0SCVvAf0}A_7iw~iYuC&#NQW*bxN7zCt)&z!#1O8A*y;@G){eC=w`a|D zLal*XFk4$~mk0NC=Cc+$Y}u#xRcH2b^N}yxg!&IoHh z^XtxRx|Jg9>9*Q^p;~RC%l@hwV@bNzdAhCj>%LHWCwv=^vsweD>z?Zyv6%DTSvqaD z8))wh9x$icbpTTXtA%vU`1*3sS8)%D) zb^~L=0EuYLjL_gf*NEj_mvwzp_1+L?!)PRVC9-mJlx>#EOhsdUdy3HLbV?KAhf&wr zPSU#(IkNE`<_1aF4j$9)o39?i!fv4T?iV5xVXE!?b|dU6V;;S&-v}n@Ka9!rOlY(9 zd(MsDiVO%AOsaK_|7Mv;br^$B?8-f?(r!d^@PEUE)|E##6$6 z02(~{nu=_g>OmVRfwssxbd~w{Px*Ae_#vyXV;M26(`_t>hOMc&nOf>;XhQ3=rc8@N z?`lx(T2Jh_&YOu7?Q^B*SsiQ$%b6Lg>6y48oBGvChV45}n1a~MKhF1EKyrG&t+y?Z z&84x-z_s_4#1E%U50=Nxi&hV}-i;|iW>mgLLLhUFF!M-$i=Q$_&K-wt*%pkx7Lo_X z_IgL(7dAZ~cD%4Qqp6Oh8+ItLEVVlfzq{>743q^<=>DoY7OB#;P_sxiJBoLcH7MQ= zGCNF)Jwk@IB4x7j!8*xf?+8FPONw2HgFgP|rn#i_4i-%V- zV0#N3@@DF{pY_bbN%_Qfy9ne)8`%Q?bRWO<>ChCgYJa)7Z2~#?F=P^2dJ1u7a#zic zLU?N5%?{P-;xOd`$t&b2`{J}JcW=NBR?Cnr5|U8?@U;|{9{!x+_yyHQ!(s~L; zEaa0!ppV*mZP@Bp*}t0E{2jGnq-nna>GorpkIK!rBS1iHL5K=Es2iP>HdsR2UkwrQ zG6@F256#j19nG1p+Zr4(2Cwn-FaI)`6L*4+yRdA~u?@Zq?#`GQ5&b!^ z13A!Q+cHc#m4z9Q+8^Wpv0-$#=mj;y5NqL-*yCP0;ZfhvV&8s%OtH*ODcv2gKOCu< z4YLL;0FUNWk9vgi&UBm3{1Vog1A2Uo=G=dr1v(uBnJvZQklg*uRWFXx8*VA7?>sIX z=r^x9;+*6^T$m(`nB^Vs?3_8UU0+O{mDMkqVQzas)^S8Cwvu5|3Tx`WQ5VNQzBt|syi?lG=1<}NM!_w@3vG8eAx2dCDJZu*1w6q^nX7jE{O zcetq!>YGkZ%#Yeh&Ve0wVv{aW&^Of7_hjbxTA_U3r5;;;_)_lP(5Nci)_BmW|)ZtkmhMP=_*GWja*{;HGeUH0cCi^`*(-9shk zIg8r63Hh0e`3*J4X9UIFKio4yz%eE63Dk$;)Q)QZ7tS{g*LOxDYlis6)eaF+Fbh@{ zX8{|3$sKQ*`5_YvaitMwO&w=(^L=5{JH!of-T!?_f^ZuJXIJ3)Ks#XH9CYCRKMaKZ zCy5Av%mtnO$3Q%SF2g~P@qjDpj~kAU+e^P|iI02pj|Xc1d-s10gg)rB#Q%A-=f4>U zSgHSQ2BK7{M5)s1o^GK+tI_EkbaGF>RBbev$morh00o86l9n}eD5D)7$wZSIKyBC8 z=s}#XI%>+iRe``l(o@hSV-SYTLLqJe20_LQN5rPq)Wjkz8H|Z59{pUa)Ef`!^cV1p z1RDw#Cr3PlBtZ~9TV6&wD}c>b$^#vdA?wv$p&h(FZ6Yf|9(pb3k^!ewjO%E3IFLMu zr;YRKOaLi-7?k;d4d2e}5e~{|eYoQxw^Rg(zdp`xdmB#@5@F$$9eua+Xy_Uy78A`PSM!3YEQ zAqj#dCIcOinqiq-!Qz16hb;6%lK&p<{NO3$G?CIFao9_^pB6VZb)I)skL<*aqyUFU z|9@{FLh-z4@+0Y5ETrN9fPiE;#VZ=qXe}?=Vp2-*|AW1|3To@`7k{4wcemgaic{KB z+@ZL;7AeJ{KyeN3(&7%q-QC^Y-5m;);t)>yd-mS*TPO|Rb3mlt?x#N*$lx%2&c$Zz4)>!l?|*Xt?zxB zHHwA3XewkK5V11&OS<}gw{pxJ6_reydyuWd3`FM5A5k9Nwhs#s9#lrLScjDlOR)O| zgRf*L{~#}${{LqnUi}{pgy8*Ns*m8qKGJ_zg8%}7sHmtg2?6{!1_1yt|GR|vR|n!> z5&{6Q008X&T|#)v$^AQq_#1&BAo!PoctJ;p^%Jg1Nn!c{h900Wm;g&V@bZ2KNH-(N z4PkwJ5fl3_@c=6~+`v>(h#nx2>#(qw zf6)e5kKrHp@Eg`+fVqa&)|i-ysHm;~au3DDSO209|3VM{As&W?#>XfBLp=2M!Xgak z8ykPc!|E#R*?;1P|F8}(ySp&s0DJha62sNi3vBy;836q6;s4_kfJq3f|CJE`NC^6W zB!nXX8*(^+Mg3Pou>2z-d?xK-Jp$t2-$BoGiyNSTKbj#@8l6T;h^RO8UDRr7QUlZh zhOmn|G4Wt_Fcoxx8bpUWyA@1be6X#qNqZ12nvRvLJCa;&0mw}csDa;Kr1<~C4ES2d4J}i?Q&ZI99SmJsKK<@5KvIR zB!qy$*p9X`0hbxu?^)YuvJ^1OJ6W#70AmxRoXEn|-h%}|AcDDYFg%d5%{FJBJ(JHl2x0} zALX~EgXIMK_CfOHz{7M+`Q}4-oa(&E_s6Ha3ZHLK=m&J3?x}J}lstgsL9Nu8JMu`x ztUb?DTYSJM7gWej2rhiV>0E-04Po#sMdt>9eT_2TyVQ(Nw<(4 zV064ZG&W%=qM$v0Y%n(Bn;GRtHyIV<3G5ymG#Yq^^+n;6K%s{(gNsw|+1}XOh%QIG4vH~zA2G0IqW;(s zP$%DYBEtaP!CE^JtI<$tO{gfmn^2wU#@*rTc<%;a{!D|h|> z_YwjtnG@|W)a~-!mln09VUMQY@;~`W+0MmB9Dy}@z5M$ux4k1(BHy42gJeXU9erb8 zIo~VJK7n~R;Kyyd-s}EpHRCz&9WMhq%HOpTiWc-u2H(^uz_)=Va+IdD=Fxsmy*rBI z=KYWuC7m}`ZBY%A5HbDI`HJt46FuEo3NZglh+|eU?cuVFk>aj*Cl#|`+B`P-a$Sd$ z@;~k{3E^C7Redsr??Kl!FH>FhS3;z|9>A2ZRh>R9QEOrPDymoPyQ<*NMGNM%XNxPpXcH8Ga^aebr`(6 z7~yz&g(4}_8wryTZ&vBBD&+e4R4#uydj3m7=vH42#d*G>CXyNU{VO5T=;)*6M&D2W z&YUHi|KWWvV+tkCFxcJaE~p-7^xD_FfD|s3BcX z2ijhWvHwfPR^bk1m ztdL!|e|N|CsL$z=D79r%?V7@|e))}3dK>4xTL?dN%44E+@#C6vx8(YKCX&|z&dYVX z)%u@;gQtzDj0g7Mb!HQTwpF-u_vM9*v+4zplP}Ni29$zhdC`CN5jH%c)z;YuTn6{P zRC^|IY~1&qOZ`T9?-j(qF>cnWm-1Vk_lj`w-QV|h)9`kB?bi_O-b3Wi^VZkR z$p2@q->-asK4iZ)jlS=-{9qE|Lx`V$zyI%kKN}p6T%>?^44z_(rfi2`?nMZ#Q6P

    Pv%61cR`^+uzMpO z@`LUci+=7>j$eq)&7=ZenfpO42ZM9Bkcc)p8`ZI0LP8)6p|OqTx%oi!TmaNbERZ2E zt})=-BDRw&pvsbe-|%uN|Keb5G2wS;UAA#hSXtN;HKD zp~SH)1=kS8*%61yOhr=<#_@#4>JG)@F~&Cs$En}{VAqZnw+N3v{I0(gcQ_xEBpL6) zknp)Ej`Jwi(k)IgIiao4*ZC-3!7b6XDN%bV(Yh$n`#!M(Ie`r&(Qhy*k|f@fC*I*c z$;~Y$h9~KVc5Ye+65t?VbRb#sZ7fB03Yl3#W>GwLQ$jUKYOiTZ zN>B=+WP+7TvOse3Pm82nk`%wCRHLHgZ#>CyJZZAhNi{qvV@GKQB*}gEsoic#O4 zgu)y^VHO|4a-h;bB`tBO7>VG+eoiL;L>ji^WAc70gD+Byqbc)EEDS7jGR zredj-%ml)Mz7H#fJQPasmQAOWpe|>&hLyCZlat%J)mQH!^a3toq1 z9J-f}F%{BF6*Xv=q8}Dl=#=Rl7coDScMMn14ipcXRtRPn5sFkQyOiFil-4y@qN7z9 zKa`pjm(eg);qjGkHf5bPS3sGHI*UuXWvbdGE3U&TEsHBLS1O;ug(^%HY+z_v?dwW7 z=92#W3fp5CiKr$LDYg?Sp;I4ymB?C>sqcI|3K+Ayxh|t7SH? zAt)(#Ev{u4sUkfozeKGHeke1QsbiO^j+CjnJE{ejR8t(+#WU4^JgNU`mEkj7uB%&P z$82q~QuG?FR=cFm^09(tB*%rcM1`-;p{1Nyx4|sD-r1v3Q?|ipq)zUnL1d+@#j@Oj zujz;ES0yW-Kr{kGS)A-}mv_uy{*eZumD&a!T;4~*f|BO2mc|lUmvl4;drLzlX$$>S zv+ZSb+)6_#S}Rjmi_KO`S9o*LW6L;GEe=}!tW2%FRn;%;@`#m^IjB`z>~Q@RZ)5*( z+uBLvJZe+QO5^xr>oi|OC}~r2OYKfev9D}iW@^B?l}#SAjcIsWGg|pVNp2mQZ9{n7 zkVmW4NUK43)2>w~Qfp?yW7VEV%@tp@lx}@vN$a3)SJO%z{A&HAY{4aS$7X6Jz`6_M z*>%QO{45J0mkYuwwQ=Jsxh?4+X=(31X{uIJ^`c+k~52v(2R<28KwU>Rh3XQ*35;nS$pFm5xJh7!? zKfF^oEz5MY({i;>F|8kUwcqfm-$=Jt!n$rNwVe)q;F!4w%BVdyWokjSjYs_MHBe5M8IE zlX8*0q=ZeQgSipI%dKN5o+EkoV~MMS^<)Dp;GrLh;7$JF%F!`}r-8N8zTEHQ6{|gZ z{NuY3y&+E|ztg^N>y6i(OuVq*&b1OIJ&pfr?MG^BQT7ack)24jo+N(i8?zc$*Bt?1 zOc2So0a^QlVCLhrdkK9?P;cUfY|4>;iclXqMLITh-#P#$?>$=`@YZXh*Y9K;o5nAj zCKhNjYn`4-o#7T3AX%GX7nphVJo);m-GR4XU~pDGy;tjWl4f-Lt=B9Z%M|C?jO)p4 zmTpIu@+7j&TnhhOPs`-p{G=z#yw2*7n01d)DS?qNh*B72q|}FaFtp&za&N(rp6M&VcVOkOD7& zv1Q##7}F;#(_e5F($|(KH<7*zENkd3zbBnG5+F2S2bH9+yb)fg^jcu$Un$UEF}y^e zjaeyq27VJ*Z1akbFSB(on=#%(pn)2$rrUr%131mo=SRZlz)$ls%E+GppxLpd`Df9k z=V@#HSzFH;X=P-6Do}*{8j}*zjKjKk`Z|Bxx{f^lufNd zTZwQfzs8Kc`NwSIp>5_cd>thn-~}Xe}N!W&8!)7_)(37Y%_x2k=WSRBQfCAy(>r7k|{A(L)zxWe34iUchjDM#u-JL z6g$+Pwr;()c)Ruup+M+cY-BCo199s`{?aw6GCb!_kRc}M-R6O4@vbS`ioC)~5(d6g zB`CBV!T!%d6q~(}?N3uKQcD?m64bL`!t&fd6>D7U-Rys zivbGr93qIX0Vmbtlc^ag>E$FMpQicVBBlzgzq&wxlAgXpJu0SHjs1i-h`CSOd0KyR zO2Kssx;+va!z&h8_am=dw#{3OBI)y<;u2Y%FJImDKJLyqHaI)eEyD{0AodBY(!9m=Hb7ewG1u&?dtuh);SXJMXQwI7SJ;RPyP7)D+Avh8d@w~qz3KVsl+o^8z9 zfK0M3Z_(FYr$aB<+AqncHViR0UB>tN$D3rgj#6}wv?2~-2H{cr0v*nt zR`l-e^0gwyg|fh(k6&?2g!VpD;0u)RAlT09hSYqDy0*9dwP#ykMsYMfeoWZ4?@oE^ z`Q|!!;==9h;*HQ9Yvq9#^l;tlQXAT6oq2`kixeWbPF0Bz!FEq*aBlf^8KgLeOnsaN zlL^rCY|87fuS>d_14OTIdvA})HvS#V1i4La*}R{rvI zM)?dpe=d~A-fD+#cRVk@c_e&_KeqGx>c%=-YQ*#<};ZhZ9+1k@YO@an!PT z^63;`9^#Btiqx4A>2j$>0PuvOhwvja#cIW$#}ouoosE~Ol;_$5Qzy@K>+NTzX#=uE z$=JwGJ)xN#Y#cZC`^1U5^6RUw#sGnc z`GY8cKzy-jNr~Hb9M8M(ozH^wnH1FS)yG(*tzJ^mm}&HgPj|rGP^#O#N4)0=`YS`U z%Fb(C(#g&M_LE`#Jo*hxgVlfs0~#; zj6Jsj$#NgNChzF5e-L?e3SFwoJrKIbYHm8Ti?1%v<7>uLKSmr-d zBlwDH^Cx3q?hfjij(+(rxo*CHB#|*4^Zu8oeZqW$}t_* zwk>d*L*e_(QhV=}y`IqKzESo1@tHkRr!n;cayF5lO4_4TS(_DAO9N$V&c-hiylm-6 zL^CKovSgoDwj;SLzkLieW%-@A1`%{SRV;wsRkSIde&er^Af7s3;NtMS#G=ovnl~_b z=REhb!P))RtC~XXX=7RcJRvu8(~ZeH6mA0wjq~T*Zj-RvU`hin5pj(&Uht#GQP?k2 z@wnMzF}{!{Kv@>wpzlZX?Bn4*R6BK!(AfnLiLb-^&jiy?DoTrSi#^!(ch9L`1Tr2O z6uU~L0=&^&aY>Eg^zX#t;qBF_I3lU1+2K`q&R^x>k>h{m5*2;g!qTUOC+^^u_|X?* z^UDGbS1KMJj35(Uj7xnDV3*{buZjxT48dFYEwPYgC(YElPV%LYP{0@kV3#FEL(n9} z3!vf+^h73PR;2)>3L9VnRPKY$aiu+Xo{Xcd;B6hWWJv#`M9^J&1 zyhGw0?MkS}N1^?IGV(|2dsuXsAuSiQsYoFx8r3=NGn*obC}rMvwfx~pc06^tW1LNp zBk^aVcnb+sV`(h8&Smhsr7Dpdr3BOnEbK&{61Aw@AJN@LHQ;_(wFf&N;z?n=h5KUX z6q9(68ZPiadwezhn~(Qq82szXNfhgEp73QjIo_f4%s*6Phyuges%jyiO;tF`v4bl1 zEC6aJP=8f?Ge1qc@|{{10Kg!OAh#?Z@^BUmbnW@b1_27`i2$=WLL?g0RoS%B6*-87 zF-9+tgp_;%npunz;r+d0_*4Z1mvA5sQDET@lT16Z`6uH5f8Z`aNL09o`cMgyoDy4D z^x2pI+b)o6wyqr04Nf&58#8u*t65`~aco4RP?M0`x$JwG@;IUj3j8Az*{VzkuEV3&8gkm53>OmB^=mta01WQfKR2*P_4Xz||tU zri1`tlJO7Gq}G{aHn@&Ynvzi0MY!-+o)g9v!Z)nKvN~6jbd{30S@@26DF&)vo@+Or zFWV^=CP17Hj-kD2$Fe>3rVJl_BHRUmsl*BKmGCc^;48a#h{%v3snHk#nDFLSA{)bv z+F?_T1{}75Xrdudv>1-QlMj_)GfoH~wJxmM(r(o?w5{nBjZ7YmpWXYLDoGlKn7MQI z5|N&}!J<3~%%%kb1$zBVSofWupw-?D);}=cNTom?>^u&Kwkc^0QE5Mg8t^pjv&^`K z3#EZzd<4Q|UO0+Yb7e3QVaj?QjR~H-g0H07343zO(%>}8La_VMDq>gLVTs+jnECa+fVFQRU%-pii5U6GdGjo;??jmbGxv`hkgkegYL&v{!O zXPlL}2WUQR`+W{wlW%g3!Hl{HlH=czymw6_gIb1sYc<`xQ5`(jv=9Hfx{G>wm$jGs zJ3g9!{!N3_sJ8d(UEyv~G>TE?5&ubXDlm&_Gg7DsH)y|11( zT!WjIbwAxU@R8Hu`6R8530ibxweLa-5;n6yK8_hiqGQxG%&${c6NY-gR5Q8~V1M-6<6C z>)F<0`OVAQ!HKpDMUy90<&9S%W=X$O4gM^B?HHU~5WIc-^*p^ndbjoFWi}KRk@h!u zh(8yoEvq=X>M)SJQj9$)itzm7BJ_M5-GSiOzFX5VuG?|c(-BMB2`%BeBo#t>YI#s? zoB!56CfmuW-3cQ5f#yi~?7@4R+8Mkeuuj_L(j$QADg5%-QS~T*64!>PC$jI~S@KQ9 zmsw<^MTD%i4NOap70>}FZJvSaB9ap!ju1h!7J|-n9>aB)?{ub-3WLx^$kRkf_@Uhn z;iCBPov5@TY#btsGopllL~%yDQb|Qg$;9sYIw|o*>C!|$u=M2X_KfiLPEUy5+9 zcH!xXGBt_uKlK!rh|MJTV4(MY^5rW<6JzEOC2$nK+Uenn>)}T4=HL+HqU~m-?T};< zm4fdPM8~d=&3diZOuH*0O54}XEH1{;Cp9YmcC}X`?qf-(V4$`*ZLT=IUSD+KNAIRS zwo*~O(T~Z8eUA4ZQ6u^k)cTPfKXS-PXn9JQKMBe?_8W@#o12I$ino2H6|=^dkj3v5 z8T~0{f~ic_XY|BtS=*zJ-pAi6q~yIYDq;21Z3Ex;^m)LUcAye(KpMI{@WEaZ z&bm)Au2-gZ!1j*>%V?+n>_kc zAab(sy~CxBGPV9PnY~hh@FSVn(l*JmHTbeEd?Q$}%*B(eK&foZtiEt%Zp z?BGB^)ZpyE(4QzvkKy>$_-tC4^-=yM__r%h1k0uJ<+XAZ@cpysBV)a?)#Bq3X&+}f z#tv2nb3Nt#p5zwMr4Lxf4*BIR)W-Kq73NJ8rdSlO()#P-q_M#@nyDPP|kW{xR-~w({JN+{L9lg=y~{$c(Z6HJ+MyUaaQ3RhVpuwnUnzVN);dv zg_g8&IE)EfIKKP`21L4v$uvbIFC`uL);3(_iB^RiYh@yG`7G6`04WIiBxK=t`CfN9 z+1?aITRG9y6cvHW(()AbhiNL-=~wD1=Q7iDV`Z(SI4n|72)t6MZ_?CaIGV(YlG>Dt z&5?@Ly^5)LGc!grFkS%^sdUIcn)pf;{e$X7fD-1~v`23fXI~Zihtc;RReAJhTxZAf zN5@@e6@5OGZ(92H%B6?0=12l&*)$!DW>#t{W3aLd$WKPpYr>p zBudFAiLMx$^%7G)oeF};g+-m9a zdhrn{wbCk)t(PXsI)PKN>2otP9TM+TQwFK3-biS(gGL zrVMQifLCzE(DBvRwpP~)g@r5vweoG2 z&(Jj^S#`3WwbSKw68lv9<+S5JEcT?T1wGI2tuEscsOBN8aI4P<$d50UE*ZBi;na=Wu)zCfFx;)i+`Sn8a zmD)C~W6yQx6a7r`PuputtJeBc`YZc$qal4dM*;@N*Yl@dZH4Nq8+AIc2*fvez0~JV zD{BT&ef`}p2502@`+){_XP+WU^!v{Y5TFJVZR>wN8vOCpuZTBz#xPjdH@vhl{Ox6k z!e&?|u=cgYuwl#)z1+qX5AJU1#$F z0dp$Ey)WKo;ZbH^=gl?84RF~GgAsRyZOu~HOkH0e|E#yLUOyr$H~FD&nU8rKg18eo zZlSY(NMmbZ5M_Y|wcrgh_l~kG&Nw!~Jb9F}WV5wQ5U{HCwyZEU{n&mKFLA`qX65ng zNPWyK`Nlj#&_dtas))i0Rm1$+&0=`WvTWSSh2l6z^FgL@br`@Cg^DxwOyJUX9 ztADL~|0p@=xSn&b9q|O(5mn<3-Ko`BDR%(2cX|W&JNj6xFTQ zUk^U=ozH{jhXJI4tn_1L+oBf;6XmbJTp$s#Aq8KcoU@9?*r5(wtf*X|XR?ks;fW=I z5C;8V{RzALNGRv=-TL{R7Y}3JwAh6|N+CpVfQ*pl|u8|xnmmt;g&;S$!Y(N{dTUkL_mH`h;CiS~zV&%B(k*x#JL1YPlM zTt)x-CjMeA^l~*!aTxf?w!8mylwxE2^&bf?$27KYJDe7+3Rg4rHX8!g+4WcQK4<)i z-#%rWOk-ZJAUeKz<0RK$PyWVHP0?up>L}ywq;l?LP_d^Wc_8!EAu95Bg@BX5f}0mk1&qNTOqi*)Ok#JD+IBuGe=C73N=%F1~+lX_0V^B)Yb&aE&dv z{dRli_~y5*nM-uAMNFbwiN^i6SvQ$C_ZgZl!7kSU1a*ejg)&Hj9myf@!>{Xy@sv*%WqXjL`gRwMMe^uQx2cqazw(Zk0v<3oqppEd*MwJh z$D@h-)5?OEu9;K+!fgQ(w2;!%UBWBN#q$mHc}El4t@wOk;5hx_+4A)P^3{9k_9@oP z{wOgN=a%>~llb?Wm+xw$#p3toU@Vhnmz0xLJQCgr#bc)?W!BLr}B;lMpxXvh!BswU!IjHYYc%tBno^(`8n- zZ0oJ=x4+L$Zr^Nn`XS-5S>Lg5_l6O@w>`akyF2)UUbWo%{@wm)3fH$^r}ysbV$WaSn^?K$O0U=Tr4-cX?C4G{Q_Zl zZ!$C*llsdo5xu)>`T=$D(U<4=59((!&IpWX=DlE%(Yv`NVg1UcTlEugfpEC5n#GZ?;( z)~rS>Nc;Bt=yf)sx-Z}-GMR;$bq|3HS0AesX&Zz-~ zi6Y&^9gpXIWGzp>^R)mm)562!BIl$a3#C2kh4r+zqatW)rUZa2E$kt{u4f1$9q@fddi;=xvSHfVPGPx29c+(EL@9v zip;q{_h#+S4B%IJJo1ShzP9mt$JZpIoe7YPF5_-N~@ezXFpL7VlJU_k&0pJ)qfw+|rM1Cp| zUSTJ~yGmb7Pb&CV3|%NHm41Y+REX~jyI>=?{VATPkeTtY{||KuL_{Pcw7;?f4Gjn+ zK}DtfS7UT3c0BRZmav-+je2j6nbZFkf-~PiEp81LLoO zz{h_fCEY=%`Kv5gSpJok_ztlBYan0+2vt?6p5BXz$&0o1t-bw=qvMO07mV-#0N>Hj z{wfQ0KrsL?fsG9#7BE?{LJe340JdPh0tozjlK(vX3pL3t4b9)W#D@p!_c!QY=oc}cy|Cow58~|asNJjt} zV;Sp5l^-NMtcxWQYXaKoGLsMP?wHN#j-^1*!>k z5IAg5B$$roopH!hN$tv5CBxE5!E9siE`#54y7It1gxIo_lnws7G<57dP~9pxXCVNfB|8O zujdJ9va1R(3Vs71NgHzXQ2b`}1qozu`ppMKd1m5cN+D-EtHBuxi2VSa`UEF}r4%x+ zFk{c2{#zg71g(GO;W-*LJr9fa4R-!Oz5u<|CSSZX&DvzgQmS^$B@jXGYOXX8j~5Yx7;RA8gnos{!F= zwkb7$pMX7*ZF|`WkrsSqF%)A6G*OsTNaBT1BbGj*vuKW?vjw+B@ zZdX<#h^lhV5)NT%UbxmZ=MFwA=*P72)Sp%r>}w`7ioZ9qE-YG zUrY^$g@<-2X@H%`k6e~PL{kFDTU>Y_I39Taq@-a%LPZnsq$pu^R-iETE|$S?XB>R> zJE?pYw7EDE!fH2p+c5N0KxO_=YiKKpDK*?#RUXa45H1|Gu(a&Y_#8sJOicJrxE!c> z@9+BBo*m^AYsW?Ur>w@0W|;5}7uFN^5*9Mz_?VG>9OU>Y`BgjmIFfMF2aku952G#kqvHt1R9zL(@#vmf_CZ+LsB9%p2t=A40c|{&uCRVpEaCzkysLV^XG`Jn z=7nP4*<*oLTnLf01+sCmiZ?Tw@C;zHytZE?X}eoj^OkU-3A5Dj6MvTHGy`@lC#D<` zawpIP{?#x}0NS&5XY>OBn`Wei{kI2}SkY9vf$xO1cA~7QGRy^jCKI5;Qz)&P8R?G( zT=*==BB0!^pNkeOXK>mr>K}tZgGnZ>)p$&#g2N6lSazmroU>%R{5UOGj*A_%2#Kwp zq?2;+ZPIDft@$xhuny+53kjShAtIfkA3oP23Qmf=e)^i5lKIp$NB;mK6=&#>&)>T{$Ms^s*|G6J0} z)yVPGQv2pie4R=^u9?FA{+oCFey!!mO86-{V6FgoBkPGlXzbCqIM81wAD|C5ZGd0W z_r1}`6|niT(7Tk=bt6+)MqvB7Z)KyNQ@)lQ>`(x|swv{4KHFw%Khe9I>3b`^C{N%n z+qZt}+#t8RM&g|azo87gQ-v3_^BU;gNENx0LjHvx^uBKki;G(hKZ7JJ7=Bx}%TRP#J^TNZJ!a(?{O|?sV$uq5lkKE>)>06lU!PjX=czSE6N?ds&-3?Tc?B7B@TQrZpAC0%tbyo zCt~j&dS;>2Rc6w^)T=$#Cn#te-pE~$PCtHgfsPMQx|}>`Jc)2^+$#<|&Sst`Z0Gbo zT(vj47zMMFALE`5X8<$CYAo+4G^v=7h)`0rRfcv_n!#lc_lKoav>gi*( zPt2c!3&oIQX>w+AQ1+)7+R7o4uh{jgV$#+pF~by4PQsBLLzbo zY?MPB>Oq`WQhs1p9Lf+PMlCfB(TN}%0m z7DQl}5pmd0?$8B7Yl;gbhe-hTYwXgy;Bu+ZvLrkcS3(CR^;vvX`0wEri{XQX;qB(I zHzL3pA@p)%Lt;Z+-^x1~MGhxLjO2ss%$4A}0ED~11`eVBs7w4~Dy}|ro!&)V5J&&! zj{c(+ePGVIwwM2qP$e_vsHcq7EkR^369wCcF?v0sipi4vT*MgJugF^QDW`QHj!r%8bP= zgqY+9yR=8XFT%wiT72mclA&0(d%wKJK(EGdR<}4SqaW7XE&?PrQOE>Jp`kX&;qpcC zx=j(vNA9Xa1hmqw>LfVt7>RhA%#9cmzM$Zkkq}u(hsiC)^WEEq5nEa<+1QXUXWUtc zTf}`UigjxG>LTst77Fnov5zqi{6U=LaFi7778)TP850_($Cwm)7e9Is$K{%A*_5Ps zm+0vBeMu_?92&1Olq~3)6oQf>vy|jdlANy{H(ZeXzA#06FlB2$#fc#$Njf!0I;DUo zSz9|a>_W=BDvo!t(7N4mLzqoDSeeO zIh!P-h9s@?K6NTI#V|BgUMhX=K0Wg=HB&lc9VL_DGQqAZZ4V_KvXm~SnUqGKd2O0b zE}7{angJNj05WAzN@nE;XGy+IAT-L3Do86a&78Q;Ix5PjJIY86%}i&^qO;7XkWR)< z$)t7vnaudJVd-a6QKnTvcHvegOY={j;v6`pbXVydUGprY;;fOO?46+;w&kpVqnsd= z+;oOqRp0ajlvGOh%y+yw9!crvZh0S2^JJ6a+J>@Dma-{|bCKw?dnB?M5Avds^EajQ zOx<&(np13bGL3ceT~i9EEEDB)vJ`lKST^T7HD^KXc=H`}@-&X)*?H4_bgX^B-#Ee6 z5)YX{?uGW?Y%ktyYaP4P;Ua&XT$kp8P~HNq;zAwXpRaX_bHSOJ&Dq(ZyXb9g_nF%MiNg2NrLLF z(TYBol*%%fs2SCWTOq0IHlA44?IFV41p&KotpR(T+XYh>Nr{p)Oq*s&>x&gZ5Tu?-7x7z2ds<2R^XpDU zcY<%>HNB~wSF-Wfy49g0rAkw+OpmShi)|$Q_U$DeRMt4Yb~Q{bZIq>*n4|7fGNl9& zc)Q^>`zwAdo*m3p4K`iva4ZA{?9H!Td#EFdHdk_?BX|!d%}-W6Z}n`5BAU6$YL&7< z;^CcdG`oMvlzdI?%VNgw4zIys_R}g&&u{KCc`E1c>LNesGG^(`T*;^#E|iSG^D_jA zmvq~#_PXEq&hhmwgyTcsmsWo$h1ibv*;)7Nx|i@@wlk4-0JH|pO8d^hL;9gr$~^X?%i^m=)M$9xr$rQJoHhlK4S$lWHEJD-SsnWEG*mKLE24}jKGI)V zI#7nv8B5w1uZ!;#QA4*0`}sIh$UjmnH#9bk=et_v&*C#^T~cIS;C)&ue%ZtQ2wLJA zbI|LLWf_V0#FJjFN?sjnZB1>LYhfKNlQKfi@$6i18J;a2okt(8AH_2$t*)^4{_`|8 zCs%k^+Q{cSGLF{vax<}oHeNeAT3U+dYdF9hK5)oC@awdGD{XX#A8&#mG^IBcX5E6` zHoCn!`XPIaX#_g9l0PZIKYgn=0xv&awo*l3+1r0GhDJV_J-dTZ@` zM#zkSSw->&Q_`RIX)`h8c<(lcC0W#%Q;5KWSzVv3=2VJc%Ou8*&)m3`pcd=V6902 z8r3Q#RC<-L6b}+v<5#wN|1==01BP56QBbY*Nv-MmMsi%vaFfn1lh2HxQGqI3bW zUqzuWMgP*;xJ%!F7H&Lp*K*6kJ?Tfk5O2aOY@%szBA0I@fmv)XJ|bMBsg< zTE=W!JM+pf1a65XFAB)vm8@0KL69=Ms!!K)3c9v>&bI3H@fypjo4vN^e=Ypd2Qvw- zv0xT*DKET=Syi#w&eY$@wcpuE-yssfTPUkudfxdSxy2y36n(Z#(X|-0wxA-ntmwUb z&9X;szhua=<&m}^!QE}lx{rag%xyKNvA&{^(POecYub+O%RcjpeH)E`KHzLRoplE) z5{3I_y~@&R_nZFW>Fquj`2mXkD)-5bOVpvpP-mL*3NI#}w8D)4+F`(Wg2x!FP_fD? zvd7I_Ig|Q-v3FN*aX#FFrVDpcXmEFj;10nl+#M3!A-F?uch}$q4esvluEE`%qWOK_ zp1pfd_sqc@%u&}LP<8fRSG{Z9>p8;EU!Z8;@Rmmhk57_E9JtvWGmjq#3!-CX?-$7) z8=;uBMXeI%K ziRLLccF7=`mb{Oa&QFO^SJ#+MHc-(IEB^cU6pUJik_paIVQA%5_mb+s5ltd zI2$@gtFQcHd4ArzVIP}qZ&-Oo#d^?3aB3ra&WJjH?Q@E|fd-3wh@EkEOmGn@dnF); z&M92SYM;d*2VQvfId2pEiv@8`N8dzIbwSZ~Bq4B-QE^VQR&$10%VMxkVAsk1eoAa~ zA#PQHr!XfF(@muC7Z2@{a1?S#`_|6;R`K;_?;K4>c8oLY3Mh1>yg4ZCyGPUwDK>hl z9W$WjJA~W5*Y*Y^jj1KKyX5}^$7EROD%Ne|9*wzuL}_iKqrBedoNV1S_~mPLg>7bYy{wuz*1a7 ze2N8-UbfggKYhh}hTlAzuRtTrW&O5U0|Y`CGe4QyJxpca&up9^D2Y0=%#sKLYCgRv zd0eK0NsoMd(ID*ML+#=6BOyEXp1g$)6Fxm2f-gQPiH2^$NlrnMRYSp6zph>!`Ci;a zC|qDUyoA_8iwQ#u3qxRCLXZ1C-Z0!a$h`pkrMCWOQ-KEIh=T@%LNN=zOwARBkE2Et z@PR%;`z94nDVP1qjlTC$m-t%dgo_aemBwMS(I*{mI+4WU4u%e&Iv5dE$AMO~{|=8< zMEFzC8(!^rHczEuq}+pJTfRcC9lZO@VWeJTLKv^t9DJlrra0Cj_M%?d-Sp#3qMeV$ zTED~VVWncV(b_PKfPS=h{SEpm* zu!tc2H*3X}kd(oR$}A(dtGwbANxREujq9T$LAmoc7te>Llg$F=A8&6PFN8N$w4H%F z-%t2vq02vsJYX6R3jwr#TsFaN$A@>-7a2y0+_E#o^d^vH0@;DZ*NUy^aDQTH>D2k+ zTCnpy9h!jk_)29sQ4y@-WGn<{65C$Ls8S)8nKi6rT=eLL_`geR#HRv{nWQNv6O^0C ze+D=TR;2QeNss=4u98XUQazMmJzz_y`;v1KF5A!+7zx5&^a6*;@RIhOP9(ND{$S+B zO1Kdg5dZT-5$%S(j+Ev_wdRkoCrEW#lst$*E}O_(nL#3~giK!MbB}7RBEp~B**PG` z9SIAUcz%r%p`2QY^!M@Ks+szCbqsWtR# znCX1EUlcChs;@HrUC5znQ9K{Bs!80hu4UTYZ>4QF-F~tPnC`FBZAi|t(y`elOxCMf zOF~&w+|#3vYCRQL-1NGe58q6MpRiK(OG9tc_drytTo zCNG2uueG4!%-y28Pi}sL`q%yOVa$BR%5i48;ILIQJk@hG$5KYiYIT1{*eUDkKD|xD z0{G&{VKcaus#%sT!({YS|94bd_rgm>=L;2&iUjQF_=6wb|_pWUbdVj5D7CK)^ zx)^_~4>vTBdw>fP^65Mn)VG^+?R?D|@Vt1*dIy(7b&0iCl7yJ|+#-hNKwUHYBSykM zG}H?93o8b|?rvp0hltFw0{wfgNOZz4gLTvt704;JW!Py-fi5fobjEpd1T^({GfctT zyg851ZoMyi)dr$Y_)k8E@wm~0K}kH&7)5X&>lBwD7Ts^s>F{OLqDtX(1v@=0O;ik~ ztQ0!zFT=!S{UuqB(ZW1cei6$B z4Aev_eR0j)ATr&TV!cy}LpCZXzlX<_DpQP?=i5C*cOU)&c^!0)YfK@cHK;feov6)T z2!Ap={Bo6Nof!BR#(*b5bH*ZsSh^6=28_V1d##jGHC9j-j*xD+5TBaC5Krmq9&6kI zm!3`rR_(CAlXQV0GXd&rzDn;=cb?8*L3hjgcXI7Y&5+fLxbFt)8nLehh3I-h{@ zc);r)E7J4>?c-8;FXf7?=QTurdY*hgwtjeTlEcS^CoG>|zkhXUn_A<^1cta=q?5)| ziMmTmhC#9;tOnAcP_J}-kH7u}d3CUD$_{Tc^QBPt^)OI0d@7~rcP<8ApR~P141?P#w?VhB&^L_NOJ8 zd~GgW31wF`4Gz$l(b^&3{J=7(D0k{&Pl z@oFE~3s6tf-HXv!PV#Rf>H|VYM+$I-@v}xMT76lraspa81+B8|NenhwNkclOStgwY zM>l$Z1rY9X=_uiqeJVCNA&HMzelf>3BDm~w3wcrD)qAKqK4ZFG8WnqgGXi{&G#F?v z|Dy%#&Vd?cw0Pmr*Otnb_lO)QAi&_0DtAZtjxZD(30$D?eb>OzPqc-AILMFVfOx4; z-lLw)k0>Ol6w3fOaBdJ7)~SJnh{`rp6a-C(34jxk5+$m%_ha}t4)1bQ>H@s{7W--h zK|btj9#b5Iv0B2~EQt0J%m35n0QJB*d)Nl_h zYL6eHs~?gPjB|;&fTeQE%3Lulhm%sfrF!Gad{wY>xuhIi^~lOXbB0mc2QnVXa@aeoFC?>Y3kU;4h{~6Z0s;JwlN^#=<7O zLO^&>sW--zxA%hC7S^NXhKO+hCbYk)C%*i-mSgvWiA02+JcML@&?uR%8-3sy)o%jM2~? zYHcI4#C$Nf?tWZ)FD%e-2c_U~KOD?7F3G!@Q~PD`3YmA@hUgOO^ZFqJwuh(!*y&?F zaQuB?1G1dOfdu{SSoNKE2}WO#o&f+r>4J1mCi>CPNci{ZmY9&g+7F;>h(wYyJqP7> z8|0%I%*r4JcgX8^kgayXu;;0bvB?huNrvHv7=wc9S#-LA4J^ zfKi4A*n{<`A50k!_D)@UQ>vhTF~grK#5^@w5?z%M>&%S?KJV=a-gTr@ouA2h_L%bD zG+ZFoeXqZ7Y+XN|7;L$0JaaybXn&fos=EzQcsmj5eA&>*yl+&{TgW)eaTF48%QIEQmV6=PzB3GQ4HV zU62%At5#hq!$MDg1@h^HZdSWSTf5*3x)AsU(Lkw4eZo7d6^N&N;Gfl>#=5}YMQ%^J zmVby~-WK8pqP_oR#(?fddliHg>pl(H`@(~(MjYbbebTH z-Uddd+!egn5hkeu&qq&9K`;Owh%Co5u;=O9JX< z!R&>@EdA2F||5jUSx3v22ssO@kbRgvR9!G4#AO0t|5k} zhm5X#3RKZ0Q{@+xDHqd1?vtVz_|7gtecLYt*{|Q%Z|F6!LG#u4Prq!YgyovV^iF@3 z$N&t4#8s0-%7}!+sRSxW^3zzSiPM0+*r0Pkw+sKEZlI)R+hAveguQY9H|v3UaKdjp z{tSomXfG(lpL02WA8nbnKHssg?hJ+A1Vff{=;7s3LFMAXAn_3XJ|AR6kylJtXsH-u ziD*zCP5Gd5pwxk|)XDVMY#C`=iecBW!37;DuE?+4Ydx8nJYkrbNv~)D3{pm~q;XzD zX#~;*V*)vWgb`!FJSVhYk)-*jQgp~739n-Qufyr8l9i`2+G5gCw~|@qqQ60cCXv#P zP9w#-vZb>lMbIM#*0Lh*(giZ3RqUg*W25w5vRPrWR)He~<+857MmBCn@-k(`PGpIm zM`@(TK)4_WIuMFAXs~?D^_xs5Kd8HHj3sQ$A{~UY2AUv{<7^w2UK<6=tB#Zrw9b0< z&likM7|TW?%Vw?(|DhQDZ9N`YC%5L+yLQ{1tqW>!A7e%UB`32qWy&8X$~8vH`*=<0oXWQp$eroPUj>dYt;w4cO!$^f=;A6!HOpIL zj>bdFx3?*DyiSBgDk$;D6G+P=^D5ZrDs*{GVpuDr$tdhwPpIiOjv0?Zwo4&oDOR&j zo<@#CqJ=E;>pRNt%Ie=f_jjGX7USWNXM1E z8I(p?m9JlwS?U$B`xR%_l+*gA2~U;Jd6l5lW+-8l*D;inkX4?%RALJfdBjy{2}g0V zdf(PY*yoi6>lL=4Rh!CZQM_lVqGn5GRqA!;*u>?j+Y2Q7WrYZpM9XT{W1 zOa9Km-^~fk&(W-pue>TU-i~h?tA(deZ_JHrWT|Nj$Wo|HeQ8$(WzDG8D{G<1YhbBo zBMYVH|75(JSe#QkgI2@BQuAhmew0x^Vo;NcnxpSW;Acc2eqIU^ZXu4i<-pJp_EZWH+1TFveI4;8^

    6RTPu}On@2$Vyl+v@Tl>vg+mcZG%b9l7of=!edTEsQU7NPcnzjpywyK^^L)4F;7$|{HI zqWIijXO+#j^~wl+=6U_mUH#Q0r5+fArSa8EEQ3}oURlbO9S;3llgSGcm0n5%xS&nC z3cYdf4e;G&R*?Sbnd+0C0VLB_HOI<%`}8ZJ>Uxko1eF>Tc=~E@QzuFHEnR;gX$!&B zps;uKY<+7vaW#?y^I=`*u3`#Uv33skOcSmz z2p6w2Nw3*p7=UDlPYiJ-^rx!q%Qi5=ehv(Wh57tm-ZcE zqMd7)-OIc!9wuY*=mUTc8x%U%nt>S2Vu;zWB6m8}qVQP+gD3rCmA#O61X<~bB=0Ih_ z9c}90U>Z=l3jsF$vSHSTV)n`QP=UiFkjO~QWnVwoJdVf$N!|=u-^{S`KyktJyXip^ z=RpMQhEDK-Nb-J2hiRs5e*)@mVDwgagSlztk?y{UAk|UkhH;9zMHcL#zrJa9`#~Vc zA}IJM72DFc;V6E?B%jHWG}1EV)&lSRQ1Q$Vp5Ope(CnM(aSZg4rJ$vIrKM|!Wia@F z&&9Gy-^z2}LQK&750RA_}!^?;9c%YU35yR)rz8l!cAjp}5y^$6_Ql?n341^ukGB z^2QkWXdKmYbm8nq?(Fu>N)z|{9lkZey-hEZEp(Pmsh|z_-r0t}c~qrUak}yN62K zS|&TYWQ&C}I}UH#YOrlTk^OtN)d~2tINBUO#-0Og2}HEIB(mL^Fb8znf;a3wy=RT zced<>l(W)O*}PSebe88bcI8!%33BdBzQZj}NR+!1GH?z=zhhdeLw#ISXw_8BuQzeM zH?CbWOS#vKxVLC@QKt{I?7X+(sy97wQ6k?4(uTusK?YU>n7L347o7~u9xxyBqt2Fu zngA$Z76E-%E1i@}Lpvuf4T`VT0D8?(Hd9-%$se3T!+OU7u(>~lK8_B4eNY*=32=3~ z+bCrF?g!KL$RBa%Y4G4R=o<52NkDytq+u`MddREcaL@Ue7VTDNd-Pg#oJ4J(mgDYY zcBVh+q}_NGQ*0ksoQr#WZnyg6>Ts4wxwPqe|e35`!UgYK~*&zS}< zU#Oir?ma+*FKsE$jTau}pJzMaUbAyNI=Q?;?YssJJcc@6v^PD~4%}xJJP1e3QgS@O z(dxH?3NLvVk6key{nW2tFT5ZWyyxvMi50x+KYNW-y^2h}((QQ6ak)<({AjIv-o(E3 ze)q0s_NX!NW?=UDYv*0(>ph+0y|w7Nt#O=c=h-~zeIxO7XmEAxd%b1$G}QT2#O%Fq z2bNUunKJNc@CBa>f!%ez#wwqyGQ93IDW_^4&M~ZvVyx5M893 zE=PKK-pFj*;;xkYqorlC*Jd1b$I`k*7fyMM4)T+PbO_{Hjw~{YR3vrZ*w{}dt3z6% z*Q*9LRdgX5>>0k5Moi10X5XokFu3m7} zA5ammzPewExBsSQ)OYrbIaHY}CieaAo&LblnUj`t>zfTjv*q&{MM}*-`3`Q@Kb3=f z`6rM{Qz`HhBlouQXS`riO9DYvqwgeSR68m}*hSlRRH9;Jh71iQJ0YjtO`pTV#@$w< zzzEGli_xBUO^VS!=0kO3+p)B!Vt!B}EXG5kxbMm+(7{p0tD?>sYis@rDoj+5pEGgQ z*QYE>{+@J{9QjQf##GA8WzSUIexQ^p#nQBY-^2L0xj4mng$FA;CEN{B$FUzQT|8%0zu%jYN$CdeCN#C4Gi@#Y~T9#&p9jlh$d0X!NRve(S zDoU)BNrd{JOvSaOKMXRwC&Qm%x>knT@#hggn2CQ(#XJ*IMg6j6Yen6FrBucRU@pGIzc`zc6<}AbpsMZWw$omL3H9HkMu# zzE_sMCvc4j6sqwyC7})h0z4dwF$vrNo(hjczouAQ85GegsU(!P=5TkZi0xE2u{Mh$ zd{VFz@JC#*W-i+(Q_d^(XfS+WKdj=n=`KkA$;UxRauX7#I9V>aLIPyuz}qQbQ~p>i zX**B|oO~~iq?~%H06B?q)mz)d|PkcGFHC)DO9AcJUZD z^?RshkmR7U?tVGKR^a*ni>WaBc#{Cw@r73w z(lR8#l%t!coD~)Fs_Uo{5+E2b9UaWSt56L9bdZ9jqe20G#Aw_8Nbtrn_8>B{FSsB7 zzzvbIB7c!X0f(j49b;4GDCkrWvI>m00c^|Lco$T|!alLFKU681e(<0%kO==o*~-Rz zd6bkPBTEgMqhw2vCY7Y?Gym~%;W(dGj*zvMlsR&ny*6zeL4Ar8hdqz8w^U9T6EXvi z7MiEObi(;hZPvLLHUD4QN%xuB?E5xq!JE=a@9Wwe@GG@26y20RdR;E80F5X{*;Ei) zT^_18jTkxIbeMA8FYI<2i7#c-QI2)_L~k@wU+HGz;_C{i1ZZVc%4U-O)D<#$(}KR! z&8E%N6>+xH%Ks>v&AP5D7JQ>s{7E;Lhh9%wA|XJhoKQAb$W~t}?@gzgPd8txTwkW% zPN!a5HeUz*zblJ;paVnz;NJ=c0QfHgLk|GZ;^Y6X3g*MV7?6;7(|r(`|E6I6O<=4g zCI4><=HLG1KXl5!`XcZDmwagjh>fF*JqwBbr+<0Z)O>e!{h%rTW-lM+V+N4Vr8EAkO8At(O_ynF;j`1t(_fx(Fb_B{xB^c=B2eYDr%yvY$`Q%`-8>fB78MavDiqHCk~kEp zpouJ;qKx{lni@&yM_z;wFzv5FqWayJiwP4R3K>%qEhYeYSU8N(sJaUh7QoV#fC~^U zh$BEj06@V3?7Ms+A^v~g`U?KURjDxVPoBaUT@N@f+$N+o)Oyg+WViFs+%l+&x zuz2$@%8)>qX#I0|;TSlym26BZ(q>`_0zj;Yv_`DOj=u^p@dz>la>@eg0&N#I%`X(e z55Jfx_Ba(>ZhN$qYFGDM780<(l1K!JQaR)b_&#}(xvLsnAts1WMzpuXn&PDLY$uaiahEZiX}{9rECT+t|e zls;F$w_=7+IDl{-?+H;Gs_Di(H`S%6?uN(UxH$p=x_KzHc>Y z&VlW1nWUG-;#=?ytgv1AK|JZ!4$Z_3IM^>7=p3wA^7V^ zWi%9*UO6$ppdki+C1fE*P+4lhaEv0E;1dq|RqcQGb{_ntbS29Ao+u+MiUh27lSx9r z9a~c4?;+}ihZRZ#q;R$);U(CqDpMB*qz?Jrh%6()kP3*@jMHqfJ0lL+?*vUyD^7Ufn3;7AeL170Gr*se*L$Jyh2@mOdy3CzAt2nkk^{Q34`QX-<+T)ky`IcR87|8(mzE0L)b4dwnu}Xq zE0f@Yh0p&!x{fpM*u&zQ9GvdOCjaDnM&r(>uS^g77giHpcn{%u+(E#uz+ zbt|-| z&t0*>!YLvOf{DrHC&1yQEkB4zsZie~zfjIwv4ASbNO0u`r_C=XY13reROT+0qB5t^=ZQ9 zA16cB*LM5F%VSDF#L1c>3qx|Wf5!eF1v8Ez(>XB9 zHGQiiwvMfwl0M4^;cTUd!gnG4*cEjuaQYZfqKTgC(~6?fmumZMV8!DN5KsC?PNeaNrAb~G2_4dqhPo}V%fOKA<%oW{_e{ED45Q^y_D`JN%LsT zZ2W%|OtY+$KJG79=tFUlXT`)0r@Y3#!vz0liBu-cGN}Gz4Od>-0wUZ>Gw2f`h?m+s zviq9im1TZf&z0fIJAFyKvoPBitvMps23Ndu-aOBZvvad%IQ)yGdrz&~4_CN|cgaoa zwS&TJKEU-dWjYwKW5eb?f&`|}_XX`UD?h38`Any94e#TBc@B5VrYcU6K2{@sj!*Pq zt;!iXj(B@AZ_K8sQ2?Ejvw5c8Zcui@fzPU<9u+^m({~F!Tz&oX(#!r%I&3C=tH$Pi z%uGx%$qc&32P?n%E`p~wH(jq7iNSIyo3CaeuPc)m$>;ffZ%Dqa&nFuX&#MO4*D2%o zxRAaHw>cE=aDIyqXfM<_FeN|;ZpYI_AE-k#ICz{-p+E#0bPRa(kFp5L5*pg!XMA(u z=cXS>ZkD9nPJa*F$+@klLj#VAed8A09#aBrU0rV)U0JwYaW(CpxGWf(tT@bn3WTB) z4t*AZ7voB`6XJH`fye&}FD{N_FLxNoHWYB;>dWsIIEo#_%N@kr6r_6?5W@8{NHQqb zENC`4FsI??_oW~;nqaP)K=l4p(6~A`zJn;fL ztOE$5IRFh6u>UZ~$~C>0~z4cko-1`6Wi#1_y`^yeS= z&wJ3($&W!L)37K2dFXBc?JmT~t*9!>;z*Wb2yx@_d7{m);FP8SkS4%&oM@(}_$wN4be9_h zuCPd7NknaEq^?l}HiQe67Pg-u1bHHm5jTNFI(*K}zQ~BlPLbFx77k7+Q3@eOMLKCm z15Y`ZN)snE9yEm=r$!We<7TZI@xt8$!0lPUn{u;J~*N{ zfx9Hd(;_NfD%p@H#fdi6;wi<-BE>u`HSEbv*)7$7*v~5sOE4|G{BxQjcWUfW%J-vG zGp&@Ew6vh+w9}#F+|tyKScn5cYL;|r(NUU>R9c-`ntFFa(LplsD#4L7DZ(PTO)IG? zEM^a8E)$kOEe<@B-U^z!A*;HS)-C(DLr`Vla=orNS)luM6|igPPa))J;O5e=6ynAe3bhn|_4vhVo>^^P z$Q53wU6yP9Y^5rLC$*A8B2px1S)@>wXSR}S6`lz^Mzb3!1TVT5TBb+%wPd*Rek4PR zf{%+spL4^X(cF&n?Je_ZWU_wY76pZ)MYa@+X@~y6v$IYwCF?FAwJ(icDGDjWb3QH% z&@L)lDJ}9yF-%W!kU=Zq{S7rz7JFP)m|jF#^E+_mcRgKBBVJ}RFIwM9NgZ7|t#($X zWjXeAd2UO&)KH!;UFo@d8EE7;G2(9wxQq_T&;{)ud5B>ZBUxc96{HT80)xei&%aMc zDx?w7FFi1o5z$@{z4Phts#@|lp7XcxN*B4`fYFB_pC=SCbG@2?;amyV&(8(?< z`td3ut$ri?E=STq`}~rRieGh)|U zo{gXpI0LK3^YC&)*=%B2G`E+!u+e%6ohoOYCO`T=Kk1v3`6_Qp!^9Bl0z4ZGTWf;p zE39A2u~;Gfb(#e;T8OzCdL#>qWSg^Po66`L(td}Fy#O;KT6{g5f9td+xwoQTwFs^> z+sn4ljW%l2*XO>V_25JHWi$?)G->G+j$|~DgQwdjN1Hr6+bm@pXTuwC{M%db8%BR8 zcHn1ptpX|RTWUsIcVz<(bSf)H3p`mm_V`-423tnBI)&2PxljJs@w7X&e7v4TAJ^$T zi|AZ<$ruiATIEAKdC7;@ZPOTS|FN34`O^HM*admJr*yh!BHHFo8ZRQy2nZmF%G;-P zy2$vu=1+c8IP}oIb{?%pK!VDcy~>G6d+%GjwpyK^>AeGodJ)=M5nr7|`0c)eIt7q> z=@~qvt-ZxOdVWmx@t$@(;ddI#7EpHeiR<=gL^h*sOyZsS$_MUcAUY?X?!ya$pPt zT%mP$LZoLYfv;`(U?V|K0CIm#TW4)1u>N(FfncnJe@qlqK-E>yur?x}IodZkCUZJw z7de*gHPT`|uBEnAH}3U1VgwotksTO$1@4^Y?|KdGpAP1=Hu#T?qfSqdUQWbE z4mG_F-kx^duK^#+Co|h7j9Ak))&{n`fKV0ViEG27x`Pc!)2Cwv4qH>s@Li3~qhQHU z0p1B5?)1LrBmBqnbmQ}y$ep}V9U9|6)vN{6@kwFL8Az!DLB?N>>yuZfb1oHrV&RbHHnUdV zb2q2$k)TC%(j}p?#X!apOU8jC>p{DAp!?hWFwO!B>w>k?g4Y{b_oBwmY=P_5KgJT4YOu+gDTJ(qn7!2X5hP*t+toD_|d!D z7l-A>HM8*S45RzO-ou~d&_~~vxETj|^zf)>WOdVeoc&{iC%Uo8HL=S;w8hdf z4lVe%_-c3UaD&VnT{3&O>TOjSb@#n|f~^v0AiwFYwG92Zh$$6np}#lpy^ngh&kT0} zdWNxNN(1-V{4HspEgJ_i#vXXu2G&=gQAJ}95&k7ZI}nKe`@LiR<8G@)CGaOW--GGk zVtn5@d#VgnkaC`%20n~KJ*wtk)$#hsiXM})9Lt>l75CZ5JzXudK`TE$Hqt+NU*Aoz z-A~E}HtHXy3?Jc{AK<_r2UZ^GRUYHS9h%h~suQ7iSDuQDpZb}fl7yZLt-$mMW_Szk zmN1R>`2fo&&gS&DI`vPpCq@^T;F-D#_T`U*8TX692eyQVNLS~n8)wMj7d9Q|gmMMX z=lNIQ<09LYyN#2?vkL^)OH#$lX8jEzrX!P%OQ&cc>ZhybtaGc0RZ0B4n{zbW$qR8y z@FvpssVT(S4<>YS-*dzD^RUn}kH-*S5(xN@Q3C)%Tlo5y!{j09zMS;5(EH@Jg2GI= zsu!`V+t-IPMca!yLNKz(D`5L;?k7?oXhN}6#ck1G6hgs38YzW;l|}keS^tVf5q>C` zu(ZWtZ*mWfce|yKCvJhxfp=x1TqGC8 zADU9BCW3gW_<4r#chw()E6NdjB`@J~GDb2%FB&+b2HW zy2*KcwTIh}9ju|HN;4?b3}dUfxyG!H`!_VVgROp%g>x%ihb3XL2DWWJ-R9+^#2d1z zY(1dM+KQbF^YUP&e49hJr>h&0z}Gv5=BiKN4hzpm_#@wf+Icv_n>+CryQ7Z8T_}4F z$OLp?2Q(kscX|><9V?MrireU(zldTNU3)B%N9B|*NED)|d;~QVNJ2B!Vm->3$9>1T zZ6%=<$v~z4SVL9R!AQ+IRwg3mR9yuLkJV%Sr42&9@9%hh}Qj)QoQKbYSz1)%rMb4EX3v=1f%x!py zan#65TRW4g!Ib_DshESeTIl^|a>1+r?tw+A_wrX(F3Yc}x4{4dFPTy8r(OevxwK`2 zL`V9PCH&8lGR|T1vzxos`l5Cv-7rMHZ}b%L7>%opS{x4yjv|hY<)&}IZ}e zO|tPAvKqzY5(C`YQ405Td(p1~95v+)jsdipKfrogGU-<5nx+%SD|9H(Kf%uXdHH{E z$5W|Q@^?^V2Rzn_m6$x1bB0-LbWVzFdDkjVPFqgroo2&|vD5bFk7^UbpU2C&R<(*N z2Rd|Ycn%~omO2=}YE!d6a;BgDIfnK6XtHHj)KrkPBA;vS+49p2`~~SY%sBB@IQBDh z@%rudP3||J4fU#QAyMXLhM7g!V!bnECg6_rf2=qUiHZs4g z$5Ppw3Sg!%`Xqhbs|v%)Uf+_0CLY>FL8lZv;rPv*p9Tn2rjIb&$-`pp>C-24;3UBx z0hEysYO(enwuZ|9Q!X zA4(~8i{i*-Ec!BDt0OUL z7j{P4ykRCIBELwY9D&IK8_qgcrSN`)r${FFhU6~+BBxnGLPMBXHm7AV-?n?DGb~&x zWI;` zm?MwQF}SIG<^~qMooXL5N5tlsFKlGui*r@M=1HNNTEWcso!jC=cUq)Tw}r3YIDVU| zl|@+}LJVP5k!WyKckAi8Q|f*6e7fs%H# z>O9I=@Gw;tTBxj?+5q!jd@(-lnGOg*nZFhLcAYq}Q(UI2oQ1wcu>UX_G_XMc-iG#t zY3Y|_khgZel+nWKGOgk#TVY$r&r+Igu$Gl49yYosi_^{GB7iuUF2|e}Rc@3T)oHZ~ zr?7n?DC;d0|MlN4HABnC!mLJD#&-Vv^p#L;d0t~tjD?y=qTA2qh3v~_F5FxGFSd;? z8KU{Zfxu8O6JrNGg1z%4iyw^U7Ubs+KaV{eeX;2oI7#!%`97T_c!fa-IGk!YRgj^G zLoNi4d9N4>|2kOC{Q(w(1OPyd^~d?~m_cx}30RtnL$L>ZQZ*O03E};Y`Rmw_oumud zaqB0mR5w8Nl2tX0t`iEGhulpQAj#sl7sHkoSAhrxQ531f*R~B1*gubnD;B0@@I$mV z?8UkSp>Z<6ATsD*dxRn7A}<-z$H$Ap?t=a@CS24kw%fXpE5jg@h#?X*(fW8|?xf=Y zJ~@L#LoW^e3~1f^bZ=-1(b$4eSOOvF&i$|+d9Ab;|E*x01x{|xR~A2N%+*033TE{g z#gp+L1!HY`q7CpE`l+5Md}7A6y0SRnQtg>#W9z!Q+6LxqlqJYSrg>^WqHX+Ixn(8{ zHlt%MnsChJXN2dQGNQ=Wzb)EgWR?tRs4Enx_n~N_^W=)tRebu>nDGUmp*@dsq8%zi}RCqaY%Ej3o=~i7J0)Obn)5UB+l zKjG#$57NV*SWxFcIgLRu6YqWkn0s<)_&V2phrbq%Kbz%M^b7(TJfw%v%yCUVU4^%g z1*i*3dNOZrdDdO{KeXNEPbNAv9zSP2@ICf!dL671JdX{!-&<(A=J|9EA1b^r9_ad% z-MGAnX9@b%WlKHe;DSvwI*W5VpKDVV^E(!FV&4AdgCm4ak%TM131xf}1`r6nzX z2nVKi?Ij3Z{SdYv5v~vwJoD`884r zAgzfI?RMbIiJ+f$J=}C#$aIq!cau4ZPzH9BuL*2^?LuG`MnM#z&;|F9)(PYF5s`TH zKzWH^yozp?_At$L(v-*2I`L8KcGH)4!M=7?j|$TVcCnO;@CKqV>Gtv%i?XbJWsUsG zmdN*IE_xG#a09oOfA=ec)7MXR*cih*${-xXjw(7v=pQKH5GiTJFld!HNM$_aDm3%9j1?r6&!}TMOO3#ee!OYj)70(-si%Cp2D3@{^ z6N_k*QoWJRbr|0AliE=lq5L)y*EisvIGl#bfAD3*<5cD&GAp(`lFC17J2oVX*?)~M z+w^rLWNc(CL+0j9&k{KIW?vVEX_&)tE1)v=#zqY;OK zs$rvkuOnH|BWbB)a;0OrV`K4Npo+lZ;K(s5+_7F{S#Zq>XsT_D4S7sYMs@~SuFFeq zR%|%K8uZ6n*7$WSc?l$=C0A`dE?h2Wj3*bJDK~d2H@4gO_jPz1dU*FEBGM*%95<22 zKc3zu*EuHF+$Mj@AYWWI0Y^8!+$8e_VUi_GZdX@+=c6)mI-0}=I(wZc08Pp|%9nXf zE^sRx4Nn9W3>4`~mUzh&2d3Y7P1HM$Jr|6gB~G5#fnfBe?gRS)dn4dR_rdFaEu5GS(R6+$RNGK&_y7=2Pj>k_rmKLqM8GVyp^?tQH$Uuk}b>k>ylf79J zEa8m!09Z{w7jj{?b~WvG4KJGo4e$&UzhaFOmZD40j5C&IXlK=W_fSfw|XjyKBhWhw2^7x{C|Mbs7jT`)x z{Q8yOl$t*))IBLRylu3L*B5`asy<|@t1zynKrj5#RDBp;kXTk-id4~SSFg>|X?dGh zW1OzV8WWpeknt|8ksE6XQg7dzYoeTNNK)-^*6Adq?CPJXywi4_mukD4E2h-x5l|Xf zZ!s%W?UP%R($i+zTWh~t1NUjJ0#}r42-n9L^%UJ#1xMz4`*j~xbw^2L=pA+Wf^wnvIN4@nA@A@~zXBPCZra0DfY}V!}mAlV$ zPm)ANl5~#d*Vn~2lsNRAvy^Y5^zXAa>I(TzqawG}Hg>S|4p4Nj88@p;B(9S5E==?; zqfpP*bzi-8!B}d5V4cS(ei$l!h<$zXJA*Cft>+*^D1Dh@n7Q5gxxI1y@x4y?hAl)Q zBXo5I6baR*_6;O;1EH*~Q4fECB^l0}=So+&I@=I8S+jsLu z8uJFz#)exrTTeFNZ`2K&`!+_V{o4eUJA7hBQd!&l?ccaiB+1m5m^QY_O=nx{x7#?3 zaItqfqIQS|3{~ZJGNBDpP!iYvM{D=~&xGQ~aeTRqQ=uD9-!f7bigH`3MH0FhspAqh z?C!GV(&jo;wo)j?(s4^HI$6RNCm|J5OzF%~xs6T3HjK?>=IH!zzTcm|-(SA}!RNR4 z6?yXl_A^*P|S=kHp~EMBl0|q?*&4^ywNrW{B5gOS@23+Q2veR zodLXKH~Htd$bkYrvJ!1>iE@U7cr*C>Ed>FfUWE9h3v3t;8uX!}XI~DQ5d>%qre<`Q zQH?xUh&ok>bf6AjR0iM+F(^F@8iEPo3Y?k4-eB}mOJt~WBuEJx4DJ$;NLUJ`H!!o^ zj@|F6hYrgPNfKbp?U9Ly5hD|FxrcMGez~{- z+p%Z}?m(;Hx+VUOc$A`sdy*J(nmKv~#7ifksa?oxnYc;=ye$R)LLDFOjwiB(t`0&S zV924?J4B|SSTD2yekQ+gjNFQjb-<*WYk>Y0 zT|@U=Irrg07G^?u>HA9BxJ37RY9lHD8X5@;?JdAF7@Hq8Vyi8~-pB&$WSl%@SR*_% z3O?EZ4$M;GF6o6aTSGGj!nW@5&)Llzi#88bpo z37v%z=k?Alf(Z(N(_(&-h!e=-n5zRa5cX8xC>gYP`=k-sC8#N>|l&A*E^rpt>Z(Hue4E?SgL);Cl7Oa?oO{dQ)JPINO!`hgL7c#r^YlE&sn?;E_R zIz}*WB3N_8E{4QIPo?HMQR*u*h7RJ5Z9J%3zp-0nm0rvy{VC0+7@#D&olCTDxsn$R zpw{$R(4#y_tmtb5au-^2^+wi!AM8Uq57D;9+)@8=2tW7lS2-_{&K&Ib!Jw zS(zn|=dhxm%P;sxuK!8R6bIOY(_A+{*U~M+xbeK&ILOO>dAe%Qx|H?pN5XVOp4gZx zj?s2w5B+JEH#099CX=ww=a0zB_ux_vG+((RsY^u=EwEDG6)gF&&FakL75QC95U%P= z&ozm($+J2hG5T!_`4Yjhcs_k>I?FNkgM%m+OFAZx2;cpo&|@Y-LtLa0U)DQ)^wDAg zBlaPA#<^&|vMutN;gajB5pr8R>5;&CI(PQK^cn0TI9W<3C+xt+)#}7uI1p1&BxQ|} z3N%Pxa*yUTNs8ss&GI=lY)D;ieACL(1H;7N-mo`_I9>YW-baZ$IfwGZzULUCmGrO$?>LdPXHa(ot9@lhtWBPtr&mYG;lm&ZE}N7T7H zv8ye^=Fm47IL@l7a2af*&P0S)3WGFHnX z9>#(3RpmY9>&m>6G+E}}PChkW{mRF+X1!Iuue|5Xy({`^oO>SYcCafs&mG^jRKB>w zJYP?W6L)^?l^`C)OMsT!Hxoa;upg;vzP$}D&W$@cQeWml z1Jzg0{n3@|)zp7PMxN?3+hgb$pAaAgy?%-rgeP^*OznF(C>)qg>Ry=Rj9q)_h?*1D zBCu+3%up(TDl59&c|C0iwE+SizN!T~{=iw~!p}L>1HrgIX{l+ZJgTmhFAr`olUCxq zQ^x1r*vpPBxfxM$V)IR90^hec6Uw#ENp$=&Uwn(Do7Zz&eNMACyV4|%n_*>F!M%Ij z;h<-Zca$zarve{`&J9R2!_ZaS-=Xu&9|%9)^JDpW-zT*VET6~=J>vZn}uiB<>JHX?XHVqUbU3t;o04K zW}@1L){ZAIZQKis=l$_N6ioWpN_D;c`~R(AEL8Ox{#G#W2@Uce3PxJ^^@oD_AW}A| z%5PZwhl1I78fx`c*FVv!b?a(bq|G2fVb#9l2GshU$*+ml9cI5ZSiiS;p|Jj7g}mAZ z)Ux02LMNV&ECp@1O>x?GP@>q?2|2wZxgqhx@!;5zNF9szp=8xBv${UkaFp)Pvz@7e+r8K7`Dmbuiz*XbUw^AW?mjUk6aaLJss%l}0egO@k*c4bYHSc-&6`h~)Kvi0 zk;*!>9M?a;G$pK^{y%yE#}{^s!Hxx*Fi{Uk%+dMgRZ+ diff --git a/results/animations/car_parking.gif b/results/animations/car_parking.gif deleted file mode 100644 index f4053de9afc9a2a0de0de58929266cdf8ccc22e3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2653276 zcmd>kY-9#l;2S0RW@`A|fIxDk=aMfPsO5lao_W zP*7Z49H0OI=l}qL038E>oSdAxy1IdZfti_^wY9aYtE-QX&!)W@JA3gwr0odW#Brzn^@zm^T?93_5JefR_`I2l=Z1TA>%EiiNb!Pfi`Yx?5zFodj zfbT|tGHF0B64EUe;1&RQ#m0UGga1-f-w+YKQc}LMP~9>yowKo>2?!j$eY?-V@XE>g z3W3}TbKVLF{O9mhnD16z^j1}M>)pF$J-wfj zi%UsK$;-=2P3_6f?##<;FDomnsi~8$C@E>Ft!->*Xz1zbd9AH|?(ROR?2aFa z5A6@ln#xKWODmf$D_tmUT5alF>+Jv05gIxa71a-izsAJ;$J?av+q9V5l$6)(?AOf9 z+v4Kani@ny>1|KrZA;5*PYQC(xF(?sx1}s#mXt{W)m%yKgyxSs=2DIRZG=I%}$#W zt<@{_7K72$YHc+?n;m{snN7CUuD5&aP2{Sz*KKzD-JEVtw%7mq9*lxbqu$Z5GZ;z4 zVLsK-xHp=}pq8iJ*>o_O$?v>1)!BSBTOb!hqtVrJ@}okx+I+gJ_4i7H^<`-|;CL=3G~ zZ_ne+@sH~Fv%TM*?=SZz^R>SB{(FA7`TcA5`}hCS2#s|+7)au<9fHAJu?@o!I^GTi zDYEXs!3GXHVPtj{JK_aMs;O#&n0>DAuxy-Du9XH^BHKZ#o`K^*nvq@QLAt5$$w7uiINM>S zO}gXZSBJ97!z`D!lf!I}5w@co?`6lMT))H0qr9NIlcW6fPe=gNV3IBZ26TvYMPaOg z%>O#9rp@6wQ$3M^RN?7R%0FSz6@eR9;=C>Qs%WEt;sRsjE_T zu4!0%I<4)>>-t^aGJ{pq&`Y9r*4RoNJ5<}SLXW|ptprFBA;@~mb0LpOWd zye#&4$2#9{uKKlPHP^1Q^y<3SKLgmc9aUEJYvdROMXF_J#(=)>0CdjFJ|L;fWj_W> z&E)`&@Y&@cNQv`m2yEzbHB4q-b2UQs@$71pa{ZZ{8OTGQh@6EtOp6@3@H5+46y3~9qjR-Pi9d_q&MUJ_do8F7*LuxsDslNtscE_T{E&EG`*$Ad z{-<>&9#DYk-~!4?WV3n`hDGVrTzH}5HaNYwR>|6Wx8cH3iirS}1>31I1Pdnz1LJaX zg*Mz-(%N;(hjJI!qBuTd?W&8$FK&HGx$7$lPr$w3R}rLn)UGtreA-PY{v4p|68u^8 zS7~7lXf3bY{G(23!spZz#VGU6bNNR%;R^*z8p=PehBE=zYJ!NjH!9@#l-H@{=VCeo z9C+f|o%pj)f9mZK6n`t*zx{(I2G+k^9^o%_Z8d0p>ChP>Efv%GOOz({^o+gq1saF) zOS?q4_mQqNu<)4{s@e_)GDCwEEw`VFNWZU~)%vb>zt^T>6&-P$W4$Q;^*26Q5-WOE zaR2Q#`rnB5J1&o~7k=8?fsf)SG)#evIE6Yh+XMOAJP`f;!K_1D?Q_@f*%dFlQnBIJz~_qV1oF_KvCzkt`O&|%Kb$qUDW;2?Ph8n31{ITG7gMNunA%7e1RX-QI= z8lyH3o5G9Z!e_N4MrYv9Zcb#>ecPI|1ugCPUzJBK4G42j5O8~q-YBAvckukJ#Uu5yuUSq-35n`1 zOwx|Y8UoQbEIGG(RF$l9PrSqaG&a(2bE8q(5!-F zRyv7k<$o*lc><|1G~i=(x2}n_^O91&s7gn>F3rHLo396xwrp}LnkHGg>2p*2LakrL zawp(vx||l&f9&-$dlo;_ZjKukW-ZRnrxYm<({4FEY1uE-SMy+Q8@H~tH8g?i-XyVb zM~oUYmTA{|2^Q;lqAz|0FIRujVA^;(HSB4VuPCKsm&eB@%I8~X67F|G*vsz|O zWSZtp3z#`#nrr0Rsf5BSp^J5lEyYQQGp&KI(19)krT_)UcSvuwyA+p-rk`sxSWSMe zSHU~D$(^AV927s-^g0AYD+QA}-=4x6np<4h1@l#P_KM_N&u_R@6W0k3(878+EnN*z zyG`CMx3>1%p4m2btKU|^I}1I}rG}l8BiS{3Mfxj@PtYwq_=pn^HmVTE&O|rJ3SF}E zXX08W^M5sU`m0O1Jcubw5qB%SY)KwID9-BVXhdE7Aq~&5I+&LSB&j7_uI@jd4IY+- zSfe6Ca4?W}Q$-$fLt8yyqLkK6SYi0Qks%WSIfUTJ{n0<-9ukjF>lFB?1S*HTw6#;V zeDtf8WRjj?`bMd0jQ(Jhc@KoX=tdiIs6jWX;FZ6GDIp7GdOwc}9}{r*{nmswoRQ`_ zE=BaPfKe2LOmKy^gfk>dia$f2#t#KKnUvuqv8s%~r1hrM#8>tg%$N@|+9?l77rrw3 zrmIxxC+|Zp{g=`Noh~i@87WWdEl3hH(7iQHWxOzgs7qp|`VX9ts*=~jeY}~pHj@}R zjEUa}UBi(i_ONdP1`E-mahq^l>=NM1T$pVt`|n(3GKgc@xT1+VaJPuMJDLATUNmw= zI&%h4GG5&|XeYk7n7taunUL^hM#Z|ik(7c|>avUMT{lnA0=D(q@=7mi3Dg*k!Bwnx zTGy@@ZzXdUac6mk5i-bbDY5k9QNh0BhJ=5J0t51I${O#YH#TvZjX|42f4-zifM1?! zx1OgR#{!f0Irf9*6y_gX-qYxr;1eHz{`;VZOO0aKzVYQGzN1gZ+*azMYemdJ^hf^G zF#!X0nPvj#;+H443})Z@%tPOw#NBpT30{ky+<$G9wvsG~Og11t+mipeEu=-PUP_|9 zCLWL{LrF22qa8XYIDM3E#1Vd~cu{&8D*Txrj{zc+X~ zliCqxdg^&Q<-UJR4fdBvyV9*f6af8Vfis@ebrlR0Y zr3V%b25c_f(ZpEF>r#R&^P|CITym!dO;AxI|#&MEOjzC_j8Y^rNdy*U6lo(8VR;-5$8e2_jEH9qO(_m{^@}Jz4)b7*Of`x~ zeh8}og?=In)$V{*Wky$Ygq8b6sb)rbvxZmA@%2QIS8QX%LXm(CpHOz*AX%d=8Gf>F zh@E+eog<5zTa8^Xid#^Qn~jWH?ugsyh+R95+jxlE$V8jWM00M4JrarA?1E*IV9rzOq^9t#QPb4 zDw6bb4DIzkCi@CNWD$~=972vB!AX`}%NoX^97<0f3UN$kCl6I8gUcN!zo|sPK8Ykp zjM=j~!Z}ouS;F z*2|EtW}IOrn*9DGHOV1O)j!?OKeTc#!oeunn>;g^JOgH&`q@7{o-Iw{SV%l7?UV7> z6#ooUr=1+8J=r{P4VCE~4;GEMoo2!FfP9s`wc~WkGu!&BF zs|=l=&|EO5eDHI-siP9bcjNb61HK@i2Augj2U2*~D^R2-2d- zJ5N=9of3%#5dBufsE`Ko7NEWf&_jvwZ9gqIIQ9LyW}{G5`zH%a$s>4?xsu4FsyEH0 zyQ(^QrLLkNfe%p2wd3wxUX$S4;OJDll~Hr73Qjpf)H!?Prxi5em40T5srYf|Bihoy zINyXpR&nIp3{a}Yh-o?|ug8}O^iTquzQc$ks@9e+c(QK6-wBFvs%lYbTJZrZMPpPY zq8W{#^i-K7IW_W?t6iKLLaGVbvM`((utL`ypl`vyRoa*oTmA}GsmM4gXcq=9i?O}K zAWv;$s%qY|%|2{vA`qzmRNg_>=$hUq?Zw_;sMd&fA8dNxY!}ffOP7}c5ZxoKk4RfkEurVpMqmPmC~sOk&a5cQKGh_o@4t3Dv}b~}{ydS+X;2EPAKpxj3*wni6Ua}bCwqgb(k zzEmqeWqfLwevUf?fnJ>Iip|O?RUJS9G-ZR$zz0P^4h@dZqc?6xVhsPegPSQLjP_8lc zU1%iBJFr8BvhAr`mGq-Ga^rwSn)dI&anR`K@p7N+RaSe7VkIPxS4~HmQ_)SGfX|fN z>4nfnyyqMnOk#*qk0w*sg(^`xhR!=lY&k`!J(=n`Ni{L@s0T)WaYDQ5Tqv)|wjHZj z|Ar(u{E-tpxdL<)6048$4C|?|37_7m9?CWykR_<5j#V{{c3@GQLQR?+WEx^DoJ#4R z;=cMuwKMywKBWyp2}-m>r>iL7aIdIQv~wYR;v|2`F%PI#yfp|e?~5Db zx)K7WgTqZGRKAG}v{Nd)s8bWJohol^7Tp0OZ| zX*J`~A8XD{5jkDqf9HQ;{=iZOH@^k3{LPZCsUM>vxSN9N;}Qtrl8eNd&{6jo;}Vce z5d~nhEyRLS4ChixN43=_GE5duvRkCDrp4PNCL{W0)fb;shDo~vz!DSE1l1`oR`n;f zgQtBB@R_)XMZ$OE<*ML9iW$sCw*ed*c#o#)H$MlQqS!zBMARz^S3jkaieNSGFh&PD z(+iU_>LIN^1=fE06EEZOF4L2Kq^|uT5tI+hQBpT6o8hce%$;V5TeT7b@2i1kgv+6T zx}k5H#1bHre`IEePo`i0xz;d@7=^E7FH7C3bsybtpvVjfzx4IvQbeA4fDc!t3I`{@ z+2AAyB#3ER1!rA(wzD-fPN`SLY<+S}CcUhGZ zCHVIiw)U#4?dWmbsNC~<)5iLyN`EaCN;vK|)=pJ&HPPdy7Fv8TkY+QUcT>Y)^N?*F z&vTdC()0WBAQs%#`^=aMLD2HY4I^&^%iO#+TN9TO-1lzwOs`O6)EDciKgg^t>TPx5 zBoWMY{;XtBIyj)Lfsc7L#Ej<9a)!-fhArykz^s?A)B`Plj*U6<(DL)48+Vuu_n{Bo zp}Fg}04@=NbBm1oGohhGze_C<6lY060Bg5$fw&L=x#7j~FkPYEkG(?01Ob2`q>g^d~NNaa}DLJ_IfJ27u}z`K31p2k(@& za7~D}JE}!-Gxs}D2-YhfJBJsRn;VwSDjP)P(5&vv!tE%_1Fh8JXl^Td&JAmV=4gC| zEf57zZXnjPMW9DH*tkU&=#`7=xg~)*=u8d%=?eNgUg~6a_PYD-uYb#H(JA!ll*IE~ zG4(u_KWv7A~U+g0cQS?>f;vy$`2<@NCv-Nl1QbB>s{f_UJ)c*QR83J{tDxY zM5s`cMStlCky;IBsShKSijs)Db``ndc^sY6yy2)1=ekIi&b*QO8O{CchF&>J84Z=1 zHH>u}Z38cw=S|q8JqmN=jog>CIg<0z#B1l{8;QpQR`O^c1~EFaXjax6-^?pcvhytI zyEn685fyi`QgGE@cQWMDSkvj zC>%-#^J9JGaEOw}ywY?G^|^@#gkYsr=~kkZiIqA*s$f_|?0RXcJAE*8B5s#4D6xDL zGA2c=-@N501uv@vJTe-W9nPjCyAi3X77L-_2v`5gTg0vb0Hj*2dRk3o(3lXK`9YZ` zW57|qizmGHqdJmOe_Ak`m=r6tBDOZfJP+nW-?v8NoX$BL#ON-45ODUa)(myg-|WMKVKMfJaaYzxj^N{VIfPa zG0EuNU#Bq_qwnF=^FA(XNpFTDuSAy4CW}0DDR3$J`qp^;e<&WL_<4?%XYfbR7~6WE zCI+(C<(WO-O@cA}5L8)#cY4mycza1|37@0i`q)K}9TIk&yalnEc_L2}yN`|TzosQl zABY;-eq+h=^e?euSP-bw1l94*$?Nj8?Xl~*vf)@Vcnpr8{@CUH%hL=LRudrN9#~bB z*A%_wz6D8ifOD^O9bgyLg~>s1a92F zv*;6@OZ^d0ziz_oPMuQZ86CP*;$y22DYo?hvDBK$h z?ky7TZ&fDG*xUS;A{fGdHs&$cW$1?*{%M=!@<^-uHNK6gmf0TFf!D1qXsQ@P^T&J0 z7c#8F-=#TFN{EhclEmvfP=rLvfX1sn$3~F#)lO}!^|i$w>%5`ipZ571Bj$#=Q|foZ zJ1?ZODROk?-})uAu4aGtOp*NjPppCNg<^g>tU8dVSA@Gv(IgZSHUxfH^LKaU7&3{gjOc#x z^>L2Ty1pYjLH#h!{Pwf!I2S9?i%U&{rcw7V%CJ1+#iRsdf5FZ0mXoZMTdwd;DLa~` zjb9P!u9ixFdb^ZXzL?lvGYI|qdRJaiEjsDH_DBjsF!M_K{tq5Kt%cTBe95GQ&Z zs`vZp{(A*#;)g5B1t4!pKb-;{+DgjQKKl<2F%_0CB&xI6=(n7p-D5v0cq;lhqbzDA zNd2^1n_U$-XX>vTUv3s5@E>~iWh1lSq9gratVjvvE>v3#_~Wu~bdYA*L)@~Qf4aOD6{UaK*GAP; zd-iQc4P$D}g#;6K)9JH-J}#X)yL2$H^u7&|A!1PZAq);`E9ae3BLR4vA1 z-$7={8%o9H9Rc{3#4HSsd@w>w$cXM|+FG1k$OJ10l;TQ!?bPHU&?^z4KZ%pfs<0(g zEhnB>9z$l)9jvs4 zi|s|L)){1T-SSs%aZ|1~`3p77XF;g!E-lHqhvBLbJCGAD+u4gJ>Y4m2Sy*CSw)s4q zNH3$R-;=CTPt#Pn56B+tbSl$TtyR}HMrk4d3ToJ_Mh z_At^YpKnMKui4YPHhQPs%N{e&Z;rY%Zix8C>uh&~!u*D0GURu?iKDW`gwA81fhI{P zZ`r{W8L5Op;(|k&8fD_Qf~j7do9+)U6sVMybJAH&+3iHTK+&&`l8DBLOIt$rX<~xU zX!e@Fo;1YV@fISUy?qI5kI#50WCYQOi~=`KCi_@)18DGxgJh$bCm&{qxjcP3f+}QE zx}?jv6GKrZPCd}xz0GHu&U2Q-%GV2tqxkmsXXGCVq35hNk8r9WT))HPR8}-lYkec- z?-Wvyr^j(vakzmy(gC$=B5y@?1);BqJ%d6d01Q!e4#BLB5e$L*R-D(&D)q^}v zNhG>&`qm2NfQiLa@L%1>{z8W9B$WF7#sz;i{CH@BRGF@gno#58Vi?&XV8f0230V}+ z0mY#E$n>9o=*p*yf>1oUt~3&U&uS_o|Hn*C(}a? ze{s2AE{wcLUGf-!;NI!H*Se%yTkCbiaYZ21QLEV9T!?3 zabkVvwVJg1HTwC7YjRrxb;8b?(uMXOY59HcceZJYuv6TW-gx)#8xmZctk7iM$4^T4 zeO#%5c#U5KS4Ka_>Ab&Ks;|0UA5T|MAyS!6xG>;bCA~$FC^hcYUHe8B^8G~ty zelqctgA7BU$(>R>=56hH(YLGWP9f|Ll%8Vbmg;rgzVFt3V#xht>|*tDAff=tC5WW# zWWF{AdG8JL_nX?v<_02p8FbD#AeBs1hzR}*2Te;uoipvM7YAKWEK8QOf0YO|oc(XL z1XC(EJrx3%_N6~$zE{NhTUUtebS8C6bsr*-Fukb7CRB*v_Km&244dvC=gT)jZx)V4 z9Q|%SB=WGJ!Vaw1Z=a(HDKWZBRi#cSL1Hy>81Qak_~2P+$5S@=oFm?ZyylLdgxRYR zBGNpr%b?JLV~JhyW{O?YbciW+@Q_!Y{+WG;sECZLY3=uSp~-r(K4hcn&bhY=f0|_2 z35T_7V(+o4!HXRx@(d0GV0Jx>i|n_urZ|}&1~jJ>W`7PxA`gof8lL*+7`ee1r2v<) zRcYmq@KNPzN;h$i+hF|k6b>Kp5Y;~|>qt6dMDRwgPH+qD?1qFi@08s8M zJQ+`x9qB3TZSjtE7#JlBRG6;7CzqBT^FzV&3q|52K7F1XF;WY2M!^Ma##YFt^W>(+FBK5R zf|1s(gA|~#9Jc0{Or{+qlMkU=`!icW&8q>Kg$A`Ej+tTQnIt(4NRWoBTE-txSWuFv zWr&9Bhl$b1aWVkRY-jrX_P;A{W~pLStZF2eG47U1O;;K^GzSbBizzgUOz@jS`-_2D z3eD(a^fi-@*Pjb_Z%q11?G z@zEiu#k#W4rt-m58_W0#juhUWJwHX1d_oc`RI=kZpYWG#%D| z^Aejng^AG|aSPH1x&&eK2@VTl|Fjtu7KmDZfOEBbRxySuw2;GM54>@(R|x<-C_}czv?U$0C9PV0t#3=l#7n$=aT0U-MjD~- z6_$R;Pw{6i@dk&Gts-e11oIzg;(-jbm<+6KLrvoh3|p6-mzG@*mfdVo_{pX?1?Gfh zpc>LR>K==!1sJ;>3#pLUH?5eypH_S%=A)!hbww6AiRbGPiH0qaD*?H4AIe)REl(fXYiopZ{Tp1y>pi=-Lkl3u734pKQ0*i`&@Aosi4iZu?nkt2u$U5Kg(IAp87BI)V@TcooTT> zV4(0A;QU2HI%IR0U2EjQWLadEQ*ZjrLH!zMf|&!epK=VE&AXh5X)uILx(%DD!JS;H z*a{Q#1)D9Jn2rZ3LK?T?DH{i!OjXI>UlI=gj0y?jg<(IpBeY=Sf3mu}B# ztX{}&N9uBnF5dsO!pa`2b!{q^>1XJuG&~3i+2ozHXkLX&oq!&iP*#9Cqs88mdfLt_Ip*_3lyV&`C2hu1aI>xS16F!Ear=WDTM zy#_a4Q*=l;o6SZCa$b`Ip8sz|Aoic!L8rEs-(&=iroicizUHXInhfsv^+couIwja= z6|d#;MMVV*grg$xNL9y$m>D;dPguBWYK@1F5|Sf3mO<0!`1GQzWXhO{XE(asvCTcC z$B3)ViurGnL2%h|q$8E)vOCMIYnNv7(wB|q?qq8Q=l4v*ud=Md$@G^Rr=hZB^Utx9 zn8-F@)Vg^R8LWnm5x0f1bER;1*x~@Ql(jKAul3Rl>RRtx_4e1kM1NrIB?3-g}8IsRy?U+!C7s?u{dK3Ze^`oLrumRtcB2*y>#ASVaG zXKA=P6?fm9dyRK^t8!ZJb~bX%USsW?WF=pIr$Hs42y=--VuRdF6@HkjyfQ@h^fTC8 z%ES2(@ zC8m@#{s(t(Jc5d7E}*(a)HYT+;wf+y*fM=3TbEV_}jnZiGOtGmf^;& zp06tsrl}mNnfMSh`k?cGL`DYF>3c{(e@rBOOk#OVF87Oh^O$PrAN55SunkX(c$5nM z?;qb^>li4lvP|Ld`*irw+Wi6bywM7OMDZseSMaG=>8ZrDxB6#ob z=nB2gHzhYd{)?I*kp@GE+ph>Q8P-QXk;N8hcWl#CJpU`UtrxpFAN>fx^_IB}Tt>&x zbI~JUBx4H4Q9~u=b2+}G8;T^v#>#QHDq`0K015^i8lgClDro5m9BGg(flv^c=Wjz| z92sw2i4JCC(R7ZOE0%ia4GT0P>m3@G(=F>liIAX^>!LWr$X}qRo#a_GMj`Pw%)8 zV@k~QHM-r=Op#8-lf|E`r0K>+7MF|5h0J|KCZg3TEn||oOwu(pz8gi95xYF_SjDIl zNog>pc`j5W#yKg767tB%@}X)VqJCT$7b(>bt$yfink_2CmQo**V+LzWOMMhl?G}O# zbbP##?CQ9mt?&t1_s+@cP*`-sWKMRZcpUDvGH$|KV??vpXWFB%6@9T}=i;-yMPjG! z8ofDYIW@o7`gd_p;yzjb^zF0E!J4*l6#;{)#RJ#=>L*?Q2tD=G3PNJjbf1W2g>)dD zEab*67ii&wT9Ptgm66wSlm8xm@ z?SaM;Rz+p%2z_^*+(dGuW!hn#p)m=@NfJjS@_5x^o#MAPLoFw?r3-{shD{78=ipGq zwyUV|`BLsYnUymiJm^P=!wa@zY_W|4+$$q^|N<5h>hQm9J zs*-a-?tS{qIRYza8Y$!D@Zp1|4q2cmxMPY_nkf?y>f%U%7eGB%3zcruzqdAaX0Fbk zw`f_AV8xRc`drJg3aEskMA(hHyMNc*mU^JRj^BL^-s7W#D2^(Wd_zkvWu7gXRFY* zlsdH(4o;0ORtvmq)G2ak^jD4q{bmgD{qIesscet*=_H?_9btfD27G!7m|{2(>BuGx zs6K!D*U0R`5P%OPoY^xJi7aMFD8K%DWp;Hs!zTRFbXY(BteFncqu;oHW?g3e%t8d& z{-bu~zKp`rWC|w79$(BE zYUmBo3c-dilnL2NZAd5J1Lyx^id-(pm8E2UKo+?0Jts&OkM>v^{n$fvE>$L2No_R> z8qr76mH3ILhLHV(0n<}$gh5ib<*q?y7xf`9P^@xOwunzYL0T4-Mw%XDHyD#p#}-n& zDx2t3fJ*--F1AnmJ#jW8d+uYSa8)3_qm{+riw8m}8qPm;*2hF7*<~9?;xCVtxEeyR z+Rv%RsdnYT7`ZYwgw-eZYl)CdnT_{S!Zc?Uhdd=Z)FFoMhJ(@l30|RfI^>{?y}K^{ zkoY!HI)$ZgPKyUo=uWg*6hmbiA55pgoXnc8b!u>?MPw|09cfpiBUhd~&b?i*DW&%HWfZrhLuE zf^J;0&N-e)Pt%A(V}!&?vrrt8#X_IaA)AQM#dO?Nv(vjhN&-aZq0l&HX_1GO+9YDc zg(nq{`JO6<17bf?TMTtP`lp*Rq8g32{g~B8BjG~HAdyG-Dzl2JLr&2|8MyXC0 z(^-z)5_Nlg8_RC`K=SIxY?bB+4uD6Ffmu3OTd<^ByYvTLpf2X?>UJt_f1!r|UU*wF zNu7~Qm68AhVK|1Tgzg`#RpB%;vD26bb$Q6rU4hfuluF!c&{iM$RUuAADwo!eeO z3x>>p9`F$80?cu;q$3ZkhC>jHPh1}OUL;&qvdAEdT4r_2Xi+PArb=ZMCFqsKb-WED zL7j&ZjSGoh4m~kJFHe{t)ed@$A0yESPkfN<7T(8wa9IOZSbdWfemU77V|YW97J)T( zvB)6%Ay3>#Dl00rjzM{nNH%GlT`cF-0nWp#h(gW-Z0C+4=gE3Ci1;tEj9tcD$c4%0 z7aKYy;}L1@oA6N_OC2K^VI*V-^3sRSW!jGg^^heB2Eb`X7L`h6DTEu)l zB&M0}5m5dd5i_5|K!Qe-UHDDemR)@hKeH54mQBe+2vi9E42FIzK%yiUB$U$LrLTV) z(j)Oo%6r#F*`5E5wQdS!{7T zOwS_IQF(W%88|zlc>;a8U-t|!bwYqVL&%h(?c}Qk=RVEdo9CZ}d-k|4{C{+B-SrCh z-qc=v+Iz-POvEHuhF%EdFyh{mh4wqoH#8k9^;RW%ayhK;;l6>zNHh~_ueF*+_ z@5>38=|h80QtqG`-jh#2hy?p6aZ40^DkX4lGQV^om7xVsC$WA=xarw?`~IFRng_*m zIv67WBHFFB<@J%nY*XXC*y2^3$Eff6e{K6m8TJCeGP_?tpbs9~Si4JQpE-cXe62iU zzE2ZDJv}3d2u$#KNk`prSduv8T|YTLZfaj$CNSvUWZT#yC3+rmzYkoSPPXoodb%Vz zFY|(NTD9gQ8(R3PY?EJXQzuvvh8+(Q=K$b|Ry`|1$1!cd z^7sYbc!l5h(;_YczrSqfGXVJJKRLCVO+?_ow4|hBJ%n})MvuN_C$tPpT;9ft;(5O0 zqK%w?|NLh)rZlW=iF(a*^-_Xt?}~a8GryQOFOC4%ZcOcoVS>mg%A=VANVklH z=^{di^q?84B?C+lSz4ohP~z6`PXI`|pZGEa0zqang|WhyWsO#RYz@D-%EJm_FakP% zA8G<-<79%u_(Ejj9%eOK7uYJ_4g#fkOb!etlV7&+f!Kh1lZqk-PlXc&&v9IDgdIOVXG)plBI+u7{K$%jBER!G7NTeFB zhzu1wK_m>qSUN0-LMIMBwzH8PvAISIA;5pDqrlFn zLo~H7Z-lJlrulnA8VnpD)3dYZNeK*6FbP&V$0!RHIn>fa))|19W5MikF+S3xx!>7Y zy)e7M30sxR0!b#cPg)YL+KZgeOG946Q=8jF4$NY?LqiEyGfNFFIJ& zFu75|p_0IHoT8wD!%idQ7_pELgB)Ceeqtapz3G5C^N9cF6Yj!&Ay1w2%I5X zIU`v$gB&6ZnCuh7J6!wTV0Mp^f%mc}`lppa@~3(w1FWX9Oi)>Rh%6ll1_8oqx14B! zvUPVM1k(M-Y3AkvA;h;bbb81id`F7-st~@SPLZ*d?`=qQz()W~Hkn9S+J=)d8jhR~ z3Pto0dgqE>IZ^T(#8q8N?`o^6>0yv5WAHvXK9Hheq`GIOy5kZ6zU(jbb=GFAZqiZ6 zyf)}uj|1rFI& z0RAli1e77FpaGY-fTjB1;CfMRUK8CO6?SEpL%()qjO@ORm8?#}2c zA$fLbEnImbdWVV*UJyd}ssq zPJS9+Ob?qM3*LG;T2|C|h?Avn*&a2g!UrPpQ&cf5EN_76!H}}y@!+j3)?d+)zXk~3 zP=rBT;&E>6*+H;@yIrGP;_uuo>zrM;t(WosXqrd5aw2MG`s;T+Qkn3Hy9NDTInlQvr-v^aCtj&m< zJ0viWT^86+i~(~*+$p}|p&<_4_iDH!OC0`zr|!&Qt~&-q7F@RKS}53=|HM#h3sQ0b z7x7zo^os|>VfMFG2kpI97%@B;7Z(;Y4RhBHw0&+6J!BG4Itk+?wu#~$mJ1H)u(Q$W zdLHZN8X0Lv&zH#E4)|^I* zRLuQDX3}mYrb`(zY$q@X2CiR3*HxgX=EYCqiRJu2J*;ymP^%`3WN)W%o~#OzLvws^ zbF2E%nPXW{W(8sVP-Wg|A<)F|29@!i;O>-}K9O5i-qQ*SqP?#OH04s_Kl4mj0ETex(%_Puk1U# zrp3Jydq2yOk4L8gWQujgz6g)*;I%dq7<18Nc5jrT4QB$jI8^O6y4~n5+6?-g$npzN zc58WTG03Yo4~zCI@}uFMOi@4t^n-!;en62Gw6d;}`n2Zoo@Tjq8`bJ_)#eNSSA~$0 z0Yg11@CLUVj&)jzm%WXezBzo^H=GsBrWfPxZFA$+*J#CdtDUVbXN{>i*&r7zKdgZ0 z$2VcdBK)Hh2s9f8u(QND6N3LZIZ2eGYohRm=CvZwH1uPVn4met`+^$za27ptl^mFj zmXNJso9%lcJNq^}cOkovvJ@Ud4iRk*YHg%_eV|w&n?PA57E~sj^bUdkAE!feSoUW8 zO~yobnj3U1)^Fknhgii^)a8+^-``viw|mkGe_(0<@J856xZO+Y-ib8KwUZGaa_Led zXk~HF{!7R$L;GDfzRKHS=_#FI!G4dABWTj?0rkRx?d^fzh0$Ds-|NYOK?Y#&2LDB0 zov@EOtX>}tmp?YUTOVZvO2(Hy(CxwJ#BNK{v^AIfT zuKUvy(!r(WEd152!`<`#3%^%zIeRV!Y$ux$iy|qnnJ!*!X1j~%x$}_E|;2L?wruexgwt|XV61zX>$Z^Kf z4l^0$(1QrmwG`Pm1Uz~azf=LWNtNgTA0H43se9p(8DU>O`YVDSdp0_CVv&bYVF{DN z1=Wg${OGc02XR`!&BSD!%;fhuUKQc~vsoQ^^}zh!y17yu*~s%n^%44S9^GsvC4a-! z;*e>jHE>;I%4dEI;M|p(sFkTXL_qna0yJ@Wx!q$$&3^;=& zr+*E{NDV_o`VAVF!gS27?`NF=9mv~@L(-0iqzeGP1nIMacz56bvG-R`b$oH-@3|q! z#=^!m1b26LcXtmi!5xCTySr`N-Q9x+3kmM-x-&e__sp+mYW{*bb?&;V`(oX6RrjaX zdcT6YigaHZ+vJ)ak21f7;>fJjWmo0nSaeH?)7r%$DTTDlHDRDBzZ1Q7=hrso^J$g7 zDw_VvZld^fIl6v!rv$VDaGdufSG3TL6ds0kAo;SQb?f4L$tn0YYx)x0jM~~o*Sg-^ zTti*Ceh#ejK~L`TGUOk{5a%P4?1fjSXS23+y|u}b>R(VuxZ+#x^fe{)WgYUJo_#av z?jrShQ}ONm+|aF{KbE^tLWd4bb1nSh&Aimbws=`J|BZj)YuJRP+RCHnno--FRD?V+ zkPtY&uc&__5VG_&-Qq$5Wrj zq~>q_4d3m`TSmac<9UnV#!PA_oJ0%kp7tsnaT>HSQfd7Q4dE&n6CN%P55e<9#Mm{Kl}IeOZ90}3#C`CFJxC8G6A@9K{r$|fWP zET-HI&533cQ5Y(j>K!+QqG?PfpO;|z)#bCfoDP<(=P&^Ze1W`X$+TAUK^3bxtevjJ z*(vg|pF_QyC1XT6CC&j8pXSwbrF*a?UfAt^W^zoGX=Jw^&bDwF^!6O9*UmJ!nT#?_ zQNf{R2bl#diDF*LMui#?N!s0>HbP)=sgZh_aHRpMX8WYsry1t0h{64MgGhL(}glBKe(Rq z*c%-p8$8`z^!u}+d?`Mal@$=??YR5>dU}9}pj7uGS8)35SE+8k_P<()Tj)ah0x2A^ zrYvkRt_^N%&q05YgUHrFm6B-kMes%6X#%uk=ljtVYNd)WZ5_GXTr^3PN>CLO4c2kA z;~);%ZDcQ8iwkP^`S)fPFrBH@V2Sz*fM%eWzxk?*u+9Z-l!BnLo+qUiDW30(+Yk#_ zPFS|2L{1(FVI+uh0o2I`u5Ogb%8bE4xY5tulQO#ZDVVBqK|aum?0bQegX{ zKhI0COs|ebbxfb!N)}k9rU<5mqTz^^bb>CS6d#D4-zYd^7CZuSuq%iYAsjrVbP4UQgkqap1>bQ1PO`Qk3$UavT-1R%-!^nnDst79)^hD#8qWRo4A9Qwb?=g@k?n%h-E{^ zpqLtf%g4j-Eq{L!$33wk^@IC&!kKGZC0}CvP_=Vl&PlfdW8k_$hjVl@XIUqIzpcguaovf3)K6U# zsq?%0>Gas+wN6o<7n?=BlKZ^Z5x(hp*^$2ayqVwkPNR0@oa4Kmn(zDas6s-%meNtT ziAgQYd+oC~65oBl4^P_p@Luct^PAD#?{a}pL8!h{Y+nreSNfne>%2bs{(Yg15QbKr z^{RMMy2Fj=20|xzV1^i81X%VX3C21aRsaCTxMH}Rro{GQ5wK=J09$=vxWL^uYT(fj z8%$z^IH4(8Vum;cV`8Kow<$*8)9}|?s3?tQh$(uh=Lo%FVzj}Y3BI?q1e1jd3R{E- zS^_s5et;Q*@!bw;Q@aFruS%R2<}N{tv=sk^Q;fWRFy7KH(Qd0Ev^c9_5|m?Lvx7Gg`<5E3l+3hFqjv_(7mAH=VU=3xl#HdlgOAe+>a-5Yn3(%iItV<9 zzZ6rCz8PGKTFdIEC8dI!_sGA=@M={iB`5L?(S*@V$R9YTcbb*m6j^p^K(l2fh{3*? zRmf{=s%50hN6^9y2dlm{W<>#GP?}3REG3z;z;8;&t2$kp-pN@@*%Z|26LJ=^pZzix z&G}SVW_;J#GViO+MA(kG%Ts=4&A3uS*uNagncAqP0XHq~vAMWKDn}hbCTg427~Gd{ zHF^q7(ktUb3Bm#7z$sS6zq~^%+_@rJ1okMDxYwZo<{&hD2I*y8GS#gR8s$LJ3Ym+v z=4731FoF=xgehYEi*ftfb-%C9+&vT(m?wZipZ@tZ9q zPh<%qAQdbE`4dX5WZE!tzRY3TR<;x-*`kqN{~tWaGPDJ;@o0v`bO5* zV$zz^S8{jt6mcZ^k6Vwnv=h~pF5pm;9;P=QbhC{=!ww};w2c~ZuBcN6uc31{; z)Il<$`cpGq;G}rjsm3`YTxU&1t=pH|dHX;dmccBC%3pFIS+hvuiu$GMB3Av?1T0&p zPzRTKq)hMwWwY}XlOc9axwB3naq-cDRS>k!57?;QP_N5Cq~xu!?iMb5BFFG+(Ve6# zY2#055*;?ek)_RT9A>78fg;reXn!9D+zK0P`1N++`#9lr(IY4XO@mWdO2^!+8}$z; z^MwyQIr-e>gGqw-(S)8Ebcv*C1)W0!)r)8a94l0Q`08Tfz_m0#GpGJFH6Iqo0mFDGr;8~I9|RMXf7Apq)Z#ZX9^XxFMyd& zXoe1?Zj2SJ(HT5y&hb_m2wSUh@-t8tl36pExHI>y`IB0$4oAk)s@uCxV#(z`8#*8pJl8TY$9rx7{@}__{|4r zdf}{sqNf&ME4e9n;ATJ=oByLpr<$HKRMrEJ=>C|^09lPHBSYvTGXx8+KnLKl_-rKoh zqW8K-<3samrkeg`=XN@}$+V#?^M*vX%3kjJ7|#A>z*t;ALCa&CS@%yef4RL#&D2Wr zO%}tx*d3_D=N9!pH(Y4^zp0EcmpwWz)#e>(J3}tVMg^(6F9p{1n9^7Dd>*XvUM_Nf zg1QbJs$0Tke|uc|memVBJq&bD9l>3zu$3%NJN$SUdA~fVGk-F<_OmZVJ-RE_(M`wo zLoO)rg5(hXn>@Abds`NLzpg8JlN{^2o~S)*4Q)|{0tycxdgey7 zU}Qvlw?-jBgLmY0uru)_=-U9Vt=W2exT!&4JP5`f1YM_e^Bwt({eoDWgxOShLeUNo zsPLASfZ%3t{aYN~92MDPa0~GYP#8LA$V>%2=g{nklx_->S^epd9_29pvpuvRGU=yp z0Zr<`U}xozkvxh-Jp$V(e5@jJAT&a(qC75RDfS2mmB|(~Pfw@}a)bW7R@aU_r+^4C z?GuI`GXC^ZTfOybZjN^b{Zl;14Nhne#G>ekC9w^#9zjr3=F@dbphd$nP{IaNX_8!ZeCD_bYKi*#!31i7LR!R`xT|?mXo| z;+NBFiV!ELw9ayo+e&lPiXK>9|ns`#WBvD3m z6b>}fnjy^3%Jon77$geBa!C}3tZ1c9jO0ms)w_V#D6DHaJacDCjUq~0Ix5J0EM{G? zcnYF7Mkb2^hEywD_SlPhA3V4+S`Dl6tM1{eBOpP&b8XqrMS-`AA5LK#SXUfwB*v$p$tWV;? zq~_B%^m>e>`_7CEq%4P|%*hIDTx{C9&MuT!BqNEK@GexJo5)$%DAyZs( zNf6bjFqtWBRUGLTDF+*Fsc)ejip8(WXmp#X9TxfWShX*r5vSXf!LNXfpC(IJRp znllqeV~9$l^HfOkU^sF*nR3*O@_Y#zH|-}LUL*%MF&DV>$EopsD}f;0SBeQHaDE;( zkZoZ5*+kym^m&_=L9vNcjg9i*_A`8nFwY{1xCkghne!C`fSSU3qb3xdjMua%fJQ2O z-6#@?N}YU-kn7CSut>mwY1w{z*6#EQKL3~|O2`xm+Yd?@?Fhl6i?N`bTFvkZ-SP5; zN#vgjdMJuZsaI{O5%{sbDL40TQQEREUDC2kBLqq2vx#a*%8tQFVtkY7A^oj>gG9F| z<5eU+W+PgjD8)56%8A}r?@C+E&N9wUYQ|3F!6s<$qKLOB_BV;9YhEtdMLM)vA=gHs zcu9!_T3LfsUA;BUhhX+EdbCO^F5~w@VBTF-b=sU z(b;0r_H6-tQ!Rf9%Ofo5AYdxBEg{XagRnG+X^EkHi!lYa6LF>TxF>=&sYtda{2Zm+ zO~*WYBXdVN+{i86NXre##%NB)43@F82K}FxS3V>6WDI%!EXLnw)TC4qLT6`Qh z?hmK^rPcTIG?d>*-_JQ6?tj@sAxJY^hdNt@!9inuHimX5bCQKh;yrR!x6-Eo1`>O? zDqA|UxPPl?brPVap$0nhtr)9}8UNLAm9fgyJa#3Ba)t__wwrKfYs->fNix%Pvrczq z;&RR(bjCSxvu;a<8FZstaW{H&v3+#<3idbUa^HaWObznl!gl+nmCJv0LaOOW)mA9k z<{9~D@QudHB(g9k%`-Q>sN2JxiOV&%Ex5oMQdr&QwUM5e}#S zPRJW{r0BQ*p>ad6p(dWHO<*425iCm=q?V837`otpyN`i;&w|NK3QTnXt#Z*mDFxr# zF+Ra%vlF2_LNOPHeA32}H3_Oi);&)QJ!et1JmZKSk&0vt=2#6w3bHL%M21@-A%6-9 zRtf8Z4a=Mkg>B;ct0EY$p`_D7j{CHduqy4?PKjUksK>_{VfW~ zH28~XxJpB$Oi@%eqbA;TG~c2^M8^9LH}&)?`h2^@h&JbKJI%xDmRYLe?^R~#4)POi z(4{9?2rhAUlF0Zf$y-9z>Jum88VV|;gY;@H0M9PoK!d~Ti6swL=+QH&tv*SMjAEoA zo}hyS8H-7^!ys){PG&9WQ5y@rgNH8zyJJbZfjc_gEit?@6@xn}mQB5mTg9s*orUM# zA~Q|JD?!VZRcR?BK9gkU&OoqTVro9U#w)GPiwvT|A?}6nO@}mKji(bYF&8hsv_&zJ zN2y##8cjpdnj?MtNrmPrHPq_ljna?_D(Rig*Zl$rhSRh@lAKtW0S7n*J{O?}XE9B+3 zconBR**soVZbivo#OjRhseE|F7hk{zykOZZVu0SvI^Oq?^&|`*-s8@gb6)Ab7h+Dl zcFGMBEBrc6y^>O&FfFL!H%7Iub-13Ln#H zlk6y4p88bYh{LQp2hyhKdV#+kZDZWE9IDNA>scah%}72qYEzPalx>+5jiDGVfy*g{ z-fax(9q>iPfpP6T^^le(#`bKKe1?r?A*C)V_+Am0c)r(H!j}q!>}FWe?lywj#oqnwGz}k4Aa9x1V*e1qz?x!@LPGyHz3Lf0$|Y^alZ{`Ux+>2E z>|DQz25_sIvZSMzT6DaJ@%Wo(@CW_MTCb71PI-s#Q#u_+Ivs{bzwQj-6xZ-%_Tmus z7W2YL<#cyd55uNR=$JOd>!mO1buM}j7yfQi%1J!k9kA>k*hK2yTpW4l9cOtX2JlOS zc63>EP9yA$e`TJ)$^omr#S5i&QQ%FtVEk0^Dp=#^w%VvD&lw@povnJ&%6LW0&sNOw zrTFdpZ}@HQ6hb>+!yD7X*LSZs?f3EjuMdaQqwL?s*8ZkKPndH}$g|zO_zbuFOu0y4 zx_JGQ>-etANxvMGV0`O!a!hu4v3+(-Z@|rO#mW0uuKL)QoR##kRgvW7ck(Hp-#<62 zms~J@=K8g?h^-;%FOX;q4&@9k53Z)>Jj@Y{eDf`77MShuTl>)?i{#0ULbplcvpN6L zGMoEUEigoq+hAfaiWEJ$-}5W5D>@cy1D5-DUDs~~zdtid#VcOF_cMQ&>i@d;=|lVT z@ZF%7&v&Byeehq-Up?QQ<&^P}&P@BRZ$)}@C|RrfFNGd6n{qr`P`dRzKjsATXdH9L zhCBbvB+o*m^7c>!*DVFFw_bNxdh?`me=qnN7HqQC5UwS@=jXoe)AWq`7#{lzVjvlC zd3FysLMSc?PIh~C-@l}o=#O;0ZDaWzUh1!I@SO>T?URr$Jqko7Hy{0bKQ+%g|AKt@ zdb*gdHgNyr((-v4k7xBB6B-c!Koo{%hRQtb?m8Bntoxy|_xr+y4H+8>1Dga2GvNB( zfW3wcWsb-QU=USq2wDRGCdJq1m!`-Be$5)5eETE7K?2SBHSgB%%8BnLRIf0fXy<;( z0zeEEc9$hDf`O}Lo*Ef+u##&0%Z1p|ooXy3g48|FKdtO<8a>dX@~>r6YXJD)H$SPD znR|$9f4*HxnJLk{olv@UnweHd8o1Mjxh`JA=yT+n@0bd%HN@&Q)$(q zkt*@6l!*reku^$9zn!SlhQZJfRa-flNXDS>(B65nm`Fz>QRRt_z@>^uVoKPY9ii_{ z#k1HZ4QDv-NoMmo+=Lvnfu+@W=<-ClRm>}6s2CdgWtl6)%SiJ{4Y-$!2Gz@%p_tv6 zt5+M$rm_U0IcwHi>^3^h^`HWNcQ_M#S=s}~LIcei=3tG(Vz&lDkO%~0xEppxVhH$t zAoDctO{CE2^~S6@W=-et`9P3)n~&y8zGgqaaJHN*SL<~NR#hYxOEz0_sp9@RC51GC z<)0s-WQ;Yp_0w7Pt#h7)Yq2yMFpnFET|#GD@cCt!QCz~8F}#i9-i;sA_EZ#b@|Rw& zgCrwGLm`{Ko`=V~w){#)r}D?Qp%@`ghF(vxV|f9$XxxN;2&5jHs?-{7#!e`b(k9M` zy5n0;=r$Q!{<0>a+hM~R+$Is^&Q?WE7m=POk&H!8I}tRa8Ai0?5@xD?`+%H78vqo5P#B8R8dkToyvn4KR?m)b*~X@NG)l9yx%2)Yzb)_n zsMeO{#8x*OPL93={E=>!?IiU{ESXM&J!>+Jq_NlesY&;zdbTKqy0sGd)V^Jlh_04) z#k=af=@>iPwqr6%&c5SN6X|=$L$73QdqmV!O;_CwpF_*#iS1?opI<%>gO&TI=fO9F zl@4u3jCA(>8@17P`1_>Qj$?K#G4|bm)?XYat}X~_$5Fl!(vK1K`C^YRw`Q|W4LlGq z{@m_GU}4T_t->EW^i#qR#*FY%*FJF=Da1{hi_-_GOAjT(oyrrd&Ix4uiPdW`~?ug`lNA{spi-s9^=pECC$Lcao)G_ab9`-j7;QS$12 zMZRsp>v^&t9wUX8`52zr0qc>mXG59pG=V76L&hz$A?~*;C{V2|L=W};sN(qW(fa}j zleX5p)9MJtS`uSZ)f>`X=T$xyU8evm@`Aob z?h1y+M9uGa>d<4B!^xTParwz)Z$U?N0v8P$es@byB=^$NJ7}tCZ+UpBZ5`OPPKm^J zq!3bTFdbZ6f@ARx;x<@Pv2{LKkgcRt+FAw~j@8tfKLcH3O+wS~XKKoxITICvj5yp> zdQ@e}Yd{6H#Lj|h>~soCro`xxIeKb7rZGBK$23IzBq>6vi4uJZOQD`YA)`&zf|Fo* zT0YQOxh9x^6|3c^2#Qn6Wym2#OXQ5pjZ-!bSvgQaXIO30A+2?~To7+UsdU1*aFhIK z3pa|vh3HOE(k1;M2dHSe-jqhNXhpq?Gq0!EtahBE&WFV<7WkRHl#=d9+68Y&a}=#$ znOtAs(sdzvb4d~1&pKO{mnPxDx!j|O2xixd3LrQI21(>AJ>o5@Dkc`I3Y-XFagEyw zVpV#S99%}|QkDEcNbAI~%}rSsN&K#%B5bd|i72Di&f8o`?{=)KvHVNY%T?I|g-&~S zX@zqi)6U;M8BxtkOGzWe2*+SeBePA54-%SOPeo^!O{!O(N9iu-^$s?l71vCebgf;; zq7vZf&`F|X56y^8wx)VqV<}8+iGQcE&M#eCinDD|sj{!8jHWO9aUa22tz$QkqPNLf z(R60VVBDiKc7(lmy*!?f@!nI}ngl}XWt$&#f9yGj+Dua&j@1>}hK6Ouk|^%Ab<0``o=x zAJ1&tp^}-K%l();tLaSmRGzATYAo6ohixm)Jj8I^SE`BWm!oyLcN;_3x^tY-ypY99uEdT27BBp1l@X z2paDZHR^JsaQ;dt^9TE*u^D?2SOtp(1OUhsH5`XbI@3!& zb9V0w$P&vDGGGP(0B1qiX8seuhZ|XTfGd{;lsVgMsV;w_AZ(-T3_2Zux%dT-UW(2zlr_H8{6o8u{~2@IkfU%T>tXOEPK9ExfM?mQp9T z&f87;xZIDMl)CPHrugS++aI?%m)(a#s4sKTKkiDHdXAOiUzVzV+*dpFoF4B)B#uek z!~%n%VRo=m;!C+8eNX^O-%oE_Nd8a5Oug6f@o&4IsGg@CdT;Z;zU_U&n6_5AVe8^K2+6N~a+G>od^rNIos^#CH~ zzt?>K*E|0X_JFn>|8b0f2Il~2E$j?og4j7YfFoSlf(@)EU4B9U&^&N8InZ-Ckf=Qn zKO%qx7=)aG9UJaMt{t>-8<^J^@TbwAjGB?@NbDk=hTSSiX2sPq5D{D1rFK48XdGYU zh*5ByNzyY!v>jhOBSax1SP2-aLLI6m9jaj!sudBc0}j<24>dRnH3Ej2P=|e!4l}n3 z(-d{0I%I%=lmP%`0J?DC><$pa5l|cyvU~%J2m(M6GngocBW`&vHv;Xb1OMFoZ@CKq z)%i$o5&-Z415`*EjQ{{l$1r#mXFh5M<9c95JrFSgu)F|=J_qL|0>Ij0zy`o!^@mS8 z!v)L(F@ym^IP~_)P<7PSx;FreIbckGm}~@v-4-wogcC!}5bX#68b?~L!U6kT0-x9c zfS8JFSXg34)48beB*0VzB5b|qHZ-6kLLX31upH_eic47DH?`4TrYE6e>CpE{TuTACwd7Qs6{aT>p1-eF7_YX3=}aa80CyG>vUrA zGz4NO1Ddew2nMf4DnHXqYn2q#00a|{ROfM^5eN{|53G~Hu7iw6H)>}q6lVhfa6YUV zP;-&WW7$?8*;8f$r-r0I=xOOs2|SVX1*Ei+csawQaM6(o{%E4~$fQ1;pYR8Zb3bn=o+{=IenV`TnwMgHqV{`+zMKZF7(+JaBA1+X>+@KFT_l?6zX z1t=#4sECDVw1pV5g;+L)I8lXom4yV8g(3XhFmPpu?NJW*%RF=q1mMEN*C?S@r z(3YynmTK6PYDJamRF>*ZmKvOt8X=aM(3X9ZEi<<%^RSF6v#u<&oh-9IDRV$9ccLwK zku7(#Dffsf_o^)SnJo7^DfdSN2hxIrWx=5~;P5DLWFtgOhMtjIm7$VaR!q^&HLtt_>vERU+JsI07-tgJbytV677psi}MDTIOo{J-&t z|06|&0{{SIWMn8)2^|Rl!2J(Z!TpdVKJEzs2*?Q#5GelxR;W0r*xA`Xj1?sS zKpg-O6%qo70s!*=>#gVkFyt`+CQzU3K0&!d0eqppczofI;tfxHGxsbLFKorFEiploOPdB0g3W2ms^|62@r&Dy882e*B1|p&13h9Q+@j z1ps*bAX@(OS%`?P|9^=VI=X*sZ2yC^2(tYT)bio8$jkr!@LAN<*0i)%K8ThNpT*mI z?89df72T4SIr@)i`Ojz3Q@;DKT0V%D|8SQ7SQbaen-8KT%;zp7BqSy#CM6{$H#avY zEiL(fuKzEbrL?rPrlzJ8T=ai%mV$zw|9qCqtjd37Wgkk*dr!}Y(o(iq*1g%?u-fpS z$pQwi{l~H-NBmzPOG?Vke;~_$6w8On@*%VQr?E^A4J|J(e}F8D6BFaR<7>xjA0W&B zYAleMnTP*CmOp>?K1`MmkmdAn@BZ}UKal0}?sEHT`#+84gJQY9zW%=%#quGg`29ap z%Kv{$Dcev0U2d!qR9=TJpq@b*_>2> z%PLPQt6NV_svz~Fw5Qe0zidux+7BvEYr7v#PV4&D5vS;ipmqREy%`0^!XALFv!*#o zy7T5GP22O9RY5x8*5B@@=WSbIbQkS=X|@*~M`cwPooB757hP9Ha%YxxxXe+)nfSvM zj6=}Ei1h!TQi|^tT|jry|4Jzh{m6X$|0AVLJJREMoH-3*`P1KwLxs!VOyG0H+)Uz( z6|qh+QxPK30FIz_i5CzP5*PvfgG(fG*UrF3S%h~sHAyB|cD2yEB20RY;Ib)d^>}Cz z#7ENMrdbKp8dtS&?%b3)ak~BcRmZg~AnoO#e$|NM;CC{c&G4pFxme?;a=F_JQM!hg=&>CogZ=Sn z9Np9TZ*5WkiC?St#EF5Xi`eK`zPulR9~XFgEAt-U-1lp*&TEH2_7zUMtC$4URi=X2 zma)ADctakHpF^yyJ}!v;Fzf}5oR8o}I=GyWK#h=Nq8NfLh8zS6guK!rp4FC%rbo?-EE!`vkC zKN1xDX%=y@s}G;5HIh?;#$k&*2`48#-lL;RS!_o7iHwI&oQNX4!KVb3X04lovo;o! zy#%&}dR$>t#jiBQg!y0D6xxkyg!%9mjroq0&QJ8fb{Is;NSX)ETChX|g_M6*QbCdh zn28V!!%;EgzEd9vWH95vi(0}YMXB06wO0PgSQV^eG$CTv&_JC^*PLi{ zB1+U0nVc#bXUzC?Vo^I&?90VgE^D4F`I(ykHS%LsD5h76%LuNLxx&ZqIe{s+Jh!oU zl+ny`b*DrVKr}CHRr$?wUL=NK&y=gPSSQ;`Ui=P;F?YLJ%K-msXbD9yqS8%qY{aB# zxSzIj+SzD;<;<<_F*hxK(M{fapcpuxb|j%)ZdF~bo1uuj{aiISm=#|}GhHjqY`b0r zhQ|41UCk%4zH!(|-kFnmp@2;%ave9^Lv;*;ktGazt6l7)hq{tQAD_HrweL`#&i3OF zMWAFR=~>=K2#lXJjQQ?XmN0W->^F!2|L8G5f>tjp&Tk6xf$7aotW$_P9q)xM#riB+ zCrsMCVjxsLi_i+CD5`ndUo%CrJ}h|W^&^`i(rV-f4kEs$hk1* zWne0;ei0|HyQ;4HM0RgeWg)-@yh6SaVeZ9PRddI~mvV@~!mG5mwWaxF>f~%h@`nQ2 z!)E>U@FuTKIV(5nTvNY5KC^y}Eg2pjhWO)%C(Q3R9NOzLz;W=i*1OLI8GRo~ue zlFuTDs^h`{9X{zXgN6GJ?`P^wi=Z!qhPwk&Fb9wK?_!*J8GxfeN4fB~9yP<1&uoDx zJ&vzK0!A0!$#9^0DafuC1oye2PP|Wkb+9SZUui3P`0Xo+pot_J018I<7IrP2(GV&? z8~8;hap+$uQ!M>EM$Nz1F(d%k|FwB30BrY%jqpdu z4M1)WfCUFag9D!*1K?K!(O3P$6OhJ}0tt`&KUoEm9r+_i1Tw4!ew7aXyc!^$Ciay( zn29=w1?Ygs9Z26E$OjI@JPJ%tL;Q>l+X>=i7!O7Q2IBxjL~%pENC#_X1W2t0cFf6l z5pzmthf07$pQwT*xkI#9gCC{LjDaCyLr7*;p{Ck_TvlO9M?pFf;a$ezuPY(XhXLa5 z;ZoG0=F*{-)Ikug_MnLNz&k0A%mJhl5F(2)6YMdV6POK- z%-4=8UX3iYiYnKR%8ZDr3T7SU{BRCEs(FygT4!^< zO7hf(1e1;XGqi_uAS5wXBobyOv*0PdXa&()2iRgHaUUnLd8LSCrf_rwiybD39VbcX zgy==2$ay6@0z;sH$)ADWKDQz|fCIE-QXI#VKT{`1ai=+RC;cl=6&g>W^bGj)l%gY( zW~`I;uRMhqH&r7ePq9}Y63|FH^X!yEtDqN zGcq8(!#~yvpE3b@J=|T?Nv~B3^Zmd$8(?cCsck`K?}CHR0zj-|Mq~j1uBd!+q=W_! zL0_>fIx0Y^nh1d)uLT?%buO=rYiM|40Gu&&i*@!yxoQ?C=Fl;^g0RIAJo?Hp+8SgH ztvevAh$2zcEn9%ab!x>x0t)u?0qi0k2FaM3{9-n8;g2L1AI63}qBcLiYd7Wk+$4*9 zrtN&Df&5&!JSB=eY03ipZNJ?ROl@WBkOKE^FK+>o{6vv_2B-r1LXU-JH||8(R7!-a z2~c-A2JSjKFbWM55f6J3Js>^nFGdmkcHw7ExKgex{D<5)pfX&i7DXpIqO6aA4Z3bW zOgT0jb0vuEL|m#8MCFY}^MXrvQtU3~x{F;x(Euyo@2**20xT?yF)wu*DTTW(i9;); zNi0F3DubUd!3ZpM>W5KMcE8j7!E{2Ggm@ z*NI`Li{`_N8A^rO5r&|$1(O?)zuN)EhAK;T1AC={d9J~~OUkapD?o|1=?S)}#D(y* zm9Qd}=ptpYCS}y~V0kG&!3H?_00ftQ7)Rp@gtAILsHzx}DyqOTqWwzr?NZ*rs`M)a z`2^U0{O|HmmDui{*`Kna;43;1zbW)rS{&3+z>B-l+6HzCfNU@mCy|yX5Oq8Xyu*rr z$*OSa%19;FYV^Zo1=PqMR1Hj4r0!QJnkmPq*FAM28TG?B&(-qFmX7h(9v&2#m~nY^ zVkDj*eFOb?S@(Lg0rNzu0tg&22sDuS9Hj@`pHE^#IqM`;e0D!UY6m-Uhiz=hqMZnA zF(^;@k17x&aWJ!N(BD#A{T^~+IKcGVE>ErQPbWy>bLIP4)`(LL*Dpm!4^|?9rP*`2 zU6XKpbe_%@IlQ#Zf>2I%YT#|kO0h|V@?VbE!_qiwm%i~M&VOmJ0mZ$g{Aa)-o96NN}K z)IlReR=23j3cAZ&Ci|v3tORi3Ds-=J+Z=?#W z#@i+|P=gtcfLq1a%ZDD)WjeUgu;tU8Gu0zrh$znM(oxkG#L*Rm*lxMfEIZsqCEi0{ zXf*fI)LY+6AA5{%%$OfEY z996+Rog#g~hOH{K$BXv9A{bPV>dlwKOuh1@SV3xw))(Gu>)%ixqSO28QynZfND(uP zIN(7TBVgDMqlw+%+KicJD}-A(n0UpGdfHBrpBN>z=rId#xg z56Jfq?3;5UzoAb~Vua=3M#!TBk%u(6*!9O4)F=K~W0oGX zhic{W@=efgG*-rdN$Cg7vL{s~G0)*(p$m1}dEtYqvwX6rayzG>R$B6XG2nd7e>8Q@ z*-Qo7^di4a4b(Xd6$_$E4)@318TCz~4NNXm?4_ z;`%xbA2rG1WFz+AU_9(z;r%njZW5^mGE)}*v+WGy!omWmGWW5Y!yS3B)2`}idY(P8 zjV4>R^w>j4WdwSElCf|YC2=C6VdCs{rp96kWxki8Foe<95;)*)jGW7h(!<#^P1HS4 zkAk`VW&#ZCU5?3)$tio4A3oE^2#e+u&n;9m0Lk-%e4>y}D;w&%tgT~5Yz;K^emmMD zk9^wh=xFWGef%Xj*@nT-uSIX5^X3>)gD#nEp}$^`inxd{Z?7hxQNq`XH#3*_CM$1m zOXSxn4_Nw<1L_IL3)HvalUj@s7~*=LEj+OmGwFS&uy^Q$6GN&MwO?4H@6vr3XraUW zqWO!o2IPbcPH*WYLjwxOjEX>f<|S}ekhgy_B@T6?m>_Q#KGOH*e!=Wx7{WIg-RN%o zS%c5?)`&g>`a(I@!_`7%H-ggp z^XtdPD7AI^d3!h%lgQZ@}1y8AOKtdbVsCgpG{oK0(eL<2$9MW;7YYe9JtBZaPUZh*-0SHXx8W7DJB>PijM;&*KEh4 z;5B??+paRlH#!n~%f9EKkJ*Ew1wh)~%bs~F4A@CpG2vD)y>wE!mEa4Mb%zNe%~!*q7MP^YIr0 z!o0l1iMZBTgZK-_;ZT8~;7lTCgCeUu5|Cx0x`A=5M)9ZIxARZ&W!$mH;M>E9TP}xN zA*R@uqv+L)*kbKFzS-z0>Zq#nyLIY#MWYy2quYw3NSUv9T78i^LU+eju=2)m>_+!; z{s~I`Fy^3pJ)wJLra0BUsKfDCvwt6x;W#^^M}@!llBjoGs}GtEkKTQE(-HTsm-iE^ z@ml_OA^yN0LifS5_o01{`{NJwxQPscc;h@w+0Kao(5dKQFmGnM5;)BoH=qPHxKJsa zJ<{BR`YPT1rNH5(_VVQ&{D2SUZGXt6_v`6T)0QJou93I^6&v+~~`0rKF z^P&Ti7eNLN9dJk*i_a5ly(D-J>;LigZ_Hyy>V4iJaM9sSKsthfI*=+N>F4FE6!rTE z>O0aAWL7Dp?%yc~H{|MH;LR*#TZ#Qi=^tPqI=#-I*Z2CwO*&m95FQWRb+vv=*r*4Q zh)~*TOFRZdqidFNO(GTf`Rk20tZ|`88iPS^2%g%3d=`iOpW#fkLwQ_y>G>sCz%Ruj ziAW;WEcN4QQMp_}4$lZu^-5+v7V8Bh%7vV^EM^&vdm5%%)0tntHLOl_TA3$WLtoL; zCfnW4|J1B~WCII5w{K`&=j+xC!ka$}zG641$ji63r&h9k#^8vym2A~-v9@T);NgSh zcHMkPDPEt5qhL>$b<;({(+qX7-BlW^Eicu5d=AWb5;*QxoR=IZn6tA zg^ZAeUt9%P4aCND2wrDqHs;;`=7mm_W#l>4n%qdXd0p$w zUw`g`LFLsC>KbXwRUN1lUQOGLAAmD|t?T_q$xkPQ_+AVe{Kp(pi$PhRAS0OFYFyN| zCfeNfgm2WO5MU%Mue8E-D%_uWW`f*>Dl}zzOq$RWoWmA=i?!5RQo%D-9l% zI$G~w2DzN{(Sq?#QU>?548N?R*?cdc5E-MFB3oRooa$K)JpBN0xt$@8J%#L7Z4)=K zQYmCakj_p=9ONO0(U_fL z7!+7#5|_KGLc)h~%k4a#Db^ZU_`!p-BWCxXSM(3<5^GicTWXo4GWR$nE}M;^G0H?k z5s)Z*$zvBEN+>W#RRZ7dmq?>?e_#yC&7iXy-|VGj-;vEpWkBh z8uZYmH!BF1RQ$>4CPY~x$n=X#7pcDIFbq8mRocWEXi-u=ql^xwRB~HyLeQ7&;@ql zFXd6(q&PQ3|E+bJ zqx_9?2=$Q3>1g;5^MOge7$_9tSbV_?wvdVKZy#ucei#b-W$R3pFb>e!a7W`AXggK>xV+ zV;#i{+A?eCALSE`?WvCj>ER0h&VNc7`7BxHyeLHbi#dNagwPIzu&pxgxNlVP$mO&=| z=JeynwBbR4*~ou^J9frkTDmlg*wTTdGQ!o-bmIzEh7z(daEjDV_Uo8Y88Y<9<=Q>u z2n54!1T2Fc0ZPX~rYJjnav?IAsi*7sHiW&;Biw}yaB=bK1Ej0XRlx5Vaz=o9mS*(I_}%%NOe%B;S>iqkRaAl9RrWwT+@=oS!l8p_=#Py`1_ zv0_@-czXeB__-{l=|?+xp_^4#{-h))%{o*0U@umAK=qSPro!-(GYhrLALI^%uMR&( zv-*OKCRa04&=2=7k{rEgu$k~Ddf{NF+k?c zP;xE<_1ndZ;@D({nKD{#EzMM2WF*Jpi}MS-$VvUhQ%vZQE+HG4W%;+bpf<_wi%Nl5 z26Lj6-zttZ0QFVh(>vWt@zR)+f>JRbtOminkCy8}LX-(Es6K+pv(H4v7Oun$i7Trv zDWq}#POH(KvSg>dOs(w0tJ&8dh>$)MYv4Ko35jZft#x{)Gv3!tZ)sd+{Qhn}M~axu z8@SJ{X&)J$k)S>(jLoEwnq_{jsy#Fc+Ymi}qR0fy9t}964!)PrK9)_P_~V#!g+Q;z zy|LEn>&|TXF0b40X|!{xkvf9`k&$^>t6|GM3S3iWfk2?K{&Tc7c>dhQ41r=5a2PIL z_{V^p0J~|JlV#F?N_~G#UtYCEvhE$5@oR{F7SN&8>wd~io(6kM5-sN}mBD3VL*W*? zqPH#bV$%3is3i7&mD_P>ld){-+0O;1tJQ)HiQJf&oh|^Yh zEYNGJ?UO)s2o+&5WWhFJc#>IPdUy)5NP3{5>}g@AtiSdpf4{F@%sE`YL)WU0m`Q^f!Qj#{ zO!Mn96(`xe%NH-u{ugo{f!tbA2sTr!Nzh*2%|R2$dr}o!E@9selUGZv=S8Gh+jJ}w zcE@4bofFY}_yn_jf-x=Qr*RI>dAj5$cY`oaByj9bH3EKUo9WtVQ1br^hCq40GU*#G zmWiSs^<7HcmRGNDk8R#ptzz>T*R?t+k**4|la1%6C_2|_YOyEpODrU_1xrPwO&~_I zqbA(R)qY0RqoKyiXMbkber2{(ru(26{)HPJ%?+4*VfY2a2@ufH% zcFJxx#VcN+i^GlNW6tLddpsE^9~?GVYyx+Wa%x*!dF69%`F2bW+O%0Ff|HFh$}V1Rg4< zv;GoB${Ht6cM9Iq{8W9TeK6-fi^DFYcbg+-fu?=Rfky+REGcL1iGMs)Bt9Ew``uJm zmoDLt{c@$m_U*~ijBys&1U{eskn=?W_)bqxl*(JaHJE?S&~F?0r^sF=SoAPdy8IOM zK!KW0KlSRdOM9iX-t{a2JYgn(qCHj{Dwr}MRWxsqULY$A744VscS3v}pZ)lCNq%v; z-*D}3pS`$GHFIu(shS6o=kM?P_dN@H5k9!*c7c9z1wI;8e1*8#9~dL^Ir+0VwW~5D zalXNkI-^*i+zY+u*q6qmpYi)Jvx`3hWQ*|QGTZZu92@OoP1YDm51R;boiyc8cH`@-oYJ!h5kPF$r!12I@qB<7zg+qve zKmY)4p+Vi_z`Mw}8Ug-60y8$P!wxL*y-F#+oS4GPA~z+}i5TRISb)D7IYQDTnt=57A(L%me@VSAi-|=!sbXqGW3Nf5N6SR4;xbTYcV2cOZj`ed4Tfv1j z)T1KS*#Z?4FRK!JJ(1kj4)j$lQIWJge>$akDbcN|A} zG>ml2M?7psY{bTbBuIwvM`zSXib#ol14NlH!&>5vXUD1<{Ogql2roYcvi%t@To z$)5zuptMPxtVy1%em~yvt-J=+)Js;FO4sB#7Q5 z#ov_3;9NzAM2L4hPEth2j||0c#K`1)$K9+&V!`DG*A32M|SK5PVhgGn2a#citq%9jG)bm zj85N_Pv>0D?gYsE#0ahN%?gcAggnI!RYm^PPfrBV02K(QnMDc}&;Ml32TjfhtHFUlj-X-u89lR@iw-gz?#?-Cg3IE34=bgC;_ZQmZVYS8--8+06Yl( z1=);=D0~XRqYz2tn1@1^|4R%Rv=1!G6oWWW7{Ssk9m6J#2~dzp07!uw4L%ig9NTM* z`Qf#ggAWr_mIFmnr<23v7=%8h3FG@dEB!h(6x0c9i@id#Mbts;5FRGbgfb19Kh=#k zv>i2l3PVk^ASDVdog{X86$ezR37HJ6U;;2m)Jnm@^;p%IAk^dIRHaA=OT{OyvDKMi zq!GJQ3OUtOrNkIoK}~fM`ire1-HAX|*J*nSTp%!L>DU*+5;CBONTsn(xj$@WQmBQ~ zpp7M$H78KJpM}M)BJ>UtDFY!{AinaiT>ZccG+UgITAfhan`kgKgo^F5jK8%BWGRES z5L3Gox`_qYy^UI9%|Vv+g{DOw{z)*q{izobk4VT9P526YloQIWLjLpNS#9mx>@ZxX zb6YlSqf%;Jgymc&kOY_@P$tlVrb{LAVOf;5ywtrr%3a->NWB9I4oAA&7r_)sc#l*d zFf1Ti3~M{Rg4t=>UQTb<3> zq$s63^o!DkkKp)&nYabye;*PCEGoeNb8IjSh|{+3PniY$m;v|3*m7UCfu z*!#d#F`?WgEQ(toFnmRx7x9oRh#OTPFeoTJvkGAMd)h00y)3?uFsuvv^(39a5-sTA zgCp5}*#dvL1!QRg5sa2D&R##%;1@1n;0s#3-4vo2J#vktJzfkfS_Ag!1!z@ae6w2i zh2w1{V&$pYIVG6>lfX@J&p4whq9fm?jR)to4}D2Qc`B3bmPgvDtE{#{y`jk-5pW?>9v zSc+j}!U;e-W(49|Nd;5XgVr_RW!3Fs%hjgSCDvU24x$5YV=uf3GkccgsAZZE4^BuP zG0g%=HlpqQSF#P~m%wLoiBq7JU}s_0{&^7sQ-y^tid4XqCdfh~a$JUPXi#ouJ}l?; zvWaP~W_x;O=pYa(!UYOugLs~aEe& z0vqAXDp)_}>EJRR%Fx};7~8QPX_B7a35n{_*@a!0g+a)Lz&7l|&V?>m0xl@*!*=Y) zhV00e?8%<&!JY-m#_Y`2?9GO3OIU(8ux$QXm<6%8gs*@CUi~gZ?p=GhSl|M(ilfz zSN)V4pNdyOx|`;Y1rjr-(ek=T@!*I82Hw0+3*v?@b2m5GCohO40<@2QAvd24nqhP( z_lr(&mW8|PTMF|`RdR7IX%QbEMyYXw=!CBb+kZp3SV)08uyB^Zk_qzhMhC%2ZGvvr z-Wg|gB?oj&XNmWg?-M^5dt5lt8jTl_4g<)87{ipX$Z}FIGZJ9}FE=n|Z|+JD=SyeV zzfO+%o`^uW1!viU_>L(&{v!ne000=g_dOUC9*>GS=L}3BayUqJn3!wWO7d2Z@q$k; zI;X-kCj{}ZLnx8=nn(cvI00VR1AK1)K&XkMQk|Cdcg}cptT1+RndgI7_Hhmva<5$M z?r>bF0w?G~1muiSkd9Gch&(U=>2QE{eu+Kt0+t8_cHb&w`4CCxp0q{zyGo_Mxk z_X%bKC`js_&WsZP02FAAJJ@*ufPgs>p1$gKhA#?$4-Pe``s!wRJ@<<-U%4`;V~x^u z^vJoB#tSwT0GyW#83+LBhyYM{32bJGVE1;?zy&$@3cgzDsF>%cj|;c2xTd#zjH~T8 zz=}v9`>Wy%3IKrq7nq4yhyi;C022s>mT;D&8uiRKidLxWVz(Z)hpwd`=}U)S%C~_f zkW@S+*un(>0ie>Ecm)^`{S&}>e(!f-hmBM)`Y7;p#$T7UPIjhOd3*ACl$Q0|#{}31 zY0H2B0EhvcAO&le4iuP#sW;e=PYz9h@GL;>P8(%UKKJRLy2aQ?yDF((Xw zPQ-~(00!7bgvuxPdh43N7h!Q7KtT?gPB`8doY~cj4kj0Q9N0JPAh*!y! zDpx*)1wa?em@;S5tZB2PE&#A@@?^>Dki(urNB$gYRAQwi41Qv&-UQa1H03d^9 zs1pMPz*vCTQ*HK|(`2KTP6vOY96PqC+o>*L#;t4j?#P@w@ftnEx9?w?m6#|M z%QkRNpm_BFFhG}Ok`My}#CWA}DdLp3i_^eGtU}=06;(h6tQscmbkgImNK%Ni|kE3r0MJ0U$5RC^04=c zyZnYfSbNSc%u&l%jD0r`fCJN0vSQNY;34CUXVlPL{yAD6u{Y6414@*gfeE_Roq`B~ z*Wg!$_@~`@zNBXuc@Tb;VO+WZx5rGHaP$x$zyW{&AM<&K3ukC;qM>^lBB&vaH!-Lo zhyD=8xLs|O9CTq&1=1*FTz3G_fQlu>!Gs(S@lwbh2@G_A9trZ|M~h5EQHfLrj#uN1 zHHs4dlsQQMk;Z5ff0z zam#>D%2{5RV@jG*nF^|jqjyU(;p3aQB-J9UM@p^pFyo~}(XuGWSl7@XRM%3)c<((O= zO{5GIF-`h%nrc`R#u5Xy0GtpCb-U~sQ7dsE+5{V^G}lYX9KZB2)DeYDGRzWJjTbI^ zHnHx?o?cBIBRVkRRti4b6a^DpuchjQ2fgybKmedHN^^(MdJ!gjZj=Qkcb_ISm`_Jd zV;&6%00GbxOTK#9+E%SIXdnKMPClzm(Z zq`XEhMXJEjSrc(6joRY_c071^fe4_-C@%yMi{d)f*h?UOE7SmfzTj1AO;?0VC6ez=396x~ue;#9D+mD$2pu5YM2nZ# zD}?OE8csC930a8WL=?un>uAn;48g%sKrs-y)nrLciikpLPy<=;qJtj%ATM;m3s9I~ zD=;_(2vg|6u`rD#onS*}n2-idD9h7k=teKbv5Q%(B1+gO#U*C(5*tZF#?tskUxfZ;79o_-6rniAD^~F< zdGz8R!Pr4I!h#j4;DjbJQ3*=OAr5d@gBsGH1ubMD3s{Ik6rj+AvmC*J)*BljyVyr0 zp7ASmWMTScqDd>x6P=RW zqb>nD&NUj77e#!G4%rh60MN`AF(BAOj1)IK9ipQi{b)xEQHVi+^bmzOL?A+{QjnhX zqar=2NKIPOnT|B3GMy<(SK88$#_{H>ZQArd6msjjBhD^t+R$G^scZ#8CtBhm82_zS_ zNJ#L?vAkzIL@pfU-g}yNy=iokc-O05^UC*%{z^1vd3pKIbJDYynH1R1AZ z223drm%9n6OVSHY%nn^q@bgqe9Ue?)`Zf5|-yJ?JrlB=RfQV5A+P0Pw1=f&goS?)S z+-G7a)LIUg-~=m7_mt|{5_>%1MOChHlUoT$TWp(&9s)He-^{Nj)FyEg)}RS}3#H+Z znr^qZ1Bd_s?*#@RUjK|oBc?rjHx?g@CeDI|R;a{s6JdoW;;@AnzEcZqn1d!%(Qdb7 zZgZU*3S%5|6Vfq(;tm1|b7I1aJebGO)~ux^^y}=^dmMnvnj(%uC#aEU=*xoIoIHco8;S3WXQU=ATV4;Teh?ye7P8 z)j%NNy0?(qDXEx)yqSQ7IBde`J~4Z9w$63-_|H3y3-!s5(hD_g-ZC8r51Zq)=-pPnI}n1dH+p8Pn(o@zt+4FK}c6OAw*gUP-LB9628sQ~UTxZp$_ zZuQPIP$Ctxj|jA(wCVXJ;)kIaq zKwW&^YxE!+$lCtl9M-K(;6RiaHV7Iv2NDhl*^NafXhajJj7Xf|5AGi&P>#zPOHahY zov7hN;KHd?L?F(DbO~KtAmDY}!Y05S&Dn<+UP3Am!Wg1P8Ajr4Ok&-ni48u5SujBs zG-5@x0ww6p{zhEeCftpx)kqeWguq}FPl!ksRK!mx3{ChQ00duL2u&~Ig(_e|9B9EU zN}d|voX$B7Bm$#>2&1M|qjs?2O|-%r!olpZ0wqMA7KCB~u^ohzU`dbywTMekumK#h z;``0S?Zx9%0MLN2!Y0f?8Yp62ML`$^ z{$T>%bq$7;BWW07O_YrZ3}U0x7Y9Dq(>vVWnf1*j+v5V`9M?Py#2k z!v8r%Sc+w6kY#EFASnukD!5M^NCZ2f46dlb#I2ip6iY!8MQw0mZe#94KNIz|TxfBaQebOO((G3(k+M1&*)N~ouOR01o+0qw{^vhoDWWTw@)Vq-{TP25UL65gqjgg^jMU_41D*a3$=V+FS0 z$jZpWLM&_WYG!<@%eW~?u!7#Cf$^aW--xWTw&w9r>{>9JIQE1p*hgma=t_h_e)5GX zP{Q$TBpYbL$6m*iZd=akENbvtge?FbWAeFA#5o}Sv8jSs{;W#uL41_!Lo7+1 zR)-Xdk4k7o3fx66Yyuo;BowT{C4B96;G}|_E7=}}+3M-7W=2Ye1Se4GJ9#W#EUTF? zt%nGJP!0v!)T_!`t4PEj0L)1YSXG(0j&F)`B+bvYg zMq0089AR6JhfO&-@U?Q8g~*qSWvl1Ak61=@zDMO?xy zWl4kq-|CQ^AZTLUExruf*fe%7HF)&jfvWBhvRNFpj#^ew(lgwqb)Kfco%L?cNMFuU+BUL>&+ zs|FK`j2fG-wcK!Bu|ci=4Q?E6tcxYC5nv#qnJ< zZ06l=8{dTh<3;TvMvkxo&A~w+pDjbs!Y<6hAk4xpl(H$GGAgICDz7ptx3Vj*vM9f@ zDz5+lP=GAovMSrb5_kbFm$E3+f(6S0+?yUqaT!Oq|0kX~nBvaxg z|3x!9^GZN7!#T2D_(d-;B)X)*HHStHpff@zv_hZr1OR{pEHp%Sa}JP%ZUO*rri3cM z5U#L++RVff%Q}i1XN)eX_w$#;FFArN|VM)NL>I%hR zd=FEb-Kb=7NT>qvZpl*11l@wlUdu&P$2H{6HG8;qT(m-oDe!=>YXDu1^Fr@Y+{%~^ z=GF8u^O(y(bE4>lG-+71!;-LMPc>zSN2@kRSl87hur}rD_Sr_;AKlJ-alY(+r?E>ME3 zLBSl%5{t08kKHW(oOf ztA`&&{oyQZPxw$&IQ?-oVz5aQ%p`xW;lGGPAHpi|t+vMAjGQ2+qEfG_j{C3MCXbo9%TdA^RYoOei-S09Zu zHnA|c$vsL%U$jwhLZV=LsvOI2$7x0|d1_oamg9L($akcJ%%p1vh!?P_v*OmI~m6Lzvt$wU&r_2 z$hx!pz>gyvV(U~a$-&fwwWy~P6aWAqfvh_N%{BJjsXrHx}`MKSd610lPn4D;R4OWWsKG-m)|M%rCuA zl)F=ey|PQa%47a~`bY$dtGH3z_L`GKFT_fkmmV${Nl|+TgoFIplRcH&{E4FHzc~FK zM+A~Tg%b*PuN}fB$QnWWf}ODMxIq2BqrGNoJm3pU$DbuNib+#{K14{60Q_}NFhU|6 z0iO)r658TL)?JB%|xj)!5q-a zE1V*&r-|%espfBfMc{sO`~K-gzfr_Ev!=>%&@WH$n*$yHO0dEkQbArDH>hGiOISW+ zOF8xDMd#ad(;K|sBLoH?#jjaUu(1T&Rsuj2@-=WEDFFaL5mdO4VMB)xAx0#~>ku!A z7cpkk$o{a9#f=|9f`kP?S4fj5QKnS6Qll;auvo@4Sy5(9jU8>~lt|H|PM-@YDg*=| z08E>VY$R2xlo7~OSeP(T)5;f3f++x;_^H$CR78AD-weJH^Kj$7J0HJTTDe5v z%^e1X4pDlq0|4;+#PQk&4vmzWFoAM-VPsH@NljOnTYbal?FSZzKVNKe`s?l9N6cRT z{`>hf@c`g}o^ndWh8hCHsFf|EQsXwD4#|%K0A84Hm&)|>MY;^-%g{s4UixrD{XomG zMEwNP#Q*^G*oqA!Zcqvb!7jQaye2S-4mCso5a1R1Q1h@C|Jv*D!y`|!FGCFbBd|Xa z3)$rk02@US1Gz*XjIqbYk`Btrt2O@Q6WQ zOGErn-sXD!*FzMt+G=4eF1kgFsO0!4mlgByaAf83nwBJuKLq6Ci1=-fQ$68rGQ-6h z`-zqCI+3UobfMq`q$wM?7`hXs<#1=7Gt}c}h=Qg#N)Ic}Rao`D1z08q*N~`^@Un22 zxIX{1dDEgL-J0wB^f2HdUUUik6#!nb$Z%hFnJaM(8MkQh#SeE}@wxsYM||?e8Gjt{ z%sG#om(uKV9P`f++q{> zoS*9$xWM~0aD%=WTx<4bnolu?gp3&lL45X*DU}cqhj8HwUs#A24g!WToM8=JC_@+0 z5QjQE1P^N{!$Ju05JViJ4`XP=A`TIUOKf5eZ`i{q262io^!_0Yk(k6HZc&I#)S?oP z*hDXiv5Gd_AsNrO#X|%lhgr0u6Tvt}IC61`Zgk=kujs-+l*t5ClwunF_`@0!;t5Ou z!w!)+h(P#(3Q;k`9E~W)80z65GMHf^?U=_u3UZS`d?OR%m_<2uF_U(LA|T(0N;7gY zke*y+8$mfrFxF9wrc@&U7lZo|=~`!z z*+sK}rK{XDw^z;4W%F=|^T-3sS2=GE&~w(r95!2r&TGDJoz?`4_P9Baa8i?g6)Yz; z)p<^K>hln%Bi-Th`A=$&GoJM%C-m@XkwXw=6o=3S{x7JPP;&zGeR5y|79Q%6Uii}& zoCr@8I$_V&5%h2{0M*#C8BoTlRGRyw=tK)D&&q-Gf+XGML|5w4oZ_^lJk_Q+!8y`- z#?z+vOsP(LDp6j15Sa8yA;{PgFRMXkNK?I9gzf_YGgU<=tcZ%#9CC@MY@t*kF$e$< zakJy7^*DpT8+RMWg76n6+fC_({3hJG`tY?my82LL;ZwZ%G>bKetF1}?a1kEYE~FJuX#!YLvYXyKc1c!+&LAkO zSKS_ox6L^&bhdRQ&mM;t?HWi`Ymz=KG~{XHQiV#8cEZ^P_q)@%?Pzkl-S%{sy!BO% zZ^?FF$>c#mWeKcFIDsXGgpUbiU5N<*umXbkx4+i?FNKYhU;R#pziYMdaex~u_^1c~ zdsxqhFVc%b#cUyzsLfkJa=rAF7RAF6@Mvzl84Yi^IUP36c-3=Y_28*JR4b26R#vpc zvUnw0JrhBItR4&-2fbR;E|2fyV? z&?qR^*f%)~aCWiGUCu5Ev~&&*R;T{+DF;9Z%o~1~q{^EGbhA$P8%xR2fo! z#&2cwoaH^=hsb}0l6v?A0RBiCB@2tfgM4uds6ZhVG9hkMDRZPiSlTpEhR%*N9ULwD zM#xvC^=LwD8k2$xLM!P6nhC;+LPbGUG2z8t+_fIiZtB-M#&oVnyy^Socr)DA44a@s z3dR&{A;HGTq2oXhRiG;iWn~G051`jF2ie=10k@U0t)E?+rqd*v@{gy}*oO4_B5=6q zvQiNqEueZbG-JrU{SDZEhxyw1=CHPbG;I;p+bgh5ntQ69U?#M>qv6>?p+iEoU2$A8 zEN^+WHG^x5duHFG;WA`l-u`X1nMS$~nYco3fi4znB0Oq9IY>xcHwf)K$bR)SzGt58 zs6NR<;SKQ7Epr|KoN(YbW~~DI|vHS6<@OB~OphYspB19$s! z>o{RF5BmRTD+f`(D!#!#v!iZPi!NCjtS&IT$rF(egb8tYfR{m zF03ytcmcZ#@BWk{|0Lt){H+1uLiOmPys+aU_KzSKL<qX{hP0KEdjQeahT@GK}zs#?$mbqxk>YY5GP1C=8LA@Dj( z3<^6?_?n31*g8Uw00MP{ty&?j(N(e;; z?T%0kM}rLS!U=z@3(evIPXZQJMCnoxBakI3Y;P+TDgY#}5TEW5?;{NH&?oe;0|C)2 zATHuWNB|uE;KN3y2W!JD%nu_j@eln_EK1QUBykdRq7pao3sVmkV{xwf1jFPd{X$VJ zhQa`*4kDaRQ~K-n4`1MFfDLTBkar}df{an$TV8@mxideLm`kt^u& z2}eWVHX_Q{ASxOx`#$43YDOcJF&pu&4uvrvPfrQy4Iz0g9L15;EW_g*qZw<<`B23o zPa;4D#3Og_3?ot^>EavHLL>F0AGty#eL?|2f=G@nDzJdzwn7m7WFv$RIvP?DWimAI zQ6>ISf+f#F8!wXgHUkAe!n1B6JjO+C#6kuDV9-7yD0Si|ff6Qbq9~2hB#`nfz)v}} z(kIUHA%GAha*!Zs!%&*dEMj5Id=euq!!9onFYf{@!xHHzQaygLQ~FOcuE!Nlqah3~ zDoE}uKBe=r(kt%%s^D;Td%GaP{jcAx_~paL2I5G<@jZowekEG;~a+&1E!juAWcgZ?k6 z6C=h_ES~f2qSF#RgBP~bH^1`%2$2EL%ODdGEl@@)MB}%P#5CyxKI0Rr-19z)&}i}# z5_*6?E#Lu;YeS%-!QjFv+43`;%_UzlB^&f7=2I+Sb2KFI8hzstdY}V*(*i!AH5p<^ z?4lqIg)Vj@2q6P9WdcM)wD(HXEKYPQ+Hyo8GB`}3Lc3E&)l(q^0wjkLCA82a>N7v@ z6E2E#Hir~5_b~=FvFdP>E==JEd~*jb00cS`H*S&%+zl<{utG>9OWR^hhr>>BYdX8s zCW_P{eKaP3G$v9MEqI|!&lCe#fa^5G5DYRdTaqXmaVGwBC9KXwR`fmf{&Y{h(K`7r zJMU~dPQgrl6H(Kn7Yq`*+Cr-!?K9{!E%4MgUX>^_Ra5oxLAUK6J*+)W!3X#gQI(*z z?qaaMbRz;)C9JVMxs+C0kyELxSX1Ik6^}l46-IYJ14IA~9%CAfwN;anTf0?Am33K% zb;!Kc6rp5NPr?>T;7m851;*7URHL|5!dX*-Uh5TIQ-VRm^;(#9IJmM?e+yqjB7Bs9 z1gLcbfWR_q!UGrbSW61R)3xHet{jkz zMLSMO9d zF%@t#wuL*$rXAzoANVj%_&0su^4bwMIxh|SqL_c0MMjm{wUg*Cy6CBjQ(nLAN1p z0TXnR#xQ~uFbe=uV8%Y8Ks~d5ALe>>f@9%IdZ#xd-ZwG{xEc*OC;oMk09YoD^gnV~hcUN?sdsRJa)$Y_gkwyrh~f_5F-{Nod@b>0S(ZeZ zn1QR;=H~Y|xVYOsB!(Fh0uI6eNYg!fq=f;MZ*k6xzj$B57{@>>iTN#e+jb>*0T9YW zK!$T6RMjUY*f_>mA{3N{>o_ECcrqe*VI$dmx&Cl6^x!%KL=QYdSbt)YL-c_mxNI94 zjGee1rMON4Gvkan4=~vQ#B;R#G)W<=jMYwoM|rRA*fS8=wm!FS^*B-R0CE{aUS$@F z;bV~#ID~JRARd_|9?}R;nRj(U7wn2L91|@;St5ENdx3F@7x)!k-~a-k0c2pRn%P+S z*fMrm#7_A37^9TubmM3_GiHsBYxfXd01;f_5DZ{dAL5+n)tF`2ZXgyFv)MU*8OIJ9 zBHGs|@t{gJ3!aSwS~ufvcX-kg`TQ1o`g+-$zgPyYc_Ns}nV{!$HmG;D2by@{q^rlC zE~pnmr<+!KpiCNqUOJ{n%ARIgoCM0A{_>-sdWWS~8h{$-rUytvewvv#F$wx~E&3saZO6APA|&nx2ljsh9enwz_wcnwzdEXFkWQTRNrB z+I_y7tN&@OqbaCqVy-nLtq}vSQ`)I@x~}Egd>o3V$;q#=I;Rucs-L>6d%B?|k`w}9 z3KwF9NT`LH2#cQRj&KNwY{`m38<6bCl_cqvI-9fcsFY@DjC?4JL@9_y8@A~PlsX%R zRJ)d*2()X+mD=dGNgKF-8;yWFx6ufRXgiX68?{#(xRaZU+{l!STefrQwx?UPYpJzu zX|#vCv!A<*ZppgCo4R2r5OSOTyFEL#nOnDsyS&55g@!_zsdI!%$b<;u6&gTJ83J$w zhj99Ocg)9l+J}FTD!>iga1@7re5$PvoN*o~fOty4iyFXTy1{4Kb{^Y*LMOpF$95ik zoHi$~SBHH}XTT|3!Vw(6Q_90}g2O{RrlbkQ|GRu%d~{^|!mFpkE1a$)1f@rOf^bU5 zO`OI7JHtsl#v7-fFkHwd9K#{X!U_DmZam739LO7orluUki=3-9yu_P4$FtnYrK!ga ze8*>8!O7aO&HTdAe0y$Oo*IX#GB*~8X_)MM6g&dIc@$`Jc@`y>hht@<9|Db~Om-vD zmdzHw7m&{-8j%IvAu|3tA|n0n64a9?Bb_aSqBBFXClS9*;1yuu6^_p#0J>h~8A=j* zGmsffQRLCP&ea!!)A6ub>YLFk*=ADRGqjj4cHIGCT_M)FJuH1CWPM0WeNN}ud57JP zMU$rjw*-P$i&LLnvD(Kq6a%jGd1(j#8u zsgvXDa^y+A-u`3WJv{hMc3vT9o;GcsSR>xv?JMHf{Z%6VdD;EY<$IZjUN}C4n>%Ic ze;#GyeeO*DxBg01CiRRz3WL4=Pjh*_t5O)xt$5mqfefh`#kur ze!^Vd7cAaf|6JusgzA&I?nij+@15n}KIO%p>H>D_-CgbJ5Z49z-d*0~m45PX4eg=+ z?lZ&aFO2v+)lwBd=i8m|Bf8{GxNl)Tu6{?LsdB!Yc9l3taw-o9Ahd0(IOH2;>z-yv3A*j?W9C$s$%KlJ%5_S63N0m7HS zfdmU0JcuwM!9offI(!H*BCkUcD_Xp$a3U{^96Ls2=rN>7gA+%Z6j}15%8rLNu6zj* z764r^Yudbt)1fW^uyXnoxT}!MpErB8B=EQYKBTT)Y0< z+0(1Zt71hCDmzvwT90Jca^wZl?c1nwF&d>>H|ET|eES*%>(?UPzzzo!ZfN*0!o-RV zHf@X;a>JmK6KbuD`6=Mc1s`)B*!Hu=&!E+k_7ys_=hLY%Up@_ch?^$;ob+$by(?FT{JOYyj>n-pSH66ALQ2Oezl1vXKGr0w#c zUjYt?VL=6AMxSCGHr5}92a4F7g9%zUqGT6l$l``5o>(7@kR`{TjOpc6vWSD&|(L z3ixWDsOF{WT7Z@sDyi}P3M{gRj=Af0z54ZNpGC%srLuCN8EBinoIP9Zp3ZGs zRo>doZmim$h_P!yY+q$L$hb^k+xAW&SVJ`SKh!YcRt) zb=9uM>vh+xHO&>iu=VnFp-C(K_ER*Ao!8Z9!4>yXYo2#0J4Nx-$duw@)X820q!pffHhY+jTKEKmSN0!dMW@}eS# zjM%*_HgJV*(PIQb*hZMdAOHY>Kr9Zz3tcGk6#&rTMtJc^fjlyjsPV-vD0#_BTGAyO z=|vm7ON#Qjp@u?Dzlp*t!8s_iA|9@laVqEWJh8EfSAfO zrlSxDEJ%Tf2%O*`cbF*v0C9+*3U#PN6>1?4QHY}^^{7S-DpLnh)S)s}s!l~}AfkGR zK_s=RScNK9ky=!yKJ}|$C8}7h+SRR=HLO?t>QtLrRai&(H4R;_qlEMKeY*uVZdR;gn>>r&r(S->`yvX50PXC?btvxb$i zqK)ic0~^@RQZ}`qO)X#jdRo!Om8`F=D{TP_2tc~DBC!|+DMsO2;F5wWj06Qq6sZeF zzQUBjWNs>%drnAR6uQqfr9fH93xZzPoQWKSC#UO6Tz+?!+m)v&t4rQ>X1Ac~HD_~h zxg+U@7d7aeBzVs|Ui(&bzT$unBgxTfYIwxXWif_J{NNJfE0X4&WqlJ2U7RIQ}Dx>gBAwmLJ{YJA8aX>O)?4-7(f6Gc!3U&+@>^#%YDZxBW6^2MVsuci*FW7 zn3n=XVe#>9i*6Wk2K^aPF>ZK;HuM}(#^(oyipnYsbWQMxKO|P#D~Dc6qrHNk^5|J` z;aT+&$w=u@bEVWj=ZAQP=DfwXErP=_EBdd((3D|2+Natrg4Ia*^P#MM7($ z;Cj*y8n%Z(?G`Jeh}l83_Ih;tY@0-TkA4=>ca)c8YJbMr;qJ(|ee%M_*!tGUUdfm@ zcs3$dhTZMP$h&ibJTub@{?_>>c<>0_Z=(GBCigy|!8^!n7-ss)2}jDpZGyLAp?Nv` zE4Oa+Jvuj693~gH$*H|E@0z4qaS?Bfl)1QWaF5(1C5K6(84dCzaXZ^5=L(wBtx8hDI?(SCH ztw7O2Aprux-QC?O?gR=HC|n_DJk|9J$xUORXJXb@vY3dTS-8y0?;rXeA(tnl^PVjZ*LOWh(va=Lfj1 zk)4y<_?~S-b*Fwj_f-}$bPYc&zCnI$+DmH5d5l=s=GbLy6{$~Hqmiz8NPPXh_6e`!LkG{yLB{vB6P11c)}XX--CfyXjN#9tov;R{y+d8>SLUp)gYp9$8L`EPCRW&5+ zZIE-@^EC=9{uRc2?OT;isUG9%`pdaBkm%PJQqr{`a&aQ2HGiCL6=G9DntLC*Za>dJ z2%T*NqitZ?Uc^5O;!DpX_oWd=KO@EDA|NJ_9)wY1r9srFk%7)Z)v1wj0#RNjQFJH~ z%z7~6wMhDF7mi6%6PHL!aS06ZNGt&ujZY-FJIZA(3Tco91N*$UB!t$w?Tw?DonSSJ|5205??5MRQ;oa2vuBsk3PCU;ouFY z@Eo{ma81mE3Y?rVmb5h1Z4JJ+=P8gLC0WB;LJ>zQ5GMlQ}95ZlkWLN+Tyq1&Iue4s>vvKOvtC!xa97{PbcvNPE!G0-~0?3f>;z(749Z+tc?qz}6nToOpG+-SmXpGe6Kr`JX;qu9Z=0@)63W$+Q6iS| z8y@#1$muc1Uqmg_RN}39ZmbO@;XfupKTbrfVzbRpQe4*)-E-l3x&Fu#;q;GG0<{#5 zr&4dH(wkkfW*u^>eZvZ; zkWf0u3ds&G{KQm5z*%gqmdS+0Y3Q1^;L2r{3ndXN4A(0(RiH_bDEQgq{?#ncv$Lf1 zGz)#*y@t~DvDW4HREkM(LDYS5PHZt$uLOZvm=;lT$q9d=O!;dT$C>+%^d0^76v-WB zL~(HGz?Twn_R?}n*B5zUdrHad2R|2yLRR&Pc*1oG*iCy}O$X{tM{Z5WaZRV@O~8_-i|e8x1egYpu4wV#aqphmXf;ItBJ zw32eSlE$}Ey0?(mx6+=q(wwz2YP2$Nx3QkJu(-EzTC_C(E>~E!7-F>?9LI5&GytXm zeLEULTZtts$fc;MW!!~L%*kXms1z+aA3d4@mgSJ=$GD)ti8OT$8ABWo>CJXy z3sPlw5p!-*%ST=-4LMWpfW(dFWwlPGj7}Gn&Q9h|jfKwf+fFjEF2BA`1&c1&gsO9X zY#>8cSRakxRhK<>_b0vXNyhGn)b0kK?w8-YlX0GJ?w)jwo=o?i?D(GC`kwqxJ%wjI z#W=mC+`Zhnl?&69A}j#R6ompgY(DSjoiITBC(1xD3JMsIn~I5te2!obcjcg9i=cg| z_&0Ls4g6=CGI$rzNsVGlMf4IKHLJcV^fzVDu%b2^3dRi(E{h#w0}zm<5`4el>5g*kO5%%o3eBsfDazX$gd9B=zBs17{+2g zKjDFR_hk~Ipq%4i?lx4T0OqKPo|}lu7}O{wm`a-fxD60Y)6?2glQ=!}G7aeCM(W@cpj*xvmI?91U+g{aRUYk0fXrwz&W>0ZcSA%Ltcs;Hbx6(ODQIX zF6FogmmR&A=-~n;Siy!KW34Etm<%6&$zhj*Q8Bzn)2^`-c)+r_d3-qS z6;~Gh5FlW-Ie+r#(T!`3G%YEvF?MJZ?3OU8${M||87BFj(J&`%q-z&cB5Eh%hp3NVqT zM`DK3e8SP{XF`Anuo+xGPBUK4fQkafF1?ERCN=c^(;!XT8~}o8IYIe79&}`x_?&Yd zLN~D1q;l}+QJSGFmqmGN?EGzu;@uVUQ*kO#27Nvz6;l+^S8?4Tq%@l;*GOAH*%YF{ z23{z>9xm5dWc6HRPh8||T;!fz(*3U67C zcUeJeS;=!*C2?7;aam(_S?gk12X94>cf~+!#mIBTByq*8am8YG<@LpiHQuT%@2b7l zs-x$sbK~%2eY2Yb7n?(PTO+(%V_I9|o?9Oix277m zKFw~;UTl5F+g{+^UeelL@!bBBxV_%Ey*azRo%sA4`d?~K7$6L4000e*@?YwS1@OGT z3n1Yn0Rq{ms6_syp8j>7TmgW00Dvz5K%`0pa0CEC0pi-?0DwCH5Uik}@XRHinn#KZGfSor@J+N7ws`>)va z3^n~1+Vnq(P0w6Y^2^ljp#JHg#{Y7g($mwQ-KO~XtpAQS)mN53yG{RvHvKC$b+>m< z3=AMEE0GNi|DsLt7>O#GP|eU};kKLDqqqW=Ln zJ-bc+X*m6THk_UTr_U1;v$M1R0#2(lGh5HqhVQHYFW~g|zW}Fy^`?`H{b#!A*U9n0 z^}(~=^nWnj^nBa?@4lY3CyW29Jw4o>EY(|o9vpc5b#?HmSZ8SP>GA&d?Ca;Dp}&6t z7#zD0G%}Z6D2T0QHv(7mWH%D5%&`|mV(hX9qj0L(i>3)U*^6O_=Gcd`WV!6ea#Ypq z$MJNY?8oy@a2zBEueuy0ihrv)NRs|}a*!;G!FiaXNalK&s>)V-n5HRudYG=O%z2by zXzY5FY3fvalw}$4e2{7r&G{|IA*!|({K6S6P(8deygs>g+bqHkBdTo zo*oxxWuibZpS7n27F^-~)Sfc1QT-eM^3U26Vx)qAM}3~F)(=~q^?yfunr1KiurSQk z=ulECTOWlo{NJ@Fr}~Tkwf1yI^tjHBuFIrbh2fJo-2yNKP7nPz?TPx28g((t`G06n zG*_c|8XnKu6JNsh1P!~U&qszB+?ENZ>=}VEwrY>-k6c{^-mHKM;0E;)c8V?+05ZBv zqtPgc*{1%0>!&aMOB$0~j(lL5S_4WXD$OD!XXcXOH-0}uLde`xmT7Fo~zbkE}^?O6*KLhoEJ$6N{0udGiJ z*N<@ax?k;Q$Lrpyr_U5SYehY}{h@M{^!w79{O{7$sML?8vjJk>0UZ_Y%6|7+;`e=r zBjiW7zm)&Md-pR|;f>+Fg6CKBUn;cC%jdIFbYd5cm|8C{bNHJ5e-{W*-Aq@@l$p-G zJ9an!+x=0xLUS&#to`e8#!d9ubyV1t#qJ{&#Skzp>AivgJ@OBk>=WmeAMPJ|pwX9} zKaJpUvgIk%`fNE8FI^Zdjg6j@xI9(BtP3)1iBWIsBh@`t@*4&kb)v|&A@Ts;Xi3WA zpTee!_;HD@PVS}P*a#U4`S}>P@_n}i4jBRrr8p;MYsxND2_cNictt5&k4aS$x&UyT zL@GTXwMH4W7aSDSk45;=W&EFiQscvU^w%1RiHDRrgx)U*%EL~V=7RTXL%5O$UAR3cxXrQ=i9 zBH~18-tR3>1xoA5_yg}XI}@UqJMq^?eC=EI7R^MSS8HmRz1QpsBy_w`pqh`mVD1o& zy7<}sO!0XdL=&qJ%_#d*t^={iCNlI;hXDRz;*+%c@5 zDFMX|7JN_an!6Xb!Q>aQa;+vhxinW^XfJCh>}xe&1PHUyd%6gjY{>BzEoB!t?9B;I zr`yquSEWcjr|TpTsc!8R^fc8v0P`OByC2@x6~`K!dCJb;N!U1FGjsGQFBQ7n)V`3b zaV0U=ZRlmGSW~c*9&uZ7qf#oGjN%j+m?nDJcGo~XU}G6Lx&&?WXEo==GZA?A2|Oo~ z?7-{(IpOBJsN3{)uz8 zl5Vv$Rr9-E+39Q@kgWY>EYeL!!Q)KO?q6sd1fmf~GuOZnE>(;{3 zdzE9EahNF_lE~{#KSi=S`k{v-nEe2#VKRoF-6m^xNr^?Bp|z#mcSh|2hH0opdy)6C zr+Vtpl}6Hn5$)osd~Z|pjH|3f82m~ip(kB!yRSJyRHm$VAAWXSJ;9kln&5(H zM=k4R3k1i=^^S+=NG2_b%PzdI7Ce8#Epm~{L%7o-ege-#EipC;%npuKh zw}>W>V@YI6uJd_f43rQ>T`!S@WqIY~@1b?j)HBG8(XNWXon!lSIC*i)DFfw_qI6#T z%%Rkw4zk=ezUrw57&q!o;)=)zntf&z=tvW2B&63hWgufyuhE!sO-Z51kI=5E#Bn=* zNi>dKjNwPU5UQ>;hFIk-y>p&vAhv9;n3m(6hEUHs`pSs2yTDv(rOMntUrDlCDSJmp zj)H*9TC0U08pH-RcPbXlvlr;5Gh-LAfca&lA&Dt(A0Uec}@92v_> z_tA@~^&(pX&q+U8G~Z^uAQG5MO^Jz`MS4xwKqD@Q!Z(Z9W4xw=_g9zqn-7H;Ti%CQ zIm4NMX64K-`2%* zgIAp0GPpv`&xL{mi>I0hyFVh%3*0^jWMCEJ*MT09+^*8HG>5l$KRw=GqJF+A{I@lVtg;M{ zdfLNV;p-5RvG*3`JQ2gz^G}y%e~Gg5qkh#?c{*c5qDMIkS4@AzZutw^(mKc;D5wp@ z=pm&}3#_Z~J_O3_zaR80pEtqu6b(x_4I`XtPJSZud9vdm1OP~Ef_|%yv-@_&8P!CP zKE?1f=!(|!Lnb45{(cEZJ#k5Lg5c&rp1xq?m_q8jAtx9Rk`ou8xG*UP^x1au1w)xm zAY|eZv~UPTHxzXN3h0i&3yL78fDoxdSSBHaAjsQcQ4rjVtJ{&a2FiCI$>stDuSH6q zK)GF_c-F#gm?K1kAR<8!T~MSFJW9p|reYdl-~v^B3(1qUk!iv9-VNt;iIi1^%6G#E z;83~lXhCtP2nb5N7AX#oFsXrg!ed-cqQ&l^rmB&KrqTE=kXH)P*s2huYfg+#4cw?E zMlUGZ2M)!eh~TY>itUa`qJY0SiQx@`6$V8WcZW~MP}b{Wr2~Nfv~kW6@p|%OHi=_C zhl|?8srEwY5bOW;B3 zBo8?ylwv(rf09Sm9!|v>0a8t4b%oYm3H^0Wb?8o`Ur%MEL_$e9VC++Alv8Pp58*Fj zQ+-pgu}otHPosF(Vbrzhic_gfwNMexNTJ#cY1MS;dofIx3{eS)N^UwGWrps0hJkCQ z5oKBiXXkjWgIX%m~_(UT>+mO;Q0`MM`vH8@KtH&f#oCXP)<2Bf>h zW(S^TLQhj^U9(MNb7p`!Pht{6Q`!E(nel2l!IbGC!MQr88CsliRjDX63}IU1wq%YZ zkIFVl4F1wFd3qHAvW%F<)szfitV~%f1^~bhkavn2PP*q`i{%$S;R4&uEB&ZtPOe<; zLPE`<}*7q;x`v6ShQOxHO9Gc{AfWlQd zn6M(I(~9Ja=U>BOy6aLJe-h0Nbje{UL5)#0isl8F)uzfQ z?p2uRCt@|Fxk1joO|~)K8D9d9Hn0y=8%*k&FU?wv-_`a=gemL=#J6DkdKcyEwmzOV z5QX@c1uKFdiM>98WR|L!xn+3ske>J7>&QZyQ8h?3r$KMu)|o+?#w+U>rJRAAP2bU) zD16G3c7=$I(dN0{u|BHj^}6p#gruZ3V58LL zF1NkZE6D>(l1_sf9h(V1)iHjrXTk1}*>k0R6tYrp9uR529&41|`;djwsmt0yjZ*hD zj%4{1E95q$JMRO@V+-G=olZS*n1%6CUyO(BMF0(HC+r( z#TO?Qjjm+B9v;2k44>W?NV(1rqP?Kh2L4toajLhCyFHSS4{sjBye0dY@~b{$>u+#_ z?;O#>Il=CI?WH&kSF3etk97m9gM_X%A|oZTdY*IfGFBTt>W^>7raJC%9Mf?;7yF2| zaJjgpCbFLFyW1Ut(9IMt#&K=qEbJ z>dWmN-mM*aSQ(*!4gj)?B^ZNfzbJ9_HJ|l$8RZSOotgY`2O}SeEK5+Mz(YU*8`1=g ziN1HKpN7RlT{J?i?Z=10xu8}D1NfWDuchsH@AA+Co7|_{<>fj~$Rvu$`pN<($Y|Qz z{rff@hb9dAByGEpyHa5EgmF3xbCvUU6St3afqp2CUIQ9n;;a!%lCf#W?s1i=Inq&Q zu~BxXDV~ur;nZF+y*&7>N`q`6?O7YQ`(RA}L~MVr$rka^Dyo>WOvP_>b!pGL&Gx2- zK{XG3rRza4GSP%hWesW)0F8@ie{GPo``T~f3KMh}OK@ed*TApV@y%(qz!_qdF=?MV zT5==J=ixZAPa{>c$lT!%h>sGf=#u;(R9geDjc!eck7W&dtf559Qk1KkMD@d($)5(5 zpsmUnFZbPN(KA1@m8!89jEnu5>6vL(*mD&n`xt)^p!Y{PhsIhmfzae=e#T?&Z05b} z-lSau_%;DKQ*`ddJwP;NIra`$0{b=51=frL;~+PMOy$Gqcc+gfG=a3V;dupt1zTh1 zxFythMAq;QuV}Cr=I7tJO+57zn;wnA(_Qmh6~F!wufQBSbojVtGIvr?vn6dP=Slc# zfN0ml=G-7}<+rrTOMm;qWZT+0K@Y$1fjkvT@`g&1f1l#KOm*7q?XJMYq#WrzkL-1C8-=F^8 zL}Ib&P7hisuSUH_t%9znd5;GDqW8qh=3qCKx_25T(8kG6IEyibn+)z>3QD$*_<;d!R-pc*A`yWBBH^kq-!F|c``enEg#1t za>v_5%N$iH*&`b1F;3jYeK87u8WN!+R7pC_l|qzmgR5l=NfU{w%)g92?iA}`;DZ6^ zEhwFVAxgX>zRU#_NyLzTPR4%_5}WSF2M0`yJHM!@C?Oab{8&^rfDGaT8k#kaxk98I z^?ugdlblxF8RE$@fNa%&C!V`t|L4lRkVQJ_AP2(he0@2<0vQyYgG3*tC>GdP` zqcRks*OxA(f~m4Dnfx{I8ZT&FQ+h*EtdMDBqjp4{uAE5scU%#8 zj**dYINW)X2S4aMF*v%p=v@9Ze1`6Pt_fBL5PiLNPWo^@aT(=Vb3U(~HZqtxDQMH4 z2uC%=tYv@<(_K`MN7J94t!rN_;QtVKh}xWkrI%l#)j)r}xVZNEahr7h_XX@p`-cyY z5E}i}cGCs+P|S|i70~(z%9`Y^*A>Cnt0nv^Qu=F#+G{=;3aTprVNcxrA~FsGE9D_5 ziF4@YNj!z;#|dP%bm%qJMF)5FLiE}ek9MX{Ugd3Z;_lLAAToP{13;gJ7eo) z(;q)=hLZhwC_$O#_rJ6$?}^3l!>sT99-=rY@0}}+ zjaW*4EPnGet@D)pR|qHQal-nk^Y5RvuYWcOkhR56K$nGvUC0c<eiM#0d<0xYQS%0@KmqX3L__vEATXl0_hy;lm12zjj#IX>FTNwhDq9X?zi zOePoko!6N1J184S`nfPsrk8T13VJ40u#7r>t zD=ou1nOf!9U?V3cT2(Tq@inCw(nfNH?>vuh9XHBJ)`6tzcNdnug0IlvcWQha5!z>$ zmX9Xi6bBxGyzw_%%1CZlw$cKwQsgZ@QPf;iroJO2F)d}sQvzMv0rVO=VnP! z#+F^pgITQ29}omR7^7z|9z40ZtDlN-s2uEnvzqKj;%cfQrN|;lVX>++Xnew)JbXM) z%rBR=#{9Ye3O6*V`zyu*V|?^Ccrvq!_Vj#9tfYrG{^{YPt_&KfVk$ER&K92pX7zz) zH$+NY+2Fb-d6|$&XB7eRg#A9?bt%uyvJlEl zSI9fRn!&%&O}<@iIP2;@Ln#{&+JB+mgfsXk0{=|C`GW+7VD_q=S;y07q+ge$%)@>$ zv7rZ4jQbB_uD`?g6DdOaqV~{Us$WV@L7XX6MNln9Mc?>!OBy;JvU$*2=S9GP2m#*U zYqK+2M{0I{RyM1Vn{XzhL5xy$JitYa%Z?_xkE>2XRO%cu1gX#>^R(yu)s;a^FvI* zXP!D>o-x-X^IzBGH%;*j!E7g`I7La&+=F5p@IvNl|2!l0B9wi4zvsgTaFBo^KAJ&J z9%(@QI~wXe2aswu9)5tk)+jG*)Ql5X7QpNC=rEUL812l-k;c>T-NMWUR1B zZm@R#eSm=T=vln2qcTeBZsYHqj*_!vVIDbF-Jtc2tLmSoKW>w2_tR%wWnwnAj2$ss zMbFfWE$6^fP_e*YbQN7rU|m9vsw9Axn2mMmjl8P4U!uGf>{&jt4x;Qh4z3kKLBKJk z_OUp4nYcF2x7Z|N$90u&MV8Qtgf22vg;oUF7M9?W^mekRq(@nLw#OZl!LQz8V-|Xp z?!UQ={XEB_9w(wW-6$FI$y(QZiMrrm00%OfoAptz-kd6L+WixuT~{pBA0%BJd$s-hP2EVXxv zb&%Y2qj2CH22*E}T&9ct=hH>q;H*3jEnEk`;gMwR0Co=;mM#en$sC4P=PTO=m(-hQ zoJP35>uKtBDzGX#5GTulT1~j8(~f(kQCKaXZ`2DvA>f?_l@!xfPK&$|854_l zFw;&UiD1Wq=cz%N<3?A%k#0$0d}hXG>PA|H4^|(RR^4X*0b6Fj=oIfe=%|HOgwIf? z;~SOVV_cuu?ipjhqqsZnTkLWCBj-zcMN|Dr8MFFmNVJwu$B^4LQCzI0!u+e&a$XNU zbKAHHmUncZ{4TNv@UsgU(rV`ifu-jB;uHHc$vhlX7RM zekWvqGtQddjg_usD*wnBET}Gn9cX4b+gtJD9m_(Sg5Qz>W4Jh*9Y$g@>8TOl5c-TV zW&QBtmc>X7S6FuGm0k_@PR=RCep9=)+l@as3P8~lgImX}$>Wi*pSYEQKS zgBKQ!e(W;U({WfkDl=Bx(4NYd(yC(37eu?1So@o0E83us%%#;f{n-1$fLT}@84@RPeb0PLz17jk&2l0W(v`@z z1C?t(lSi85Gcb8w&W+mB?SZ#6lV zRr1fxOI6qSrr4Lre-bPC^d_0H!u3<=SY9W^8KUb^)=eDHNYq|7w5tb*T06)D~$t zRbL=-=eyqf5Po{~l@FU}*B-X$wF!VFeP;HXpqKBJ6<_^^@$a0@kh+<53w|xM8Q`hP zNhj5xzV%9c8X!7;f@u8JpwBeoZXgf(UfPDm;rf%Y=WoqX;ft`ebD7_0*H2MXU+u5L zJ9yH?q^D%*2~9f(1yb%(e-hgxZ*f?j`iovQTf7oJ=%~Dv%D?KbDFM^YHyKb4*M|(- z#}7R%^&*Mks`CI;0Kn*M;51+4Nh1NUB?az)x8)B%rsK7)L4)#(&QS($+hpTwP{Bc{ zfRe1g3hl%sxKE?vHT<%#<7G2*QfJ=E(l3nIU3X9*;CP`R8ng~QY8ow^iu&JpFfL@o zJ0cLBL*36lP+_@jhQTPTWrXcnxRM-|BpTr<$2Ncv{UPcWQj9auB`q)j8H=M!FpMB> zivQFO^V2B6Oksv#gbo0r;{r3P0U5yw6r~Y2x`;Rk!Z=7#SyRzi7NIVUP?bigcp%jK z71b;iH65Pc(T!42)jbrIW)R9-iW=vNx_=an92Ctov5epdH4-H)9wn20C5-~qvJxd- zOC^2H=g;H14&$#A6m_I0jBu6ha3}6lk_<~gRwNTnisQzX%BD2qMnPOGYvZ;VNnQ>x zAChsS2Dq=ZVw@_LgS4VQV#3xEJ!od!EjYW|kcPzqYG{O|d&ycv_5-FAwS#+Es<`Z@`Wf{)60~dv zV2K}))+XXZgL4JAu2WJh0O4$0R5%?d}@Oki~i5Un7 z=2bMta(0K5;-d=C0Qe=k3{wiin&3HREbdxlwgR<&lBui#qYm+f{0j%E7ce-JmL6qh z0b3<2@3y{NNIt_`Zob!`d0WZWAfRAjJenr0#Csh6L>cxB*?|c8A`lDhYY^23+*WZc zS{I;fW-%AKtWY9I`sn4$N25V@^j==DUtN`4l?GyCGs?KVTxshz&UWcN z?H=%PFVrYa8uZD?qOHZ3b-y4tPeBph$)?Bk% z{}@YYwo*s2`e_NuX#+EPIqdCf8Uq^)o`u7B%ae?-M#rcTzjbE~nA2E64iOP?42B{~ zNle80S+ww|N~u)Z{_u;Ayn)zXW~7Fh$&}CtsP~d99(jw8jBc7qO5(yh&uTxnBFD;iW84FlIb!mU3_5SqTj3~hq)cpv(*FAb{9QEvL`fV``+d#&0 zJFsHSOPDAUfj7WWupl%fhXjx(v~B!@+RA{L<&(vSMCx|*uI#wj30GM$!A%K5w2S$u zE>2*kBc6I=S@OVE?3JBu-JtaM=?DEjsWd*FNM8 zeCRy;zQrxKZ2B z1EVY@?1x%uN!nEG?quBV7@RJJwldb$z#pCEk=#RN-w>LOu8glQjduX*2Ymo?Pox~68lKWt#Pw>bOe7_mhbqb}kD*W@*h#!sf#eV~15X?^|o_Nzk zDFGD1P)tY1bC&~-3Zd(B?iSvDg?b+pyKhjj9h`T6wHk-txqg_+vG|n3$TLr4+`USp zw2xWT&e{o=v4YcQ6^weK=e%b9m6_TdKCx}{jOb;*^cob+yL2SNR}+^m2c#9)R#*|&td)Am|&X&t>+qTqam&CAHG!qEnKmiS(CBy@+{b~UKSzrU>{P85^#v`yF@7cd*>UL_LZKyaG(h9lKW zHS^y*e_8}!WDrJ6$^2sk7ysrkNS^->X)0Ec0fWuJ>_*I{l>mlWr05on)e=h)d-mj! zmNo$y(k2Pi&vfNX%O>=2bdn@vWy$E&PUJK{>=13k{m4!8&n~`P9&20xR*g(tm1srw z&H*^<)Gx{TWiUu5C?BiS`UYa(!Ui{xt!f1y9o;PZzxY0Qb+XfKo1}+s1V$I{-t7PB zKBSD!ItgWwg$+GxPs-;AH(8LLX6LP z8BQ$HPfDWIzX7hj?;*0L_vt1kY#_O!9%L0E3DylTjndDcS*Z`O9BV>B~5 zx%d`vc^rLtlI697ycqUfVwya?F55ap${%#vw(eL`xL)YZyNj!Os7^v@#L=dme*8@G z7!3GvpY>+a>bcw-H9!Yjm03~AA^r<6#BpbD`swxB|In52WOn{XtRbi^nyb9s3~q%! zsO?=Y4l@w}p7Rc(9&hgd^g4X8HSTyxn1ZiL4EnhO6?u`AaG7~Y0oKd8D))}+Dy0%f z^WG=CLa9D056cP+ILXcN{z|dS9qc~O;MfUCK=h=Nze2_tbQ?2IUXIOsiyV3%$ar2l zl^$tdUFYPd4Id1qgtAQP7_l6;w9r@@)7q++;xtT*(ZQwRo5C>_mOy>nRTQ36BIjMiHj z!^?D7-DqB2_O80>TYRUT@lCbiuGsdu$w|G>jg*ObDYlK0n^+C(veYH;rxla5$W8>) z6ULoHb=jVRPJN;R^h9g9KjlB%^M0%PTMuq^cMA8wT{=-=;I5 zjbaBn?zmX0cm>1^U(E*?gMqXRqaN0l+-luo^8q9CXp*84oEDpQ#Vgbw{UgEtQlb{h z$+l1UH*_F3Hb#Q^T51`-U%ldi*)0*7T~oqegs6(nxQ4{9$$Ylgpw8^{X)AakA^+qw z;~0A{)iIqeXunH-17AdTh+(=WxnA&!$I9mX8eldvV&v2am(_7OGfQR+dU4c<$sa^+ zRD}7a_%n2)#doaRSsqC`_7pff86>NNhD13*(YsGd`K|Qm=8Nwg{pNzkH0t^PrHc~& zrFZ&6_v4&t6jC(8qtQpY_@swSAZbnWFRH6?(sdGto7=hmh9ogu@2eJX z(Z4+~*-B!~tg=Us#|)e2N9UtJuBwF9pae&K4JF(EXC5RisCu>0*9w9XWx^ho$?*+N zB7S58r^g@4^&Ub0Ty@5TWdq=Rb;=34E9xr+#@OV79w+~5PwEBjaZD2lR6+rZt>t?( zdT4lFJg&Y6oP1J#C*u1jEHgQjCT1C~w@wPW0R6r5(_8lW5)uOx0P7uxQXb3majNRA zok2;IX_$m~8|iF~IjPJxlFBa?pM^n*?2b$LXgVulhN-YU!&A3VdT+7O-GouEJP^vZ z_1IozooL{Xt1sT-!95IpvkL7EvL~mtqF7{k{CPcLw3O$S`YY;ET>R5akaaMY}uZ)Ve+(`_j#iYp$Ur3=qx^5@e zN1dxVib!tNhpF&Mu2puACoG@BEJP14Koj-d>H4Y zA8V;;TL42GS^(u5=jesazJkLG^Vf77hkDtR0Fn~9eB7MeR02uaUR}okr)&^X{Y)NBhHRMP%6TZFq~}xMhh&lek%#CZ7Fa>({34A8qVOQZ5~0 zO~`4klAy9!=6DYMNd_yw5p*(RLmvd8GKC(3K<2JxOkMC#!c}Ec{Lb&?8or&L1M*rR zb|>S#_5+u*CJqGC^hr?Ax3Tr~moM0R5j~Cp zISQ}85e3F6^2oiCnjB?D{*?L* zG1VC8%AB&r(h3HPLj-MIh)Fj2V>tC&6$l7bhd5v4~4epr8$2cYg(pnRoq?xH& z?=je0qOg6z%rqcijBqp|zJJgd$x#c2oT@FhcF8C>Vi>jMv^oWbfHD$OM*bs$#6kDt zv48Hq0i>M>@d)4)pt^eu(H0hblhAT%7LI8>`IIyVG-e9=*l`K%)J!8o1>&F*dOCha zuwjM**H={~<0`?#f%AQGBTh}hecw0*p?yLWmM&GEYm_(fn_FJLx+A?E-+rpkKOiFS znZ>#cTEQ(i?oOLMUQfwupr{rOH0|}AnD<_b+7Vliom;SFC8f>S6A=>A2_C%4XK2_w z&AWr)$tM-ofp&0seYJz!mWrPWXr3<-wl+VI@bz#6;eCdx!sRfgvTOut%P{OkkS!P{ zi(sPI1F1;M6X)$B*d+I`3{Ie_Xj5Y{v>RIQzF&Byx)9TT%k7rrFF|Ti)ga`I^;+Zk zo8G(ypf4-y#ntM6s52hmGH&D=elz+bXz#E}f!RDg_>$y}<Nwy0B92(&+jRy zEtNEA7(!$$F5me3T8>;Fw3$|m=@~tqgepDUCdmKODvro2gbpWLE2<9j`vxeDDw1#( zp9yDd!-YWc3|&#Yj94#jdStblzbZq{V6_s&`XaYO6<0$ONe#RV6b&HR_mV4Tw?u@% zh|J^|Z+o_a6#(B>pg<2CCjLk5k&5)aDjqvlrK>2l7mq30JY_hl3@jP}-cdZEwuJc% z`6gK_4bDoHMBScaYV*1f(boV>tfD#F77gkPWK{RWiVi6VWxx15dIXdcPetttrX`v0NGr%|WbE&>kXISe^{D2QPS8rGF8x&O+@(h2Iei5J!4W)J4`+ zx$NT{`|Fd_T-)dJbiZZ~xgq2W<@z?^F(z*dBQ@RMOjlJUeKY@Ds<<*sW*EVVKZ(i~ zNMEbL)dHwys^O8$SK$^=iR}VYAnW^BijdkARpfmHo4gjG%F;v+yfdw=-QWZpOM;_N z{EZ{07FacOWCkWJPcGAVws>yFQL-lB@3|OBGY{wjazxsPqS{=}OuRr`04Mc5U~-4% z!u$R=%}Zn+FK;D9kDPFrjrSve;0F>rFsS0+EunIQ%eGMl+jLI0Aa*Kf3Q{&otV~z{ zjCm+`a~9#~fL)xT%SMV3MU*e6?;8a%@g0-AK>wYW3}5eXI2#yrNHJzpHJe#5(NN^c zz@-?`n|(X%51fD;*L1lP01l2TYNu0QV>~zf*nC~FN(}Ep5p>Sj%GNWb7wwCuLoFeb z9m}a)5efB*B2AVJWDN0!-8%eH^vp(1amDqv<%8G>aZ$!GnWCe`5<(Vu31%AF!FBSN zCD^=Hf+jNPKN`s0&W2qDv-@x0mrbn9)E|Ls*g9}>liz1`*Zs=!3{#Iqha^9ICRrSC zAQ-AlpI0b5-84twg5{>;uT`Vi_ILeO?(?nzzS3{HSGni2-+xk;4K2cGt()_M5}u}# z#KV)Vx01}+Yy{*3{~T9=;JZJDDYN}d7qH?b`%;uzLw zdM^hGAOG$`;OuDv=;wWS^BUMH=q~0iu z{LgiK8ce!8%q9>Bhz%%H4#K4fra`$8h~fl~7GFSc;%qBgwlUPz=)BN4G~++*BACIS z6yf&M7#MVG4kQR8iIX3m&NF73hzFr zG?3AIM9|BSkO3vWH9G_^=WZP{*jBEWby1~)nR2k=9fHNJpVm8+Re@zx{T#AAzQWXP zN8pE)`}=grv%haY!=NpjfFgdV_MG}~KvCv@%?-}f`(W-4w^48)%QZtm&-;q*#9)!K z3$ZmPH+*ebz-sOrW8M^R@dCqXG)gOaJS{ka+{KVo{HqQaH@U@8Syw)Pl1=GQ3cAJj0fj$d=cu8UYOA+>0o zrw^ry5}kh@b0FCvQS8zaXp9I}CJ%Y?igElPxj?}aql|ByKN0Mj8ce?x!zyePEl;-n zWf5Cuu9G9oDNybJj1icng*Ll4KYN_r#M^gjkh%#??I?EmYts3=u#Rcn3ADRL5N{p= zg9Xo85WyCt_@(myVec-V;(FIc&v)aV1{w_^xVr~;cefDS-7UDg(|F_V?(UEv!6jIN z6Es0Phu_|Hc0Ki+nwmNDZsbo`RclrCece}oKZlZ%At#ONX7)p5n!wjD6Q5})UVbwB z!YVzaET#%M_QLw=$9{o{*c)5K!RN|P4d{i~n5vQyCO8)2p0ctT!R>?5op>wezXAAU z;ssrK#TSU_NVdj?^fl%-wnx^Id_%frkobl05?OjD`%38&xHb}tWTFyj5WS?NVYz0m z9t4iU+A1de1oovis@inCvgpL9;>7f*{8J6NG(kwG@Y{;@y zXj2uj{P%1C0C{9zo~g?5cb>Ft$cd2X{Ej58am|2<7?U_cYl`A%##nO<)5kMAS8?hw z7mPOI6ui~5kATw2Dao=`1y!~XEU=iRB$G5`u!SpGsb+`7GMJLiqW`hFCah*50%>tu zYP=0*k=p<_kB5VQKy7pJBY2Kc`j)O0MXE$=RNC-lTs+KvKEsCL{dSk7blOp#uiP8@oTN@ zf_9ybVckd3x`tjUS`ZEalw}ZSgpLGE5;cTQU4PBOdc#wHBg}d${p%)X=t{o+rYkr{ zH{{N-{yIeriwXFr4|JCha%vJ54+NxGhS5OKQ_js4FYCs@%yeDM7iA2S+tJe*5e#8j z;<+KKchQ%Rqb93hAVCB0JsTWt0~~Gx3W5m&6B~le<>MTS#7LI3_e=pE&}$uG2u6W6 ztnB!5a{97RQe>VGN~Q;39Yd96LvL?DZ)QUP3;?4B&{x=i1)_>+#AebXH2z947Qld^ zyyvNN(8}m}gtNvG%g1|*V(gzTrEHc|talVn_u7qkpBk^Vo$xjWhfEu9jl{5mg7H+? z5m`rCfue0vVO3%D6wcMw2fy?)*lkJJaVW!a77r-G znOd+5aAuDk+lhg2$Hrc|!R z!4;go$AQ4eHuSfxOuM2fVvXfxkHhe&NypsLE*FlR9FBVNgfCO6SMO2{VQ)AOft6SC zGf|L7H~ZC7FFFp%BQ|x(_2HqgL$#rJ z<`H^~p`E({f&nrOLU+1$<{#H?7YS?`KiCb;88efmg$pK-%~p}}U5JsxSx*6A8I)=q z{4Xog2iNK4>|rAjP~ZqBF>!H>;%;TPVuie&DRb8B!Vh@VmwO`8!l z{6~k95 zFvhmrouaNh#CWRk!8LlfYFH_gSF9r%dItDBx{F5D@!LSE1f^muS2>PPfh9Xes8#+P4BSa!+pkDmhj>z zQN}S_qDlNo-T!(7$VmB5dpUe;_vEzm`s3k;JeIM2_Z~(O9AV|ze*t|%Npj8w{8^GInRU$9IH9|E@nql<1rN!5vrq4Y`5sys^J ziTUN|1x|No4=2}fVCWC0%w56u*U3(Cpy&6|SoN|?>&)6m5BtvG63JCC-4q?k^XiLv zj3b!DAS%y9(OQ?kp}QfGwKbD(FK~5-I)$f9UuUl%rk(yNL`VEOM*{%!D+e`W&E0V@ zCg3VWc$bK)T`@o>I>HrrvflfYPmh$pm-4(pf;r!`g_TcICtGQ(BK^KYP+}X}(Ho2s z$AIVJ|C!*ciSd+n?OPw{dAs{))IbuDV-qK74Zzqf=9Y1kro!f%3}IjbQ1NFp$=c-5 zy)MGbJ$F?`@{?vh7VABws7z+cAkK^NC=dK#Fq-ieCha+08#;CC-SCs!@lyqHJAmBn zjGt=NW%6lxs>}Tp-9uIpfwZEMVd@aio2QW{0d)ZXh=QQ1s-Sa`zv_{IA>EiAx@h|Q z@TTtwjP`3-prK&eofggMNtsXKPl(eS-P7>lb;#}MlRYXkQFX)?n(jSH_Cr2;V(v^R z$NVqqeoxQBf+L3~&{LD|3xWnS-QVe9VJ%iXCPf^IxBga|My&Z$fuKNp+8&W#3N~ghRjbv%~K6gT9bT@iK_NMvwcx zm1O32$qf030pMMu_W0WYVP(QT?fcL5-(gC+JxK;xKYopp5OU7*hKE7|)_^rKD97T@ z<78iJ4BiTruLQ7UzI^VFy0QAO`o4xF$mAVpD0&0l-!-VlS;FE;kh$(WAbIGS! zi##HIYv=?-8(vh^lxXWy)0AXxdJZ%<4 z^l!m}h+0rBX~gPu6$z=OB6R~Lyk!kBi%}X)r&g_R23p5-cpqK1@R)+lKQ3vieS&fG zESu|#4BKr=O!E{9%iimO7#0G^p>QBKY97 zcMSzvnu$_)z$vPGMG zNazwpUY8a;9oqjQa62PM(0ehA`FGQOPKCAC{i}qNkZ1jmx!RiiO!)8=dAj4gKk@-^ z&z*`IYqzOdpD@#P^wN=IwbXMy{dh3>nx6k~k{W6Blv%kXynR&O-|~1l*dL&EIQvQ1 z=a}(i=}C1z{yprWTj%}b)uK$`%S|n9^NN~_N7d66tKT&v*-MK~-wSi1cr{S#-ITB+PT?B^lo5h1RiFGSSu{-DVJe2pNDho5+{mM0E&CJCjzw6~+yU{pLez_LbPTenj9)e)F2KQ0=BA{xUp(VCTArbzoj8o7S{+TW7Q#UDxCy?hCP~r z<3LVAANTY6NP!Tu3?8ERqA2NTieL$QsE?{_D0C>C%?LpaD=D9#<%O(xMV4y!1H zrX&)KBkU8B@-7ozVRk@P?KGKMnnhL)ljZ=d6@*5vtsY6X)x^t^g7eOefL?>88Lx(E zfo?-$X1ju(KMf?hzy~**s;Hhx*( zb7GU`_BaCakVc44Gc;o)#U_1kA3{ye7A5z4jmUlIkQeBB2on$ktDF$ZrQJv-uqT@h z0WN8B@RueC-J>J5Ur%AqnyA!uHxa?#7C(TwOC-`!)i&kQ_zg=^WTJ89_9o^rFdOL= zbaz7ulSJbw-i-|Lyau)aqVN_YHqJOzbAF`sWgK~6rBjIJUc-$@nI2XV(+DW9YD7%R zSZbi}nCzXm7!9$|c2yaFL1P<7RhCbM)5f2Q9cKeN=4 z=x+VxC1Ykd>5Rvvuq7%P6uZtsWsbYc9wKKT4o1RQC_O)B{@6-PvU$zR55vUbevmMh z#vZR-0J0Fc8!rd@SE^#>Oj6YyYdtRimVlOiiTKb%^2VS&Hsv!-(CD5nK$M3<1TUHr zy0@uKriUy$;ViAa3jmOGki&V#rPpJa&+hPzkFQcqv2?TMb_3{ z#$wf69>nDW0YL9+)dma#kekkz;$7FwP}t3n`Bg%dKbQ$ojFgH%41C^)tti&SOY9Vu z(ys*AP1?lbM>PQxLx+GY!h?nHv3puoHk`=lJEfUpu`11 zJ>}GgwgMz>4@t~yLqF}AyyONcxzEW;q84J&K~o`K*AckFVH61omZcIohi%UfD^S!n zORm`o?a*2OVO==Z?x(D zG{+`{ll@|NhH_|0RpVQ6uYZZ(5ObErC-nV^&k8WJ{3=o8ZIPlxz)!IA1tS{Y|+U#m3JHb`4^{YZ>{LQIkLPJG2*N@D&;D|4|#|s)<#~jry%!7A?HK^!=J)C-NlIWfN`%LEul{h z-!mus3>npJw;=h3Mx5k{%0Ke<@5jrjuT|fBTONdXyL1atV|~JuRjdaUMIPRW&0~IN z$Jy2iki9?ec{u5`~l4KeO z5KZ6v3R@_8W-H!Q|8;+@vY+N8O!zgQmF52wx#Sr50B*F(}xPFQP!O(NvT@)zX7yC;JV}x_6Fr>uddl;H}*Bc~838Xs= zWHY(nrt~Npdq$55G<|gF0dtdWML2b+r(AGoKIm|aubva!UkDprZUgg>@}{jKM(~~> zfJ{hLd=LMNbcHGfesQHJ1)zKq;~^2T9}aVoZJT9o=uw3!i7oG1m5MlOkAtljT7+VV zLC+OaEK7+!DvrwwOMXIg;aX;6eg@67)ThgoM`JxFm;FUzbhekNs`Xe zQ*UGU09=svU6`OQ?`A2$^QNS=SMPzYWCW&_k}8A*dkxT`*1jRA?Ib4&4qZoG8}ZdS z+5%ZW9Qiy2*)AMb`xF)Ho)JUgo5vt($zgCnQe)3h_5>sK9QI}aHoa;S?>99ntq>{$ zXG$NqJD9#ab*u#I3;?7qipXL@jT4F&09x-et-POm@8?Jm?}Qqx{&&5xEUJmylY?#y zr)FReks%0ClS0L)cycD>%b7j%xGSw|JJ92vs1#UF38T z=NTQsm!qe$bE9>1W8}N(N4Q|L$H72dWW#pbT7?q6u-=$cz|*n_xVZ3_y1Yf7r94%F zG1V-PKM!zm-XM>TFom5S8&=jsnm;^g&{%5-u@~{To3eOOuuU?PD$I}vY4AzxAqP(~ zeK}{f3E_>M{P1;NkQT&>2&P3zqh)r_W4mQ!1A|G?DbSkX?g3PB00x8~OlXcYM$JSb z=F(pB`~of1!fBL5I9yb?Y_sz-NjAcH>XhGXk)vD>iK@8!fq)|c^o@5HRpm9xk7Ec2UxyZ|0GoD%_a*s%>nf@XkPgc)wv#dO30m zsIK_7@EddP*3+|K$ zN;jKDn!ya}$)+NAu@YL`bb9H{QRy<69x&xQDvCl;`*Sn`I9yFAoY4X~SxemVEtUOO zApM?R0jEMDjI5F)EPxS#41tA8L(5o$s7OkVt?8!+S$-m8 zpH|fz9?gdPN6f3&-#V`tv-DvTj;#{6Q3Ck@7>RIC)~Z^!l<9>;OE>El^9>L6H!Tz7 zqK{5{AN|Y}T3ht+_AoUuUou+o8n_YLJjfu5$b>^$dZqxMG));#4j9g|xf7g4=$%k< z8?*Z0?g_>bj`*jCRy-65Y zPMks2e{OUa3$aMNc0_Hmd(TU${)hBqhOrm!W&jOf#u(4`_nRp*cnvku$d!-9 ze?-wer`7MgmMC1`#5-z)D9aIW(V0{-nB)A0!u`G@-_hnLIfgO9y`IL=y?FQBSGc`R zQoKUNz4Ai4ltbm}_TlxRaBMt_HQE#{E}Vi(fp zJZeFgSrIFQkPb_igP4!t6bgSth6^JD2DOs!+*6Uj@C8Pl622CJt+@eg4nc1z8mP#b z4?4!#*4Quq@ZsoD%?1G}OjD#Xt$?7Ai4LK%JATq294sFSNe%EX2=xviX0a~qm?9k$ z2LUOal1)m3kJ>!{P#yGBOFJqEy7oCgOS7mm+bcXAPBy!Cjkdujr(Z9oL?)yuD=5V} zxNydO3e9=y(8N zN2K7n4>_1<=dg#I;)h)9iLCi>3U#p{ruBSy-{M1=TkA{V9!mSKx3U&X15LSkVbZ&v#dNX z^DrNGnxd)Fu)<2w_b^0uY(R4AL-M>w@~rdq9FX?pr}d~;88ftpIYs5 zT0KfzBdOawWcB=?e6mMdJi=RDP|7~$w5D5W1{rkP{pir5Zr2hpP=4FyvO%L=LD7%%?5+^4THfS0_H56L!APH zF9vQNc5r8vny>kr!34+GP1DHXv0-xE{=!!$G^+MsMyUIBPv@@ZD?2??{Q`ERL9?lVXf z&h_vJ{_UwSH^b5A=-H0(OoV0wJ-@%IkYkF>k6)F+d$_8T0PPj>l$)ue9_F6RaqrDp ziI8dDqLlVOnDBX-dix&rFbQ}|ZMw(gzea+m>zi}^ZIR<32>D*x`Il*@qGN4xggSb_ zl&BPyVx-GZV&?oJ_KXYnJMSO4nr+i#Pk{Sw{4e-I(q2ZE|xX3O=v7+q^YyQbxJEg-Df?{($tMEg2tDghtZvLt)g; z=^womYlvKDl%{9!ai_coXKF=9=LHc`%0*8vR;I{e_M3tCsUZt$F+vJ-G6}rWYZXEbv4O+?q1leRy}rEg9Gvz-Uk~ zx<;~MhI^uAbZuHdV~eq0ki2B|ayOrOgFSzF9(|iU^sD*&#-wjN{Zmlz_gg8Qr^1it zi^uIy5jxR87=Qiua<=!ER_`fM{=R80I7M9BNq)b}{Qh@`2ySG-szd+kedydhH}hWH_KNP;7SC99lBj66`Pkqdj4qW>PE-;OH!o3(m9cMTHWu z+Mf}cOvNTMs@K^&v;Le_1iJmy&AeIqiYSvxdUSa!x>!|Q<(R%uY&%pSn%^g2qu16;FF4<|2FV)dbCvsDd2rz!65CY;6R|(TbBaz^ewxecZX2l0x7Re zB_yLL&}ZBt8Djmm-rY~;XhyW;mXz8AMP>-5*3gKYwRR&{Y8bDX1*VJlr7(r zH6ur9g)}>?GK(r9x0bKWRa3ex##?b}axL{U4-rwWGTaFS$`GSx9AL$HM$WxbCNaYd`A+EZnln~NWv&fL15 zWx#eD_gP7KnOB|uv1!Dq<<|s*td`)$$&0MjaJZi;gwRW&r>_*_~T$1+VY3W|7eo*2OLFPVy( z%r+WN-nCOXfSJ1|`c%Hq)D|rR-Gbq#MO@z(?v((O>8q~Vt8=X-&#&n` zhC5}7zh?tfW?ZKe6-fUq$5-3_-VLM1(mBx6Atg*yzBz3k!?IK6+NOIwJ$(B@&FAx} zal?Y|#L{IO|LeOi`P{o7lUEux@|~sy3|lu~co&wv@rMf-{Y*W-^rVC~FUPDB{Eem( z5&2AG34A-7+M@H@Z}r&UJN`~^_>1>QpZH0z%g)ZGPxHH4JBz?)znH%PRzeRZlRicB8iUFb1FCs-!NESpItUdoe2}e!cT&_csnL+fm;k)b(Z17X(VN}d(0qT#mYN3=uEyX7 z5RD45?nkLACFkVICY69lmYK7;b8p5~9`KEq1ewBHYod@I6Ur7dxwt!one`zcm(tL< z(vYFN&bFXqOEnaDCC>Wyt54>prx1(=qyTY4|m8{T#~MLQS=WV*zX zuRw3w{O3aMEZB-e!vtHKO@r)9t_6Q_=NH?e#oW~rO9nrB1#Mfmj9M~z22zTzK@7N1 zcsx3Z_m7Ic@P$eDUkn>*($_B`{{Dy{5I1PpeTJ)!-r4$koc zhFbb1w=c{7^qe@b z`Y}JQ-MOyx-h6iY{7XP-F5x$%MaaRWAjfc3w!LtM`KSBe2T&o8HeFdsC}q7aGq0yC z)(`T%DKK5PEKO-ry2(xm0Zufh;vTMw#lSoAI9e>;H+qCWr{8D(*{grO6#ASS8!3_t zk~fC};MfL`tL}GHIcmpZD0g+4;zTgfVHRTnL-JzeZjM9M`6fXFrmHe1@56jPjyo%u&Z0dG(o6vOVAq`B;%h z8K>P0lAak9e>!}fU4ug3$sUb1WU=zsBos<`+Yo*yVoA-|EO5g)lCd)XqQGsj?r_pm=v=v|W%WKu``6*6UIUBiQ zx(@ip$O06@KT(V7pZP_&2_EElQP6qA3qhxVLPh`k*< z36RUzB_a3sd)necZC5sZPPfBNfw|XBC)OwWU)FWxd>4*(PtlXPT!ePArYrN-XH7Ue z3y`oM)y+_0Lz>Z6o~XMRyb>d_T~hCJX!5r4>#Dz<%kvQLJt;rPYYV4FKe-&Ry4(!o zImmjV+J=H%E>7w!H|?J0qh`l!kmoOntmA&HN9@Rb&p^bM8kY zy&U+Bh!!)meiO}i#>)NmzOXXi%&G~HO9;e2q78rcNrgQw{SCN6AN!S*`d3o5!1cCU z>S@_iM8iCg@pmTSr4<<9&DdcTAe-q^EFL7J=7L5Ugd-N%)NFyXEKZjhG}a!JHWsKf zA56-}GsH`$Z|Or+;rX`0U+-25|DF~b1-p&coZ32MC?ceHI3!@1XNfX|9w|UQIFP73 zu#h)+q}iS~icMOU5`{06tHTdh+|$#Gcs0{hr9;ZAJ&blWjMY?ZbUswQ(cR4?2n=x| z*LBme{>(uTx-RVllhw60v<$bT!xp>8-sUBEgTl(v0s5qC?%e@;fA8cE0f|gFyAt|+ zqSMg&AN#Yf3Sbp0?VaM>pO2HMF?Al#S5Vb0zWbGXrX_tJ>8 zE&&s+kPh6C38xIc0Er2ADQj1=%+S%@K=Iv}Ur4cDV&P_n2jt7A|4Lu03 zhL7~Y0fh*AuR=_;orX=%L#Zr<@gccOHbKEU6%?FU{o4=0E%t6OiQX)Qi^yK862y{4 z)u|gKrf0{YmqMUNheMwNN1l$lo3MG4I$M^`CLOES7P=o5d`p;t5}W`(k`f%5F3+B6 zrn$o08)`ZLprA#Zm5x@Xi3;5*4@9d7W~d02uL!rTh_tP62&#yk zs)#?S2w6uexUBd`dpapkwyn&nstkKXg>+RGJXYp0R6^ye(iy5sW2zFn%JZ|UYJDp_ z*GpwGffjRUp8O?9>{^`Bd6wAy)w z+C}+)X;0aj=|Nu7t<`DHNb%<7-ulEPE#>8s|I(hS>Q1Nrr9Iio7hKle$k*T5)*lkr z|Ea2fnyUZ7Q2&C~0IaTiU}!)zXh5)QK<%zascyhDsK+>kHDGtwL5<}t_#KoG^-}M2 zs{y5Q)Buu8Z>~u%`X-DFzMD-lN^pQyQo0;Y z0Jt51z}A06u8$#WHkpUega&>hzMVa8B(?m72oo5c4>=S0M;du#~jc@ z71d1@K;}$LZj6-IQU>?hIee`k8#e~LUM#4}*z3PWk^d~-DUFAWdg+J&lop1K?mV#E06;`GS9JvdVRRD2&lAC_5nnQ30T+$S*jANPrbD#^7^1t<`)Tn>lr`+7X#l?SX zYGD5npI-H+SM=#W;?vIZ^61{^%#WFs)0O{I^y%R8;QyQG)2r;{@c+wB|Ie1427v?r zlAUOf{w+IEp~DCLSJ?@~+~l4uPy4?iJ7uFW6#bY7Ft`09JJq%P@5xR?42aGYbMUE- zQKo17`Q zY5yfV@!uG>%*hhvam~v;%y_Ic+hg9YN_|k`w3%W^yHjuVj{nAF{3hOA-G#HX1*Y!9 zdG{(iRldqjj=y@qTh_REUVDJ{B({OZEr1JYKl7B9RmrP>2DFKW*NG&jfIBl4fU zR_1$8+X`T}KO+b}dvD3!#q<7=nLqDV+m3wkUtcND?|o=|;_|!7D{%Vu{Zb{+|FNt7 zd+)R4l?eFq`(n=D5IE5rZp^^R#ZUJGI^Y8CUv$3KpHz(g2q588hd4Lys3wgQ{~)q( zI(wUc*&;K9vxgP@P7``VwVDdlRt}X2E>uP95XEnsi{Rhgu@zhueN=lB3F8Nn|1y^q zC4fmrNszpMTrLx?txa%}#E=IEno2?y=V^6D_JCOs5!&kn8yb>5_*iwJ<1D8*$-+W4 z_X=XtGWJ-35n4!x^th}@{AQXa4t#m>04gWRH0s_jomimRpZsO>)+>*4C9 zBxi8XAG~xxL|L`j()GEv=q31O$S<({`rJuR<$1Xb7fNDu-G3_XK!%muu2OBNet=4e zQvaMM=CCF26D3*-8I`eR2_YORKtG6iUK}LeJ#A8j?+xQ-FQy*B>~jS?#0TG8aMFeu z8q-BvsR)}k2i`nK^NN&z$+&H%L#O^O;vqhpTXW4-i-3lc-Z^8cJ(u=Pz!Dc#e=tmc zzGU9~Cl4px0!vj(2&RXekcqr{;4&6Ou(QI3BU>(shCS}1-!Yt8wuT+gHIy^AQjOGC zOfVq6!bP)6Y1(GapW-&1`m{3uTYu9uTcFZAW*TgH>cq`^R9de18Xn}YP-l{fW23l!%I;ZCpN(g=D4(7`gZqIk zNj4-3GZ@+Fb7?v}VDUdZ#Z{n!^tV;H3maI@G_7^8#J0B}sG$BEu^G?z1W2Frfwy=r(@ws7)~& z+9^OGvK>u-t&lR|VBk;>T7ythC~23_T|ZE11WdxxMI_8)q=|Z4Ipssjq5HQ}BVX7C zZxlAGJ}xFK`a88vLcCITUeKs!Su2}VkeCI8+RbP4Z8(+l4YhG@s0Pv6r2H7q)eeDc zG)Wh6B^xo;S(Y7ivK^O&UomiG+DpD+Su{G2`f4`u+;>mAwaN`aPX_wf=eVvsQpn>} zW*9P--qSa$fO2hwQyn_Tws)M_vn?0{)@izoqKjPAqY)_M7tE0ytcT@|MB%;YjYwnY zah}l(*z^kNi>D(rRS`8G}b&GUK!;%`pG)vLHoKhB4-wmFNT>pJFMYKZXd;x7#Mi6TSlIqLR; z!D){h{5*9P@+3me!wX>dObEqVD{UpT`M5)zx{MM(jL_mS^s&)nc}r; z130p7WQ{nFgEfm1zc{GH>XB9deFdE!%57fCZT=nxX8&}2^!kT&f|o@{>HQ_2_}Mx?}IQ=g77;6pAR|hD1&INL*7-Gy`2al z^$z8(2%(JPq?QfAI|>!6K(;6jMx_hp_6{Sf2;xNv6Os*Pt_UUO3vOXULybUa89*ka z3;7TgCVd}FcN9bs6{>g?ZbBG>pc^K3A0o*aM7tWUP!VRO8)3&6sw^AvhA^0zj>iBJ z@fIc0jV{uABAmxMB8V>vmYosUbcxK)7vu;DGnS1A=?FFRj?AD7Q?W*`NOH*#L(gkK zrBG!>m}go@L9X+Pser^(b;Q)H#?-CG_%_5e(#6*E#nwY&+M;4Qy<>Y;W4k6|x+`J^ zy<>-UGV)YZY->l{>QQXt5ppjiuKXyz;V5nmC1FoD zVaq#yts?%&J8q0Ft_6ae3n3!f0V1je=EyRk&_%w5M708cDC48R_jEx| zkxa3xk;W5=Z|)Nx4uhYpl8~a3{EmXL<&yX#l3!%P6DZNK*Anr3g8d+YZ|IX~KfaL<2QDLbB_q;$z%40`3ZD-0`qEy_hB&^C5{)}YQC{t8zG_l2Sp0y-C)U;>9 zB=O2Le)>ou`XEWlRPME8-mEkbeF{rfl15g#;aU=GB`^>-!yqeFEIM8OAx#7|!+I?Z zVKR!yCrPFvovt#&U^0bjE#3VgtKppymO&7rz7(6{n}^T?6J_L6WxaKq1<`=hYeCS6Bl`h6UC=)v?= zb~1x`;hIDuoD#?ZrOm{H{UP)Iiif${X`iKmh>H`RM{-g%KKYq?c0}NUAgcoQ&HJfe+Z3lKQ$@xsmN|MOofbg9WH&^R_bkQo0{76M_TZythUey5dc#{fD%*O>kRwU5q1v*2Hn4QFrFFpWDu&JL zfd{PeWDCnvl29ed5W~AX1tUwxvh*tM`~`PQPqh)utMs|oLA=?xzt(VRZHeg7yz|yU zjKnyswzx+8=-oDGw%M8|a^;+!<#I@+r|wlKyQM922$G_xyHwJX`4dwPePorQcn5~ZF z2bD;+MSS9v;;-%Y@*>FjFdAc_@z(!u4Cwfz$f_E<+Xqd4(J!H^f%~>1WU2%Nu55P) zpW*YiUZQRPZeIOU&Sg-Ia?;+Z-3Fg*+CQ3~0j=eo?m#tY9w%zvwFD=~xfm#P9COuF zf!pk*TX zM%HNZgZ#2j`q&S6h$6Hg#SPOS;%Y+Pil6*#%k*72I92EF;4N5LmxX2t6>?>9CD`($ zJ9XV`Mxaqr%-4j?nJ@K|EScI{yH5)Oy}uYif8>cCPH>bmy*_p0Che3{^MbHt5I&cy zbgbhXFL$R@HB@(N4(DKZ5rF+pR4r{kI*;)BpW6qB#CmyMkR$=9YUe_&uVHbzE09KP0-ZvdxJVyQEIL@TzV5U>Y%~adiCunm? zXVFw=a>O9_d_CFt;HVc^*RC6(u(zKFitJamTdfjoJ6s}%aIWoYXl8QiCkuYkX0Wee zimO}IY7*atcyVg9Hsl}*bmBba>cbmfOgs+cL_4JZ zZJOb#vSxJRXPncKATE*Z$iS0@anCGD;|%NV@IHPk&Qz)PRJUkwH~f`q0@1)l@fU31 zaH{1zh<+CkgfA3>^NG9jO^6*|&Tt*{7f}c8 zBA!RO6~BQR7xBrL62z9mtY!g1gJOlvFm#D6?Xh!&C30YwQQnxTUFG+<72ZKF>~oRU zfn2E>Ejj`4cfWzUo^jt^h@?pu0?<*40ZAoy)!c3+5B*yW^@_Ept+max7t9$##9J;J6g~5nIi5J`kLG<=s9{i>SQR3>Km=ta=ghhGV(I!{Q57d<^GQ) zA04L9P3BTxBsehpeEo+~6#7IP3zcB83uuks25H-~Yldl`Hrr+!XRqke2)%n#I7&xLhOx{pta&pXVVtzix3;~r{F zGxx2ZPfiPTRBhqPZmnvy^sCQp_n!|kV=T&@EfVx>bDMly_1wM}0^w|~oWrAcqkhe} z&6_=&o7p0A+5rGn0dGb9S`T-R{rLjOL_5y0H3WO#0EZ|P)Hcj^-(7v(@BA8@40Ihp z&4B_@MeTax1FFwjMS{EK-KC(l-H&C1Gof=8FGR{3Ij!Tnf?_L^pT~Iy*NUf=-^R>* z$epYDvj-*TBG+IvM%gYNi)cP?bIIau^#N*e(ciD?W+EVWch{0&gr;L?u{<)-=6C2uI>Q{n501q z8t?!GL5k60is{(z{{HU(AMm}%jjqRy@UG|Zr|1Vp zKm=ScjtPH^6#tDK-|)-$@ysax@+QCV*l6*M3C~m*G*!=!T(4<+H**T8^>~l# z3F!5HZ}n(T_D5*ZEZN)t z6PMfO60vSXz|=Wz+db;imN6~Mhc*3to?ktyJ(0WzQBit&1^{78;6Q=}4IV_8P~jh1 z3LQR#7%?I(h7v7a#F(&F#f%+2LQDlf)<=>hO`b%VQlKmVsZ_qSxDn>ehqM07qL~vR zMV%^P5h3#GAjO6kM*)S^^CD5DN_jSQ`Uh&ykRzvF#hO(iOP5+-+AQi7<;GfKUve}X z@e&az38iM7LL^OEgKz1YM0=NHUcDKs_5~amBUiy4pBBc*7cs<*VHXR0L}ZNHvKTE9 zDN^|^Ma_>NQvSs0dE%eWq7(i#omwwp)eaT69(Wk`L7S?<5RtU=X2&Q*9s%Ax`ygrI z2!j_Nh#L9woUEA(JieUib6c_>*D6B96hfIDDG@s(}w6ajR z4uyM=xdRg<5u*2)t53C!LZgm2(WD?^l7$Mq2nyfyN>Q~OQ|s=z5laLTp%amt?ztUJ z)6cV7fD%eKlD^aMF1z5H(nuDU`!Pr@2O1JNJs7NVxgH;@ge})-jH$QZ(kc=~G(mJx zM3J_n{?ni?g$wYxHc>PU4I0sYZOzd~NsJV>F_+tv$S?(a1*t$^#fVTtz4{QgB=w|Ky*W>%0 z-F6%OHCrvW)zMnh%vG&bz-l>yh*2K;)}gr0h&JHGq(#nP#ITi@I(qLl7B+-EbeFE9 zj`&PrgpSe<*NRh{SW!_8jJM$uA2#jd)HFtnWvJ4i5a5)=AR-L0Tn-H9oZ+>~o-l=IJko(zKdE{?G=q-pOHh^vyfXOt30CbVw#9sD~vcJKciTe zy|Q8BgXgP%?&`U(y`@?-e8qx<2rw8^St3~al@Y71d97P(sOhr$?b)*SOlgYSJA5V> zbE_$Gf%1;>Dx0ocPLIMHcUy4;89%sh!#^*b^S)vY3ZlDXvJu*=Oa~oI)rCu3bk#^l zZ0pu6Ps{PUBq3r7iGa7|G9pg7%J_7VP&3o2`So&(`` zJ74t-gdvO@b5;m46KbV?X`jx z6w4&HsTE5CGMtR+3wHd4kyDanEktnIOp*w$Ub3m6@zmx#1yfJDq*6uf%w%6M)Rv4K zR3pM=#&e>Q62D5RPRk zC5WOB7PFXN6HG7u%)mhyhV)X zW?I_cKCzocGcHu1D?i;9M4tgQ%wQveAtI0hCE|5t31_=L-&PkZ!NtlzMbllF$d@L0 zL)%`ms}Pz|^SSg@iCcB#)y06-y)S|9RTL{4`#uJ@D6vuCJOWg~^+&GCMQ`&mtYN$! zI4udDihv2a-udoVA!W+kM>b4Yph#H7CRPf7&jMrqofz1|C;_o{SNuX6>*S+NxsB{5 zJY26trU=`?aF2HjQNt0qw~f6qJ+Dh2CC}u+RornxbQ#+u(}j!v&8*s-yci}IxV=&C zNseDg;?h;w%2`IpxGwCG2G0Z*{YkDz24^L%$_dJ7zKWWoGG_R>nURKOoq6#>=$CAn za&0Yh?PbEWtk8k}o<=1b2c)4VjaO7?6d zMw0{<*#R#}wmTD=A;GhwiM2{(oRS5z*V3&{^OOY{?34@}B_e)FWFmMHXAfkQ#dGqm z0ki48M7l6GMs`MCtrH@%|=uufU>94Xn+$kA1O@91TW;a_a zc?0u*Kiw1MJ$f{?KBKp>r|O)5``#AGw?G-b&VHXn+xzK{ix(}JyqWrV1BV~Nfm894 zIQ-!ei8xHqUDtC@oOl8MFUbo+vm-DsBApftv<=tclj|hqU#a$I@7UuO8l2jQsRfLp zkkNhfXyW<~I!R34bBFv~CG9q-%u8Zd3Z;x6Y@edu-~K?hfZe-Kw}=ttZV z@o$a#)?v)A7}YoP2Z;<3*g7KuP5!silh24IG++P#l)E66zb)N&X2+%g9P$Kd{7n2* z1VuXuLLe8+#q}cjOaDOxdH{gCV1M4*kB8okYraMRN0ZMVq!zcSIq6#zeX)@C^r-Jh z>#GiU9?E-aO{w5Ifv@1+Kw*&rL9F)nKH=*7#opj2Nb<+e)P!+AE4ja!rg(+yFf0su zKCyrW8<_&}s0CQ?gZ0a&%iF5H!#|7Azk;9zT9AbeLA*{kG^uZQ%LKv)$ahif1 zR70E~!Rn|5IHW-oEDBnf!|Gs&qEJITq(d*{LO-;^Gt|N>M8g&=g? zL->=yEM&q%RKh{5!yLTC8+=0$tcXh#h&U8PPK?1j%tKO)L^=FJ8w|u#tivaK!71Ft zOr*p##6&ODL|oKGTj;=Jt3ZShzk+auHUNNPEXF+0gFjHlWn{)?bjD|d#%PqrX{5$# zw8m@1#%$EaZREym^aE!6#$^o0ZhXc%0E$K+M{VSTbYw?sYy_Zqf@aJDBDjKfw8wjF z#&N{QeVoQ*AH2wlw8M*BNFR*Ik>tobR7EkAg^sMlD=f*D^hk;vMGzE8n9RVM^g_>p!#AO;b*V2t66OP2}8+=#+@oteS!R&En+0P_fQU+D*&L3C?panqW@4 zfEgm7gxefCwF%G2>MmEMQFHqCooe2nN->#FD)znh7ovHRwc82^uFNU;_U%Q8C+4 z4iz{1Y@8DXB^m{#_#_DBfy@}QQHTHvB9PGYlMft4sLq7Z{Tn=Ud%U-@5l_*v@)#GO z2>wzqN;MW;H6uMz@1#9HVvpG*iOBG}s320Wh*F?fw`rl!#eC5$l?V^r3oF$L>;yKI zc(*fciUTZ+aq)sEwNq6xKirv5Hg!|_>(R<7p_jOg5^W0My9=7}f?7yXjcW}?y-wd` z(}x(;FayysjjWWQOq=r`>foX+Xb1p3&(@GG5G_=PP*D8K)Rlr$io;Az`Wwtr%~+j@ z+t`AEn2^f!7PMQ_OT|i0xk%P(8IeJT2+9l*3$^oEPd4i z?K2HE389*-@_>;pD2P%U16;+h5<=IPXjSmr*5#DbL;6$Jw2^5Iv3PZe-sl3({-I2= z3p}^`K4FD8VwJSMIw_NYnK0!r>gbI|IEYKg4k>s)?z&d8sn~;PSJZpgi@?`eSy!SG zIgS}Ut?1Z<=#NG~lTqjwC;-(oY7g)8Gl9K`jlI$Q)FGXLtC+bNPR)w!sDn2-h5k5# z-YcCFx>$qA*vX^WgELkQ!lQ(pSRMP=lmLo5PzYG)jUpIXnF83DmDx5W*oEuXYw8G* zEve^N5+djWhqykVSiFSe+5cl!Ny^qEUD}8!S+_V^#&ek#DyQJt+kv>B6sZLOg-tS> zT477vlSo>>yIXlZ*0HsSaZ=dSdJd*3f*t8Nf6ckP^}T@o+F|`pk-^OVxLvJ|P@bXs z6zb3=Bya?Rns9P9)+;W*)DY;#1i=S8M7a2# z)$KNQ4c5@LlduiBrbUr~yA3HYUOhBjs3?;uV6s<$5jRS>-yMkFl}{`U-Q86PO3gaS zeTcj{vIwLO;t_-Gsf8##Tzi7w8j@ZUq230XSK&xiiGVFhJrvI^hzU6ZjS0Oe_%*H2 zxfzY#|K*YZ7SYJtx(><9)&8v?ySN_@}phUgkIo zC|E9%_+z)did?Q1L;l}cjtx3~u_P^sQ|On!m9*Ra-rR!)E~=RbW+Y$*T_JuwBJMWx z1whT2g;`hyK3IivR_Aq&g(?^VDu{)3mgjk<=X$p1d;Z4fb53V`=I4I)=YO8(NEiY$ z&}UX)g_n?o>^Ooc^*lB<4^4(+`c&rg{bW}z4i-3pjMnIl=ID<0=#K{JkQV8YCh3wk z>61q3kUnUYFop5m-z9_IZuaI29$i7&-VZH~SxD)f=INgH>7NE_lwN6BTTdt;<;X6&~0 zwP9IgTj(i_0gcbr30R2IC^+iyy6LS8;uTiyyH3u%rR=9Bh;f zVCsi+YC@J_>{g-it_;c)` z?5FrAC#ACGxQ)Px?)Da(^(=x@<=CV?ZSJ0H*6wf&Z*QV7g?>3#G!5MT_!paCZ}27v zQ;3UX?QP!G@g=M8rH<(C9By&u@0xJ_?N?C1A(x2s^d(u@h#WVINf7NbXz+z_@|6m5 zn7HqI8}2TLsmadpK4`y3R+1#or3?whn>g^ScyG*r1h1;_;G1pSMQwqFY~scd@ow*0 zXo3uxU5?t@?+~>R7xRJ`h4GC7^PZLBLT2gRbEwvpv~JrYXl2qx4wxyY^?q})uyUXX zgG?U|_JH!?EArnwauD6}{?==nDS{vWSK*+UM?>^|SnNDgxArDq z2MKLA%sp4+y^Vy7js)mNa%}Gi;;E{0UyNFi1ksiP^A>mCjr8@M@P<-&LoE(S7=jEx zdA4o&f*^4Cb8~3F4mHS*;$bUZ_m~Jz=92%Ee$UR*u00}Hc@b~-Ha=PyS+^o z=r}bv?x`2~+32YvCzA^PRQD08lYje51d771DaF^eM)f(JE{ENL>~ z!iS^85NQbo60DOlPo|t{^CrVo0A%6p>GLPhpcG{RNG0?rMOrnHGX406R#Tg`zz`{7 z>7hu3ww6Y1{t6OmSD<5vJaYJFl|ijxk8*8z3eAz0M8=R>Yf`CNyFzvH)a&;zV24DF z1_r7WY+;{I6HA08rRpV!S#2F=+_O-NLY7M+ArhIPQnVvCpR6pg)}+TRqfDwry5S$! zuVwO`ZTohd1OXguk~sKw>Da(cwk3Tk3XvmqC8wplcsRyEDGZ)SF$lWDS1n}|Jlh=m z#9755k~&kQ<&iU^W-A4sv9|m8UGoT#!^uMdR1ts6r}!ste-7bw8!2%iVTwePZG~8X z0}VnQgxAGK2@z5}^xt<44x|u+6u}}16mmuJ$Sb5hr(r|zp}68q4}36?0dVYB6pK#P z$dE<;wpnss6eT9uTzfT62cbbJ$ae-2X$W|h2_~>Y3zShxIVF`MYN#!RKE)?klLm^XqlI#+=Pa1|IclVX(o!g*n3lSzr+|tlORA7= zYAULI+L|hYk~XGKwXXNCL?tX{>RE z7-4`Rg%nXl0Ywr>98tu1JrD_@W_{KwYNDSqDsQNe3hHjM_7+N6y&+nX>mQ=HFfjhX z1si-Y!U?Yac5 zTIsTX;)^Swu{JAl%p=?UC!TZmg(lDs&8f*iAUwd3D{TO<^wN3!@if#?OFcE!Ra<>E z)>&)4HP>Bx{WaKK>ybrESM;GZ9|rN^N7!gT?S~zWbm2u7UpT>p5nal)H{X5t?Zdj% zwa_-nOlB3>V%7) z$4)`J-q6rRI{+Fjamq5Mez`&=X{Q1uYv-r@4%$1g!z1c@p1{l6GEa7vEdFbzHCJl< zy}z&OD)qthDXT31L93PZCG!sI_|+$GYAq}gp+>&s8$XL^vxNFotD}}Le?o}O0!t~C zK!S!Cq7WCq@vR6*h=LWuAcixnAq|g!gd`|YiA-4H5~CPJDM(?8Q@p|ufip-U#Fstj z8P8V86W;UkC%juxND8&;lR{F_Bv!bhhBmw*4s)nO9FEL{#XI4tuE#1zdGC3-lFjjG zafvewkO)XX!zIpV!u(~*h|!Bx_juC2>D5AnE4v>Mm1n=~fpJj+@!9LrNErdJNgy2P zz>ElUrtxSLxL2OyhtDhctae~WSSf0C^4ky%n{bZ z$M2j-B7uCw7?9()BS>KkX^?~^Oc9f)JZN1K0uOSovZPJ2XqG_vq#2s{F-j~`DE~QA zDph$VJp{l$9|(XdVu_|+)`*>cp~QKha0*ERiH@eA1RAEGH;)xl4U`~7DeWR1>R2Z} z+95(WLF2Lvq3D!H`D7^N0tQIT6DZ##Q#i#*rZ^Zt0KD-Hjn3rIYSJ+*YG_Fq0!op| zaA+W>phOz<*|#W+0TPz*(QGi&t_f8rBHkGdi`1W#OasmZuD zC`*C)BpO2Gu`oPhuO+c+g8&;?RSvdBmtB!(^-_uRAVISwsRb$AV2~k*G7OL~?TTvY zo>3%6rQ%W0ibe{US4={zd;`NHLUs}5qDZx?O=D}@i6(^rs42BTgO`+w5mSWqJVP+Z z62>5jIvlo+s69%1FY*W?h#?{hp=MCy3m8&_b*%o9odkj)GFMbO^}0~aZcr=RpZ5ag z6;o&l`!rIEON4fBM<@d?W$D+ThyVZ|&~HQ@Gl_`66{rop=xypchR*D*2w?DMMF+BB z`B>M$K|}C~yL;lbTmqMs$Ov=Apf?vo0-%!-4~Q3>WW_M80h}NSELwuo&6*fRg&oc- zDiPCtRz~q>x|>`+Mv|pq(q29jD7hC)wJY^l?c;hsB2|0-vku} z0DuPm41hTBnL<%W(?YAgI4YYEz@Qt#2?s3A13!DnC6ePG zduwRT-sQI?CXuZ%d`Vqij){!4Y>QfI;)z!@M9bc0p$&n^QEFomM zOkol!Uuiu(?jC&0ILlU8X?&yuo%T8(h$I;8&C>iI71pB zK?z50@b!p}uf9()t!ho;e~`VrTzCx>&wpM%p?43p&7Sp(gc_v@J%t)r{ALo_L_zZA zr0j{aG(b!w6&zUF19U<|5LXdYR*99}?6n$0z``X!!Wl?Gq`AZtjDZ>;lQKQj`q|en ziGgVOO%Wgk`IVo0oL>U|u9E^r#3YkP+MGPNFN!UxJK^Vy2-atXJEt_6g8&cE)SfN3H?L~o!pqYhKRneerK%q>u z9}!GJMV&$#G!Yow*-zvd?O_Mr{X_=H8lQE-11!x35Jrgn*v@g*v@uwgZCT$;ni^CB zS|vvM(byGYp{8jencN?XaFVXgdidg2MMwvEe^*ny3}2X;fHh}7zAHXuv9PF zMj@KSCM=B{oW%YnFu>Aazz}%EN)cgj)x?CU!GrP5e^nuHC`JB3hb`XXZR8?!cwus_ zVM9QI3Q7Vgph1@uK^kBpP#l>$LdP+Z7&LCcOwfV{EX@Kq0!CQliul1LxWU)enQuv# zeApn1j3YVDhB*#L8=lw+p29YQfnAA6YlMXw0*yoB#6RNRP2d3ms9PMIq8`QvDLeug z>=P1<0VU8Qc%0o|9b!bH$V37MClXexwHfOfl^EC-mhci6vd8GngdXf4PN0DjT)@(3 zK(4)2NUS79f|3#*ffz^vO)6Pa-CR!Uq$0Z3J@VulT0#eU%sl>u8X}5dmc%yR!O-L3dSiWX|#O7_3 zWerlqD4ZG*4C7`PBS`wh%K<<$&gFR!B_Qyg0KgJ#pkiW}f^&+J7;uwM@#c6YWoj8F zc8*|TCKn^7V|+a(--H2CCPp90k{`_GM92a(a)3`%f}}k}Dr^7%PUUD?Mz=(+YeGkRob0h zyuzHlC>joAWm@J}nrMTd=xY$Bdp!h&?#&oTCuxwUNU5eRunqtaO-~$DS9Su;0RRWc zf_TX1Rk`4|<)%i6XwPw{ZMY_r`h}CuVv^p5BMyWq?9&-^C1Z#LE5HvQtb+U$s-Ye# zq9&@ME-Iro>Y}a!A2_O`dcvQHfTUjPEV#iCSb?LiLWdf_X@k>jlT1 z;;EK8TZztTIR@y6`lLX>!Zx5mx~?m`63GYv zfB=v{yUwc#M8MJ@012=_Sdapj{N)(PqD_G7W(aIzY%8~Rg|~*Qo9ueM% zq!KEoR;$T%z}y^c?4p*z5Ujz)&Or~RXB4J}h)9C9(kxRX zEMtHKnGo0B#OS@1=Sln@1GoZEaD;`p>{Gx2%#GqtkOE{Pfn>th!t(y?l3FcvV6D$a zEnV>qF_M&nvSEXo1nUTZm;OYEu;6Jy#U`kohb?9;RKl&EVOPX#gYbd2zN+2ArmRLO zibUDoNCLqsXy^upO+rK`yc>M}M9vl9UHH*)E{&6&L@j{GU!FnH7USrWZtng?)n;x` z;B8`1E}ov6l0Ye%fvrZ+!WHp=ksxJOYayff|ULcTKHrcrR)6 zuJ8T?@ak@ZKxRiE(e45U_?k#KhJd;W=TDqMOF-}1J-4O%pMd`|iZ&HLNEX{!4L=b|3O#TcQL&U+m#hXODLK<`l zZU%5aMzCH8Z+wU^0^@`N|3w93hnsP)@tWHJGe(UHM$igHEu2T+W`xguCIEOqB)tMW zhFlQa#mm-Y4j1eJzp!4!@LxP}VdUu?=`CRNBt>8-1I+AA^a>ONY?^$ka@J}IEAhZ; zabT!$Sh%nh&jb}qa0c($cDZp^V5=O!E8GP|h)6;TS5|xWUW<0g6nuul7O<KuPaRn>_UMN5YL4_=FVK6dnDl%}u@gti=B(KFK zQ}85HvK5~)0@4D_WdKr8h4@KQno$A|z#IVp0SdE){wjatEHecww=zk*@>-y>r?D~n zO0xtDFZ>3;R02gQ5`p~+ABb6kFbM$!EDZ-NtcnIjgtM^n-3L4%hSdrnE;UGg8bjLwKSVS)29M!Zh7xv4*iVQ>+;--x^cE0uU>Po-}Ndq?{(e+>d^5MO!q94mM#Q1zIyj zEXT)azvU*5N89BGQ=HVH+4Ub(0*i&g?LsJ-nx$ed_DZj_BY!s98Mel4c4A;LtT;dKkeNMW>xHN||5 zaZf;El2jI#7VdUZr(kP$w{o}WeYbe$wq2CA6L(0gF#t6~HW4iMOqjwpGC?U&geG&c zJ=-_b)~$S>HGRV@gBwP8-?w*vFdzOm1#8~~P*w#b_(4)EFLq3@ECYAcW%q;2L})Vw zen0bs2StTbI77g7%suvb2)Id*f-r?ai7;4SM>Fygm}jT>c2BpJnfPS3cvyI_-wuk} z>2gy9;n~Wrn;`)n+T;ZTKxR{u#?cSC-;Parfh3xsj=UsHe=2Y;OD9RZG?xkGsI zkSi>qyY{8uM3~F>mkFJMWd61Z6?RInT6@1?t%dgPPZnC`*|}1I*=naMQ3Tc z2>`n>1u3+I*G|MMR3aE~uW`DQ@&W+!l6H*4IFbW~t@Adn!?>OgEYN&9i@?FVrDRk* z7(Z)7kF^9KU!OyC7&Zs?Q}?;F14X?51URnKyi>QXBL&c|T~ttL5sQuFB(!Kyw5|#8$3V&1i;U;y!!FFOpthd2s(C* zIsj}yM8iT{?6rM?{#S)`v$avRRd@HvcXriNLDh2>F(3v88H=riU<)WR=k*TW5(Z-T$Cf>tc5T(RTf?^P2X}AZuYc3l9h^9B4FC#|CO$lN zA0tGt#I}>fs24uPOXn#7AOrL3*nxu=zZ^UB@#lqO_mju4W%uvl$Cp3faVk!oIOWIR zX(0Z>Jf9n*MV0|k0RR<-`ol<}!5mtUAeJ25$sh+4Y*3&CF+|8Nf&Ms2!wl^LX+jMx z3^Ah-?Wzz(23LF#Bbw^^P{s>q+|b4dg_?`R7A4d%#T|WANRJpHS_ncKk-V|S3~3B8 zM-_wALn=T*qGiY@fsF9PAYHU24I-e3MMoMBvZM$ikhp{_7nw{kBB3TajsaQTvav)X z6{N983bRbIO|4|<@F5W2lxfU7O+4~PMOow$$`EPVXwW4oZL-i28Lg_tN1GI=z{BVZ zRn$>QE!CF)B$EYzR7`DkvYGmGRaV9(+G^HY75l?hTuDV`I}j2Zt5s8svcxe-jQ*P9 zl~8N>0003t;T2b5rM=b4YH=+LRBXBJc2-n2c_V;LHraMDRay1cRch58b*6S(od{m} zG62AVSZn!1)+vY(qp@1hFzSq5<>Mp(0N|Kc)O-~tRo;d})fVE3DQ1iV(Exc2-HPRV znB({IjrC*q*d2MXHvkBrlf+BxXyTCsPX-b4TZeoXtL+YXX<1&{fU&dXD@qE+E;#~CQb>&ofDlA}8*jPww%eAr{w1$`)VS@Q zsByP7x4h?~JpjOfbnn);R7;FPT(O>rP?pqGw(|gRr#rX2!^$bQTzB~}x0@>4H+P$1 zq@@Hvlg4IuuNEYTNMo@_j2eSr`i^TLP~DSXx>nrV+ui&4dVf1|yVb7TbfSF)K!ks@ zuPk6F2oAV;Q{#A+lky=yU-H`R&i(uUQ?)A3=`VjAsT}`&_5gbYk0At{&nS$dCdAYt z3`UWJsW>sUI3T2bMZ2BtEayJ}j<7M|6P^R#)EasshF|gnl5h`IS zoWVpxD)bowHODAXJ^@4iLQ)X&3a=eu6s>ZW z0S?3=-RZ%JXk#MUh-kzjA`xvYT$>P2SjL9&4FDW~j2qo^i3lRb6wE_H%u4kKspwB> z=F=TrxMwaks*#Oml;hHT=rjC%>|zWco!K54ndK3Ih6o{r;i9lCQ^5`Zz?$0!$rnkV z6|#TbTjVPnNjp@^ZIX^VBgEKayvV?jGKC-n8^E-cQ5a4NSTt3=8Xz(}mTj5Lyrt99 z_{#sq(rM3JTD}ZuzD%mC6We*iWUT3!L8RaWColmD0)Y_JwQhQ%fB22oChmU9r5FiQRy+8L@00$_tyyC=sGdBB6d zEuZ?-9Y2f4OK0k?mJo9x*>*Wg%8+xR8h0|1y)Wt!QTroQzA zg^*SHOlecV29~dV9U)kMXx544ORkXYEVkGqfaCp)tO!}bTT?Krdfm%0A}yO{H(OMq zb=9(K!|cv7DmmCfjIHqM#KFF4nZz=t5hA5Y`}^JgoZB$j@=63L z3!`NMs!5tj0eU@XgJWeyi@v24zL}No8~4jqSI+mN_03#<=Y?T-xfWYToeF${+88zX zcPwo4WUP%C_P{FrspY<{;Y-Xc8m zm>e&yw-64YjA#7S8p}Ex_v{;}F^#<{G!yRpgS+vc6U`C}aJ=b=qT=vMs} zVf1NViKEA>lUAnA-f}b~=S;CgD|%#%CTgfBCTZM4`eqK`j*I{HNQWBbD7=E=Xh=I* z+p!p$Y$mmJr<_9e4!d3bEx>>EY|T@IxnHn$4;}r6SXR>+)v2y>*+%{AikX^Y*OsNT z;XK%CDek@<6ZZtAKx>HdD#cZe%zG=RW(ZfiVcFL9#JEkd+}iEjYxDN3QsH9{jLO?% zp!F2MZJAt-_Gi3i^0evvWJTVazV1eI<(6Dchs&yZ6Mv6Lk!6%9B)l@+T-?VYuJ4qq zoZbqvH^mi}?};^8$DQ`{zg>0yXK0b?jCwQ*6pVQ*g0}b59&EXOB@T1j2HVLX9HX}= zoiLua^A%@86CiK3>F*wW!~J&V#*6lHrSq8S{^okSioQad2PkJ5DAm3ZQj2sO#T3%g z#MF`sA61(S=bo+X*ei}bu&Z6L-4YwJL$y7{7~CjbT_Y8)j z60DHCrgg9-Gy(we^p5v{w5zmJbOV#sH7$`sz>?Xbo(< z54hfr`GO_}W&SDY5|Lwca1HCQTG;T>*sp#9fVpOc*0x4kXu;Jo;Ot6K4h?M-dBqJs zkyJu4!?+N~)UfMhWuhwTR-(Wt`~_S3YXVKh30JM~0x%cnC=Pp26Mcpg$0}Y*5Le`< z2y77{JPZ<TIf10asXu2>bwB@^IjSZ~1z0l{_&W zqj3>4@WQ$gSC}zrrUVocVOB_i)?fh*x6BphZy?9f5k>JC{ZSFcPuK9vR3PgUT;K&- z!Bt>^)_}qSbxsgl^DHRa{6ez$2KEYI2v4^5kxM1;C3{kfPt0`Rt z7nKq|Vsa%_Qe9@zgOD)2qzEB&zy)ZaREn`*g5@a}#>c%C{vRcy8TaMCc z3evrHYo-7o+7P1^UcdzqVN|xUbY_tB(h#85^5)1A57BWjWu-9NuO@qvG)r?-+HElo z!3AKT+SZ8(Oz&3ikynaxWLUDAk`gqrMKmpMGrPq%e^XTGsxf511$H1*M(hYpPcIRp zdTbFmvBflXs4XQ75p}awc#~VC(_yxgJ5eot%8W4-!3A6(6zJm>CL!p!QdZ&*B~7sY zGpEzgn6q2V@;WCYJF5lm@@g#UW3_ng1}NYLWaTgm=3s_0Gd1$Ua??I>1wToV5I=7| zw9YX?Au<)gRc`a++D<#+(^R^X=Q{LtK9fN&XB}~CCWUG~yM;g_<6vSjGIqcPWPm7D zk}vb~L&Gsdxl={$aYRWpR2-Bxag_i3atr4p1f-$?RFN@U0R~*)5VFrhrv^H6h5F2= zNJY&@e{?>Alpv|}0>4y9QSA@5LjVqxF%W?QU?3zt6ieA=JAjW{I4eQ5N-(#yRJwFp zc(hu~k$9>t6^?^Dh7d7mzy)+*Iw{gQN7GFwW=Q!@M@6MR@02m})C94|&`ACz4i2UO zP}Cz`02DH@RN`+*A5^0lmAArFHnnt8-=k6+5K$kQx)J=l~panRWY<4>C~3Eju!gMuox~eAkzgB@@A;>F?Oh?fVEg>k#AUcreEJ96$(rLP)b8$z&NqBU8e*X+i@f9v|Mw=0{}r3$TYG_ z$V9Pg`c&3c{v%~x5Fy4BBt_*8;RCWN62BPM(sDLFBvm)zAORplVg5^H7W_b6h13~m zr4tmWF)wKbD1awpHB|gF3$xWIy>(Vl6x#x}Tt&bE7K0XAVL)V|Kn_G9P-HGdLPIv9 zQ24?_mZCyZByB%pAw)tUiQG`S4Rw)`+F5I?n&0-ebU}_A2O3VTjB6ATY*Kg65aX+F%+}3eB zWfrD#6WruS;+AzOmv9M%Bd{V;G-7fC_asu+Q0x|XW8`&pmrY<~co)}20@qI-*K;Ko zaF6#ws)Qmm0(YB)dg-=vwfAG1!CYl-nTaN01l=`c1!~{c*A~CBY_pTflq^h9XNvJH-H_OJ;?Ps zF+((@g1JzE0r2r_#g=SW!Xp^Bdq=oa?jk2VB5h5WPg3|TB!wDn1&yOg>ATQWg&Fzg%iNm zNhh;~lURl8qH`wYh%ID7T!E&Rc!C($ir2V^&v=JxAui@(EJ#?4PuO;)_>PhIER0x= z^JF6u7mwXoicRE?5rv4uxR2L_a)p?XmDrGtq>xwsIFeZyiACa5Ko&9V<398wKl-DC znNVX;Hr#f$0+F^_^k6#zV1v@MHFY*Vz6c;Wv{|w0V>h|?7=QyZNoWHJLiw#JQK4R7 zLKS3y0uD9&x)1>B>h`WSN;S%8vt?_4w1YDM6|k9>eR=AlSs&GffRTd^$kRNNEh=qx z<{Wlp`c&;sIbx}qMDI*Ag0_?!t!nvBT=h$u7lRXW1^_G|K<6W!agt)}`C}53?-n$d zxs;wc24aKepoJBm-GdgKWdO+YLMyPerjk^tcKP`85EWV%8MZ?K8sby-X33{o!HI*BN6Ks_OE|@I#Yd8(M zpgE?b*)goens>;0rc>G`shZPvHUy@I0j3o)XcZL>COqkEuU*BV<*cdidY)-nd!89l zHS?6;RVqSYGPFy9Sj&_<_QDj~Gu!&H&n2%R#-`sxuIGBPgZ5(VrD8EjGA6X1Gje4C zcC<-5F`znD`&u#}+N*b_WdlH_|7PQE?PY~kGe5eOa67jVVz)yjYn^7D8+&I^VQDvD z5oz{Z7A&)R``u7GwZ9uO%(q;jd;UJCn;*S7Xux@Nn=3LdM#W6}pC}Kfog1>Pv`%d& zwB2J9UZRwOXLgEbux*pIxf2TQ`@S9Hyyb(jn^ExkNsE=#q8@|NGF$D;nlmBXt`+<~ zO?wB!JJ-4yl6)0IrQ+BCP@4jsxvSj6Bl`nG zoHDjMuQ)wA1p;NHVi*JR0BhUWkA29m99}BDtif6!5u$zoz?SmcZUQsNvz=16yBH0Q>Dkw{*zrBz7ku5%`m_1Xqa7Z< z2;LP{J4;9W9;wVwI?#Laxazy075Ufq*j#Uma;KOSe-JC!=VbP_z@FCLuW zJod!$;d{Ln8@3O zeqvypRd=4S0e)7uzG0_6=&8*ems{kIUbhvVEq{JtGJfpcMNnMf+cx;dY1~541gC+< z3GS}J9fDf|K@x&XqusbW1a}A?+@-PL5(oqj?k>&n|K9oD`lf1TF^gHu)I3$s;?!B5 z&8fSt`}*-*w-YRUNNoLZzMA7ujM!&>cQEC<3tOFC5kFdX->2N&o}oT5{&bA}_7v?+ znShB@vdF(zS*Mu?dz3DR!z(*i56aZfowR0k(Cmd0(QW#q^T!I_|88oOt*IT2cMqB z_Wc&`I&Y(&FH^NA*-DNK{m=X`PM`d&l>=1D{%(`|BTmSlXJs@_77ni!#BO}P?0bAK zw33)V&R*R#LqsEX`<|2jbloAXTu5|1BK4;Hx9rp#isA57Ho)~FJCOj3k!dRO2cxM( zydN=n@?X~Sr898u{uPeI1lU*k8rHtZPT17b?dg+Dzp_zn&L7jy|NV+252X-`(Aj_| zDA|cS-cQrYma6{ME?viR zlhsSw+rPPtEwsFzh(2ra++~1x%y)|1?H?tz*;{9uOr-jj#Hx6>m9@*u3waGC&gx0_YlINV)x-Cs(cU#~o#j&?# z&cteK5!Lp};m>EjFm#)wUuwX$d3^_WjT; z+o(CCo$~N97

    mo<)_#Qjoq*eV}_>AOOuJa723I4Yo<*N{p~Y+j&AtMYC~F9*{Ld z^fa*buITRgJG{KeF$(F%`_$B%B9+VZYKd+BE#P)^Hhyq=`vWX-X{n}i#{mqgC-|E@ zg8szXP+dv=^Qy|Oliy%t1l20i3cenr`Wh1nuqHY1y^&63vJ?vO+P@0%~a$VdpB=h=x}jterQAp=$ePQ;jzi+X`H`1URulxrw)LvN3}@B<#t zC)5L;uK&gcAns2l0-h1i_}u_3mq65{w{Nka-KeZC5FE!`luZvwiRP0){K~b5bDFv% z@=)LGml2`xEkX(zSB*Fsm;nw8i)b5XcWY$JI{GNp*mdUQ_VWuhPO7|6>72%=SW44* zM+KP$UG}gLY)f1r4;k`l7l(R)<=@-7R(d?b@b@P9xUe)C`ZwIL$}br@IZbk4J;Esc z!VR40L20s9jcC6DxsSGKgM!tXF@6P`SpN(JJ6htMS;3jqPtYM@^z)dYufv;028zr| zKXAf`*fOAfOd1yA=#s29E-=zce%lH!sa;DKTD@G$vJS(~p~U2%KmgGi zrgcgRLf^vHVw%Fh$fzmbn)QOKT{T5uREvu}l=Xv`FtgEzCa`PF7p`qbZ0_}qUv*nw z*#3Ma=bxgh{0+F^%FSZ7RDJ1a%YoVYS=tmcT~2sN&)T9#tBTbF)d_melYhd}x%TKM zB38Ha0UaeqQF}b$MoLA27E#g|#2QDkI$*R{EP9GYDgIjMS=`=xrM_5cQF*rC&A1(m zK7Q0LUDE;Y;p}`if#t;B*UN(0lfj8gDMj**#b#5*JyF)&)t`&XnvlzNWg_Mp>>EpU zZS-NK`%^WY$@vaPqeitGD#y^qQlEhc&AIahkL$S~!A@9O2OpE#v_dOiS%Q+WGD(aO zlDZ#Qn2~<^P`--0IkX&Afzd^p{hzpPRF!-H>HJd zk6laSer{POg`-)F@M~=TOt$T7*5z#u)pnnx(ejIiIn+-&d)OQ|{HYm>VkeqmkxA{> zuxxCv>v97maT;g(B zq}XPW{Sr!C;W8T*dDeV9YuU~TI~hzQ1p__mOQ(?mL{>SNx3wcqIwoioU;=E!z<|WH zVw^{>6`PaNFb{vNm?3!U>YHAly%UdmPCGHH9r>teS*=x__2xY(S^9@!tTbn>)led` z_m0!9j#7g=`~utK0`WBg@G)ZU6NU~%ty=^VwJpbi*TgS0j(i86E#3)(Y2wDTY=wv2 zbS|$clJyJKG2eU@g|W$?fm&C^Xj0vs^ck2_gSU;3+G8ttzSQJh1?2D}1vUlqP!Uni zwy>%K`^|j&_`4zz?-f3u;)TkD;~JPBvAPK33>WM|x(qkbbQ5(pdf;1==2Nnoj8BG3 zqd}3gBemwH?y}3gn^wQr=MY7aWx1Eqv9o?npJ2Y#fgMiwN3erSfE=PT^!+z$%vENH z724|Khq&6>{?8ezOM3es4*O}3kCIKYbYI#1h^0K<3V$2694>rQx3ZE1)i>T|o48dX z!#jTsdo;o-!Kydjb4w&xTBuQ~_Pe0GxcT*%2j{qV#&Nu~WD(viCciIr6DKVVxBgd| zAgnCBN>aWI+*W{ijr}uCjwbGyR~WkS`|{{m9E^HM@x!BYF6#K_v+_XTnK1mfKhZEE z<5ypUu%ba{LguK@(MSB2u0EBDSX}pCUp!u~V^0vaA7mZK)7~{Mz`lOT^!^(s0NYZN zzUjnV*sci{E_a3Dc40^7aWY z>UF?Be`^^|u0wh>1PrUIFxHH4;Ue?tjTG;IKsoif2g&@6?`;WTd6@scou?A|r@HHp zn;0fc7+5UOhs)jH&@R3O^z7Zw{Ij?Exbh2VFfFX8{*B7;a+ZhgU+YzlhcfQljGb|FX$ z!JqP-d2~a)8+|qHgMR(fBP9+wOAda+?Op!b(MJGc((I4;P|Ab1_-0n$)+Nm*BK%uZ zaoCppx9Fh|4Ce4)`GBo=VNb82RRSThp23tzE`#r&V5DFo2!w6!OLX(=1USL{Yv*tS zLYvZ{z3X7Lw6EUw;T|AoM+1xZX&Q!$%t_4zu^?|hPvR88&uNN;G>Zln240Z{ugl>C zWz1aK#gRay$VsM1;+_cap2(`^aNxf%M4nH68bKe3P#F{Y?{#4DuD#F(Mi-QzN6~Q- zMA%IBdI?G(0%B{rwZQcZJ?jr`m;?Z7fNMXaY^E6$4g9JXKM#94=9LE0MU?3own%>KFkesw|htj}Ob3o=K5Me+r zNzVtE1eOIRu#_dR4JWYgC2#^0xq*pZfml2ai2|@hp|XT>$wcA3L<#GYWkUfjkZ#SWI@ zP?qv(IK^o%#Tl6D%98p;Db?K})dQC5RhH^Aoa(oi8URd#u%xZc07DnVY=?oaEB$c1sj&3)vh>Wd^!VZQm)g=imW((hz5<7g5}}N0u5@OdjMBY~ zAHUP9fSL75nUyfCMp$O`UV6)LW($6;jE0N-Qf9?t-?X^@e-OOk5; zWBt4Z6yn~+S?%)xxbm9-80Z=lUTa11>wr>L0`$}5LL|V~atDB8dqx%=YGqME)|*+WY!`A$$_Dq;EE*DN z6z;0?_`0TUBdRg@z+$TDq6y6F>DUVsSq{d z6`#mlPYW$6D7Jy(eg|YWN|i4h(Y6+Vyt^&$41k$gIK|d6qtY?=sbe9s<99{J@@U7( zLC0V0&ULoVO_k2=Po4iFJNGI&4@NtW4mwY;yUy6UE>ya%K6TwhcHLEUJ&ble9dtco zzhsBIQB=Fp9J?{1x`CD5*kj$ehu!!%J%r#MV%45kjyK`h+U`M8^8W4*Mi<`lZ1AGOGP@ zj{OQz{YsVnDr5a>hyCg}1DfCgZPfu?#{vDQ0mI4xN)FUP?{j zkz;TLivMfzhx$eE0TBKd_k;5qhw0_%KbN11iub>`9~Ne2K0ZDXQ4uWw!0_dbB>?pc zDyKK6sDr48h%^B32>|c`gFng2$ov=jV`^%u|4rZ8+S<|4@xRcYmj$CF0ALsZm<9k2 z0DudW|F}OpsQ+<)&I$ex=npZBm@=A@E{={ZnN1*5fGL7WIZ0V2Uq-h=*Dlk}zTV!u z-TPbXH%&m50iakC(CO@4`GWrZui_60@iQgmf5e~vmHQDD-TZ%o`}yCYpUB9>#Ki3E z?6l;h{LIXln415#ev1Atpr7{odU#jYi}Leg{p^)>yjVYByxYMjC;MCX zCnwkcc3z;Lo%5Zot>?qT=k@iQ>x0X)v$N;R%gei$`}}fVzV`oz&x`o;>Himh{@*SB z)V@@f29maFGGTK`mgYt2k&Ghy*%L??Bq`7K6yk%GC&9H}y+@e-Z-_tM$}IW6d%D4m z_PKkKLC9-|^^@{!M-8)jpN<+AZ7YtN{(L()`neXycHF#`^69u`x47cC^|0ySb8El9 z9u`stW>T3{)*ufUkeRh{(gnZ(pLV0Zc0BDtOSM#B!4x<=?IS>`dW$UOVrkl4&;Yyn>h0ySH^TReUelkL=ZgRdDp| z8ymKwt3}nLDUt<6MrvM!1HP)!#kk1wQ~k2Sij<(H<*47ShUn1ByH$lf>g6Q~5ybV1 zF}9e;d?atD*OpzEyw^eyGvnw#3mN~U{R)pavy-x!9Y1#iXPmCyRCoOn)+`aw71n|= zhqfIiE>z!Yb$zKOVQ-_yyIB+YSDUm|6V35B-+~d^s<}*={J7s~cS3yCps&`tUB&6% zdMkz&t8*dU^4(u+tIhUlTZ(f)^g-;*^>T4{GiRsxweSNuK1&_h>Sn}XS2iDq%f9y7 z*{*)~{GSO>jgJY6*RZe(18^tnw_2G1yZad zU@Yq>DM6B&&N&nzQ1%^7#hzqm*d=Hr_ze+ZT5m39{JYoS5pYgPl32)Tm}I*WvHNSu zf9_LWhLyv_`oshIj%Umrk=f|9(02To8sEh>Q?gIz-9x5?0mX^tL>GEeAR^5`Csd2= z4TAxs&e|~X{`~u2yNNg>?D2}f|I&ur_sx#SGjYzYGTP-UsIYR!q88FJ{=6Q@<2q;l zo4CQU{8JgDSSvXX{DCoYQ8`;sD_(_fo%se+So7XBMXQjGV_Q!-ubs%XaZHKA1Fm3} za29K;Q$X#kubO8)&7AP3NOQ0>gQuJ;e5}6!bK$m6389tII%}&*)I6MSGQ&Kqvm@fw zJ3i|<6Y7p=qeuU@*X_BnmGVHc#2u=oKKn=8<0xd9=WW^hV@49D$E{(>?8PBFrO z&GIp$jmW<9l2zwV0?9D$}PzE@y7+L!=)SGneEnrevg0KaYq{h;|o? zAas7+nf8r1zaHPFov3OLa6+C zr9e7jyhU5M}s#Ae*du*CEGp0 zmGoSGzVb#!M<+||7E(r%YBH#PB+*K>o(EIMO0g?$tFaa7yKLz)RKf_!xFffP&UZbW zYTjwa*K`YM^`Rv@AD83h2_TpoVn0-GMgC9@CWJi8Ie0ynnWyijGA0SS_yJWDu#MCD z=+C%RtJ@l`&q?}e_Bb?Ivxu~)1ly4<&Q$i(8e8};s*4kARlfcqdUdhYol5|XH4|80 zj1Xi}_y&YYB(7wEuU(NyT{Q7mXC`4(LyRZ))7%J+YO}}ydVz=gKt>F_gVZ?VO7ni$ER?$iy{eC!36Kh7X zkGll!`%b~rk%+6Im9(_@^RN6deN#Kx*(_T3@*c;%d@_R>Gh2SPE1X4kl*ZA;D0gMg zaiY(O)h798IW2Gb5#Q7lw zwJVN|H*$Q{&$1(O4f*YVamtP{j0;xcGC9wHKM#6|AfXBEC;%`+nJ!%XcsY` zSKWiBmJA2@jb95br(0rfThAW7^xn^6gRp*afzrWajtBrSntw0h*)8sqW{(IaB}~GkmfD17q*<;=uzkL6CDM>sPyhga-Tsi-DvD{B<>uH_$-q`aq&I2o5~(Ey%fn z073(DW-oYgy$ZNq6Rx*ebW{5N>j7u??7ZY2M0sEOg zjNvv!8XBZ!AEI{~WY-)vFw z&@edw~rc1i)@ES%^E~c z3P%4XiyH8ZUVui<-bOFMquW5yzFZjT@-gGks6J?P*KTwLC}xc;^2k2+rw7Jwcuccm z)Cx4V3m)5A8qrZ2TVW8ha~pA@82hjrjm;8=!4lOi7=uS1b4V7u42|!$$B0WMr#MAI z;|@gg48&8!hG2$E*oRApCAirqB*7C>?GaFRSRlAL=2}T7E<70vF8zka2 zCo*~^h>#@;FY-DphREH92nk`!IzWhb6M0`c@Q0JEza+7OAewuLVt0v*z?97SBw2W} zQ456Qn|Xe2l9pkLj8}>id8%!CC`U_(OId=dS1=ho=yO@3$6bhySF-e8Dho@Pji)eo zJ(TJ;$rP9t(~>5JnH+GJY<36v5FDs4nDU-HJz6PUnMOQ#&Hi zPvS>?vbP!lBuN0pX=eAG&l4iVCQzS5PSW=NHPQMV;pQG;Jy+)Lj*DS|_vh`e60WEi zdT67=S-wN2NhLPh9`E&nbJ%UXq@=znXyj1S`s3?+?a#r6wsYngd}Pm1(~B{5Q*9?& zvVSTW^!)bC!Z003C(wvQGrjulIszlnltirzL*vLGpo<_z#`+}ZO#l)mXT{R&l@nH^MUyr6P^&4# z;P#E~&j%wF*e4g1x##VK7NN%%w#gSaN*39@P(d|bM&a_~LPTn;!0G* zKE+Iyj5lRW0*eq= zxpGHd@%K`BeK)Es4KP0hewP)})NF51OSHC(xxT)$G)wp>1}=IQGX&Tx`%L)H7cl{DKXQ|0zk6hGp)f3UmS zqAz`ysjbyUMSRaYt@OR}r)R5mman~WFF|`Cro?vqrf<`5Q{UZJ#3EG}Yf)!PQB_(l zrmc*c=py`s6`hMMYelFgnN^gGjW|7{UYxKnshjtu#49Dj;5zj?&wzn8wyVNaUhD`) zRd_tk!gLrPeKB=zP_7c0@)$Zp%7QKUK6Q^pNqc{3G;iZd=~!I$ z3ZU>CZF3zLA+BN5Y>t#JY$G~HLpvXQ7tp4T^hk6=No1(fXyem-UMTb|LcAv5SyW$a zL#n#dW|DN@{lop|hb0gBb#HS(S7V%oVs}r5N>@Y1=OCXZS8S3PKt;m=Zv$6b3wm95 zM(f?O+e2hyHJk6taLiiSll)OcH@D>VjX1F{ae|S_#=Tu9W#6O-hIF{+xV6*dl$bfgRQpSED@s>F{ZCZAl)`#ugBV%z*87}7TuMbH5F?&mvWCOYudXMz4nw~wD>t&K%Lh2Rqf z`V(oDSP-AWRg4y`Sl#Pp6VyjuBNSNMhijyD&p{LGT4)APBx(@!iP9^g^1U2 z*|~~<8f!vWVG36MdwF>&YwWXZZE=Sxfo1XZXvzF7m6VPcoRQs>u(eT@ZMg*{b7e$o zw952^ePk}HMem8&&D4x(s65cL^!aI+NUV0NQtqphS`aSL_(uYzWDCbX>K4>>Posb0 z4!_AC4boDsOp7f`B7J^#w5i|Dtr_~eW->*4)KiACL`u32s$J(^pGWIal$6a;hLrl{e_eoFH(|W17s-cprSD>r%Q-wO>WUI5cLe&GWU!i*E zVPQQoo^R2Cz}sYA^w-%@HRmxoXQIC}DJ%V6da7WkCyRCA z2UwElK99q`Cn&M*bkpTFy`*|SJw4PK6Vf2QUxk2pO@@Cpfa;P3s|hBFk{|XV4hA|Q zUg;RFn1>^ssocAVuE3Oj#Gx`XwvCm!g-a+VNXggh2)yg9IC(fMe$-c;C@KVDB2SUp z4d>QLV1yn_YY=T1^twv^y3Q8|zhr@gGL0=0fiK zg+kXk*^A*Fyh4ci5F#fr&#HDF$w8`7+q1`Kavui>1Yu>IXvy+&0%or1ii?1iw z?0>Iz1$iAmkkixv&gxilKL_G^@^Kj?hD(G&)gdsmq^P$r;k4Uu&Y*Z;QnXpB1{9k1 zJuKz<*1Y-dwV<5OWQ}d^r96 zaaID-jF0%kiTE4vl0ZPi?sYJfLd+i(ra7NuNUN5EBlHPhIfb1#2bo}WTQ%dI z(<&8aem7H8Eg-9xT&F{!pv%aZR|y=3&by_ZEwxleX3|4^|?d*}6?D zwi;%i(i_Y&qyhZO{>y-9sJOE>o1z^^K^G#rk^;#x(SosgaN>E=9R@yB5qca)wRv?# z-5GmsPxf(A@PCf`>K0Ps)u#NXyhcd_r$|3$%(wOW=nwG2^_v_A*R#fyNQF0u$9-kl z9EQs(O)SFRw9PMFvEQpbPPdHMIyR5NjFZM4oaZn4i?FTJk^ge#UX;wD9w>A`~FHX20CE^Mh2)$ArDt{ zB6oXXJIOC)@IP6EqRNq8d*Z0*x-U2yO<81YS|I(`v$uJllXvUt!8u%~1rH8q8UA$dSE+hAz9mV=QO}nWS=6#csOCi!Dlo zs&M?UFwjRJsuoT|emU|(=!xzMFe01req@HLEH#&IGNjvq{Sdg;Q%kSZ8~=c?(CDl1 zGbV7DhvspP8nj8B>?%6?gnz~;Jl=Gbpi~@VMitMO3J;u~-%B_0(q{<${5#KaJlE=e zW6?Auy{TUNRss{J>YBntZG?AoX`z8&Nb@Z2fd5)gUu=GC#y_?mMiRlwt+R0&Slo0P zFM*LQGo{P)O@>I*SaGw1ml?zc!s&SUHxBG-+W+&sY}#OuPX9rAX~8W7%E@!z!K4qG z{#vzFzf*JHjTi8tc~`DYeCt}DR|2G}eTeIxS|?#?RZ}eR-nJ)m$n@U(TitWsm@9GS z+$kbxIwK=`+plOUH2_EN%_Wda;9wNznXXCnAs3xU`wV)dQOBp1CKudWtM7%Z&-l-f z;4>;;%F}rR?X%5}ti#4C3b$K+RaB_6)I~NPueQ|d6!hRUi$76|!p87hf(4$bPGu*+JR(8_NIYx*8Z95jcsWS>< zlNp~DJkRh4+M4GArM{MjW~-fP<4feL1T}<7siv3M+6pyz2MuJO^s9)X^r;h<&v>KZ z4yR|8sfNolkia0++GHP7e3U1QzKSwR>lbKr>CAF2k1etN*2)emv@Jj$9w8>#O9-@` zEQGLZJL9oxHO3`baiU>sv}lbDr9m)ld2#hIl~CQN!?EOXAj*$It27xH)<*K4Nzl6n zYe$2vDo0Y3SIZiG5>&S?({<{t2ciRna#vJ8C1n?X6HT<4vjF}yF45b;)D;DC=1F6# zKP7VhFfDweG@7z{KM$(V9gS^w*C*K_VO6G>u`l)^?5e6}+BC)Xu0L4$qqEQ|)$>`{ zN8u$RXd@n$bzt=P6;i8t{6=4-@mSQe54Zo8(_w=pqcX_K!*r|G18Zp*c80m!z^!Mc7rF&ge^u zl~4R+li@-(0iL?x#lY1?scmFo{6hD8Q30hShK%t9v6lD6yJ%h-JS?m$jBlP8`0Rx3vpO>X9u7au_q>X^ zI5G}jNmXhlt<7mxAJjb04=eYx{+K`SIh{w{5=dDRT znaL9NnXZQF{Jis@ZUkw)Y)C@>Y)~d1e7zBu=cHH!GJf!Bvwk<`LMMR|6N--abrWn= z-0}h++Mrks9lZr{KhG15ti;f)vGu!?nBk(3+crCTiR<<5C>KfX%x+@TuJg83#*GM= zdDnE}&u-6-G7yPATxzGKn~*^&?pA6WiU?%`qX9r@7a&+gS||qzrXiq@n=h7!L58am z?IoYWCo04HRfgY0=3PTid~PUzNMD6UA3sB%2u|OR$v#2ZK2B8`0Wi>D4aI;!mcyja zFfO#{Rz_5|Pn4lwX-h`1p-1krHvt-2N7E;d)34~;FEH#w zEy|_~4q8Xa$;rwYB@GCM44C#0avcsD_4f%!5y_* zN(XaE1)B%|TEh`(MiE~O7DKEB2a+fTpehDX!GmQLLmr0$QQ@I{@DNeOa4wY8D zF-vO&sXv3FR71w9{k@fay^pC*;4vpvnQ+0r{@HA9ePGi( z@vgfDaVtDVT4b3BD)6F|>ryR*SmSXfL=_Oo4-a9lOr)8OqP&b`rs62>CfP7cLu{=5%+>Ppo8i)s)+*~H2_$bCmm@}m;J!T-GR`v_41Jinx>$XBOQL+b1 zTZ2Ijp>?U;M*7gK@emECMOF&bbcXay-%4cHjWP{L5H{kDd;$`?gY)cra*1Lq%`xek zky#iMY2Dun%R%4tcQ9uIv+3WVJ!wVd(p`89klO$SUm~Ksq!f(W%)?LU3tF7>IhgyM$9Oc%A%k#& z{oV~S;$m&woc9rX<&~`uDb=U>vS75fV5O}c1eor@X7y;KVg~^Q8>hX!7TMhvOyt@_ zocQ&K3^QCpH<6RST*VUq4yt$=`$VK^Bp4x z@HwDyhZd|m&3gKK2Ek$mncJe0x|12Vl_vN2s_V$Dw=`C4$)CmAgP$-`0oufMwa93apeUu_ZWge zX@bc>BW|N5%_}1dhj}aNUb1bPu3EY=*9Be+R5GN{O>bmaba6*Czr5ccgjSJ>+q;x) z?&Z9`!JAQYSxlY^z{#um8TQun~}xhssnyr(wJcwI3{7z)+1kEUxj z*`YV+vsm)#FphB3A8a#CsWI_#GmXv-?Vk*e%nc=$BDP%m5G$#%>;7jtdo`Az3%0F! zAx2!-%ku1!|1J+rP*+p&N^^Q{CD_0$zv9E+0pk(w@{eMa&zL#M+(ult#sEs=qwT*4 z>JArNL8MjYKe({U&7ae(v60e2`st_1q5 z?@Mc1V$k}^f{1@qp-s~6)BLl|dbp}@TUML= zVN1ih>mDrp45ynRKJ&j_P#b7Nx5pR#vUT3BT8H3nXw+_e3$5s{v9|EuqF&M>6$A3V zkK$6acBB0L&fmr%%H{~yoHz#h>Vbq7Cw4wJWNg?7bZd#xyJao5Zpm*efY9dL+z8<^ zRxxFM7EIL8VAc>!q~mH})7o_8u$5`jxT(+$!Q9pqXURgar|rT~*xk_1UIm+{Ffzs1 zS^C>}qMJcd#MTC&P0JPx(z`5{P)d_7=F*)4!M`*xb1?rd6lD2%q=g5$LU`WntTcwX z=7Y3~UA%Y%S?0FX`@cgg_L79gs(4lqn$XRJzmpxh%uG{8E@-1u5&dcnZ!suB_LI*NN0Ub+pa?^^(0Rp;CgI5l3xjL))8gEa%?OP@wsW8_+d<+xJ}Jj2 zct>bILivRVVZ8LZayT7(Y1g(``ZRhV7bi^mj~>M?pZQ&!@d(cb<18=u^wyn&HAvrW zprCb~LeoO_#e>a{9on1iQ;!`da_ok$5GU7zxDu{{z<)7^LfkQHXSJRu{gOdDx&|zx zyKm=Df|}39@SJfMB5957NU$z8V3T@LXhay1%BM*-#2;hf*1`vFBnY=d|6TOqQ&aHE zydN`_I)?6FG%@fywa1r+nQ1zMZNIt$F$rj^O{-}5yoJ0GxkTIt6MkRZSl(JpR`ttT zve3KII+ECQJ_Siqfqkrh=C7o$_^i+MPf1vsk5MjWkI|SRl3#I$A{AX+c+?&rDOCcL;gb^7zovHVDVuJx=vxCZ~I;bpITiLmHdtC+DThupy z`)-R&ciSD?^Q~GVfz@+?)ec7k(M@tQ>2{h@Z5i;-MPd19|Ke2lCgRxk=rpky+5LkZ zj+r_R7r{&Wg4kFHZftOYhacwTnap^H3c zkb^p>x?f1QKdLFd`TM8b-`@8F5LArRAfKPk(bG4i9_@#`cnV}e*KZyNwD0Gj)?yMK ztGS_kWOtyNI}807*P%JYZ>BlezekT~H#&nyG&?WFcRmH(Bp3S+f9=uY)p5q`3~YAr zlzs?R;`>2B9;IAM@669E4Qj$bkAA2t574cqq^yN}+^`P5SR(-Wf(Cx4w^ASrD9X z)|tGyp5rpoK*BU+(Sn!jMoxf(v0ndA@rRx+%l<|DiL`^}8VY_=FNdJ!&-V3H*VI_e6k-ZD%$y{mXL1dSYplMkBF@w{+3+dam_W{Kg>GFA! zL5;agS&03{`J5jz1qAW^aq5aymhtEDbFAZpDGHMfMh_QO`fV~E*Z)KO36_gRN5|6r zXz`t&_>=W-dyDz_Nb=1`!2~z?6!+KpuV6we_wO9@<*iaf zywk4-BAP$JEPybJt*TZJ^~&_rW@!y}a%nXmN}-E&bY>+BB~(?$U5waI3&Zsyx81>g zGFhst1zw8{-8FpJe=d41@MdH@zGmNLubpp-puQTsCyr^ZGq!(V*~)+b@!sVGp)tW< zIW_o7$r2_Bl4J#=a|}?sJ&S!y`SLJahY^ky?{r0*y+{!b!nM=`AkzlGodc4Pj-V%R`2xthFB2-FDizcIw;`#WSfC>$DO_GUl z%HCX!+cu4YMT5Xq7R2X;zU~jHY|2nml zN`FH=4P$zXDw!r@b*z9Lw?3s{2y&%`WMqD{i7=u0n&HjtmOwx_;9GyGv|5VWf(&%f z;;$pOs+CS#3VOKk6~&HmT{ZBZ)fgAyzP{9UvCTay7=MKXe_SHN&YL1ag|x4gJM4se>Eiw(Ej1 z2_Idhv4S1B`q`}h)C}WKWDzic{kUmV*M-}4^~%PGM&A(4m_&{fiyWQJieO}&gR#1# zu|P>C$T0fo+`KSyi@-Cvmk&JRH=W85oH8Gp)v(X%pteOWs5hHe*Ae>`0+Cq9ck_-y4N?iYRVJ8ySOzWYBNewuiC{2l)G z`R>r8>uDf1aN)r0y4eHc0j(x*XY=g?LcdeQ9Kxt~`}bz{Uxz3TDg;k97k#{>3w0Vo zXuOL|+CCY=*gY=H;Y*8Sr5N&dGWtCSnHdU-f%w(C8o!gibxdy04v|?1qxa<7Hw-2H zjMDF+qEvZz{-AC`WWtDJ>@})tbJPQ}9;`?M^Bee0C(=G=z!tC7wJ2s6Ee}`lQSjOg zgW!M=5kbgyeQ

+~qPSHu z2aTiXXyNHy?FAhb=|?UqutKr?T1@dQej%<4H+AdBa78t$}@#UG~8fkxbU34?FHZ!e9-DtCm3+dmQ*FjZyK4 zyXr46xrus>1KwF98za!mS2x&+gB@;@d8Cg9c3qom8z-@UY04!H-gm}1%9`>(*Z*602r7A!Y-?{4wl+c>YYRMk+S+@X)0 zUg4eT|JeT2O9SZp3k2y-=RN^EK6m@RpMxB1JvF66&=JU)*=a*%7{^Col7wslZOkWc z>09k)lc27f2+3JP3q`;pFB%;1&T6bfyhf2tIiM@*;feOdj8crm9ZvD0In|>(b!VDc zMZp`haDD7;h%yYh0aWC(>soCYT>7#21d-{F$Ri-~B6fYpJYT!Cov7{LN!GW!`%&_! z&})}vFK6N)=O>kH7}-^9u?-nBjom+)H%3y^5C>Bu;0qv3p4AE)i9L=0dlYeqebyiE z{LbnU0>-i(3<3eCf4sx3K?64UY7kj?;MoBpgMheWWkk8eB_6tGxtnwKB2S0_C)-=` zFa8TK76Gv{!XcY{y_D7QG?|41`aBT8H;UK4LQ$RQ7Ol(2{P4%r%(7^4aB1!#-0%SX z9#CBkG@jmi%CW^pM!Q-=Q>+o7fYs5*R+*>VyVRJ8nMWZ17pNqB@(zSQ)fI@1(0}x= zDkYDC7w=1SGt1_38EZdl`)QbFz#xQ2jEtQqJaV=%^n2oLVVcWfs=lcOKV$s@AZs6CHer$nAzMyC`~_pAG|Nyp!FHo72z#v&pm zQ&u7Uk@KI>@9S0@5kKQ5FsozJAMdWH7IXMcBz|W9!nHxK_qsQ6BDA2wN_IpxZ94RY zk}g6$dzDK{s+(521UFUG<1o|HEmnR~UzP)cNuYAj-CV1j)oKodi5#ATOa*~!+^eb- zE!)ZzLw|@$$rwDhulsHD3*!^K1}Y1(lv}oV<71*?iy6*Udk~JH`JB3exLL72!-c-h zZ9@+FNNG1$Ty7s-(&h{k2Rrt&xJe~o_ho?we9}Ngq_bU>`2g-{7`uDWhiWMOe@MH} zpr+$>(f5G_5+FcAk&dBvq*sB28hWS#3IZYmqEzW3gaDxj>CzDpMS7Jcy`%IF(nNX_ zm7;Q3Ywfeo+Gp=OckbLbnY>A6k{8K;p8xOje8oEZA!9I;`Pa>nv5WEg`05T#oa`N! zm$y&$^rY0hPJiQ)Jh>l#t;PVCj%bI?De1==WfD(mU5hP~IQ2Z_2*t}jmpB6po>(oo zab2>oJX_?xgc%^&8up-(MG-VfMCc#lB#WpCr z@N{;VH&Y)nEA@V!KQSqfpHF6l8EenMzuJ8LOQ4$k=-zZ;#zJ6iE#POnV`hw`kJEZ& zeO1o_q3>N8jV`MMurpJ#hW94+>LeLD|HjRfm-nK*6F66TO#C!N+;xnX#f&gE`|-)` z%^yy6I*oBveQl|JONOHbENbEj1DA5F1(J5LH8pI#sYb;wmG#acP%Hn;2hgvDZ*3Auf z+~&+5Uv#;gvXPUkY>T|Nkrd~5{{1}V6A%BZ$bhloi&Nh$@1n;cicz^Z)5KU;@%-Rd z{-I1d4YhAs#nft&GDzYk1g|!n-FfQ6a&VPj35eS;DX1}i;`Ua~*XP7GLLh@~iCG%| ze8XG0kbFpund)y-EDc|nohH&F#+t6mkWj_6j6GvH!#s`hJRXIRRRd{LH8rh1;C|*f z!F^qOg>y?5Z=k%|zDIdj7<=2%>zdGqF{+0zvED%a9O3zD_mkOf!RUKX?WP-fOfgXf!A$PFH#KfYD^e^15QS+L;5l^W0gzy z)pvu@5-igkc|xQPENWbX*i=`qLo^~SgHj+dC(${dn>v~!us(t*I%bsK|AR(_{$@JbR+%cBn&JLCOsk-XXeyvN!Zx3_6d}~ z6}geTe5+L%CY9tH6rG{GaTngbp8h8XxJ^02^L};v{C0w%f-mB@w>x&RiQK~%4YV05*k97<96Q(F}uH(L5iTyc~cTtg)v;V7G#^2zhG zhQ`j+InIRR(SVGcLch7oA;_$v@h4~IY?o&23gPC`H@6z^&mQ_Fcc+ZhKh&E!*T?2t z{V-Lf&A@!SqzffUY?0xt3O{i3hUKP4G~|pIJq;MFl+trZ%UqUr3&75IZvNr6y7vq% zG@i*$Ha^fg^8F!th2{QsVX4}WlpDq;&G)yF$Uv3Jn;gU97-H~FP({#^Rb zw2;KVy{iNd{9z#d(==Ko2}`;eTvy_0r8o0<`i&VsiHCI_RyMKGjBg%^?~iy8256cc z$TNg*DPL(MOwfvQ$!72!c;zPbo!F!KEfpNm_`eZO-JCk-YPN$eUs44`q|7rcuYP~q zZQ6Q>s2g;2C8c1#Y4>%d~z7seMy_2 zY4PAH;IgiqesP85n{Pl%)GF?7_ZNWgY_&L1cSNAP_17{vjob3*Wq5hjzIqEGaabPXGFV>*b{HarM>sxWIdC?3QWuyiMmKbPthW`a2^GtGRE_Bge^*0()@S0(xrgH!tAEeuOb;}#S zP0mhtFGXLmYXDJK=$=;*AbovhD;7)8;cvGiYm?7{QZ>GLWJ>}#f-4tBwe4mi`fvOR zU<-F=MDgE7p=D9`C`xR@A2mieUx$Vu;X&21yngB$-U&U8xT-F7b1XR^FYGA-AJakV z#?<2~uRf2$t3Xr2Bpc1RDN0~i*G9(3Ek=$?*^U#ai7U161nA-Ek)s$~ z=(xN-mk(4ydon8hH+}}PD!y&7%ZT{giH$``=ZRtYcx<9T5$NrEU z4)P}ma#vg3-|i}>M0`Dg+30jsBvWNnyKZX`E>BIU7CHXjtcZNqJ z8)LY!z-%LQq~Te_rr@V}U4u^(ta#%85$UswY{<^| zE1o)xlC{Di&u^L*jzW6~sl+Xt&IXhuM!#)u{~73k={JhH<^Uhx2GF-6$bpy4hVm=@ zu>jx*RN`}BZlmSsM%7qMBarNT3_@o7n{hmO%c!3pGZd;s`_OpXR(*a<>CfAC-lFmK z_7X>oCUw;Z!RNJqSrNbh<DpU zwXuD&5Z4To(~M~9)(K=>3?zsG6-T&>0Apd`aj{87I4TmOb_ySj@M1E8gex-@56CHb z+D1;8bZDAIvBplWM1gceRBKGYQKN(7a`c$8D0&{q32L>u_2wNa+M*jRidb38%dzeLN!Ho@6#} z*Bcw4y#}Hj4#H<4a{b%&X)bXjEoP5|BE|zDp7@Bnlx<-h#SYK#wimd&JfGB`-%&W4 zF+@*3=)ucdwPWLA)G&o+BOllrNv|RsBS7;x673*;IsOH1e9=AXP%~~#%I*Z)SwqI~ zIHxHuCd+uVSzJ5XZ3OesY?6o>|KS18tQ4iUJ~tL-kw8%U9fseYz?)0o!TOnBcS<7> z=F$A589WetYs^}HB9}%sIBz-<29D8Z*DicBbT478YI<-F|L93!P7mHZg*2fK@0s^1 zyyLn)voL}Or;otiO=S_$F0{QR*O?s?Ihh|Hoiha7#r7}6Ar{_7E!6SgYs(;O4hx2I z1r6EEk^Ep!7;dQN-j6V=JJM7n9wWLh?~TYUMq>)QNunzB=4*KH1%Gglcs^|}g!_c! zZJ*&&|KR+D8d@kMb|S;Su+~4T`yEMc}u%-!v7Ao-?$t z#PeJE<=u;R65f)gbZKm+u39*48O*h}9?7f3G@AN4nfd5UZkybVW)wHNUY-<&U&)L} z`T==J$$K9#d+CKgTnb-Nn>DOdaDjy1wT;vZ$6NC^Hxfu3#9MN+VYf7HwxpPrKj+&@ zHrNrqUJYcbkrHnB2Xft2iiVJcihPMC%-wBNepI&{Z85+5omA2D&R#f4KYqX&sq(VM zDyo0}SBLE9yFMGOMMv zTfv;Vv&Le)4nQ=vKNwZ1hcx}cEBincY{6=&>!s(}l2W&y_pH}pHX_{}R0772PuDi?4j7*4e9w&B z3c_RXpPcjTBnutj^$?Adn+E-~dqtnroy_DL9U}WTv~tqlC{Uwbgh;A#&KB9c7)UM^>1Ca%YM#_CN zM1s`a@rtuJg#Nc@J`kyuA-wyyNU?7{v3Orzh&oK$S9ILlhTeU7Gm<|{@+SiOX_Q%H zD~^9GB4X>xC)TM(koYGnMj>Y_d|dl@WGg;6tFg*5;f8Z$70#D+J1I3?T5~(ahCbGD zJMHJo*rHALOtU4nZYa4u}G={)g$d3Qlp;P0#&qPemsOx!)3sIUQaQ_qjD3^ z58AxD^Jk-Xb8az;AEf(khpcB-uid%Hl96)wt06zm-Fhdk+#pvo<5$^IWaDZKKWJdr z<&VQeDF^5Q2k21_#K?VjSQz)W^l>TG^33t$m|2{v7=N{&Xr0qut>0c1-gV$FD29D6 zSqzB#%Un{oWQgC5hJ>j$x<*y*E!NUT{eI;dk6$flrBO{yzl*#PVLcTj z7Jd~6dje|RyZul{_%%yQlk!0{M8j{VBmy#~{CRBi)BRAcv1R9P@gs9GTw}%hJE_|H zu}}AlKYL7YjZy71EpM2$+^pI;cMmqG^*GpWbG{oMI?+i+c6i|WL=An5)dWD-+?gI3O zO5kyp2(W zArg=mB6Y^_bnq#sp^B|K5L|hzj!J#!;K>XMAw!07;7_j4ydSggbJ`wGg^|N&u~%fX zC&&-HKYl)4vFR|U>(ON{IV<-RPdh%6`;KHPx%_!>Rig?x3XyUORisY-xaYPb>NXtH z%XdZ$f}JX!>o(P1-l}g;_)XMJJOWR+g?+E$B25c6XE9m`L5wYcyUD@LVY$^&&mz?9?kMyEdA$xlywS3_bP+QjE)aT z&G*6F;ne@?aTI^#W*olE(%t8U4_GYJ`U|^W45TcGM75omne;qH?#wsrr<9nNIOoIr z4S3U!&!XMr07pLVGw-b2&R=`|63rv_ZxB?XzQ_iLINkRvZ9+Nbeve|f0N_KpZwfWf z{VX(WbTaj*G4?IvljlDJ+z#SnL0t&m*@^Y~=$>{14-O<;9#&z~5?)+JP?2C4X_1!k`>3^u{@DC47B(9i4ll= zw3Ot0y))<7v+Gwic^adSRiRo4c&fN-o#T(KTHgqD%2JVUeI@+){byJG4Ap7(>4hQT zW)|(^M}A#1e+tu%8q)p+h}NpuxsJ2e)2`ls~U${CnW$l)tn;E*E@OQTfsG%HwUsp9)fEF~=_eyhE+1svJe;b+*Oe5lQ%5R*( zn^n;;B2M+KU7L8M{EsxAoTR~ZJL_pjdQ4avAKN+ ztK-j2i2JWwwuKJSS0GVnqL^KmTmw7ZX_R=cTQjuU1TvDh5i>%^0sez1Qjd$iI_Pt|G}AHQ64o!Mq^v>`UN4zqeviOLb+c`4&R4J(J$3V!K2n zH^Bk1Y#3uDU0TyuD=?iNJ=+)q&Y{PVrD!* zo@(iGK6RyCwz9#a|EvWKXR?hwpEQ0{PG>0IN=N(oHY-~r%!kxDa!fqJf0GHE$jxmp zo6GN|C-mm_IQ>mMP*vEgIA+ZbK8MOJej^76T0mQKQI%4Dag4DWMg=(2fcx zg0-`}7YiH7-9C>JD65-~Hh$IMldP)a&cr=~JWnq$diRES6D;wWpJj`%osln88&Sr% zua{=L0B7fnd-;j)%Orl(%o3$(loNiQ7+bwfO8eMZ)#mc4<-<4UOsBI_nU&9rW=snd-#pvZR!B!|p42en-$ zD}FU7AjwxXNYf)fI%Gg1KI(fp{hLfuZU5ZT3B)pNGlZhhPpwnaJtZI4=31I`%-upx zhnF!n^EnZ3)TJ>!XKIz6(Ukx7Y-Tt`_eOe&Aa^w-vEL1u1^MtX_gTBj#d=xT0;4R`7c};f2F?bZ@YhWE)2%mPA#YiLRjOTS$ z#gg^l3Bu7us<1`v55Xn9^3m${LM?dG?f$Ie6cIkA$GyX+{Afbq^?8*%d$r9QjVLO9 z!pem9$Wd>mo}9Q|@xDP;BT8{*d#iuE~}eTT)dgqW-nbp8zJBkhD|HbaWrf z{`>ozcKRG)M2TB9!U4_Y^b?riuyxJ(xU`t9Xrn&i3h4iIqln&(6+0brxVZPna}q1x zFLubKTjbX<34jL-;&h8mwLjRr8_yW`=Jc}7MpcT@%;TyHfzG|!j|C_5mAR?D;QRRc zIYtu-2b1`s1dLt_PG!AM;_d+LnAW_TN(OyTc^ z5YLJ-=D;`AmHU`MNM?56-UZ*wga14RiA)xSqG>B5o;>aixJYCJB@{+Je{Yc){jyQD zzS{VQk)3=2@JN2DI)_J4;m0d@%g9MhF^^05$pF0KI;doww48+D#I7g>M z{oXQtY%>QnuPRlDeT#;-P%^Y0@I3teeivriw9)$W;X^5rPM*Q#hL7Irj~=mb7Ki#x zd?aP(PM_a}jmlr&?@wKG4CjRNMgQ!$5x+*uQ4Kr_J?>Wxj4LfsikZ4C`PgjZE`7kV?YQyT|-x&IyGYvR*q6%exDI^uo zREE|Ndi68vwxucW^Z0?>J2XzH2b06yu{{z?zscl;HikI150Ho_TiS2<2OxH*d`)_^ z4jdq+<|3&QqRCdA@VR)dyQjg~5nhY2pglkMhZhYB^Opaxm~_qq8w}mGHhC&^tLqeH z-@9u^+dSK=EK{9Sw)ar7dG1rNOzmrteP@&A`RO*9`kJ!+t0!K~3(M^N3kJ{#_ZNzu zcJ4rf1H!?x1@$Fak6(KI)(8F*&C5UAWZS-%9X|iw{N?Xo*><4lQ7CQ83aN@*CvExB z+H#DbLj zN%lz>`MA~9feE?5=*= zULD_F9ozXIu-xpoFQXe@rl$T4%WW)<{8P&PpNiAx`TtUJ`hSvgi<8~gA*Z$f8OycJ ze{TNrsqQ~pP6vJ2yR9)>wa>qmI{sf?Zg6zCZEWJxK*#Vv$6(*bzMhZQEvJ8}xvq~5 z?X8X1WbWUKPOS}<^~3)tI$hhj!nUq|*}2C0>iXJ>cMY{k^=;R6r`oFb73HPx|EcD# z$=o%Zi>qu5{dYB&seMi6meSM~layzZ4X(*tNpb$$f}DR#JLTkLXJ!6ZGUs1h{Vy^X zo0RO9SNkypKe#4y zX4hoS;vZyA)Aq?bEtxFw|L}4~W;Wr9NCT6*x)=+zzL~m?$#u&KscHCsdpRZae|kAl zY1F?GPXAxMobUhS<tecxCV|D&jaT?5yd4s6>;77JOW+qbcuZk1v z*i5Hfb7#0WxO}bCqj}MCB0wjr-QJsY{DaWZwU?t|iQ)Ex*f}P<(5o5*N>M-Rtb8z( zqi@34o5UD%{&v3KvqO_CMh>J1)9s3Zeoc?ZXRg(b>&TDg7_>J1z!jK9Kb)056pQ>q zwstjN25UmD5cAyxwR$$UA81eU?0L1e{ke3T<7LOEu2k8OW=9YdKjLID+Ox-;`sUq? z7KB?D`<(YQBkVR-kQ6%VE8!4Mx_GSS^M3YV?o_8WlL{sE9Aq!|#)4=x3}mQw5SNl2 zJW|$eZb}?qALGH)%D9e{lt|_>%o#Bn<>Zsu-bgZlH;fXh>H^{vsEINE_X7@usr zI|M$EAlHO{gmBbjdRNj3-f6^qHY8wDSHb%CVevaw)kns@~>tzvN1SD}pN7JgWzpplSkE?sybp&m>Y zxZAKY{b~>8Vo=DZwn)zXM9m+DE4q7xZqR*zJdirj-Q2GhMEw#JguPxR6+UVwnaUq+ z78Z~nmDM`d5x71arM{)}^?|-CY7lr+1c!st|ka0n*r>JFiMH zpNBGltm6$VpzvT^LSN5^yQ~xVBNp>!5WXSSkLJ@)9f%@(9U}&K4Whcm#yR-~+2h1I z*7R|aMH01=_3SB1Na$2Y-{exzs1=y~wRD92cMek2ojY)gjbhk$AHo+?C z@g)82caj@g5j##wiB21SLlaMX?lH&T5>QJ%*DEdJJ=BbN`F&^%+}eA-J*suhuseU{955V$P+zmV)}c&_2zJEHvQe<-^-)i{M@{j1{i?_Lg?57GLEm%FYw>E)B(>Hnvf z6N}CNrQijez&QJVJD4uplz*m2&_>nt2cKoRM3avfES~f%sw3>oRui zX#w0C4zBX9zllXYMg*cq*yynow~Ti6V?&_w=JEq4duy)5WDn8MItb`(mww#dRI0Hg zr8@gYYPX%b>8WX5SeEB~VxmoG2bM7`tI!Gh*z$;!GrnzWLz+Q=EaZ$gaVlLEQ7zH` zshtD5%fn5zx(ecZDR2d=WF(d16}o#%+Snj=e@(i_){t#Mj$nf3(s~iJiG+P;+g^FX zFhCrmoS+r&9S$_g8_V`?%Kz*UfiYTX*I@sX3|}=h;i*dEL&ZLT>>jDret_j@Mm(pPSHrji8+6)s5TAlZDKGh97$}aFOI6RY7%uI0(D_Cv8y_q) zAQ48>o%3|i86`pX9{+ceV?*q%c3S|!hfMzopLT{78K-F|F3h`m)@|cbB+nSl*_k(Fwg>iumH^s;;+_^NpmQ z!w*0E)fIhn^y;9qrddqWv9b;}CDHwEO#q+DyYRW6lDmdMb2OQgigLVAFKs5Zx4~6DLu3R! z)iN-ix9&GfZUz`wNKX+y@^&{PPiOq2izK2NPdU~`7er@eEwHt&Xqm669>(hT7`0On z=TnE87g9sk1TMkKK)jELG{Hw++G5%ikK{_})Metej^o-@^)C3-KbzX&_;A7AS9}56 zJ;QOAXTq@vgn`90@*Er)%i0vO%GLF^w1)t=o-?dt} zm~Q-3SMEEqYjb%q(@s@i8L7W#&vH52Up&A-+O+4Odkbo}V$VhjhC3-<&d+|TuWzu{ z-1WR%SfOfY?6cNTFpXW@GH7U;89DH2zFazrZ)o|Ze;5!}I`{LFtj6*YX)L21!__A8 z6jXlL0YH)IgoJex5kau+M366ms19ccNDj(L)9j=nkuIM2kQ>PK9uHzg?uUrMh~oOL z(AO2GHqU;z9$6RxB#}x)>xkf@p?q=jae|TR@!7SPV}OjdYk<-ZIhjl zE~;Lo()e_cKSbh~2AskLImIDJy(I)W0^LKxNoMAh#W9Enb*oH!x8ojYN-p;Z6pz`2 zo^~)FG)Brh8WE?^0ppW?bH71IKQkBRVy3htmEab~SJbF)l3Pa1lTG`ypV`%dt9qN6 zIVdzHQFI6V;u?PsPG9E{Z$m9Lh1}bGG6BRVV9N+@tE;lXr0{t&mMmZOig zC4cS?eiK3+kASh|QEgO0Vvtn3n4o<6>naaqB}8m0G>AMM_AU)F8A)Ge3p2m-d?|(b zE11vP3^q*===E@94)v#nV|S0JuiT*=?yxplDhgZJqY{d@aPrF#&~-Q9awV*F^8Ws~ zQdKCqVF@fI&C7#>j1=XSU?1qn1Dm%OtM-IaoP^S@-sSHwe0Fu@1cGB-5a1kls>wV& za5b>jp13iD>H>)mx`>C<>h7+@xJR@xQ{>D$LnQ0utQ|`>=x+QX{kMq6`lYy3jVbf z=n)dTH>Q=38loinAo(82Q>3KPfT>6q@$SBNG-%u~2oV`7O;L2Xj-q zt|>gzfKkk%G7ZF$JTw6JzLBkT1=oHGkMWle1OdTcwj#MZv(_wSbufvncQS8IylOsr zHM5#?m?2dn7Sar(eEvahxDq#+pG$6+rns7UdVLJY+E$9I?bi&vb|&e?L%czLnE* z$|VV)m&r({Gy+uEQa$iXfQkpv90PN2NSmSQHz7(l1!02%ELb_J=eA4(XI2!)ocoP% z)P?qRC3X)Wj3ze|nPA*Uno*9idF8Q-ztWVp&(^MrPCSYpGs*gbX1RDv5d%wcmxOv? zENUxilaL7c8_ah+3*aEC71JCBF39@#>lw}(sR6X_C2 zECD34*KTV?ZKJ)o*&XVVN>}!le2y!VMS*dHhSMI2EKw({VH*QbjWy!Q7(GIJ6uBdrzlV7X@~$M4SAFc?Umrw z%DE#jYvnsRZZN3?l&zRf8j@2evlB?4n_>d|`C9)KYh2H9}r~Xn_6fCVC#CFCY$hkw-a?gf{?y zbTR7PaB#sd8h^Q>FEy`2VoJ?-MXS~=Ro7!8=V1ymuo4TXkr5#0h+3y3WHKVkEQNc=fO9WZGZJ+;#mn@JinhF(ute3sRY1*E zdkI$XJ#i>WdM~7)qngext}P1vRg1OO7~lt>`q@rZlSgF33!^6`KQW?Irl(rgg1$(l zdDUFTI`&~=K{cUJY{$KZn4_75h?LPZE9{bigIpAFM)P?A?i~mu8&;JjCil27r5Gc7 zfq=_aQV86Gy@`R`N$eE*eM3wb{-@}*rg)c-N5>Ht>HIsI>t+w+s6&jd0yNeL;^^Qf z!k@iW4oZK0;~tWkKuOh1^8(S$pUg}Uf=!8aYA({ySgQQpuJX$7I+!3M9j2Mb5SzQI zde&M~tXfLnrd^CtF>R*6urN4eDbtJfh>Vdvey55qWY+RugQsTE8lR_&9W`z4*}%U?(ILok*Ey%PD9G?kz4pQd$^Azvu=c4jelT|E%H1016qvl%cB z6_xFWc2HDV!Pu7qUs6Pz*g{T+=_oRX$W|$5LnxOe$%#mW_fdg_DXX$6eepgJ z9c57q{aYyZuQaS;)MjzkW&t(Klpl!v<2ZN^AT&xEG)nPv6wLdaZcb+kyh`~uin1O7 zn-iN2({BJ*4Lw$`yT7N>^I=x5!;MjVn#c#%qNSo>&aH5lPECLE7aF=wn9)ouqh6f> z63tQ?%{sbI-J^RxuZRrPx$&|rp2TDN`xIQ6jg{Ah;dt*|Gv?)+>m6x{fMx&?J2FF> zPuaebI}V$rt|ChcA$6>z;C5GS8l(eSbbxESt?U9LZ%|2JS;HU-bD{nt{GrjkExaw+ zQR9FHMGsGssu{|B%Ce)GIRHE}ge)V3tl5^V8L-6d;M|!wrx?0K>OCs4Zzj`B(GD2P zG73hGL2f*UWg$fLjI)L7XiD`QLcpw(#bMXfNr4|0ECwA6gmfQK4-e6FQUdwD0fALs zz^Y0O#Vpir_iC0Hf`mTF7p3|kWBUXeS-ExIC0E&A-Az&Z({(JL%DiNU51 zl?feU`zc^o395}ac)~p_P4>NJB+2!vg6sBUA2Q_@{0TA9IyiLvSbv>3l(P2;Y%T=o z7((i7OO}@RrI|q1TuGMUPSymtn@0gzA$l{P6vqmh&wkXGT&@~<8M!Th9yTlxz+}le|l@w`+onIm_N6eOq z`U<3QM~Y~UE`M)TZQJeXZlm(ZJCVJhHi~OvhHA?#=LNkKg*OcML5TL#Irs4*a8blY zDs1N>j&wOkz3ke3b06?^Z_U7*}hBDvR1umpY@4fku3uQHgDk=GeoQf9VuOZsv0fJf&S}Q`?MC z>Qwrv5ekm5hRv^>13k`2JSbdZX^TF6E53=G65})=>(K0u47jN-AXXa`beZdRsg+qP zha!GtOBO7;BL_ofcrvJ81=IfFg^_oV7t0D%=q5jZ0Va}y z6I3$BLvQDw-#8r?Pn`N(PXS1@ok9Mq;)Gf4#6r3k$LsZ3s+~Zk8jC4qCgcF9C1=cZ7@ZNiBJMj3xa zUPvtHE1KrblMsGm6uW4WqPg@?lqm&I)Tkc@xaJZ27O2%xd$5$Cz#Pe#W?fJ1XB4p@?+4>O-OZj^zFkyhL%zHm)Ga;; z1a#7ccKqVGKyzooV)#AW`eUy&_{~k}6>D!fG0W&XuQutr=GDE|&q?Vmi(DQ$kgCQ~ zt2;A<>9)l=1lvu=+r3g7N5nEQ6QlSWZFqLY}!9ItKbpk=Ww{VPGc z3kgVRgrQYB4W?mQ)8CtUrzD)6b~o)r&M{AAM07Ib<{W#!=#7w|z%*)QP}6ORRjO@* zwSsl#p}eAc&z{SbQsPGFL2n>pe1krysGaMUq{E=$`#>O57dO?(kjksu9Ae5}V2~0{ z-heT|-QJKs@&R5p?*xT&uA(Ggqi0QpRvJ%z2RQ2)IKDj4`ZPlk@ZP=jsk0-9B3)I> z$$L%7H0a`-#;G`u&EJ70>1!DuB;d%fmg!z}*KE-)Z?*t`2(JK-{)5Dx~_HW58ddRB#qZD)q zT4^n9c1Ix0Sd(2ERAIfcV)tq-`Hi6V8v%LO#1=kvaEO6VuCf6H+@y*!@@2>xe-(?lH^M(CIpoDBBeCrqW3ohq}R+cjWu5_zh2| z8*)}~XEuSE7&f0q2pP`BGPCLg;AGPyC+b=5J+mdq{Q(r!?Mb=OskfJEK)I*^hpa`0 z;;NeZKJ57aAkKf?N}pT$id6Mo6-DQ}J2Em~6B$l;AU`97-nVeNp@?0-ETp3!-#qCM z8Iy)U*eoo26L+$fOr@-bSi2*lDkXO>$J9Is{!#|oz$lO7 zhtzgHBXgK?fv+GSa=2alA%27@t64>?FVVVtMn_aC;mWn3d+5QkQ(O~BSuAm^j!Z8o zb>PnQx6svr(!hg3SQ{Ziy4yAG-2PnZ%nU|huq!O`IR<3+Lo}<<2&ynKH~c1pv2B<> zZ=}S@<~5Ca+bDtTFmbTOw|*qy!rumIB0TW$g0A3AlCdTOH;h`yHb0MRd%KW9IZ7jK z#K*%K70A@-b;!gBHMQ~nXDRNa26fwHK(X48pD%vI8ugKsePZO zUQqX?NWtKKHc0>=?XN41V(%^zlN0gRi+yj38B(C2EcU4vi=qrM^m~AqXGF_j3Hv6z zC1{9bbv2IpX%|cpvL%C;sfFX#Pf8ai0*tb*>Tt!@xUgkHsE^E1_MvOzVcp;0bPtej zk(z4&B2G@OGe3{;#Pz{C^({!z*hA)b9oh`S9vffLI~Jeg=TisBqV?&G`(G zCJf(+JL;hI?#W%0)hAeNm^}l1{5b{yfQLJ+-n?~_>f$#ebt^+c0xaj6{LT2Q~!93G%Z;6Dgjxf|Jkm*uXp*+qNO)a1Hg0X-Q zUHR_r2ffHV7c{4ee^|OQcRx~7;_uRx3&+;wArf$pBMqm^maR(8zmrsr;ce1CA8DDRIk2fy6@2#hXU%Bh~LP{QBtfZBFcMd ziDJ2)yjs4Zz%p51c5v<`?J+?(3YqF9RoR7Z<4~Q}vmEJTWxUB!Dzr@W_Ob^Y$QrV+ z5y?)4lCYGs&aT;5zAOgrd6Fv;!HiTpWb`?4Dqd>^kDukjQ_Yi{Jtn)i(t8o`QM0n|4lLgq5K+BG2`7%sTd#6&$#7c; zC+5yBP*fPoQwk$!U0KWHJxauygz)wjz1V9GRRh67(D6~|txhe^ywcFKaGTn`1i(Nj zM!X&a!gWg^LP)Xg5#gugk-u3h6yp-r@ivR$b%|PGkVqd>NL))4g%F;}9uemL(RxLb zfMLWU`rRC;UTs%Laj|VC#Xbc@sgQy59ioU#Si<}U2<=+fk_!Krfl&Uz@Q}Wz-OM*f zZ@nTKeDA7Ou`>8Mqjj)fHw@9QlCPD%(igf#TCEq=zzwm%;L$oP#ix)SZb;$ln9{6- zX5kFB*8`E~6uN$D9p^*+>FAEzL!CiUU5nw}4rINokiH<5Fi5i4OFbMw_xfY1jE*d| z#K@Lqd*SVkkQ zVzW!KK6T{*r;$w#r~TIMBjHX1;=l3jpr~}I0WAM03p_G)F}%7u!rJL`Z55j2NzA)N zlA79EpEgkLEct)b`Ud%lZH5P(T%#1)s|Hvh=MH54K_p@P7_8Ih&@)nLaXb|kT<8!( z_JER>r?NeHG-yueJGhCfidZ#Mx@Df#tB|p&gv7t)hCHpE zw3e%-S_-!#7)8i|wp3{iA;}lD48^WvSeTi9HbWlK$d#mmZ>1bjGaT!nqlOt#6C%}U zZ)7HkvJ}%*32DVza+!#ou}1<$Doo`+@X&S3M{uui!4yP$!+FoX86 zn6NtotYL#fklS0Jg~u~ECmi}RtmJ<&cb8F3|NrCv2aK_e0owp+9NkE%fW_z%M<}6m zqaYwENVtswqjZ#Xhae!`At@=H64DKl0t)iy^ZtDQ-|w&gzl;BKc3~H`vvYP~ukE?V z?Qvfkm-jIglQXm&4R))LFCbGA6jKU_sk!j}Bo$mSfglG^peQ&|*w9e{?&8b;yRfu^ z6!a5{@57V$P$~cmEYboSr7{`E7vtt{9A9B9&sB*aViOuBQ${1h3Kde0CeybgBE*c- z`Mzfz!2#+xsR2ON!|%D*;Q%;Zf`~4gr+5-&qQF-vXhfdtj8t|gDs0fV8phHB9;46% zXP(D#o)i38ljYaxj@hVs4ZzB~<(0m}5n^P|@)?C~A<7EU4bBi5QS_&Z@1~MN{wUD0 zQh$H~!IF2Hgi>ZB+_)w|UK2wzvZRxFc=_D6E)M<7>ysvO1XUu1lHj-8Gq8jLP!VbR zAx#wx#Igwb$Eq-oB_~hIgjGp8jP6xQoEc!xl zVB@R2Hz+2I364+jCm`)*({)=&3{6}04C9mBZUF@7xlBMbhOv#pJPG$0P>ma!VGLyp zEXQ}_n1fvIfFDja96uzwCM$dp^Jg`h<JsO;p0vQwkyzrPZKmvcc zflbWMQXB-~c9^?Zp}>L!{n_A)lKj^1;Xe?)6AYcRpM4g^T^8vf^2ZH}ci++A&&Zsyk_50MfDQ1osH7QQXLk< z$+@h5m-;$FO_85MPi48x!s?#tyx}9LaL)4MM^K%w%clI$sYTo3VeH?tWlPQw*3U79 z60)x`-Ek*~6dpU1MD2?K7R+jZ-B3#+jj5{;?&La+wgMgkHYPURm&xApIKd^17#)F z-xsgN{w3OdSWhs6a5pXkC+uMQj)|P9l0<7xf1C>F>bkmps_I6-$x2q``ozYnA+7(* zF%eT*?qIu(`S0ubV;iQ%VYahQ6%Hyb6=SBDsG(@;iBX3P9pOAsWV;06veJU^T94bA zlzRf>YoJczTsij=t96O|Z34p*V1X=CMdEqiFq^`8{z`H7T}Do=zdokSMi%wh7pH|A z{asGGArdXlusW&R83_9Va<;nSZ28T9Sk-xCjKAjBdfN{Fevd!{=k|EY2iaohsaeYB zw_z78Dcb=VPPRhpt)5%Y#GQlNH|wgmio{(stTvVNwq`-0D_3~dbsDXUcdRibM*%Kd zTF`GPA0*2_G9`~&V;xsIjaOA{YrZJ&vI(aqv-p%%wf0dg+}&A31q?Vl`f&c@FDTF3eu zQdByiUizo)H9p&~Wd4QX#^Aw@_<{HO`jR?Y9W5+ljLT%pfF!*xXR`UtLGjw-6`vZ ztE4kLF!e)7U}9UfN1wyvegOxT^K-i9{J4P*gN^AkjDp_b~*3t?S$y(OB0{G zYdsT9e|(p2@it`-RLS*M0lV~6C-jh_?wQXyLHx6;(5tt@uR?4ZuM!<5N+|=qfiF<> zcU-z$PwPx}bJ?8rwto{6)duKtf6>lcwV$gjuN6D~*) z$+ti^yt>z+bHKf;X+@XzDczngs+8$Vo@b{6{p_`{(J$7Y-@kvJ${ANjvv~ofM6u*j z*&jClog(oczSE0lwPPp^o%=$4$mRdNqgW``^U!adH0K}Lcc_S_1^O+;+Q=0>yqK{n z=T~R4TzJatL)J?#*Ahg3jh1!cVcpl* ze=1HMQLezh{NFtdr6>lgUi{oS|I;tq3XF{MbmCRTX%as($#UF2JK0|yzE@2}Ef7$I zDV4e(y(2z8dJ~1CWK~ZRAKopW(m^*=^*B&z%5nuTUcL{W;2NHHLgFf&`et>9_FTby z37#1kUtWd|@ypkTGh3^Bm_EO^9mxGoZll^-ZD&hBPvEUZ4xD>rPhm(?i90Jyfrq;$ zH1al|&`7j_Vi(T`V|-Big`%X($n5=_PICP5wwfmy7#?mled5!EQ~o5k8>{amK<#`O z_9wNAp&ldIK~YIKsJw&63#`(t*R?x>`iX?gic=P&Jj-xKgvlGBoau+c^w=o7-$J?R z-^bFlw^ewAKjnR5jek%F01v-R`7AF|Sb@CxJ*aY{R-{OpY~qs^4|GDLq@7g@nJ183 zOC8rC|3|bO792d3KWO4zSO%vF9m<(_^JlxD=EKNi;#`8a%O}7XQM_)uR!c9x+u>Ne z;pnSza>MDy)2H>kVwGB@f1tN_gJ+OF5-s>gn}c6Y_|GKT4zIIGwliiji>T8)u9xiS z#R<7|aD~D+u~T*gHIgxLtM97INITwf0``o(|5Uv@1M4bE0j>5?6rA@ zO{gI4Gtx}k(5z_PHipm);xDp*@JGE&vK|r95_aov6fGCnjwu@jQuglK$%LHlpM0*K zTVPX6U%da$D7u9*n@vehnP>8)T)6Y5<3@FQMS3`&l6hY~9x=7pUgvxZ~22vTH6+Gq~QZf4D#0 zE)fuwZVL0)>a6F#QI_}3*}W`r_UzKj3H7-}mR%;=1muVF`d<1iz2EX#6?$$3Hft$M z`BiUkK3zjC$1coXyA&`9v!cPlTHjGO2S~k6SND-JNL>K5bA7eE>CocN)Q$mO;S-3s zBay)bvURv~B-h?_KMFO|l%+5f2Y1{>WQmX3D>e=e;du?Xl|3BQ>Gia5O(Q%VZR@wZ zh4J?J@vrma?Q{RSwf!ID%+gTZ^ibn}W~ROmHg5GdO${_m4b)E!)Lr74pPfll zy>**)fvZJs6N9b)E=^7JR{aln=D&?ib+k3KwYU5yo@x6B&-`a{s-@``HJ_k98>>7Ot?)hK z)+Ly^3{usk$9>Gs{4X<;o|=-9l$4l|@ZV&nd_Mk1W-2Ty=CUzm8x;*!mDS|d_lJNx}pn)34YyUa{^yn5s2@%p*jD;L*)HKv}qyl{NxX6NW) zZTHO5#>w2u!6+j0erSqHK*D8dO6GqmO+B%&H!-s{eEeT#M%?~wzN*YWnW=v@rmVH~ z?(3Oc2By@s|My_#zX?qJ8_fKNmbrFIK>QZJm^`nj9FK@BxA0AFp_^R)o4}O${}RmX zF;18)NcQ8{uO4zi!Ja70T zG~luVU-4-)->A%KhPBM_y1zk9$V>Ht*mj&=$0yUCe}Nh6QwC8`tcVys1Ny|%W@GnAUn%EOoIgy7Et$%wi-(js2(~C5|T%LPxul zthmd^OD6_IW*G%gvYd2#h^PozE1K^Ezl*$N80n1gT*(vAJ?Buij6;^F4n!9Tu1BX+ z8p|P^puQAqNk0)btcv&?n{0I!Vi<3{rJj?`hDa`ycS*q)shomtcjw(u(1FSb*!`oxL_73N zz4B-Jugh9j-6{fGzk$lFX_>*0PA+gBl z*H8yrPt{;Po%8gTNWWddK_B#&P#KyGWCBkoeu~vi&PE&_+;huRk`qCccz_PVYGUw!~^{ zi7}48HDWz$BqIK2%cWgHQtK5p!*P#RUOpxiXx!&^-}cjCiRR7W&u9BaUBzzbpQ3jn zHty1R8=&v-qe&PVDz&!gx8%mm`n)B9M;OGtkJKOdKs8PPev4YbNmBl z6a#N(`11V=%;dIA87wk22(o@Ox(rNx$JncgfNx+t{{b^^y157!?o|H-rs`M%J~0sg z{}Y%B%NDiQ=rQ@e|Dn1!Tl{qw1E0oyq4Oak1&5WC*>7IvDYlR)*U}<|6EE8UXd_d%8Cg)nv4ne1EI8bpnDzVX>PRP?=&rV?QqTQ-qXGp7lCK9b- zk8X3k=rs2WL@}ddWzSvZVt~?*pJsxB!7cajC+Vi!z$o!ohVY-vq!bv0106tF#FnkZ z)P75G1@(dWN_R1dI$hfX#T8T5K%M|1%5wNnV)kX6A_HA4{XR_P|!uH=HMEF znqHs|q=-|Ek}xTATW2zXhE_{DM}Mk6+#wJkyT(~4|)Zg)_V*GxUY=}(t0%w z542*p7?%*5V&4-!=`Jmc=p6xff!tSJfvca+Z-Kpvxkf{42Q}sZntNcyG^ovm( zH7OLsMD~Xt!ML~$@ zJgm56Cw{Bz{{2@1z2yhIH(Q03{V3D@QL!>hH9}nX6{tLpqEURL4j8>6rVzOV2HYjT z_vht})6e-j1(MX@d#_@9em`|6+HF^m5-|CB1BlRA{;5zbBy=Ia#H7O=?R`U4(AOo5 z?yn6me&=<8Q=BbxXLW+oZ5SdguAnL2R0qwx)fZ6hEP$*m)(-LdVW`Z2P}eC{RxN<9 z(GuRY3hi?VQIz~8!nk|I)FTmtabHKMS(de6=%lc38!H6V1YZux%{?-_(dxq4+)Y?* zLIf_rqwGhK{**I{N>P<>xb&K@x~$;uF#_tfsU%-#Th2l1JSv>4#I)@G-wM1TL^T+oQaoLm0{riAyfRC$lj zH!cHHV^w`epS{mFE$F;mlnZY&cq(k=O`n2m=E%#X-DzKR5)o#Wz|w2|l)9enuV!eO ztEm;?{wVcn!%nikLfK(8JPPAK;Tx zeeioImUD*4qbwZR92P6X!xA-6e;QcaBDiE4J1X9pDgBFGsa}!guGjgZZ3m#WXaM{K zfEB-GM@rt}G%qv)DJPVK^*m^Smojxi%$jkAf@vuKROJg1?tYRj?4DZ?own>WVU;Gx z7^V) zq$@+ha2T~%GU~qVs`9)Y0d4Al_s&7%gXreJ%z+8T9>Z0UtW{{Ut@99HiEx zxbZ{5jkIS|gmum;gR`i@&jb*NQFxjlyrAW+aizt?CTr>1r5GQ zHi8QR0uJynN}fAsx^SpHTp|}9dlUviQ$3A=&$x$C?NQUWnpLPjIILv*Ea3&2fHpEQ zuik|BNdyi^5i$n-9QffY3miH`hE_y4of{Fn_YNdU13w7)5vMg`!CK{Ji)$uJPz!^Q zdA}I&twq1HXBJBll>T_-Jw3|m!5H2D- zS`eOO#QEdnB{_i>s`H9oRMS@=-jSolGdtlEyF?i7JyQ2Q9gg|;gik&Amxq@G!fyyL=QXJ46$10;LmC+>V z<_Wjphqo*u;}2+#%i-~h5(g{r$Wv&v2E6<$L@G|Jogc24cLj<9$9uxVCWXX=;Gys+ z)rH`e5$ogq*a`wmqXp_mQ-rZ@48=Uughgys7EYK70ZN?h^s(RDPzcQFjg zdHrU&v3Tm;RE=7lL~qr+%-anpg45*Bk$Q(={vB83NE9SvL^d|0DNy=qu)~qwW%LYu zAwf%tMLyq!Ubf0wB|h*@rdAx%O8xe;lB9a55!J09^PxKRsV>wR4?O-EdnA~7kgGT`UZii)vo^n}l-^wo$o4O~*P27J3!f*VRb zzDvDGLJHMpkh@X+k|4)GGpi11wDh4pzZhn{?yiGVmL&;+I53?%v0*n=q&Xr@RebwG zAE2Q?=hBo@b%V}rm*$rR)Q*q#pqRE5qn+DCdw_xY7H6ft;t2-O9_-T2k#6e>Ydva7 zR%s@K3Z=3dq#wj{;=4m6o2bKGsk+fz?Uxrm1(rq}q7{u}nKuUs1yH&%afiU_F@R@p zGP3;XRId(0nIR<1ENd64c+)%WKpytWp(oTrdzSKe5%A zz)2F4fuqd5Ot--3=ZrO%6_V)fWwLQ$_^@VSp~^=JGVla|jsnN0woCVbHOSQjy5O3j zl}6V|0{ilm(veXlr_oGbHjuDz!8)2`SBh)i>K~cRF;O2 z{UZkhxRo%~Q+UJ+rjHofYglqY3D_c*oKZpkaIV~qMAuFNxBRAy3t@gA$n0uDqrFcx zoNLN$tu?-k7j-E^xGZS$yWu9{txD2Ry00_Z~$ z;7d|`UoJ=Vr|PxV!w%-k%jRh5P;kT0Jj29_=apG}Sh{{g^6-mdT9dL`C<5d_U57}g zvB%VX@DTIZ<+>h+B-CWev}Kc{^YLW$eK~1 zmDa2HbuqjlwV9S01<&1u#{C9trIl!X2akBeE1GC^v|hgwMv%?b3Th#orXUm~^>Pd> z=a}Iy)JxSM^`RR%l|172V>TZQ#~!yrBbvHh1X^T-fZk+RVEt$V5vf(o;$|)3xeZ5b zl@oXA>YAu>F|Xnkn3%8wzwIX~4&4P-+16 zwgO!TAjoSMu(Ny90}I=7rCUp*MrVGd9E3O*Af^W(WUlJoIGJ@oeo>r|Q;@17@rxf< z&Mkea6KrnoZMbuBH(N6euBp*COVHC1Zs!)20tX}AD2h5y$rW*|1En+f;@j+dLC*M*EsTnU})ut|U=UEA+CJ z(74`Kf93`A?(X$lN_(?;<&V$ZW*-n>8_^-EZd}QS29mJ1 zb8JLK>MU-?;9XIfBia{2@V6Hz7V&IE^c^_&E}a)w2IBx-1)64#L^=1APC60k#13*x zMs9}cR>Y5Ec=IX9`kthJnIl;x$-!OMM#)QN(#u3$PdX$T;Fr5W7`>6)zo7@N%|$43 zwhTIrZxej=aMyGAIDCQ2><4HNg1MvSM_Lg6yr99AZse>oXfbM%{w4c}UkJ}$47bz7 z&rzf|i0;i%A?Azk&ok8n+Ay^5NmQk-bTvezQ$aU8f(D4AHh4$<-F4Zpu}>(GT7Xk) zD^8{34uflKx_7bzZ2s1V)z9Dzbk<7EmMbxkXcEW{OTkN03rb=zU;FXUrcC;8urc=> zrEWdwFSJ`yel3I6rSUuY{P+rhjGLAEr$o(ri&ctw>g}{u5mR8E_5!ekrigaU=f~STkmw>jc&+(G-LBFm3l9iSkw#%XGkRue?3HP z&*#XA(~keFTQ&bv+7Ikh7f`ug0T23aIj!%qOWaHbF(BM84$YR=U>1Lk@w zQZft~9RBc$R?#=(ohEG4btDVZkT*N8j`5^&qgc2L7pGgZzXz{z0XZl@VzH1o6g++x zn$WcK0lO&-&{BD;Nh5~P`XQt$0ph;~7j257kOb5h!lwW<*Dl~w7G#uY3KzQL&Cie` z%yH4~j>Et~?%{%Iw6CoEmI&g+Tk5qf21tAh7ns?9cMU#S{7X2rmlsR%{4FGQ7aEfW zNf_9P9yrZu3;h+Qa^yH^ymySS{QbrXXoUjMm+XJO2QRsR^UuO7-h+xP4qn|mj=rz} zd7En<&#HvF&|BX{vG`!B931`~m=gOpn9)wS z{tuX0)k)~_{0n3?SR06=8#^JbTTN*?A_Ov~Zvc7jvpWb{cJuBJ<;%zt{|QV@1mdA7 zsDA~fq6?upnruRm+AKxt#qEhq>EVXlcEUahB|_+6;ait244!X%+A(I9Ey`Wm;D$>u zqkXtx*vuPy=Pf8X${1aiE+mEO96#JhqE>`?+444B^pe$7Qo6{VJhTj-D!)Fbk+GOx zz@s&5n>>A3g?|bD^$B)7>aaXoXnxPM81`z}wz5i8DvdwPS?l`7%KZ`_MB8mf^X}g# zjI2x3+d+J)18pL!DWY}Ug7JSq^5?5K)txh(6fbhD;(zP50BTmHSGwm_80f`|Au zS^niiK9*aQqbMG*J6XAeyQM>hVuz2dkhAQ_W~Y{FJueNTVs?ohJ}$q2ROU)KhN4Yi z$%mW!n^IHa?JUH=Xcm*0;wh7F?b`hY3hw#Z;%KBXxuLpMK+mVc%IP~XLgV*AF2yc* z3HdI{h9~k6CEa1yG$8K+_x*8s3)bJ`QX9W%j)qmheFzBoi-G&`D(I*BU24uMaTT{{ zyJfBc{}gx*S>8&~oit=9e-IRS6%kjBe~=I$Rq2>?q0U*n3V3_t8|?aVjDb@LD}+DJFb8t$89w)y zymLj7vNt;awC%eL;}FJu&1D><^{oDQY~8VO7%A6L6&37#U1m-{GV<}o&Y|7cswL)J z(X0Iq1_D&qe6IU&)MeRrzfC|hn0j(0AJ)5`O@G7bQ-vCH;0D5X>6O$oBMT%n{Eu!5 za5=o3VX{eB|AA9X?-_sjg709dyfHa4DlpbD!Lh9{6L=wI*7LP9{Y(Gro$SDdw51nW z^TG>e>%YAdJZ-6Gm`4Q$-0seIbh(SfE0~>b3^a91#;!l_iZ;W68{nIaEfjMv?^XyT zbuPci^`fk+B;4CuFOs)&4dbhhQMic4w%!}f4TL?yz-ayYy!n(N@5x{DL6J5-5B5VM zCERW@a4Iu__a4xUzmmZ3VuA#51BoWgJk%y1ecpA?(6LE{bay@o9@TAX8o)=%$s(R- z{~l)d7!Kh!QKMYxAuRaCk(;&kN`ttGD;0M!iv2s9V}^irG2z>1TxAZmlz9 zb`9^EoMrWoYZrTkxP=l{|1E1oGceKV`?kD~CuSmz)m8Hy&^UmLPN-Z<5E<#@mdbXo zrbD-p9F&YCxEQ2sY{ilBCKM9{v{6`Pp1EjT_IGA-jBDZ$H~ z7m_jlO+Z#0W%ULhTCZ7i2YB%!uE;Y*3Zf_A{0gcn&(6rMo0sV5uK6?^VSUq)tI5S~ zPmJ#wW{RKjn_={D60k&BeyXPb9wpL`#+^f^OXJ%g3kmv!H08k)M|h;KeLA&fPB_4* z%YsJnW)y18m-eQ%rp$Ue&7LyK#GQceT~^+TObf=;vIaY8@Q9o{IEb3S!xo$}Ee%p3 zoDl)3GBP>RkxLIsr1kM5BRStSGcYl=sK+L5d0kv>D$<&$T4TJ(gLdK9vKZ3yMgqm- zZ^A|yCU85vaB#|>6qd(G3i$yX$^+$SWZxzO%5kwjXB9zrLqFxi3gg@<3+#1rk=*ck z+e@`xwg0BceI_LH0(#$ck~hDq=}~2L;J`OCbO1$`$yiy8BuaYZqy~$Gl~L}cSDhR) zv-*uySfgh|tp3P~D-4u_GzzQM#^S#0i+N;arI$kk2c9C;ddOkZZCZGKN|wQJIq|A|hRzyjqF|BdMh* z4a3UbYX~p8c#_!7PBbW8zB)8~rQ}@J_H@{a6FL8Qi$7uFYqYo9H+TDo?`J1Egme`g z-kwFVe+dIs_FT02WIv+fzd6~Z%~|?RDyi%W+qVxzSjo;uQ(c0uJf z4m7HQvuDM2H>$k8ndL;#Z9-S$q9+~pzO`Mf)vu=AP;O}YR64TtOr|yfSnB<vW zpJeLQ$DvOayyEYmti@oNTa!PMr9@JD4bzC3+h5$!awOLfh|hY}m191*{x1ErE{qK% zhPlI|%iRO^A1Oy0ZO<24DE9mG^cFyPb#H>b`92N2{5~`{r^M#n^y#j;CHlHu5m%y& zqdvMQCaKcW;p^n_-p9hzN~pi=b$bWdTs~BNl?ickYFhFb-3S#9`5Zn?8T`7hpmzH; z9h0j6_RVh>`{$((j;A{6Rt&6$FV7we!h!04E52(!+udX??oYqmNXPuHYE*v3?W^m} z_NdG?zsI%nPxWyU2cp-jS{4}HIMM{oxSm7^*f&(Xs_Z%*`(Zd97IEF2l#ToRqMq_V z@?zVtm^#BFO{60`tbLR<7kQs@+EP_)Cd%)cI&8y*6=YPu!ruC4wl^(HtKgQs#MLt? z+(Yuk^Kff<&m{gxcCWskqy4bQg?w+OOO(&>tjSgHl$$pM0uHth-tyoc`p%R)vbX-K zRBLd@7+$pBjQQop-qXA|z!9G`c>8!1ryDmD?eLhG4VG+SUxA?=yO`8w2w8Zdyr$^~`?lhYQ2F=nvCwUgoK{CCD=59V@Q70?X;EXo3n7ktmui}>*; z>2o)BL?Z*D{DF}RU-=sp=6^c~{T~3|iLT^(PD^AaWexTY|xZ3;oGVLu?Ed~>Oy5kw=fHn${2hm@R zMcd;6iU*h&XE5IQMIaudHe*>=PDZs@rTC5V5q!_{5^+QtG!J{kTS%SSFF>WMz z)Jie&uq&xqV^LV+iE+JQ@uyV6m+0Rd4uV8G=59*7^jS1~dpzaxo?`C}6=*5#q>b&mqk`q44wEH;XB4(z>7{oD@JW zPqNkU1T+K-4^{#i-v(!$%5_@>4~O2ud){gwRpeOXpE-21JNL7Z^sJrQSZY4QIV1^SD)DTvPGMko zzFzFEygy*HN*;XY$#C>8-JLg-7exK-Xr8=@q(igrVxocV4n8S+uK#_whtSFAKlpP)cy4Jac}#kMXl6K@Uxc? z_tE!;sMZI!!De|;=HbEEyfEAI8)}_k;yK3!EC%a+p5;R`>{}S7I7;+OhOpfMW1S&5 z-+*($i9ie5HFfd;XK;iHAvVCcVdA~KtD*m*f&ZNHn56XmPRRr0Oj+`ydk8xhyR1=;MEp_VJf6Ay&dH=C4L2HG|?$^3Ii z!{AKMeQUDCz!z(y@fH(do>X|ukgTMEbi>GR-ca;*RVp7b={^S_j?DXdPN)H`w8@CB zg!--fhA|SY9|*T&^8?M=M*=Of%q-KCoB0ME?CylL4OlS$9Qh zrW+zA0*R){F=IvNSr&kP0&sBqI-nPEsk=gD;{zhMRkSoEeDbUK5;C0S+ z&-dYBwsiJ4Z2$>CCu{zvA$!cfFL~SiLM*#pOa~xH_Lt8>-g>svriqGWj`D*AgVVtE zY8*Ia4wiEjW=p};WI+S61o`%#++=M!P7pBA@MorsDF|FsF||6G2_w?G zSiP$qoiV4R67{9z`8vNl4Y;6OX+7T^!YcsRz&DEiPzJpmwDt^O7@P=n_=0DqB;Plz z`V>`t9W3R?4e0x^xHT{4_01hZU^iJ3rq0995v+WGuS{(2qKNAJL=AD`b?|q?If@4W z3e&c4cu#^A448RzxlwgV7sNON3kSWL6ZFI@i7%Su7=kO8pM1z?O|v!qo5GFhUh^?E z2Nh`h>wo}OR*zO}?d;-J9vHdU^>f>_!B!mn#ON68o{p_NZdq~uWoQ12g79Z0Nqxah z^@<8g?!_bf9bKTqXL}hN!Tilw_FFw6} zvgQwn=MnH1?^?XXmy6D@wVb_iyx=7&pAEwRvEFMYoOU)ipu9S8MM2MhKxvUtWg7!L z+*nH_nWq+H#j3`s+;+5nNT|RHm3FR|Osp5LIi|i#`#>w|3UI(zuNii(;T>`lY0>GQ zgPmS&jKXh6`vq88j0e!J<@N>pj5+lWP~Le{XPG&0$gSp-xfY$Y#73z$zu;iiZr{Mv z#8>tmcEPjdTVyqk-hIzP6gK<5zDwkE7lnnp?GM-*1%)TBIE=sR9s8Ty z`eA#GuywU``(g^jeYUKWJCYvr(kmB&?6y#r^P13R z4Zq8eo#u6MF0!eo3y-#hMt0WtpZgDIP76PGyVH3c{FAkG$(7e=%z$G!^qb=RLUF3IBE zz^2{K{2iK$^p!wYBLJ0PmUYtQIs`+vaQH*{TzYQ58oxd(f&yGxe~<3sM!i|)#maMv z=kiytrf>zAM9*cOnC(qJM(~d&=c$0@cl{kbgXnApw_OD}@9ifHyVdJXdKmjOr&SrNlvz4eu%VapvH z?LCs)Yx>RX9=yDf_1(A1sMQp~lt5Oy!`SK<{#yHSntK{lwW8Pf$j1+#zc_qg$baj( zJQMTJ$HMNqhDXW8`=E|J>czvy!ZZ)eU&9G02{}IqDbZh*-5X`z z(V#nG%RhAQTGXzwuC#E}Ey{x2w2uvqG>luV?>y45Kk(*Hd-~k8e{R@Zt=vT|?rGIX zKk1!E81cwKCO z_xSOsXU+xw`3doDfS%;>yfDt@>nAFvBTw^}CaE4yuM3UnK2&m_8ZtlaH+mg>4Q%!{ z7g>GOkC;BuKgDA`o1EYgMRBgjFkI?s@Y{fdal4y8PwT<2`i0+ApaZiWyvgEtGlseH z;RoLfQhOji(1_W^(jlUajKjp~%pSz5UMsS5J0 ziVYTS7z!lW$9EpHAS_r12#vHs8efnSTQ1os8ATFM zsmb?Znu+=q9dz~wMDp)!OKgHp3MBOoG4t-3GB5b2EYaaDJsH+-&5(EeOMsaXs6cHe zN0OZH$499qPxY3Gr|e^R3r{39Fk2b^BNZaU6cY0Z$2vzQD@ZU91&_Z!^~Jjo9O0FQ z-0vPFx&pw@B+U@fdt&U(mtaPUH*RS(nNZs(Nr)yHv>HkwKM0k%BAX3Z)FS@{W;CNB zBjuv_#h6+jOWC$On+Rhmv+ao%(pr&@&reefs1$ZObjXj^WUMvW7_k}tsK>Y;?{p+Q zmM;#@===xF7)21pp8hK6vMw6wu5+@Qm$0TD6;l>`$nw2jNUlC)WB>X60BPF`Jxx!= zYYS~5OwumX1DT7RktMaeMpjZQU)7xW3SI(5WX*U(xwK9S4Od2JR(T(u9LGyNlB8P1 zIRCk^GhO@oKu4qU=5Dr7uZfLp*bCQD!UxG`W8H8#C4k()MAk?jyY#*4#e-*Aw>nZVyp-7^-vTCUd~+ ztLl_}%}+FbZyV0MBonXZ3hMG5=XxD;4&ruwRZrdpU2ayhcnZ;wiVQfV#452~Um$S= z%WcTU!`QZ&r-}Dg#;%~1@#DSN7pV9FUY`gCYd=LzIlh>OjYBap#!kUQ7oiZ93cfhY zm51a^Rta7?uRI|qdt9@Sfs>d@_DG5b~!2)SGaf4PEP)N{0Q!tu^ zH{*?*=in1+HZki$AKEqoIu(Nn3F-IfcK-b zHCC?X&`q%#3-@`&kIz|gZMMrHlszKl0}()u@_O>;H3N#9;$QUm6Q9Mws$HLbv8wpk zqX>RcW#ig-Y|R*d-|P6smN$0@9pH~h?S+M-( z@)b$$NrClbcqUbMvFB#)i{hn}nm>(cokf@@1VlTNr1Z|0o3&Z3Q7RK*bKP3^?i_g? zxlC1$KK*j%*zg+~BW?EJN=)`l;@i8O9!VQLB=E4Y>CKZ=0y`fL$mm`?-%=X0vXDr6sh#; zl`LWFkJK>8m};>cudA0}W{PkvGE3N>A1ig zJI7E9Lc8I-KJ3b1ZpR(*Tv`SVBF$zlv($bGDNuO?{*Am@Nvbr$9&d5jU7DdRUmE#g zdT@%tzg)|`G>UfvNyeu^8ucoT&biGetZ&@JSb`BPyntj2TMKE;Ob?1CCh>{C2u{3> zr~FWR#wSsz1~>N$h;6>jFXjItb)T;+zONiAk}CAgaYs-wKI;<9OtP0K>m|;P*u};< z#)z99B(6lSd@{4t&h|J++DYP&>sl2`OlJm7I!V^{lYU0>2FI6ObDJ{_c=}Fx?$Ul6YfvlPNg+$P)fJ|#rYQS? zwc^v2doU3-wQ(-}bW)^dQEncRPd)?^_-*p7M0U z=#j#abEIJ7X2sKl7XEtP63GDDUQ5O(qjqt(&#_?{f0;|i19C@2!5rDv(zo&zkh~=O z?aM*Uc>QmYkMzAv)lDlBSkdYk6`W#X&nRAwoz+C3M!;&`DXdd7zr_*rs398`#jr{M zMQ;5aardbF>1C;^nm%9g%hS}Eb-k+Eu?F#1W%)DP?p1ZO=i;8NBC~suRrLu-B|CB) z%aKlCLxkH;Zyx=?g!rn)Uk%s%4)TAT?^k_Uodz?rP*`-qWThxwdT|IJkqfEnW?DZ9 z0*~lCM8CS_N~1&|Pj8cXprx%x+Rud>6*7KEQ=wkaUT8{Mt4+%}6uXi^qCak7~(6wKqi0G~s54O^tSNXMA2@ zY9Wx8b2a{D`k-E#H2q?GZg^ifOQ$LIw;HBf{2-4s3ihfH=8+T2aQR2tVtohDJ_1JS zm1?NCa-o98h4`IKvZVG;gUg)KU-3XL)hkAYo2Cb~7yFBC{da+>TY-;VZj`G; z#VK37;cexTDK9H@Zlt>RhtbbRMRtQkZeH)t+ct2huAN3*TW`hcIeWveu7RY_$36H| z4iTiwO{aI#%)J(P^X+mW{IMYoo3m<{%n8gD{CX-d^*r#2$1{9zqQV{i;EW)qSqq#1 zVF(pirg-Ik0IpLY z83=Gmx>7Dl*B&_odC z7EXTsJU-evKG?i;t;f5|`+FP5|H>f!M+xcwsJe#!kE*NZKULS^RP+CZ>KgmE>ROl{ z{-=l3G5h~8cb`#B^^3mm0|ZC{ftk>&^j<<0l#+x{rFWIyK|q>-ib@F(s-gGZkuFV| zprG^)B1P#%MFFv++&uePd!M!T-shY<#=T>lGe%zLRYsCI=lA#jEYJKs?3(^B!>+|w zGh2(#-Yh(OGf#RAtSnBvUKoEpKfXFYv@zHBUxrBJqDqNTf+uPSB0N7$nl3>-N1{p<$#+SHP`Mzkf(b|6|qV>fz()>SgET zZbdB9kN?+6S6~vKUn0-Vg#TcWEU!8KZ6IN6{p)lT3uI*SrT^M<*%)2@8$i zmGiQ(et*3?VuRT0)!JM>lJ+l?t^-q+i999YWpjvB)l?BW>VFtWNlSsQr4`0ydIcl{ z$s%(Ld{XLmbg1R&AZ3pWm&Gbu+@AjfsW&>Orooiib2Znh45~ILA zAs2K-eL8G4Ds@`e#B?e9qXpJ)k0fY9XKX_#21S8 z&6Yb+OU9dqk+c2WEl;=n86QqzutW@`{JlScQKf6$6_@6=5YsES$uSP5PWn<GtK{Wla zVKw-@4{ltmyb2TSb=TwqxTZEe0G)Z@iWf`zWqP~utQsh9)cJYXclLEhL~o-{VXg}6 z&u&sb@h5#(^Yp$hfTFiu`83G*S+Ekl&z(2Z&VG4tN8H3TNXFRN!1)OCNp#z$l;`=j zurZPb?>8j>s?O5L`5375O?GrbBnN%*#%E^I+F06w-gwLA)C_|}|@4MTVkr_6Q4U)Dh; zrH8StM|z}xXS;973zQ5|a{T47T^Zj#{`$1m@J--okmcstaU(HO>16!kr?c%`i_bLD z0x!(9eXsHS59vqf z|EPhK&iBnjRwWXAgRe1|~E$(#?OoC$ZLl`(V)lT2rix*w?>v2Vh6K_gPFeP6qD32Y~yvdZgDcoG?2X!=!7$FwlGA11xHmCGa7k;lK z#w@|p8SBzz5^0=KNOza=k<}r1Sn>3Zvg4J120~Ddj zJ1t5a?n~AGM4NUomDwQr98~7Jhd4k_UIP~0B=B2^0+(8uWJiuW0D{s$XIvN&XLm%@&aW5yqnICD1_wE2a*>v{xoc>v#;)B%(h!c(u>zhx=9rrQWulq-pAgD_QI-v|s4Eh$;7^Jv+ z_Wc{gUFPzFk{!Gd`npkMrjpR5FEKHKV#t?;?ws|0#K}@+t^zV`9z9Ef5?;>LG3R9$ zOn*@NjfN97CBwN?dC;13{AG5RP6}_ZvTLs)`*M_o5zljSR5s{rJ9Ra}A!uK306IKi1jM@W?i+_6Q9OL438#oN-&AO{Z0Z0^cbj9K5f?KkZ0H|;6N7Gy80nf_eJPKJ3$621(8MoIT40A6 ztW8vNhj}R(@=)qrg3cd5RLTZ(3cL`EhRS{sR2~3O4|HS=c?o%CI3$M^K|n+&9@q4h zM?mimnOk#mrMl`nu_|32!;R0;oqS08qLB;zg~aA66wT=oZjPo22vrBa^Dok!Yyb20yxKUsPK|5P#afrQ zHYjsZLw*L{8=zi^;$ytGq#^k;f;wV4{A=7aUU``;%Y+dW-*W5VD>ZTsOkr%rv1lbnX8C?lo-g96J5?g@nID2 z4<17*%zbb~1RcV?u}SBAkzd~fXgPw@@I*c$E!Rtg(IDD))AT8Pzygu)BM^1J+@!&r zD{?wKnHnEP7DVY7mL5QR2!a*G@OcKvk}9T>5G3iwN;HvNln6Nwrxutt7ybfTC+z}^ z9}J%xvuzPQwj5$y<>7DoA)Cc)JDV(AN7S`VfU;7s@wTkP=DIr{&-4^ zo;1ZZm`t=t$(?h*gia6ZL4Q+&Bl;c_c!o?2*d(Sx%Zp?#k?^|)SsEK+pL+DEumws8WH7m7{4$!Rxa1!Y@*6(dQ z&}CpKPS@c-Iv!Bo*7T@ki75u^))RGS$xfAk^ePrjV=z-Q*t5lRQ3R+rf%~5Oi=8qt zaH2&%uEUQ~g&O%U(J4pnDgl4Zd(d>bAlj#n)T%Oc-7Kl*U>LcnPS`QEw>6+l5Wn?} zmUIUC9B;yjH8K%(?dLiiZ^Ep^T(G zR~0H=kw2>o3F8-KuzB`S(hLwP&N}L+dl{ZgvWL2$VK@A9*R!L+-?ZZJxz&6&%h)|W-@~eInNPHZ;!6Z z9f-Mz_`>29$Op4?V^pj5d&-c%zL6en?A9F(7`4Q*@)lAdt}dpDJl`U|F&3;NCk?~I zUi4GDX^BOX(Z8L}y*kf*kB#w7T#?Sc*Rx>Z3lkz%WoRnc*Wj31%Y)eq5v@<>eMV2lZlF;$R_@U4N;cB zpM*o5K_H2Fh!axmr*RaHEcU^V%Sl#6ZDh1gWzcWuCSq!LSU-6p(mOL7fl9DUb4nbCLH&J33xfsgGD0z6Ii#Gz`L2n6TC?>mr5fH{^Sm>ei%ej^>s%ie?H zhP10_{R9%`X#!hHDQ8N_k4wF*AU~#IuJQ6zDfDZ??i7yqN(Yh7##QypKz%OUv%gBk z1r|L+mmG(-{0R$C;^@)?ToE-?8;_cvn}YQO8?$SIjOqK5$fGm|2aMrTCAGOa;^Pnbk6!ik$FGfIRE>kv9e)OXSiW{f( zfU$*2$0z{hhLAR{3f4oc5aHUO2BC8oS|(vcNH#JmCuhwpH_W6t_5@bR^MKNyt%Hv< zx}UlT?aahmOf?|bZKg+V^1#*{9@YfCBS&#iOm_!O?a)oBqX`^0Q@6EMswwCcf@qV% zsrUS^u_Gv66A{bB@Vj2vs{=*4CAn{+QkU6Uzn&m!PXv-c?CYppda^dCqqVKMemf!I z+|Qi!f6SCY?B&t*LqCB&JW>?Z!EVx_JMEA1)u7v*ME9H_7xL85}Te_-sI z6^n{HF1fLifT8(NznGtJY4rO@RZi zpnHTJdxcIJ{Vp-8U03t_PJ8tZb9`~LgJWVN8l~?{NBl+Ke1(y!8yOnk!-1z&V`tj@ zrTQR`1)IR!1ES9-4wzSQ-!-l!ccgm(YIo=c={l0llh#WBMYTeh&M9gARHrwPv_(Px z-V(G65|W8$^elcV=HGL{{E?b}!$-O7&=T{~GKhf*&H7b{A1_ZK2Bz7fc0`mf>M|E~ z)Olfi2T3uAy<`N+VgG2A-AOt~% zye0Ns5dC*F{qXrZm4^-E6X3aM3Y9W$4xZ4WFxQ{_$+DRlnP(2o49oySUDp93GVx;@zm{jK$yXx=gSBLQ&T1Z zTo(iGk*#|x#E@D7hJ-}k(1bxYbbFtCn74@(@<_n3>8mB9s}X{3ng_v?xs zm3Gi2O;c|+j7H?S~G?V2k8qd)6T6I8Db;O&8iHKF#73u7H=Q+6PO>ySJB z(48Z?Mis{9aX{lYtSu3^)jdIB0@W*k#@8pcZ?21~GG41d8yumd4=6OP^!{E+kOU0juQlffew{xbo1a8QkF5)%a}sly#L$hbs5GDtO3y83p_!MAR{(-FlEwPWHg zWUtYipg-F*C2&CpBL*HTAe@7=D&|Mu%aH3$1O3-R_;abbpto8Ge6#i#38u z;y&~kzV*}D`pqw-9^Iy83e|~R&qCsELoSU`7t(op#ZPLrv6$-5d0LFpK#atM`oZ$P zh&H7}sW15PC~+{} zGeF;_J`fE8qpkyuzJT1_UbUGIi3K|!8Lr;wMasWXk2>f+eN3h|1Ij*n^;Qj_PJq_l zXYg8oli>jMYFgjp=XctKUlwPmwnJC{crQFdE#Qqtu2VnKo4>^U_;vUvt!8q9FEri< z+WAJ!UX7ub4t-nrwe%^uPdHRe2^b8A-VdjUNM=+9wx6A=LQieg{Ju?!Zw$iH-&!PT zINm#BaBYR5WM4=Ko;w zKW7q0L8H~azNYBVYW_&RomkPJYFos-9QVk*`BM&RTk|Hy*$$ob@;f8q0|Ud4R3jk$ z0kh28r400!2@2S+-^k%LH0&Ik_LRAx@7N1CoDBS;wy_2W$9mnwK7Ps^NWYhbg33;+ zXby{D2KJd4e~FbBq2Z`Auvp+i$bxPtt#2we%|cn{<sHrsdu8w2N3 z!?T)f;^LVk^#m%el=NBUN!{<+2XE`73K|rWCS8K1cnOQY45Ugdy_`>~O2yHXK_TM} zeLjyPtWl|EQXly(^8?dLg95#h1(mPV46g)eo~=KTXm>BXnB%)`B+p046hYGtrX%mvJ>Yve&<7 zw2T%|27cwdCa=*3-Ajxi>@L_|NjG^a1Md)W27)a;Pyyx*w_OOtkG7Yi2+XuABT zXBmY#N|1fi~J z(29GznTI(AFFRVA9jHJ0Gu@SVdr>hg10H7W5pls=gOawkJz za=f|c#Xhak2+zB%+BUf%Of{E36(ysQ#<_)9DM5p2?y*{vWw{)yu5d<>$rbyNL(?7h z`kRT}w6pT&CK}t}7{m8w$Ek|iuD6DdA)XoSWhawZ zb@7#rj7fd_2!+?vk(wS$zrbDZM?_L`w0Ixp?_^$nBZ2>#!37g&;E_5wt-Q{c8LqtpI6pvEcg^I>g0GnXBJnZ6`Vp56>C(_ zC0mwsDWKE&p?&ERdQ;#r%SgGJuYV80L`&R;OTxuOHq*UQ*)mJAj`yZ~)G;Ds!c?>}q8D>@~fA9>B&d+Ps>7c-`@?$klSx zD4TFwk+_`Y{mVOgb`iBFx%J|%7=On2ugXdd$Z@gWnRiNh^sGY9rz2qS=6m3rIYm5? zscKc^omi|VTQrCs@genwJ~;5mjbTk_fJQG=UJ@U~uNy(Ayjm4SxSl_#zP&;wNRGxs znlzQg3BOtA4yx-wZ%_6N1oA{?9vLOy=f%yWC&e{-#9%?7a>We*ty>Z! zBF`HiU680|1TJ$gB@jLIX9$@~IWc`HM1`224y)x6a{_l}Qf7 zr9Sy8qH3WclRQ=I%vDfTf;;284!yd>!%&vvE@2cAtM8H=B!oHB-(oE~D;Hq+TwK&E z6oU)U!UA#Sw{4w}^nk0xuS`9>5`UV)@|eJM6Nu*cN@jtlRVJg(nAH+em#mtMT+#2! zS^s8M!2yUmT1VfR?;Hw}_K2bo+rDD2CMQ!-<3e9EGR{mEPT}K0rray4X!>u0ph`M=&w(ICh*x( z>|Bwrh=4n7lQTGrlsYxB2zm(Mi%iJF$!w-U@xks455d%0d!@$LJScb-*R&MrtWELx zj1@4Snn2cOz+iY@62=s1z)}kLfkZr*L3tWWrkgTId{(=&PT8_Nlc352wr7l+6JPc) zFB_NR(6jYY#OA7b;wDUlxPiC7fpuuJ+@CfvxDJdq*vMDM@GFuj~ zJJ#z54H--d^?9T$Eq@gvQ+kh8djxN*z4;XSL((q-w*EbFp)oWQFCiZslZInZxz2# zj5&{F3OaKZvKk(SLS^*)`>EI!Uyr)qk;RtMt}?bpP+aK?$ev<|Mai(gTH) zGdghHu=`c97^LS33YHXPjjmiOR1S7eRb|Jx86S0sJHe&BhWl9@!Y$o$30Zf#=hD(~HUn)a`ewz1P^ zOmJs{QVjL2Xika;cXWo8T3nT2mi&gCyd%(9tMxiFPTmySm;qO*6z#$fcyqQ|fr4;2 zI zN)GM+#KjA%(z$q{h^Sra60QH>E;gS#W$a0}EVq7Ij_UlF071|2eQD`$m_vVLD6C2#^le64LSoytcwu3bKT$DCBVv#D zE4jVYVhC6&6&3E!&28w&$jhBD*|^K$Xc`=$*Q_gL|1v0y(5FEdEKxg0M^F!p#Rpf% zY?nP#E`N^d?!Gjrk!_8Sk%*RxU)%d5O9)9t#@+c37hDS2S+8mu&D7g_sxw zPq=m@Xbp+{C2pA$Se`s_x&d~=LDcubDrks7xb|%v!O#Pu zvi>sIMlqT+w=l!M`25o4xpt8GaJ0*COwe#Fepu7w1)+TSJic`}VQ@H&bue*zIQew= zp?69gcqFBc_KLtr+6P`Wj|&eOb<=|qv>oWOa2;?DUDR#-Qp!kvK8zO;Yidr=?&K`^ z(3ac!PyjU=Gpv~qiZ5jtt<;BJ^oBUIHuWSBw5R2(21j$&RjPvs+QXxEE5mRTFu5-H zT_7gzXtdFMtWfC+VISXWGu9~&^;y+xHRpaZIF?Qv#UI5upN;f@_2a^oRjXsZJW{_W zLRm4dn?^fcoen9aeHjxz_M&_|?`SmROsBL?e=ICIG!{QV8)@~3v{zos!x}j+u5KH|9F3koI@Njc!5}qzd_&%FL}hXtXSm~H zh}XGt#mn%u#Nw~I5UywXA5V)9=NYHKM$_9Aq>d zmqbE&klrzV3hyxbvwVDQaH=0X`TKP096YU3K1DJiX4$66HK$*qq7}TTDdeG!dd5Ne zs$d&PnSP`#9`ZZUI3|4x@25qFA!sZaZ^{@5kX@#BC9HT%AuNVB%pj`O5-#Df$9Ex! zd(q1-CN7Lm3lj(|C53;+XKF=f;Kx_Kl|djDW8cQd_)}b^1zlL% z>>O@ZLRA;OGh4`JY9|Wkn7AS+X~gu~^t{BInbW|Gm`)?@W0tsT+Cyt*^kG_wYa|UL z)e%0~sWPptpD$dlrqZiJr%%A4#vf;!VO2YX!zi_xXeO+gwc0Kg$eBMz6V*!1gU5<@ zo$vsThQoEvpiSoq$kcR4!MM}h9A0+Gb-^l{phjG{T42#(ZEo$OqdT;aI6iNi(P8N@ zPzzYtCtcKGqA?S+40fJ%(bRPDvvj}LJ?OGX$dB>dPPo1{u0Ay8kTdV;Gi;~u5SmxT zX&j|%9K~rZezO8%HAL^=_bMdXDnu|YB@j|rXBxx0cm%v+?S4p;q#L4c}!sJ`qe^Jd=cexG1GF1;I(2`2#$z9Re_Q8 zBV)%`M21-8>a(oQo-R(PcQl-A`Wo4OxS|6gqvCRU&Sa?E9BN8kPvf% z!;JX`3UB5Y?dnJ6x!#a4wA6DeyV+t;jx2Wkb4*Mdq19EoR5orU)L_{!QYV}_D$=IU z_VwzWDrK`6m;O~3zvzh_n@QW~Day5JO542s;!2UVvVPp{xkZ{0O^W#X%L;L|7LaEZ z5G8{|ItZ8;WfPTZbDp@v6}*+yvc|L#ohm_swH{HTz)&A^LNAWcCqcBRwy`j!GFQT@ zFOkurb2Hlbg6=Ngy~3I8u<|_J62v=Yawl@yC1`57J}_||;Mu9{ge%|QDU93c=h>*$*`8wDNeFi+9@*)KWSXYJru|&W z;cn)EamPQn+T(nZJ&ru7<;)4UgU7;yAn#J*=MFtEa>!6MXtLqK{u7Uw z;-_iT?pN-6Qev6Id>gDBq*QhC4LqnBanLM7XlbA4AI~y>&_PM?e%Y=9A=r!RgG(WV zxjNZPoPRIP;owmp>hkek!gONb?z?888-oz$B*nNUsTAsMIR-0X60ok4hU<^InntkWjt#qEEJ03o0k$Hex5& zL&Z04*w&#{fbaC4Y?p15iW_D=6#DEP3pt$gZE--{h&j5ksO9q<71y45C^Sd=U@`IB zrO)SSfal7`L)6{FnCTDelfwKmhZFas2NZpU0-?K>kZs?OMq7sm_Y02iQHBEVN<#tv zKS}fLzJ(j$0y~2Dlc;&y_(!~RWd?+obT^lwT(pw$NYCYt=6Bz?^MW1T7=53vm`Vrq#4;d-@*#Uw zQX+p)PVt(swh3y$w@{>4Ybr1vwMrHPXK{^}h=EQ%KFwksE0_!7oeJ7pnyC^wu7G^G za!$~>kd!J2qx?X(D;aS86Z~q?7w(WR{nZ{M*SKn`6Z&H8rb2pb@3R#K&8lW9Ajq6uH_SiuNj_y(Z zNdHuM1!8Cv^59tA|2tTd_yjjxXVde-YFLZA-d?KbTk`SK&rSp5j{@;W<+f2pYysM^ zzVb_<52Bw&eXmUkRi9#JKSU>ZP$y1>hP)1qCWaEL_fkSKQ-yo?qHkq+zsW#1)Rd9bh^2IcMWSwXRe5E3>ECulNpT?wj>yZ)&Cbrs%*;qnPftxveMlrG zB`4pj{s$isQq~Yy+H|w1K8l#`lvPFYBmOxz4v&cX_uLqH?|yibo5`K92P8fsrlP?rnLTgQ~&fI>d zbRO*ty`_d9M}0*5!6i8a6#S3+hp23O*s~80-^^8;J<{S3D@k;OVkEtTP+}URW}Y17 zYh6yS2&ot1TdKQ@52K$Z_+Fdnc@o%LM&AVqBYxIo330t3uuHs*DUjoiJeR6gW%#I{ zt6dp7+1LB)n*>Dyhe#$*i`@vv{Zln#muG&x0%=SSNbVca6JpCp;*8;p76xF15-}Wk zXhnQLu1RewJr5Q%l-`4;bB76JdX!!P?1B~Tw?I3uC=2wY|a?5ehD zLQW{Nxt}nz=XT1)jI5E+oNX&-Ewrg1FP7a+HeYL9B?p?aWE;nZ85?L_M+beG=S%73 zsoBl-z9vActJ0@L#6yIli!*cbQN(;UwV-UR$}l(Mbi|OZF+mSm4mD5ws)+Q4-g`|d zjt#r`FkF|+^Rcfvx0lekLJ>UzwStIoF}On13X^kfz6MhSI}fs{XkGNWp>I6nG+If~ zmTOvf-3`a9Npy1c5|VSzlCm=UYKj>k)xJBEj(?led5yoVl(m{vxtPV(;k+>Fx~ zPOCEkm<#<1aHdC{@rg40-Z;W%!y{FN7BF*eXPObASt`N$CZEv$7I;7?{jwHbDvDwF zW9`<<651Cj5)q5r%q_(lF}wIiEXyJ|QY~VAlfN;6z<)PFHzJ52QBwSpjpmt7bSIBe zZe6){>3B@y>BQyV98vb=sWMgeY{W}LwL?!0?9B;C5xBm zZQ!XNA6#ILl=Y)^cFf_4p6KL<88Ei+Je{!>QuK`1dDp^MzcHuq`06>)nKgrdC=&dN;hNU=kLiA^fZr znGD80>`aXDapg>`LE*Eb@t0q`7NMCSCyHh}LAGu0I-LCNp^wD{~daIH7-0_Qnyo8IwAYY>SC4t8@ z2k*YY;N#_m?x%`8aP@cYf zJW^^UT&Z8A>SQphirNJ&xpTQFBYa5bQPuE_aN$atE)&9a{O71s8_p-l_!%DNNf4dQ$2=#!35E>h ziXeI%)qsrVo&66k63}urLa&L^yK;&6KPi6{-Jc3lX6d7>IEy&o5LAA7gUxguYu zO5MQgehN9`Y7Q4p%l4h6^BDWWY_yr+GcT)^pNpN7Z4Dt4@9lp5eAQ3a-V|%_!HMJ7 z((peO$I0!jRsSfCC)?XQCjLutY}nEDic}nT|5`gW!yMVse!5duPWd&ngmb%?h_nWU zGDFB{!Puy^6v? zk8@&Te)vXSN~{ zz!}B{!zX6E!4vy5U8&`fX_O00{@~{X%55Tb@Np(@7Qwr5mA8vLVsNfJ^iwW5A}9vs z%;Z%B<59W^OmG|=Z3WS$k!yPT!@yr4IVe2|hR*1-{3qlk&1eE+p&?V{OPqqixe|*1 z-X6}5Elqv+^@MC#6sqh%_>u}H6rmSY4dWcypgomq@g#V3^6pi*DKkmG3JGB=38CEx z$SDr;G6|)eq1CbC^A90E2yh%mNyN20VATSCzvQ8waZ8?wpq_E1sss!i;d^BFyUZoW zFp9MUcU`q_*8yRn2zdP+G9$^DF+8_k?P%{s^#{*Fe88t75=O7SfE|LQX zjho--!ojtkdsLOcWC(!N9`$&HKe##MlYi*KH&)m52nt?-E*1peK5{3-(s!xEkl z%aTGJ1KFS*e8nBk69nD}|KNX1!I52H+8HeZe7^{chQzQp7<` zs@9`@t6*A@aXI~Q6Nr#h)BDj&HdiYNfqcLp3uMHw9l4221fMOVqvu+OfXc2*6ei9? z1`=!yO!mW$Vg>Gt0Jn!ZW502fGDH&MT?Z4{js-uaN+eZj z6@~LYHfMRR18gh_b!S7fs@PB55pS*IgiD0Kb;MY2#68QFj6&Vs31vTkAVk;MtoW@z zgd!`C1gAZizIDi!DO-<98|N-0Fc*A}5Pd=!@ZOxzB1YYSm+p|{ur>4wFD!RDTORoM8vjdY2Uo#(MOJG}Q@GY!F9;8keAO{gO8lUT%rNlluQVH%P zdZuJTc?I}Sa+ymU)!Xpc7?0Bw;D{9=m5ro052q?5(yTfFD?}PkV{#=tO{GH?&i{58 zn~G~qnwNj5Zy;2by2vjD*m%uf5df@Q1>R#-ax5NniAw*Tx0FPXdp5yy`r&)GfxQv< z6BHF0TH}n&0#}lD5~|{Uy9ho|0Ol3g-_Ao0&`>!QP$KeZjvus*0FM*^rso-b}4`iv8B9a!q6^j$Z=6yPPPJN zR{A_@%u(zU;7qZhg?q+kdo6+b98)0>L4~}7cv4IzYaU=4k?QtDja`&Ubsm}lT5(m*C%!c;7n;y7#h zbAn+kv#0J|GpDlRW5Eqj8Dm6ko+E)uhI_;$oq8j4CP*-6Q>2JI7Ca!|+F!+x@`!!l z5wMQkt_8w}2>fIPTl`g4$7Rd1smu`+DP4%3JNYv6&=sWz@Mh?}CPZGY+6%Ep3ryo? z6lm8INvf7&p-CU_Ai}IOKRef1mo#mpQMq12l2C`fTx`Y072$n=;tBFft_FLzs$lUW z!5MgAf1_|KbUGIhIA5-$Ca5djF2`-$F3eTWEJm)PYa~ty8XM8PxoVKSriKybrAr3$ z@4_fdK<45cFO5Mu7!Z()TthVpr<0H7FsfWvx1es+ZEmqDk$wLxfA+?vQy&;D7d zm69o!>Le~pk;Mm#P}EcULMMC~@&1`gT#ggzjQ`IliiA8y=Pu;hQIn{A7gnbI)Hy8s z5|ckmdk%=hd6*$OMS3P(!LvoGcMA!L#8)1JHc>Fj=`L+vvQ@thQABHvW?1-j^}LZ* zA?pW}DVCDwvOURe+O#st373GyW9TlLZ0bsfmJHSW81U8)zGVDVsvBSydt77D^lh#q zOT3JtIllNVu-RP;cI<4`QlcMVlLhDrJU~K1o0ek-Py#0%2j4*)=xBm-jt{(9hf}7| z{JgF!I;P(Kivi*en2m_5-_i*%>rZz<#NGx*#aUkUYYP+MBYxxu*BD!V0n91@Yuy0O zW{_=sK%v+wSG(?KAhGzz({P6VQJsD$#$Lx-AyKh;VHBvi0#xPIp93$P&gdhJ8D-Yn z&|w2wJuh%7&@>*XCy`3Izc8b<^;=pw^L0jl?b4h$K(Ym8u~jXfh;S?w#^*sb<5+dh z_o+grheLSi*8QkOnHcW@PiYW?p+J^RaxrS{^i+Js0rQnHL?VNXA0ThcfN~gtMT{VFfeUpbY^x)MXXC!K zqkj6MmV>dGkJM$XpJ5OoLMU3_v?nzFqUC;9?Nb%9-5P-n@sB5hI}2mxG`(uPH>nVy zZ+Az)CR4EHLgjEOPabGG8k(^_UZesoJtMcor>TRVD7VXqp&OD{fZ@a`s0UH%Syu_Y6GaiRq1`ED0pY6F*C^H z**`YWVil-^B-8^SmsIv-y8mW+3YitdfvgGu>;&Ku zhOkq8b@S{wwl$SHee~=G!+`$FVTu4I8LGK4;6VX!`wCJTK0Tu{=jpHrHh-*I{z{$f z^}yC^R{zc{B->#kzGbis?1>Q&kd!EpZ0wf*#M4|Va-(_!PX6EVBd(SA=MG)jqrs3ah z-n!?$6>ok!#X0SHbn{zOl>+k1K<+hB14$$jkaI8;> zM>t6Hm|U=MhGaH;i{esxk2IV>zZ%DaQB?PMV8i(|nc-A|>+9$gieX!5DtbcPCCz9R zeW^ghwT8kff=bA6T0I#%ZGh2gP(ATpv-97xZr<8CPulqs2o>8$I#}<~m8WsgX>=3z zt`6)5z!wYPY6~w*q&A{$3zsMm3(Fe&cXffxk4%Dp#&4>r>CVxVI?~9BnM-mIGRusRlLbU zJ@xJ&S*56WQ+!~P#XObI2w`R`AXCV0I6`)3;Cqus=I`>lzBQ5-yIcQD{_qEDo(^mxwD^gxqcUO%_ol3^oH%RN=XZO4CEyoagt4R4) z#~X68uPo-bq@PMVJ!Oe_!0thu2~x*!UclP1?(=V_vo*0R6&*3ne_=UII5rfOf68tc zM>ZbuiLBu3dfJBCU~IRKxXD}2nzx+a|GcnnRAqmvap}nt{l;T~lkcWRK<&d{fuFY2 zKOyhl6n`+q+3|_<(Z}6UN%d>q8ooxNQ&XH*&qK*Rm>m1wfAf{UNjd#D|NQSmvOlTD zrz(Nuy+(*vH#H_cVXjt#K9>9$n?m**VZWSnk9>RqN)ehv{~IFlAI0%^KeNAzW4pm@ zlP#@eE>+7gMZeeDe;3Cs4v!TEs0l#A~H6|6u%PzXp zJ0_K>Viu+8Q3vMfpQ`PKaxETV+$nN=DD!GGt&4T3sdy4T50zJ?V#}jBtUlUw36m|5 z5Q);)`k>QXoJP%|{j+HJ1-fMg2Kzx_PkEu5&|>>x_Blv{K+}oaWPvIJE%@i>{j$^w z6CwDFXN9h**|+?SxXg2@|X1TD>}KNHMrw+%N%v1dm-yQ z`)~tuE0KJqulmYD(9FR#=N1;iX3+t z{zIjsp-d&4-f~4+S?}E=Y2C6DHmRWm(kLt$eMA4^+g8FQC2jG~`o|zbL=wY?{Kr$u zObl~VFWz|rAhPp1kuoy1|A)4_d~54p@O~dWL4$iqa4+r_+>2{*r$9r|LInvBJV=2e z1%kU4clTn&3KVxJ6liH_%i*{8KC}1C?3w%A56)kZ2P@Z=thHX>_Xo$RQD5zlxlxa3 z!S+&LYnbpEYvg*nFOMrwNLUeYeq}$d`$$KK?7+VCVlGsX(iniPYDHme`P*lAq4n`3 zwuwH`$2^mt%FwhW?Hh8HMaf6{Y5dkXq*U$t@jwR?t|&JXJ(GI2<7L;P-y!idUAs-I z^G%}SyiesBjH89MJ%uRtXBiDCgX&@;A+C?G6|ltM5bAb)+y^Zbc4xm0-kOpYbAJx~ zwz~*?NC?c3Bd66hAP(DMJ*{J8oWi#Er_F1zk9#zvHG!{xra|{oC(>&ku;J9|JYu39 zZ~UO-d8;Y_6SW1*2>n#(S|C0%v&TqjXmWjn*@N26Dy|PTR0-m6!$ADxm8aZ7&~mbNSY06C@pAM|B}$8&s|**N%2I8i|r}M zM+b?|P4UI`Y1q$i?V+Nt%;=v@dj1T$Or+S5zFb#jgof&~oeW;mW$o!)$1CK@XjnXY zdY+8s9-3~#u8Ip5!>3;d0f;+qHn5OStnI6T!d@^lD;90)?1_w7 z-XgmUaT3W@#04x_s;j72PonV;33 zOcc#!NfY_fDIfMA8Qq3hfwHcdbp=bKQI!(Hl&wM@uDma zThf7EXA4v37eD!yZSn)PIeag|Le$%lh{rO{YQp%ltXnL&vcP8`wc-jJ;bB3@bR;JjW9S%61>$m{UmZ&oXu}rPSW@GQk=FX0&RXK#ek8}f(z=Vfo};0bHs^r(>%J=TaDL)wKI#8WIp((kc>2hE z)&ls>fs7AEW4eOA$``CwA@m?&`P6MI)`(-y_r$M#X`Yz1xgE#LDmW|pbGc{>k4~uL zXOY#d2aBy%PSts-S`V!fQUpHA68aMrSUHFVXqUY7VuRhXe+e3G+En@CIhJL;H-Uzn zO#&AOcsMyW(mJm&200YpQqsEibxZxMk$Z!?{_vye`&Y~up#<($VFE3zA1 z!w5ik1O6qy#-nc??Y8W1SUckG2wo2nIE1N_LGyqmTu!!{4mXRCQGiPQigUbP2)u)^ zEHb8l*`Ca$FV(IKD7y0v#E}1^YXyMLo%&SiENA#oaEC4hFS%b{N)&p@iWEg;-yfe< z9wyc>iH9=VlE_o{;XH3l60bK&ie#fFqc^lVblF99l6Lx|i?bYfv zcwe7{q29`Oz=4gu_VdqagKJW88%@X-4{|7!=V+e$u@@30>C+d^^AQU-*;s(RYkxup zaAQSxPER|V=BI4E;p}(ssQcTC+n{@!zKW|dNtC9D4|s0g^}tz&L7@%^2eMJ0c=*fE zNT#JIyRcbyijCF8@o+PbQyX6WuHFVGxs5e2Gk;=>mIXmw48~Ke#K1Qu87M#y556ig zf+vstOVFFN1h=;1`1a7ft+v1I#w%2~M)u$j^bpSX5MkpRZ}yNF zB?@5nk|GF!`9KzC*ej(Tx=^ktvlf8{QivS-?U~{FaImxIdumUg4+aeUy>a#OZ?9Y$t(<2_qex7lM>?P+YC8rRSb_RxU1bU?Ixpgi=DV9{8($UT=P8f(81_`y zW^;~e^=dId+XbtD1!1g%h!dzu()cPQyM+tL=7?YVYrJE5?2md&@i=}*wsy-cwqb~N zO{GfR>V(p-As{nGIyQYJ;ou;{P}j-e?8HzX>rmMQ{d^qCv{a)UH8I1gGD)a%w}h>b zEE7}nLS^QPVLJ}&sHeM2C@Q`)nQY6vQrO}53IF4ZDPiA9SL`Y4RGn+Re85O3uSPh7 z`n%(KDAAK~?fY2~q~@w#K3yrcCF;?SN^DlaN6C6)f*8{J%!1zMkN8)Mv=53RTw$^2 zlkRBG>g>mwR-(V>K5DE(V z>I(W4j0h^fnRJ1PcgUGPN)vQ-it&Kv@FhjWc^^tY5po``Ac0V)(GI)OlL)S+<4YH< zo%Db;X)q%{uma;!D?)D`tV-aRnnj{ABKc1Z&|?S^oVnXd;DQI(dj$6mn1TTZ=*0)l zhUO_gumY027?=scHeJ$q_T@wMa)=(+G0(BN;@IjGf4G8A62~!$^3f6CB3~iLJe1h&z~guBd6`7W&zB zmho*we;w}4Ebw)~bT~wbegL?|ODGvKRAB&JJlDfjF%jZRr+`l-0wlv+mEyrBeL!ro zXSgQdq0yyju$3Ne72>O-NtA*vLPH8+_CaqgPQf+qY3|dwmW-Y@_8WPDo;XHumMmJJe6D4LS$|EQ zPS1d#Oxq}0>gD7_8!+|tV2@dZ=%=!NZMb&*h+b>$6yCt{eyOp1t9H4H#SD#k2B*1f zm{HPTOg4I%V*YK#b)1TUrTFs}?Z8j9U~sNe%*PcI8jnwtf#yb=#msELZa*@WI5QfN z@>;&Q4yV*gVTsoBrCZ*`8G%(bsCd2WG8#zM7T>EfX3=MBQI$+SfrGE(wpzmneGJK% zW2AYnO=-{}J&+SK%va$#fM0*zZ-#GCi7cX7dR#NRd{^1SY#P@y@;>?#V`X_KXr)SJ z%Q$-Onbqva$^#kTrW2CDW4*>bvz=(oK1OvHEwJ0!LUV3?^)qwK7<9t6CKZEmcq%)% zWd4rO;(Cp5`8SA!!D^qcUBJMiK)~jfuN}YqbGmJI#;#2sx>L~*=rWFUzXn+`*w%l= z25XXxFicc80@Xb~XSvdS_1q}g!dapRVzGmM7=v)vZM*0qR~e82;3)kitIBB#O}@>h zXG(@rqlt~cA=o;NSbG3qH5{2mSvVVY^EnwzPP4FybhisXm|;=vq?;n8{|5AJwN1TW z<+d&hI3Ec^N$AvSCDPdQL`oZR<7^slB$wLX3G6lhQUQ^vZnro%q`K0HdTlpp#r)3M z#{5M$JqR2U+>-vbEwB2vc+@UVftm<+=Qf#`RBq=Fk3+)rwu)H2fRLm5La%_7gQoLC z*pMT>ha>V_VSCMy#gMSOa3QpITaUl#(Klp`zM~O;Q`s6463T2E*{-IGtodPYQ7mJ= z;MBJ55Z|+Fy(e!?wbwFk8wV^f;oqBN*>&QV9ujo)ZFO`Rk_J3?aNiU6)ptIA>*z65 z3!6gpUORs#-}mO1(wWiL!Eo}SVtrE}iysL>o;dh>6%_WWxQ%aB09=A1-+!cgtdi~W zsu~@zB>N~M9pkZmLI#t6UzQt{EAv?X-N0M9?w5G=9ULn^f&9;Kj7RvQUb(8FU1O~k zvp8!){v1G8+Czj~ZKPwKh$5X__fpn53=g)dLJ(P9&Tp$(hee87jGLJzTyn&Oyx~Gg z?7#&>>3ox;BIl!G|D%$~qtdjavf`uirlX3XqsoP&sy%m$A=liSqj$jLESe|vXGaaH z$Bib(@137WZ1U#@K3NLc%0(V$l|E^Icigma+_`t$_3gMD_oRo)V^85j?#O7Cty%y= zElZ;Hsv~+HW3yKdpOqlSw=+5@PGb-0G0GnU%4r6!oTO&JroI`edcV)hi^Rb{O$WM9 z>52}Y#q~dkSF}7$5$G%Q_e2EF-OYq(WN(NSl%A%lA9VA3&bH{inQq>qIqli|_(ANf z3?kj(j4wFh$$8C{8&bQ$56Unyo1H#O)a%boJMp2UsEa+zyYWg4Tsd<7^3DIt_sB0d zXw97++>HB z2*Sf@rnPBs8E89qghe9*ae@SjRBJmxrrG$9fFtC&mEord^~gbX?~j5Pp)?hxI8ksR z5`BSChMEy-4m6EC@_O}Y)P`8>j`!q+cR1kL>H?CU?`yT>S7~0LeE9`?0GfjX$r|-c z2iRmh4jnA|+EMp4wC8JN#~EEDBw~*g@6GL3FGnCbaz!-C$AZ6wRW2?B@DDCq1>nuP z=dxFrl>gU(-hYP4{|lF`{Tr9f*7}^G@+n!Sx}xNs%MNGw6c-o#6UyFadH)7w)BiJ+eO21% zS6J^?SQmhJ}Ryk7QBPyPXA zQE08`93{lt|09&WSF%D*LFLMV*@FL2vW5m0+WO||x+ZGc#>yIoit73bs*nDv^TM_#c5@P5~K?e^=*)a*F+1E^GO}aoHD3lR3Sr z^hz=Rh0F4J_GW9O6gFo{_#CZ{{s)&$-I_$Jr*K=1HI~hl;0(fYGWAyl!qv*$*T&vg zEY|2=Qn2DSo%B3*z7O<{H&uO#Y3X?GyI4h;9H|KhA%+DW^CUj%eQ#mvanfe8!%Ve) zTv1O8PB;#W=MT!N=KW&3yi&wtgb zoNN%Z2`zQ*SMMT=?gPCx9OjV?cnQ?5ymszQKad~sIdFcP=y_0$`skU=CtZD33IZV@ zdU5kEn-MhS^PjZ$h8iZZDF^e%+t}C8w;DT1t-q!I1zj7OeIXJ#(V`L zeB}*=!{?&e3M_J|<|<4EX)_5`R}v7|Ih#?IrZ}^&eY}}-w9{(}9Zpm-rg_tHENz4V z;ak!{q=^rCsQFuEO5N0LjUR4q`#IBf%Q5Lq#-N2jzE=@BiXj?C9Pg0qG5NXB-<*0V zLQ3xGaI%P&c`Gax&goR$;vH9>xau8tSU#C=5xTUv{JzQ?bTeBfa&fl|&dsc6GgNXV zqu4I*__ng}s!9N~Q%ylcHxth7j$Nti`ab!wVi0rc<5bR0GskRNeG70CA(sTIvMZA3 z%xFL^GghG1d0rc0oN)f_ zZ&pQzvpCt$<2M^0M&GZjDOeyRY7R5BZ(IsA2z{dWAmcrHYD~n`^ZH{n|99Sn#{s9; zi`bGx-F5pk?pJ+Zf9iK9L@4p_Z0P$2g4*k5 z6UkA1vlSqzCG*sE7046_wd)>1HB_0HNXBA=)LE%4}V|Hn?C)0ALy<5{cZKH zK<_=5{qt9#_s@@mzqst*1HIe+Hr38-lX`;}4d2NB2t>>N%&vyhnq9r=E?)W|hnEUm z$G=H-Z$v9&jz+c9(4<=a#&#w&-?$iX1X}{fp)Kd?sR!bu$LcDU1k6YoOv>co3pD8~ z5FHK+S)U1SlqH|rfc{ny_?Uvvu2V^`?T*S`{8&Vr*%lwHhNydQvcn=6hGoE`aDPmf zs!(76Q_WdfOeyAk!WffF)h_Z9>UDw?`Nk5}%<$~ZN}!U;69%AUB$N)rSkP_jd<5R% zT>#Q8i>V2JGlJZ#;^Z$hAs8RYt|U!j7xM_i?zN*<+agV+#CD-^!y_SKMa6&A3?CW~ z2Y{G~1BfmxvFf%|O0hJy@1iG&O^ zyFZaWto3OO9k_7gS!QjVo*j57g{|{vtSFnfPac7-sq#Z&PouOLrs^jgsBxSiplVL; z#$T98(YrU^7)_R_Fb#Pu0+O_IyaQACKYD}PN`OJ$rx`s^Pub8&FCVP_DCOoUB*bk? ztlw}V0-rTEmwQCmjzd4xte*1EV|8XW%y*JGvycRa`$rSzU?r-7G$PMviF)R#7|u~g zvQRE{%0AusA2`%GGzo>(&q_@ezCNUtRwpBhL5J?dM1XqH)%F%-Jt1M?mnYcLMT&X4 zTm$hxQce6%@Px+@zWy}ZwB}MlI!Na^$PipjZh@4W{4BMM*&AxC^=!gpPmuxN9juGP z9OrZPl@p&0$nMt$#-l>j1;Z(EwI_HQ0vI}7^WPS^{B_i9-qM_|O1`k^?L&Y|Gc?|l2Rz#zZ# z^`By_WTmz$LfpxOCZ)_|RSKamyDjk@OR;GI#a}{-Vq<=94fIHx!JirD$04t%DFIYS zVliGYF$JRQKotAc^*GqcF~h6H1H_qtNu0)ffBKl#HQoq=)Fic!^@^`nG0oe)x#)&1 zl~UavkHxNbXQ`J!A2;4b@v}M&4OHCgQ=(mcJsw3X9|I~pg&w_=C$kKx+%OhQm{*ov z<*WquvdWbDCz~fb-cg_3koZ^orl4oYOB7z{A`JC6SqqrC9uPOcP}!Wb=MM#+_v~2W z81U4G>=feEebuIcDTY;sQ%exJ^WbWMiRpNX*KHleBUfqpUYkS1UTNkL&F&l9T^I4R z?P^ZBX{5_x=Mg6PmW569EM!!YzVX*eu*?BtzgEH1xBke>7SW9tCt_$3>dW(ZwJ?-- zxPbzj(8yEiGuxM?Pwt1_3oA3Ax*nq^pdW&+c+7`UMjLEPK_TKJNg`v&ejA}U8>_yH ze3|sY{@2#XI@vgS#aMI5RNA$v?Z@#@&cl@~Ct=e}Fep5nR%*aYh0C^*iWvNYWvSSy za*k-IQRJ7_>Rm^@Qu0f%(=YShmI|$iwj`IElRn3&a%1l$_vGHGV?A%o!BNUtt=W+1 zaA*{hWN|iCED2%=vk8o6wvKPoBg3Z*!Bmw<00(%tQF4iKYaBd__D{r)!o@VqIh14w z1Ur0k((r?s*#RN8qlepl@5h8^b6%)t@jNp%5~@z%Hg8l^K&{@YGO+j;nK69v#|)^6 zn@M=lsCmJoA!9I5bzz;K4#^(=bs=Oe0ME6!a`cHfGW`%_x@5s+BtJMT{q09T?5DsN zFBJ?rSe);#ZE_s-Xn}>bwUzs*!?r`4R^Cv#PN)?G2NEg%?BW&^o9UVh)Y+>$8MCb9 zgh%QXefL#V1huME2uQB}a~%=PU4zT^3p4cBL@Mm&6K9!Xru(ng6JBK2&1kyll2`b4 zkTO#4C>Ws)^#d6LYle^)HV!YU0Iyp^U8|A^DD6QW^~C-Kc=KZ9xshN@Bp4Z~8D|Tb zXD3F73bAA1%eat{L2&Iua0MhVMp%d~-&2&O;aeAAeT{-{2aujRtN#)Q6EzELqI95v z;1|qp?7|3aI}N1(GO`}L3^>8E9(Wl}kkNxjryvt|t{fCfu!ADer=gIQ5H7(D&6yEM zo92=q^5fP=;M|9F^t=8F*4v0h$S!r31YOBU5AjI z<~?Wg_H#cF#So{IoyMZYVDFoTEPV~<*nIsFWwt;aL$XP%3*_L0;)Y6)u7nV|<{{Hn zf}9IpW@E4qoYSv`^6jFdSnHr7OW^ELgZXR@hSqypIJJCzCxRWvEbpaLH&rW zpf|z{1fv@4(8QJ680t_Ea6>w1%S_!a-b)zeiNS6X$@o2#kDCkXhe5J_cOJxf5zuN1 z;5Q~F4s|vi@H*|`8v-OkLqRO9q#0m9Z+{~Aek!gP3(wn+%#6b5kkWja((<{KYi%mD z7q1)Z4Gu;WRvpN`jFdn6r8Ft#l0qUhiAVq}8_xkY0Fhcrf?xUvsVAjdY^EDwWT3-A zY)KI}NNIZmLUV5um(Wy?Lt2~XWNy!;-{z$d)DbYHl8x@Y4EKqhbBJJ1iqKt_c4{F{ z4t)HD%7aA>EDR?23??~*5UMFqa0AlWp}4I(Z(oGRJHw(Mg;KrOPjOntAJ7v-DiEVl zcyR#Y69|?PEQ8Yp*tvM--z5GYc-V(m{IZ2QyxqaR{j!;}H-^{3f z4Bj7t(@Jwj`|rdB^+Y@7ln5EBNj)LD3ZPWm^3tDjbwLs~X|Yxq z{L#Ba^fBPK=MWnt)pIz=rW>5H$JIr zZTYf$)uI##*RtwfQkESRH&Ft@Z@_u@M9{lfaE&^cL=VdqRi0v7g&SLoe=K`HN|>lA zlP6h>W!FHAQ9Jh>e74)bWm&r*)wnX}B5))z%AP;yP?+1+C~gVX`3Yv5Zm3eI!VRu6 zA!yL_ZsdiQWX=JWz)jft4ZgQE6;h;SG4*qrpsEnuGf~-Wb4im?neiB~|0nRQ8>uMd zy_+=1t*6xEQ`7r~xO=9!jLJh2G{wYb(bYA>o|H=pv?`J2R>5<$lA4kIcmbdAqucL4 zv@!R#;bm}nD34@hY7HMLDrdW?%%`1-6rfQ7uE_$MF9Fy{G39Ps-16GuF9QTforn)4 zKjBljO!GLy)4B8Sm-@gTdRm9>vWVV&Lc5H2Ol3)Y3lourx;AD?o@&Y1qgwGVIx%}2 zBQl6?%gN$z8@LEsdx9m-^-4rHZPzm;&4Xp8N?WmD-Bq^TxJj))#>vLCY8Nwc@7g6u zKFWL~kb%Josy1q-0bTa7MBBGy+@d!iMR zoDGG`9bEhRi3H_#A3H|L+y3{XEVzf}V8W9g(?Ei`5pr4WcKKil`#PotRKcKdFg>pf z3>AZ!L?pi2a}|iRhqTLV_H+KKkHG4movZD?3^N+(`H&Z3UyGp;+Sg^+leg{J!6Q2< z0GIG4jgG~Lh6#RZw3%a$p|vTWc(j&pkCgNe zk8h7RPEa&eHZ{);W^9j+ZWA_~P|it#NGHZQFkW{_%gi#2j;>OWYrl7^?Q=}=6(ub~ z8#a#2P3Hfa)U_M`xPqTNF2*%R78@rucRbPEKQ*y2rQ2KT$^&|a)yckTtNu$e=S1cn z$39BJowq1oj1%qLB&PjEc61_%=P5&wLnS9ul@=$u4#=yCnG~v@arYki_;bcoSZiDV z184q++{@ufhgr9~-qL36DeDw{QTkpeZONSb60Mwpo~K++G@XS+Ve5#sJ{h!k1zSI^RJv z^g=($!#-l>f2!_ZsRArFdoR<$ajg_SA;Z%~`agA$1A6#Y`-uSba9raMK(!7_rWI+^ z8g17a#oApCxy>Z_bCneC`RZaPWx5Wg2LwC)k zkO6S5dH{I3vqFqA4_>|aiUD{~i~C3bz*fD{?St{5a|?jN^w_`>ZN{`19 zv|X0*5?!=plB?cQ;9pUm;@Nw=LlcG}s>_t#iD5bokk)15C)%Bc?#f#;0rD`O*kbGO z^J7o$Hf`===5J6@*p-F1CMADD39`3FPb!Ttw~grq+VwD1F3<`vx9LlVJG+Au8P*~1_% z761f*?&2=iWntJjtm@+Kda_?Zeq3hF@=5mi9=<-AI?omQS6G^y<_JGI^#33$y-@%%dr}Azm;; zm(+nAxNlv0y;{y{P3q#o>kq;Q2Mz;OfQ@tF)l1#8tGW}Xx?`c_FI58P*xi;81u)?w z=}dtOiW(5AOYZwCDUyd@=9FTIYN+UIzKj}j6!v^MaX6zRxnQc{oT{b*K4O7(pYz<2 zSP3#+G&*P%xqWFeyc~7V$&|ZvCiP=Zlwmud4|clD^6^tAxvDR^($3{ReJ7>+K}I99 zkZ9M_FJ8*9TgHC=I*oGP;t`nk?uu&G1vgjHRQ#LcYfHCWnf{)K!PnlLOj4fmU$dOr z%x$Fny1$LQ|Ni1B2jQ{QtGn-kn4j~6Z^nK0PL<$`5JLY-DdbZbY8!nEgShg;*Wi&5!qJT{T7v7E7oZ<=ku*WDD8-Q3&qa%0_cGfYDO z?~0HAh0Fde&`TUZp=|PZF8d0b)}XN8i{)>D-d)W!f(9qyoBAS624T~`X4A>W2kMVo9 zH<`nu`seXa-=mM)&zjy@-TI%&*99@IKIcn=DYjzusP}L?Spo-A$q< zqn;hw<97ef($q*pnacd6kTPH-nwy+nnA9bQUif*EG<7hxkUCWKr}xNI(@~6CM8~L0 zo*l749}O)NS#h3jAFV5AqN|82C-0+Gq^ciWu$-L25;j|tS#CI}PFCfORJGrc1di** z)YZSS_m~KWkXvHx=DnEO0Y2ip!y_BcF|p?z8F$LE6>h`3y`DkUbE<(l z2OkiRxkl(C&l#eVkeKfsnb|-=eg?fQtUx1k6>?nT$`<|7N8uf$?EvYT zZy61g6PD73GkGFa?*94QkG9yCkPDKo)M3?ZoI1vgvtrzVn3mtn{o-Sq^4#)+(xGs* zu_k6OqOW3FZXg5uRYc%*N`?QzDUv3FkbSA)afHcH?7p7d{kBX^w2~0wpsgQ zB)wO-WkS1G`9Y+Vh0CywP^#|xjRfv=Gx0i&-RLDJYT>V7%W6$D z4A{ttUHJVDrFs5mC;aQuK;9K)^6NYkyxIOgz}fC`B*_arWm`=sG{IQY@+_)iA6MWMT#S) zml>#%m^Y`Rt_6)p`*u6SShu6pWWdcW%}H9&ndo0XZ07%ngHN~yLc}*=diB6mzMqA$ z)-Sf!i92dI=Gj7Zzt{tXK^t_2; z|2=~OFb{QR1fXbD2gITfj;w5w8k#1_Y^IHl>?EyXO?@YFRAIrZo?+8Es@}SvM6Yc49jVMEq!0Bc96`R(2M8b2vQ0H}^I= znt>zt5T&nsm%=06=qz?;uj%REz+ZmlEK#?m>76#0y|3&dB^ar3|3i@T^M{l4t_JDT zkpjlHuSnkg)(_}&MDAT7Pz(><7FCFuhj*!b9{bO;(P5%spK<(b4V!GwTS9Z`(TSfN*}@3>wb z@FVYcY?5LE6jaL9Sc{T!**}(1ygf85;wFXbek`vNaMkn+GL8~St+4R~s`g4PrKjP9W6)~=QWSQbBr9WhkBIId*QNeMl3DyIA;r6;;UjW5WJi|?^Fcz(3{e(-Q zCnZvMXGnSMkYiysY9gfCeEY;nw0-$GzeAY$j8bJ-k5;TEMS2J56AL8?dU(0d zxg9Xl3)>ryvbPwllaM@r8H$;Z_vvmj1cA%HMXdi0X%6NcC$$NYk z9g#AT7rAsZ1e_5RDvTpEFB$P<+l~;(Y+13wmro>0^@R^K#r^$H$^ZT_}hWg`2 z&3~x7Fe9s9e(0!HBC1C{cspi2tLYr}E4_Vv(mQat{m{>Nv6n7i*j7)F)KK_)`?Qs4 z#gBg1N=N|zvkW&A9{Z!uxB)Gh3!+MdISkL@NclQn;+JvRyYI5!D!hM!(^O%&VWN!L zzpxG|Y~Ru|LDH|1dwem^I~{%VwRmkg^wL-%dZz(JPP-@9+~(_?=Ifw>S5MI-c$dD` zOGBh&90#s5@5-TMJP`Z*sDH(DcI-{G{A#$lPOY)Mr*~XLCFFtp_)vbmS3-&_8k?5N z;ygYzF8!CimCti=`V&gGxu!}%lF=S&j<0AGIgUj4k^u=BeuK8trmCCdbmCjzA{Y3& zzMFk_)_QNuopL5mZV=8z%yngd^1i%x(R}+9EIIKvBrhJB>=tbrl*O1nE7SH#95@zo zi#UGP4QURwSE}32c{&j*VSjb@z4rpxz%%Op>1kg|J^4B+JfLGUvTh}`(xKMJ+i8-e zra4e+XN~TtNqycLr5EgY#VOgTVNmmPl8LR8!R?dR7E#2LlFN!Ia!>8%My@HN}WV{e!JxiL-V(0=#_ag?j^^NUT&>34a2%%UM-;5mT;zEDpD zplC&vcNE(J7V`C6brl-zTV_X*||h%tMJf93xv01{)v2!p!GlzS;eh==Bo z+lDX>vR>*5NRt9@R|-r%tb@K0aw84IobTO^=J=(A#QxQb8v_dqiDUkiSL*{b%~W8^ zW-O5C4%>inKBnH{0aA=&J#+0U0W0!kLxfV;jWc8gQYiy!Gsi7~cWdE5;tUB!fg;C^ z5FtX46gEg&r1P_IKLQdlMUdv-@-_k~i<;&zQNS6s?U6Ogk|$K=(FFYxV3V2X&&*_z zH5!Q4Q_9OIN$RQ|>D5)HNBMMxE%otJr~uLAaMywGyc{FMpjqmmdEuZ%k?u7;jstNq@1pR&}PRaz2!1QMo2dTWC|fYgRu5oZ8AX3OZo@}XbM1)~QtTdoBG z9uYtv2DYOiNJB!tR2(PWNVu(9mqcCGjq+=4!VsCbKhF}HUQG-|oDjTgBMd^Qr!CQS zgSpRvh42CO_37j&ia2Gd@&w1xG~dy5#Art9=-a~4%*N5Ifzc0~RoOeE@2)fk)l*(9 z^Q@U`AUTI~S(Ai&lkFhnx)*N_X^}_XK-1D3)f@G~U#K+m^5pwhh5ef1hqzYD6*bEA zE_U>Z$@7cSXf39r* zC&%;sbo1WvT%B%So^IZk@2-yjH_CIlJ9l5cJKkA5++MoaocL$+ZgpVyXz%mh_J25@ zgU|PT=O2RS9`x+3Pc5&n{5Qw*Kdx-wJD%NzzRwH)p7LzW_5L3z&*#aeqmIP?OUm=_ zhPMBc=4t%<(DuJ*p4z(iwT*RE^>vjM^=Y%{sDJVGqaxNRl8)C{fF#HNKCxn*N%&ecTdSpy5H9RmwoN~ z;N5Z%$#MYhqCZ}}r%JP#_&+ALgI@Xt1piMH+s^w{ z7^KOmwCNbZM6`9v4HATDp!vrup9uN%PJ-~hPf)bJKVD2Q{;^|ee5I=R#_+W&r<8!^ ziWaE%fo{i*#d}O?XQOv|i-tqI*HjaH;B@Uhv?H}|bxQlimyLdcyNEw}Hwq^>vcm3J zYPK9v#Z~12NRd~MZnrLvKYy7O8@#4U!b=SSy5UiUfc1wzhY^a6Fquoj%0$YFAPFa}U ze>xt^Tn+q+7`C*PtSx4qWTYA$hM&w$ddM0{W=@-&hU<2)lWrTyWf<*<{su;h@6u32 z7J@{m*+lZqr=w}h*!58OMVx!@Ui3NB=WviNk>zpgkAjn({hdm(UWy$Z6ufY!bWoIk zAi|}C8$_#*wlZ+!EX<2sp?t>rJROxpw;4@dX3jXkqUcF?ml~r{lZj7O@rKT^qO{{1 z{u^Jf(N=e*ZQE#frPH^mPpXMQ^rQ_zKedR!1LF7hVKL8<8?IogI& z^$CNDvo@oxP`N93;Kk5bc4wxmntW`n(k5milrgw>lknIYFceg+dbtGS@gJ^l-RGl zoRax|a`{04kMC+)ncDMeMxCSTYF1nP^lDB|jqiHi=r77+=2CV2cgkZM#rGHG@%*;z zT2l2FTUblb2$_&8*&s zq$aZjiPJ$1#E6v(I&)AZCkeGtFf0e^`0^8unskW*_Sa8(sC6-;SN=f#*qgw_JZ*xD=u00R+HpzOj6a|SG}clOdu^QU{q0LRQ;6% zQD#Q4i@ybnDYBx_z$gx0kT~z?Qz)Da%_*jVY+KbuRK<)G9-#-YDF>ocWHe5usR!=Q zKgHr;uqY~MfYpQeEb^8oPFXR>qfe5c0HJ(^7fPkqF9gzAHFgwkp0(*RBgDev)LAHJ zC(7)0sd6OP1Wg0k5eLW6@9o7-X-J(^fka5r0k*#a%N?;XjnB(MpF++JBPFf`VQ9Jt z2Q~p2jhmu!^1eBewTFh-^Xn}19mU{{kj0~9=~?hg0da6+4r zGt0{|ZDIehw=2H(%?Eor0b_ITeqNO*5S8miY0jhRu1nQ*$_>)T=8L7S%k<*QjY>2> zmRnqxn@yIRG>?6(4!W+ejW1_mAYG`>ysmWBsjyfaTWD&#u7bx`Jl@w_EQx<#9XMHG z{e5f^& z6T;~_E$NVPPkB`MYUDx*on`u2Clw-HU{BPz@4yRnG9VS9%(|pSRn{id2!>aC5JqU6 zJ#ClMh_Fa(oL-;_M6w6NlOPOhBxZ{|A2R4gT~DZPw&9ah4h0@=3$bEVCo zTzIi)b2+2o=Hr$K-|y`Zf~T5&=4qQ!sxA3?Lr#=i)&_x8-CTCOPg1l{PA@Qfspo25 z2jhSo=f$B@da5qLVT8CO*tGe~)UR`qC>n}g)^!b6PGiCjQfjr9VXG10R8o9>g^YeI zc6Fhf)Ipibhm=7}ajZ{TwJ0J~nW-p89;^z#{b{`S?xEEO4JN})0u}^q;RZg}GhXmF zF>Y$TGYGv8q?$UJT7#v4%f^g9e6c1g`^ym=^(SB`?12!!q)x-*lYVBcPxtN6cSy zhcLA9dbq1*z>q?mg!Zn|2SH{ALu)P0jyRNz{CB}O57dRcCLpiM%BIn-?^Pxy$j>`{ z`oKRBLT55yUKcvC4yr+6xg=|jnUq3om}WI8+TBtY+tPYArF@;xlm2zz9G1Cie2HbY z?cH;YIK4xW<_5=5ZTyGf-lghSw(lG$5v0m7R|<`9Xa{6yvzj5oW~tsz+H=w}xwZmA zh)-!yur#wLH%`O%m#CkU5t6ufrW#q|U-_pu++y_SIex9zJB9C__N>QOtq=%9(*Zm2=I6jBo@@3=BTz@JGNOQJ^*d=<7nDxEUxS zqEMm?TQhGg#_dS*u8)M>=>m@z!;%D9!jlO41ZjX_6uXA6Nig*3F+%ZR59-v&A$kNW z5ClmQQN}qS+`*S43F}(L6D%CEBF6B69p6*}Z0t%l@*S)%4z_Lq6Yf06(GMdF#a+@P zU4r0>MT9-L^jWyurx8Z8PkGBEnvfofgR6$Ym7#2}OTl#|aM~n5MjjD$Xe3}mtRH1T zmh=J=>V_E_1i1`Ag>sbUvC^Sg=aqoJ+0E#^qu;>=aAEwxsOQ+dK!Bp=loGhlo1ldg zoPNIq3`2rpfcLe3!59y$5Z%qd2Pu#1fziNTnqhLL_#rijcOV)b?bP(*2}L~iW;mrF zAOlR60gv(Ok0BxrA`ivFS|D8cE-3j887-X1ob=iwJW-Yze~rqQz}ph%BEWHwg7}b< z97KvyMoy_ADuyB|1d=U>5WU_Nmnuvo^#)isg>hg-AyWYFZ6l%iMAw00c2t@~b}wl2 zgSqZTC0@eGVqC@E>Lq-Fl0U(V;8jYM+Vs{Y2hh2ay|+ztHKfg3B71`y%fa#-(=OE> ziqs8FAlCx(U{G8}bFyVyOlPdbCzk<}At}Oj81%KIeg_mry(oMx{Qf+= z6qqc|G|}2LfxS7v@dr69kW64yu{tn>zn@SCNagpO%Bc4Zrar*k6+7HKLzWc4Kboq` zCH8WJ{CYP=wBIidNX@MRbeXBdfFb5P*ZkWoX&8#co9O&G(L9(mDNh#bTfFFYBz%*0cktn3Ovc@1Edpo`NyIx) z{=0AxMbsg98B8SWLIB3kUlPctumDGoD#AyFx^@X^e^S54CLZz(gxP6!+gDcLMz*w4ntk4Gv1P1sMkwiCc)ysgaxfFqgl(EP8fBnG(u6 z%B7E=FTK|A!07(}zFrowclvZ7m!BZv^Xc?AAiTI9&>esv4vr^chmchON8(_dxs~Xa zCu1g+fP+9rbfxLj6>a#X#z9z7_>wZ;i{$zXT$3D`MOcIiS(6UQaHa`x1ao;WLW#X| z8drQsF|Z!Ou}ttw!!?V#xJ!*QixTGY#e}i3{vX=z`YXzI;rsv4GcW_^(CyHTbV$w6 z-6bWVfD)1lh|0hKLk|*CA|NVK(hbrjUD7Rrgp>-3^2~Kz_l|q-``+vMK5Ko~I)9u$ z;GFY#9iMk^zMo4OxPzdj5x5_c2B2ZH*1&QW>FTv|bLP@`$yBWuFYZUcj5+moZ)b{17QW?W_>Vl4F|^09{65Lg=3Nwq?EqV*|PESdKBfVK*rG z`i(5_SSGn|MV$>WdzcNs9IrszRBdLFwloCk`982ZPr7IJT70+AS_fdTflKDS4f|XI zS0D_H772ZkpPF1K4_9zvvCLdz&bbDsy!OJ4^!BVx#} z1drEJR;F;Qm92fQP!y7)r;ZR^t5xEv&?Bg)n5?E>1L<9_nI8mdeco~s5bEpI-CnIz zb4lT@ycbR(^?5!piAmNORBh)`14Y9G!>DD)YPdbBQh!R04p8e_Rq7BmtD*_S!)l#4 ziHXt8B5RfT%?;$q&t3^t@px24c}Uvu(g%b0@W}y_}DVnSYT`j>8q|@6^wuHzFttr|)Xm+#fF|k!5YO3I1YWP5rf!Xa< z1u4xl8l*N*pa5jx+LVq6IrXY;i&nbJIc|G=Y`bjd=WuUqz4qAYFuAKdKV1e@GpXgrJIk+ms&D7cCDY`^^_< z^GorPf-qlr(0;P9QbDfhf)3;eBEa90TP4WP5pP6Ov_prkiFauc)nHmAFm(MlOy1W) zK?Fz=4;*3ZkhDj1slkbdke=+&;t(v1*mI1C5cHmUvI!qMx7xUMWk_}bN{^=!O6{cD zd7$+nQ3vWML3H2)MQQiYTJOq{Jt#;pjF{+fkRgRBMwdD*eb^vnl&P}L=7hj7YtRlp z*jNhU6dQ)BT}y+%3pKlur7xm8L=Pwd)Jt^voPobf39a1PEMW=6EI^vpM1ARBP$9bPd%*gxZwDJFToHFF)YSAw{vN zB*ku^Yg(1=tBkR@=Q;nR4e6Cs)};1(RF(s2o;U*xBn? z){}_VS54NPj^B5%PCt=cH*{V;?^qWsmlF_WmwO~TwIt`jI|r@WSRLQ+H5--x4N&}M z)AVMoUg9HNl1ClL7Y)KSL<&86gqs?4<~A~n6{Vv ztZ%wg>Hz3!4JE-pK{7;3n4Sm{p7wHVm~7q(q?A^DD?_$_l2mzmn<(|n+pb`B>^jj`O6o7=PV5Gw z^5t@eh7n&4Z%A*qaj(>Vc3I(6WY{+J|Mt-DMCj^@`Np@!HOA0%kaAoY zSN}|Ow*LK#EvHzO=ZoxF9H65h-Mhk%(?2aI_<>-6s~7?vmx8kOM!+2Y2*?O%`65Gn zP(OU5XCUm@i>sbw?Y9BJcSDI^Q|~yH!AFrU>9!@XdE^B?&q24L=_2-Rp7I!kK!&uJsv=0O+aOnoME97c=BAV2!k4OVqbbRIHB zGFyB`W)j^t#4q3N8W`EOJ|fwj)DrQUuSzTXDz&EyEtoHl)T=0NFY(=vE%3AYf~P$D zq(E0Op8E*>Vvka=GPmzeU{i@=y?%T%{H_3t#n9QG%XfInbIsdz{3V|9D9t6mm@4CY za_0R`dD}E2o@vZIe%w0+kFMj>HBm=mA6LMGJDG#?h@?=o$ z56W}XNEXajSkZaV&2pEILUvP38LF^pNNS?)sjp5AmmII8MG^0+eK~az*JLX5uT&s) z>xQeq)=I>+t}sz+<@u=VtZQ*S{CuR%134~Cv8(YzQws<%X{8DXT%SNNe$+E<7O6hn zQ4jBi4v>i17Id_UmNXxAl<##uDd3KO)1QJ+QSCwKMA7n$CU~QZX_PfgHudu_X9~-Q zNzqxJ84*#Z_+WaI-2zA@a_k}-csX&) zVtas_m>xW@4?)X0pX1bwOfjrI-({kz$v;?!7rwO23zD9fAEq`9}&(p(Ujku z!21W~`4s2c&ES^v;_A3<_qfxlLxt~q`G_^YzKiJ=|4|h(rGRlQzSe+ABP}-JucmIT zfgc_YT?Ed#y?)r7Ev>4+AMgM6*9qH$x8Sw7AcokW)g-M)XGQTwZNW44BEk5pGtNwt zxygn_$&nfN+a8RUSz&=1G^{?)w#==2Cwj{AC5%o8-{ z(T&Oj1P&C74)7|vH0aX z-_-~GoH!>9(a$|G(D9=PNes70#ZP}ysb{3yJHJkf*HG4zPiGEV6 zTgp{}=eXzRb{uvP66HhsI=TaOKf!xoFd@?3-26xE0$p|#uL(irMF)~y6lAk}R z$-j_^X;TLiFFC3UHJNOs3L%v?i}b{@-qnfGAnPBvYKxzb623Hj$#Jx;cO`;9Q<+$v zt8B-ZDlXGJeI^-ZxLpC^*h~Sm^&ao z;4mQ(xw#asSZ@O^c@w#B*~Gkn!GB+?A<^OYDVd+|K)#?2*|NE>V3$9Z)<7t}j%nnXdFxN)xt>$ZnQn7iEa3(( zhF-F-jdsQtCB6zKxxm1Gj-)|42Ex)7w*lJCFz4F;+y{Rmn_z|yq4 zV9=9J#*KTuopV*`Zay*BYZ`~2W}skwLgrL)oU!x+m0lCjFs6Q0gtvFK@Ve)%H{Hmd z$^3bZDL0_faI>{#&L1R-0+6HY)GoZI#;-2eyr-);7vpXvlZD&!e{p?JI@?YQHN9;_ zqu#C*EM4kBj&7k1QdpbKEYhyS>GBr36FO;nZ5_v$;0T!ptu-Zc;0f+i;q)W~QX;z4 zh?_I7Y6ng&PwA^wpbJM#dUfrjov^Z>WlEg z4c5kIbnjbOD`l8Dd3I|x1obm55IKk;ZBhebMGR}`Dj{h@M=`;(6Sn#6r(Bc$7zm+m zI5q^K^=gPe#}{xTwkQV2oEDOq?&!Jw;7va|kD#{)Qq(qElF{Ch?wwKnIS*zl6ZeKD}r^v?Aq9;tCyQ~p6>`g!O3t)|O!aXT5qkkX8lUuFry1r47X!n`;%?0za|^4;NI>fFhy%y9Q9}HxCFT2MW!oCO0A0 z4QsAIAanZ(LW-4!RG(7C#~+oj5pa|HJCjbwm94BH+W_?U5*$Sf1?gg}Ta(KC4>rNE zcW=Wg$USpUCCML#Bj;lY)Fs+$5n|!|od*OY=mv$Npck~}O9+@%L-frznt0zRElXaBqs5 zVA1?79So|(+ZnNL?TI@NDCkSU%61&|R&baD> zUvn_kq1YtRbS@7rP2!pwrKPay$|efphG9$~O9n-E)8Z6QJG!`oVkhdnqSQf52t zOF8Q3<8v(b0xVkEk6G`<1(9Cc>klK;P6xeCVjb}3RKtM>QUi+IY&7FQuY&^yoI|c9 zZ(=`X^k#X!_VI`*!Rq8fU*F%vvNovYm+~b{Ve`}nJ*s$L1%O%k2VOyo8ruhAD|jOd z2XnhsaT$YU`ur~gux>Uw6??n|E#OKiJ?{|SvQ(^_>ib$nzBfbKjhp;Mir|Kt_fbu{ zF~;v(yI+;$>9pdD+w%iaXYV^(US)RcI-2Ph52D|O4uud7#uW7ocounf54~!Nt;(T8 zx4$3O=WU{mccOu|li1V?Iqrn6Y7S?HEPR7<76Je>H{j>lhWuI6yZJ=NYG#9;eY5r?nWT zyETqqzGH|SXG}Apzn(0{1kW!T&+Q-2o;6`_9cLn$K+sKa@Jw(@PjG2W01q^ug2xiA zwX%U!G$SfI<0+4U>AQ@UEPmSk+Y`O+be51lp|8*vE-|7o2zUv)EJSD4CN_z4pX{)m ze1BM<7c{wppp%})%5!4L6U-7b%$^sSEpj}WX`f8QjVRY*k^5kcUo{_5Q%68kuH#gT zYJ%EBh*8KCuHQ664sIU`SwoZil*Xtofu)A0uF12SmVrGKr!52Vt?g;+wCU?Fr)_Gd zZF{Eerl;+DO0_>u-yoS;l?R*E7CPQ~#$iINOpwY~$$mOF6~3BU9%Si4!gl7HCbr%o z@X``$Q|k3KPvfWA-JU#+4YQbjX7L_^Vjs5NcZ8RXfaX?A37v_I`AuNAc@6y z@ZVym^?xH@|NDB=zmTuppWpU>e%-q`{qz_4`pbL$_}gyN-@Vt#(SP?|cL(kfW z-n9=stA9M*c=EOOKYOpPrN2!#EsnP>{PDETkGFju?f;kcrp1xQowm&XujH$U#7=I{ImK(hhrXvh5xN|3P(SD zTz$**?*mSF_2nCI|E}*nZ=V1!{Bzge^KO8Lm!I3;Vy8}ji=F-fzhZOMBQq8LD|VX1 z{ZH`gy8TTn8)tKC$G=LaI@fQ#R1*Jt>GYcc!zp$uLtam{W(l^Ym4!* z)9O13kU%Tx2($XwNNrCm)N7Z&)|+hWL&)hLEY#so#F|RSm)_UEU3nLF^_z1BMOj~T z^`Nw!^kLSFIZ?s@owXso`T(5DOg+s^T&v-hr8C}hJgl#zqQ3M$ z%gQTN6Jxi$qks5aWQeCZZrZ-J?blDQ@nuzybVuz^l;;w;kI5f)#aZ@1t#R_L+pm+< z3fML&RCi!Cb|`XJZbuZy_51W!2Z%{1uO31ISRV1eD&jPKDH2eCj8^0y6Nd?OKC_Tm zrp`xZ?L5uVIAz78KZ2qxlM`Sf-!}|;*lIRojWq>$3=fv7*ilncK_+oJx2%ote^~O% z(VSZISL55o zv{JL0>f|*pG4~9e?%dXV+^Id5bw5h*a}imfoH3U2NHaN^a5y+FRJ-FcYeFEE z{d7wtfxS=#ZB5Sm# zLOK)lr-jD7ydDRQ`IIR;O&yw>ZYZ?wl!$uwawm^z{lqsDf6!1+$_+>K6?#0bO+-2()&wOI%={%lyC$NgAe;>3DJ ztas~&iK;Nw=2xAlM>NtpxAK|Bv8intrwcyK7L__5Wr(XaB1qG|=KuJ8nf86a7f-&d z#jHzk`2N-87RreVBd1ooEK#MOB&mKfEtckSN5jhIbbmE3x-Cuk)>hS-M*X9c3f1U_ z7GI6rP_-K4=u%ZK)aq&Yv1$oJfUjqMq|r|AMRfM`WC1P9h>5gy}SfL z^FU{Hz)HER$IS-`e}bR z@3o^CF!pKpN@N|yyX(JT{?OkmQ?C6;IhkE^T?$xJ z;=bYCJ+K>2D3Vh|7|ds6O&E%&oI=w!ff=J%(C&sKi<;>LJXNx0-t3cr^=#vX_%cie`nEDmX|&iC=m z&d-}kS0uPBO_H-eN%Ok&vp~LN((@S~?lszTx?_YNtD%@bc(~wU@h#%HC1j^lg3(l= zM$a2olaLU=LKt#*i?|A?C9FDECxz)+ZJW_^PpH>_YJf|6S} zn)b8EVS_HZ@Y5USpWCX09W+@mZWkuCkE+E{UBf+kh~$#q$!=*Nz1WT8he-*tDm9~g zLfGYyKnQi*Q>wf^(#uS!CljhR^ju+y};hZnE*12e0N|kIn2o z8`*!QbR;hm?0PKJ3f@j~36I?vI=iIF1rOXSFC=fa{zhLInW)XuneAj3{)}+WUCz}G zFgI7NL+9(RBs691kyuJa9q3HtXd8yIwSX1XufDQhis?G zi|&svo2Q7uOqdGpqO^oxy&fv~D|VV)xK6VH_j?=tQ2EnlL4WuETkMpHsT;9s@Fis7 z=knP|ecSipFOPoyTmexvw3GctX~~7Jf{hwF8AcAjo2&-Yp0$g-@`+=V3caf87~Xr{ z?u$Mn03NMI0N(9;gm$6As+X%o2!t<%B|e8bhV7Tks)SnN2&qF6!6*77N)Ypwgnn?- zShVtKgE#>oa<^AEr-M9a_oCA*FNmeXH=)?}*Jo{8!ilFx&>Xo9dR%+Qz{)Vj78lM0 z_>xL`QbLf2P7t{U^oX=Ej^*Yel_Ou|`{r`M6{!lobP?A#Tub!{2>&!r`%OeO?8#z+ zJ-;5HE|9v6bFEmX594pv$sPF~A+_=48_mV4uWdEPI>JfV_hRF2I8n=0t}Tk&Q38l@ zvdX?q(okdUgx8Al_$X$YI2fc>Lm?pe)`2G=npo&s65uWtL7OxdYK%(+EVWl$>WQLR zzdANl^iX6mFdJTq;mW9aB-M|I<&EoYw8R!6n9^RVTgu6voC0egz|F1ygn;0zFsPlX z6!d_&654oQEZ&E_=}3Mnk37VO!>oe>?L*${$I;^hjyIfT0CYzKm8eH#s4J%(K`1VO3PibuP|TLR zUGIqXPKB;Ga=jdf1Wq!r;~u0&1NPDW?0L*LWW#>l7pAHX&kUmQ35sd=qd))_^c~TX zM^XrFU}=pNv(4XP348yQL9zi#z6O2eL(wD0_DC#hVvV4q2+pes47g*oi&&Lz!Gp2z zK2$6Of1ytfn4Z<6& zf6{)7e;g8mymH-)5>y4o`I7$v!}$h8=&b>P{z&XC%EmEF01CW~Z?qbdlU~a61Xuy3 zKDba0;*UY_E?@GAv&4Gf>I}fJS7O|dsn9TaDfT8q4L^-^qaxr`nT=XYB)cbmHJ2vT@i3CsZC)I#oG739Hr z6z5`OpL-!Y1Vlfz>B0y6hWvwxI>_tg>E&@myhqVwN6)zN?-VhBFsbfWZOR!_5J?!! z$dbCC(X}|`29q_d+*t7YimW`B=gQkD)8dTLVTuoZ$!z`>(o4TnD+m$SEPJIPO+K>lZGzJ#JD3aSrLzva$^Qgo!$r~Lhe}rLG z#-G(2XRe$;=iV@zTS9(_i@oo7#qETB5<-!B4M?{EGK$|w%)fbV10+!A5B`unK7t_q zp_)x_0t9J81+3n&9PCs+4?wsP>g0r4_@T^^)%ktS31jIky70}M2Jp&``VVHBUp;R^tynpxuwh!W+TCE!c+ zOty4cEyk*nNFfhiO$SwBA7Iw=bfzKjjIdW{aM`$G9s1u43K#>0+~Bb-#6kn2bR zzoK?K54J4`Z$OZmVjhX06C?AK@inn=aoe6eCRg8LqK|^Rf6%!p@<3bmJqo^tKDh-6-3l*^2hiW~@09}qELZ`RZQnvS!$@zj>VV-y1& z$@ByS%yIB7W(a6iP0%b)tujg(tb#ntCqbnVO(d=16H`8ntB3?zr$*xjHoC!_3}ebO z;Mw(950?oc7gLa?Gqjl}ROQlHa0~yoW8BPgR4*UUVwDCz(}v4}9*nLQ?sSn6Vr%Va zA-t6^<7~BxP6+-YwptL7Q9(unC!r9(Yvt7Lo!<^WBKs;t3-tstaS(QH(g!8*g*+H= zsHSFfrwmP97NY`XYPqi7%+LZqi&MMj3pMO$ZjzwsDXJov%Ct!B!_}A{x z50cZ2fpX5&V#dO%kd?&IO(^2_VuA5W1!5wh7}_rPhRcnTs1Rl{1^Vs#jIYCjoCN>} z1zPuZ>UqZ((io_z9PNZw*Y~dc(Y$y1+$RJvzw(U$vx z{o&L|ABERGybW8@(V)yxYw9cusHkF_V-D?4ygl{yK)>hK8|3UQe~Uk6(phobnik2!JEzXK&Kb}KyTvJES(dP zc%_3R|7aGxdau)gcRzgNyd@Nw5v91170FDMph$G;!>|liWOfs z;-jwI><=Y3{p?%e0q6Z!3C)?jXl%s*^_JNW%lvf6vv{%{tjYH)$ctcdR{ zF`S6gy-URak63^uv5EP^@g$MCCl6;v%4Y8EYPe{BfKJ6pl+tq9e_7o3|olnf?lz*ZM3 zCDC5l4TCq}nmhPbPGNIrzZPZMK@RF;(3??)URQ`7@u@EWM0qf(qh;2I17t@8$NP)l zf6d-`rs2XkMAtoVmb`}GT0D5TN+sS)DNe{UviMC2vd^Xw%J+d1lgJ&fE-_Zzr3Cc+ znrx_e5AOiUw{7qnHX2Ly(cT=Z2j1zY&O!**VH_LO97M2#)o;(%jm+b9^idrpQ@SXU z6`CagO{%H9q5XSuzJh@HXj6e50$)}Ki=afkX^t)7EZ$1=Zg2vNDipwl_5|u5QF0$xw>S?LmHQ}PxLq6jykB{9^1t#e`?R&7fUX_4FU;OkSeZ% zR+o`2^VBLMsID_;Q`;{4^1c@vruDukYnB%HvJ+|;v7 zZR&COXk?U4dR zwvUemjMRn?P|Ubfy|?O*-_l)M`APsfihituBc=JsuFCLEJ&Ed^KZ(#$j4fAQ}#Ik+#pbK2K`>ITV7Xnbk zU6tS!nwC$;474o|pQ~5B^>Af8WZ%3{mHMSlO!Vv$L9u&G)5h|R1w&NvdTYOH>p}i6 zPk4t|&3Cr$e5AMf=f~>ry=lztR8wD{8c1ED0F^`(z?bA#BQcEwuh$ zvD0ym6m+T7AL~t<+W6QhZwtzJPUjEug<&#FLh2Aw^~7)MBe?%uZ@N>Fk5uL*gOO*M z@0g|wkd@zzl~gw`wjg`d6;NU$%~&6sRvq%*$hzv*3uT(wp*@>AFM(@x;OTw4CRd|j z&Y~|fFN@?z{YqJ^eR{Pb@Uc_!@9B1U@>RWe`lfWfFKwr|_3Kc?t&wLUg06e=9CYJ} z{$(WQHnnpFP^)*AFy^|;4tO<;>`vU=w}V`E645ob#fp{Joe865>4TmEk$umeb`zAH z`&Wx6(j@8GH(U4@4T`q(g#J8Bav69|7W+^<^Zxrmy%4i>zJx}1(^U>Ge zuBx1P3kV~LBu%f@5HSSY=0(#wiFM*K;9wERRek=B{n9QmK}~OTg&Lgaj+Z*k-SI