From 05551f8c644e33f4a5594a0fb7224245aef15fdf Mon Sep 17 00:00:00 2001 From: jontje Date: Wed, 28 Nov 2018 15:40:33 +0100 Subject: [PATCH 01/19] Added a section for usage hints --- README.md | 41 ++++- docs/images/egm_sketch.png | Bin 0 -> 322505 bytes docs/images/egm_sketch.svg | 337 ------------------------------------- 3 files changed, 37 insertions(+), 341 deletions(-) create mode 100644 docs/images/egm_sketch.png delete mode 100644 docs/images/egm_sketch.svg diff --git a/README.md b/README.md index 28a5c96..2d0808b 100644 --- a/README.md +++ b/README.md @@ -14,13 +14,14 @@ RobotWare `6.07` introduced major changes in the EGM communication protocol, and A C++ library for interfacing with ABB robot controllers supporting *Externally Guided Motion* (EGM). See the *Application manual - Controller software IRC5* for a detailed description of what EGM is and how to use it. -See [abb_librws](https://github.com/ros-industrial/abb_librws) for a companion library that interfaces with *Robot Web Services* (RWS). +* See [abb_librws](https://github.com/ros-industrial/abb_librws) for a companion library that interfaces with *Robot Web Services* (RWS). +* See [StateMachine Add-In](https://robotapps.robotstudio.com/#/viewApp/7fa7065f-457f-47ce-98d7-c04882e703ee) for an optional *RobotWare Add-In* that can be useful when installing systems on an ABB robot controller. ### Sketch -The following is a conceptual sketch of how this EGM library can be viewed, in relation to an ABB robot controller as well as the RWS companion library mentioned above. +The following is a conceptual sketch of how this EGM library can be viewed, in relation to an ABB robot controller as well as the RWS companion library mentioned above. The optional *StateMachine Add-In* is related to the robot controller's RAPID program and system configurations. -![EGM sketch](docs/images/egm_sketch.svg) +![EGM sketch](docs/images/egm_sketch.png) ### Requirements @@ -41,11 +42,43 @@ This library is intended to be used with the UDP variant of EGM, and it supports ### Recommendations -* This library has been verified to work with RobotWare `6.06.01`. Other version are expected to work, but this cannot be guaranteed at the moment. +* This library has been verified to work with RobotWare `6.06.01`. Other versions are expected to work, but this cannot be guaranteed at the moment. * It is a good idea to perform RobotStudio simulations before working with a real robot. * It is prudent to familiarize oneself with general safety regulations (e.g. described in ABB manuals). * Consider cyber security aspects, before connecting robot controllers to networks. +## Usage Hints + +This library is generic and can be used together with any RAPID program, which is using the RAPID *EGMRunJoint* and/or *EGMRunPose* instructions, and system configurations. The library's primary classes are: + +* [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID *EGMAct* instructions. When an *EGMServer* instance receives an EGM message from the robot controller, then the message is passed on to an EGM interface instance (see below). The interface provides the reply message, containing the new references, which the server then sends back to the robot controller. +* [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the *EGMServer* class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. +* [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from *AbstractEGMInterface*, encapsulates an *EGMServer* instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. +* [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by a user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. +* [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. + +The optional *StateMachine Add-In* can be used in combination with any of the classes above. + +### [Optional] StateMachine Add-In + +The purpose of the RobotWare Add-In is to *ease the setup* of ABB robot controllers. It is made for both *real physical controllers* and *virtual controllers* simulated in RobotStudio. If the Add-In is selected during a RobotWare system installation, then the Add-In will load several RAPID modules and system configurations based on the system specifications (e.g. number of robots and present options). + +Retrieve the Add-In via RobotStudio by: + +1. Go to the *Add-Ins* tab in RobotStudio. +2. Search for *StateMachine Add-In* in the *RobotApps* window. +3. Select the Add-In and retrieve the Add-In by pressing the *Add* button. +4. Verify that the Add-In was added to the list *Installed Packages*. +5. The Add-In should appear as an option during the installation of a RobotWare system. + +See the Add-In's [user manual](https://robotapps.blob.core.windows.net/appreferences/docs/2093c0e8-d469-4188-bdd2-ca42e27cba5cUserManual.pdf) for more details, as well as install instructions for RobotWare systems. + +#### Notes + +If the EGM option is selected during system installation, then the Add-In will load RAPID code for using *EGMRunJoint* and *EGMRunPose* RAPID instructions. System configurations will also be loaded, and it is important to update the robot controller's EGM configurations. Especially the *Remote Address* and *Remote Port Number* configurations, under the *Transmission Protocol* topic, are vital to edit so that the robot controller will send EGM messages to the correct external destination. The configurations can be found in RobotStudio -> Controller tab -> Configuration -> Communication -> Transmission Protocol -> Edit each *ROB_X* instances. There will be one instance for each robot in the system. + +The RWS companion library contain a class specifically designed to interact with the Add-In. For example, to control the RAPID program by starting/stopping EGM communication sessions. + ## Acknowledgements The **core development** has been supported by the European Union's Horizon 2020 project [SYMBIO-TIC](http://www.symbio-tic.eu/). diff --git a/docs/images/egm_sketch.png b/docs/images/egm_sketch.png new file mode 100644 index 0000000000000000000000000000000000000000..7bedad702ec05af6c375b2383681df85b14dace1 GIT binary patch literal 322505 zcmd43d05if8#eAV%{0}NEmO`^%CxAJr7f1Z;Y?PhrdC##3s_oemXwN!h)kPKIcaXW z%b2OTl9?I`VvD(prGhI|DyS$V2m}bc2d$Z=ao+d)&+oc^pX-`yV*7B;bDrnE@8>=T zZyvU{TC`x*0yQzWbpV6NA% zcE75rl|(O`I{giJJpa#<QVGni{yqUn+PVliVqX<%c?yRNr7I*Y%W=eh7g5PVCsPSE_esFjcJ zt=M{S%d(%>-rWD&FORaX@6)-vJofva;^*(2dJ2)4AE)N!JLb0L4T;FuDgu<}MD~>S zI#?k6`in=a2_c~}r9?IMzpt94+9f~EJggkZPJ~sC-axv4#I=Ka7-=xE+LJL3oYoMK!fHqHzE#EvUz*P7~F)y>5*_sd~2N$B6(7aR7hs z0a)u6cy%9%^p%?X7LV_~SG}mFb~`MIu4yLG&{8`}to!W0DzpdRi^R9R_E7{B5Y+_%4?p)O~QLFez55krtCmsOP^!xtG zSJQ8+;Yrwd3&~(yOaFAN_H1rwT8F;u3DfyXZJYC_fvM4L4ak8#KDn9!&D&Wy^Hd*Q zQ#)82L)sUsVZ+j1uBMiyZt1RiT1~CK`>{_u2PQTNAWX+}Nt}ia-@k!$X^xtE{OM0o zNnU6`y7U2|CW0$DI4sA78S-qtZm8izhM2^*kmo8lC{v=B58iT((evM5T)%?2&S~bs z@eGQj1rhdqHNzeDIM4>B?{>L%1#3t(g87#2s_zGJvo{?#4Diazq*D|^UYNMb0V)~9 zDG79GCYp~19%@39Xja3l-^}n{q)w<=-*>ScCfrM&@5}+^hqh5!XVY>jlWp# z5TAI2_00-!XEjTA)qT~}tg67=cEDUYC19Nex0Ap8nAzkL=&Y;zKlwK?$0VfAp=n3=wO07-zQ~s{Wjxy!$ z323_4v6}he<>i5wx8G}O{Q7yqe4K6i&~lwa4xzd=9c;v4TkeuHjm z>Wb{JA*ZmjbGe0g;{Fx)kQn%-r{CzNUAl_Ca_s!nhY8luN)Ys#zk<$A3uxV5vB`$a zHs}3RVyd@$mN|{uC_v7Iblzw;OGI1_K!oHZ=f& zNKEyv{;L4?7gr`hFk>YIbc=7ZZO(5VQO4&09-aQX?=fw z_dx=Z-yrnuLV0EBUj5IC>0@l%sMI|Je>Bn^kG_9xYmltr4u15kGT?|+S@mOs?gVt4bQdgz<4*Q4iY zgRf24Ft~S_|34P0vwbQKKXo51`9ajYlbV!x8jRwH@EX+^z$jKu1K#?j?^{vT0fW3h zzndkztFBD#BA{=hm#(-3syOwFJ1kIzw_^Pq#uUp)%vrpE`0skSeF)?v&JFfUa^lgi zni36+3|^|K{kZh6WLxp__G&Ng{tqPZw#2JBDCi81m^ZeRjaeuLbS)$e9eIvJaQR^i zz4Ib#fL%yKcF5*UvZ>cL$8)1wTFXjD_v2R2fSGU|-q0tO^v4c^2cfDYCQAY2?)X$K zKZa_+f-{LrmtGnxsS65XKR+;&)X%BH^XDAyY?NP+LjmFxWSJSUk5YBEl%)vC5x4xUuMy2txZV`hxZny+i4(8qy_^vaY?GWAR zJoGTf4XkE*!%j&4SZ&nmdR9$s*gU*Owc4@Ojko*VV}&{PH(GKo^yI?P^EejbzJN$!j~4*09R0VG=!sg5@sKKN z0ioKt(7}2Km|2uKb)8d!x`h%|!y zD(gtH73+yw)5~^Vjqed{P9qgAc=G<)!j>D~s{N+*iRs;I5-5whCh8yvuKNa)CxTy9 zrMAkP2%ERcZtw4B6#OOw+X|`dxLdO&XN(?_!qP0nb><(>(O)a|S;%vG-v);S^ljZ2%4EH;B5J)9d|d}sB+avW0jg($RD2y^4Hy7t!n}VPuZYaTF~rtz!NVv z^DZUL5N^SdgeK&lBOCT@w7B%9rk()z)^hf0hsqmGT_~Gw`(S&lB5$}6%KiFPq4a>FZ!G6Wj>BslG2idagx6fWw0?68rC#OXT7B1ERoI7?Mpqu^l4bw5z{i|_A}Bo>)-i( z8IVzTFwDwjX9-q%$J3$ZG0n)Ke1%k9%WSwKcd@3)u|g-Am`4cJvh!)?uBQ@KF7%>2 zN;*Tn?P`5=CvGUg=~kU_0_*6x>YqUH`0e%O&08a({hMay%4OZw z(Xuxec5HPiA9lCdTtrughfdT!4x3BEvno+<3$3OR?e?YOf)%%E6eQ4!Wm_0o zXb-`z-(FN9izgW+Y{@x^U*{wYNUzY-@){Z(d4E=}$hR-9IxGq+JK8zoQ5rB_81jmF zqB&A#*WkqwADK~g+6}%i!79PtCNCgeSfgL7{X*ULQ50``2$jByPQfgOF4wg`#5+03 zv7fJk?tBiBxMst7dw0?lzo|AP8(}lpk((CEp%q1d$odcdE?^vcy>G9igM=20PA-++ zs1*)-m4!VIUj#7gp81P%6pyj9bx)Q(?ks!c-H>;e%ud7L8>Dojn}bA3#^xMKK10{D zF0LHij3B%Al7+2dXXVbkF(d3F)WBpH&av8M1G55w&*M&nc*1K33U3jAXi793H84yp9ee-wxk%vu zrsm2*{U^UfUAvq7_#s?gIE+x9X4T4bRtcA8x>hT79Wu5!8Mliq6qZrpYvQDIqnRRd zAx{0i-QaQPwBWt1ruL`TU;J?r5&V30vw6f-l?YCB^|ubGyEme_Sf$wx1o-LCE0He$ zafo*Wq+n1rf>|B-qh5!V;OlvdyF84Z^;#66r1iP?`IGGqI4+TWDE=S^jum!JI{dT% zfs0{@-rYb^_Qq~<%()+@zo`nqLc-*HbN!K0jM#6v_UjO=Z}G9SWXYbO!TP0`^i7iZ z3Izzpds{3TIExIRy7JDIKjXkIP|IQ{X#E_wENre(w}qK#~_0O!Pi7nZOADNP!E zCKZ;NqPX$vmy8;qr7QjN+DxXkzK4EdqLYPEV1a=7tyqKVyUd#N)#q831j<=E;Q3QF znTI7{>-Hkt@6QmFp^?*d*76@~L$s|WVHJM;qgaEDg3HeuhHL}x=Z%EqIN-w?v=fhs zG>{Bi9|j36dbi)35|p729gh>y&m75(-a1|i$Z~n@SO^buqI|NE@pM2BG)*ZMhMsM!@a;Bsw&BciGh};t$4fC-N_u#D3hOl((3NgQ76iI?(PqVlD3_`&ij3% z3O0{B1Q1tU*I8jBP4jQul-UqY#)wl?+`DJF``*}CG3`@STt1xpWse z|4EuF?HqxrWBtHE0!JFc@x#G$4q3#nIFFA-?ryPUCx(>|lKaLe=FYEi?_S(wDD0vw zDN>Y?k<7M>vpu`yFg{jj)Hu}G-d}h2V}~e>#e;62HFTE>%FJ6ISUHn_wXN4iusjT& z*n4=JU*D4$%KCNFX-#gmRZaCmZ+T0H_G@TuL+0aXdBhL4BA1L_oQd6i`Cl|MQstHR zm_iPoX4$q-r9uvfrxeO3NTgk$0QU+LgS6r^wRxTK z`mp=*AxhcNZlQDDSV(WIw(VG5YV3;)&t*P-^d_nBD-&WH0n`iZP|86Lirbf$&v_eGC(^crJIDg=|MdJWFBuxp!uFU?{y9u6#PF^1)bs zmQR6c<;^{|!KCW>uc{>&ZU)(Q$nA`Das-fg9~o1TXM11BX9BUdz4L}VCtzz3`5@CT z|A{>ovpE+Qtn1dyULZ6vTAwDJRA0YRrlEUxEOSj&^#|A~9~=+kJKv3TX;fJHERRlI zkPFS01W?U$g`37pJ?a)aYEalGQgY=tLeB#!Q0qF@TVc?T@LtxcmAZV0v!!7uc}J0l zDC7_jTv-W?#T6?AkE5qt3KMznW0B!HX|EBb@nn0Kvl*?yd4Y0~QEI40HZjk(In{_j zqR3meyoU14!gclly~ZG%$Y07qK<&S`FyI<#Z<$pyd_`3#bFRICbxiiyLboL zagi$NHi{A*tglp147boYxwnMU?lWW?!6eTt|8cbWUDSv7Z_nT~x5h4Jh@U*ty>~ys zTEK~Ss~cZG64G3EGljTYqt!%MdhZ$?Unf|8y}*2=7XR;(dCwf&5ImxHlz zlPReB*02Oegn+it)F^vEFHj8`f%gY=>BckwEEQYTjNq{LNRO z+4^MKxNl2#Sp*efBTY~{E=mfhZ|Bv_oG_b6A`!Hm!4~BY_AOD>UQA7+)fwY=mE+28--x?8g2+E^0M*p6-(%1EAbA7SMl;j~}Y`C|)ZG8@=6Zcx@O zHML(5@8duQW{a6X>Rx_20JZ{1n80cFa+0dwZ&daI~l zSuk_Ctxxs&&drV~ZBUGuy9+rVfjjbA`MBL)k7j!h-??LLB)xCMATp79cT#05R49Qf zceKzzzDgLu;;RG#&II{F5FBf0^#sHLOnuZ zbFMM97yGy<)?rt^hEK7BZ)2}j2Q^(GJ)M6pqdM+xyM^54jt_R2px=n&pmO}BxzRl% zaA<>5Ay|#2Tm*FK1C3f&N?R3tt+h1-L2j=rCX~X>6K)CjLR|`{&CP<6RNS~Pe5XNW zX!8n?E{r$2i>6~zqt;X65kaKB5fmY?1^v;c>!yWKXO$~qKI7)xBgqu$XaT649pq=S zMe^fyu@qV^+NAgXm^|fm(y?&bDFzepq#{ROM`jb?s1a9|jXmVEHvk=&W0(nYqO+r0 z+EQ1-r}&|zBe@!~CYv#+PFd8osfsAx8nfWGhJ>+WP>x%4TPRS7&(oeP5F(rrY|)bA z4;-@kMi2#f4qmuLM5lb?Lyuqt*xtweS=t4MAWJCKx8WtQ6`am`G2QGKuVtuUudI`F zKRVAgSk@(!4%t9g^bjgw*GFeGu1TVLOQb%YjmI%ufpvy8Mk&u+OA7nxYv7KroErKN5YsFymj2DF8$DofDVr z8Yc*A70%$vasaYC6Y*I0dLe@%3V!;HMi+MSVr3x32a>)q7MJdtjkDYF*xu_8hhW+7 zv1T0H+zXBO_$3_3)lQG8F6L6UUqa z9H)ErlMfu`$%>T0`>i1=o3Qg_12E?ius}(@L%=kN&-;tSe=+J0i~~!%^YpXp)qP9X zsxm=nqHedXgDO<-OyC)H=pI9`gUJ0>7OAvU!x+GHjU$Nsg>qr(-p%Rq&DJ(rh%CkP zQ#hO0HaMOHB<)}+p<0@M^Gpw}>F!n*#{(pWjo5cI)|k?UAr?88u5p#`>!K+)_!mJ#Wu_RAQO6u#Rc9m~}h`WDH9>O6< zJ8`B}>TgqB9?`o%x~gU~`GckV%zAzOAoRNneNQgm=6c>)2-NAz!>}DkVraRzV0*zC zIp~0zz;KrNKpYbfa$4%PSHUQ*4Y^|>aWBWDPa=+t!3&+Fr;1P_y~hl0mI;R-WGx5p z(K}v3u?dj#kM($gf$H4KRv9&iBD+9?oQB-INx+JYC)Amu?~05;_Z;f0X%>756f}^z z=NqJU%zZte0ycmAHnYxC+(`|F{MO-WoKoReWL1e4ug*7s=K@}r?LyvMIt*t3Q|3W( zD%lzEpRCm}l@&yO4b2RZ&_Nx^fv|Q4)H&_uy*$xs3U;HUfBD5<9h2C*v+VcZD>Yp+ z7z^gV%S6yN_u9^wOM~?>hDONwE$QO;Wumb0(?3^5n_vIIITuBF-IiyBuNMP;IWk7T z9VT=s6P#c%)Er@^wT{=-{4ThvTJ|zsn!ww9AB6!B1SUXO!b4g8`qzi=6QRxVBDAW} zb=$i+_fYaZ?1k7pIJ=|S9OK~ke{Q;+ElW^B1BdVAwG!ZZ32uah^LvElZJ5*>qnLCD zfP7V2vdi6@19)Pu2i2kJIfi#diAtKyt{w6wS=T5VwDE(b2>>tFjeCqv`(&l!0+sfd zwzXcm>NiK~L&9s+)Xe|da#7n1nUf0KVdAN!w!D*{jJfTJsgZl{d9Hg48p79o=jgmX zV*4=-5e9_i47sb+D;iKkp0@4XE@2*MUQC23rt%wMv|fuzy4bTU2wNF^nw}e}!BF`B zGCJub%{xN|FT(erO;AJqgogs)H~&hpxsTn@VRM|38_G8b?Ar@kpU4}fz>oOx9M&e* zR-d?`XxcvAhroiyoDZ6{rmBqC0eA)`TF_)bDNNX0RN(-7Tc{dV0e;1L8Z$I)*ap^z z$Oi$81GCBz)u8`xk|1!n-a33KIjC2Nl4HK2yW+{Bul9Mf_Kg}@wMrzCcOvb*e z@_C9|!goW7@E~b{IYt!BiNtko&nAiq%Wd$-3r-|gUaz2hC&U{eGAdxp*yKMwCsIrS zI*%sBZkS~FFvKaFRcuY3cJHH`8p;?WrKg{NE5G1v?!%S)#)?AHLga^sy&|WHRD+*a z+z|;n?_Fob-743r_?4Byg$XT6>TMK&?0Qj99}G$Kj#p)0HxIOclaBUe)R`^EXJ{Hf zdIr`l+~9*V$MUoZZyVQ^;j@ZhOVDz5ptict-?nzs7(Pb&b*nb}<5(^8H44olA3gE%x z3?X%C()iFu7Xy;;o{P|40lIi^Y)Q0YYb_rNj4F%J5AT63pAU~^WlCesCY|;S5w~S; zN8n@GzCbkEV;iQ|z6}(blimK3YP$S5O7JeMT?o3zifA_iym-(t6M+8y2N|l}yj?i~ zlD1hgzH#lt1E?J{vj5Pa|F7OAF%NOdFa$8%=XoFP@#-zVn4=#<`?%#{tF(DDInwT6 zA)kz;M6t&WK$qf8eq5$J|F$*V6gAehH05Ai$f?{-b_bOzPvw{a=dp%?a_!#b=Q0(K z6m2hD+9~!=fbIjf()d83Rn+MR(QEK$$d{zS%9Q(CC$W#tHmyXE&0e>KSw>g*kmESa z>i7@@1bvQbE_OA}7>O&myXBP1{{I0_ID!90kot(j^+93FKI_3q&y`JMig zH*9?oyrC z3gF6l$;CV-LiHe1d^J`H1?Hkj#A6TvEWtp&EkP8cq%CgbdZZd5V9toR!D#`kA-gZk zglhAwfw(W9T-tyGV(y`*|3QBQt{c%VJp(o)7_su*jh1zpJLsnjhbDpJ_nHm1Jtm5+ zWcR)9#Y({nk?%7?(>7AcoDrllDmq~EI5RP1AAB6uTW;2X$6h0z2}Wii;c2N z8lj*oO955tXsTC*s|>D!SsY4WgVjqT2cH%jB+s?!CI%f2g2c2I+>qAWj7g96)P;F$ zJ~Eb-72F!;m_ki8q8`)T%gJj7(9*L|Vby|M@}alnE@a$D&qT6>i& zuy+Uh@n=4s4RKdHUcEet=om9Rws@W~XoItM0x@^Ye#07QXjdLx-ErRHH5<7o(B7*i zQvvPJZL!sBWcQa|f!m70dm+$$TJKwe8*ttD} zMQ^%&Tm%9!gZug#to@1VmSDyif6q8U{fb?RVMAZx@7bs=AaSQRa*~=__OE^Az3wg8 z91J4c0j#nx6LvV72J^BL;bBD2IfwQLrI~F;Wt&->Tl92mR9hW`%-HF9^Mk4! zciIi+3pdg9TG}mYll-Ok5wS2^__QGBj?0FY3z)^<+Kpgog0HPNcg4absvnhk?Ul=19at$ zHw)r70Kq!SAY)qSx+HlSv?F&4efjROu`J8|K(01|#fI9Cb(O3S4Be3ErRx@*-m7v& zR9@he1GrfVi3>cbv8;wx=}Vz^MDfHeS>F!0Hxw(Kyf#l= z%h>O%sXhx73}A3Ys8yZ}@>fWuLaE zq*PH}%?2Co7_gBpTqJk_jsXB@zj`1pQa=7k#{-+MVTdvdhUM>^dqQa+{^8GyIwRcXv8u=^m$Jx5G&9 z%!uZ~*$>Y|h5tWm$R_gy^CnXRjT4)FYYe+goi2#kJzrIQku z`Hz4B>rK^n?Jxdz$F!sHB`f8xnd2L%YdKBF|M*~i=bx$rWk$2;TF}rwyFMRFT)%hb zAj>~Sm$mJG;=eDGq05-3QjzP!Yk-6V*SCj~ z|DR3DKjt%dzQ$joK1;OEFTT=Aii?@87M?c!|Fe2j$?!+{|K?MCkqqu^(sED?(SH|1 z0&niQzc&WH2=l5W*V)h!I(N6v>kR>=>+Uj2wtZyLe@1)MyM72hOSDJTuXGaQPEYgD zKar&1tEM4~+52u;He8xr@lth6i~@FrVsOIeAJ0|&;})9c#Hote%UzXu1-3G82tQ79~v;IY@G$q_-h}| zuON&!X)g8u`{IAq8Z95Es+{jHnH1y-SHQdgcJk7|<+|It{%qWJ)j!kH`ch|;nc}GZ z?Z9UG{PJN`4%yF=O@J$Oig3>`bYIzc2MmVPgo~e}w-sUU^Q{etdo<%!a#Y-bq6;*zf!7%3u|_a1CcCgV$1B5^BrX zolj#n>))_8(QX+CRqU6c$`7y6LO?!HD$8~&gNIjJ+`+YfT+^8kldh4FP3vY^vH#Cw zd~B94Ri#N^b&dgQ-{j_nk=43!Ba8tN(yVy(%*;k*Hl`+~& z@?jxb7o-pK@7mtXoZpQ3c%tX;MB^JG`bqV(*O4^`B4(64wEX+sAl3(rE&thibwcJ8 z1k6;=r6$n%-tCZ0##9*x?%8<_1;g_0c-wA<@hfJ z;h(;~elTPFeO_jR316vU&MLUc`~HCR$aT<;xYnb*3tvkmAaA!rV3|9`-)voc8>bwg9M z8#nBZX$YrvvqfzCW#~U#HM1qgaYJkVU|1FmnrYsUJbcG&QB72898*r{N+N8GoxMz{4SP2Z$1 znMA(!A=oLeyvvhSh$J;}b1=$IvSN}`nK)RKsxe!t z%(S@N!Bj0Rh2`JU^lIMOeuh?ZE+>uEoij1+M`+=@%0FP1jZ_|2lF5d0s^bdHpg5hHOH7QUJ2Tt z4I=?z!j9pK2ogK8Ot=*;|Imh*YCX6n!fe`~Ig-e^KUS&R&pB#Q9P#BCjOWsZ?GLae z{PFSRh0QI=CkIST2DgLHg`~pG%aFadVxBT`(a z4oqfTU5{RKMm5QTETcr`8X7bWmXhLDSD6@1dGGvR#8V!!f%|(iOoLoP7>F-Ptm=6%omZ+e3!c zx?JP*Zu4i%|0nx2qUQK2htFbsFZNhW=3bOkER>8Smg`r&?7L!ZSREj^y)zutDW@v2 z43X-Ehy}n;ZzPZ^C(usKxvonoi3h~R>Isso3FqjpM)lF*Q{g_hDb)0-Vwo8`rcAgE zH<>%0XGC-JdKL#qBj1BejDy^e7*P#1BKBS5SZ`?>;y*&dLpsl2!mfrfD$$v<(@q>W z3=s6Q#iq^5_ohYG%v~t=Wt}MR7irq#i>i9ml}HTLqHH(hN9oHSBo){g05orXR ziAj-X6$TS{7a6209CS=|n`hFR$n+372c$b9E-;D3Kr1I zy%JaLeX&STP$i*Z(;ZU6#E(RcGNEoYX3gHZh_tk+jm-lKJvf!dmOSZU&R9STa>J`P z(o)fBC2|WRBxZKB7-i+cdrZ6@5&L5|R#^(djmq^Y)mWb6xLldR;Q3tg`W;A3pX$rZ zw%qC-sbbeFjK|5wR>u~N!a%Cn&&}v{Xp>ecy-^rC@Q3L2?eTu9*9>5hG$i>}5m5e( za~2Lbwm>rjl|JMP*)7{j@$1TQUF(#Q8Ld2Rm^^C62-EZeBBdn3LR31e-0tr(sliTl z!)?I(J5HLMy5JPdpw4(QRtParcVb4m|XhMvTL++8Fwk2Xq*U*U*YbCYxb`gF)thMVg8?W<$E=8C+5zVDQb4P$@3 zpfKGIvTQ5XdyxA*_%OYJ7gkB;D<*G0xvre*oa$&_4To$NXmd)z{!O)TF2nTB)Nl)B zs)&~Cl`2^K))=0{=n9k8R3r7 z=>locDuuwPg@QhZ5i>ExUu(i0g0vciVy@W8qOa$Pfg8~e3DGc?xDPr|Hd-8LId#Op z+ST~tNw$Y|HQJ$rG9~>}k}@x=otlBBneI&CT@~| z2eO=$EAg<1R4gb8aBJKt8I0_qYBlIzb|cz5|94}ybVzJ|(J%kS6v~x$5phv5(Pk9( zGib%9;40*SxS=_+qNd{QUVhI4VAPX$suo{Yp`?fsb56ktXCcroQ(EpfW|&!Q#8mQt zzB;kH`)A2mZTBWxf?#q2=M6XC#la^I86Aq$*%q6<8{?`f5Vrh9|>@ zR=KKkhKf>G&L$E-_dde4B7?T@;R(f9%y16k8LsZ^$jfh0exN(BvaAj*HO5)8%LYs7 zLBahG1*v`uMTt{(b!9Z@X@jHX&VWK7Z>BgJ6|GQun(lnDSr7W4L&-Td;7`cp5Ic`m z(Gq#iU~Fa(Q%M^A*DP7YrEujZxG(p{!>s~9F2mRCc_bo*GtdOFn8?_Myk z@b_NUexbZlRkw`GP_LV5PZa`ZfpUU&i(`3K@g}-SY71p^FPKlz+~tFVU#F??OWi=n zjQwh?_Nk!Q2ViwAdb8x}aRt&@)j&voXNjTR8U8nj&Iwb{ohYnEaoi0OvVG1hG(XeS zzNO;LUss3Z6R*7^m+lb0r1d*Qx20K~|CwJxSgNrqqal-omG3iVX1{?YPE5JO#E9ulz2DCt5sa%>TR z1I!*&Kj)1&dG9R!-6*r+J-dn9!2Rf_k9B?`PpZxaQtmJLya6RM@7e293eNMVLz zj-7gB4|*Lwlx3D5IWw2ajG68wVMeq*XQPtOltRz}RKt zpwaI{gYye=%kjZ$T^uM;UxQ^sTPqqYHdjUE38RxZuz3{f2mXYHtH&hss?7GP_RKOSklC_MM;8vBI~d|GcWqxA!=Vf{ya7tNp?#{C z8A;7J#5D^U1*CRpI%2u`sF{3YK^_(Ul z-haO=Iq@oIt*)*E=*V8`-g%pmtH(uBtJ)+dn=OQOr||oVl{s~0oRXE+pwork;v3t( zYdZPXB-y+F@t+gO9clk++(^s2iu6Fqk22l{v$APM%5{5|@?RR2?S`f@t^v`nxe6@# zktF!e^}*G)P|3YMVI~V?bY70_MATUGjdK*aiikl+sigEaKrSGu>n}gw%0+9KK+;u6 zpo66wS`SL8r^evXWq{G*qVKsD-!)=#iS{q=O)XL)d^@u;IH%h=UTGD6&hE1>-F;+L z7G`Y&t>?qoVa_9O|E2{^d`aq6)Zq=3a|eRzv>B`VGC@orH;AtDTFrXX*f;yqJL$5oJsgCA%(|My@ z&2C|4t8lOcKSC#BJIdvqs->e}Z1+$I4pIpdxT9F;N`X)5p~$3O3-s!T=QtZw#g7T= zzYw5lJ6McxEcWK1pOUr0i{rAt^ddUf%qc+YK5wByjj9o`p#ELaW$Y+h3MjF-IFuep zpp?>nQ{pa z(QUpMyN|oL@#^smQ+?XSA3<14QtA+k2Zc7sT zs~ul_1stu7X+oJJ{9<49nQj#GE-F7L>uHs2D@$AuajF24qf$U8TbvLJ8QT-42H-xI z%!$ZT52FXyPd%w`s0#@bTx9)lYpAuomQyMyW>MuoEqu4Tdj8Gfi#3Yu5OWosX6;Ta z=xeD!7b8kGT8ub$(i`$ar^LnEXE#}&73r<+Z>S&Y4fEv21@o3zOhhY8^(TNW0}U4p znO;R5(#HE|VPD-T8VljSVycUb1s71CDhf~TO50zHZxZktTdPbg#CQq()%`>KTxu`-oFh6wspm4AXy!?~<5IaPY+DFg8}%RxAwxO2Wg0 z5>SNE%6_-J^j+v<0R|syz@NNX<_FtzPo>(@NLG>xif^&+%|0Zej+x_B`z;s^I~@$; zbFVy9cNgHU-hKTy%UT(oZPyW(#{r-$3VN&>8x&SOuT^VXJ=U5q)8HYe~{=)lD%ZIgGwXH*(cNW3(+RJPQ0@KKf*+` zB6&Hz_c*7s=vI>15hSL`fNT;R@u5gJFjzM{EiLrWpo_?pjhQextPF|${t8<90-VI8 zTiV;}OFFur;+rT_t)qhNz@b|#ikV9Ji5n&p2CMcbBJc($liirN=;U3|Mi^{7b#{M~ zIF-o!iDVfnK>~jU0(yAqt2R7LUl|)0r@mLwc4aKo05tNPsSPRo=(q z-n3^3j!+2#gO=8+U_n~6j{*Z%7sa^R}fLd>4OEI zZMw{CcE>bPDII-ltvykPR~9}-6dP782lInU1$D}jv8WMtEBN;Ahk9M?u>je7Rbd7~ zk>$p?W!(}a$5qxLz(@Op4TK7WHw&rpdSMU8*&X6iO}tr zTWDZxVRS42hGY-`1K;nq1VeKq&vsq@dOe+;(`zOxTM6D_4;AsPnYRf+$zzo$`Bnwz z{))SU0~A!*?C!+!9KsrDoGlO=J{B^BNXHuKx9G|ccS)q@cZJVQx2u50LTv9hf^>gg ztQw4i#Q!0+n=KVj;~`WU0ES@-NtmiHHiK}cLh%)SrEp)B%@4syVi&QNX*9Wsb6nq2 z?44b#!^Y;-rT&L|yc5?0TrzzJzhzaZ-)pD5zblkREd(Ih)gthxf93mK;k%F>Sf8oR z$u2a4WNIz80 zPeXlSvX7?MaL-#{UND?F;>Gd?Z9W32#oQq3+q6{RM5`PC_B=EwAQGebdw9(p`Xb## z8{6XOU2{+Ps&a5*NfHK{@4`L-)<0OjmA^s(MfKCC({s>c9TRo(BzAX@e&de zB*?!HwoGp!?kZi?s=3hgdsaoOkh#gH!eyLuV6t@)m~}mSJ{9@1)|>*Qc}aLpAGBe~ z$$l03Fp&gy=pSXRl*do0;yk0dvO_L?5q0}BE~v~cltm&ZLo7}{=_`HxEu9+rrAA+2 z>F)bz+WqyHND`&I_{Ywcx?z`2PUD^xE+d0i%c%)>LlSfwmL%mmn9Ze4Ps!2i8=St9 zZ(2aDGgJyF--#q$*YykI0Mdp&9`eGkCUMEiIMr0Y#FdXn9GY+vO@*nprDc%_$xToA z2=zy}>3z4#at!iR6}B^9EJ_aXC{;}n_r~#KeK&lpZ>^N;cc#jRGUOr-uw+z{LJ2`E zf{BZh-xB}twfzFrc9N-f(Fu&AQKY~*RM1{xEsJWF-ymKOO@j~z$S}%FTiZ0`F*CuZ2FZE+p8eU@YNf- z*miZhTmZI9+{7u48_%^`nN#kqeK<%en37~9ay%AYIZgmJURr43V5vr(hS_>lf0f4# zwuz6MnJs^US=Bf@*UWD}@jX`l4m5`qcyt3}Ltbmq+J}AV%VNI2a-4ZtC0VnGD1TeR z*BsQhgw^(ns@!j6Y1m@i45DUPRD{<&5*%rW9%}@Uzts;9(1E7vM;hvE^bKIkxJX{q ziVV*EvV_69u=nEsu!m8jBVhk+knj0jGud(7yR{FUQLZY=_0CAFT71&deFZ(v$Mzke zRYmv1Oakb=;@IHLTTsyaU;qH2hXmJisW1C8t=&dN8h|pv$eU+7VFEVt zj&K%RnayPp9oMl4g_yb;%sCAYl4Yc_{;76s&kO#ee7 zyU^GFv8J`70R_>?rY8)ags}v)+o=CKonkjm={eDiNFSg$zV@r=p)V@a_q`ZePFAWm zMFDbr9jj|bzXB#h6TVnACqM>(zj}H$#8ko)dI0pLGaLT;4I86MH+l*gEQt8GD&0>BI`N*( zH=txmK}g#+TpxtU<$qQ5IOi&z47bR8D%^>$@N-vf_!_CKLe=&CpZRMaTJ=z;47#0B z7P}^ek%Msgw*E#wJS;+K-_Ulr0PBWfD$6Tq;a(B;ltT(YhmboU!&ms)xwwi$9w}lT zFnYa4Z_jYq>s&K-RtB66k4;BSu#6$?W`^_EN{X63F=@2LAtTkfjr*6w-p#v4C-dN( z=~Bx@J~x{MQ~&1l&+6XoBjoV>v{JqwJ|Tb5vh|g;y>3Om#VUWO>%;u*_t-=I z6wM(Hs=R`W;Ds?d#J=e&<(#NtaJTPcts*D3G}Ph5HnT)>`sBhR(yR18T&LAQ{O{i1 zjWIoaF9x3*p0ovj)@ob-W`EwkgWgA9w5CJt#I~?x_Srg$i!f_9iiTg%30Z`0kUUYu zs00H}Z2J`Ih37C46fFeWuOZ4ZLl;iAE2oieTf!A5B4kKDU%rylBx9p#kfxy~BP;du z9EGTuT_9_Uxa%x;WC-g$VIFCxfugj)n87`LY+yT4rn#R^T!-^-^-DCVQdQW}T zUEr-f65D(~Wbx$k@BpsMS$deJ%UCs*m^L-sT(owZc*-Wc=DeGQKvDwvU_Se-U*5JL zt7Z*^1)96>rKNir_erq8%t4u?OX$W;vNP*?3BvnCZPZlNab}g-q};JIS}d~*#HM>} zq&8_nW^~HM%YW;XXGh|7{p+3{O*e3DXG~N)RUrA)^dlwAh{dc?J(-I?cFS1_L4LrO zaiEHLfg85`whTjO{t7WohaCu=21toaUj03O_sdebJn6#we_ zyKNM_m;M3~WI0h={A8~XNZ;l-0PNz_TM;#*Fbl!IY~W7QD_ebeawm*$5ypSmSEG^A zDVYSo7m&NJnNq;j)Ij)6h}DOlQ@%E|;kONp(?edHz133sb&B<=O|<3tD1V+fb#g>% zQg_(zax}F+dM=;~{e-)&s=3obq^Wg%19!ad7%<0p5YU0|+IcAMdas3FMyHd=A(-}4 zK?2qF*zQv+3OehS4KakMw%jBTm`cGF=Q^(+SU^}QFWccAvCy2;%}lT7#Q?5&KPL+I zx2EJUD;Ryf7TpIh8J8eV4>Hn1lh6RyjiX;^>aB9M5TH5X=>OVqCqGy1zg?3|8Ur0N z9>kG3Mkoef)1+QKR7EP;`lz16Tv-G^MGiDjqB-NR{P!X7_elEld2W6UMY_j$gAAV0 zNV^ajm1!1Znz8wBRpy9z&ok;i;KVgwT=G()?lXCX+0o` zq6m2v0}9n-b>o?rB64vp1GKu(+PiNCOn9;1S}<*+sFT^)U{@=L>H$Q{W$u`a)?gJT zcWd^@05}B@^juh-8}MnW)hW1(*En9#FD=fQpU4gJ1^VD8%u_=3?>Y8|dU6%%_AL>( zdEW7Zcl!p)s`qWS@-rV_E7L5svtmv{ml;}2r!+@0mo$2wkv_W z_MH7&x^T3fZ=(wagcyMVuBnt6B{Rha$~7k&nuZoSRR9;1PGMc{4g06Ic2ArN^`0R>OZftOndcMD$jHqwUX48a>i}dDE5;%Gf*o3Wq<0TYcVtA)1v?Z}a{dJSpctlh$N1! zn0&6xNl+(u9IM(blBOm6T+GDX0KW17ioklcQBiZsyRK0_nUAx z^!-Ez%zL<1TR9W5P@$C#RcSr3s<@bvRL9zOcid$wc-Fqn)jp@5cQInFZeMx?wDiM? zjn3gCq0Fjg;tf=fR(+n|s~ygScZ|yB2giI=jVpTE(~jx%p1V`)X>%+6-^vfrIr9g- zeF$0K8He!ty_r=#6}+t;2Tl%+!^6SVcq>+0l(>0eC_C(G2UtC(+`-X7qQ0xZx^heKPV-^@bOIA)_g{~rm z36k`wOZG>NKX&0$y%9}oK9U3wEm1W5tRbS+yX0vNMLQc78u)@_&Ii*4r-dm#j`X-; zEb;_*{mfXjd;(35xttAmL9^HQXtQyvmeDkQAe6LI_o;d&SCX`GDU_(nhYPV2b*7yG zD>|owhS`rmO4rqD&M8tX`OVBUU*2e9@_#@qR0OF);*uZ-xiS+FW+B+k>8t*&m8d&W z5yRo1eCpXHk%mqiwl9m|$+cIMQrPfuaCFfHXsK%D)9eLZyy@$UlZn1ASbYFmirl3C zjF_#N$RO2jV*Vo@dl0YYu8z?i^DA1XyJ?7nDhrT19QEE?m=E`hb)<&qabgd^W<&(> zuiS4xeg45c<0@3^2uf6#nm@#3Wz>jU(dBFIKTLhmoB==z9_PiMbT1yRfSy=e3~qj= zr^A=a->YgJJ>ux9LH5a_xX|<0`w1&Xt}lj)jcZZWWfiYeQfi;4nA~OXD{Vgu)$GA^!>41s z4Ss4@q3E>p6N~y!NuS$dMR7f_55KS@5N_ zA#p5>O2zq7Dn7DGHY&z2!QA=TzqBhh@B?-Z1lF4KQ}2{T zC}%c`lrWN#a@EhU&Te@COa}G_Xc34$Uwsgm2EW5>o0>=cFecWiPiwNx4C;@qJG$An z{k!p&jY`{HuIsdXS5X3S>mmz&3T|Wn6xv94e-uoPxWRYNOd?0?_-{R( zBKSF8bDOWP02k~@U66T5xI)@yuGv8Eb$q3{f*dhiHKIcZ-NhqOp>3rEQmK8Fq97)z zg-G&{jaEB$dj|7v8tUNFMVYLka0;zYDv>#xvkb{h)19zhcx+@Ha@_E>swHhq80PXy zSuhqP65@@pB-|wv2=ydp$%GY~^l=F|-vt8Hb*V%TmJ4Vp!xTSpb`?O^vDpMp;EqeG zJ&GM0(70NREb4G%viEc;x)9npR;F&7Kqne92I z7ltaFpk)mB;UdB-*ILsZljnFj*b_qKf=W)D^ckJqQcZ|-5e)GL+lLT+70_?g9L$rS5JxrP5gz4IIyhQ3N7lUZl)y>uFly_W!U zPd+h|>@^h?{{Rk_&aamDdHdwXLlc=7C3|h7h0sf4an=rNRf#aGi#+C9eMtRoETgpk zY>QRJ`B(KsU3U7tRzkdo^4ZnlHEO;m?pwuO_YSSGfI~R*UU@X3>KGO4TNLJZv46jV zHXTTC#wL0T^%pAOfmcwo@Ao&Bw&dfA=>rCV(suD!l|7`j znPQmL0Oag%CIgUU4tr66Lc4gCG#_ruQ}@MDp$0F>=r1Gf+`UJ8c|XV({q~;>-3XK<#`rT>$Dkqr8)M#nJ@9- z5c~r<<>OQG3AvFEvh(#Y@{i2P(k1ZfFx z+L`*4#r>diEY}AgwZtil$}2kk5i9#Ur*AMri%A`j^`BrTl#?FyQtx87zdC<%?L;dS+! z+nsQ5-Tnur%VfZ_Jb+*pjg@%GYey`Ta56*f_y;1pBsr-!CuieY&&H+XeuMv(FLUL5 zw{F-h)RM1mIeeINu7ztG0@Ay5xV0{qWkKG%W^UKrq$pLLxeg3eUW@1gBAw51*>YlY zj{nlV&1Qr#EoF5YKZ=eBVO18J-37gQte(_T)~L}S_$$$}NQt)2Ayq#1F73{|^e!B4 z9Gc%4hU=EoXmA{@(CYyb;>c{9L2BhxM&kwmKotcQ5zeqGEZuoV=y~Ro3oyY=!{Fk; z>qk71a$5!V2E5FCgp-h&Rq95ulY>#`nB`Kv+^5~Kk8_wUPV(ZU6jcxdC@gl)5TXBl zGj`x4893@mUas9ZVNn{tyG}G~XM?27K2DK4 z{KSM*Y7dvEGKqGHZ=fqeSq~E5a8Hs6sW7V`_%i63cMec!B-_kJ7TYVsj;SM-byYDUNJ zl&70wDN8}DlF{iEXP=as&bQ5z`It)if-cIeV{gSvaDRYI34nuKf>gNt7#Y2}+oeZ# z+wx)(8JJsb0m3LfYZzONp15naX&q_C91bt6RG@!2&19o|uM)(0fUR&K_(9dlCDaPe zT!V9|^98lxD~#(6)^K7l^p8MPEeeBY8*rlbT75>>Lvc?ceiC+&a>(*b?SvWMv3WD; zT%Pt?Rk}Vyuv{(h#BELhkzx(kvra3JW4YDHED%`UDR5H(D5I;{b^zQ(jYw|`z+&1) zDVh+=k8hhm*O9BMrL0h9R-VxEQ=>}Du`DN0KCJSB%5rOREc@W4RSe-iryxq>rkzXE zhiy&v$GUFAXENBh8)h!De;B(RzM{I=Z)rq#dt9Pi@*-Y9e;LbpQ2J(u$XO?Mwd0;L z`ZqybTDp7t&MT`ef3!;f4L|mO^77GKT{cl?BuexZ zGSIr~y)dHIC)su6di=nnw8TJ^bh=~vjrJk1d^K{a4S+*Hv=!Je(^mj+ zkgmEg)Lw~V^@|q;fZ}-&$@*nk3^a&>e~z`u-*4^-Ky&-UL@$_FdD!5T672EXVMW0f z6FTHGR>BUQ^LN@81#r%rKYARW@!6|V{{6#k_?Y$R4cE5d6fduSjvgqG^xzqjmE)*d z{|fLs`A{tCadxdL$q-RO-PD9q?rK1CclCO`ni!=b8^aTORlRP@_cZfA z35EbzPDChk{se()iah|7wM=V0uROZf=eT84Slmc~531#mx!&j7Q_~>ZT@|-k_TkU;*YH|*IM{DW>$sP2U z3>2Eesupgt55#S?s2HJ(mHnp~LGVxF-Ikrgscw4B?Xe1w9aw=+-gdsALw0&P)(K76 z_(oHFu}yy=jFOTpFF?m437{@MCQhRS^9dxKXB}C7v7nfx6^2M>wL>YSwFP0dqrU_> z75nbr))j>29686;@3GA}fICzBwam4Nb(0WzAK4x5^0mL^HQpCAq;5;5uoXxhe(LRH z9lqk)3D``?(dYPS01|}_!_yJ32j~q~Y@ATj-@IYr;AW7I3f0Lp*)(@1ih#@WdbOu z74V$}Kd1o^lg5_?@YC-WbTuIf)P}KXO@QSjI{#xF)Y5OoTbTiK2_( zh8&N=L^NA6n3tf7qNt6}n~nN2ug~_3OdPycK`gM5P7mr}2hVl~e{PJ+#v~+wD3mZz zg-o9Z4aH>4bJAEv_Utwrhnw*o#^NkqsimA@}d z0r!^xvEseO;T|_wV*0Vj%zt$*!Dl5&_tvY!`VEEXO}^k(!13bP{RSA_;L_5vL%xWw+W6vyH;nQ=BA5j7gPzFUfmx;9eVhMQSV?XYf5=mA%PQXdF2(^9W?oc z{&!`6D6*>{)8II)PvJbOCQP2sl$cZ)(7})#NvWNB=`n#P<_yOlr&{WgV6wHG(O=Nh zhb2mo@O|eb!QBW|K&eT2LkKIdKwd|1^p)sArQN{q6?u)>=j=&!5$)6}{aX45mCZSR zb`^v~Rn)%U>HEHAZ#!_Q4*ba6aDwj$YwUw-^W8nDQS+gzN{=Oyqf5ML%NKudSnX|X zD^Ql10f3IKcw)pU@V6cS6u&3kThyH3|Hi=dcL^$--A@G3QOUAb*`d!ujsMHxRJXU7 zJ-53@N)7N8mj1ykSPW?q19=zT?PGh+LB0`0W`Z0lsYf5;s4M1-cNrEON$Hz;m+O*^ zQs=o6E$Q{2F_jXZDMyRLNN5!drY~1^aMHf$s^DqnR0vknS-V|5UlEHi-DDqlalm>! zF~LHzZ7vU}6+IhO@rx~~4-c8ElxIhD|DX}sWL7ouu8?bYE|x_;shEPP`{ekX5X-Z# zO}9Xs<0J@dGZ%$I{`P~)Ekq(I$3Cd0^(7*Z&l%JA>UUut){#?(vH|@KNakU2G#P#F9K7obqx@#C78-{x+_j5;O=tHZ3T1dRNUS$iq1CW0c^y2*=%qP z0f$X*yZ||DT7PrVH6Z-=1`yDBlQd!&aH`X@j-ia&-8U==ql4CrP1xQ;syj@fXC>~29R6C&UBcZ+l~;f( z4)86Hcv5HH<>W|tZPiM^Lj1QVao$9`wwRKh_{RUGRpk$^U|#1)8K?|TT+LC8U!C-r zX<|XXu#fpcV?eyAe<`mK%L-01ggq@^{SO#*!d-YhSr0{A|BEe`He$|g{^u}CPlK8X zL~$aFkRT*x#UQ98YSMFcwncR!6% zKNkN}s|~%m-wT%eyIMjD&zd=ZA1|TZ6?#60s+60;q%_L47s2;A9>C?uZ&$$X(Y+Gf zwP6VQ07pD4K5g;={i8#b-Q1cjj<7Z2cf4X)d7S?=B3N22UnISTwaqBq0tH$Zi{87O_J|SJ(1E%G&XBD(W#zX0ws;Jh(W^)4_Uw@?4HeP${ol*feR(dd~7oavs0JM zwGK(9m|63;$0GwNN1LsSNPsws0#Fa2@*h#?ncgAV^Y?in(zgS@0q*Lgw1G!Kzb7Gargry}U=Lge zq{iqLT;n{cVY7MxS1Eio0N89-rnoHE1=o5Bda$#>+5g^TJA;Uv?!F&)PeIA!`f%-ac;Jv5NmTL6m6`7u8&xR!n6>1E6C z>35SuNeip3ke8cQMDE~4-F)Pgg4+NJc$j&5vvu?rAz`5O zygqCQdQ;ECAv0xi1nqB~#qnSH5+#?j-9K371;in)0stS9O`&!1B zBR4apRl#)JW+qno!7)|A)86({fDC2IThEX;oA+)Ii1H=A9$5VanG+GI8Up5xctQ_~ zaxPU3i0Px0tlTiy`3j@$jR0xiA!*A4^gd8W$pF&|BM3ixw^CsJaDCHTeFQW8UOxEe zo-V1XXQVA$`Am%%{4lC(qBRMZn{KH$J^POD_v(NhHxIW9q?m_L+AR-IbJGLyrKh35 zL`SHsJyX#0`zXZsr6lxwVnUTOi83YETU;HfsxJg_5I>O3({|0!A_jb7Yyzg9u>pGT zDR@n_r8&oXb6Va=vvEDU+Bu>-@>SP|^H(pB^tlcts4j#dqP|WU*)V`M?9yVuyM3Sb z>x_j=^8_9=NGvGu<%!7Jo?YPSj0&U#OKa{wy1o{!`sp+IN^day))IOLxJ};H>Og}C z#NGlPv;*Z)F)2;mzz~yN<$Y;}b;?-@9MnL7;X6**rBhORL+>-$+x4TIjp>{;wuaj& zqmD84+dejV73K^N=t*AS6Ydc?j{{u41wCdl{1FO)*_%(^@l1WAmTt?c|<#7T_`$_J^VJ ztL%hWU#hvNR=?C91ZeA1s)Sq;RB=NOVr7Oa85h4XnqoG;(TdDB-d5;JRI-U5NCNZ% z9XBV^DP8siMdIqi|E)^Dd(!m2p{rsyuQPv1g5^|!Q*H&kuL5uW5o4$s#ycnAn#m>Y z715Ek{vf=(LOfkGsjU-j$h6tAhF2URdN8`8CaZG!d+JpSbXOuQ)-pY2B#nnJ_?e~l z^6pWoUq`BYk{k4sX2Wc5ZWAxaOC#pXms#pnUYwfnNU2m{?CzIe^`p6M<>B+7qHuQO zCVoY!ark3zT8aFidcwCH?r*;w^kp(1V)`7|pscQFG9SXJ91_@X_>M9S@@QXWLWZ-n9Xj>X60rf%c8u+V9tp?fHqh<{QSUd0wNn7fZ zo5Pia$(X7AOBq7@z2@;h_*E=dr7O?Q7- z*i}zCaWAMxweUhYI#rw!jl;f!2!p z-RX`;uAeu6GbUBgE3#JnfSB>OfxDK7K(88UxFD=Mo3QQlcqK!-lJkBDUo=MA@smzo zYEL<2FGF3=GywgOSF!x!2w|4U5a?d`J!nrA?gcCc(4Umr0r}+WC78%GqonkZ%ZDnb z3&yA4$cw#KIcU9TQ2_lvY8(k`6d`f_YU47)O9P}iAV0lT<>TC)2N74PX6)i%s=jta zgEu71?LP&mQ+QFa+>LNLWxUbyvsZmMZ0D_{E1MO92~;?T58faOvo-|z((72zF8~h! z9F0l4p$;vM9Qj>;{r`9%PA;6JowJ5Rf$Lm%^LNsHTYOc6ep*v7heMd2r^iWR0YrHS zG*kCLTVpc!V57UxbkXvW4@RIYK0%;E_ov9KJ@2G5Is#Cxiie48A!F$UiHxml+(B@8E}jy; zV@sN#VDcf=ZhDP7v{>m@=nsoA#loc1XHA*NMSKB|enYX7Jcs}(`l1w*18#CyF*<`X z92x-@nGeP$lBbrKO;3jIcKYz5xN4OI-Qcq2^hO3T{NM}hM8H=AhbB?O^ejqowYrWl z#?Pb_U*izC(~Cf2C}?EigPd$QhMC3vD+6TVqUq|Yge7nqgGIGURP#sGuUu13ki>1n zN79UPsYba*Xrg62KDyour)YMqvVjsco>8sF=uab%MewViw{sS9Kj(4GZDHOfUp$3r zqD^YA=UCR8DoJ4#)n0#_3~)mhi3u$5#Ki13WGkoyl!n#T#}jfWs5IareMRE*ziZac zE}VRzA={mbqYip+ORTjTxxzxsMGT$t>c>Fp%WgJ_5kp~dKx9HlX$3l^bVWwUrX;lG z5RQwLX_emKehQzX9&;y zL+jKbmAv9?zrB^0_zU{hnf$et#ZDI;s*tpG2?VEY819AFKdVQuO7%_1kBHo01JS#{ zBp~R4FkcrGr?*!$II*Eyq<#MTXi3)Lf2p35)w_9CqtAkk$ZMm+1KRkrL&Uf#EiKc} zbY3sk8Lo;wdbC>3C^;H;N&YdrIJo+2n!GZLHGwB#bQmlZtYo3-;=7Cd2U5Q zAaNlC26+><^tus0WmYTi4efu4O9(sha8C$DWUfXOW0lj3plLYqXPJk0v}R=}kGeE4UR z$^4z&03!nD)+UPG!1n8o+cH*(4S{l)_qm(FGyqp+n@Cv-{cM#R6JEQxMc86bwKh5c zKsasvjfRpvLKYavkby|BE_^A^p~fZ`2u z2BJTg$|OF%do4ZujeJDDJiu$IFKmUr-&U?k*Kg*Ic^RP+q6K@DQrzz;-$-D!LFtDq zLeUcbknVln9;nSLS|guAN$E<5VfZ43P@$Ym7pPTxtQt(Giem@=mz!e+!r7360`CK* zs`A@Yd%w4eY|x>fOsW@K*aLuAm0lk`q+^Yz3D`_*9+!S&Ss^za|B#9d)ft8`+;!J~ zMAE9^_4ZsqHH~2u*iXqoJNo=rWEWVTXtd!7W*&AkNocWJK}8%@>3 z(H;L;+0L!-|Li3Ym`i`+!AfYV`&Tb9<^qaaM*w-)uP(_T&z&)Q6~ogXjVy8+^M_3V zip8-l0gO(+31*6&*#}oEU+`L>-0;@dLd|7Ps$m@|S(m?{{G{)FLJiWW+5JEto0qfx zMwHB%sjn|&_q-(vRJ3n4RRzgmxl5b)nXuwM&-Mos9JQlnO{&4s3-@BUGF@K*#hR}p zsD{Y(YJl|BRGu`ItQ&@x>BYWYps^Hi+3kJ?I%b1asV*{ygRYw(5utliFCPRd?`#zx zR0WoA`yW?isU07Y5-jdE(KuN(V&{j$@ZD)A1VG#4tM}+|CPR;n0OqPrfH4y~%YxO% z!;?K?&;&J2&UpA#BBnT&`$%9jqx z|8UW@rep&B%#Uk4-&xJNbtCj$FNoWcfwyeU{dUV?20xK2xRqhMmCWy9Ee8X zD^$y?y3{34$=dErFUSgc|p>Gs7-(@)a{Fk+T$#*~tWVWeoPz>&z$q^NS zOxzTZ-l5uVA?25q@oxt)(*yOX`+-A^wV&y|^%p^NA|BL-fc#JB+g%T|3X}TjyvLp^+)9Rv*@AmK?6`dr~V6sus#B8Niuq6OErZHa+kQw@4QU; zzqxnGC&5;>H*0Wna>2Tymh3M^HcwlQeFhAx|HJK7kDR2v@6lspmHa-@JpgpLsFVtZ zD~pRw{-~`>cUM~c&+90rJ9`f9g00l4oTrmla=kgPAHcwf{Cp#8OEPBqB$s5DT$Dj8 z;J4MSgIP$Oe-@i$dRT^-O^a*m(L`B}qw|kS`M|-tV5^SM<-rcHT3w@6Gg-(}g75lm z<^ViZ3_z3gPL_E~_kIF64NptUf$ykrp0));Jq7(j?8y=!yXr!+@XFvPq)S# zSYSb6tbq|%!-nPm04iLZ_Z8p*<~0ZmK-LJ%d`tja>IhyVj<{=x)3f0li#T42q--Es|CIx%M%bYa%kc{+gqJZe2MgZ4f^8mMqE zSwoI1-gD{;1GYzIscWQiCoGD}wc9>!Yjwt6^lZLA7l-q_h!^rHOR;1$)la_S;%^}D zzzW)1|NQosdmsrhn8Cla+J|tSHm9ui1WNzV_c*hPj%~pwsUCC^GV0Zl$>gDQ>19?L& zgu&28+_;u^g&^Tf{R}4i6BTPX^*6A2o5!Z8IA_K?Mfn8o0%ry#-C$UA6bawL)MAM48T4N>7Iuli zT$WICfLZn-E^;@-?y)UD?Ondp(rwcsJ&YZ0P5xse&)I8f6uFgDQ$8;M*q{7~&WAHS zq)^wM@sr;hx(HXbRl`q^U3-da$ew^dN`$F8j8n?#RWaUXRr8$;QnfbIUtTiwjtg-9 z(UE;FmLBV_|FR{(J+me=<~AxlMNbx44rV@5SR*Nah^rkfA9Kl5S!0V)+h;OS%KHS7 z`ZX!KpAK%iVEbk_XN*bvQ7H6}`#coB3X~7wM8Y&?QNMN<@#mY+Ph(jfeq+C{s~t`2 zJUE{WqVT3S@H!0MhN;)1gUtw2+4Uj%FNe14CQZDf+U3`b zI?fT7ue0%1nnHPhk=j|FtrG1?v**f7UcXbP2~Jh9aH;a@H~7v!j+Q#*Ii)@~fqL6! zDNc7z=iztxQkL+ECPMpU!IP(}0kA`9sb^!uws~wnDPM)R$A+6iZFE0M97H@wFpvza-nXbG3)=3W=Ov zh!6oT33Lw+@zl1IYlK&&Ao#ZdOR_y^~qDCT1v>>{6s-Djj$&^fdK{Au zO7@{J@-|#^1Nm@1`lSPru1Nd_P#(a$DQ=#ac7?l^VI6s$fD7b$g1Ch(THQYl$jY5< ze^M90NYCbSQ0A(klYG(?DJRsoaS17{Xbu6(zClnCK}f*arMn*{XPx{UgW`+6h7a-) ze4_M=4s}-|e-sTOBEpe09($VjR3Dy90rq~QT{MU?xztf|lBK-zRowFmanojTYOo@r(lTwvUA0IJu5lKX#1nuMI znG8@3M491E%DDSvRhHS?hhy|-5YBKUm>|B}J(VBP-E%2G z*i8%R6t8Z8Sa$;`3VD~z8nv=o2vnWjy#J%0@h5>bv0V041mXaL|6)N-YgVH%F6V)< zX!$(jauZlVQv&0r8#QZlCjIii>qeN`$)lg_f~NwF9LHX8t5AB_4m9DE(?oT*G7DaDvjyfZy^RPJSDq}MDgq1*3^Vivlv)q zThRt!!94_*`zL#Egrn?GApaNCs6nFWciiJ3#^814kSF10SR6Oor-I~cxpQEznY8%( z^hTkkl-d?HL^P7D(8q1gs+TMy{U5Z!!B*u&#^uK{^>1}ke#FM0bGe<1)0;?UcBJJu z@uJHyJoUBA8~q&yAhyq6vjs^xv+&#=`=CTq8}xKz_zP)SHW_Lk_R{6oLNneBF&}nM znVPWtbNTXa-PM)Zq8!dl73kf;@b+fbE zck+R(?~lf}I~BmhiIL%iL~lk97dUkiLdOwHqh<_SUeORoMRKpLp?tRzb-E=@VQ`MV zJe2P8^lfJxsWN$`HpX!L1iBW~N1Ebre?~V_EF;0?uq!3ik+&$abKd1!fJ_Dt?%7c< zS3~R1oiF@0?LXr!E;Gh+{^q50X?>V%y&aeO{O9uy-~oa7Sdh3IS{pxJUnfTC(3w?F zImzEKee$0w&UJ^1g&`Ay)ub!j;&WSa{$8|t!Sru+WNg&|7m;z#wrzK0eTbC5>+_G< z>{)zY`J-r;eTjQvVJw%YeJjTpJf0ek`#c)oYhZ4gb*tJhxf7KTN?4f-(bXs-ofPEzow zV=9@DJ5l;n-}#{0ZKrcP>T+^3XyXQyG3KK^C%vg%K@)h10Y#zjGEgb)h^L{&qF- zS7zjQ1?7jUI1ZWid+)ZkV2r(c0?D4JJ;vU3SXNSGN;*gH6rS~$?oqb!;*6FW^ zCtvX+mdG28_Sft^)^v|L-gJ+Pm&!Mf+4*fX*$$}P<^J;q50GB`uJ<$Eiiz-@AHQu( z>XtPC-AjTsmQnxuIslnIKCU?UmzU}HSP*}V8|3|WRM26BRH4a-niohE9)BCzX?QjZ zQapf#4?7X1)S6>nmtv}F&4IQ9wO+1GW)&7Zpf{R7%F-?BZJ(el)S&Bo43yZ2oz$;k zJK+o$a6~;z{NjIE;@NNyPiu!Sk6vKyf#?I+T|LgxCLv^0c^YvYqTUUz3{(YiOtqTq z|9uf%x>_0E9lU&Uw7Zk%x~Af#e!rMtGAscPsk>sv6H}`QC7qw2(?tUZZ8_76TfJY~aj;H>5j zFm$=cDZmS%KXW@v(B@cDL8wmc{^>Xn%HJi9`BMO~H~l=E=E!f`--HwE?@u4rF+wa$ z=eYYvl}P;c+$8Wg=VMOWhlUF(xpXN`vyu#r(N7oShS%DyCX*1Il>T|q*PD?%P3%M8DSvU26Js#N< zt$0@4bJkhN$BTaf;TEKSH%))_1?Hjm(m4>RfcnT-GCWIqGwD&(nFlDYW|4vNeCT$F zV#;<9ea7SfF|PXm^;RJKI3KMg>g1j3*Sl^L7T`dIipsVIJdCryw(xa<*hw-@JYXqWGrnhQsiwY$0Xs-`qTUNF!@8cNiX^?j^j#7zH=y1;X!Xk-iwCCRWPx-LoO$U zBGG2DmpK+NU6U}`TF9NwNP-v56oy|o)d7u67D4jiH!epK0gYU@^N>NT~n~1{RHv=$71Po zom0{x-sq*%7-Re|jY&Y35C3^Rn(rl^pafMRUp$^!)L*=c(Mk76wF>7$>}B(_@vC(< zu7%5|;Ash!r6P6HM7jKVYN$+e*xj%$FI_G%Y}duUR-*DdbzgE~E?%w^11a4;!O%*( z4-Dy9Bg=Xc-)LN|^(@lzXTSj4_T>%DT0#sOR4zHKGsV`_KfszRA9scKg{D}Z*_n5n zOxBA}L);EI zUwTZOwCaYL1SRsBS;?umNEb%vX`VwKWL}*Vz6t1s1>sT=y&=`n#+xHl=49IQ zpz9GC$Z{>=;Z&5Cp)J*1Zz=O;_b$4B?Z)4HMv>{Tpg}^kMses~BB9&robx3YPYJ?A zUt3-s{PY`__5j06Q~P6R4Jcdb(xT;W*^a>Bq2u0d;rP$i51Uox6~XBEZq)+KUS5<$ zeKIk5rxWa@R0*pZa(u;Qm|jkyD~B9I3W09LW;J7_9eAyJ2yysIj^2Y>?BzOy?#0TB zmtT>9Cy}KgezyC&%vBT1=o zCA5C}V0dRj8+ahN3-B=_0-rQbEC8ze-EZH9vIgemOU`cJr=N7W@zu-^=*DFu0^s1) ztmhsd6LiO(uQ)qBLR~4f!A;tPCJS0{9a_Vqu!A{!-pppIPg)+|*9Rv-+}Cn`*jY)O zeHWx`LcX|#6ZJm8V(_36k2clD8xCi7lEJ$eBa5jm&gN&`cnZzU6UE^3GZX8(SGYZ=vzL&ju%V{C zM5zv0STd{Dp?@(N7ny1~tpz&xK+ddUyvt86rNQ)X?87 zMB0802qH~lXIzA5ay?_@krnx4UitVsyOPYnZkxTy8-85L3iKB_7G z*Fr*WC(-oXMAVX?>yR&7ysV%&3r1UPY4~b_12RGGeq;SYrjij%iwt#_x$?d4dIH^cr#e1$&X1FJ)$?&arpEBgQSd)$o0J){ib9@l0jarO_G z3Yt~1H>|H?0M_CU@cQ2^sugt8` zohIt5k#KhEgr?dN|Jfa3&uDi5ij3Of&}3$q_Pr}@YW~ePu?l58Hc$HffH<$L-p00d z8&jQVE#_g0KgP{21`dw`Sg-UJ!#No$8P?Y0PaH*s6BfufYYrq=z|GYy^pkSNJ0;Vx()*6w` zYpLEZ^Uw+9^4G9^s08q~2uDcsKZWTK(rN9x8j>LgW!tA%x?SwCY8$9n`4S|3_jMMX zH^^ghP;xXS64>8fw7IFTNy24-YC?Xs9hzEPt9B83fsWIY z=i4>IOuG}q0e%~=p4@0$hnm4@=a_8~UrhG4_VhV)?Sit>WgyP0pD~2ED%rf)|C4Xo z)o%6VLza%wU$#K8l#^`Z%LcJb(!4d0X5#?W9FLr|1u1E(SAs{XYt5jJE(nTHiXj2T z+$sgyLqDTQN}tg(MCunbt%kT)B&FQA*59c`dI^p(IN|G}64>}g@$5GMk}B7xY#uAq zA2P=&HC`?eyuAVM&LxCCd3l)wL=nF|v*TU0!tm5DEt(JKkkMqfMlUA_+l(-*huQy*YzE8QA>CKc2k5f2C{z7jW>zsG! z^^Xrr_{%wlZ&rmd*XbSn6O#E+q(LT@`PsS{6fM$2*Ecg@HkWGqWUdNaXbVunc>#9< zjF4Lq`Eea5Jja%)7e8o*n%hv434#C@!mjJ7$Ja-|TsXpN*DKz%(wO-MPyKAPFiRKB z!^`P)88@O13m=R^W0Zv~59u@--90p3DS%JMp1wEL?sN%J?9(38GZK56X1??Wm8{`+ zVpaF#z0WF0qt%-;pqnCZ7Na^GWFm^LesAwRw@>?*xc)_AuG&nYoH_9k~-y2i?ikR#$vw zL#;SWc{VBwWQ#eOB^8l+<5*5hFG|g-=FJQ|cdG@)9C)8}oa-Y(3uSSbXPCP zg{e0u^!rAtXU79Mz@z}VCE#9kfTRqvr{FY%2{D~%fo~2zUGzn#x66ExH3s;dK)^B^ zWNmo$#9DwF--GjNX|Kl#J(4srkRIsDoD=i6MuV)I=e7*Rt8uIo2OXYR=e>Tzu<4?Hos92^nNExa zmS|`@gVQW;y<|>`6kmrY*?%t2v%VK^iLy09ZIB(2m@lf5%o1KZnavKws_Z%LO>Sk4 zKon1wacA+nLNLGsHm_s@a}NAcG*OwqXV}vN7$~6C#sAX@7J%Zji;9eXUWGFkvKgt2 zKnwp`J-y5Q-=?UJ52~<`7{e|kZh^@ixwLkRDG%pjJ~3kyvbK{ zDhX~OL0m7Uk-&){gy)_!ZK48?*zek7B}m?w?=UzygOmm(8WNyk z9=gkg$EcaX{2Nr!gxd{3K!W}p2*>CB-6G?U?b6)xz6Lj#nxH7IlG8( zfR z!S6Q2QR~9(ljQ>Vjebwu$veUjqMgu&###tKS_S#!f1W5ltuwB4Mq$3`(zx zQ~|R{ESMZWgGYC-IZC1j;l&ufEs!#pbs+F9q;;T9bgHUHon!*`gR>XF^v^O|ml4BC7!~`1qJfPFq{>=j zneiakZQk{L!}lH9IpF%fuhB>+sSV@iGFRgd#xRmqh2^=;&5q9={pvT}`-Z`E#1T1r z$>tEec5O)2A=4HCAZu;)8Yx>Mi5(Bw-q8YH=_AxD$*X`0FHb zXmI)rEI8_+Q=0lABtoPf_{^+I?wB~$;^^3G@|~~T+8sO`>^IunlZKG2l!QfrW{k}} zrMMBBOaVVm?8Re)b6n8iCAO%~aIs|iNTA+RD8u^EQbRc_FPCyHpu87kYBjB?Sw=3D zmN-R0{qHa8kiFcXY(&#p(p+dAn#TTY{v(4L@cTawfb*6K){!RKZsTVgVP&_r+ZjCwof*4J=z^B+!I4YnZ0m5B$|yJ zEtkZKjhKjj@ghjc!Dm4q+3BtJK}>F~_-`!_5*KF=b<;d1xaIxc&REI2wr6G5Z&LA? z$D{mhHLl=zc8IZ_nG1{25*CFxrfB4h*eo!x>?P5*FR1nAv% z0t=3b^1Vk{pz&w~bm->l0CajzudR+)3mWt3Jf)R<<`x}{HhkRRv}_Fj{qfIo8PGRB za!&zCao;P;T(AWD{l)YKJaCQM#L{{qIl}<&EBP=BB&UsTlmi+Ag!qmUoL8trYpBL+ zUJ}FPGw(I1^kqQ}@J8&)z54tkym$!ivy861aedSZE}QhUE-zS-2Wj>|t*ac;?4JiJ zcxMziM%IhqVNn5dpvIbeK_+V$6g&2Wgi=nkdxrhQSqsfuBWSw3-5_Rwm4%JeY`D$fxHYcm3Omx)(O^m;p9B94J$G|*{LY8qHW zh><5TI*95zN6w z8?zP)Xlt<=7Uu&dgOH3^3Z=hK-jr%j49;BgKmaM1X9U-&-D$$n+mXN*-PhroaPJ{!Bl zLTU!x)v`i5$3wep^e*>yCdjL#aVFUrXu%jsZbTZ}3EF&>`mEoA8e_xVu>LTs!Y{)7+Sb5# z@*ke8bsXE3Y7cvUrHnn2zZXe7_NoNvy(X@R_sWqMfU_Fka5od2J~QDpY3XH9?2aZ*8soc$ns;ifQ z%5OWIlZmUy&a|D!B=!((*!72)zzzGG`XkJ!q25ri|OBYG-dNJ#f z{@26LZSmBFkBnu8>|>78Guex_Iv(g|_?)V>Z53z|lUFQ`igueP8ZHA~zguE;ky$JX z_^}lOEWLHPb#7_Esbz6>(Tn($or1bsX?kou_`KT*ifXn{f*(_^6@Ll?Gu-Ep{AiP^ z6If6ImvM7J(<8*8R5Or3Cg`;hS5=InTxeO$L-RnFEhBupNk1`8`G0BttQsDY(@M-# zXl)To>VnT?>hYsvdBkFQzF9pRYxKOxImcYX;W{N?2b^7o&CJ>a4*wT)?xQz)}k#8>YGBkco z^No)Te8U7SE7`adJhF|J6;eYJoI;dOiC7H*p!Kx0FSSc8pdh=%AgJdT*a^kXIMA-e z!)Q;mQ-B4<@i&13|I>}t-ySqruyZWD-gb6OH|v5qwv0dWaM{H_hz^8 zl5T|<1BOz$8%#P(tDb+PTNxVHB^kq}^Q|O?MyLo`0Zzyynk>z0JIn~LQ8qX)?vOF3 zw$(uUPTKK<2OIuuKwI4L69k&v_-+BRe!W;~=(vdO0hfY8s$e+Nv?tF z$`b4#V!A!WTwO%|7Su}XEv@X`9@Z04T@v`iR&jcID0Hrp8jlj_U z6^h~!XsVycqM_Si$W4xvg{?@i8g=-wF^`kRN{eGxPs;A}S&g`=`0zY5^oyJEZJU}? zzlvY9A&S4EP(HnCgCPg0HehKqE!q$d?ql{c1+4NMwBO|b?jkZV`YLFvrL%j{Td>@M zqq#J1ALPd!0{8tEi%$|X)jr3~H%8ztq-WwWfKt9rTDh`)^Xnw2_g89GgiOT?O!BG0 z-ZIeSVct+3HdGBXxj2U{>-tYnv?~byjkC60)e9fBP9DT-+ywsCW zE2h%;UI5D4l<~6MFErDvOvJicc6k8o1<9<>eE`}G`@>{imXoe{M&M7_<@Cvn?|Ox+ z`nqvKBFj1^sX-C!Ki$;762Lxa>c9AiMqN}z{#jP5@)1GtA>LKo$798eRlBiX&WRa> zJ=#q4BPl=jgPb6BXXf^oM~*pxeq3_9M^5F2%2^a`Uamay4am^a;>zq%P53wH3!iaL z?gKJVtSaug0NP_}Yb~Cu(@+<6%bvUstZn)voXo$7%}yKzx0(cK1@d3~Fxb-(R3-uQ zkRs3ZxFtK(exFoUpGBK|+=Jy3*aFxGB-a1w zar@W)A<%YL3L@__F_e1g*U3ijr=(Z@71E?=e2PJ+vt8Lh4c`=zpZ!7wqX!$YDRb2V z-GQ6M9+wXrUTGFf_(uX8X`zZjm%x2}4hA@G%ZzdDgSQG`2J%T4r}pIi(s8yIDW_uW2tNmd08qK9~>z3quHUOL^C zI`Nmh4cn)0s*vek|{tLk3wapI`vlH#w@NKWIeA=J=gmcP3mJ+=_%)h%i!@`cR z2f+o)q(B`$66;<}=pUQVQ(mmgO#MaKdQYk(mW>ZSor(TBJoGV)@{O=KKwPJMw^8h- z8}TI>fv<0&=2?6-Jn|O2DA;mi!UH|8K_Ls^b%t4ef;c~#B$pB9w;6&-eT2t5z<+^s z1}(uup9fNyg%YOKmhWY}Tv}Z=uN}3!0>z#>RwU7F1EHJdRE`PLf?K}|5y|72_E1E( zI#MnSw7LFya1D^umQ;~Gw=mL+kZ-1+h8ge!%n-4YuoDitK-<(ibxdzaf|vatd*qHq z?g7n?JI?TUc^m=aivyRg9WnZ30 z>7CybJ{z^-LS9W?kHw3-ePf$9JZ%3hrsG2V(}SBjRBCeHF1l!stbK6hQ{k0Qt2`ZE zUaAe)a1m+uAaX@hv{btFN&4|T>AVQr?3wbDs`dkT9O|>^c(U7@(uR>@{^v53LDdSf z%rv!O%Kx%BV;mhz4n8eHN@*qYY+Df4a#KRzsQXBF;f_KHi8ncrO4<_J%2)94e$KY{ zwfLi?Aaj<_uLGOjy<{A#78?awOk%W&PpX(y)RR)eR+p@FMWwVNI#xx~-=x#q*sRis zHm*pth(&%qr&xs;qgCU_@Y)5RX^4XKpbLuDLau9#t%x9tI9-=6j$RO9A#1N(6p9gk zj&mP!+?k`;AH@x=o-F2(+wLiD>S+oHduU@pSOu&+YmN+t(+QSd6|H3(dXlqhqv@@M zl4G9<@Kv5UCq^;loJzT;3Cql^gRt{}h$Hk2J3Uk?funU{aaUm)WA{yj#p!a_LVCEY z8?$>mYdq)^I5rl7^=ysWzCc#VWyl_HVrWvU4}( z1=~iko?_2rr#gHTI+vMIE|X8;E|k40B$SC%4{(TCZ}?~{qRv~G3a|Nd(C3GYQLXF6 zyaQ!A!6K7@O;bUqx6QN~PIa37#MNX8wYd#lA)~gCiIvihZ08rK@8Ni%UPkug_9?|T zKFej@7_F*VtQf5E8GrH;cfp+zE~B0qK*o4*S*j69Rk;>UCgYkWwY98m zVqq#P5ll)ibzZ3L?}JoEVS>I%;=(Ew2??;aFCOA!bqEY{+CU_+1eD6iuAW zPI!PC3`g7EFeUZcVikJ~5(&NdvBHZ5qN}oQrWGxJq(G!vz`3_Dt5UA*&h2ff36~+i zJUwv|{xECdyW}(mf~m!jy{RYJicXas6rF-!74f%&lU9SsGgYpn&W!qoVM-QIeC)s{ zVt8EG>SM#H$2o|eWQuknw^>Yr``XgmrXD>Z@X6Oo>w~(20x%gfkGnnUmp20gD8umP z?zkhEq3#ufFZLwf6E;w``IDOsHP>rZm<^qrJy&UX6XfpDM||?=a(iLyy>uZD_Ej|| zf~Bpmtn>H@A=*VHELu4l<*BH?g;iBd`iy*NaNnjMFsF`A>ah`5Q+^S^7CC&Wv<@_A z!pnrslfJrP`J%yk<$G`r>upBATo<>sLACKMp}N|26(w6V=-`E2)?jZ&k!CkCYUu4Y zl45?e@f11TGg?cRrbZmm+K~+F_6j8Hp5J#-$1M^+RoE0hlrBCtrU*xeioH2{SYPd8 zosEjw1JWj3F(bV~-I8c`B}Qt?$veS9z{7!yW_>A6Dwj&Fau- z=#g=p^@8#D=xf=`MJTJM=tqo(y-R}_1ewo>(7nahQ&AZBI5I*it5nBb^T2;zgLi)AS;Pw0LWGDvU>HLpb1s!sMdB z_??d4lCp<|>nE#~-*$iEV_1i9GVfhuzDv!)8qbbb;J!8J^HNz9@&3scjeR?%DETM3 zu8cJztb-9sQLB&Dre`-+M!a8FwxT(b!^m(%=BA=+1LrU+@WuXfm~uTYfekKrFqBPi zi)BA;k?YEz(2kD7b>ZzkM_-`(q@_zkx09B_?LsDDg_0Twum zlsnGEEAQ>%n%#-ydu}>}TgtCB4BhGTU`JU)2JmNS09vm4IK#wz4BEt1!r^l(Nr$v8 zX%mCtr7&w2Si&98C>+0Z+Ot$4l*jHtv3-g(Wg7do?1=<^0?$$0p}Kl^6J5kRQoIHSUiY_D?dRA^t;rA8vV$ANRn@1;FQXG|s|>5^SnMVun+y&P7V55H%W z`XrCleo9oJI|1e)HlI&>!#Ffc6b@W%cL6N2dng})H-DyDAd1b70i7nDuFS!wgoE%B zKy%LPLPZ2CC^!$n($WC2tP96TX~MX0dcg;a6;Y3J zZn+)7G!Wz|WIxR$=mI^vm495IH76#5vp-vVtu4oXxjjqu`Mgz@cy3ww77a7A zvLSa#yKHT_*aTGKA14MKL7uK#ZQ~Ia9SL(zED|iTt{12&P8;z_jjjDP3NV8j z$A*X06uAXGeViACXObW8b(EC_3)+IN#TQO!TOXu0yKyRc!%w&%exub4I4B&_9o{bY zp2U>$aK>v%*6mTsg{bx(wXq3T$8PS}_wRuU+$~wD^XGsWq475p77XB z?=odOBd9HW-@~)!uS3l8cAQhV>6$T-68P8?8NI_Zi&|Z%nDi>}pNK{i+VH`ouICpQ z)JIb&i~y(fPL1`BdK+ac`ND5>HkMYY&h-kSN0C;cTQSO}*~($D$q$}Xgr$;xE8IGE z$oVMzJLgcevZ7Yl#@Q|>Un3XdJ2~$Bcim$ouA>3%4kKV9|Ik}UOJ!W4duRqGC~vmp zb+4EMf-rs1W4rme1Js65p(a{xiyg5%2zbTItgYa-S?Du-sMGvhoV<(OUjn8*;>w$? zF57l0W8O>|D%h13Ru!Rgn5129EZ=0-$a$_!{mO67;w(e&b;%mt`>x0tTyK`R9`mv% zq&omUk9{-|t#dSfFDG4iUiGFeEBZw7{LgvtBb|!LLKlhnEeFUm{lR|n)q3Zs zu{A3`in3+ZiNy*&tdk-SDxRQC#`_=s;aztx zZB)x{_9}f1dS!Tf4`aL6I8Gs7Gp8;_vd_na8gy51*u+P0E2Tv6YL|h)4G>eH{7zwED3)ZB0;Jcc1nEJDRuW9WT5%Jk@-_o=V51^0w{(FS`_^vXr5_;0(@ zx_gHPnNu%ttZLs1Mje+->LXo}1J z1ro3;0;mi6+%Q{dKYLY>X7YBqjd2X|@nU7fdZ9flHrC7e>qeLSAdGQ1`iHI>-Y(u7 zg#U{@b#w2B?e(S`)1JJ8m&lmn=xgl20pv&dnkp56M|*>=;Fr%NM|ND06`jL-QP|f^ z7nqdvB1EySn!*{g6sB%I8`@Am5p63g$i z2x;ZHOXBvri~|c*h8oJhcIPY3Tmwz`1k}Lt zet-~K5w*OOQG}OR^DQmL%32LQw$29WOokjBi20cWyK8VwVjG+-+qh zC69llb)35^aFI5=$%`7|dDr2G&;{qF73YO=xsYC{I28TMdM(#^4flkJ@Wi(N8uhXB z?0^9(yTKo5QA2xXM)_&`Z8Nzj?~P_xIQiQ3z3Y@YcNl9`XQAF2`CU{;^cg+r0*BT$ z8z7VI<4}D|RaPQ9vSJ84&g_qfv!ps3YB?8kT zf0^PAt1RGVm4N^`QHErI=l;&ro@=J5cWvLe_W&!)9;J$|ty{tz_pM*cnTk~h60ZgI)Eu7{9{ zDUGTz3!S$;d%Cq3U&ODqBxMgT1219CsjSrvTpz?#1uz4YP(V<2YEKZD#|N>i-Ils5 z(mMJmgX59xkQ$KbAu@h{CmbRieTpXa=>heGleWu;3`c{IIatUMekw!Xrgz~L)G#Ws z5N}o2Kt;)gJ=l_?rwg$ul|KkPWbogpD%zwT?{96A(-6^eWLvR@v|L`GO@NBRsg^jlM2={X;R%#pA97roe8 zI)ALGSFx`h_(o95{7k-Oc(LO8NE$vdXriuy-RY+2!c$R|y>*)^S(ld6P1h3b{MX-A zy%`*(MY8KX*?3Lh%lsQE0Gs+>7G$Pq{as||0z}g4%kY-8oO*J-NAh{KO4OrRWI(*} z|4u{wr79ieDU@I{`ST#5a3V2-g~FGC+QIdd${uiZ{|~)r*o3a%`)by0MbL$3J8fma zYQI%OMgz#gk`I6G9RhRpw-3gd=00$skthyutN0*dCAy?D>Us^eyaBV5%E>b_^X6*t zQnVNR1S1sBTvI3_d~*ArY|v2S`2B|7I84gxGtY&eER3-OcYw32Mfu(~bTipcdtf?I*F`P{GFr4!_7_sHTf@FahXmGL;1-nSm&dyoYG$T5Q>-Y-S3 zzIodTI0b%K4^V{T#}~7Ox8Gz}LIEP=T)`9JOV{ty2r)@pc~f)BX2;CBX&|Hpd5i{& z{D}}iN=x9@tRWhuU=HIK2&N8J!4xmD7>-@uY^1^pA}8?>eOvuEeVZBiekKvj4Jd)Q zUt6=HLIw6Lt>gy-2vMDMaJa3B z-Z({ua`Z*fF#oni~FD>QlXm)#OCn4h^Qm#EYCarZvXK zgoig_mE%sBtOmHLu8tGf^3f&`&F+iRvhyltyw9#X6s=_umCEPdWR`G&V%fdI`=lS} zU>1zRv|IJTl7(T4(=6>mNwMVQM<_#@21!j$yW-%-p=E(R5>)#Z*iR}l4@mQMpkNSc zv6}(aU};xwv76oYDRvErtJNmBhKKzSKo!Y8v@niXOH~AK_*@mDCxpSUx57iH#vNzg z$iA{rfZw)&>9PS&?zwq}=i8mIfO~%l1rArg+T$ zpU>K{hP}I`jtXCTl9nY+d_sC@Io`x>ww?d&4lqA~g2NBI3XDdx*{a>to5alN+CV98 zGX$NW4CYl1m}%%HdE;`HIXDPrd?^%EB;_Jvx-Awy2oli*bk`5y5^@mO6Z1$B0Jy$W zW1=7BAdg66P?*%8C(Ks(OD5B5G9~OlZ9P_U5S+a7n6O+7UN8~{7v2cqgMr?++f8Sx zh#niSa?etNBO37sR+}#WU#K8v79Ck2ds;;di-K4#7z5v5XH*p1sv(Hlp#{^@CXNXc znMEpKLh<-}Lg_QUsp*n4zvLt5+vb#f?aIL3-QL3-koJ;gjz$~=2bwb_8|B5WU7dCA z(X-Z4?>`qNTe+XMYi+PwZr_V>y#4HF_IS{fh)Wf1u<5cnC3pvr zB3c%73wZ&6P@f7%qS4n!^N5-ii1A?xmj(TWB#YERN?NIFhPC+8pR6EI~qeBDRROt*nQY?m>6T|0e zz;NyCZVG1ucwDG~oa30z7Zf2(A25PWgIsfbsIA-g9^?qC6weIX#x1_e!G_0n{1IM$+k6oL_^ajg7;J120w#@hsx(B0vy*b_fwA$i4l zK1-KPC2j7OIDZRP$QvG)9!q<$S8OQ%G1HxAAWUpZMh5#CFO0{_2MnduV<=2Ri^bH> zC%fS0-szlxAa--sI#zbjBoH;J8aEjUDP_Ily?+|=IDU-E1u09hRxzwyk)v?_L+hcM zxaRt<$kB$n==HsQ?3oRcXl!p+E8hkzO5OQVKFveW!6v1zu>A%q%A-l5ui9YZT|v1x zWc+`~B91Z} z+N&zO9RAv6XMvF3&Ip^Y;8d2}?;NM@%gs0a1AR5+6R*0_?t;xjbqI-oDi$`BB^45a z6oEaeOR8Ox{uD?+dmxro(G|?DEH#bx^~zigcpWF4lGyt5d{b6op+dB;ymgjS3Mcr_ z8PM~}ET@B<-4wtH`j|8!bc=iXAmu8y z^f60+f#hNF$Y7S#X((_tA@s26nHD}GWeXIXJ8(=Hps_*@%hxvSaD(@*-6#G<>*br? zq2v9C;Ru)-j;(lyPd<85+Qsx60EL8wwbq7lWbyHl8a(&~2}R$8AIe9sgitrSN{LzA>k7%&|vQgdgVM_c`T*CbW1QiS16x#Kc42?!)HePE=Ly^ zOck`Q|Dm(-YPR_E1VFZr-n)#*y_}jB#(DX_8P%LsH|Mz29K8$oJG>fE>rPxo6PyGB zy=$+Oq1J0i*nh>H8$HnMwXEb-03Ia`VR1IHik3&yWam8Ls*W6#Os|-FEMBNo4d+&6 z%7)``27dU==(xJN7Q_VwOkTI63`LKPGr!vnm~yy;Ay~gw9u6^#WQOBF#qp1vU-AE@ zTp06n(QzOJQz6J}CqijInDzk#b6NkPM1 z8fmYIcy}6g=W0T^vC-6k@rgG8CB-LxQX>U4b+|$k_(PB*!?H}yr9Eiq`@%y>N?r5{Ap#>7>Y}r&_)%QA= zgaX2Ii?~8+bJoCqh#9Wss2iJ7cXDG@)dlN>CXZIqd|3qMe`^QRSrT!`;reY?P7Od! z)rh$9<3%f)v$Xd^FQumV*q(0{r#Z$Zlo|4b%T|yEcNWNy5mr**A{ZqGLEHm5NUPkw zupEXRjI5D3>kLOL2I@yiuL9uZBZEy0TGu)R>B%hM?cr{fcn<3<_1KWS!j@V-*Q}wX zO0QEC@Dl|=MPxF=(AT-<=zT>$GdDZ4$Io{plJ>UbAEJSUI|k_rF`IH>6mu!%A>+tO zRFISG7e2l&D}^Xaz{gjHD_@rK6yyMW=01gnqO@POgFi_{NNq+`=Cy`)ffTg6aC=ip z!FnipFwvE>`(pg#{l4X_m&o5fLLbVIH8nZ!MewBGncApSHfO<2XVkh zZ{no;Ub9mrHvb1jQidl&6lw8&n(SqE@@wafWM40)<#FV+h-Ej0DzqKFxHvv7UnYL@ zLd&eUQRuxnMBM?bnmuRh3SI+F#QAWK!i#8;RaL>g8+$vdT||6pzEGNME2Cbc!f{qt zIZRu|Slc92U%o+wi#|R-Is9^^f~A(rx1sXeZtGo* z?{zQ(1HvYREajyNAwn399Q+g$h0ZcMQBD6B+51sQu28|h57dK2(gKFs6rM2Wq>;AR zjnkeC!+ta+d_C4nR9q{WL%qM%tlZQhHGoX&vlEXhve&tF2|=NNE$pT-h)Q{2ElzPY zRN>x=6TfGq7@MV?ecbwmbb)^7bo&#C6V5XMWnPomfrlasQuNQonJyv&alUcB0~e7Y zoy>4`cHzh7{b|w)RAaWolj~La*XYr3eQ7og{lR;41YSlcOmsm$G@*5m$3HdgNdo8) zw3C7EGv$QgUz@(#bRHi(cDPj@TSzllhNnNfg0${KBnt^nC^6lpfWdC_*$fQ4p%R9@ zK%ZrEmYNbI1vS!W^i^v4k^j(R-I;a%niVjxHs@&IvU35_sdkHe^vU-+MRz3@RO0vo zPMrB2Vo?l$C+E8`%u7FsbC-GDX#q{)&zc}AP{q;8eZr57QFwB0KNW}Zh!6iEK$$Ct zfVY{%oywz_2s?k5WlXvska8&7di{JqV(Q!(gphO0n_m;oPTRHv@C2*CFSj+~KKIB{ zhzi#zhRY$2X}i4m=c$&qm2Vbhl9PfSrdtMRhE>rNH=8zFB-icZKOdH=ZU(k?l&Vwq zaX!GC~I@uEqWgjR6yK7anNi}PAST1AFmj|h}&mFyV z)p0rksGc=Mw}?VG2|m2!rWLckWZ@hN;FqcBa=ocO!VX-$#7bb6?_Uj=;I?ga zIEM(_hLHkRszdVl3!RsO%D_G^N1k-Ziq!k80Bq3mq>4s&FBuQKUqzAnjkI<5e)hfB zj2XQd-lX26b`L1Hn86m-hpVA=v6E)%$7>Hp!vh{jKeoF^yI!S|>?*Y^!I|a%RMDZC z5GUtUYOms)V{k@Z_*JEBnp#+|#qKVd1lJ#DrJ`h$rCYr4zkXkMl9X+-T&vHQ(+%tC zina{A#YkQsC7B1b*rU;8ADmGczWgt5u7QV1>7Le)%`>aSAt>@*JP*U;kZqJL4Us;gSEk56o?W-FQ| znE0eLPTcaqyT+C3^b>iUPK2jzX27=~`~NHxzTfojz4qGsm30jf3(F7M9O&6NzAUh0 zm4ZuIry(hS6E*986&rI!NX3=SVQ9G==^3d2#Z*hHhQU6Hg9cn`e}?brbB}Tl$Oe7! zc?4eiBrDnGn|J1ax3PiR7FZFz9a^9R3P<1Z+~y@N#o^GmbPo2|zrN3T;gz_x_iG>H zP=M5ipxw(kw&aZtO&E?`7AXD|$HoAbdgZ#pJy@EdNc9tJR67&(_Zu?6mv@*7&j!u{ z>o2wgt!@8SW^m+tP+7jRojj4!q~+Dhdv?NQM*5LynPV6N(=yu+ozEDDjz~Q+vNJ3D z)!>|k^b@dZR%O?B+0I{ZLx(Do;ms|Q?VEwLkWTT^K2cU~%WzRk3gdgChr;RS6MHO7 z(mzp($I}}bDJqJU__MEdLB$gpGW@Bn{I*fRoVV+yt$OS(4f}Q~Hnve#vYTT;cp9Xb zXH>qv7Cb27Ri&p^Z#sIoNxo(U+{Xl`Mrjn-{xH&A<3!;+xRX&yJjN+vjLvx z&*ew~4IRLSj;wGRcX*;fc3~VWWrhRy=u)LH6Ps2Oy1EeE!236t@o8FSA@8O*j`}UR ze>`aFVoyMmCHBx}$*C{~!Pu^Z$A2kM{bBCA#%DQ%uASbJTisN`B*GB5zgLl(4_QO-z0WrDwpt>!N8s%r?3G4n=wwqM1+IQ5~&t2D`kT zc$E~pOIsmD$ir#atzE}F1d$yXcR7LbHn3STrF*=^aXXhna|d3&)H_W0#Mo>fr#-KN z!a;G>Y>49R|-Fe*_3c8I-vmuxTJYJN~JY4o0@Z_2ZMFzgy_8CV= zqL*GI%SevEYKGo*y%lh7b+|_#QDF1+lh1||Wv{Mt03LqFOSmeA4W6;^>VTUViIq1U zC4;9lVAAvh@#6#g%b?&`J1nH4JJTbv{cqK60l@YCr&0v?Rx?TmD4!%gzKKeaE^sq zII@|A# zkNXb={jnWzF&GEXeJDwS{xE+3-$Zq~lJuY7VvF8~{U1vjqOYY;g-JyjlQzY}-=pXp z{9|yEA`1Ma$7K~@$>4FF94ooZ@h5|r@;h8hzC7q}B9$Ar$NucmgpvPFSmG~%iFh80Bn{_>9p{(Pw)Zd+zG{zE5;+T5wKE;-zYoy78dd#Y8i#1HpKP(y(`&bHKCg zJuSf!^gSqirkAq*F&-MzKCXDJ=j?yv$dM`AB}zB=TSJz2bmqCOUbV_HrHPD{R99Eu zxpT)aW;PhU>uP(pGlRk4A80X)N;C;R4MTuuY$JyDGW{-OtJ_M z__XN~_CH=6y@AYFqB!wS`6KLS7m~@iv5uUyw6p}{z|qI^!IS)2KYjWHp1xGw$d5mE z7JF@u(#wgysW*lr$L+vP;W(q8SdlVV08az2GPdYBIUSfnW6t)Oj*gBmUcBfo@Q6Ec z3kGl2zG>ac4Mb@O$tRi4yrr$Kz6!bV8h#UBvN%qpr z(Yqo}pR2S#)Q>X%ny;_#`Sa&77$-M4q4wFE39|YnbN@rL9kuaTB+Uu4;D5 zP;&Nj?N!0V>(El(A3*{Bz}YHKZ)Y{OXZ_OL-2BI|dGp7{I`cq3^h1XZ8L=TpD!+=s zNP*1ar;C*KpT`Ut)4mpOuZc30mVz;ROHTh83D7FxRPKE5(6he>HB?#P#cosn+Tqv( z%}4`aw`61Ub6SYRp3*?#i9kpXsEz`U_KzQbGn<^LbaL_L&6|x*wFXydyLea74e8UU zzu}*+ZNEkr9xXgA1RKAtt3AlVXjqDVzux$ zy{oFK`ug=$0u2myW5#ZM{WIHR_ZS-TL~E38M3vGbwEY|`Cm$&;>*Ll|xNJo3h3XuC z+c;NvuZ4s-3{7Lw zP7v-)CR5zASZRN15PEK*8?9AE0N-O0kRo#onPfAj3*~>mbmA&JfUc>6?Q=*oz=o*f zk&*9%X8!_2d*JEk_t@glOeG_>KQT1ng!wTS`DC23jNbjCc=CU7_0}rIEj6#E!1R@T z^W&%*pf-x#s+$QW!9LU|b)zIGERK@iy?Yt`6#zx$BZOJnqmvO8D|zs7QWGQ1(F>0h|{j3q2>1`wVN!q#Y3O1H=geXQ)`_kUqCLHH-HrSeyB5IuW`~or z3&AVe06$c^5x+%C%Mf^7=Q^bud#1f^uBD(_F#!w1%M{Ox*f~w@ax-Wbjw*7+-==`- z3RJXol13KA(Xxq%kv;)vr|SU@sU$RATfRp192k24qiQNOZ5FUpwOA~Mbg_Q~H%YrE z7k$hb-V_E@dG~)*8APdOMK%p1WclR1DFF6eQrTb_zmqoR=YVaRgBL?%ssM3$8`XfU z61jk)h(MMdbbINy8O~8@@AKZus{LPWDm(O$H#rA%X7FOS^`^wRl#t2Udeeh40BD_v zU$bsqQ`+>nzHd@fd8eRpLnmvr^vJ>s2{)U{>8iw{$!LX%G-Ce$SV`c~LtcMd%GT%G zG9eg2>M1E1WqjE5?vWPaj)^f4RB3-vaq&LvHxMoLU}%3aCs>rRL)0sS-Ot7pA%(Fk zAgc%JMJ^+O%J?6VU9L*uM;$Wmn>d0!F!^0z3br8_oSq#3CaLZ3!H_os?46uis9pec zuQeo^8p&n{arG!N@x0Y4#Jh+8H(1!IMc4&hz$?DSy;5R_(j-&|pG&VMlG^g^uPro`t?T{icfD5#GK~Rck1`6=`u3#7KKY^!Ao8!UWo6khb zACVW`E(S0)Wu9^2(xsF$+q1H>N6|nyoxtTCa+$57|EB?~JbR>Y1N1Rmp0)M`}dq?S5t9Vl78oRGt9ATS-rkPon z4!`Ox4I}`DpaKCrSSoGm=n@QVOhEk2|UUBzED|6F zjwbpN2-L7EAq*Nr>Dkz#7U1|;Y*Kmv^li<~@=!z4Y_N0b(3RyKJw5R!ETLaBx*!;$>8KVv2t)&xh-n%Kyu6}P0e}M=Uc7j*KPgP33Hjz%U|2PEbz8|(z}>dbQo7N`i8IK|%p7+5{mzwr z0Z#^(y!6ix6m2bid-?KZJ0#L@&mR4r_%8%Fx;{(Af1c9te6OX-O2e;4MngZ0J%$A=8{EhBUD^w}D(4ZkH{dwDCL177Fo zs@1F2$h^4rG@DeQMt!Z9#H-1IQ+pcSLj~ilN5DKP05(M+5ERaRbeWJI=^rs|T{1T} zu6)cI9b#kUPVw0X5bMLOc_P|@8A?mIPG9@?oU3ns1>UH1-pCT+R<+>`o*1**9d`gV z_8t0i^&-n}v}IfUieXe&5BBkr{0}vcvvgy@psbj0_oIe1err9THUzRT2p-ZM8-Ghg4>iaUNFWR_X&T%)6E zgy`Hw=Wsar$J>k6*-5Tu?^iSxj)PZUQnVHjyl;t^$r=Dqz+~Fc!(Mjq$9p|!sL#_b zpE9ytEgUyHbB(&XsW<)iEwhxCZDB@iAXW+*+_#*4V@P`q=pX(sDm${tV5 zK67Jjy#~;68>HiThG2G_{)iiZy2I|=nc93#{l&!vATBpJPpa1ExiySF{_V}xXTaHe zZ%xg`JYM4WV2>H>Qee&J&-bdodas+&NXgHVY*oAR;?_K6caJ}YYt#eb0AM!_HiJ2l zu|a9WVKCU~wAb7P&);0?I{Q3Oxk+sTIMjhIA?9(frka}CIt%L6*?-!?GXQ)w>rXYo zIsvKx>|@_(1vDlG5TrPaxi3VQ2rsWXyh%t27HlY=0TitM`hJ5&XYad`lJo=pq@0}d z^+Q8LZkI2&ICqYXjZIEYinv3uaVM7Ckf(U|T6FF=_GUu~1Ngi|Y4)uc133H~P{ESl zwV!KiYa2a#shV#;>+Oeg&AETe>b(R$e-hBzyu7?o&0c`QAVylYgiro8CW}TvsjdGp z>VrFydPipKCRMH5zhv%^ z`UVCmEp0glxkW`+xTgN2kL$ZS92)Os6sLXdN(&~RuV^Wa&Na@s*?pt4$s?$yqvS1Z zn|{^;uT)1fO`WL971l+C$aew5t_1g%`V@J=`756_w9;p@x&_TiSRt1Ad)kkL+^&UIW`c>TG~os%fD z+VM;$sN9&%}_eQx?K+9qj`?QVXHki*5zB*TffNF)zwWqdt+eWlEI>L6({p{ znRoBsJ%4ws{6VSH4yU3mOM6jGv{W^X2-q7Up6c+5S$8FQ@}YDplF4Io~gaq$29EAT<|h=yR5H( zk>2|xZYo>`!ata~yQK+;55j8WZES7!o2zC!I{U1$7k*r4a0!32rO5Q!oH>2*+fLla zKJGohvCLey1UaagTVJ7WKNa{?BoYmxCsw(+Udhb0W?`Ltc1sR+MKxacjxHZ4)Np%l z^6Q>=&(cz&b1UB72X1l2NA1eo8FMEV-@Xn4$>H&zFHsGO2DnX`5HA|**a>*i+|#YM z%XvH=$gUDJ8#g%=&1iXZw! zrfhX(U)903yunfJd(TDrqwnpxxbl|I7Mzy+i#4{VXtsAD7FuwmTPe z8+8de3sx8Z>{*R%(2$szbk%H$$$}mC10B73~#UtRWM-4x@ZT-EQ zf~Ty43V7gi7N&hs&@alfwXeqHARs?;$qKQ+gCRvo{{ z;PAZl7Xz{9lf-qR9Nn3Il>)XJ;F%-U-1eb(9MT)sd6(n0(B)J&d@W^nn8QzS`h_!ch%}EO^iK% zJ1gD~AK!FN-2 z^14WJK55X~KziBxa4eRe>pHl(xu=5L`O!vbbS+&%LISt^Gr`k)L$1fRayK1`*H^CM zTGPCyGMfF}=yklqR1K z_=pSPT*=R!Yk)m;6{lK*!BUgFDWSh+J#qy2-#bI&K-SwCg1 zFz1|ew8N)R5|2poUi+z2j$}FM$Vj&Qk;jo3m`-3_5};~rb9mswrLI%m3kzn+-6@n# zJ?L+-KGP9XQZ-o{!)^T3S_U#1B**S&`z9RyQn1O$-WhOJ7s7?%zWn^yIRY(@%%f!_ z4bfRWsYRzv>iwp-^0EbNgU|s|f8PR8mm47ny6W=mKuQ!6u^>N85CtkIC`g40CY9_# z*`q<6AbzmqI>Z_^(!&&JKr?uHLE85R3GJl9)#_W|2!iFRB^4;it-eW`roWc;IjN(i zRi^MFp*Eg{YsXKRvU}x z#&y$|H?<(c)c5WHe*KQOkz}{PeE93->7E?O^c;dI)EV}VQXVk>==AdYx&Z3R<<-@t z#AO_}E>Uu>wG%!h_`131bjyf6ChAZkXKitY=Q}$;GeNQ|9{G!hKDjr6X{~}h%GFpWX#>6o@TRgCDFo%edjEW_9p>(B(ldal;x`PoHVhh1)`6#CCg0R7LSp^XRkUZL5IE6Ib<7sO_J3 zZ{K+ERyJe@T-YPZ!oOEBGacEB)t3iWC+OE0se-w9dE?3Oa)Lrxa)b~BY?2?MiC+^X5Ga{OH$4uCw|!Uej>(k2p< zk~};;C#uSMkvstnDvaGwgNG7=)K4@!I(Q2*9iM5Ze5(U>g`U+*P{ZYWo$8-Rd_*aJ zLVK05K!2h^tZR?5I`+PnscCb&rgx7nVLihy(e-DrZX|rsG10{k$^GavPu|gip*!Fl zsfFQJFtUTAq{VcF^q>E)MZWuh&y}wWq%}a|&==Ay_B|aQjC&18SqA`X$`3XgOK=Ja zrFc?CdBVqv8JL`DBPXVJ<@hZIfJOn>5PtG||Gq~NOV<1aZwuZTlr^a6wH3}`i5k9q ziIpU;QOK$m$LC17y7LR!3pIn?01w*x=H1=0yZG&hiw>NiKK0Hu3%>*CnEBYz z#brNW$>#&0T1XA>4q^%bn)RL9TFs`ctE-y`KZL{;&tkO|^%?K_3`R^v$MNl0ngb7& zl_!MP-bX0u;1r8qak_eFC_K>8P3Md-@q$bp3jO9b1uP>Bff2~B2AuxOWxxynSf5N? z@>iL6jAde7I9sB5~7WMIh z>`SloplCQ(9AXYmE?YsFbI#(P9rLB30bTh>Sw4m0jyZ@5Yz)P9C;SK)b{T@5UpPbS z9H#^?d<4_*mtXqp6bvmOHM}E?DAeVi)62iL#3(O>?R3Yxi}i8r|7$_vX=9!mxlacH zS?V@?fP+(4Rt{t}Z{$*Z=@n$l4fj~!%sG6S8bcR33b~B`DT}XaEXVF--Ti-9q&&na zl#;gqUbM+Zw7v!C)7jZ6GkmXh=30HfSeK-n^^X2Y9nTH?AQvOm#W3bp^pz1DJMOlR z)?$BtnWAr39@H|>e1QJpZ6A8`zm$1H-2zD`1pUKVBF52qXAlDl#cI0ny#^Bh8WznW zkVy6D%Z0qT+U_$IfSd}zwJPY`Yw^1I zsC##$Oo()HL}vFYf=j>zIA1*(cw?u-ALTfjl#=2FW?i=`9bzp>0@Tkxf4ff<*LX*BGB{|I>voSCt1dJr-;fBhLt z^4D?}F|znmTQ*&=s;on#TS8%-2oMmBz|Ul*e-1L=*1^K({Q z^+$>+0*n5pQWxgbuYm}mk0J3P&cDng7Lt8{JJQ?oyUB(132*x>k+sktda1DRQh~83 zV$T0=M_~Dh@9KfKg70ri_O-I~HcNB}$#MoG>)XiK(|*3Kx1-n8oUw64*`1IM+mp8BeYRE)26}H4k zlR&hlTZL|Q+9RB@+dz2+1qZhsRA%m&4x~d*d8@U(Wk^L|=x8A_b&bdx#9hw^MH=1O5Y5+hGTa7HcqTWtLvK74p5fq=zVTzoI;WasXaRZUJ< z9rV)7Fs8~qmRu>=)o3k2iYdz|l#Z5oVj{HlMp8tMvF86e>oXbY2Lg!^2ms_P)dV6l@6gu zpx?;ZR0P$BJJE4pOxqG}x&N=lhtBPNJr{l$5ALmRtrjbpK!ViL(h`Fy9;K0htXVdB z`Jg%)U;Dysw9`wqq#A7U5b>Mwfu>|a71lVN{(;~_e{MJ#(=*Ig%7&`2USPQxO| zfPn9hZtT;Swb8pBhw}LM8gExi&5e_XP!&1$kG$woxtkZDve0u;kyXSZ$zDfC^dst- z$-@)s`t{4HispxeHV7pcIOd}-CgiI z+(jA3M`Zdc5>TqWgKe;SoOMl#o>MtPq2jzOI#duet#_&>OUKCb+|m`qfb2#? zR(?qb>-(#g^|F3k^C*3F^#Qkb#PDBQYX%wcGt|_ULN_7PGLoNu1U2sW+j#5h_y0if zxB*AQMS->}9Y%hJR_M`|&nHeTJ=C?bQlJQq>WYzh_cxmu`HlW80&iBn$II!Ts}~d* zOK8ETegNO>M!9?}PerbwTTBCsNOWTjYj=UNFzWV>4&cxorQxskdV^|W`Hje+6cb}^ zO?T+6DNpbmM>=A(=F^_VNw&0Vy-RM5H|WRVslU)|jNUi4Ypfr;aHg*yp2bo#&^lkr zvvxEpZ#~w@E1lr?ud7U1&VT`9p1oqyIi&Rhe@v^J`+uVw9qeZs5ly4;kshcn9iG+t zI5Z@k5&w3wSaL85l{a(6??zwL_=dby{k4AxhXXx2PM0E!Z}TTyl+ET{!~Ut(uxVRBqC=7l&@oLDnMA>&@s zb8^3YiH^a9sX&8&$kGpGd96pEO%!6D;SPi7Y)3;se|=j_pQUCVb19^Q|8YB?my72P z?5P^zO?pBkNZE|^{F1M}j!twRJ=5`ej(;4}Jys>AnNjogvZ{KXAP9lfj%3$ae>)V! z{krsobd0?<(_(v4yPU+|%_bV##n$_9zkkcS^QBO+wu}<8>$M{=eJLKX``~!>&CKqX zNU2*iH#N!Rge(%EVt3n_g6`JV2df@$?|q}UlaO;paigeSD(j%Pm3qk&L`U9tmp(GeO#TCR4!~hk(3zMv=m6^B_%5J&u znSz{lpayB+^}P>!#y6tgcu5?sqF{cT-fa3CnvDA+h0&NAHz*9u93VvPPupb|3zU-$ zCT3`uoh~WW@3mp)7V`_T^$&i2NGHQ!O~5{z^1NYJaWP%CS1+9E=dmF}LN3&5v6`5R6lR?%NIht;&PxvnBG*3@xMEL&1i zQprq9n{I+GCLkaH;u{^~n_7nYka5`GFJ3PT*Njj6;2^-4sVT$NXzhTd{fvR5JJFMD zePd&fVB1qyuPmcSzFu0?+%hv-P(pK-g%aD}P5OJoAo11bX{^kOKc0roop&TYn|4aZ z8<(t#r3AY(-?Nhla`aSEQ2}bo*A(w7kh1FT?R{_p6()g`>6df>Vbs*s1r?(uxksUd zYW!{lR;!dA$W>MU6Nq*^J2Ru$eDT&2!x}Z!`GRu3~ z%h)p0wx?QfZzn3Sgh|aCP;9|p7W^&|5z)G3dN=SBfUTp33_L^;+!zB$NHBi)nU0S-jd`M(xNwnH3Z_tl2nC9o#O2@zmR zevo$nYWl)n$RFc=gmV&;lSQ=&p(YEIl|UHP_`lw04RqJQ1$GqU-v9n2__&w|Pz zrmQ!|WB^JL48Ztu{qKj#Fv8Z`8sC$_j$q$<7yo;;!XGaInQE-gzoJ3}*g2WR|Kna{ zKo6G|wZBwX9~9ErD_nqNFiM4+)*wtpJ>ORngg-?TqfdQ(J#cO}|DebK4qQ+qz(Xqh z?fzu`YrFNewQiVCiP=E((1tBI;&vFO_&Y5U<_JUxOnG9ZbReop5HCbUZW{M?o^rBf zrmtX$Pv;BNGa+(P_W0M|`!|FL@Nsa2hjOsM!VyVA|N4~Qr|Dt|HHA$drEI7t*4Ily z+?Yv;>>eeY@@sG#O89M3Vj|Fxy*xZ5rKFORl9&#o^ayYpaa8{`V-8u>k$?Ur{2xvX zP`kDT|A)*a1I}K;ZxP)Q3J^H?zm(-VLd>G2rKO?*VU#|YBFxeCOK&}&-2GfJpIIllb&IzH^kOf5wjNeF5u z^mJ6OFrkB^LVlh%r)gFFWYPTsnL)Vkg&wxOIQr^&B(v+NF8n*BqJcse+h&te8ZcyF z&l}mVOEFVbn0sOh$j21n#F1#ehOlro$Y?A5rfoz9Hr~>@<$9 zAM*@(H~frq;VJmDkf8yxCFou_?8Okq`dM{p=ldWH7GbBKUc?XDME<~knl81Ycsc9W zYrjn#yp{nZQLU<@Y7qBhoq!h{J%jxHn_ey8rhww!I!*;x4U#)ERgI9TUBF&MeaG2r zl#J?c;UhoBB|-$j7udjq_>yMT2(#&~^zdQRf4)Ju3tBEPsHBHV zO3j@A^$Eh)?bm+-?;1l;G#(BhRDUn(EGga)nEtk9noW>1_Z5$-sj0d3>L}B`|2Q-h z>Kopc?AjyTJI<-0!g6=Z$LW85Je)cEKeq<|r;fkRir+TM@dnVGyI_$XkjCvRSb+-! zQsV?(EKlM;7P&ye_VxAWh3_8e>B0AG?>UR}2PolP+tEbWw^dDUP(=fi`2e3L-Yo%% zz}+dz;M#% zK%Lz&rGFj8`W8>ps%aKz%h{O&cTmtVZ;hvTC@`1c8@ zZjzn@UMMFqN(PTOc3lhkQ_!IGyO~4K)&p+!-yi)AxLq(b3M}G@#y|Es?&#iM_ki+8 zwAI%)D~oHB7!`|82km;m|KIlx$65HV1OD>^wCtFfnHd^>*%~=;ANA+IZm|@BqSVxF zjS;8SGQn28)}urn;oo(Uj+CH-aJ~pPye9nt@V#ge`_xniWc?f6NYLAoph1$k&v%LJzpJc0aWSOWly>DOhzJTJbZ`35R+_j_)90rD6FL8<2M zGji4h2{kn}1=>7s8M0)@MqnxfQx*8y(X(XaSZ@P(2!wy&uUaS|r|ih!?(W{Hcmx~% zG3Cs-2GskMC&>`*GMtU!uCoc-?p!l4GkXVc6@FNCH8>gfPujxLl?TWW6Hkb8-oZ{d z&HCvLo*15wYYIbU`r7|s^c7#;e_KPONdsXmaH%2GTuFj|tgdosXb9A>;SutXCLN%8 z@`HL8zX>bx5vNZYea+ULrgdNiLx6gP$7%RyIRW_*N=iSba5)a@Okf}}zgYiTTPq&- zKp9e_8XAfRQG}55fDgsnpK(j5+O|F;LLQU<2x#n&9^KH81>dZ(d&|~HH2`o+B<^$7 zxUOFZx^r9#K!u;@cgb&41Tc8T#KbHs5hv`pw=>Ut41wQK`+?MeM`?JieBKP~+y;5% zp)wahiufr{pqf&4-)Lh%VBl9*To89yADXW;G+|BWKZ!6^LwPTas=q@`U64o6lHHV5$$(oN(`D4+-Z z1Jbw9RAyy&<`3>zjME!*a5UfzV5!N}uat2WqSo53RJ8TA3z&DtLNh3Etnjso5;GGN}$0;Duh3d{U&27sHTcib}b<30-)K$o#R6)N1Qd2VMMwrpb>`9 z(bFEnU`MBzGH5ozEwwShD}1!HdEmb zB~mV9YRf)4puZ+74?&IsxBy8>eog$!kx93V&JpKCg|8In=PQ3->A(4WOt7{Rm0A`D z-^jwQ*EeRdweifL-&2c2<`_cd#}&5-yLF(W1?tZT{oEyIlWFJ7^pJx-Sq|3MV*N%A zEE%1&FM|Qy%R7-D-0pKNQp>*$Wu_&U|Si~5()KUI{sOk z!21hKOt~*M-LWB~az|_8r0uM|(&6Zwu?WL*y=EYfbQ<;;ueNKb$4CVSg30*MM5Eje zi!jgR{JlecJ-zDUWBNhRM%bAxB!WkgClM6pNY@D>)*vvR4FvZj-w%l&^YxA|^)SJQ zeRW@yJ01M>3p_RAN8;jG<4TwL%+E@=RdQBJTJ6(qK;sAV#@TMgTx}Ymq0a=lkNW1X zK$t_=3RHT)CXO^ZigJA1vvqO@h;kx|k?+~#NLCBw(#*$Z=w~iY>(gQI;RgNJ5CPCTjVC7EYO-wTa#>RP#2^1KWS%_s%vxZCYAxql z$4&NC7?mE5stJG5-aZoB;%V?rEmphAGUu4M^LPkQ*@&aw|EPy%o-4|n(97fBpa|_H zR7PPUQxS%oViGO*LcC$vCTJ;GkIa#emkp!zh~=lCN4VvGJZuCuq6TuHa zpV*E;TQox=P~jdaLb>8x>Lf-;2e-+&CSMkU5_*IsfbrxC42iNH`X#29L47&XJzEYo z5h|DeT|RliACMh`%aYN;p1pIN`~$&(qZ{oeo9%qiMb}ZXwIsAPEM!cpN5}54R+l9S z1}qE`Wsq5ELzs@WH}*izQon-p6R)hbq?}jZQ|O2yrgIOpyw(3P`;BOmy#3Rwmy1Y$ z-K`4(3g23O5Ow5kqFa{b4vdKU@k=$C0L65#${d013VTdDpB2$0nCv!4f$rad^}voo z9SH6dkS-Nm&@Ze4Wk|W0Gbe>5#7UJ`9d9m?3lmR3Yyp-nIXQXM-r!lNL7WZ{ZltPS zcHgAD0i=^hCU&N#^I)~0oG#G*F)bn3|S~ewS5#qb{a1qG)0Ra@2 ziaNGUf3@KJ$I)p+!yvL^Bp}UqRl)_oPr!ey_zfFp?5@Anpf61&7mMn3*aDJ_r&)vV2rC_o_zWTa)%(I~>MJ8 z1PA(|KeBkeEu}pk5S1|d@M&U{Fc!}4haC`qMz=V*l;!(lX7&Q_u{zj{4o!-z%Sjpw z=NM>@;yRcCc`BVp`8MpCeoZ~lXY@Ez5BT$_>?HKPPf$mFv!ZTI5v5rxOr>}H?`CN{ z4E&vu10xCyZdfI5J?lLM{Y%Lmg`-@jHSE$9nBjh(59E|=8rcUPK!rsC)>vE*I9vCXob%{fVcOQ}MTvnRu{d(MN*NWUZH zsHDNo(~8zt4X<>+F*M{_%36-`u+rC$TZ^|?8jqO5G$&2pxC#t0#M~B$^qOVRd*}8V zR(bgaQ4h8eI_m-`>t>Kaxr%5)dIcg@XI-30wEt1+L;!F)av3mh7`wpM>hL-z2})Q3 zl9J<3ocH>NhIY8soK$CQe^=)>!2%@{xRy94_=*p1gxn=KO$8=pACSNvej}ui%@AdU z4ohIW*^fL*3QS4A50#4Kr`EQId+Av-)+paoswwGBghTs;ReDxffJ>Th&qjo$flj<0 zrms)T9pS@$0jjtCTgh(h?5S(3IYf<(d2#>@mC$<%}VL#erj4?NL9_%{ujLeywM zMP2=9VnnT`z(b*lD?$jxG`*BMTlA{4`{d9~xnZE-ci%NX+#b(|Vy!f0iIt%d=@fJ4 z1*%>^(LA9j4QAoKGrVU)57$g3`=o=0iCq}>q>t?BWp1FFW$TNV?}L!Wq-YnFqm**Y zzL|-#C?qm*W8$+If5QNI@$Rh`H;z9X$X)I>fDnUe8vx}v@Ok08c%A^<iztLWKTS-Iq#nxE8YcAO3j1g?7%H_|!88W-UK^x52cQHNJd4T6tbUA!c+S5y`| zt5kby8YH@)U#qqG39a^funR9Q9oE*J=$k%=)I5U+78cS0Rj3d>n>`-u2M*6*(9c=N z-NQp)DS{jl$_o#>nAw*ug}SGuNJeBQ~*dR)9`D)H*eSRIDI)>j)s+ zf9zp!YG&q>8U%OuROMT4^4z1|4>}0ul50-Cg-ju0my7~YF%`@`_a|jDIltS)tuwJv zUfSHt8(EZ2``MP#WmazF=UV$Zi161 zkMYmJOStcHutK6L*!G*v#Lz!k#8VxXa-$60mg?&3-zDbYx@?BfG4YCd4A0Jd zV|^}jHonk1r&he)PT7VegfO1%aC(zZA9T3%e9w1K(bB%c`XJN3JT^-D+mA~xRv2E_ z8bG@X?Dpa4moN8{&%c}$k^~9eVa5i9hQinT@SH6?dXL!dQbv}_QDvAOAo3dK572et z-Dh({-s-%GjLA8GClQu)GRtIe6Y(oB_QW6?gP92WyDm~zQgC}dE5&}gXJBhNAvu4d zlFB48Z-`tBH+c?sUHDz;a~N-bY&61uAxT-XT7gCMjhy}crnLe@Uk@2R9!jDNQwM{R z4-mDKr7MrwjSdZL*-<#{;V>R(5uSeLvi?n{bz7+Zo<&xcA9vnk@N8E5{=U zsbjh>%8KIr0n)>VwoetnGv}tYXy0^io~))kCuW9Rx1$v$Bo&9CoBvL>&?A|B?JAft zYs{E7yKO+bOe!Qzd5Y&f_@|q9l3F#=Ne6X)S zzLs-Q^{QnvQ=ajy`?u6A#IGXImcfy7Un((fD{cX*ea41{fIchWYoEK6Uhg|4$;(}3 zv-E@#n!)aDsy3erd{q zp#JDvmx=IAgoZYI$K2>oUUbRmE5NOCh&!|_yKph}@!5`B_31=)%ALLut(UX+JPgg2 zsC>;jRl@o%;cIo=K-REZVbd9ewZ8IQnTt#09JSnBThf##QC|H!u*$W@f950otIWhILdKE8BM>Kf)ZM6DXJa^fbhc9x|4w~NT)qk|{PJ*pDCLfnFSB7a^ zQZW=3JuazOJLmysUUhwQZYB0k1Y0-4UvYA|P0^|tl=TD@@)2f|nt?91k?mF_CFWOg5~BP=!8IMe(>u_x2kgaSGh z0$XsWZ9d(dq2R9a6vQ??F1H}`EUIueoF)Bv>zC!rXBc+->IAc3ceeJ2Hjm<*?`qHMRH!Ry`ipP5FUEbyXb|82e zukkd8;-T=X{px*U1^fHc>5}eU*l>MA;nh+by*v$*2J)h!qI9zFS+-*8NkB=X*$$QX z&|rkfW}|-Isjk4p$gk+hW;fpJysCa4tq}8#s2*uMC=eSy7{MJZztNV|ih@Kzt>De> z*11K+RZ~&mqxK!MJYMNn!g^TokfMf?-VHvko_E#>cbnacyJ+wk7pc<=0r5`htEJe3 zIwp(ahg-h*IdfmPnS&nEC3(3aFpl6CjQgWtYkg8Bc>5v)_4Ql3*DbmSI6T^`OG8x>=@?=$trasxsfCTG>=86^~}Zo zN;l-6>!^S5`87#lPPf~O0lzYp3m*|8>%rcv;4Yt-cfW5|@601Gw{9i*z7wPm&juwZ z+y{a*^ew%NB?=uSa>45SGQ7dTKE8p;P6wVGV9S{z`*QIfCd_`S&Gp>Z?&jNu-82)D6Yx)Yls)N%Q zZ6kElG$wSY`)ut{k87R9&2`uFGbfqVGcf15nG}Uy=6X|a&sdivh^P+wZNFwOjxBVn zT))`=bVE#N{jI`XrA&=N7@{K1y0{Eq{7iVxczfcOI?kZ8<{+bmbeiOqX^{ZMcg$24 z?d?rztxE7-zwK8Nf%<*I-b;43>TSLJ=3domYbYoJN0Q)sH_v-Nzt&69s~{ZE&4L#W z>Q>SO6@){340H7|*aMInka!S|*c&}G2J)&`m47ky;h`ITz$o9%st)o%t#Ux}EqLVn=W2 zjufS-u1@Qw=PW-Tc(4}m z!ZAzea1tf%UJe5U8si@vEU(U>Jr-FRfbct~E`ilZE=xBjC9jnhk6KZ0|kBFv} z!LXR;nY4=7J-%&TEv`sGp`*P$#C9exHnebYy3VE>=EK^oU)%cGB5kmykUQO?vL|{f zb(;U(WTBSrE3Ug!RVp_uH&#uf6mD_+_M(^Qva2c+?X$e}E~Wy0PxTqQl1!7d#wJIq!i zuNuXz_BDz3a(%HJk|VI`i8lnRjGpz*S)7|LSzOUO#QyYdFVE|erZY%LZOiF-8QpS2 zAT8e)X@f){=P=^Mz{=l(=qH_uORvWn32^8(-t;g~1vEB20F994M>6Ih$UuS8vquWS znx*)l#xc2MYrQl^cng^_M9kA0CgGwzsCX)PsJxFbz&`3aUvXaE+QwpILI3Bm$;`_k z+zrMa7flKYh8;!&bX!eamS#t>&a@lCaoS6pxhJ9+2e_;;KO<~c#eXIY9Pdnzz3TRRt*T8U4U*ro&e;M;=Mod7`_j5KZ@ZU`?Y7LSs`uRr}J z{EZ}K)~1Tj;%zEjhp&iSY_5^VlA=$r>im24=S&@Tk_N;2!(V!&bB3tNx6K;`Vv_4r zw~dRNBR<`GETq5k?#d|&TG~ecSs3C;5am~atto!x(Xyi|pI6%yH8zJ{v!lCJqAw|%uGtK;+@IW3*gIr+VaJXqaz zwkty{bPbQ{t_N#12{>5~AAI&zZdGnPc1^Eztijl znNgiy9VnvI`&7JOzpJu}Car|l*NbUQ%;895+#%W^*&zQRc21<5U?yZPp3*xfHTu~v zWk_Ov>4~&WK{_2^U2B*T336F(s#u#KJzO`Y;YpGTQ4tx)V+b=b=~X-H{=F#uVWv$#OFac*Z}QgWInQ)lV-7cEPWjy9wUs>nP<1$2uVuB( z_Um(tL#~^^5APV`W7}$#lV-}I>u;1`FN&PXU(0{ueNCg~Ggz)3fq_iqI)bl-xQ~1| zu2@1w>>gt>q|B*3KQhV@{01}hC!g#FjMfWL`7D+Bfi<}`JrgrDNuTUwQ~B&-1nr1? zdDV{SyPQ`4bF3=wPPd)GLa4*mTKSeF!F=ZY?fF&a*DItN+VdN^d)zh5YUtNH-{a!g zx*unpX8;&B)mERp|KQ}7Ma+~g8U1}|H$A3lWwi`d4fLtAPdgDR@1AZ>NHDqgqy(&U zTOR*gBVaV7jL(Xa;&V?BATlB2nY4!s6Fi|xPoR(ee*5^tkC6CGY5v;y6a1y3;z1V5T;xI$l7$Oa zMWMUg47KaNTz~D?O9;^) z*Md5|%NR}2?|vCqUX=P6`Ky1J@j}uC3$NhXEDmOvyaq%d!mrCUu5_tGHc(!O7YUsK z1F|(euw|rnE>Ul)_Hpx&zM>D6rx?kqfgwL}RbQ`Uy-n`}(oX5fGE*MqmiGCQxz9vg zn_?jVX)-ZW1M3^5rlO5uiJ>XP(Skx>7jj3Hk9&wcBkRZfv=-5tpNbI%s%e*5LfjV{ zFhWMIn{%&(5*vAv&AkQS8x@0fhO+JRlN!o%Zsk<)c5UA7F^bf&_1srU+Q^q(k{cJz z0N>Irzj>`Mn8;w^JR41;wW^Sq7md8SNUIlLuSk06Uj2dai1UtGo3lU!i;D?y^F&Ft zmMkz&47^V}8ex~koLCigk4SUYrp?Ygaac*$C%u_8-E zp*-anOV*bWT0y&2#B78%Or|gv1l@c#mQcbH=v9!{;Z-F`JX`g{uGb^GZ#akRp~fD~ zOJ)$sL@s&zYqWS3WJqn=Im|iJcDAnDWfT^whR$Z5PtNnJs2au@Ey~wIORaLoOSsM)+u4}2t7?b#r+j6frTfoS?4J(@*b2xwWt&Na4tN9vnsC9U# zFTo;pkaFlOm@bdBzO_8`DZ=ZDW< z*9R(xV}TP{Aq}hzw>;nqA*C)%jBBa?)OyL0vRv=xugm2ffmShFv+0WHL2N&l=wDsj zfA53FdmSGn;e>DUMqb8s0Ld}NC2;y6-Sgas@3I`~gG2&CkQ`YT;)HQ^Mxh@V_pzMw2tAJ@dcitQs``J6*Om-tQ5`W zjXkNrrb$6L9?`e?`S~{(_bl-W-G@g2~E6@(h8pW>NQ;HEr5AXp??VjIVVfC!BH$IKDfIP-QFHihxc7r$qy+; z%&u#LJvH;gRYnys9lFcv#OxRn#j)zXR=IgcDA_lT!Yc@UX>lSU1v8U37S3AUdC8FI z&<~*@50%h~qDz7y?lG+*;khjPOoPjZ*;r3hM9}{rJXX)6{EnL|WHwNY@Z!uVAA8%h z;aeLaM#eV;7Qb9oRI`+~*d>eqf1ozS==hOZ)o5#h(*RBj$ZI|1T zdd0{W<{jsqx1)L~!R@C%DUh^%Ud)p*h0gRtC0(|fNR_$B)kU@5{sM!c+_i3nBs^>i zZyZ{tT|elLbFKzmKOT;eTa;~V6t>@f|NXi8M<~5H^S5%8x)7aiWeC2Hm#ni$_9hR+ z4!t}g1nb=xo#NxRF|_MVufDFEnj(nTG{Ccd9zwu5>k_QmdmYun=*Jw7U->|= zz`X?+`fi-IUqEMxNIKTqp_@Tb?%Y_QSa@#IZIy*)Hn|ort)eb$?M&6Ceo-FrwKQ5% zFEM9MuFcy+rYg7dJWWiOOmmjnzwj`-9iFPn;^5jOfB&XangAk_hRBhN3go)qtA?{T z)G+ne`X0!6n*_N@JYAcwy?L?LTK{d}*7^BdzP+tg!|-8B#?cIcDMCeu3m)DG%n^=>F0_j2=oS8iW1%m&gzr*~&m> zM6PwiAywa}4|+o(O580d$+j@WKaM_RrUNtGVIh!8w{bXJZX>tnYy``v8R@EMou6`{ zCaOZNYqCN>c50r!e`3sFVz|AWvJ&f>aYtF`y$0slW=j6jW>8jEmiv|(zo3nGrx#*; zs<5Vgl<$vqN|)1h4Yv-E&96czpQ1jo?lsXiv?iMuR737nF*#=Yz4~qDMnXz)zMzoc zz^Zdw`WRJ(1H_h5th#`{&In<8v){bgGGM-rUgvQ#?Ffpa^}=C{hZ`_QTXvRgY0)y= zCi6mY;FhmihgZ=0R7N9%!t<^RlY@Z<$#Je!9n#&aYN~PC^J|r_7gaG@n?a>+Wq~&K zLY_vYdFxjoI1OLvf0aB`Rnz7GvOYLJ7Gm3wA3rNJYc;9Nb-BTPCCJ~TDj?I2XY^WK z%Cp+|;RS;sHX%W&o`t^1bvtW4j|H+M!0KZ1Ee?@2x%J_g;!1^NiGx!YzrHuc%F*ug zMmRuvtbEjyXPk{;JjWl13CWlD-7z6B3_?yFr`Tn&l45#*{lZ|F&Aoo3uM6h#G#~h^ zrQmz5{NB3=4YOmf1mmJqhAM>(mr*44RLd$XOl*EpBhNmmUErQD)jZJl{IMkqpmtop z^M54_o_@4ky_<3zna6>kLKNz-77mMBLtghAc!Ty6($J7mc_X2B(+PSyw(v<>=KdoIvV4iVcCcwzmZ<3-yOQr_? zs}^^Hd=hAfhbRyUSemyHn%`1;E5|Ri6>)FbW@;ezWoa5sa=}b~=EkbchgCbO*i7@U zei?TstFqtBZE4sHx~yIs{ydzVP`)+oFc^<|W{c)@o}b^M>Sw<< zbWJijmzr(@yFEzapyzG2q?JTTrE8CA^;%#K$M`579}(jU_SEiPqmOXdR5SfK-W+I} z&u2(K+S97XzdYdP*Y>@K*;tHTPqJ4*Y4h5o*S4wiseue#FF_&(gqPT)Y$e)$osc>Q zsvK=i^4v#=tHp>RvPy-?k6A||0IGoQ2q0hJO7)<>f&4iw|go=G*QUhiLOW zZWz5oh6_9zDlyj1xR>S1v~|-Q$zmqg7Mu?%B;(c}it;-wKk3?*1UU4snKJ(fj!SzI zyHChCH++S$CLTAxLZ439Q<_lyXUhZ~aPucBF_)jiXILKHqCD8_sHGZB04-T95okz)>LBPK6S(-;nH&RF{@9uGCS>dSU2ZRCuH(Brp- zn-?mLi1HA`hb7V2%KnfsW>8n}w~^5(m_T?P%fr_HbicnA3vZf3kdJ@pL#3gI7bY%l zX;#@3C(xUrN2$2teh9@6yN(symEs@J24~+h5_FxdjXm@wOQ~uvVT5OVRX}#{5XaEc zFz5W%@Yf+%GVeyAZM%L9+_~0RaOSY<^h>s`+>Mx!=e1EHm#$7Tr7cNIW?cav*NGY$ zzS19asOR`MFe%r~zW-V0)%ugPhAPLX7*ni|Eubh}rGKv)?&bUoqWSm{L7$WbAqZCm;NVtTH)aZRaqT~!*0c$gvWdIB?Bak} z`+KVdebD&a#_&7A&1x5Q4L1y>_=bdp#6VxiQL`BFRYWVrDUIA*MTVS7kAq0+>XH4r$fG?cAwcdl5*Z%+FUvRV2NdTkEDm5|YWq>l5pT zKToaYUtFok+ma6EB`eYGK`NIund0wB99GMgHZOX%JgJJnggdp36}(tq8HsKmE8w~B zouY5KW*i?^lS4msVghTOK0I$q+2csMXv8*eE7tWmr>NAZbZKpA<%t^&mmYe7wX2ON ze*+9p$Enx*4VZh-mHI=QuofetL3OZ{pG>U$#Trr2{H_r=;srTzmYqW@jMOkuIou#EIEddrK|-A!S8B(sYv=_g#xp z=^3dImL?L;+-eczCMRa`hKUL{Qs=7F0^THK|6OeI3zx1iMBb@>VX~GNB99Jd?@;fe zDnwEPFo__UyUlGUmE7~$z<{p4)v0T5qR?|a<*c3j{_iP0?HvA7h`NEe=%N)~2Gp##;_ z<0c&`5Q^ZlZ2Q79EWQDy<0T4#{j;m{!^^srMfX(?$x3bq`uUV(XD|1fH;Sxr-?S#~ zkE`)AE+d^4Qn!=wo+UKVvRYea8*=91S~H&G+N9!XYyDn;Bm=$*+d-d-?Dlb5-{T(`9e*duFNCqpwkbBPVW_p9zr#OZ zbWV0_b=78b+nsDgOyy5fT4_~LBvIs6N#W{sk&Py2nwb*4Y-c2pKYF}Fy53{Py-vt( z^(mkXz2e%0RJ+-0!zZw5Jn#HXSn{{*m6{mZ##AnHX9*4CeERr)6uB}F$Nrb?zA1A_9x zvex`MCVVBT&@DDpPx88KG4|?op;oU`EW?0n=;=#x&FPE-qd`_1)|-4#`hb$e!*b7@ zc|h^gIjr&J0P#ewpE`0)M@F;pzi_KoC@(L0q9{Zb4C2{Eflst zo?DQDr2Wz=_@(J#R>mLxb5WFOn{;-E#HM84sl$ zI-T2OCeYAnU}e=l{bQZaB`E7X4y2BUAQS4fRV|wPi)@EGZtc;$jEkZt{dh{&>Xn%!Gov`XU zATtJGO%knF+FkvXed$ru^*l*tbn3U|uS(@Kp%;w2&E+H|i%rd4$M}-3F@&TXf&{Hi z-z|Qj=O?4VGckV#fcR{iv?iE>q)cPiq3)oDyyH+kssA$Lryfs~00`FB-F+34I z1-SO^mz@17CB0u~lC*o!b{ogR>6v&>EVg(`Wc#+$9-xCO&x8DnTJcS7#G6iz8Bje{ z7CM!-^w8VnlG#$5V%1{bQG@xwt-e~gt?uXdYLT{Jr0N%!%~ z2b4@)zxY&0tbEU-@8VsLt0DuYg`e3QU(L$&*YZOs(}T>zA>RAMN9z=h-f*Z;U-bZI z>RUeC5GbcNNiFV=Ptvy`TnA({DKaJ;Mv}FBX^%x}y)T@)@wMJTk)CI?5dqbL7s@B? z$t00v4K5o^kC2uFWBr4IT9CG(o{KO}Ab;pQ?OHW_S4HCf;3pOqKY?sz@t#1k+V^v= zy1T*aO9>@kr}kAw@H(%r2`Uzs$=M6Ff43Q-QJ%LO>$jbiv=#4@S5%Yto&}7Nc~^f^ zY^7QjEmGf7(ECkNa@%;$?@eckq<8}Vp93n4kKt;lgM2zm^ch0tTSeX*o?x+5fBu8M z!>fqTh56Fet)HdiVtzK;l{(WW0DLs_OayL>XFuXv^UR8`vBnKCPj&!%xDu*x?q^Y? zZL`SDA#TGSjH(HEoc`RUW4;jqvD<+I4B(N7JMY=?GZ?LjiP*>%zZMI(>*0nkgQM+K z!-c~SzrUn1zB5%N zwIYjoaFT3xfLouZZS;f}pK-_2#iZ^3kFxiUr}}^Y$B~8xAw^}+lo2Y9S@y^-vP-f_ zc5%=$vNDpr_m&kxDMGeGBFe}(MpigE{I2Iwy?VXApZ6cXb9>!hH@C`pKAzX(dR*gv z-5=K_*=mUPpl~)oH@;c}oLFwCJ;dd_MjcJT_LQfr)o52d2AplkwhvwgcLw3NJ^CGA z`9XZOx9!6Ri{0x&j-IG~+g#MOYi7$OYc%M4X_fV-hmbPIDHK0a=75$&YP;;k#>t** zxif@Vn5w^UTD_pv@#WQG2te%d&E<*TPvn?Ibs}5~AN%r#5XH8mM*FooY8yV?h)YZ? z6hXJQw}1M2A7JiP zf+NwRiUxK+Rtq^s-Z`!!L3{6HEZnRH{EWfX*~A|o``r!i^4vwOaLFbeEtbJC;^54@ z=y92=6;tOwYPojl$%xyBlj3(vZ;7eman5JJH9o~{mX2v^Pe1?Yr6)FLq&|#}&^sE$ zX%uXlQn|zpLy}}g+l36sj*$5eh6?q66n=5~0P8u2RVu8!mkw#;iw@DocOi_D^GmE6 zk}b+FT~lqD?Q-J%XPT(%IMXlDXh@zLbo7Xu-v^PxR^Y?8pDFA8*BEseD`<3jLj23C zzN6!|o&ayq@j8KKl5aM71Bx^kzxEqrl9*reo)`@6Jrl24&0WN;I$(%VAvQJ@f)1#J zO9!F0*;`@mk7r{Ze}C0{({%z#w5Ojvd-g{8aGb8oE zOK${v8l$_mp|l>M^A$(n;?xMl>IfN6L=Jp}l4jYPcXOXlmAzRtRhD+Ac{WnN9_wG7 zWv4Lhy0+t!rJjZFX3Ia!AoIg!z!};q}GrB|YhYDbU4FAZzrM^b|v^oiwGaRStaDtc$5{ zPP^GCScR)*f2Kya9)&)ex8`|!_}ie#8tHpyzFfbGtQ#;vK&PVI6Rr@xW2`sd^+MrG z!T86M(!AeK4>q}U#4w8-y=G|Gc8=fFRO_b`sEI0mfr`$CxE-khZhRg{ET0wf%V*!@B~gtABo#?|(g%k}pu|IwKr&8uj7{b}&T<;1;=!?tvKof#Pzv}`XE zQd~l^_)Ad;ll`)`ikg}=kd|@?d0qV4w+nUGo(MOeHd+io*f&+{{Tru)Gfq1U9;YrO zjSWSt3+tMNSoqnI(o9s<=_v#xp{{c?7Br5sF+ktgewO&TPP26sU#-G9mmO@Wmih#z z25yUDxN;M>Wr&vBhWy@M?5E}Pa}O>6o_=;%?MTSl*t|!$3q}6=D@Oy)r=^R)mZ@=A z)qnad5n&BrC3)(6)*+Wav8@z$zCExq|JdMhj6F{4O#GhFb7LW+5aH*n;b#_#&{T;i zy%+Q-f;YnH7(Ft}ppOFfupq8~ghpeC=ZAujFEA)=ZEo#8XFsf+pvFAYME9~9kwZ0@0`OJd9Q|Kz|~3*oiVf4Yh5#2wi)`% zyt#A$QNmqw+mid8k7vXgrx*4=Vf&HzR8oCW{N9hLp5F$<{3aNXQ$WSh!%4J_oZ-}Q zklv(nW0`PPEVyx`Y&y&UD7tMD-p3yn&#AZFAE0`^C~hLu-#9>ZUcOB=;_`7 z7gdq^Erx*ex8IvMZJaF|cN4B+&9@j2?_^;qHY8&j;#xmEdT@%ZAx&c&i|C@3>$yBUjU^%Mzp>Sb@%s&@f61epuDi%8au#xJg`_{&!A^Ov+6}Ym8k(I6SLa=_<=-}4E z=t75$a|Ebn)WKQfC}7Y95OBB@VIGR%bx$vdAJ{e42L%K>%>uNFr=+Th*!LPJ^oV2n z=?iV1HAB7VhtYnWlLO;@`lu{9ESd0e6e$DB;|4Hdc zO=`;d6x#=KildKc!%V^s#lH=0e`NFF$%5S-F-Z@{b-Ze#XYgdHm$2Nz+4ae_yt@fG z=lb(Ruq9XX^`f@WjeC5|l%+Uf zLnq-uBTS$tWu?(#Yx7wREuV{+8-2F$ka?gh6#4)4w4(DZNn(56JsO7M-w(c)9?r_~w za&9WtzB?q^hQ>EgNFKD+(KM_yXUY=eO4O$|`)=^(P z%E-fwJ=>$m$gL#I1-5W1=&H8s%k$L>n!#NTDX1VnD4bd@%XS{iuAQS(1}byKYSZ(D zLN%G*^t-yA`d+$G+I!33H?3-whH+mTd@Zxo62zKosmly$u53%WU$lzwh*US6srtAi zJ*g~F{c*S)!dJ@n3nmrTbrGD#j znYy*1L@9NYVJMD~VkY-=rg`bEaqIM??~@f1K`TroOOJ$QjGv07k$#R5?EKNBJng4J8GbudmXLIj8iA@%{xpcQVDj+pb~DP7jc4 z%sB3D%x$n_(3r{64pMzjmO}O%*gr&U2k7rl(C*S?#>Kx+tC1--Vxk$!VoPt`%jj_! zcjKbu(u7lUVJ;a9-p|{EnOw-4690r-W0>Qrjhgh+p@aURYq8R;ww+>OcQ;}pl;TK8RXsIb%G=FlSNW zHth^(-r#^wjDy0C9I4-O37b`1>pG{{##xgLI~tI7FJyN&u0fr|OjE*^p5^6jv?jjm z6Z=xZg1Djo;x{blNol!XjA-3VL8Gp5>spec9-8?ldz~tVr5yV-aSPtZN-{Tajw)yV zRZQsnLPJx$*i2{LlIO9q#IPClFAhx)oSlPiR0cbEm6^33^`ie&vWZVN`?@O6ws+1p zjN2VM^WgQqe8c8ogTy-7EN3?=>f&JebJHt@ajY@k(0iCjs-#mxH~1_Q4b1!Wdf(~G zY^*?%P3!YT{(_=rz}vg@kpUi(vP<(;_Z4(ln2h}t(HFWH(d*YYYU4-6eNKf;u#B9M z*xpFozUF6Ll(*+H`_o{>d`&6qSx^TiJlFAFWWr{8^S+3|(PwG%kKMZkC+FN&OCiYs&vuVIPuJ$sI#Vx?}eb}W8+Np-Cb@3JYunQvqv_1jo18vzZ++SJC%fLf5a#Mg zMvsfF%^GkigRXFnlH)vvycOUGFI*1kK9-Icv3((Fi(J?P8XJ^#?`V|C8`CgD;h87>I85M*KT+rzC#Gkn2e~9#pYen{P_SmZUKHqxHQ=5XzmcZlXgigE~UIamiz9Z&HMx%3EK*`q1$p2>a3!~Q08*5bV@{QvzCd)tU+ zFaX`!*d5pG5l~@y@1ca!<)uHaIR)x#&mK0w6&*9Uk9*LR;GMh2f#V+a`rKLj;ToZZ zGj}8Wd980g6m1#SdP?iH1;{d&d~OHyf$C0F3$^>esp|!-8aB)$?D|5|2`n}7>IJ(Y zIP_*4OA}VLbNM%C$H=nktT5cBp56Ej@Y7QGH_m!S5_$>px9T zn4eGFSdN}T=`8n8W;dc1>bAitz)<^#XA}KW9G_B1teZf8AC09efp})z&!4Y67!>8& z)@(dvhFq@1pBA+8Y`>Y(d)-F$3|b{BqlfCN{qEii!4#*qJdShaOGq2;&$92a9lSSG zar9eePowOK)VTq4U`&VcnqSIt*o_+8hRA{Rfb7J$FB8Y^3^8jP@=O#qxK%mSYEvAg zRyXgt+TVjD&`}4EH86(epL$uiS6_n6}6`p)@Xa7vO!UpX`Rj*c&e~kJQFzNwn zD;ESgR(TaT`gX;U43BWqy?fYB_7jI&x_2=lAmTKKqVu_nY37uneB-hVYMTCAch2HI zYp>6_=SVrH-S9|LVk%t$>+scUYdLXAguM3^mwj`fs>s0@##PSS3<{B&;qO1*-5g`w z<{C29;dr9IACCG?Z05k#y<-tZ)jhEf(jGGpY+PDau6D?dJlxf>fBe98h4Wm>H<^8? z&hqnjLYJQdDbV&IHC0+0?85MlU1$U}lAYB$1zIIdh(1x-n5wyiTi~J=y3)Fqkapt( z=dk-Ey=iq}EiUKm$o5tFM(h52#wW(guyxY*d1?XqTi~YyH?)24o^~hiJ&M(nSZ%{* zrd1W$-FqB#H8E+k60fE-QeyU`7>>EHac)DwK2wS0nZ^pm7W2J>!qmM=c^fH-9@_Ff z*}=sUmj(Kg6I08#j;z~oW{>7=$Bcy*W2Wcl&;Rf}g0X!2gS@Y7v$CUdw8_B|6~$5t z{{MUb^+1$!^N3nwq5O1Rez4?7xiQNlbmPaFdnk(FOs#WUReLLxx9?Plm!cRF=C9mR z7^rg2HK$$T?-PM)bU&|aL&I~37sVZu^|oP7tXQOc zbs49Q&3-R@ln1j&niDC>CMxXd$=*K6Z7>Y5r%pL9t@{f|4_)b&x^n~x06c>r0N|Ui z919i`+iTzC{_Z1`HB7~8+aJ_ksr1pb+TA@_8!!dtEqE&~nc_w*G5^tYdLh=*=*}A@q+IiSO=K6nY3AY~Ew$e+FnDL`gR98RASxl!M^LfsS0?TRQVN z%Ee$NjYw2}P@`ze!?Ru{CiTxcs%~|#R0g+EuC|LVC?q`TpZ8@%b7hkoRm1hWFzvnV z6|3@C$%`$ZEpV#YJ02}(Cx%U4+R(4CJJ&av9rx`uK6xWdEXo^4j9-|aewD5)3_7*f%>)z*Bol<3i zU*!KW3C##gAJZ;p*XD0iIv0$s`UWv2yyHwF$72^L`n%#DK~pRv&t}Kurw8XaL)i5B zvoGD=-e7&Lg+Xx>SK0pTo>_j(sApV4NKoEvl;f$Uhwts7D>Kv+uXz=o^Pn17q!P<27; z;ngPn`Pa@CbuAkVR`iO_NgjIJmbtwuXuax#Wp>sV3Itbed-P>2DF>H)V~0O|;?DH{ z<7i~S(GU?u&{0Tk^5eJgO)zd8qWd2E*Uax6zeR2a#lg*<6vi7{=n~J+yR@w=>if)u zEr!^wqC(MJh!P%CONmRw&ziFvM-X>j8iJcK^)-jZ{IBk5QMsNR^>vijG3S=8(EU|r zd$*}!^iNy!jo1o12C4f3Jp=U@2UxI3t1|WT^`uuxR7K~6=&n)s8#o3HEjs$&%Pi`4 z9;7$Zv~iv?Hm%iZTDPI45((E>hTeV9(X6qe{#5vRVw`@N*5Tw;k+z1`%$Ah~sS;69 zcxG*`I6Izi5=rJo)d%Kx54k892-1&s~opd*tYo1J(HHtSfYA7 z|DIaVjT)DU7s}p_?|&Q>%O|fEs&U!CGUWB}E0sUd^L>niE}z=I-MuKd1SEmp6sAau z>4>Cj5o$kns7wHH!jLtq}QpQfSEtTWyE_OEEZL@bG( zvh=gTbH?|n*|Uix{#4ZWy%2VAQhrwQvOqf@WuCkfi)LbKZ&x`+s_)jhZ}*%7n|5!^QhlGjaAi$t z1KX)I)dA6sk*!!MDr_!SI+o$wW$dneW+QN4S%!KmdbRQ^=E-N%XtA9M{C4qH82Lb2 z=D$=)ouEpvpU`wiYTWh6ubq8%e$Iz)Wn*(vlFxP1fMkB()m(<#oP$?0tE&g^T|LyW zVHFRWUGDyk%1eS;Hj~95NFD3QL7g5PkV$c>@C;io4s8x+U}JW4+G>)lY|DF@L|87@ z5pGML$Etq=Aq<=yJ94-e#ZBpK_o(yJDw7%FbWwb-R>H<#(qi2<%29c_+p*eGUMW)s zpbzf-i%jh6JoZZi?=mL4?1~CLog}kcvmH4=c?tX8{Fqu)6>s@w<=B^L*y?9gxDngjC&3(ntbjn$XU)hj_s_P=`hzeETP|Y-rV4JpCbNgo>~i8saO1) zM4BdT-(XH?a6+U&jpA)RyN4i8NDr8nM3GL1TqnSC#v&E6$C$V9@)H?}(rDNHrwuO* zYkU)J3!6;o6G;)1Xlae=AO}OaBzhi(Z_s`}6V8S5{46M*g=ZFy_S2M?#Za8)^X{2( zoGe2Ci#f4m3eO22 z?eMk5z4vJcZ(0`q$hksPnl(iR%jQ@;DYntPd}1-M*n3Mk;fWq+-5B{8M&rW%H^#mJ zSsR?pAkt0{`5gA!3`QCew(NOc-~Ej`asA=J+z{vk+7^4E)wAx%!kHHHs4#4aTve89 z3_IqvG3QFYZlgJev#YD`@I@UBXN=6mLWra>dq6>q<>o4xmG~DPpVw8N+~4SWSy*tD z278o?>OI%R!CdS6gL7DHxc0I9;I;c=`tjZsipN)7hut|xh56;;XR=mho&B!(ntZzO5scD$zD$^ zXR*ORnYc(jL&T~Oea^a1bfKofcx_*Pp-Vy$CS*b;dD9!+*q#0P%hp~o>wvFK&*^?D zhElEBnx!$KoD^yosMJRad+zklw2~T2m@P3jqDZldBK1=v)SRkr6tyh(2g{~`nczQF zll=5UYHeoE`fd6`2`qz=M5g;koN2G65#SBFA-cXrnBs{Swa|rk^-7w|Z7(syoORq- zbP!A5q6z-9>&OHuFtaJ2dgjZDU)G6=V;w(aWU?D*X!Ey`R~vU7TAb-D&~2RzVJPL^ zvzF-U%CLp1spv;c4x}vrXNAq(z=mAT6eo)3J&xVGW?c4~(!f}Mgm5y_Tbyvxsz)!^ z11Xn?>DtuoGfhYXd&0-({Q_4g3POnZ_;_glo(K|x9*i@wZg>6(GobXKf5z76`AXg`8Xg$|(eEo5`TUu_%b&`Cvw)%I_1E?KJXwrkwQ7JnU@vkW?0IMeF+ zP|%}fuxhvIX*4ZP_VNTLvsYSSa&+61;e;MDeRWRaN$bLq@eqcX_7Rp%{N%$gD0fCz z+L`=1!^aWo<}^I?&F5DWecycKO`fUQ>sRfSid*5)D@k6xqW$^BBBhb1US3?YOm?cK zCkoHQ`Q%UNbLKz(N+BLF)N6alp(GOtZCUweeaOyS;ZTj^GPSzD@MB|P^K57I4eaO7 zpIf8&ynfDANPh4<{}D9#h5Pb1fQ_>$I$1{h)>fd`79bZx%Q~+n#mce@3l|hV4zAFq zs(Pj}XiAouKj?yXAzdC_Ly9@dZ*kfi5LomMx;l&#uSnwY%Rlp`%=ZsDn4?RodA zD=Sy8#0My>4&e{-Tvg>r>D9UZ>ZF@G=(Gp5E8eGFyV&kt`HjUmb5f^_!=7~$ zbhmcRKj`t}a@NkdVsC33xhzY~PwPeq*!{wWZ zv#S@!7}tWCeto}`d6FO|f8k@Xw5plGM~#&qgZ9b^%IMYPV~T4Gf*Gj#eG6wzD6wwZ z#S%B(?h`QwVJ)LF@=07M8kHsj4&A0M+(xU77ANL+Taxz(+^+sES^0>}`Uo zl(MrqC5jkc2YFm)^qoFidm6U*aDRA>BthA3glu4J^swSRn4v5?dNl$B#6fs3#E-eDp?HUf-znun6-F`jDJ{vj6!$0SC#+Tc%FWLf21dD_>u$_&7re7}=ff*~Zxkn-t>29qqnNt~&L{KCRq;lxBHA9qpf-t~YY<5S{u z#dlY&YA2gyUb1HW^+XjKEF8rClP096AW)e@QoJa!8EMY_y}M4DY_h!fa~6B-uj=)F zYwJQr}{ytng z+IRyCckTY?qMfc4nfRO`659j%?g5900WPT&9L%CPzS-XW`P#!Bjs9ohX-OfpXD_MJ z{q}MMI1>?pw;#d9!R6UG_$(|$b-*7Qz%dC?^BAQTNRqJlzFf(=FW&p#-`$^GBv0e+njM~A?K2G{|(K{S_M{emme z5RT_RFN4VEUFWp1h}r*r?2*?hfd#B&<>rPHub#CV60ZF^NjVXmwExdh{Pl$yADqGY z{|~Xi_axcCMv22lK}Tzk@DP7D`OaMg14!7Toh4~)f&0n~{O!K}Z6E#!gz~aU*TOyl zCYfQhrmvYB^W*@-=zv$lg*Lz{#Enc!kQvA{?b}*O!Ll2~$ zBFm!GsSmG*nG^d|Or|MKNOJS@ZTUXO%kCIS?PxR<10h=VfNx%?Sq}bonB}Rk(^My9 zaLWY?#PN#i7f@9SirkF9{6xz|h{hxSMC0wz|8b-NA4<$xZ@x90nVI=jdL!Bm*$wNu zqKQXC2P@QLXb4VpY#JJGOS&(O0|4*lx|T3Or;)R@^>cwy^k1EYA7U`+c1#r39W z#KM?-F0Tn|@!dH{Ei##s35tNP-AZ0y;IJ#YEe|Y2!hru3W&@vwO7IY zOXZ!~{}VH-tB{`*W@^aq{I#XyB;Yh;gnVS{Sl{n_MPGGwwdCe^>47E@H&rG8JMx-r zU7urzD>s@1uhL(_q(6M1mnay0Y3a)ElgftjjQGcHpltsWByw>yx?Us)_jnWZ>LsE= z8Y(7#qL#<2^YeBK_>jOEQcW^UdV%uFmWA__ee{>ZugIwl`L0w4ek$01>QQeLckRSG zEq@a57&{gxL;J3^b?!d~y)*j7NmE31kq;>nW1O|LwhsU5g4kmSoru2d0>iWKoX@*g zU^NlN*Bya=ahl}(IDIA2w=*GE<#}jw$tjiLnWU$P$LMlZeX2ecd}7>ETKr^|B$y_} z2~Um|TcKo?d;gD7h!^`0;&3F~cCftpb~O?TApYb#F-Vv+wtnfiu@)0w;R%hny}7;! zZ(i6Aln8_n(RY?7@d~%Ow=Q6|jJ<{PfFwDOM zz(N1p(mQSaKf4Sneyc5poz+O|#jUpE(IAp~Nc53ocH)Aa!G71n$||5zHvruI2BI^Peis zfUl=VIa!#Pc*p$cLlsJ{T$qN+0%tH>TCR{F_?m2)_^rsl)b>Cm0_ze!|H9%JUaOIe zoj@~a%NTG}u6vL65ggc`>xTOHsz?AlR33^c8yB$aYA z7AGG{no`kj7N+UAQlC{s`>W)YeVVLSIh09MxN1MzC&heH78)u zl(DwD3ghmLm4s=3PES}nTZBb*eAbFL&l?=hz(GWH+o5rU*Q;xUcN(eU?(DmN#TW|oUIPM*ZmBr!MRmM++Li4(BEPUro%|Cf7zwMgJ)B? zR$*s2j7Q2kU6erD$uY6M5YS#IG=XY#c!Bx42^YYdr&dN$(3IjBroUiPa=Ah|d~@UA zYTxhosDskppVQS2%?va|KKy=>qVN7{9+%KEphiSy($M3CKFNe7raona@+NXLuNN?i zxrMq~$Z@v7l34o|xzwW`M{X6(Qvz{7#!&C_D_DP2^;gPV^5hxKHy86eqE#X`y(=Ew zb*sWzDX`q|s%h%VMvX;0Mdh@wFVm$m%;uF~k~bk!Mas~%9wYIhYLg+P6n@2qG24n;#cJ-A5Gbh1GNmOU8raxTf)xNR@gU*(4eA&DJv^1iBtgh}}p+=mxX%EZ+ z`rB7djsH981o=iBf_zCni|oui{Y8RbT!f=`BL4JSXulMV_R2EMmlQ}=8e~^E8!WlT zd6oXM4mNAm-D<^yqss2y6D~E#pfs?4GDuASte`1MbEn$(y-#W1m zNfgrPPM(ZAXML1nDU4ltDpdvk^6(x+);1)qW01O%z}L6~{$Q&bQC?pD2HS+mhV}nH zR`#lA8F`eMg=U^dN@1ZrpngVMkg@>4pm5>a;P5R4AYtrsDkDDy8@2`P?Z8zsH6-VF zNiv4n2K&Q?xtPzIO-_vOaw=2x@~X??jYB954l#Qt3iZlbbQ3f0#Q1(v+X*uoPzeNB z>+;kY)qjpE36j@Y9zCPWBt0v|h;RkG`H{eli27rt!W9TXsKcO8f~APIexD@kCFa-EIp^dEkb9?MBAg#3Puq->&B}=KaKe#1+m!7y*tH z7pG$3?8Z$w#0a|Nsgoe#F9hZPw(c$6=j0E3711F$vYY}8z=4mZy1k`0N?Q@$QEFLhvrGhv zJMAMbQCnjAJZBFOXW`!_NnG{>$^*1R$-^a9*5-fas?q^QVy0XNB6YA(8^Cw%dMaM| znP_qV_M>+b9BQAq@HT==3Q?5R?j#i&&N!Wa5{W4T5I09mY^?q-4Kn!%!)nAExuLA&B zWwm|0p6_&hIo`E!ZlcOmjTigrXlawOjkcP@InC}rh*CrKU*BBa$!JoiSA72pdHmx} znyRc*{C*YnchH_z9!(w{3R)xrA;9tD$8UNVW~e3dBH{Z(LL~CM9$tPz`_0Ab<;fj{ zMH^m-JjU@60ba4Gx;m12J02UQU)|+gaLXp@U&elTV`U8j7Ix8!Z6Hf9b5cL*)zMf5 zGG2n1dzhXE_VzW3Si4-t3nN*KqAnkFC&6G@)#A2CvNoC}4g?`V*W-}C4g7)l*5DRo)AzBDG7x zMe(ec__U2t78xneDN@8n_Wq3)bWZO`+US?ksK0|amIL5t$UX%sc>ydyc$re9$XVs$ z;2(>ZL`;rP`}(T4`6+q{58=D?9J>88)Qv9wm3Q6CPZ&~IRD|L*-}QSXC>?p;0nR2S zLc#M*4}>(0#@B%~_qr+{J>(HP+~3bR;`$W@Q2p0ZA0Of?YoF3zjy?Q>>r93yc&9S` zCjoSlgVRa9HHMTCk&pISFyV>->jmb$L6}FtHuT1ZWEHA5~Y#F_Y>6A;%_yzEU_ItPj@W} zN)HIfkErWcWINUvr2Lhf#c2xQHd|ZU9O_4lC%MBW!{mQ0ys*#ZS`>$2&0=O9JBAsG zVJ;fjEVf8BgqN|ok!CYc!u}MOfE2Zwe~4tkh@|%#jgJ^HAA42JSv%)M=Gi`QeQE;_NvY3;M113$x2uhS!MTmvVPf6XkI7nRV(o z6(|#23K+4J2@M0=jrbR_V=b8|`#OC2_{(vfksc&8`iz8=l7+&b{ws}eA*izHQBc|5N(9rF%qv0T??&%=Oq{Dz_-yyca4m2n zHF(t9!Q|=Rv9z@{ta8e}`CRwqo%A$Z5=JddCCk&a=ne@{4%9F;Zvj>VN(NYsF+hsj z1;C;3R!0u&7fzq%?1u;NDoS(hDTu$&@~^^eldi{~My6^kT@k`VwP7>gZ-XJB-FPi2 zVO&REqWa-XcY?Cj+>*TIIg!0oSS$L+Sj5)XZg2ezo2lPeDYRl_TPom7oFmVN(ngQA zm&8Ra{08Y|CAP$Uo&EXxnHXk>9b%qTt|lW;OkhS2<3DiXB~G_HfoH!;+JMFOYsal( z`KqQ;&XR*iEwOiojf)dB4<4TYW+-$Ayw$v{VQlO*SJtm (Yn6d(WSnoBnN0HL{ z-|9%<8BR3#)*fFC#U#b!&pKy&x;i^%FuCjvq(Orbr?lLqtGh>Ots{L zM<-Q8jX{=gsRw&A>8gyTBbkfHVYqP>(Q9B~+tp`Ip@+ZUUz)BQ)v^zjXYf*!18m*^ z5dq+DAwjZhexI%mH<8HONyef`*$v4pxV6_9zTI@nibFZ)KzUP%zJo#rG7AbFlS;`A zjD~*-D3WD)Yu23An3`5<|8+4#rAmTzS=a=>qLc#;&jn3xCw}slYBrn{RZoTs<1?|5R>k=w5mldpyL8Z-u-;H2Y_3p#ElC}s#fJj2Ex zps2rdojR^&e#SYAQ%Di??7*dTnDd$R66B(3wmr)9$Z7D{1^ZzYTg4m-z5VA;7}po^ zm-?|^@j+QSUUe@mFIOtRS=5VKTNd>qo)C>Q4p z<#$p-jYj(@a!O^WpKrG_?ws^M;P-mBC0}ak%h%sA(?}qYjT26Ujh|EkdF& zo-!=|@Jx_kFsJnAq<0rj9BJ7u}G zN5a$x=vfTy7@sd^w?mUynSie8H)i4_pD<4OD04$a7?9RU~CH!(O!XVGc_Lj)glOLjcy1NAc9LI=jS-TfePbkYV zp&hS8ObXI{Hbr8Mf#AAav6jdf>qSB{Qv>)oO)r1V&>yn@>) zeKMQ9^`rdDjAptJ%&0aok<(jA*nT9Ht7}u*sdr{`;NgZqiR%H!f`>B(aemze0d*2s2kcu6-~m{x z>cBcl;Ij~9$U*m0I{ZFXz6)dij^-od8>DW?H9+2ok~w0iB$_pMhl85k_+3UF!Y;ul z2dQe(kM{Y3IZhJH`vvwtY{!n%n!fQWB_Z-|VQ-;MzSSOgYJgW`IL5s6FlCzZW3sL7 zhe0r#hrQgo6)9rbPS!Y0cM~z{dV1oaF*#HAOH#>{YzQ6J-*FY3G1ZZ7v+7ORCe{{m z6&N5t6nyiv%yj1VYK+X3V7JY;9Fr4_Jl6)Ppi5eT?aQ8|u0VwZ3T}l1UGHU&86Nqb z(*pwzo>8$~@sWvPQ1&_r%+p+5;On{>Y%`0^zQN&Q3lcA^@ap-P9HG8df$a`OzD4^4<@-!z}3GMu#P z8Z=XYiw>{qH*S!CezsN#O^-6FacCo4HV=I-n~g5#a-nzm_O1OZz-zq&guoog`hT9G z(v#3(MOe>%&lf0@_>5{k=8k>EtR=)Wj%)0cBHaF!FfAdhH*6;mTmjT3!2W~$by4`SS#hJS`6URVY8%J^tqM6dC%0+lH7{9?o9>bpX z^5wuSdRB`*oBnzj)E4wWQJvxeV~JVmP0HR2&HT`R-uc|epbHM8GO3pSGO;J@d$TlF z@=Y9RLNfORIZmZavMc14dK4VC_?|u3_;e-dTB<|ps#2o{v&kd>C53WKu8wl~fuI)- z0~+T(-Lj-VFwae7A`BJfMM&+tgGnHeMT)RewL2vsew?Coo!_|4n@4}ejQdxdv3QZ?ijc^&%3?rl^;Tw=Fo?7;|n?`J7}Hduvl99AwfLWCFCH(nemI#oDW8s za&{}7|CFYuum7M;P5YXrW3-^TYSGI89wjt)yY&^bJfl}J$7Hu#vHO0iRI+6lwu4-JrVLnM?bS{Pnm zg5p*hcNRkr)J`DM2kUqhs!5Ocg2j6PowQo^ad(mpg26+IYVVIB2uT3h2e-+PzvuuN zZm2|_b$SzkDTL15rQhKPeO&45yZX=mBeWcK|M#jbmkbT*jb`@|FL)063nWP{zg`rCl-+$}B2(qUpXmhyx* z%!WuR5-`cpgE0H%UjMZhx0(^;VK>73fm{KudE<}qDJV|1r+B#R2pSgf;dajmTq8)` z6&SIxJbBFM|H`)!YD9|NqWJD8$)B`}ZJ{MpHeHQ>x5z-2#HvpSM<2f)cB58*#Z=>$5jlBsuG(`&Xfg zu<^~7c6QI=gLl_>93l#pfSIxJ!VWiVZS!aSPeQT2uh5u}Za+l3whr}M`@OkgUs=uy z3xC8iA>~B2UsX-0pg+?h+dJ2uxR+4f+j)Dk8Mp^6h^l7*2neb;X2-P@iVUYnf#xx_ zQt^-PKzLPLJV>S@4y$lKM5KP{y#25k3}ns7$bc)HDu9tgh9+?FI@pMkhC7gj6SzX$ zhyO=@_Lm5_c# z;vYo@pkn&p_3xdRfa-4VaJgJB2GezI5kh))*r67hPg>0ht#2W?4WyvhMHC_U*SG)w zAeSh$!}MrzMqNWgLuKVwP;rF07a`ur>EqsMXN$+JhV3WHLLktGwY9aw!^6qR%o~8; zCRrec;WbB*H)INAgj&*077J2}p6UE`&mN(EC7sj-eS=w6kOA%bd5kD&6q#a*R}<2H zIUc6WMnj}d2G?GgR!+Rg&i41sg{e(2(nbKZK+562*xPS9ucg=akBN!20feM^56XYD=;YKvb$~jEpyK;~!(}_B z_1EU8oOSxU;D8Xij>JNIb>aN^7Q6I}jO1iud%0ai+UyVvt}vie1E+qg6cGHxbZ2S`8-_;j3v;W%s9RYG{|6TMYoFxqi94$RPU(IS6e7_|` zBt;|rQ+#!P5Nh90OiH>0VzR$`@1EK7BXF|z?A^-_ya*}EU&4b&!e^X#=RyGC>lU9& zdZCe{sD4Cg{Z{EJw!bGKAE2o8bTbI9O;7gjjRdp2D^)INv@P+ufZ6^zYKxB0*;XqZ z@FFm{6oHD&86%{E?1pQuN$etAC|ELu8nc^fnaOJsjTK@ zVXAa1?WxXzegI0?Ktl*y*JPO)&#`L<50#?&`$-SLGPa`M%A1;+TB+5745y(>tbkQ7 zmnBS=Wsw%m1;2Ex;m~<-f0hjsV2R(bz9!;gL>>l%-dl+#x(5eOBW@=EDLXDc4e^lK zvjf9>v;DfOPB@=?0I?`xY&QGw{H&~JExGjN($Z2PAt8lakOL89zA8Tg-&eX?+1Nm? zlMW6=X}^kzd(q8iDmtd!$5oJONYZl|0Uu91)_COLemOa6g4Dbp{`CxnIMB6LRkkRI z8ro#hy@xP~B96BV4daEt6p)?0_2D@T$-4OC+@tIF#F*!*zgsB~wGcnAUqZNS0#dvH zkrIN~04T&vGpEAuz(?v*4N$!9oTq@F*%1BkemhX(?uaOcyaAFnhCgY9V{5C%1QcZ% z3o9$VS9i;1ot7TCT-9us*|Bj-V5!|Zfkj{Sy(y4Rke{Ea2fpnH9fU5@|JQqP?LoF4 z?`ar1J5BFs}5ztKHg7*GzB2t2bU zB@zT9$0ZT|g{203S9kZNYNi3YcazW{uSmS+FsBJo#145{`)H&siGIn==13i*Q;aPP zbjZ+o_)z_#vr^fRAQW&z*xUj@({dofbJ2wrq2Rpe72kL?8#emldc$J~dlY%1;CcW)c6Fk^7`H$Be95RY*aGG}mzcI3n8UwBhMhxF9kK71tAjTd{W<$$Izmq(LR=t* z<6EBX!t9807usa-J+@9|dr6)z30&>Yf+*BHyDMtB|H1VU$HV;;4in6LYboG9YMgNG z#cWqhf>-aR(_tSeCN}hvSKrX8Rog_XwZu02fX>^rva%~KYVHnjV^8fle{y!V<#3HV z3o((>UKNw%m6a7I7Z*F=UjpHU4J4nQdjGOX#n7Dtt_xMz0_yCVufxZ$@6acqro6MN zTq8+*oZx?i#GI#J5jmimeK*ac)4IK3vcm!;kg=KUH_>?- zsdCMwqx>Kj%Tp0O@;8TPe>7}gdtr}k*iy(|w3gr^)j+XKQgZTjOwN^(4yF5$VnD>wR_!Y`+8} zi12Hn%{NhmAF`U;uXn?09NR_YIU>$>>rgxPmEWtta{)=~;ji-~?Q67(BDiM)Rac5Z zVlZ&rwa199&Bc_l$&m726~zS~+A*2p?WFILAqF>g)a41JTY z=fuHLb|=|zezo72Pm#zw&4)}S^~DRVTSm#y9HF8@2Wr(s5fK4GK87$~s9W$6jDa)Y zh&tV^L7hN$rtja|qlW9#`Ok4S2n->Pg(OBrHAXRQv7B=y+r{C2 zS90NCwM=Ll8`s%=Mk$gIv4O8Wj_6{v&eZfYA*oloEE`i_`=hK-vExW%2qWMBN7r}9 zHI;Q;E20h-a6|+}zzQl#6;V2(B1I5E0jUazC{>!Y1VlsuK~S0kq4z4iW1~ap9ip^^ z8X*)DNb>EA`pi7<`+oD+%x`AQz4x56_u6Z%z0aE_wy9L6^BWdY z|3^&GU)K)xUp-n6ll=?_{)%086I-JhF*0~vlkAbzwx|5n|F`cMDEe1`7nZRLm~qV~A!~ ztFK&hdSJu5R>%+`#7q3djd z>;_6ZMY>;5_u6=LY5L~y2hf~4&CTKY9k37l-f4gMy;t1QcgiLbs;Ue_8uv~my@aTl z0f#bv=>K~tT}0egEc;peOGu&bdg;i5pY&LNa+vgRKn^%YGvaLypjRv`EFv%3^BywZ zwC@-8)!NT?9|?$+OAVjE#CE)J{k6cmi2R~TlI)6WJFUs;SoNwIMVswEXE2UMfosFA zZ?RE2?Lxjb0{mYF=u7E|-$mYzY3%E&h+t}=!dk&6o^9JUUGu&Bh+&3Egl@_GEdX^* zz#D=zEi}gL5cM)ZktaI%b{ee>^#1zs8ykHQ|FymT{d-L4U46%@JGnUiVr0-5=v%r||lX}k<@ZFX$ariqpx=ez*zia`=nm8jVcs6OAe!U%2iEZ@vkPHXnR*3a)72M5BXOmR{`9Y_qnv?w|Pm%i^?`pv0 zqOGmXXHO6T7vTn2u1Gu1+6R^DRDlk~6d$H%9W40vK!+@=C4>J)|JR??*FBShu}}W* z8u2f<_1Z_UBM`zgq_z0{uOKBe8nDWETy7!NIgb5$khYOiKkgbMAZd1LuNiE$H@w&5 z4VHkwTIf*Pw8Ok4vc}cb)pP{ZEaPH6y_N$wh2d&(Zux=ku_CtpP7m;!vPrn>mJwqnid&BiH9 z+v8mIK>@&|f;b^Zx}Q8auewh49pM@+aef8RuoK$&)l!xtSB|4c z-WXt23O#nSMmr6(j+A@U)t(CzTzc59S4F-455)-aGTLLMKVfs~A%H{zjyfQ141L++ zlV{PHjL=QTN{|#PQhK57@!PO~S*dhAfjxgQ#=DQ!(G{4wME*{oC#MYGU{!Q2zAhx_#2-9q{sJEd{0%8>*t6e-2Eeg(O^Mc}H=gCWr z(0U90fK1Bu-XP0|mN*wl&QBE&)cgBygi?%*2t&AT^6cm6RjZek`mvH=TTs9~c3!h; zQdHyWq&4n$Oo)9^P$^eDWivELo)nE94r+^erYHgHIxiBn42aJ>hKBMO8)}3JHI}Wv&T)(C;Z|(_|uxmC)ZQ*8zrrt)Tsi>FmNfvj@ z2Ay(s{hqw zFZooBvXnRX-p1~#xJu%JwrA@u`+oup2ebS5F&;0@Gc1r%k6qzq_XW;gN#*LKOk}!X&cK9bR59>l;EJE6KR^7Ll%~&j@Lsr8uh1y^? zHfE*Rri6Ctthbj5uKB6p?D-Em+{LdZOLeF?&M#3b3B+_3>?hTC=alY0WVnV# zw$#vAnWR~c*;CYVlYk)8dCR_U;hB z<VMFD@=-ba|c0i&S0Dt%ot=yC6fF62X3L(w9FIS$Ieft>e zsb@%{EL{B?9-Se6P1dx|>>dyYADUGD8WY`T;amo|rD4;iFL!@N)DY^7A=P5pqkqEP zP;v-am3s2@XGW){v&As|E+4oS^5g!)(xTrZ|I?agP;H}vw<*t3+e$cOL(ipF6{ZQW zZI1NxQKo7$Eq8%zKuu}g2z2;L*U*xmV+hayZz3QIu%dy;8~xpU}=1( zcxm;*o1Qa$Zb2%7*p9SatbHKZC-Dbggqsm3n#{bHni-?z#_gcDcylyUJ33dQF73u? z-^-;NpRsem6_dx>HyKoWipq;xmVYB z2uJO{l}TSpyEc}*2_9>gGd0gDnof&%Tsvq@$@WbMe2?sL)^reSkY*_TOu(tH&j9X} z3jn}mO-X9H=L<4Y+kwNKU0vsR1CY?|q_Wc^{PYm`I&KPIJa08{4*0bLvG3lMm6gHt zp@xEZdHdsYWHKSL>?0)k!;Mlh%NP5-$sFR=QLq3$jmleEQErf8f$`nr`%q*9T|k-9 z`{*H1g4?!jLk8b^K8yotO54ySY3Ug63AAVAbB87vmxU^z7EMH}OT$$I$La!}G8^;~ z>0U#Joc^k`KZALRan$A7_4zuE`XIp0zP_C}cuz;5@zYc0N`|HU)@FO^YTt_Y3On)i z#}z$mN>I!TaqE~WROH>#w+}r$4M$v?itqo^5T=sLl(`V49(0jjQHw=Q7L;{P8Bz3h z6WW@TSF5-2@5lW7!Z%)JWLE-rf`A)sc*E#Z0wTlsD!S(RXvCLV)o6*(mb)EJRh9r+ z;bKxP+fUD!rYxvuYZ;KwBlhqud>*sT)6kE?Rk&K3rGX2L;YmDbpMqb zArn9#j8b@FQlgdcwCsSf<2_FDlscJ#5f8=Im0Rg^Wm=T?SjJaD$+AURq)@H`z61TJ zyR@dAl-w@8>?+lN4Ek`)=YnirJXweDue#KN9#oi_E8xUOtt^xw^8s#8JU}94R`v0| z0*g)v)s)KG*`OTe@CB&5y)S3GHmgN)C@tTEhlNsbj{CE7x8z<|POnS(Di$ z7pVaZ$;Xc$x9)6~=|Yac-ai}1XC3VZwEWxCW}Zt8U!n@6Wa&OSHkU(>CCM7zPN0VCDWZs%D9$>ByhEJl(yLvQsdzojJArL+;ri&Ys#c@< zfHK*;)T*=5=z%$_dkaN%%DpVB1xD4!J7|e(!L7#xP3uavn%G^xPH*Tk*WN&z?#!IO zrVR5X-ht1OF>j#m&53X6&YImNSURyC5<6%;-vD!lqZmr_l}Gm&Y4|*L-q(Pzv1QjLXnYKjf<$=ha_Re; zDoS^bGT-7oxNGQU>aN!^kw2gZHCspCH+#lrNPN)<%WQXikFT2qy{>8BTy>ws;|8B4 zLG)6*#B%klg^{a5iHXS|iv*gK8DO3kcFcib7LQIz^B5K}=WmE7sz;=7Kfs}ln2Kih zPM4qeA*z@0Ou6GHW}k#Tym%?c9Z1lpt-inB{Y;!XLua6-UC<-gA3-nU)?x&Y!H-CP#Wn{GJ1Eo8Es>PYJFW_SSYzK@fxN|++d z$Vu(wScRZ;qIiyC{mu(Mvwm3ye-Sf`QVuVu0eOX8S@{(0rX%9L32 z%zCWd;RoowLNRS|bzQ%8$-TpjVK}?p5=)Oe#pzb+$SGti76l_f>25-z??}|j+4@(2j=~sFl?=+9H+lJd31wLjtc?E73 zpTVp79O{hhJB5CV34KVE5lnTNpkF$?=fw{H{7l|lSSxr+R0JZPd`v@}TI?^J7~!Gb;G~^CC%u)L zvg%}AsyEpy&*LjQ-+G|<=2=0)t;F9nE=*^LKU5v7kaLDw)>|BKkuIg%el`kCBLf4v z821yQWy}26dxV66L{NGsBi%BO7`fae?g)d*<|U`4_qL1iy#1uAMRO8N-~o&a?ib^@ zj_bx>puOM5Mv!|GV8hSPKAiU=Bd9P*eg8@M4XOj-jyQAVzE(R^+`og2+TygMsuozv57H)#Obyh7PiZEf z(aH5hsX~c!;<0_;=^N28G2H2;&~XBCDLb*$488zZkOEM4Yr|)d6mdazRJJ<0%UeH_tDE^6%@={_G)xKgw)}#FFi> zhx7Z7X}KQn=Ph$Da-Y6~9z{hOZTC22=sF~2Z7t`^JRFOwZiVS>P?SWY-P$XpPv6@* zvuf24Y2;gQ!>OXIERh9fZA?nkIe!dRBG${{h540o#`)9b-0dks|3IC~e z<-^k*pl&9GD+yV2BqGf2d^j&ivPis%PvjN)M8A5Cfo02p zp@J~#yHpUZ{TJ!B+PKewaD+17%=&1T+E(AxK;Oo0`bvCry0;9o-u(RfDtpV=BqQ*0 zEv{=mM{IOGri4GQq*^AjWzx-pM9agd)BKW)2h<5|pO=(yl=OeNvu83)s*-A7rL*OI z4JTcP1HPylgL_n3TH2?2M0hK-0~5AihiO(0l|m3YUw3JKWVmijdIZAXQ7C78uB2Tz zEOF7IjzwtJ?vxkMvUK1UehC+WC?WVEqgFJa>p8NFlHSjSeL zruM?G4V|Ys*+c02+0NQy=MA_tm)4nLD*3prILAs>$TCP-E0?y0x1jA>WAz1CuWYd% z$0AByvVW=uzBbUNUY`McvQl^cL0#HSE*?NPF(VG&FYAtx?!n#a0Grq-`(tP{8VLX5 z;^Ixs<0@8GbI|B0ZrOKuRgDC`2}omB8V^}H>=1?M&5j0{y1zY7Ck&|~PQ2Rfo-VV) z<=QvlP5vy$OArGUa^&QFV}fXpQ@S@_rKm*fntQVfN9|#YBf6e6M-|%rTw_5BT0)yN zRALn;B8ziI@bT7gNazx6x^697$;iKS`Xd0eUpFRm^~Nd)qN984b;rhp%o^V|E~Cf? zgzr6T*4f3eC2AZTWo`@Rw^e3JVGa^+P1o6niN4*rDZAH)<30dif-B&j4 z`s90;)M9R$LP^n4^b!Hh-2XoMj_tEu*{1S5h7`v)&1zengqCD_$*oO>1$6gElV@#Y zap``raaO}c1lq#uDOi7l_`v_-7x@EyvChEU6 zg|HXAxouK_}w|uT>5bDDk#ZpLI&<|^czcjcAu>m2~YJ?C68_?|+5~ehL^dp}#OJBpD zsLNX*WoPEcX$AU?PE}&3NEvOk`m9s0pn&gA=W#2gCeLIArslVvd9Zd?k6P`~BUOEl zncuqk0Osadc0zaR|I9WIsPPAk-h_@^f>ZrY>{0qpRn_v+zM-KCXW|GLk;sQIpwDI- zl;5^ay2{(kc-|A>JKO$=yA0)E;jiSfgpD_H+W^Ri3D5~(q)9;*vZ#O?5Evv>fizwx z`tv3Wyvs7Qh=1XT1gXOY@=-ftyg!P0O^iJ|iKgNWDC=dWOQo!&LvU{6+$hh~-xmvx z%%gBw)*%Z;xDVYt`h29RkZ2s=d~aQfR?}A3?y2833HZdm{QCOEPG`bGN5IuF1NKu( z(OWyBO~FRBunt7|By6Wl76>}T*yqo;#q9Hk(jL-j{czWVXAw0hssFr_iFMgjG7J_T zJ7B!&*-dNS+>sGOi^0t-o8b7xA|6Tr0?oRE*@hN=ZX0hhd}2oHhb=frB#ty1p>3nP zH~0L=Td#w0285U@l2d=S{^J$VwU|chpriqoCux z@BZ0U4M6?8xCYzk#g^^N&9IUX6jZ{_eB4q4>#$*UgV2=DbS8*jvn_7>6!S&3tw9)P zA4%@h+Vl?dCGv9Z-Ik8opBMf%kpeAeeyYxJe&}(rr2&nqicRRB%hOu(`m)Spe%%<> ziZ}NM1Tg93-*h1`>8~OdOBs;bLEFy|Q0Gi#5aQ-JA8}V5{<62v4^TOjtQLK6qF?kb zZ!UeyMgj-jI+j5R$Jm3zRhu@1K&~$?ECgxhCE|p-j7-IWy$|(JoOUcg<}8?)mMB{) zERDZRp(KZjUx@U)*0|IF#v=dS-Iu!1|7L8E@s1BPu+o!`MfkZE>e#mJhAT)Fc%!LqZ%idm>b zueAxsq(P&sWQk-jUmVL_YyY+UzJ^>B|H0+Crm>f6pNl*FI=NUQTu{K@)|SZoax2PG zMdkTw{#D4B6kGfb|Eo{m-XoZ_%BuIc@ffX-vYUBt-T~PR>BG7j94Tz_e8@-)h8zMT zQv?9fbH{Nm*1m7wjLpr>!F1JiODF&SD0ipIn-V(_VQF{PxcV|el`UD^Z4pcgu!r?H9yYI!4b_)^!hVLl#QO@ zQwWt(4!^x4&)(NO4*FGGYWs0-4Eu?)6gnIZjyRY~glKWsu9!d#4CC%Y%QH(E-_=ZZ zuM_CL8?gr7{)ShgF~iLC^o|SOcc4*r{NK+Fp(T1T^bFziwc?94*XSv@q9QPA7Xd<3G+6Xy)p>9qs)Y%Dbgs&Xm%G5 zY}z=*cJrX#VnN69wN>`~_ohlKTVBqvd-O}~JWY0^xH zi<8E~F%~XY$C+~C>$%1g=H+W7YnwL##lOC^xj?=tel>0Tt})H@35LothYbT)q7saB z8C`&qLb+ExL(%~DboWCBN$_+x$9;y19Acm8ohr-0qE{FJ)?mbo;vr`Gg2|FdXWxh= zfYro@9XjuYL#_=O6~6n4ap1(m`g4dX)F93-SX61!i(JclM%p$Kq zmd3a?~+~rLe}YFSCii<1#+S+*vm%3#GV% z_VNhcwDWP>s%SRTnUxj2B1#bEwXS`Aq!BEqj5QSN?Y~zCa9htS|CaXIbX1_AQjg5Ccv4FUqMKWq!mI9{hnX!Flv5ohg#;fbaz z``|_jv&VaP?b-#GBVAEeG=|fISsTKSdt)rLdn?@c{wYOCqE54YHYn2jlxU}S?oN@= zRUTmkEfDW(V8Yn6^bF`7xfF%q3 z1QCHnAKlDua{)8LZqUDQs{1hzL=p~ljQ5AJ>xB8YMXO!NKg8ftxL*iw>@{_IbKO67 zqZ56MJypQEU$~V%2E5?c9^dy&P*9tRxCxll1_WEYM5aX0kJVWQz?e_k;+Bm>@#Ul_ zYs9PC+N;9QO#*@pXm&O9vN;GG_2A3e6no)!lC$rD%aqAI!E@{#)zQR?%xw+?pXpz# zaX)&u+85hPZ>zH-Y8>invE?5&&N+kw0)SP>6IU^kN3e6nmdiY{ccXEGVd2J5=CJ%J z5We%~4vlFIjU99#gvP@vM9>?5AoCILbS!~qLrhFb)a8w^7nQg{$!Q$n6}kt)%P4xY zao-zXgoUef`<#G*fg}w8*nSz+5dvVj%qGSC#7>IPMk-!)cBHLBilFy<9Ag*jtWMYY zSoVlP^uqZ=tU58jwhpoMGg2ZeI=kteRO~{Yc6*O5-nluIv6j_UW4UTL+Bas#o!YRn z=Fzm^Gk3tF?s;(dD;u0!v9{N-htzm*EE@6tV=skKo^f@8gwQNvrKG*#5+N&EHe@wU zG?FwT=)s#nL`&G;zk=8P=y+O}=QeEoq_-}beZ@8y(Bz>qqnQVN1u(R4G#J-oIihDj z$0cT!VcI8Mbw=+n%2h-O_x&WkqxRD4Lj{ytV6OTNqGnLws9<|t{@ z2%C)cO9E}~+8h>V*hbniT}?~WloM*!{vrWfY6jZPz0H-DGTeXt!*K*4`pY~*7L~I$ z<#^NA5?uZqi!`-ePjoHvh4W(7(t$_OH@0{4#9$k=XJ*j@uZhnIMNY+;=kc1+)w2y+ zPQnEkmpZ+)p*dx~v9AX=-0;CKmJ zj(QSaDBCH+(;?vFKO*4R5TX7(>cSLR;I>E8bg*b`SlpW`xyprnOfZD1<=@5^{a=j+ zW{=z9OB=y>({l&HkrTaCeavrf(5l&xfnB7FLCab79;tP`%7YAEHxlAijk%%4tqR5` ze_`HI^W#_;Qzj4?ygCsw9%YG03i-PE*9VSp9WE~9ziyYKdLntd{?yK_gxFr;N&d~1 zFUp=)>FcxV$o$4q7^CnNKJnypv{C|#qDkKVVIIkk*!3ohxl$CmcI$@cww`2|avo`7XGN17o(X zGwFnJsfVjN32wwN)$rF&tJK3o@-ur9gVx>_%34gF#rbR)CS9Mst2xSDeOf`g9xvs! zbT&hj+gZEqEYyld=Gp3VWvlxlqhL^@ zMZLD4X_VpSxmJ2eOiqs-F;3*74*OE=0tmUTp0Qaw?;S-)#+kPNdp z*^}H4oynfxi;{Wm54X}Y*?a83e`(OiFZ1mttGz(2DK|JYq}d<;(cjVf@=d7$JztIf zLke>tl4LTaCa-`#eS_z=IzxhHV_BI*q_l5*)y|tHwzjr_A3AIul0Awiljtw6i4<|y z|191spP{dNS3yPL@S;C_3<%=`V5kD~NPCZ$Oyjeu&O(nT8fjTs(dR5Wu8R*JpXb>0 zd~=?vae+(YGkuuK>G-W?^9B;~gFaG(IE{N(vsf+?8o_OQ1sjpm)4q6XFOhGFQ0DDY zI!oN)ETxr=>WQSRyN>-Bul-dynoJ2yF7Q#O0)I#-8oizMlt^U%wT}^GL7i>-4K3&z zJ&eiNoJS1)=d7=E+Y6sz_q|rOmL3~L$t>ZR<{(`RtT3*3-s6FdzDT|k?YYpqh<*}I z5I8coZN_>5KJkL!(|?toB|r1Ga`!f>IKOa^i8byq>a(^Ik5!YCH5xwZBH$X0bHtB7 zazrgXD>OJO`^{>Yd0|Os%xL5fc7cHK0_bL9O8`t{k58_L%DH4YRdvm}g@w*{G_TK9 zZrl043r7F!*xdIu&{)zxIH>pY*wfU%5Dh`%j5%-RE+C`m5HdvW4}uZl%{39!C?HnbjE~-@gv+`H$Hb_#vPqj%9i1lcm|VZN#8YO( zq9gD>vCT*lvqr^2K+>bR$)l7R+4@PzxL!M+E&Fe#a8P}jrL|;_^9qqD{l$_1KbeT-Hs3&nROozIet#p7H;a-omGt| z$sUVd9Ame&hQF5Sk50Qu?w+G%55B`y_77kiFuS1*Mtg>FC~n=rSq=3=@32LVN)nCw zHHrep#8Zp;DHdgMRe7@3iLn@3WY9kjAjF|TZ6ExlQ#KHaNRbte5-l(ctlVw>tyH)r z?W6f_@(|Y3Jhn^+@862Eq^_%JZu|gdp2MY^eVJ}Qg>`!ncojt@O;Yk|t1Fi8K49SA z4uh4yNxwexEP!cN`mzXkoetbO#*ayLAsDx0(_=`XbgU1yWS~5#=F);4G}a`P^iAaJ!W@hmv{)rY&J+bCX%!KTHBdgytM^W(dI;*wSmo$9xY_ zBYi)RX%f{VNqGKo!ie_XSs*pzC~^3wJ=hH1aRkP5|F|8k7Y>;5mBeaYpE{Zr%q}vS zB0ZQzxHk+ z_91>y;3N5K?|%uZSrrb0HrnQ7kXTERiuvIk-^rOJ&x?LPq&i7xm6X{JMDZInAEv$bgMQWbep2iwwqya4vNuxkL2CFg|(XCtj ziAVOnXzew-Mr|%BnoO&nCeuoY;gPCrXX8G6dLH&%Zk#=#@e^b6<8L*{wq_jS2~hL! zkT%@IlpbV*UK>oopvp2Qcz$N(xG*r<{LM1^-EFaST>!Wvr0Te$xNllevZfS`R6B zS}U77S0AlGX@|_Eq8Cx?FG%lyuBcGgt%{dAPenxIc%*~>wrGob`rVOM z!S|*)DS(-~!-C#c=`tQ_RM5lJ?V@#yZ};+>ea_hlJxp!UmAaGkue~F@W3w$H6gH!i zsVEeMSVEb3;StPq-@IoB z?MnpxL!wK>n#&Jeds!=Hse$<}_W^K3yVn_By_=mgRiNSKd@f;}UDJj<|Gxz2^j*VF zG=(x@%nYMcf`2Q|I(gqa&BmsbH!dbJ)Ii%dlELK^oNg5Hc~>bqdc5>nm6KtL0iVVL z`hxUDs+|InZ#z}3)V#1u!%+|A1E4naHPA7(l9y^3ofv}U^z)UTcVSJ?ZEv=WRvC3Q z>zp*|;!WC*U9U_g6~1E&GQY3vR?#1&Co(!Go9Xf+mUi~6@7t>2y>^cA0XIrQ`|s(DSghpwa5T%LJB^PaJpn!lNW=-PPAgF|qtXD5|2m z1FdNAM%~LyHM8hd31Ru=I#jwxFYhBR^`*r^iHEcxVnd%y7yqX?>Y1V#6*W5Bf9i_n z+=>@egYRQuFRb-(>(qYo>(bVb<}Kv7nYcVzTy!7p%Qht^;ocP5?7%)p6e|vuh6x%v z-5?;p%!e-WSdD%zp;c{?G+xTsz2GqLj1G}i;^SDX#Fc<$3n^z@WIvW;aCesa_xYCQ z{nPstsx94bpeat~;te6Q+xPZviMm-V04!Qw9WHfyCf{bqr(Abv?&%7g z{+HBfMiX9o8YH#{EPHIKV&>}`oIO&XyJxdLl0uh?YVx_F?Ea8eP%OP2(>5cNjz`II zkaU@x9vm2SRD0G;M&F9DIC#RS+sI91E%YSmidpx1U}z8J4*CKPr+y1vc8p|J&0Vb4 zPk4o)1^{9PZf&zf6L@Mu{uWX2 zWt|j=T>pkjj^!s%fr%ksKm?K>hNQ)KyS_Z(qy_BP0iF(XYDSz|-Hu09R?-E_`1fP+ zJqt^LY$N-Fvl6=1-PfXJ&Kq*6_fCJ|LRUjz>X%Snh@vbBe~VNQIO1ySvBTMBe?nEh zc;`$>aPCN@?m@?fsi1od{s_}(?Uu~YLVUx*QJc~?X4AE$=gl{X9sT5cFn?HD5T+iU zYrs_FH6o|6&VLW%usp+7E!CqtFOp;CvGl>67pWTY&A-N=B`QTQ&Gx)Ns!z5h(sq+7 z_RVF^e2WUGKDx9Dn_W7?Y@klB4z(J&EjhN6Tj1kU zao5&17nJ;M!`NPYPsI0duA*AFD}RLRW%0O3OsXH66jWN zV{>UgEr&j_2Tc8#uIQh8>ha$(lEF8yH^PaD?3fn9;l1vCj#zlP%;7|eIJHld|V zrgl7EaNbjC;&bQOQIgXqPxor>HjE&KGa)d2yW}xA!lZe=xSj@+^;cz+XBK+3oy5pp z=F+h;K7*H^MC*$%e{x|}pkQ90e&||s$P36D#fF3YZ%zW*lC9+ba%xj2if^qY!nm0eZizibS5#P!1$?Q)?~ z{J#D%g7|#d-P=L0yl8#OWO==Mo+&+N3Rnd-*-%XfX`I!i#VymFg2C05v3O2=hU@a( z#p9p^j=&U#cQ9A1NJJ{H0tP=kY2FQJQ;X5|Ya^q(@%eezTiB&f_qob#lVg=~CJ-)KEgiwr$ z5nu)}01^CN>gL$y63|$4%BItyCB*>L?xo_?9R(|m>6X65T*y+oBNGx}DWMM%rJcOD zb4&K7gHW*Fsqz!1zj|OJ-gF|v%`vLJ2RpcV^0l2>Uv1rOd$`u}9J)?f4_4GZw z_f5qN%+D3h3a*KJZIu!lwYU?PS0zbZl*X}bq)cpCmduqAW}zPMHOyOXTi=(UkCH8` z%`!4<*19Kq#k{T@ERLTpgz zXvO8$!;66*#J$q$w$_%y?l`RW=pb>3>ABNIOp#)5M)1q(N;zrldiCPK z3a1p!1l!m}rjjBrI;JR>V~4mM@CmD>QSLcaq715PRhP7ebuga@`;HG)Mvl|Rx$ijL z=6gjt$ID!ax(P&X=UT(Mopa2fP5*Q@Q?pPt5Sh~@Y`3)A)-0Owv1|=Rhp5i`haaF@ zY0a0;;s}S5ZgmMuPM6V{%>?@0r;BkA$s#GMH|apXR_9U#2A5pl3+jKRc0NR3Jw>hhfw$+vJ2V|jF*u9+DH(_gKR{=}SUp-seVE4x z;=i04VcO@Cus<%B z-0^^r%3^r1rKy%Z3w5S?_*ML~A+q1dfy*NrE4)HeuRbB-#=FloHJcp8s+}*Zfv{vL z2JPPOt;;Mx;V4?YK6tyG=#G~RxqGPyxl-*vS)-3}|HKZhcE_#M9kIejOwza$32P)P z>^TaR)I&)$qWLt_k2R%A;CbeQm6-b})mRzhQ+#wmx6D>16O_P3@{Y3koP>Sq3M>SC zuPmk-k=3@(hw3`kAK3nt@#?YLUlxk9_}5WU$10KvoEn;>wL?o(dT9Oa&^{=R4i*VtZpn7Xh#(oSeav87nrex|T_ z%j;d_L`jZXua(o)uDo?jt0}_=L?gYA;B;`q@2AM~BdS>E)%zMV<-wlw5jDH!BnqmB zB0E-M-qDV|F?s3or`B&%H<8(zb!T(a0^h36;BH&nn~GiTCLRx0aWP_qX9MbAos^(F z?{VV~mSwiQtK93QWIJGGNtG!$X3z@X*dUG|JUnZijBSo zDwz)6@*5w|a3$JD(w-G@W=aZvYAVVY#j-qkG!mmIN&irH19Q~XW5-y2Fhrcvsum^I z*=Bxy*#{QkYv>7f(h!KH^x%m(-*eT)0)nF#>N-kgYf%r$Bl#3da$^1#u~>t_m5hoG zVf(uF9t>v4#Cp}I{KMSo^5iIq`PSo_iqV2&WH|wON?*Q+v(9kip^M9!|C5zi@+2{y z#kuj?)wuYq(O=vC=GnM`GajcCtp7GRj+tIJ3%bVKFELFN8zerBW;sYvxa(G4oQGk) zDA5v3@)X`-PgU;87-4i;B4|YN_<*%3QlA?P(*mXG_gBkbn2tgVQ#!d_D&hX;ovzo# z9;64`=qH%p>^o$lhe|ddnAL=hG5_QQ$?^I)kVFSQUkGU`p0Rk?x2;aLdh;1VeFJ(_ zJ@Tse0{ZLy>SF;aJA#egRx&lyKhjL2peT%uJlIn@u*sQu}o1|!*Ntah1DDx&O8$F2j2{D zNsxn=Ca$c{PR;(@=eSBKQ#Gk-PqJQA?q7+d>L=W~*&hxcsa<;&g z<#x-~YlEAV(50P&moCOz0}is$1CgvfVJ`>vvcniysM=kJkuPIaZC+xTv-{&jO} z@h;q2NtdvUw=Kn`-zn{FN`_;qMRv}sEmoI{Br}hy81x|YI-hW`>8K|Xze zlqw`i^&9om4vXJ%athaKH76x<=IbW`^ZdKY2fncj_R3X%waGff?gA4*c*D2f1@jhLu&PwMxtP`!-_t{M z{z?(WUfl7zpcS_1m%#ydRg}hZ7wT=6n{_~lAo*sIK2q~M_)WN)S_zwPNg7aEM{oTrHP}mO63Ku>#98>x7hrVPoXGYr=^20H1hU&uui(t zv@hRVc(PYU=w825rAXa6vr=2zqBe1#fwzO$tIyk7{t6vl;g^=Z*Vopuo_9CM^x*>w zn$V?V`%k=T>!^70vpD3NV$;&mpq#^_SNq@BP$;`~)fo$301urL4?-kA3f8h3>2+`lAP zPzynVUBH*CFB><{&7;nd=($BPIJLsz9Wb24VaL0f@su@uZy1kI%*1~Y7T-1qizoLK zl*ceCMY4t;?9+w^)O#dvo04uxKatitpZ6NM0uQBB1f6_l9W*O#JkO}?d%U2V1kRn8 za6oNySv74qqnRwbYaNYC=q;vJuYIKMYAd9)*PZpF4c)iEo=A}e31S5NLuCtRGo-53 zWsEs6iM1EQVsNe@D)-$Y=}Fh-xbv#77uq=UVx~C;mt(jdIDFZw6`8y;*W(y;Opt>z z_N-v-hiij_a4%C&we*O-Y}y2y{BI9GEE9LB*yuurh=Y%NE2|DfmZ;*NGyFi! zV)|#JbcOpV&sGD*an5)Gx4YqGymk>K$2xe2_4v}80Y~&ipDk8g_72Un`Vo2KVNtbMY3lxjN_A5Pl5{eJeDBq~!oxdgu(#tTawXD$U}MhO5ffQ&yj2-dWj98x{NPKHI|cG9bq9Htu;?^7GwiukYr(bMPn;s$--L z$>CaDPL4XSZ=MaV%2V$Z3RDR5=7=L#IX8{k4_Xx)z>VrK+9EwCC%mvx*zo|>hm}|L z^{(wJC>W%u&O5j<-a^joKi1vKKHHSi20(tK~?jqbXW7n+ML zsnBiPB_VL64CV`xH;?Hum-)xhZKQ@>mVD>d=DA93_fl2R85#?eMb50I)fo(SgZ;QT zMx3D6E;jRt(Z$O@kZUIhv8(3AQX0+gc(k==_^PPft^yCa!dJ2$DH@(P%o)p})3a*mhQ0x_bGG3Eq1SYwg#Y-EyG8ab@Tf#z15)P?|p_5K;!JH#*XEP`1rZ zw(;lEoWN4x{W`x^=vv9b`28cF7LGU>G}e6_ofaTt_)@ET;|peJH%&e)moi7wA4uep zJ_7Aan+4vJPL_lT+Fhk?q1s3E>TuYqVILaLsjgdynqA$oG!2th7vu#u#7;A~Q0~MF zU$>oNqGDJfw<1gRgXQ?$N_{KICl7Y<=Q^*eZD3jq>;IdB$h9d^do?__e zR$M^2)NFLZfB0Vn3E{wRf<(4a^!2)HonNqh)oabVmwk?x9J6GWabcLc3n^)C)TLGW ztCY`NETI`e5}g$l4-Uojz5W+FB8Dq6bSZlu)gUgQIOa-#i^JR^P z;+||++dYiSH~3Z7VB!6inykXkl&cS5LF@WaUBuY7~q1OBA819;;7|*A=$2 zx}x=)L6N&OtsN*cxlS^zTt%9e!E#>TT!IXSD|mdgp7H#0<2!uNF+VnSYT5r!?9@fYGT zc@9|yEMoMAS4Ydn$LSSK8DYQH|AA%i5p{zM%U|nMe>4P5)xSrmrTrXiQAg~Fv_ta^_Q={JW_4%9TE_j3Lw@P}5#cJSRgPJA zqK+mG^NgIpIR{H{YMXYHiNt8|4rbrWXzX%vf=q3|a(^0QZuer~P*U6&sV+u!W_ygV zB=(R4HI(bQgz`Q;%sG3%|DypaG<;rmzWj2x5h_aMiq$F$mbAJg;m~+lb85W~m%XAo zft%esEWfy=wfu!A-JVw`1?Pdq2|upAkWW&bNl{o+m@(-BNKkg&7#b%BybX~a-_Az3 zj=J$Ex5Qgv$E@i_sjK`)N#fI2PI610(WFW(_o_Z^Z@&_M=km^Jy^+2OGqC@lkE?y5 z+MXJZ>f@==6CpwQZ9m;#{V?I36q* zRdV_@DK+*3j1QPO$pY<@zve?hyYE~68&`VSmiS$3-A`m{Z&E5QbemuowK-9LA~i6@ zSsIZl`X#hvFBlz3&t7@6hEX|>Yw032U1o{EsmS~$B_8kBZM^`-v%awdD#ckg4`s3% zcDSOJmi4W|7hlZ{P*|_@PHUp~4xwCzV44bE?@T$jC3=F}V?BC}r$>S%3p>>Cgchip zfF6l%FdxPcwVI|kS;cuZgu zlygv~CORoR6|@J;U2RTmkEctVRF5h;J2TwGm$P2ht{+FIG-PT&5MX~-AnvFf1--b z$msiGv=B;jjT^am)pY<(DZb(;h%O5d;=I)`y`rGW%*GP4L72@#DO!X+@7I`g`Um$+=DRztiQVomPUS z&Fi_um1{9RUKWXZ=?Sqfu-=DQI->L!WFyDBto)?l`Gi}feip1 z^{wVLiEuGBodS=ve#@VV?M$qf0hqFy1UbjpQN@i)B(2`9kyZmJZv@M-m_GTvm;lwh zbK~-@I98J#@$`NdVum})z~hto!}Az4?>OuG0$O>X~VxZWp=zKmt}Qb z%x(Qt8sBmPf4fJ|3{W(WD++ZfD6)cu{bf$5|L?J)EwR6ReO>*b=8T%7kQO83q1*+{4flTo7*kawWBNz;m0XXaT*i>xz9wj7WiPt2Kbm!M@(sGZi zF{<;1JdcTR>n6Gm*_U4=Ty8G5>tk!fo@|L^ocE+u$rME8+phZ^t^e#+UI zmbdh7UHs5I4i=J(@?Zko|F@RvwN9EEOBwA#T_0azDJ+{Q*}P-CxOu?e7|+Fh z0RYLMV?dweV*zmB@XY+UYfr$rvcH7T`mW9fcUF>j#EaoXPX zFlxg++p>))1PlDkq3V5%Jc|LQeASDbX^H~Yt`n3vJe@C?@Co1@|4PWs@!mbUosz^7 z*)qeXcZp(NLHalsf-~h{62gpLy(ov7+&H}%xeLdx$rfeoY~e4QE}B^k5!cbO-XQ7` zNHZGhp}vC6T{*2-7t67_z3m}_R2`T2zHq-fp~!qKt!gjX-5 z1zM#8Miuoti7A}^wtZLP1Ex%t8*kZo@SP@Ra6Y&7LaQhuOSKvP12;L~NKyOvG{TuL znE}5|l4rB9jIES-G&DrMq1@@(X%BWK$zj?ZSoUIat@_yB%-n!T1$4C?mre2_LyxF9 zOMa#>mJjaQc_2D`SE-=@8l=eI?`}3fArW>5Uw|WDSB4y}LHGq+k;=XwP_=5WK+9n9 zh<-nHa3j}7j~WFGHym6h9UT(}l)!87PxWT)o%-n=5Xq(Dl$Y;-WrS1x9P`KN7xsC% zx!mqHK=UPGssDeSd!_xyX>B+4mFFj*>Ht2P(c=+R{)%i9ouR{(3|$%Y;HmHx)(e=S zlS8=~YBvHriE}!aK_(N9Zxex6C|vCsneR|8pP5SvTY0oV(GlnUP~ah;4Ta}=!0KiR zw1d$(g0m4QA&3EJ(oQJCqe;tUs41JW@*2Do!+vC%Kkw(|q)q3DGet9D_8iX0f=qj) zOT9jP03Y&Ur)HYxHz@b_!w*-F&}l;&0Xiif3S3kvYUng zxti)IN^j z(g-J7-}O*JB9>)CHkNCZ?Io+u;^|Ab1)e{~)1)N~hhdp&D6XQ5k0jW=Xl zV85#Oc;!|AT4o9RNubwXS~@@Kb&mFxN-N#41>tMv#?63EO9AK_;bkVi&AzHLzRJqU zM~{-j%rI~}qPNrD?!qljVtU46^b3<*-Jv*=LW_2#V)LV_!oQ1nYEC%kgXVj9qytFm zV}OCR8>bpzh|~4>98rD*l>C7L+8ofw0&4#cHwdwRX^eHhqGi0+=>G3^eZIsr&w@&^ z7ElMRjQ@00U-`naUlHMhtMck=8Sytk89GA|%MDe|=CM9CT6Y2pq+UD1wlmysW#XP1 z-5A=>P!-Qez@j+yfs}>{C;NLK2lvJLn&G>9lmWz}!NS|H!Q}Zl z<(c0*&w>H+8V#TiX7BF^Kp4( zAYC=c#)ESE_OVJLr}k$@B#M&e>{hW7V5-OAibHo9h32sV6681Q4e6Ds>x3E^4}Y*g z%2+L56`)-JAbaN|fQ$fW%Qs~cjssXKFrrA`KrSf_eu=P{ThX>a__n{BoaS%MF_!t) zJA4ch@9B{493e5ghrh3Qc*e@X3!f5;ximuVx4>zaSC)so)of%l0+z!yz~wH9tJg{N zKMJ3X})N*E76ZRE!&w_g|ZLN=g~c+#5(A#jE|nxXn8 z^;HxYsXKB=Q?m0Hw_p2`9y{Br=u&j91T+GeObzfnr|Uzf1!Vj|uAKn@r;}`zNl*MW zwkf>mb6ek6#opK(tSdq{)*}^ca?jZ-5wf}`HdEvc&)_O!zj@)4FWhn)*P>rcCTBU( z^oogyyF+&B+rAuSaS&5C9)9725Y0Mf%#aLT!?8SXAN*Htz$nr+(Oxs za)6u5St02#@M_QWpk+C)h$dV(*zDBl-#|p6xiXSGrJ$mAi$sIjo|W{7Rc*%rCvk{a zmtv36-r^8~Zlwg!nRGp@4eM9%o@K9@^z(M z{bx1(KT=?G?@y%B|G+IRcgnjNT|t~B-CkdR=0PV*pPgxN_KHUkTH#8bwo-Gs>MG(R zh=}4LsshgkKr;jY84=?TStt~A(3Pi`<`!ap)H;;rs*9LT=X!NcD_3Ra{F+nycaLgM_?Zfqzd3GpppE z#GTEnSQVsSu(~2wTnG%CIN90X(uU>KobQ}Vf(pag@0U^628W}BAMNj~#T7lDOE3a< zQul&eq_Am(>T=jK5IS+X$N!yw{(v0r?UrX`XR@!AZLn?zbjZ4+C!7K|6VN9YH=*lt z1A<8f4JbH(j7aMDh%m}o!4Xk*0m~#}^c7-Uw}-xti<=d-NpI2whN2GDy;Jo_}Z|io1Q$-3<07=}U&_ zIo;YJ9VI|M7$!G)8{HfCvj?mM@t)PFJ?jX-Sz=LyL=xFitG9ZRjBIDfogG!# zLR;iEW#Zdt%8}|e__8Mar^|;;2t=-(W8xPcAqhAC2hReiN@J(!2)D};k~p8spSzEJ zEyL5JT&{??31$G*7X7I`qP6&;?5p-jRMavhW(_w{%gcv>qIsz2zb)kkd5O-B*etpk z2rg)$(F?Xqm)a*zFh4pnzKLO=RjL5s6HClRjD-mCR?Z-QjB>iK!dZK1=CKj}Cz$K; zbV`B_|L!J3X-mp=Bpp0~H$zq4Xw9?KDu(0!R&%FIuY5jxBS>5JnoJVlIO@37&8IjN zL>0^d4;Ro)2%Mstwopk3MarTpcM!RdkJ-I~F95|wAN>FoBN!nfmso0Dk{Rmu1q!{w zhjEa!f@>6<=v=j~WnI@8>iG)hv5A#Up_%eF-;J({PSzmjEWjvWx7Gi_c^8$U%~OTe z6L7aM1N6%pubDcMt8IjIxviyxLpR{+$ayK1uF4Jzdcyh@S5NaBZ@$=ljYmx}4Q2`= z?>{BE4nW}((kOgVLKZ|Neb0Ky_IY}5t>~6)N<3(7i)}lXeLcX08T`$RV+6pCrrSEv zvxb=8-DS+8&Z`=o6k+fC2LF$o!odZl8KH%-S@+~h0q#W4gmAL3F9$Z~-YpCi+czGx zs{^9At!;axZ`~~{TZT`282+HdGJ*F)S($M1i35}PstV9(YFTps-g5n%GzJ~- zC)TnIUVi@;0R0~e&+;oZA5p_dZgbq(fFB* zJ$j3W38`y$iGR*=1i(T>z9g>|c+mAd!<$Wk7N00K@5g}aJUN^$6vV9$S(UC?HoBt6 z5uGXbECX7`)u*uO+$ct@@jQx)C;zfYmy1>_dTALFTo$vNClmc- z=C`uQy*p2d>eXffFuW;#AHEV#JE)^XZ_ITUzduW>?r~$VZRhqf$){fYDeUs3l-&1u z@ND0`Ls3VqhX;EONmsSinc3V=w<2xw$xy1s&7omnng6eLKZy2vKiJv<=*MAeq$yg; zrF|Y7*SEN>b|--RmyXDj(;j!ri_LFMO_Ujhq}(TvJQlnjVYf?3(FNd`6-Xt<%>r6f zi7PRBVITw(YiFY#O1qSd;yxc*-7~BiKI0?iI%y#h%`q%^0)0$q-2yVmBQ$!^$8F}Q zFTW5c?hGy?c*{cMsW4rjbQV+9pS=uq{03rI%5q#&mC zNIf|5Z|{!2XR@${BkpkmYWy_HVq7X?d0O zMcmV6U!qM8Hf|sQXfIeIeo?vc#+F}oGT-PT&K+E2YSZ89FDbS=L7Pk&k^S*;Hg0HA z=&D%=4y@<;hjAB9m(NUJ7z9xAp~8|NORTLWqQL!H<{l>Edpm zfB`s{&m+bA>5+n|@YY?J z>V4R5BDJ(bJ=$#TFL&z7?W>J)4_Z+ufh^(DmEv&DM0iP$g2NAZOkvxK&{3Wi+pD zXUb2V3jWgv=7K>b5aWt>sy|o<<+uP@7eGa|>(K^sWD+Ch+*9oL*{Q}eEzhWkTJR(T z=-BsJbG1w$@+DL|an*gVRSLa?7YTB8|ecTWh|-vU*9%&3x}DzG=H% zG+FRP7xpn#G1GjHu%0_Y0ka~-o@&UD=z301jTan>6VrjHC8z>kT(WJPZpwB-9SJfq zKn6|?960O%(l%AMae@M>VQ82Us?+0jnqbXWB;qufnbeR!H3PY$DrZzF4T+zN^jrt) z>}ivctvo)0?deBj(K?Ua$ELO?77c&i7^LzQWUj1LVgnLame-|-?WcxK#rp7hXEn@~Z;~&DX%fRpAtq#fHpD{s1 z)O|b76WIs^$OP+qD}f%a6|-?t(M7v>zWTqL|J=J;RzQkE>?qx}_SuSS-)Xjn1noVM zk!tcal6nmZ3+U1ceLQ@toQxf;$Gdw5x+hR)eD)jcUQxS+%c?-o)r z&AkES#Y^-YaTQ}PKQ~pdS@xnHoi0*Le!D879HXZDGv=xQ56Bo#WFG^6(6-r}H8A8q zHc`0og1+Pq*c}m?S7AExJK(W+j>l1PU}n?9X3jt_{D@X*aWNb4rw1J)vykZ^(87ur z1jcM2ZTt^LENxY!zwBlLj*ewRV9?^U7ZR`&2BnM0T`p_ugy8^!qb(GvojxZC#7<&Z zL&_t=bWcdTr)ux-ggr+aj=kFPR1+oTbHl!H-92c-)H1_7u0x4d0k5L&i z5$~g73iq&t1B&z&TR5OGd2>(&rM}$=JahIec-Rc&!Ov5mvVO~xs{c3wO+8TX(p&rn z6w}k|=e*VvPi_<|Kl$_?C`!GS*#)F{u*6)y!V9oexuN$W*=pKcH{5!3HXqaEq~w6h z<6af##GmJOl8v3+5x9r)E(1aUkhanK)q6M)%+Z9xnT1lQy4-E?VApP8X4YZt4HUE4 zGP@=0`mbr9{MoM|lCU)W$1U+c6%o))p7R2NW$wi*Su)~4k@QXjPuUiABsj6t; zB4H1#9Ig%po|TK5ay5*j3SKLiKBN|m`-Sx2OVYjC+5&UJMPPN*6MLX6=C6Gq$SkPL zK0kd0qw5Uw>=n-0T4+*kYEvU~F~GaM}U7m!es7 zM?$9P7tyls-w=|=npOd@z#LM75H}VUMxKkdyc3dva&mui`>UVeuks8#Xssr$X)8~< zEiE$?m@A~4)jr-0cmmslIsB4(l8E^W=-6?Dz;p@~FE|6CwQZ$m&Fwruk9*OvFm40F zK++NoOvY|+PhJ@>EE))2Z2so4&0#VbcF`keVY?)b(^Kw;&+pL^PE$0Dui_y*vkr4Z z9;kX+hRWNuUI6-L43jkTqo@Tl_jwVj1ggM$6e=_Nf=j6tpl_RbmHwl7mZxduNcknw z&y|xH1V(l%!Dy;yiD~RZ5hKnAAMP;zn3J#wP&9a4GRl9dk6x=kjv-VaoK7^5p0bcfpL8j2@eBw_^B?rWp{2sc=EB9r>FIVz5zW-Hi_JGRK?p{6Rr7||fv1i1ai7zq1*|;tcU*k_? z&T)z@vl&ICZI;L4ZUc(^em`7{M3pDo7+`}?(UV|zY_P|o$aUaJhXeA3C6Tuqn63i} z9r91#e$C`r1F|>~Da}qj~GrF;BoAnjvNV4lP za;(&_V`qHl%iET>b?pW)Rr_nJ+lP*eQj`-0JC?^&>a zb$2T3p3$vLyt~}fE|FmPBGH$!+KeC}CAiDe&gp^6H@A`LZJ}u;MZ5sKZxZ%x z0jOvYkOtr5Kkb9>0lIvuh^v7J)zgQB)VLsM><$P?R1tMSWs$Em^R)pCR8_iqrKh!o z)YMd)yKC9;ddtaI8A`1{666kT57!duIKSbx{Dk_=kkoI6!|*%}xz4Ef>MR$?hnzoH zA@C++kD{brqnnn192HlTb?I9~8nEw)qdW5N3#!@tWca%e<2bY)K`8ed1U_gRcRg~& zUviv2?5ym*43#2A?46aNF!euLEHio;OP<(i?&S6%KMhEX!zyM#;E=sGAQmL;9uKlyFWWgs-W#c;a9~CIhAO&OU{Cdh7|GQ5z;ykf%s&u5BZvpG zE<-f|C+u26C{UX55?KzR9W$Z_6S5Rx0L(bNEi4CSVpp8f>8S6i#q1rqZO#=Nzky#=@ehJs2vT^I z4hZ!pw(+(`amb`W^I1XvOg%{EKcd24S!d)&$?<;DlnPZa(y)|ckmm2@S8LM;BBX0S z< z1gMdhCsW$M3|^ZrGZPRT(1rrJEqD2a1~hS`ephzdb01V4Kb2gT1{*73myknWG- zt7qO`0-AX7Q#&Sjm~Sra^-tt)d5#TYclq8lpIyXsU;rEX^sDGYg2q|2OEMBVBqrU5 zYtPHC%R``<#eCf73|TYxt4av+3n5KQdv}E0Uq${p+DPqiKIpds-$?4N+fO>b9X!Q6 zh7W--h1h5}uwCIX3rr#STMaINtv6~tq1+q%jPTJvMIZSC;#V-j2Y)I7Ye z>a69wpKVkNsIlpkEk~?~mnSe(+S(h5+~5BT2D2uyS&wf|6f$Rr8ld(!%f@ZAEnI74 zz(YM+hLX+)1551(%rF_)%CsZ=E#&L+_6|aEK)-IL87DlGKBQEM&HH)?}z() zER{gqo(QNMFYNh##NFK~waVuG5DIjydIc>Y&%Q2#r@0qkuC_#iwTEU;wZwr4ZogxE z!<70M>yW9R7O>#fh(z*$uhD;+F)t3=^{D836njAMu zCYEfd3?!5WEnL&iL~K9!nmi-c^P%lqjE<~JKuIm%wOkbObhYD3bWw-?XWzVTfafIY zt6=|D_B$$LGvNB&DO$6YX5KM6dP>?AYzdZi$F=PQwI8Dxl<7V4L@nrRyqpuI2jyO; z?encjMnsD}1zP8&AkQjS1yB(!{$xXur41~P!vrw;rxECuA+<3C*; zLxqCJm)!p0b+?ht^&@>H)P#tl`scg`?J?06^iD5MJQbx5)#QHS);mPX0njxVcG2(r ze!))tHYG9pxV%vh(sqvbWU$4v@^e~fO#Grr( zeCgis#FS zWc=jQTNTVn=zi}K;1>CaP?c`gf@v?^ydEd^SvNo?+DbSSMxH%K|IH!aeXyW`;d@L4|n7SU6HBD!Eu5IOR*go@D zVAx`_%5}IV2nhD6nC~S2t!4W+#8K2~;`Z1AIIVY7&)Fx*yYLrV@Xs={Uv=I)%FHex zN-~(Pf2Z+W^RoBcXFX5^ln2pG?mcX9yrUarfp0a8$y91xN(*@E7w|NVU7%p44#w2= zgh$NX&PcKxVtVVy0%k%tWd;i<>Q-OD_@sFy61@Izpuqny{PzQN)gLeI|3I06z|-V~ zWeC!5){CzfwcmFNggOv4I3wsx=PGMZ1qT&pBqqK`cyxax!+^@rJP>#c;0NW;R^9T6 zCvvFe2KJ4Rl^M#Vb+9-cM04%_?&a%xM_mKRlh>jmC+Xe}$kk5_veC6jAS*vFV{KA0@h#}1Y@I1F`d z6PoDh{d+*~C|y0}hf2#iGi@NVg4yD2;%@KgFqHX1@)`zy#oE=1(zf5#o~Wvk46C@! z&4}O8O0j*ZRrinJ=*RRT%K+_^=?%`{5eb zr_j^T6XwF-fhK0!HSTFu{>5XXq$jvn4X{p8^lwO7nw!tmFxM4u^S>YA{V)rrX+PKW z-1gVdszMgbWeqrit@YbLXHHrq|7WLo&#b{IM24?`WO4FMyYseYSxA@4AS(P>Um@mC znACy2zT0yan+4t*A{e0HzG9{m&-mr?+lFs6^L|u;XQv?v#&-xp_gyEP+3?;)AU8`| zc&WB@!B+^ZF zV|%-i&G+QJ=j6H-8*mH(mX_mJCK*;BF^o5VYL6!;aVRvts}#D=RcE60Mdr(*=XwSA z!rN)bQ&l?k)L#jTQt7UV`4N@n_9}JgS`+tqpKk^zfhM;xstI&d(NaMIF|(hD7ANTFNuqhliA z#Rw*^XqRKt6}oYP_LVoty(fZK3r8+-VaB|ImWy}Rb;x6t0PvG&p9mhczX z(inBUiHG&8URfBNcRVT*b?%FlQ6h_o(HEJV{QTg`GeEeszKaPP_50V{)$`*F zb8~ZP&#sgeMm=9SDPk%7g~(P9zH(-`)OZk!e!81#?;V#^!EVfVxs{XD|5!)D@2KY~ ziLxsv5%uliNrKZH(;F~wkD9#essG$Y^_oAe$I8j*q+SCCiNMiSefTO6{|-^ssioEQ zRnT6N{<#)pZeqf3{D~2H+0W;#t7QzV`Hr}}E~7CEkb!-5{Vv$);_Xq7^a&Ua6$fSb3OQdM^#^od@ND<}nHhLz!G1jFYaN^kkFqJzdtgBJJe% zx>D$?#q+@e-Kxm6woD5DJMz*KXg*;KBqZaGQ^2D(#A0GsvxFGO#l)1^oeA{7w(;s?22RF{a;<*#g6fUSHYSTf*IX+v`TofF zOHS%(I?|nVcgl18*+l;QTYc?mM;Ra}95&P-_vmZrj6}E0YEygrJ(d#}PjVkLq$gQ! z1lpWk$%(ka7ggZoce#JFNr$ug;20deO09MVWvpfg=m|@^ zi}(`NGrCnH&3oxN$~vLQJ7Nd7!A&F6b4U~ZSd+fH%{f$Ora4l3=U87}b#;RHg|}^% z=_+5-S-(gv9_s_?Xgd{(b-%APK`Xw{5<5_Tx7VbHl`apm;7dF%3*t2`DLk|hsE96{ zcfoRMII8wOxXp1($<~(7_OHMA`D0f?>)fKHY`LybzdOZdb#c)J!%#)+=TK<*2L6}< z1qK%{rOKt{_`#4mnY-_fs_>P`MYRfj_7vlq@04I%GO*!AZ4B z8B-U1ejnDAj9EBCuUu0Sjoe)N!LY$cn!L2wFDbDgxILz0Iy;#jyGhSaU|a2+*ij70 z7~kFUl`lW-h@Bkoisgv5tH2Vr*HmXm4s+`ja(SxllP?-zCdP4`PM`4~YI*TeEj^el=hbI50Az%Eyfu1L~Ct(x2Q5!p`3w(gvcfgQ_`->4il_ zzYI=YySIE=U#B@FXqKB zymhbjqdUzdpQh8%X&FN=w{d?Z@Gukh*v$f~N6~t;<}t8Hs#~X-nOWf_%6Qvo(%iG% z!v{(73xIU&LBciDJRgd5Ft_n0=bK%VEY5C>$k3FOPn3NQMoE?F=+6LJ>5D5w^mmbt zyiAoS5KlXNT=w60(U-gigHcE_oc0M@Ks85!bW z|A+MGuV@{m9`tIJ0jBu|nOIEtHNQYiO~!ZT5S#Rlst1I6&_5`L>Us}-eVUGy{8;d? zqxRjWU(rB{8}9DK_>K&58Xq5THv4Q2cc%eHH`X`5rXK6cD=NB|`Ehl~2x_C=+S$M+ z=FbJJiOd>0G_7V@BXi@Gx5IpI-crZPs7r!HMw9O;caxvT9ikl!*^#CEzUdTZ|EdJZ+TFo{}%XSfBox=ogScJ-ev>(>@d6l;@BeF$_0+|DNH54 zPLZ;iICinlF5OsO*rcmXfErZSp*ldBun8jTcFzk!VYh=>sp2ekDh{gCGmOSd`xX7f zSKgKZ2<6(KHi9~e5H)Bn`3vV>UwL`U)?$#%G-;U~_3%ji22?!IhidadT8I~x4dG(7 zxgF3N?r@9|ZVKQ9F)aoL2ET`(!B&+1Fmc8o6;l6{=A2qq(v~Gw$zD*Y@z*U6(oF71+tf9U-98L#Wah%F5;zTuB*pkQk2GxZMJv>w@+u)Chc&~kwEdW8Re^vw6rBDrWG;Z zA#3)X|6Qdo?^oQPY*2w))|Lp%PXDDYKP2Voy?Kg36!Ln6QQsNU?ZC8)(yk03Wf^vk z%+wdqb|yMk)PF|T9n&{jMjOm2>KJgzuAhTHew)23(f5sx7lx${aVBz6C{#f~XgS$4 zZ%c&3i_zGl#dTUfp>&ViolY-HKPK+%WD>0=dXjE8`|b*HG=uDaJDlds+ivdndvadj9xlx7Fx}*yIiS7YXB2{Y*zk zr?*FO0wZ0Tc)*HBZkRp)7_j(N^6!$^ZqTb-xasGs1w!;(c4(-4W}28l5vu7M-i^V1 z0iyPmCO@|#C?O%iMMY&{X=#?pYypS+H6Jm^((%H!9Gk6Gj$A zor)Xr+ne~Vk(z6k*DkpklE`1X{f=AjMh0?YRodW{Xj|_k#_4W0wlOo-ImSwWPX6en6#{y1*o$*KTYW`(TA4z8? z#i_4^x)PSMM!|Bj&qwX3Z(7@g*4A(4O0Sb&oYXBi*ME*y2^4MJduq%Wes-3I7HKT1 zDlRhz7a*mOB>ZTz#DXbtUidy8*Vg8*F+>&ITPi>lTh!$2?a$f1AiZC@K3zaB|{K$fJFK z{XtEuU*sVl8;5-t4NEV`)YIRu{SDJKbXO{zBLf{zW*l=OPrg z&Cw)lVUMI-z;pI^p>{P=?d1C4oN%>G-{la^%C_ciNmapGFXEB5ojm9L?WNGj%JiMx zl~y&haHT;BGTj(i-+ztJQe50Bu1`{*qRF?e4oXN$ssz?ImsJ<>c<}&Q!c&lgosVer zkc1gXGkm!e!_E#uG)F3OS=R=(aMVmh{>e?Q?Xyk5JAy{=B8SUF419rKcSkDC_scU@ zM1H=?>Pv7jqKautt~$4%+f~VH4gU|ekv@ienDBi7?zWI)U*hJ#6t0HL%OqqTRYWtB0F$-r|R7& z*>sRqS9_=WcgAk%5NYvjoP|i3(=;nuiBgU-j5fn&+w`rNggz6oC`_A)k6NQV_1fR7 zV3{<*1PNixJ>rPdLxwZSh2*?;Z~&&C_k~Y_&u_lq{Cmv?e0$p?#RPB4y~e4J;uX(e zOUR`;qN-w!2A=IO>=W)~@LABC1cHJr%I;XlZ*%jmuC9FglBTA#hRDLB~4k*9nYz6l5T~M&$Z9rk=?)LoTA!!%bIKzPkM5g*7_o;HM$$Dkpn!W5YF0XWKO+C>@v#^)n3L0(_fd^ zBt_}`_Bh(MWzYNJcGL+3c?0$u5xEtc89{D6J4xojCEmw@B6Sb8?h+P_@S2Qr+^-#5 zfA5iD+0u4APFhKf1jB;LUp~f^ANV5c$c7gyJTXl}HT@cc0QS!Hsn*na1~&z2vTp&&K0cW4 z3XmOS=i~*BAH&1>5aGTvuiqbJ4_0Y~vh0RcwsxIK={pZHx*_1f*~(jgHQy7CmY02TNTd(fP#vKLLPMwk96TL&7Q z6y(WykY-+OAg<_I6kMS#y-N=aaVH-giD%FB^CA%6mE!NTdxXNVfU8g$ZK!f5?))!#!xRI*L=L6LU1eCtznk5Pmz2_Fo z+v#oH zPF)RRrbb>cwZRDT`7pG|25ylN3p$jPAQ4iBIUTOJFC6NRILC$IxI>0E*#4k zyX~oLIa$;>vdOXe@t5fjobfrl8bOG`chY8}TVB|$JFF9r=lZ2J^dYjP!|c&aJaTR1 zIa@&gYDwgr!^2|2^0PFK+P@>rLOhT^x`%JItCyG|N*XPo)kHR@Uh^FFlr|OGlR8v0=MVh>i-x!`a<#m*L+Uc>PQFsgfeU8O5MlZ z(Y;fGe7%{mt8zAx*YVNigQ$xVu>k``cv~)PE>eTTFhE#VJ)?ZY$1ePxbE);Y4$0Vg zwkv%Q->d5n#3MDQ^F)UPm)(kGn?LSOH+&)J6ioT(T!)_G+SD&AZcTO{L*-X0oZ`|B z{fP&)K^+DqDlv^{$up_s`Lk{eAG;qkTDQE9(p88y=8y*Rbzx<{hDu|xl7^5E z27m!{lcToE-n86fB?lp?lKzZqB@xT^c~{?|Bt5AoP)T|-fH0|xw*Nx%_p)_o5{e$* zRd4reoF%I4^xCO5HO7~-4U-3i^U3krK)@7dtLx>(YnYbylgMUF8s(ka8WvJp-6=0I zj3T&j7iHENb$ShF&-D6oCO0tm`5TgMJ~ImLIW_Ypul!nr1%lI}c}<(}=GwfOQny!> z4gl-qTJzqBVUh>qqh`PDTeofv506>WD%~?P8|TaP|KjtBiBm#mBJm~=Jytd{GSblK zpxSs;so2=?Ec5o;(XU`onUyVvoL_J_9c8_Sr0s-fuKPhX9w4wZi?HOC5usw(U^X^p zDEw`Ya`%38M!}RW7inr{TG}$Rdw8?2M?Y`1pmq*n?^jtifE6P#GQxKHf387I*bLPW z4@5lf0#{XLnqSGE}{2% zKhM#>srYT=DJX0DFHB1>l`8l>?qiuOJc!({Kp1il4i5hQAn*D#=x-9mjj!PM~ z3}+^yd5BLK&X^&?{2-;fCxmvBGS;QFNsE!OwVrCYi?LTG-)Dj@Yd>o!0>^UowISo8 zPVvP@lQ#mx_FjjkeCmggIine+JMugtawqjUtlwYwD2?of>LYT0Mi6Ol+iz5rS4c<*;G}0>A3g0g za<(?`^smn}^NZvJ;mL2TnRj5M0Hlzf6oLSOqqQ{VcyX`X3h5 zD>LB~!`#v+oj zAlg$ugbQ;`>Sl@BlMR-YQOC+XP8ZdVphqobK1#oxUlU4XjMmOWa@3Q%yNx*vVY`TL z7k-r^3mZoeH-f*Y!p2s)YC=6C?hp4-zqBb)@(M?H^mxzX4T4V026_n_(rAr%{GjY8 z{|HLdw7%Kn)U}!TA{S1GUi}o>=-&Dy92*PM7&eGY%Gz2{WFp~qhVGwJ)z zN7Z3D9=UnQU|EcX(WbaAFks}H$PXqgJx@KZ(e}Ao&mz*QjStugs>8?lihh#k@?V6@ z35tTytgCvRn8@tpd08{a=1bSvf|j(0fe+fd3WJTTLdMU(R(W}f_$rD1#)K}&m^^ii zo^?WAYmbf)Tq*aGR$QTQoTWNE4nM?cF|o3z4a4u^_#QM484dLjAWuazanCk4uR0fE zT33)3MP%snAX&=9%p9>uI7Af$2W#Q@iy0-=yrV+tY>~xlRW(6lJ| z^gZcLcyG{MeusiA-e!nPwxRKC!`QCe4BXt<_>H-%?BF06T@vI_-kf+w z{?OMJlHYmxc~Hc^_;l`n;x6A@Qha@quT+=R343kywl{Nha6G5dec=Z(yYgMjSLc3k(mwdtO15$ z5jtVCmYQ=b-bIIA8m#i%<1RNG-d4;Ni%e?pTE?; zo0r5PGVImk)n`c3Gzg*Xq^&KSmX(>v|E%Zwywt#m+xT86HN7!W{DG4^lHE$W5H_9V zo-d4Jl9c&*`b3eXI$!TS%(#%xF%Vo=4DuyKo`)T3;iztTW)dXxFl5{{sgCzX^me)X zqVTqjZ~q6`OFYJyB8O<`}pd0JfPW|wr)rc=3*6AMgU zZxfmVS$k@OY(#p%W@UsvO5Y8*dCj9>F>?95g`%En`00f|ovcEPmQ|%~&%C8QfY7@r z-d2B4>)0jOl=b$+*th-1LBk0@PV3MJEj$X+33!m%bh6I`r#L<^CMxve#c|9vB#Gc$M8hf;djksYR^|b$9al%`nfuZ8X1;sx_5V zF{@@NXhUU>H;(JWPCeqVL$VfaHUx7cKnwcE&L<+GIVLC)8w6goi3WhEXJ!l zzRR+6a4Eu%uV~Pq@!cXb`|*5k_*rM~Bb!)0182XtmwTmWJIC3AOK`5l`5Y>WLst@> zr|v>Zs5VERG$V~PcNsDp84V%Sek|tTi^#?6Z04B$UnSOZ+Hr%J2yJDnM`j`q-+l7W zLrP58^cKS_t$4!f{&mPOvV484zh(W?8 zmhMQLoNx>o?>|)j>1-_#JtBBH{dvN_LWsqS@kb|5WqeaPPchr7+eqw0Qs(#tABX?P z*Lw$2-G}evO{J(L6rm)tSN1B(j_f@`q&SD{ot+Vd?7jD~a?C?!_I7O9dpmTF^?e$=5JdHv0K+^;T0DQ6u5sjYGiuHdtcJC&}5@2g~_H5xM@@|CrVhDJah$IxBvw0O5j=hO3GWQLdMlT!CYnK4rL= zdVSlz)qMcQRA_1MD#^X%?HK4lcwjX-th`vrtEFI1OL2$()f{-_4}*?|iA0;i%Pq#nA;u?^mRm;1 zd8V;1w(HU*7f3TS2j*fedDD3%oAdfM73!l5K7FRxy~XT9wMy`olj8wwKG%+lzNe#5 zpT;g=Bceu1TDr^_2gpH2i75d7Ub@H5dgu1WshY3$`O4g_D};lSK9oW~h@^h@{rsLx z_u%ch{a=!POX=$jm6e`Hea9wZ#8&-Ux|C~ybMPD$7g3O?(lJJ$u1O11Y9?wyhc+S0 z-wZTik0);FDmiWM+Y|}t`Y)MfCr$rMb-}Uf=LtC)Y^hZz%!;oT-rAE>_XySMdN;pm zLt5WBnaVV9e~TML^m&Ve%*C>dpl5yGJm@uyQB)SL@3U6F)^V^v-u2PjtO^aU2tq$nmU_|hSlCx$W(IU06zx;ObbUU zGM};wiBYGLU1GYQ7k*9N81e7`yqpLp7md!VSI$c!yj8WW$5?M{qg48TrO3uBL5}@~ zuF2>rVB@*0Hq)lGUAVH69MGW@SIwip&&Rut_xCFU*tOl}rXw9Si)qsmbJEwsw?5H| z_2X5JWqDp;Qw1qW7ql;iP;Sl#tJ(Ikr z_+g~*f^F?J_$;%9(K$^4%~CmZ6-c_-aSV8&e9j$FPC4nF;=}aR)=CrS-vlvlp`^As zXVA>$U`BD>x_w>sR)Nz^ruwbSk6+r*J80?QcoW(!2d{%W)5*uvKdvFe=k|wn6m16x z8ad1y7G(4QAGo2RVf48NAml-=(L!kQIgDm<9XrLf9LPXOuNgPYcp8j5Ke6x*KmmZu75XR$d&#_0gNwZJBb#J%<6WoA z&CLaIJtd1{vzQuQ*na5@=WjrY{Y=Ou3A4!Q z6&^3*+B1>+<>H|S@d!7BM$YWx>_pMW=N@W8Opq{zT;y!Dkg_m5_x-+6{_Ag8^yjG- z2ywhw?lM28?4!BB1?ZscSa1xkHfKkQoDj1G?XwLO>iTBd+rh>}GfPva9_}O3;LY?j z_-jk&RR;kLafcX1p?=j>@t%;CV;`pAqc@M1Gqxm+=Oe$!ka&{xL-$IJzXZ8Rp{^4l z8EPY84+(>vNRO{;P^0K7k?9G`DICYMOb*$VF8em%VtKXZHvSA6fysP+#j5>6+DhkI z{~f*wjx^y1mgY;3Ie*>e)-8841kcF>r{%w4i*GNa?P}B4wDpZ4c$}&k39B1lewQ13 zptS4}MA{J)z^->Lq!x_T?L@MmEj*f>1)<9TShyp1CFa|uOl=r+2Cu>I)$A$ecWt!(xUK~;kJ#~z82Z{H;0p&Tpbn(wJA33>am zK@PC{C7)%_eWmhskDG^?_`&;y-n6ko>2N4g8l3?XEdQ}B2`!gK=wO`Y+x7-ht(e8}yU`g>J~2U(E$r__g2tl=><8Kd>Tmej;e|gXWN!z* zEeU=!O+4fJ{>_HtvYS0A@)d05rS}?v^;b=)CNUpBe;Jb!7CgfFaU0NKvXrw27ten< z_n#)@d!8rq!rUfV2Hqmf?5iu`-dvy>Vly^5kZA(_BFVCfd140_y}s&qG_~Kw4u|5b z>)vcdifF-3LxUPkI;{1y5G)}Xmzbw_2U{Zk4OdbEx(5}2(!(jBo^iq*5eyw7J0$1Q z5z7{Nu;HK-O=Ps%v2v5|1V|dQ=!v^bo#}iC3|)Wfv-4ic)tan^=*oD4tbLV3?UbL)gm)z5y z&OwIfaX&=8(Edgl(k8cO|1^=5vfutN#z9zWTNyRh#9@s|F^RyH`Q5~xW?EM}d;Zb6 zE9t|NT$ku#VzV1O#Ql`77TeoCaJ^(@BF z$7-o^NqPpT;+@scLP|s(>@Ch_s1_4dMljS~faZXI_i9gKNC%NPbqQhF zcaBQ6yq{wi!Umn0F7gS|-sKi~PpLXKk%}2Waiy2u**Un^?g|ap6kfFaY*nRj>1$T} z9t)koJdZVidmY-XMFMbICMkZs(n%j$$&SO)jLn_LP4`&m#XXA_VLR~?t++3b7c#uV@O<-@F9s$b=c@7p9Izy!BBSoXX z`=V30v!Mi;@;d?dOn<^8&qK8v0QqrFI`);Os)aLu3HWl#_bh?gJ3J~`Cj)RVbxrq7 zL$;id%h^l6+QT6*1b_>QJDyJ`Su@6_XTQh^jLlff5glP@ceTeten{1J?HPo2iuAIp zL2(2WWIc=JbUD>_`-DBqy|>$V{dLO#VRz0Q{vv?+cq<@XNp;n>M^Ry-PkEoM`M@fk zBy`=@X`!6HJskiP)hNYWxoFN1K#;1rK;wmll1@_YL0#*}B$p}=NPo>g@jy)b9B!ul z9EL+FvxzT+t4VF>i-*jq73{`*E}zx9YwEbWGD&?s z&p1%vtDVBebP6`6FYmvCxi`i*+_p~PC6;6t(LcAp(<@h|NnE>sD5|YZ4)q9_tn(@A zy>#Z{-#$U{k&K==xpm*mzg@z8;Qckjt(e&dN48c=R=WB|R4;F4Fgx`EX+{Unvh_gt zz-Cf)iL!#O8cdpe&qb&-U>lFx8radB`MD@+xda!=5?k|^9BInvA!2WQM*@7)(3QX} zdOApRt9-{U`6vP%M#(gDNbUUGjB&y}0;&xw5~eIx;?84?dC8aw(|~1aE~_n%_{JZP zGt2gWoFxP})9E?eW(3Xr-Z}&RuymVDUXRTJf zi77-po`4=IEwj4uPI7U^82gN90j1999Hq|q?~e8bj`2xD`t9517O{-ar)@{MuV^~S z6ftnMeD8e`PBu=@x*@N!sD>iSbtrZEXW;f~$OSlBd{C`+j87~Vgy;~^c21OiujH?> z8g#$u) zZ9Xf8MX4&UT^;!JURFaa)?zp%r;%~7?Nu=qq~spCg2t#!7^XQzg&MLQR1~#$r{s92f;&Q7yuVrhQfKoxs>; zz7BX!5T>~ev&X1ER`ZVhygYX~>2fueVkIwvkb*yeJ&5I3k49+czz(^EMS@|Inzp;T zrwj|>5lliN`giaZ6@~B{ztqxdGkZl7hr41%IqCj6(mXV#{o=)eN=BnAPjMA85b`pE^qnD&WoyPW&SSAnl_txZ(D`_c%uZldy{;CJmYI)DYeBGam59hdAU_s0e z`!*@=gFy+(Z~^W`xYt~R1wf4`&lq-zKNnIl+;|FE*4XeW~1}m?dJe+nL zZ(1Uh9X&Q)08`0Hzojhbjtz`>+jfkwUm3l&{H+E(UM<;&BKr2lHtE<}Sx2{vaE;cB zOvDbAnxGPnJ!YmlT+cMs@2J?{_hS_7D}8L^|R%HMb*<{glSV#O2=Kd@Fv<6re>L3}Rny==_6w;r2X491#I z5WX10CawBZC}!$hhedCqyGlIqVeGDd8B@;N1-~Y&9Td^avLf3{Fb@@v8c3w$!x~31MMN3S0!|r#= z$$;4Vx^Cgfk>~S{CLf$O4-US$7B2?&D{!wn+=PRRB(s7$VL=f#f-DP$vx@rf^+5p* z@%F3#4U>9(o&%9b>IHaXm;XlzE~`&ss+3^A%=u@C5&QRF?VY~m71U0y@peeIAT<0D zX*1E?E~YOq=d%ewdsXq8)n-Kva+TJC_Ixzhi0?a}G5=?=hy~-dv;^Az4Mn|yQ}oM? zY1%C|@1$oMDownH9}&g)j&M7yVdBVxF>?<1Q^*3s{vdMs!(UQGg%lPgt*M}rY0Qts zmN@ZSSdq#V1rl3eBCm}NQzpix-k7`?Rf%MN&PW=JN4uKE-UTgVm!De@Dlbr*S zX|Qo3s@kP&WV2{|T&~}RdTfZ2@2vJ#)v^XB00k-0!&JdeU^=&s`#kT6{G{Bp1p0Hb zNPR@!ZEBr~!0TfM&dId;0QNEv;TP!vQu#M78a@PCv;PW<-2xX?1td zK*XJJnP^iH_HAvSj_}((G>Qzzbv4EI@(j|%Z-^YSiH7+gB|n{-k}S17dyVSx!IbZA zd5xoXsH#3~m}=qW~xD?xBZhEvEsgJ zH>rxF8Jt6Yo>-oVg|cO(7WE0OOz(6)KFtB~xS`vJIF?JekVDl)8&gy&nwTwXJ%i=0 zZD_j7+j^^|-Afhv)>FG2^PE`z$6m%%klFqr8pTl?ihRQ6@TN|&rBZHsYWv& z+RnY}U8mbdGJiTsDq3WIH=kV2p{on~1{Rp$-nlV?f>g2}{!>m)5@gYe>i!)MZQMAp zN5U5lGjs&aD$-&*wK~scII?;p)v$^pNVFPFJcD+zHg?6UcdAkzcEy);HbJ-rf$*e# zVY%Xn%>_0SDQ2oqH z9!`{r4j2Jb$;Bcvno+O|XOyS_tsKGr-n#0G(%C?3g~#NXxh;!B!5}PcLjt2Y+R1g= zt}QB5M_CrXP$)gkmC`YhHN-kBqv;3ZNcP;`bZ=F7BiiX%c_j1(?L@`eN_rmu_BRzt zgg;`L4efwBFc6o(SayooA1VRR2U`-doYqI8)xl_;A4468yYgL7C~5AMPFM3+|Av`* z08P^16Zxj91H9&>{9@zk3P_4KewX1>u7!w%qSyWfC64(yKzm#-Y1&p1h_u}+>UJU; zh{FB^7Vh~^rsVLzv44MY{+GMW)KYl;+coT9-90p9f~i?}JBma$;U~`a$_e*#i#Gt# z^U&7$59I$~KeuS|!8KRPsVfi7-){Wu4h4eW)iLeEnJO0j?88g+lDwr`4p-mnvkVR{`ELxcJY6ssm>?T?kg1c8cP?{U4a>sXag zd9*w-gHlEhSPXD{QdDbmWpOA7o>`u(LM*Koh|$?Qua`e9U!qNTN5fhmjMELrF`jek zj5xB|@%#z}8Ip2(P8$4A2_a6-SgFkEkn%&vWBlMFExdMM)-c>Zon{0>i|ft?@>~pYMrxBI9F@SbHaDtd1A* zXx8)Yv2gK_l=_{`#%4mRBzE^`@|Cd)?z0RLsMr9{VvrnpO(x!`L%2Q%M)w)bpJOo+ z=hG!2H|WTVN-?J`Gz1%SuCT=>#`HL4 z#e>P<=qkF?)DS3DemYFGAsKCh4+Qy>tb0_CSLfaU=FfV$cM5`D_&f#(DmPzJB=T!h|P7W!mGrRI8e08X(sbW%+M?ejYS@B+I-j*@lD3-5BePqv6yT;~MmcO7k}1?MwVx@fcW3XUR1}wHxM~ZZA4D z_r0rmUbC|-r(mA4@j^zsZ)taBwN)x-&+0YXXhw0Utjx)rrGI3Y^*>|nZNeJ~uyO%4 zwC$xur@ww0Huas(8u;$5i5b|1`bl;aA$<9+V$h z^B!;UZXFF8jb>2IGellLL;RbH`x_qQor|c`O1vP8PazP+o~Gp}37i3fm$P`^<2fy( zu6|v%&J5XFP0Al28HhGK4AlO@ZTl>4;@Q_3l%!mm%T{^ok%PT||LD(7TmmP+c9h)p zH##S6E>N{R9&~AyGpEF4mPjEi8PdL2J4CFIP;6&qPA9p|%i_;dfCcSk2!S32vt80-SqL@uGr9slR z+QOYA2EP73kQ&e*ylm z2Ae7ISmw^!Cf}!hcty2auNk{s0fI|lSFqTF+TQ}gvpst*-GQpU0=x~i*9V%n zTV)o56&JMcti5Tecz<8@GZo_$1#mcs?&(pWumE<)ZF>JZsswijss07&rEiBD1Y!8w zyJ6#=&?!dh45;csynHxc&jB?YnHs-lt-|=RvP?UPe;W={2=v%s@grrJv5JBNbf))Na6~e}w0SZ)t;BpkGc|=&)CWG5*F@ z?#SyK?cB?k(TEb;<*^pbJj1x(`+}+Cf%GiI+lmez8V&I-6pC-TqE8a8V^itmh;l(x zGuTKO&GLPIf2f4I`?(bo9w3+1I5f*c?JO;tQpaYSP~4HiR=}sC-3cemhSCK~oP?G# zO4(W>d`^+v#N`}_t$&C;|J{i+CKnbK78Fc+wGBka9et$@%7gM3vl|UL_UQjxKD_{5PKPzkUk(8SqaY^T%y#J!H@>x7SS* zPe8&OcS@}n?3+KV@6R2MZSX$dX6c%f`BsMp9Yb&1$D(l@GiK)WwPjxFHJhqC&hdzA zNcn!+vDy7ka2xZIqQHVsriq(LveS}0*5?Zl<4aX8X**K}V%rw$XK3;RCXLQ9#K!GC zsi@9ybqoLceru+(B955ki&$#IHT`}PsImM9dd=RL{{vIWa-(`1U2iC;wHy1{#M@8$ zZM}@(oAvA)fA@2zJLx}jM6Ju9BDa!w?2Xok$Hv|S>|@|sk7@6Co{-4a);0bWR-3~! zdS_1so>VrLSG;gnN~Z()NBoo zyo?y%_*`0r(;w9LTK^!m={$;d5`z=GdUI>Fe(O_MC#Ny|Ck9&@bm}udiphm_FYrPlO?R zZUMsEpzna~fPBAP8Ddg)&F879BQE%|C$NHovkjW>-#A7ONH)@Xfm^y^MtWq%`qH91 zO}ycJ(d&NXs(d1Vt9wz?`CV-NR-8PJk{^6Io>?Lkw>$dhl^yh1Y z5rn7w?*Fxj?!kdIf*J};%Q_FUK8~#TEuu-&OA7n9;HTM? zIK_s0((7wVY4!Q;7Qn*DBO&-{gufWZhYu)L(HCDSu!(52!vw#OSUwS*+}S0Vld(QW zH|krN59mYMQ&BYnSNCR_@cTb8BnP5Pt>aAl!at7fy%-;U)yi!oi7c4aq|mO% zq#>5$YMYzHj>RJbGo#Tq`Y5L7rf3Umhg+eLa50(m$Cd;p; zD~jcrZFc|Qe0>g`=Wj*e@1)zX0*ZO>gFc_Cj+p)=W_-FHp$c%pVaOX23z#1Q3+#~c zMH;T7GkX7lYixiSR*?Ch(KzDUPwyW-Okg2bP;NeFhv}tH)1DZ;cbv99GBSlk?{diw zG)wqFVXoq{!j=2L$Szh*1*DurZR$hB5pbUR0?x^BF9aWfuy2D(xlu zdT)R`>tS5{z_$Cz!zaTQe`NAqMK=mo&fJZ976m0xOp>d(NyAF;{}bMU+YN#7u1969 z@c6#aER!0m6qd|eH)5VBh<-iub=LG!52u5zF78Q>>b}zuE<&4{bkzYt^u27>LRuI- zLkKDQx#C?Mr7M09Of13~DJ5LrX^p2WdMj(Lj$oTipzO1pg!fogZ)c78j)gC}91agG zY}YyR8=(1@lCKDwlnRJ+;2UPOP?v zQXE9qfW38VOG~Moy*&zr8vQH^b}-Kou@W&(#HueX2HGm^@$IcE^!>XgB)>%YwcQnj zsJE6AYB+swtW@r_q&f6DTGUrcQZQ1-_Mv}9Z%Y7+zX*D#<*bdkK_6`)$w^E7n@IOK zO{cZ_oK*^Lq(f;y1jzDliIk*%Se^X*OUhjutJet#+}weLK(ce@F(>C{ zLhG+N?&{`7$}@QXX;(8sR(2KsY-rS8==nNxe9c+gdI9dmu4hhUJ*h0vZcAtVJj1`N zS(^>HmkCSk8(U`7y>ZwOUb3Kl)WZ?wIw=W~N&9-JwLWSBGN)kV!anl#1M^N(i?n7| zJOZ|{brVoOH$wpR^YEi+!zyRfFbrO4oL>BNY&LgI3xDqtI!J98NXS91CS?^BK3Ywx=X||43yeD{WTgmtxOp`aDc)yY+*>!sO)qOVj9JOu3R8G%D>!i#u;AvI)M>F&HP{aC$S+D# z4Ar?gD}9CRn4Q$mAirY@&;2Hb%HEB{5<|z_?R2>|(yQM&2^Hq4I$CY2il_3!Tfxp? zfO#>f0%7(w{Yb64>1DsI{eGG5m^#4LZ5=sM|Ij`4&t(Jqjca#i#+~#`*xWK>?)u)p zmHv_!>h$!vXQ2a_pH9igr>J@qMRr`!dgJ!TmqP*e_%WXaL|&iFROW2fV}%2AQ3`i% zyl9IODb3OESQ?}!hEB^^KD|OTaQB_(UOq`eU9gw|coz6I4S08Khv~8&47|OKx(U`i zsJ%UIZt-ewsa2WIv%pdvmXPqFY3!+s%Mq44w157C_kK8@lOFKJIOBHzv_0`8l;vsp z)1F|NpR!kI%XJ8|!VXWsqTRxH#e-NLLn zWGyWK8fJk4-B8{I03YS)>e!*_`sHB0P6wWx63rJu)*hGj804wUZ{~Y;)Cjon_X4Zw zh4a?lR{~y=m~$iqJ#MY+dN5b9qx%ENN7)~;UJVdR*W%-$_2fYBXMh23-l1*yQ;uXw zGk;c7g=t+5vx6MGK(h`a^rnF8`RodwNUpq)fFJ_8Uhc8k>0cJeSb#lc9sO#T>$QLS z>fRh#cG!-%sDf@3ROS-kyxp*Nrt9bVg{0Ls=lVYfFrWw{>wrIs0y`VrwL6O|FZnVL zzdXS(i!k)`OVYX*POT*31-I4TMwoO!f4C`EdtlRL^Z- zq`&`lu9$POtAa3ZT_C5T5828~b!W0gIb}K!!{HW1c~M6QfaCXy|H$&ryKElqy%#Q< z_7;mS(VJTaVwJ`Gh=(VzW^g}#<#;&$42En3OvD|Fsgp3F#STpQS{o7>J@~7%(phuf zS4yMfTEPHIG zd}#y!**RJ}_F?ULGKv@4Q7zD^v;dUGJjx6xQDYZrebLMlx6=$Ow3aHCGqXg?H_5Xp zjxg~eK=WvPH>4D+xTq7Y%p@(buoD8yXF;%I#BctUy*0hW+!W1m+)V^QyB}$VXr()y zM%zT>@fPuG=ky~j!o&NWws+*#Wl6(%&uA@$xU@WyLveTEVNO? zn>}IzMU!$}=(p7Q|7+UE2Al4qxn!v`{nD75qMXYSfmTU$i+5FNYBdRBOIg;gg|q7Q z3wPk=mEM;hHiYmlj%rwZkwrYG=7Ln_pU@`^s#mn*d&r}*Vjsm`{uF55Yo9jqYo~f1 z56heUChfJal(lB7V~tO__Zr_<_PUazO}+YhR6~sE&t!y{6881eatOho(^RCv7^o>6 z2r?J^CeMfL^(L?7z*^+=966FMjb0cSAMdCt=o%VoZZC6>#x?Envfrx;vtt~K%rSm0 z{wTZ2kCu={_G-`6={ow~rMaCHF1=Rto*ChFJoPNYCVh(4ARkX53eR;x_cY!zV3$BE?1>Q-F3cu_D?815t#le`j zmY2aIMhzAjfA;WOZp%@KOLyr7tT;B8?CVIy&Tc@U@Yw4eRCz$PlrU;xiODwlE9&F# z;L-(9gU-v0E$v1{W!#%I?yQFNB}@N}*FVPtb3u#5X_} zD-HI#4P^CmOgN&VIk1Ww;YTOZwX(~Z(^^8vz*m!dczIUyPq z9J|m>+cZ?>4ghccy>EsnRk#XFV__ZrJyRHYYjJQ9h$Y2IC{dhAe1gI}%h_8YcjB+b zy^Q>f+*519Bb~ocg6soqF?o8G30X$4Df=96Cis&kKP!uV?bB0vd0=WM%sqc4k0yVs za$n~KS6<%qTU_%^Ci|=0{ukTTHa(*=B`z|FT)mQtt)l-~|A{b~1sW*vp>rxVDSeHy z@>MLoo2twYv)&Y5dG{1M+Gy1p?A@d|%NJ8gR+Mu!D}RpXL4c2QZCAhOqggh;z^NYW%(9U^#1}%bgH@vJO)nItxG>H zF%8^%NLb!Nx7EdNkI3pcFKut{G05#8_t@`WNlOGIF=d!8K@**R4d16a&31kA>O;B2 zwZba1=-fFRSM1j1)UK%$>i0B!SnMqslX*wV~P>0XHh!T5THmlMleOuk+@zNWj_&pknY_)HI-kypv0 zY36-zoM3UzMrFYkc;UEUVzG^UfNp3PT8hBzge;g$OzhoH(G-%g zATPp-J0GaGb(T;V5~|6`UAJuz8O>y_lNf%Xcgt3okkitRyX7U#Y=xsrTj`+%Op#5V z^x;*1{{LAtQwq#2`@CPruK72jw=Nd2C7um`f5cfpm6gE9{L%}k*1Q){D={mjXCA6FJ%6|hnBY3vm+y7`ecq6WC!mdfGi z96flkkZ^XsJ;Y+IY`*aD(wWob_vwVflW#HINWS`KCCD~27;yX^Zwv-}g)oA1V78!C z)3BS8FM$ehb3Y@eUS3L?*x*7&6YZQzvPZac&7vQ~$}Px`m8SuQ?t+{mZdG1njp@j{ zt%Ee+y2HUoUT!s-r+$~r2e?tJlB5`?3L~s?x4+Pm8tixX*h?Y^GW$A(WCdJyrkA3V z5Buqa+4yLu{G*eipOD}e1(s=J(yGclwtK6zGkcV$lcB0jd4Cv+zE~Hl#ns@=<~Ena zI`3-~e4fQ5d-aX+_h!q|7GiAHA2-25>;(hn8~EE-?rJ0Madmj^vOXCR(G1-})&5m7 z{ul5Zo-Enf1~!t?x^DBHJy!FdT0^Dj(BD41<25hfE>ru$Q+NLHEg<=?R1*M*d+fU8 z3|D8@XQ_FvUMx`&=3CK5ev5>qBe&FuolqmQNmSx=k3*ax1Xq7q6~cy&l_1g*@ZyV! zVz6U#voCXfErAruQUyvG*>lYlDsbYmlOc5hF2|h^7(|-S;JMB$X9y!r9OH0(-s^EH~h2=E@V3{`e zRjH9YdJ9r6ygn7Z-BBH-`bwl__A1shMiZf_)gs-c(9^ObcQcc&pzu8Xo6wXl7XtRw z0z>g}1 z)t?$G&^9TCItGX@2HY9dB)1HGbRQji(+=C^QQH0xksSxn;*KI{@anwr4fd~}Ib9%< z6+~khwbM;Ol>bEH?2@!6H0r>G<05&v0$gw3JBn3C4-)9Jv4nrZN<1{zo@=CZV6{%N zHgGbQMEmx)lDrXrfhUy5HA>ekXD{pl6Gj9#HPqOQtN#{I6QE+k$&dhS)ZD-509pLM zS*uKnSau+A#y2xHy|u!U0(yGzf#T{s45zEFl%bprY(dYkr-#2i%D=!Tswp)ht-1P` z>q}2hk4SD$S;gg!q9@a3uE#D}Mq?SkV>xTu!jIiu%n@Md#WwRlGHgDRyrEn2whro@ zK;h5e2`@~G`CpAqaaFjUT2yc04fcQ!taH1|ONXAa^UM42t&9?rQfiDYl3nGuc%et} z+a&rib$pQHC3S8$-uX9lOiZ&Sqg2T>tk32=N`KA$lFgZ|c)lDg*^(=L`C0jc4VwJ5 zHOSg$F9bpe(!n&k#%^y9^wdU|Zrt8DxioQ4s~#eo$m$jg*pdc+*J?&%F24zV?r|RF zZtanY$&ocTt+4WUR=Kq^$rcfhX*M@Kuyr379Wi$@6MwR`4Zhi*+7#rX zrM}HEar|=u2ANIl{`e^fn0#(K1CA$Dxf;I6-f^I^0P-& z;5`BtuC>pgH6Vb`-UW_lm0#Eq=yqt~`A5$gHHsI+K7n+Yc_puO>WZLvdU<&i36A>3 z-?+OWO+K)NpS}IJRI9@~eSr=)Xi0nTmX1K+(PJXug5AUU%-CCYWbPL>2*vNxLtwnu zt~2?cI>9taXGY_eL5o+;$qv=Q=Td zJxRlcH-Y}SEBK4#I5I)>y8myZtREN|z0}myQKCI$mC>7s2?K)8kLKdR zN=!soscw7^s&j{&dk0PoT)Ptr%qKNFfStDL%a=7Hi}wn+MVP_m=B%u@z&6V`-g$SE z^nqBwPd{JaU~O;WPC;IHZ;4VQ6^`z82>2DI-o z;kRC85lqEoa()Sl0}70?1eS zNsO*blZ}xd@v}Bll{JmS(H>xIdx+Gahbl$OXCp`)HgzZAK z<_*C0l)dEZ6l?(}0u8{Iz4s01iL)MHhpLjbpsvJp&Fh7@0Sl|EW)KME?c0{s^zYyf zNWU5QYS|eFAE}7m6Ct=CgB!5MIU42<&U9?pwD9bWS`J+>eD&S^B5?9GjD~tDS1NniXToG9Z!WD zzdA^~jz`Yn22i0N)SEJT(w9hg4LfUv5u#{?IIb&gk{T z^Wixt_WV01Z8Wu?zrW;UiB?K=^~CI_&mb=K2)ma0K}r&u4&cBp#UNL?K!u3rv6yNg z(Zv&0llo102jAaHpQ4=L_docPK}$ae`@sw1owF$wJQ`psYRRWNepW3Kw8UG&)GoMPR>ejo_DBXN zC#TiLI6+4n&=Y2t`R|k6XF>d$@+G95o1fpV7X6VSpZpU?`sVK$^mAklV)GL;X5n8= zSkhAL-m~$M*Vs5Dy+rO%SWa$Zv~bOvgj;-fZ6F!b?0A(yHcj}&!<}-Yb46ybX3H0w zP52HS%h1)2PL7&0vrOG(v1?%5n7h2m(~T+$%pG@vf4dB97|%b8cgo>`3~aB(#ug~D zGa%hUmkIr_qohsqFT;1$Pdb@^Lk$>?BZ0jZW6|Ezg|4Dh5=xFJP;J2aJiv}7pX5ej zP%8h{TwZH*5g!!usoQ+G)++WUF@!k$`MuiPufRdg#~^LnQ_k?2dpyKDHLrU9OGb~j z?4|_%4z|335Uzr zJMf={QrY={#!0edLQ1)Xu0&0gYRN`s>U|w!Ji>@|EVVIjX`;V|HM+QneEmxZ+%zfKnPU4M1+JsRV2U2cf~@8oZqC#0m6-XHs}8^<;+{pt z*vwF<}&F?+5DTORZa{guvY=F<*CCzdYYf2Hk;BSqqJ&{N1&9E zOGx9_?UNUaebnE_c7qQ)1~507Xjm;A@xkpF3y*7KK_?!LA7rM$x!^#YW&Ph#`y?xYNFGa!3lQrb z_u?&d5h9hZvGySQUt`@G|DeJGBZgSFMqF@uB73|%PC={9B#OKbk%#{mSJ7eC1BSvGQx1cr3I{f&B|nXW%R(?XadJx zo@_0q$8SL-$N{Aoq*)By8yrT$SjB;(R+UoFE-K)OpyUQQw31__qnlhZxhE`q9Kg|0 z!%vm^&(~uEGC<^uBmi7Nxaౕxu=!%o#&8SNM`yhvy974jd)Sjs zV_CgJDepggi7VI^GyuSqM# z_?PS&a87K`m+Lv)1pQAO;A^6593KCoJnst_FXM!`@=8k2_Hw}Kl9G}V&^^s^7J1{AzVtf>?i=lYuQ>7^4r>=Y4i-=7LR0?J$cOwvLwZ#7PC|7Hq! zfui=q9>L+iHf{xgGn(wq8nX`%empug*34`GM+(;t!8OSI<=^iKe8#1`NYID4J(lUjDmwH_(&jzEjRO)QB8&78z50&?N`A2~ z&)@#1W_0i^=O}9bp}=|HRSX6C!>&XIYkv83_eH&YpmMOR+q{&I`MECl@Znm_K%eny`=s8OIKM0e2;+Fulm?Iej=Gm z9zfVok6r7}8%*tzKARX0E7F-@*M{%8iCA%G4H zxVXh>@|~0+c1cjW52XP^19X}d9ha&CA~}q=z`Mfv^;qv2_%rQJ?9sj-R2ek+z+7X^ z=OTnm0-P|37XC_n>lWxXE53c>tbjVo;1;`@Xa+l}&wzY^uv+YK#Gww?b>R(i$D?=+ z9@BfQpuE@snyhQx-%e$~%n}T=g(!TIox6Sb`mz^8NVuLOdKIc1ttTH&FUnymI7MI; zmETr3L~ou{muQRu19)Tk+Qv5AjU7#<+Lsjagv*|eyllk!hO4=QBv>xub22;8U}vYw z!*aZdONpYLfiB;1ow`~hxSeh|xLz`4~&Y;-4M`>qNZO4(|Rk zmwUHo>TT7golHeQ(hq@I-yI(&AWOZ~y4Cm(PHWMIvpG%oYOF+ebSsMBLj?Ssrj$T7c!|Hii)|!=&aTXs`J- zPxFWpp&D2??bUq{60{)u!MkwBBkqxw%PpJv{JLuub5ZXGDL7ewx0@Sp&sA{TjUHL8Rd3BBu9&Wet%ECzroKPy4bMEPDKFu6Ao&b?f=cSB`>E{E;f<4~R4FXK5 z&uTWMq(o(@e#+?jORrPE%EoV@k`>Q98r#npM*pj{i6&N5Y)shClMB7-kx^H_15+>n zS>^m&Qr2@ctQXFGc}E~Y7|~}l3J#F9-?L4uTG=_aH*AYwgO9$y8lCd~k5&Mr{g#%N z1>gFMzo!RLZnuU*9MG>#00Gs_bayc&;lqe}tWKHV2Dq1eoX&q;CG_WAA1$c}MW+O2 zm<0`Yi1*u*@&Vu2VV>sQo7ZzukFno3@)G5r(de86aCW6k!0F+wDP`g<4GU;&6qDV; zL&cDA{ltmy+AWVRj}c;>&pP{q7`v9*55K&ZX*x!kC@Pn&BY=4$wD8(+g-9NR1mGKC zr2PH-7UD-)^|1Wq=8A2)lbbOYdM*rr^;2wq*VtHl`#t31!h(6lWL9%$XZpn<+ONI; zD%=1bja&N@;cV}Y?*2Zx=jxQ&b5_h@`j6Me%LOvzPzjRn+V$K|m18TXclef~Nq0gd z-@6d7Kz1GCyro@D`~f}FBEm+03j3gHG|A}Q)8ffh1q#%j=7LgQ@NUU9VtYT%5iq~1 zc`E`=>iJ~zeBS-+9TETr0`iP!>s_5YZV6h3jPQJn6#%=b* zk49ZWgsi2;ThdS4us1he=z)G^6xRc9V&%yVP(;8G!bN%3yh2uqnTD8uuC(``W>L%>`JUy zT7y1t$Hlwg=e)nWnP@Tz9AGAm_(x;zYPHImnK5zi`$*r;k9q_kw^@;EZ`632-FLo* zo-vI0MZ*f+1D9#*vURQ6UxUvfg2VV)Jk!0ynhV}f?!9L^XL9b{+qYA)w}Ba@IoWN! z-{Y6lUAwe|gr8fjEXH+8%)c)+0DxmKluohZ@AmjMd)lK(Xj+1(ZLcaz5B?PzuBJxE z3jGdmQ(pR>tm;J!S6kin%<&Q_A;{41|D)?Gpt9VWwjV+em6nngL(mWsy|J)CHJm31h-?d!lyz4#6-uvEr=9+7+nL%8k zoaefML}ccS=8(^&WY{N{khF(*SJQL*2WCNU-|D5$#4TRUmva(J5C8o@=7RGZ`Fv(-}Rxz&E4>m0Ruf_3i%fsYpzd3@Y1mEA1!H_eX% z(5V|u$~Cb&awvgp76Em^7*HpbSmWaAdh*1H62>z~zZpC{)}f&xf(j;^@lU}maa<+? z>K1=G6~cCb$o7o=i+EnqL^~$FzESC}VXz&%4yZ+GZl1AQ{DcT>oQ3#DGGV`sdZxDI z_;tai##^+L6UL-4!-w-{2Y-J%izxKYe6W|2&D`xcOs=(yvV0X_PA5>ntMIuA04#$V zI3hoPDC%FceiRk|GMMUPz4_|*YEMZneUr9C{%*~iWYE;ve}f`6|4b1Scb&?y(bSB4 zymN($mTv5QTd6Vwo|JKrDK<`W{m_j>IFK!Zt!(wonl zG$kcvN6io3JhbW0_wiP7buDipZn_yjNb9h_(f7`lJ@7AIU-_NLhqHM&a%DBx~&7I`m}+8jA0d(_45cgPZ{5M9Ua&k(ns!_ zBQbqkWOtVCy?jW={K8M#zSUll!aP&PPOgiXaZtp7Gng(3?JI*#8l1*QnjbaPKc3-% zfoD_3{8_%?hvw;_*n`vha3;{s^{PdzwCpEmy!cb63}JH5_tt^JmK9{cobpfWY^*#0 zhqsOy;vR*ua@SS#QHpcR%a$;J9;`wASK66W*Ck!Yp@xIp-PWUH$1cVt#i$%lk#lBMs>U_=6_0&LBbJazCloX8NR9 zw>~nZWjmgBr-#;jfFrE_7OfisbBFEXYosoKTViB8!V=SpQ^5QOpM&eg z^xw50%H;8dM^9RB=oKy5@!(qqi#XAaj<=V~vRB5fp@w%~x3`(!y>DVizJ;DPvybb` zpabNdeSbX{b1~D2Ki& z&~^=G%iS5;my5bumW@U3aql%K!2+@Q9?v#d^Yx>zL$ zKXGxQhi%{o9rQ*t$8K1+XK0(g$WC(pX*A{55mseYH6WCqA0D0r)6Hm*IhtER2EVZh z$yU(&6`UCt7Cur>RVCR;ufgR>=$Wk@;E>jZcF4m86nuJeJB!3b+k?&Kh%edOnnhLp@@{^o@&(8|cdvO% zvq&)pOJEZmB`rjk-`ZE1NJ$z!9S|Z>v*1?fXcCeQEI^{s;}VF8W{k!I7YkiXIHAR@ zj@CP4LKE$kEl$YWH4qgGTSef&K;`DP#~_JMzd48})wpVbeQg23o~R8i^vtOm z#~!8N<-=UA%uK&NL+>PfZp;)&os%C3PH|!589dL<&W6#X#5%;vsbUG0>d*g^iJ0rj zRIA z=0U|;dk!uwrkfC%e;%}M!B^#?8Z%<&nW1HVq*zMm6*lpQ3ca&lV(HCFB(bG0A=`}v ze1)H70CNfw>qDx7yrU)0R2rGg+t4Wk_xPc?Ikcogd1u3!R8^%$>JleIuE}x8o=WtU z%<a+*LEn=7um^6U3^r1pMjXW60XA+w zDNm<*%8XAC)4Ooa0sE=SQSu9`cs{s5a!uc`gXpufi7<_=isevqMtWIlXNh>prHtK^ zE=xZl*ck1B@2HSjTjjnBofmbWGa{x51+TTHOs5&Mdk<~;XFDr@T3SS^8op$9WS!l)5qNIasTpgC+q@*4cn%Fi`ueFqR4X?1 zlL3+X_F%oSxxVXj!FV!PW}!RN+K<~)&T)AzP3<`wmzTEk?-^FcUw5MSob9}fxUVgt zk^1=7Yt*HFzk5+?zp#3Cbyes&6(JRuzLe}2bCh8+rtvcXGvEA?-JR*sf-2?5l{Qa$ zsieuKiC1pJWY7|4eOccQmT{PwI^Yl3#UNyWVTL0koc0O68ev%d1vshO~H`;E}VgP(kSjo5;yC~KI^ z$ZJ{7S&wkzxAKtfw^)`MZ>@~EDK|X;80Kb?83+v9y%_)T@%ze6FD8DKuU(9hb36tB z23M>=uR)WW=H4(%n#`BrZ9NB*14I0XSv1$sXh2L2y{}gON7;k`Fj|lP zeHpg_En4QM%bM)Jq3G(b?v*pi=n9@tEU{FYtkmsAW{Ql-P0V(9zkn_RVmnq-TZ$W3 z6x0=BuU1v6@Er92ScW8&jwF;KSXYgaO04q_wx7J^`QnO$htYgR`wNfm8`h0YhC{yJ z@~9|OC3;7|L+Zk0KdF_m`YvoiR@}HEkYx*ztA_^i&PJ3xhw?==9=J!g|s&p=)agdMPhnoUK|hI#D*XQbq{zdkLYJ-|YN+Ox5Jw ze@fi+|MG2Z$--!vzt8HOalZ%iM;u-JGF6|Q@qx3;OJNU(kBPtHosK%5exPb=$g(Ry zMh6CmAFlv$s-a0!GjZqe{8am5pg+{a1N<@~yA<5@T3`GlzFmrB^govb>f__yU54(S zHnuWW&z#h6-|h~9x~rI#PY-mO|2!wuDUtwU##Ai)_z3&Ad2b#xjnB285GO`=3JF)- zvC~8-xtfeE+$ta8<{~Um%_A!HK69x!9Sb}r0+8WsM};&^#p&H+B>T%(<>lnW|0kI5 z&Byg1^;4DV3(nw5W^^a0a}{mN8P?Ks>QY+I)}XtyQ;v*7W<%zQo1W5fAM%avD^4(p zi9~a1ZU`1DjQom+_Cq+j=ZiO#V%Sz8v9PCn+y})NL0Q7gT!I+NDRhVAjF~7yxYpC# zT3VkExkt&MY5q&AM<)kSQjNg-dO=wqXZ`ZzV@u0ylj^LjEMP@ry#m(l6RuENQV>!i zyxjMkq2@kL8n6X!V=c$K^GqRwD2Nk9x2{;PpdnT_j^m4=`$~>lf0eIyU*od*7b@@= z{e$Nr?I$6%VN_g?mGxCk^aqk#D7a#^(Wr3N)!}=4hFMCrcX#n?b~=rx%}zhO3vhIs zzGkZ=H6EqnrIDz_?dlm;F=k2x2WX3B9?pDkA!dgr!aXtDBY0&OYRq$e146ISc1GFI zqG*6y=dMW*wq;8@#e}kRa9E3o=9w9;c-e;RC8A`|+$FQO_cmNggvv&T5H?28x0s_c zeSZD=b=Goug2!Yyj&@DAVBp3a%G@?>v>fh{N5CveGK69VK`p zy?VoBDZR~1wblVdx-3l_1Jm+%1)DoqLWQh07W2*yFibJ`C|V^ym+dS1ud7Ff3_+7x z z1AlpXafjH0?Vbnedu-&*sY}{9K|_d1Rev*KR-gQ0iy$$d;?gUf_UZFiH^%B;E$h;y z-0BoFdTWy!Ad?;XS=Q8f@a>1{^qFLYYmh(~6P9j$&=&m$tYV|dv8|b}U$^~K9f0tA zQ_8$ zZo0_~che(Z(dW*4VawTCw?&)lH*eO(RVYiFPTJGLm@I2rRBlFbaWMj8c{H(?{#;EY zMIXXZQ1a<7@tv==6X_zW-o&~X1r1AWBbU?QwDqZrc0Ou!S(kqZXzHrj z+>-6{Du_9`L!fZmvQ%44@2x%T+q1m1%){WTaNM)~W8zehgO^&dRyBOqI&caBDd-xY zIXJh<+-fyWAx#r<>mTV{GiK*UJ@H$*=}%`F6}E>CpQ$O=J}2S73Clk4i@vNgiQ zFf}z*k(b%3omOm!kGN-XUKnNRu0w)ra|ujiWx*$_ z-qr+2w+QW!bno#pO0e-}fD)*g=NH6_M@} z%nz;VjEXqSPj)QLt{zgRGAX;N*-_4)vD<|zQ~mzOn!;wKkT>Yt%`_$mmC+#G<;7Gq zx-x4Bc}C9Q!R0-hyzG;SiKMXrr9$`Q4oUc|kRNDMaKoE}vAe3&kbbtNz1{;U>WOnx zTfxrPKC-}$(;xg2cl-S02DH!X6GhojMM`kHsFsff(0+HKVEyee>P)c9Tc0r{)f_A> zA4K4Pt<9e=h%mdOSvmQuZoGc30|sx#dJ*Zq=;I1gy|ZEX03;SRGv1_~G2ccWMG&o_ zlV0Fdm0zjd2aO2#M)~puF=zFS%1{;%gE7ol@`pB6|E%yz^*WdhnUzZ_U*wd4#y z+$mrs=uJq&b2W|cYy}c@3d&0x7#Q5p7n)7?Ezx#%#%FZn&Z{AYOm+_+#Mbv*=FUlU z@~T1(6`j|I^kl~?=v19#w&i(fHM|)9Vg#YruqhhOubjIk@9r+Hw}5JXG^>>Z?>o|! zf4#(`iQaLxH*fS0CeQwK_ zwBE8xN~Q_Q%cm;~1M@d{`Hwmd#~|a?s}RRbe`G2=uhmQ7kOGyzd^JT=S}H&c>eXme zjBfZx+R;%E*_FN6PK|sR^$ke=M=sa?hd6`Ug0j9cOr53x z^EtBM70&m*j0fV~Jw5fZY%fZ!KA+kQ z%NvF1<%k~%0Y6euwe#~IjIC*c({+}jKP6GY?X8FVcZo9<7y^1dIE+{YGr5e`O3Jss z-cSms8G^P*Isxwn;3eRA6qr%Rd%WiKd5XBZp+sl5Lls)xnxKfEK7G1Uqmyc(MM*JLn#n^+|Yv| z-UyI|RU(JC?wwzcizo950`0BN_bZ>zr&;k96@fsOf$1cl*Wf9sU(E*O@w}`fu&n5zl8lQY8qX6?0iD#-a|=cV z-nb#%K~{qAy)fQ|FJL>ZynjVv{?9@o72C$&*LsAM!l&+-_JF5 za&WPhg-^nq87DvVHA_oNX=$v;^ruQxA-|BX+ia1%rBWsJIo#gpr`)U-c46S4eOjD9-WN_Wkn&110n~9zDZEB_7haSf3tQ z-UU9Z7>n=>3BwtjisNLsfja!&Q;mH3BJrm#T@_Nx0nuf9yQ&4AM^0Yeg!EIyI)rZq z6P-dfayxnMS9NL7sp``u@ZL1dypl+pMPMp3?A+}tdpdr$=u(L<@|7r zH4%HP)Wf_DgMp9c9Gb(<^RI2WD%alzldFmE%y!|^^EHd(5q{xfhpxVvlWQ%7CEL^5 zOI5BKrl#}5m5loX)%yc|dY)|@%|ghAfiTiMVmsRB)AVtrW$#Q8AK4qYYdc=h zU(SBF>kKf*Qkh&Le#EVx=1?pTJ4XJx~=vtxc`k+hv(v1;%zN6M5P@(Go*r9=JYIP)WuZ{rHdV*w6xg8YGb7 zM07$chX*5vyR#YXCaKO@RR^gwyqv4|w?k-s@unC(wn%4E1dVEaewYt@bYH1;^w=F3 zS!3r_1d3y1r?SJHN1|T zq_@Gqiq6(%Kl7&MyKvYkOPrTqVKdX7f`IlC?MEy?dVsI{Ei+@X z_KXlVeVni!Cz6sg#$*)Q)+@Ox=>XAKNc*qaP6Oew)m{Zy0@J}KO(qr8XAT; z%Mwpti%LA@S~8b7w>L%{Ny6l{zOhld2d$G`)@Pq_Xs)q%7-PiLGHsp*GoIj)^7?da z&2My#`3Q2W%Em~>4&AseP+BC>quf-$Q6z}@ z$XZ$!uCzT482QED`OwmG#@oSUkH+}}?bSj&Kwp^xYz@xgDXLmpTGPuv?0Cn&(LyxV zDUN7ds6iLzmiel5dpc=bTGAKe*$l3xp%%Vym=Mz6W%^#^L$bZ?+aZR|*DZJ0|5aQ) z#gH8Vn85;`K|jVvJiB-+Yo+Lm&{|H0#pAmPV|tW-uQ>kg-#Vht=g7Z9=SVafT{=$$ zhvhSo{*V6A7r=!t0Kz=yIO?ZyakjjQ#2_^g>jepVlH+{+iw8IWA8(S`ISX50>zV7& zh&q_v&ev?m4?7Bsqdx6>k_OT{+?m!pL4X8LexY#N_jdZKiGJYfx5Fj({1n6zcR6o< zVQ&i_<@9hiG`OyT1~OT~N2`|$rCcpyr{?(?^%Da8Wj<}+r*&)Of44x)htbi*|54zb zi&NI`$x@l{Xh9sAIT4CL8RML&waCP0_$Ek(`pqB{2!gP{l6-K&_;=TXrID-}qVDy#Bkzup_ zsg7kX|KD&4aFeY(quVEL59L4e!k=7Y19g&U*zRSPP|2nftYR3u({lFxGGrB;)V|lM zbI^D-R_Eu3DTr|@M0_r{^BAr}SeR(_OAlLDeYby*MIKdDRGAq?!dR1vV`P5E zL~g6hya<^uD33_n;>AY%HVGxNnJ$GCO+EK;{r4xFPMvw`303z?gQe(5&pj4PB^y70 zeiddk^Gh=33e-^(u>tEbjbzuzZ7 zm;aU=NU@-O8I(fUZ>wt8#albSiw%k;g3qu*&HD;XBDd3AR6_BNVC z`xw**T!uO3X}dkdm<69etdQWyATOM_PXqgD#0qsOM0!j{+gI-|S~|NvVFG&zD%m8A zic5e+A!4%jS#(-j^~07k=s3yh>eG=;e&pufqj}2G+H+us{?2DmV9$x%uM4!ou8~wa2YKr~y-fw+c=eQhyrCc(Lcy zmnxw$3^E<6*mK#%#c_?v3L`A%-B>Jl2%XWrp}&yLMm4rYSA3?ZTF}ECYMQfXk7Gx9 zsf|~yJMV3+?hU4SAVI3vDEgbGUgfVJ^Vz8`iTVX6ZXh4#yMdhJu(RfxL=ij}Fpw4) zF!BAmrn40Vo%7clw!K^}tz4mhuNF=oU~y0=#!Lnfm`#0o1_*shRrL7RuUci%4}qCg z)k{Ptl>u#M(K9JH5(4L*s%M($sE1qN ztdECiU0Z7}5!&I=Is^+*PjX6%r<3ONrvDsVB!0>LY#JnzVH%zE!f6eIPk4SA=Ony| zUTw?D2E+x|@LCKCG3Xuh4Ioloh?DsfJlM?&XZ&4p*v@D1SR``OrbUT}h^R}FHSv2V z03Bse5Zy{1eATImx|6g1off6_5-B5{Fk9hd@~pC?=2v-h#?$fVPkB=dy-AN&a|^ks zIi3uXFv0N!n^fBszgQRoHgxy7~1f}o|3gxd_( zql(%Hr;LL@{`-PRH%c)Tiqtj-T%d0Zc#myfsUH{tj?ZUr9Q>-y%H_CcDI7vMHY}jf z@#xcaJY0?RoP50@3ji1pQ1v(D^G9(zStV=v&k-Oi-P(Cc@-HlKX`hYBQk|ZW0fi{w z8O6&`4_3a>t6f^oBeNcm1@iW#_tFrN6=R{k0$BO>?c3@jKoN5$pna6)ehgXytH4uV zT3R4`-P!%^TLb=k9|Cf=l_szE7^M_$6yk|`B=>vP=covVb9F+->WTY{3?}prcQl8M zJHXfp^gZi@@VolJg~3P@kBWlr@FdiR{E2QmG5B1~55eb1HJeQht^fdxrGhZ1UK{>e z!%}hw_yF#{)2QL+dHryz+k5bp*C7uE{^aY(NJm`i0%F(l$!WEuR#1L+Rj^V){hI)z%&w1GDTtx zvg+IdmssJj=qnpYdAuNZFceVLdFA+(u|QYnmP$m92ZA1tBt)O~`~{fHrXSD7yA-$v zN(I&&Y&Sk?`1h!0O3p3!di@(aq(0br|Al7n(!WlAfvu<^l*(4m$j@3LY-wo;>KRC! z`)q>Yf{sxsDCd&hoMm0xsyjs3RLk{R#v(N6QH`U=^$bS91;&GRoZU8ZPjlS zw>sm^hoQG{LkhvAB$%WMuQg}jR;w4tdmN0O=Vg67M2ioAyIoj`0sBZxr3(S2cIh#U(% zRqe5@^X)&VqnGKJ$gztCe=v9*)B;I*h;3@%Er`~fg!Y0+R;p8|=EhT;_4RdNT1yXO zp>9_M#wEYTI6=aN4ZWY{h?L0~W#bQDK%$Bw*}hk6@6THM$JIP{dX_yl%k}ogsSalj z_Y5I#fgE)Ny=azNwc?86lpEsIK9RDddh9%6h;ypJrDU3JOL9bF$#mDz_=(8ZRhGf% zI2qpbzr5Uk4%zH`k-?xQzSBjr6&dIdLeCB>z5q;%SQI%To&ESx{%kZHuu~l@+>Srp z6kC^Oc84THZLmG<*Q|U1m6C6=Avi&|r!CDL9fcs;Q#*DMqs?hX!P3(_4ndMRPF212 zS~ z{>f3%|5V|OhOyDD6HDPN5p-7!Cz&-IM;;&C%n985KOs3H?N1foT|&J>iac||ASpph z;02wBkU6cpJ3B(elbrA4M6pmfkt-f01pszwpUFcNbkzk^=|2!~teX$9L23OAG2YQm z6fgUX%zx;+=R4AJ?G%HUUt?3tHD>4~PIr=uGqcH#!9^0m4MsiLoKBZ^@}3v|&qby2 z+4D#)ey(vWM?p2xHP{afHKlM=mj`adk`?t>T`#J)xA*>S3i!XV{4CUeU4B+4G#MqU=dn$}pu-Qh_FHf7+oK|?X5qQa z7^ije`<+pHH%Oyb;&%C5Sv!}9>mxIfzjL#dp%r{ciFmO3on-KxAv4Ut#Nm-hXIcO6ch6mVsA z+C`VehT*S7el^#q!EHM_E95&wh)|0sBihk&^AMGBA%)-*M1d;Wc7$g{3t#zNJh1I)P6| ze(4_-O64Nw^<4H@kIBsr=acoa5Jzv`%Sca0ZSJ?iD(@Bm_@Zhgn8f@U8(OsIKZ?Th z`R}$Sq(cyw&m9%LQ`wteYS|F-OjGBEbC(=d+|#FY_FolibNm$bkjD*%Y7e?3j)}8E zC*1URR%0@8y5KkA7aq^n6$lNb9upK2m_ecQ;58bc`78X#YPavzL3O_c&gZU?k&*uX z;67tGo#QM(J?;sj@YvT+H+3}efN+Kin(#1^-GuxQ$_uNG@o-C_XBm)!WhHd}D|c8d zTdvyGEU0+*cI`_jS1MMurqqk{(NPG(q8yU|=hxN3)0B^(`@DO!p5JYvGGkW~YYNJK zvM;?113)%hw=%kyMP%ux44~%#^7uftxhq0zAM5j7iWyes637{wJe=8TB$P=BILd9TmtUC%*s<{zmVKAZgFGlN8+E zFQee-zX_&g+L9qZRXv%A`$a(kR4GtLb;?Slo#MGEg#4ATbNvn1%KcvhWh17GKRzI2 z@5Z-29hW&Hs7%aIh$LOO8pPe0F1`I;@Nlb1a;>Tuhy2c+(z&dpht+k20JBkWd;YTw z2zV#%iR9$wjvXz-4^-&dC7a9>B^pc@4*i$X)tWULx5)+IxIj@$X8ktblr zIyH*P>(hoS1Z-Fyg@X~k#GGzW+_CLdH1Q4hHr1&mXt8_@p%sXzr`uDs@7@jRyNZo0 z;FQ#F3|D80-O|x9b5G0;>-BcqY$KITa^e`!&PCm12tox@k5Tq z*Vu$S>d8uR`0=QT&bGA{pHU3pC1?+V9GQ`2p_=7>uS@1Jw)Xpnq>eY_6?G-x+xP)O zW01fHDZG^z@+5e`&fdhQ_Rhve9d|50EHbFS$#e8|!dClD(hy>3e@@Nw*FF%o1D4hM zd*}|x;17CwPJ+oQTl=C#r6(r4=}LI!Dc6=a2@Y>a2+?5!mq)Ear2k4n%~oaP2|P@< z4p`G9b>BVL%aTu9jtXxfoH8M&2G56+(dxlbb<*~ zQ!G`W3yfNR7F5{WcHZ_UXHyp1TVcWNA;vZc2j~M79+pJrB@8rzHA-0>T`0C-Q|xk% zC{Q2SP#FObSey0_L9iGq{K=CiNPi8S)VaAi(&_7<(&`(<6mHx-my2;RwfpdQ^Rrj?)%l0QLVBNGoKcJCHrQH`#q}gUdmZ5);;%H( zdG3Ax9Mb`1w!E{;3JlIqqhhv!7eY!@4!1izr)ArYa*yzL`J6=TI*Lb0QAHo*zcZX7 zh{E6eBr|Yq@Ol8b@~y30R)RIc0_lNU1NXEqCsGQDFHn?fI6FIoN1b|yxt9zss8Reg zz8KyO^$@OPED#-T+cpQSQ5TR~S%Fin8PNdmu!&L9VP}1=cv!>{rVz z5fl)R*c$bWc(uNG{2-3Z3%7wC|qH=X0=PD#{M!)2HbMLB;FNgSmw8!@Ne1 zs(qA^Rs&nB6Q!X7>;Bwf%yikPT%XnhU?VR&q!UtCX8^@#jPC2CjFiJ$ zX@}cskgS>>wC$jH^-^@5>h=M0DLo$kUtbsltL5+!Z*0!A2T|*ahlW?NC)mv67a^e9 z@*8PPXSbP6M$gsN*?*=@xWOJPH7GIu`uDSWjQNdZ;_GWn%IMwQHi%P)>v zt%aho$12<^XbQg!CXk9f8%k0r4scj8&k%k#F4ga!J;>_~anI^UZ&VLJkFKs8(66*W zS|RakyBtA<-Xd_C1`2={jl85b%5^ggoj;T)L!I!l^)-3x6(Skde^HIYmW>gMd0}H)aPb_)qvbb(eS{0sRZ+dfWS*7$cMR*#h3jc9)s6)TU{Lh$^6y3FPok zm>wzy(zRij<=5V612i7@E&@}cWYjL&aZQvb9&_u)ui=954vdW331K00EARFLSsC~l zQrvH+3m$55Tb?AS;l;CB7(@ zPY&YcckLpfeXlVT3-UE5orR(QwYpTW3ycr9G{=TxK>4svcZK!kCwkQSplghlxrbtmCbqE^ud4TAX>R51Bqgr3uT;rRDk06x-deQe!Te0wq`@AfyYdli|le!hZauZZ>dC%~qsZ@DpdpOFnX zHB{w}&-gTV0`v(L0IU7&UtT;H z1TrqU!+DNaudFtWAP`2LpnB(9Arg>#B6ap)R!XiCt%3^p=d$hIc1O9WsARy%NzxqZ zE91?GrJV5Pw|9f;K+CG_tfB(GhFW|oiNif~#eK{}N6v@`@s7~Z$biqgElDtP7b3_a zyB+|U`?q>PveS>3c^bMgypvW^Qi7<6VqtM{N(|ZXO!_YU$o3^TcMCieYY2L^dlE{< z$BquxX^a@Qf?UJ2y~%9I3=~$ZeF0j)e#Cu~OY80WtGt3LfL*77zIBG$0dl%z$Kj`6 zzHnT8o;BSox}3?fv;+ygN;qw}8i)PWo}ScgwVwO)dUH7R?&G_N`9IiYtU$Mm@|^(} zPBA=lyqfAPlXQ~-pd+`ftfye*kV-rRe-t&^eS&Rw2RCy3dWfB&J@Hn*<~En+zy8P; zR5B~FrGGLW+=(?gnuC(Sx^BOKdL@jX{My$S2fv;@o6F;5X9sIC&MFGv(tfyImo{2$nF71WU2uw zXjY8Zq<1WDbR6z=NFF+GA{Pa4OsdPz+;Cb!czB*Im%qI;)=)`Q7cr>wV^zTMRy6Hg zEp^*IA(3^f4gS<&vgg5e-I*Rzd`6vz``vi|8i(JYi~#xvF@L}eM1}CrF$0lR7Aiqa zFKzbSQ2~C~zEdgU()C}0E7ZvV;|0xzG*D7DC2pM52p{US0(q*MFR-y~AQ0X5Rvkeg z$fNR$H2R2|~sT_9S)V1{} zbVg5WYUl#576bhfiQ!}0U2$58%F0r4OV2)2c7M>SJ{;N1v19m!+I=;qgee4Ot3b*l zsjp+OO1Q9lzh5XY6?9Loc=HPi0!I#+d}qQ2 z&?;+PX^&@FU*~Ca=3k-z*QGo^DgjCOG=z)P{f^LxK{VI09}^APQgCyKaecHc)AF%xCi~nz^L* zU~%MN(b995*0JwAa7JkWh~fR~9qi2vEmv-)ep}Yi)y=5xAVs?}+lbEkxj=Gt>!~8Y zp8LkP@rG-D{8=pj`g*?KpUSTb!|z)k8X_|Lk4Dc53JL-O0)iSLonX&GbpyB@Xm6n8 zz*#nXb{Ov%aI*GQ#&00on51i6MfIet$^0>BK!pZ~G&0zJyf3j#Mxdn)Z5ahpQxgsY zt+N7v0-N(o&D+k8u}18`41OBqG4!_qWA+J-xS_`a8A~UhBm^>gTn(7nUn47{U5F5+ zM0yB~><(`t{;ss7HXrR;xjF1=S+NRJgXe*Ds(P%k4>hZNrnkQ#ZyGXufC+If1OK`9 z{Xyia^OMI_duuIug;nx*9*7`h3?QPlyZ_6Vz)g)yO=WncH2d*9`LnoCD^CL>X=(3u z-5b0n?USeY+o`VJyl7$DAbd^<7*F(2G#g0L-iKqZEDGQ5yvERK6Vx6kp}g#5B1_zQ zKbNf3o!mzIszCzeA>tL*pD!cH)rkoI^T}5CFDT!D_##bY!-s<7HneUFmE1GvLwM^B ziQU%Zk!zc-=0D!&g3RmZ&%{@+@>E3^`N{-qm;I%#1EFd-^+j}hPmLded$tfi5tu3~ z(79O|fW0WB_}8}l2YBED>VOw#nUn|>219*vC4<^vMs=&iS(0Nf)$PCL6X_<98SHyG zk(`(Z<&#kRl0*Su+xjE@4~L(@!g2`~7CnLf2qlDK@=e9kS*ivjn~aZAwe zPPdkN7h>m5BTApfaN6_m_-@=0T1asm9{W&-WJclFe^E*N*Z6P!{ki2Snbmy)e0)}^ z{=krx6kK{W?I!sE1g3&{&r_{F9wRH&3b)(20)6QnAPIJrb}1PT5(y|2!NdWc$O~X& z0oFgt0x^S{7(RRsY_Kq3gK@kIfhuD>7-LKW+df~g+uIzSQTOmrhKVHjSjsY}-$itB zw``(B5cvYo^d1mfAcpXLEaSmS;Q!(0acXgUyShjn3od1svM(){i?nOo-nvCzoC`_s z8MBj6!N0WsH1V5V4(-kWds0%;Ms7u>!xdzqti(fB+rta#IXN)O@jQyj9f^qMX7neU zqrthI=k}fw19Em*&t>kVrThF2O9VC6E*16_)B|7$FycQ7<|8apv5LVWK+_zqG9Gdj zQva{}F{_NgQ3x0AfvI)u^6t4f#Ut(&YuNXFWg8ND+JefNIkM%`T5CWkfk>>{3t706I zqp_gQ{tkIub>zoE{U%140fa`0vVL}o!h)M1cJHvCQmjh4_k?RGPA~vJx6pl(c%5@_k6T?p>@y&X*NHzy^Y< zKvJ3F{!19ZDaFERkbr3*&af+^DcR;9rAKpfNYJi z(=f|ev(HN~Zl;QY!#uMkiZN|UURbw1|i{-z#^ zmxv@jLS+Xz zG2y)b`0;1Q&zoDmeqgj(#NkRy0*W88>uH0Si<%83%XE_heEz&gA+$L&1rh^+8^u-j z`$iy;T>Q}2o~U8JJ*BDRG`3D~rp`x;xQqyB`DTQ7aSK;GhKb8v<`;oO^Rs`+l5_Z= zDYb^9SMeo5*gK@$1Q_TKI^dux(oS13fC>P+>Mc~rqHf|dYC|zq;3y#s>R~EAq5|1I zzaUtEGe{7ze+-ET2-KY2@!$$GoYzW+H~$jkkHu|XA8%}&y8~J`bMx0fr^1krPVEJo zyqiV`F>5InibU+kz`(Z7vp0sH$qp`!;R8t;rnmo7laO$}DV#PfP4W)+O;DXIUvXKF zhtj$OFm#E~3<9YGyk$ENj+DW5;SIPGJ^>4+-q)s1F!})yq|4`XymL4Hxg+)vxhQaS zL0sgyqljwMq&=Uc_eoZIyXNiNYa#p4w%!QN|o4r1ok{JN@iHTz6 z8MFhyiW1rS{6(V07#8B1PX&Pi%2y8IJp-y$?$`(IrnRq5eU}A;F_PCJJ%*SvR8|! zuo(}Ez^}YRPXLKIx7x&*-HU{H#;sRmQkd{{$-%&HaviR5xm7AgAeOdGaMRHE4EKq< zUE-Vh)Apu-2BZ=sJtdZzHH9E+a1%>UYrzVNzFkDUVUwzd;N1 z`>5J@ZTVUm2NX-}g;FX&3!2bg(*C$Gn-Mu}tm!mR7qG&a1W;}68aooEM%_hJo~EWJ zPn_6dSV)ID1vqJ}3?O>c)M)^O@Os9s;3(^t)*==i7=qkeT)>ayjHZG7$e7M~@k{5TNN`BtIvws4-vbc-!IUwx)wcbjD3Hj0 zKFlF|d$k}&-Ui)5z8)VLqWggmJWb%W4p1?`WC5*KxPnkIwCN?1Z{w{5{?|*$vEqVR zzSyd8C;oj7N}v~@wA1MU#?MCOoVN#M)1g9;RQ z@%{FF?xstF&e4j76OG{rAOlt^MF=YDkEO}|&~d5W9a{E)j5Y$-Km@|z& z0SsiGsp>^+0-k`I1pJeG^f&jev{=aYR1%t&LYOlb%IGrty!+6N(NU%ljrv@fGR_DNBMHk@fo ziiGXs+0ePn8o>627vEdXdK7|(GKQ_^X^wy*KeFoA4^yB=+u;i2LE4nqt^Ll{JeWPp z!(Ry9atOY%omRIX>C2`Z@64_z2@dQUZSEP8SF({hJIv2D z(|!F0u%&i>iJG%Ln+o~SYVL6o+L%j8KF^WVk@NkhE6RAkNSXSlu=!KrQ9HBF>CT8z z<3n8M^I3(KoSpyV&g{4l+{?ov6bk<8f^HK;W1n!sg33X@&y2%6KkEEUS^A~Abj@j{NVMBlO-RLFfP?sa1ef;l)js1I#|GA*kimTY_Vg^y|H?NTT6 z>oX!)F3I1hNX zaEUCjW)>R>!ih~`Uzc5^=|IVg7Yx*RL1B`Ve$#S_gu@79a_nV9HS z=1+tS>E_m{^n=qh_mq9lL4zh1j;7M4d0ML@(|p~Iu}cxKgasTg_40>gBLWc@SF%2 zL<*FIYDk31Gvp~E>0Rq+Op+0a#yy9AqvFAvl}@WMrD9=`UrCn zmqMhiRP=8?2(;KEOXt|Sf3jk)`z2(3D&qa2uaND#V;1kMzG-M$CmowHzqg~EYgfsh zEO~z3>K%P|io|*G5tfQDL8pXF(U>P#%+nodT>R^w{Nsvi2%#Pq^A+*u29~Wku0=lP z0HZ>m?NaZ4u~MU^)Kn*5G54&0pr2}#DJ8DqWDomGdg-WW2~EC#?sX|W`m5oBoL{&(0te_=osYlyNi(*f|Bd(e zC?9FcNOVb`APFWjb13QRh^;4QUmYoV$asyDiJFAJr0DqLJA_GiSOj^}r*I7k-pY}L z*@wQq_Uhr|4_SB3-gBzw%jNMe-N+BW{pjoC2j3DOemiZR_rCYE4jH=unfLNxl=IR? zGH**tc}L}@bG1ZaRkPSkYl=(RG$oflk=C^*fYo^{9%zE^(Us`OOrPjAe*s18P9GdeRQo;gj2gQch?>7L8U^Pio$+=n;*5GZztW|gOvFJs65_~pM$Qca9gr> zm#eFbtSpSP)RGtip(`FbUAhU0-@Y?RMhbZM@8@>U?(oFy))a+A;E^iFKuz)SHzOew z98pS_4zV9seeriXZs^gjckB{`foGX+X&t0ckPp_-hRbe< z{C*YB;3(MswtB;$Q?et;Agk?H{H|*&*ID$*%Rk$NXOdS$YH;&qrlx%3R|F|95&Ca0 z-jK?Yp^Q~jwUo`VyyUQdB}jH=4O`tI8-KjBVca@ei6kdViNueyu8sVxq<<0L>9stZ zP@VesM0YY}vi{j}URpVjw_5tH_!msb*xVA+&L3n2!#X(tz=bH+7Mm{q#-S|cgo+Jbfhj06j!e{ra>+K9OQno zEB1EfP^(f5rQg-ph>fFtV-_bpjm=i#E4-wyic3r0Ku@+F!cSCmf&iO>2l=fe z6HzYjhTp)h9y>sJnoZB?xfA6b)+>5F4SR&&EnHtTZ<`kL=F2>>!@try5J2E@|1((0 zPc7HyCrKnj{KwyfY4NmV`zrfivLj6$mT|JYbe|H6$Qr_i=DdZBWn6SH*MSW8d8ic{ zJ{;~F)+d_yl%)ZW=!+EnmB;i zr3X2B#>UgofCxZeAn6sBDw|Q}*Q^sGj4Hf2i*1x{&pBNwU_xJbae~`P+N%)?TrZvgXnIh)`8LgMXO@H@)So@^c zf6#_H$;Y#iCWYVe`Tf0o-dug)HW;M7SNQ$gomV_rEhIVbCoGC`y^JboeVWrG z$0nUF1HZckxH2^f?^Eyu52adro;Y@H`pi4Sack0RQMpn5HB885(pYFmM@5`2{lvx% z7V-QH8@E;@gZQQ08spY@>+c4E8~=~A_m0Q_x<_Y-{1F-Zys*l>8e zCUC~eYmSK-2^{;z;@u7hWef6qjVnQt1JF!jQvi$uu0V= zN4#>U!~MT`O9xfALvpty%?g=}!*idDh&PWDb0)DpO1XZ9A`c^FPkvIWP!CxsfiG>U zZsA77H{U%`ntR25h5ZrRCEVv)REyjBIlCj!e1vC?P&e#;3sj4~B*S0r-zst=#?1loHh>tW9k=8ba{-96sif^V(@~msH-vt?IxJ$KW5|$zCPPk60@>5(2-+24;qP zJnP_=3ZkUclMfrjm-64dwPT54WZHXg;Nl{ZX?Yop)C!72d_nHYWDu#+b97-XyDEdAecbs2KsG4PHeR9U%oM1>%9y_yYYAL zHlg1(3947@Q#w(z+i!@f70jibuNZ&5M94gdOvY>Pe7b5voibaWiq~Tl#8c||{o~U$ zEs2|heD3h4S&B!7`r{O*}IsT1HW82Y#VG8 z)@?@PjhcPg8^82{_MUc_cJMjeXSXPOJ2O07%_1!BO0K2f5lmS-w7NKW*j5vsdl=v9`?0NQo~Bi9i-ru=Kerol!yzAkZ@Yi~ z{_po1^XgPiQvLdd1TjU?toa$1v?j<9GJ$QGCT>lzCx$%^%$KGl{%lG{AG*X@Vg!lu;OwsLQ&k`>H#*{Yeevkk?PKBw1C?O zuAz^Wsfh;MI`{N)bT)xm8cwY?Tg@Y;eTDtIJsyeJ$;MMwviE-*n~iha3g_I4%>jAU z5CP$t`flk?33Ih0N>!yN6ovHJqX-V77jf#@XcD@Q1Bauo!e;%)St&hbaoW17+u1;udANaE9Dz z%-wnr9j~yjwOs!1i}BwU26?R{YIx?%NI*k=DlYsPy+p1fWpztSYI;h_)<@esrJyr2 z^XOOGY(YtPr%97D+T}Jhu;|7ki`4_b=1PQ1NlnekoCv-cG?CB*>XRj%kW7f7vQ?NV zcINBQG74JnE)sf zk+!7YB$1#bf>wvm6){U{qi_b z&pn^HodK6S)J6r*pU*+N1?3LQQEXaU={&X$)*dYW)eiD7J9ogu}R{zhxNFj0% zwVaG94-o@EBP1kbg0>2~v0d0~6heyJ`~Ob|#hrJmgpBm^!3jf76LNZx7oAgjP!@Go z6D@#T32H~lm39hUC@SbGKY*nYD{h74pTG*?3Owt*3ka}}9|2K-VXI+W=uf|+2ooCq)5+yP^9^`iz+5?Qm+|U%!jZ(20w@O zGbhNijpA&;+V6Jb5L7DB&7+?@TItagiklI%Cqr%|U4J0tky4_3;vEr6JN z=R=SZg?Q{ zRr)hHacE6a5kW!ss!)2$T*UsZPR@vEd5A$O$oC`bzLBE;CQ8J#=H?=0;iu+15O=7$g9SXNO2fn0B%8ZjhV!~*I5L*4gYaV)$=V;bSYLuO$Q@| z3uFp66bj*4?@-+yrvy|$=ylKdlh60J^euSIgy@<5`pi zJ3qauU4?Z6#Ocug=iETQP?z*?(2L7bPRWU!Kgiwc{4*c<;fmB@2k_tL=jZ3+8?JK8 zL1U_kkRA8wS0#g_t;O}CtA>V*x{?tnYxvC&06|%h#>Ja}-?2i9&jx`;*G9IA|lx-yYf{>WFIy=6MFrgZt zUjybg+CC8a5Mha14fHp@14ii$ghCj7DI2&KJk=7uws0fN5J}kJaJGKE(E@pOlHnq; z$#X4W^#KAO-76X~d$fjhPSDa`YbGi%#dQxA=t-eym3}k-gY#2@<0mU@drn4|!qhM> zbu6Kxbq&FPCfMnKZ?t)&`WxW0;cA}LeZB|h!v2xF;jc*^7xOwDaLL$ANBu;FFUOaH zvHCBWR2tqC(_3x9u)Y7@IJl+pRgUED;F^nNgs1=a8~@{4TI)TJt3z?uBQD{FqQ@qB zi0yA+F2^03e78($T>7RCWVRKzfu|J}SB13Kc}k)4!8mp^_t`Uy&yvQ|q9Wm2AA$-C z3jwynS5;NbylQUlIzFjKVJ;~oS8?syHGhSym9KO6CQManGQkhBF4hQ8EB7CcDtyEE zb4rjdH!PHOk)O$X@sY7v6aDt>w~3NZlsW1d4~2Hk4nyyK7D?YASx|GD2X@;XU;@$6 zbSr@L$mjcIgHYt85K-$)zH+3~In9^}6^_`I(=f_l`rApzp<-Ir*Y?|&jm-$UEk-0b zTB@LG6hBT;@J8m5lELddY7Bv>d4oyAnU2S&9g{>%1^&)ig|NR^vN*&hGW#e8$8YDw}+*wSM+vj^YZvgua{n>{i#M%A*>OA zJ-ljLMfd9phX%P-bmhhSN&;I-M^~zjT}5%ju~Vjl@FvucVz!r8T4}V>|AQO+*RYnK zy)6=Xkl4e)4b!HY;+|HOkKn!Ytj&{yF4%*iIBWX>cfPm4Y zImTyX#F#!Ltsu#@xp8B~D@j##h97!aY0|DI%msv8+l3UWF@_|hzuX(Hq&k0u&(km9B-ECejP(8&EZQf>&B6lkgap%0H$GrW2#aQ3Y} zFb4vF3#Rz<9YR=)w%e}9^I9DJwFkiI&jD7JyFdFuN&?`j>}&#mIBRAPbs}x+w~1Qa zcOZchcg1rjD)?ey($q#(Q(uTOCc9_>IEGOe?P5Ir_dz)*C4_lwdnc@WONsw81J6NX z+x;WSrNj~A+|&Yv%2fN)aFn!ZCo3(>-fnqXdWXrUR)2cqfBNLcLXGrzlK@w~H^p(I zFl5C?O6wFJ%8Uo;BmhVrA zgyaeup)W3Zm@|7hKHC0<8I2BP6a#QB9&cV22bN|RfPaac93v~&OW@j0z zMf&_6rp!!EON)wGFUZeVQir8EoOE`!42;i76J@$rxBP+PQb!~~8CC?>k}Dt2**ia* zL`m7Ls8fb^fTNXp`ukwFb{2AilDfhS|cB{o%}Qt8K2AaNpj>Y;)qiPM*7^X zkOD_7u7y=C6vi~db9dj%gu#J9cc+fSgM|}NS%*p9Y8;G+>)-+%B#?!6G|#E3>ai;r zK<60KeggpR0Kyg5uD*QmyYp8Vp?)uZjYFY)M%`{@8K?))xm&5CS5l=BS+uGtQ@H#4 zGu?d(*?nmnd9l_m0C`Fp8_EnzLS9WCOOh_oN-iE5*##wB)%bWnR7!$;d`8u`KOChq z@qtqlW$wxfEn-+6;E+}Fsx>Anr3WGC!Y5!AA^p)HLYB>D@?vAO)$Ha9FO<1jeoI0I z9t8liW3|B@kg-?oJc~0Pwa~srM5btBSC9MVLn-g<;a|z9M2pb+A0pL3oyg<;ciu*q zU8WNHB=F_yZBFUAg5W*1@uf4;DXvs~xTVs3CntMTtOv8y_{@>+1=?m(QR%us2yu>I z%e^fgGX)fpzcsqP*tT7?hPzFU6XV936b`f{v5)}VJ>OupEc$nPcc?rN0ssvC@`kx zsx+Qt()Z6m4|ruv83nfwziY#Ym`w+|t~*{@P_FjVy~9V`-OuYjKBZB2D@piz!1{<| z;LjXZAgLleAEX-zvLk4_8}?%{EW1%_M%1b)^eHpP;y~uDMe0*af83?N2_2;s#>{E5wJEnryW05 zHR>n%#PUg)Mv|ufqplr~@DHbFYH)}sS0imA7qBi)oiN7`LUsXO2I7Yl3!8;^6@%3YY_~C`P^_pNaPMQ5*-TEK-)0Q^83qG7M)ko5m(a zQA&wb966Ey&{$(~EqxdtLRf!%a&mYdxxRscfv4vyah}tUo4}p^fpF!(;Gm7XaqPpA z`*0;Wo4Bii^t1&%=n7szR=#d-Xs;I?VAN9>1#Jk#fV*m1GC*pi%8gS&Zy}Yj62M$3 z0y3tKPeu`Zy-Y4Len3c@ejP?3yW?;f(mfLxCX|qn{-NHFyy)zkuEfL-eqY{MR#)c$ zaapjJ+bvSW=vLd?!~%mN0m@hYTanN$yeLG|2JqgUpY(bl@3=bOYg+Nkrx9ao4nhtX z>DPtm3BVy937HT;Pd_lB8U>IRNlOgPwx(gD0AHaJ=u*H>eE&dpj$VqbjOsEZjqba@ ze}SM}Mk!>)gF3|$vRgRql6yioPX)xltP)2b!#*me$yyz6-btj6om7wBtb%ss+N5ecitl;FetD?VV4mKlGrQ`GGNNutfDD7c3{IZE=2ltx zHvB~wAUgpQXawm9!*Soq2euM0wpv|3$$2dtGdcbpZ0CIUcQ;yC zQA82cj?g#Tfbh|p`c3&1PX?@J34F{FaIQa zda3VZR$utA*`prMQ!wq1%%q_#TY0C&g_KfnT*l*-&f`-=jl!X*ixw;^2#^E>IMZ5N zC~q@g9zH@4De1g|uJXT}G=b{2s=j25vNAUV<&8Ih0gV+70U;kmC~XAmyzS zt-H?v9f1lQN|T*iRCI9%?}mRcDU*!YEs_hyH%|o-k?p5yffYhC^*RCi>~I;yiUeFU z{NUuQ#npjN&3JhLUbO8wht;0zIA12aT_8;P(*hJs{~_utG$;M zG8c94!2ercnuuCl7eI$0pupsxD;~*|=N_}3pc7?Q+`~Y#+(9?IRny0FXerSSSB#dH)?5m`bHxyjN2oO}=}F#P0OQ6MavuKo z_;dc}J3urjZ`pTj*~$Xh8+w{ltnIxM-H_kV3jq9a&Z%#ey0p65c$@xhXD48WqJn}2 zg@rS&8LA0Fz}H$4v4z49zfl0$CT8yj25y7s#tZ3PJ^Z1}uxJkA&uut5OzWPFY1eS$A8=NqtIb!DzE&2ej(wYO{flAJlB^gFyI;Nm?PzSo;kYkxhl37*~-&`oCJ$l-NZ3AS4WZn_hKY=p3 zT=9Mmj15+tc7VU4HgK4y${9~3HjyxW{#Xc~=@hcC9YCobej5Lwz>u@@HBjcFmoAx@ zM6+2L(U7WkT3s8 zKg&576@=UFldr+$y0B2F&MghqG2ZoIU?6xn&esYC3F+vNSv`UlfPucgB_E}p097OY zlyKiO-7JMoZgvkRJS~}(PM>f2M^jT3iZnQaK9t*uqBUMmcwJ8)YqVKz+}~sN9v62t z>xVjGE~D)^1c%1@dge5GZy-sA4GV*SvkRidFfgf2uH9Km;NLpWI*}D)UO4mem>kfe zgY-0;`3scQxy zOj6%|RZ+3&uYi%lyf6Y~5zhrU->vKPh9{{VPh97#RC3BR;#H@h%q^~~ldscy47w!x zMy^nuJ_b>;CWVoQ{16D;_Cf%3s*-&W>|~62Sr9q zUGULz{2%e>b_mnJ4o=>=@0NQHeNggYPL49wtyt~>gMhT(1{b{yFr@5aZYr40lT)lGoPG3K-;s_$Q4 z1p0Nb-+iSJ5qfoF>Fo21X$Tj6aipA(ah@9q@im_F2z{Q&HB^8vr5uP^9|&FbfP6}L2?Ne1*b!|Cx&;G8Yj zE;nRnZ|!cAzvJOCj4)h+0!2%!?=EOSqFx+#~Q z8Bq^IMfncGmQ#HqS3SKEsBP7$DfLhg4Vd<5;BFeo#*CyUPxNS?eIVb}v449pdn zh1gmiNs3^U@T)EgS1~4R%9Pgr(#RVk(LnQvSwg-yd`Ga;M_i2DMUqkv4_kX-dZ3G4Y>IJ~5;p4E@*3o$|TnCQ@9fnXpb2%yXXk;5( z%x^Ux-TcLd#KR}RQey?6<&CJb=Z|J%to9~YIn=q6Tp+|szXbq4V(|#0r0oJcm{>8d zA!xB7elXDTgz=c2(8ig5Ln8WEavnGHOCgru{Old3Qx;84z~?`?;adm#284$L9qc|h zS+qJ2EHGQ^01KD`zZe8k8Vg&jmm}P_AFBKoF}}P5)bgoR)g%AoX-vGz0oRad%Hmuz z>fzPdF7z*{_$4a~mT?P?>`j;e=I!(P=azqx^E;*GZ+u|uV^v`eGnP%uUn$8mmGoaw zO)vrui_aA)Aia_YNFO7CQ}6|ZS>12H75&o2R6|<{ZQC;f>G6d~GO-pozNZ6rA|e(; zwg91U^Sy{8TLY&EGT~$v--QU2y!40aWCIcRVA8#S0sn9O{^$RNCk0g z`uT0A%f7I){asNR;bV|2V%i7k3$olmJ+Lf~58ceYJ(x#Ls|8HCbARGe5V{z-Yc;pBnceSPUHp1||HkZU2di<3BDi```Kq6GlXBCVM&Pf?ZII_!XO$tPeH=+bUATY|VgX78djYuin~ zVpao%I%1qee)i`(u%lVrQ;3}c4~Koo@Yq=N>SFBE5{A!gelCQWa(9>glIuXYH2jhN zLK#o#nn}|oBt~Y>v?CO*+rUtKzRSxzuV^8s)yX5qe)?c*#3h5%3rwMwFwfBv0>%Ct znMBjRg6^H`u||v%epc3EfcBk&qChNL#mlSG?P3WOm*2kKj0UphGwe=vDOBh?2DmNp z7PK5gz#F=@uPW~ds5qi6gL)w3xTZ1;fDjEQm6Zy*YjNd;&Nd=#hj8Hn46b-BkqpUs zkCj?k(T&7a+NwTl%c*fd$g2U3&4PX@&|}h*-F|{p0%`6(;<@;(f11sibJ`r+%_?qX zQ#jU0TKu@__U+qq)W~tr8;2r;!TfCzt`frEV$lag6Vk(D%E>P;TI9POT>Dt-wYi?4 zF$vV4n##G>`Wo=AbXFawmo3Yh*pM>tB8`vLf}NBA zUVZ+DQht8vKhj7Q3Xzwne{xa*q)7;MN+h!C!$bD=$Py7K1)B-DdC`n;e5m}CULkZ( zyAA7U!?($9S?5=3TNvzwpgiufa?5J}f$U}&k|n#n@CrsG)m8Sm6~i_1Ysk>5+^Soj zI>mb@P{e`{_x4`mN}HqLPXyW9=kQxdQx|w2LJqR#q(Z#B?T!<5@=54 z<%!*?wgD$KFIEP`XyOyva)j`?saaS2mO(2vM%w;61pdm|ZFk5L4Gc~Y+^_+7L-(Q+ zQVnqKpX1`l=HdwCu*bL_-n`3Z0+AnuxXeHht2hx^rEmLu8IXYJUyI+cIY6`oqBPc& z&RDMmSWDkN1vWtzPE2e|xU{wje+#6U*qOC>WLqrNE-L^_1_0ERtr{ds4nLvCy)#(B zvIEFE*`1nRZ-7DO){}m^%VuU~U~IgslMs#Z71Xhq);EFNYhDZd4Hh&&~ zLt~O)B`%1ZQ4o+D6-mP?;HXmoNutJYgXJ2Dn*U4PEENO~f+X%_T09k|>lq}Sqmnn! z;|Z`g;r0VFpBcaa$H3VVkieO+ZTb6l@K9i&7}z#&Bd##(+SaDX`DHRhZ@3WfXKnVA_VcNtzN=%L_*L5l&>RLILTH8tNg4E8tKc)J>J5t}7pOh^-} zs(Z41t-t_A;{2S5;G%j(5^#4Q9A&=p`Au&bpO)t6-6{d`?HJs8Q)_Kpl9KQ3XCm>_ zny|~D--8T2RMoWl=GTGTth?*RZ%qigOQBeSH{`weIRC8ii7u0g+Kn%;NdaHiJ^RXH zq-+)xDHEWa*#y7O+_vMFk0U~(I$yO>>R3KGBa7;`EJ5Eh0kLzeprqUV7*4Zjk;Ap-Hw zxHorrk$f#_5s&f?*y5CWWqZK0zuwN+m-`yXKCp`5#5U~}1I3e9OeNN-+1I*HerQWa zp8#zeorGWClWpOQeFZ= zQB+j286=3vUGwO-LM%H>1bh9YuZ!|N6%smg0l6sTL*VB_Hy3Id1!gDi1YFia%z{Al`$>dyk>45 zDoa56npQL>O!&m1tRZ5pV=bOGVp8X7jze(MfcePmb-00h>+W-^1~K_{*vPW_@q9Wxg$?BAYRWP^x> z0q>MAYg<2-M8&1~Q~`%dm;=k&5vE5xnC*E`8oPaVzIyelMMaj(S)orcHvkHNt1pF( zXuNOeG7wH@g_MNIO&%ANl?_z!CByvRSV~xEht4gthakaJVl=dY7jFkM1OX8Che!Kr zFG6N;Hu=TEjV3&U60?ldukSNu1jD+j`lcbxn(q<(-Rs?p_~?Ugpd!eh(<#0R#5`_- zF+V|lg5)Y$$(*Fnm4XHK)N4FM3c2bPn6@+d8&DrLR8BY)EwZx66h0q~O9L-qBroo= zDwTWe;!**#lZ&nO{bY}Z{6gYu+RNUsTH^H-lA4eRvR?oJ!x*9D~dy&HS%V_sW?x34Rbs}3Dat_BN?MD~3IOMJF}>AxRP1$`E3d%z@wp>2&96 z^&w(gs44r~+S)*pMNF7^)nO3-#Lv|svwQzIy9h*(unMv> zKTLRSOFf(4uWvUhZmGeeaa#wcN-6f_mo+dH>-{t9x#wvC&>A9N{8}Dg3@4Y>dwc~5 z&nZyix%ch%UX-5r2?<}r{vIKy;oIYQa6~A0Bpk8GZLjyXyslLPHV4+8WB`V}Tw&0y zC^gbBPMdtox9iY`(vV3t?da{D^DcV!d9Llj+;tI9^~}u8aje6!73AlK3wcIZ30|mt zFYINYe5#WhVvxNIpsZhs8KGkjH5yVX^E2Zl13y4Wu(338e(Xr$vpisPw1mf|fCne| zu);X70e~I0A=d;oY^F4@xrW@`Mgbtz!d&bM0iB3xqX1sFdk*!d7MY8&9E#Ye#| z1~dr8Qj9`&aRbQdTldfCgQ9C3V5R%Q7d)YZ2CweRV19WewGoTZ+Fh1{f&xZHMj%Ya zv}i!-F?{$>fung07u>3Wskg{t2gzQC67c%RS>dX_qNxK~j= z140uGvaWpG&@zN>Mr2e}%wcHJK*n>))HKEo4q$=+WClNcU2lLNKb=}1 z#CNor;4oWcX8x5It@|AM2>5!<^w1`NE9K{7L*TV(UIi)1X=rBW>G5g<(Y-U?YK8G3 zyjHNgEnN{*AIA4O^amuM0^+HvstvRU%4;)>X&_BW^zv+RXE;mN#^Ay!CnrZ%qCgDO zWTE$JZDz(oc2AXwWbM;DW)lX`Ti@&7)HgPE7!iR^uWCL!^yN3dyoR_NN>FSM^!@aU zDYwc#%2I~EEGlw#b!~^o2aFf9da{pRc!HUL9G5`JfiO|a?XoIw>UV;ct;llZmZYt*pgTn8C z<8^g1AV!SA_E)0 z()Ps_5;4f%0W71gumo84%VZ>=6s^WPX~=Y#A4ssBdanYw0Tj2)`(rN8uivo!{Xhl_ z?k?vqW+~KzauvMiJ>dof6d}+Fu!*=Q`2TB@>&YXl)u121+Uw2;IfqZirEZzPU$mG* z$YqmVF*rWHaI60v$RvwQYfnsE*Mlu86BS53JdCymrwMm?|518qEg{W{+F)AWUkfAO zQ>+QHU_Fi=EgveBtp)BX*jf2P%gVP}RQJF9`$rw{wx^P!+Z!#=mn)M@9$c9qSeBx9 zB%@mgU|wqlFqDO2W!kg>X;qX}!FL5GzTbY4 zrVJ)q6r!}m$v(+raLUxw!X`F`n`X~q(k!7RC*QaP3H8UJp|Mx~)mI@oHZ>LgSZ>`; zR+tRWBU^RncBrn2AYe)ApA4=d;S>7_-@v5K1CU0a%?fCVMFJ@dUMkt2^A^LZxHou( z#Gu%ubz7bXiR(=WC;}TM6nVXR*T59G<$9et_$!pb$Ugja*{DS9X?rdmA3-ETd36bL z)KO@J!YuSsK}iV+O%J(8fe*vEuv=zxDio^2nD|1MTL2|3p1rlz96t4%;Q6>??A!JTDBrMf+kux^atAGhEfKF8aNO5 z97u)W#UU3Y@&Ka}S0-w2y}1ru%cg=bWj(+xp`gg%qg?i*k7EPgXk(?A!kg@tUl2Kv#quQI&}fLIGNWFaO$c zNZZ-)nH_@XiMNxoz$sW5d6D7y@f*zbL)u3HP;(FeN__LbVw1z0RSAoOw3nU|_u|L~ zzkHRMFM@mS^HG&%lxRT`-64_-gRe*6Qjn>5-g=BBO*#B5Jt@*45V+kynoxzX zR=d-VCbbiu99+P#ApkgShMksu%5vlZG+)DH%z{q`olRXCwi7b=HnjB`oBnzL#N%|N zM;}4=qTW`mZrRerAAG_=azVjJdEUo|n0ehojQ%2AH62?L7GMXi-flozda&hrdW*rb zl!-h`3iw6+)$Vlg*lrD(zs~4IfJUZz zCPep=!IcNU&5AiM#uZ*y{IDE7PaLEa3lh{T4-AcsBivRJ^T@;wUqAP+m7GP2`Q=|y zR^DLp3hBd%eV$V2?w~}AeKvo>cm*#Q_6pn1c#M|cpzSV;?wPM#ka{CCRN>0-$vO{; zd9QokkDGek4h+9=5Jkme98fc3pZ}iK?8pgG5YM|bU?flMKd@;rLSnW) zUhNJIIh#dNm{3`0gi=yXkpFSgfIaHC{Cyk;$T+^`ksdo|Bun~r0ULgNU64tu;cyUU za0rF_vaZ_uLdOlH>5DeXD{Q$nn#T2w%Ahk3c*lN4Dmpqk(8MlNg{$DAZ*weSO-=FGU`3id!RT?S~?dBe!e7-r%PB({CUFbUH{jAW$K^2|0ERLCN>t zgL>z)ZoMG_)YY`krxQ>{gvQhOuZZ122D{$(kM609|rfns3el3}GwBc$B#qqX~ zn-6otA=AS;j5Wz{XtMbHdik)GfJFr-CKKwM>dbpcsYc!_Oj|}1%==t9DI0e?@gQCI zxyh$cIw|=db;R@Im`3Xw7gpp=w@p<@^NWhMliUx6em$5Eo{$s9u`Gnx>x&KpqSQu7 z+WGs}cL2g`pp5`W)Iu%5>Z#F-3#RKymM6o={KV*^c{s9Z2H=wSXDEeu^Ydma^ue$o zplC%XJ4m7rHp#qT>bzfi)ZsIj^#Ln5yplRTk4!pn z2PM1LJ-f6fFdSHUa?-}(bH#g|7Wc~Vr^w2F1F7SGU0JiRqO0sUy#RkCu2jrHdLu|lXt6a6?S*Z7us&yAuf}cLS4E<)6FAsclU7&|&LkGwJ&vT11 z+UT5jmgEE>{gC%6rzIUz-=@6Rhb_WyqiC{gmp0Jz{F zUoE2no-?BOM)oJ4R8Uwp;Ev!GTV2hd=+_5r{98NY4o*&(?sv`;H6K<*Kce802|2iA zV5-}ly4EpN3vPS2g0-}l&k`?WqBDk_kxZWdJbv`rb|m zOvAIYvB039YV`Jp@kmZP*-+mv+yl-=#&@UsLxyp0;!P}fe`oXdjPOP+FA(yp#H1^nOnK%>?NYb^qXDf0n+e>o>_@$ZSl*O-w?NB z^Zl9_Q*#6Wh5>2NO9(2`W7qNoGnQ8BB-F+@I8j8iaoi?cW)raadbrOxESj%=>KEu% z18}9557f?4VZekZ0V9%8bGy3=S<)qhm6k08PT3^v6GsO|fT3ABaCL`s1yU6_R7e)( zRWi#WA|!N*1I-FqWUEg%DJ9IaQE!i5Nsx9P<;qOhy5rimMw?Gx?mQ;dt-*voZq*lc zF@Bq})i#P7dn?o}Gm76T+b4L{T^fK`Hc|N-9Gct!EBfT1-3ByxpK1xVAzK#V1XzYM z7bDn4aTPWa+UVAtmq+1n*Lr?0KD(=`51DW46pMmChW|x+nME@L2%0;=7j_GoOahnJuY(KTrsFbmX3T}lt`&3+!9?hLX z9o(>Xz|^ z!z;?vcuZ`;nVo6K{irAMvXOf1Z5gF+ife4^9-%{HNnK zMWg{%KxzhT9DF~`P*Z}?-AbOy{21TS}Ioe zk*}MaAV&_2=xZJJ<7KlIU+L{o$h+(;adM)!yAqCfoqG9L@?Hp%S;Mg|%_|2G*wl`$q7orL`28CqC-n-mBoZh)gF0>g>0YzzL|e6r33Jn2>~C z^i&W-*M1f-{xvir*2A?&@PCQ!9!>$<2dXYO1_Jw(dOQX$-JX>|<*Pl7kBafwB;g>) zkG6*`4>lNNg`bSR#EZ9bcSp3fsWzyPu4Y->u$r|h?wS@k(9QuPy>^;qOP1g4w3nZ* zBm_n4$k_s+hc_{|qkmApk89Pow0t_NB%KBj``jk`rHENS-nDFpqBA|2i;YLBzkuDS6UVS8mBLk<^Aabsr18ONL*y)fbFC%ar46k*+D^?PDJQ zx_ydIrcTQuR8uJSYX~s}SwtWNLLsWI7C*!GW3&>2ap}s(Oel0QJA3!KPiud_rzT)y zK;@Y!$CQ5wml%ZsD`kFm_BfNwC4UjW8G@T4kDI(ojU4n^blV(UIm}9Znx6@Vla;2Y zrz2eFH7chpWM)^&2|tl-PZ(h+&Q2p@D01I2xL$bRu5b=nEV~lL5uZbJKp2RW)#D(u z$}7@KVTcwtDjeT^HG9e{IhdrDP$&KB!V%8wQkZywoxrq#_C9>C5UMMq9jI4?*f#`C zAYcM_(cDQ@;5SegU@%-d0)YEy3-a21+1Vn2>~%E(Do`N#>%^1*UvGEGyRqd2#wh-D zkmu#Q?V7OGU6tg=Su}#ro%UOI+UdGqou*3daa^Ldah%g2Vs_4e*SbzCWtwbGwN6}b zgk4X52@e(lv6Of;%)HUj*9phjB2TWjJo>7&!Woy7j&FE+3Bz?RX{CG(&wU9;@l2L& z?;@w3EFtL>vjieR$bVRE>#a>$fRmqquL8)yX^UDYC!|?7IN)zBnR8nHR69CRZ*?z) z@n_@tu~+?U2Ccu9jz<4W+i>(Qhu88q@IcY#kPj;zJiWMkSj+UlBFi>@cuoGxd4+gH9wk_pL zR)(P-l09OdAl@5L(aZBA_70rcWcZC4=u;~ch{ZH>C*iVfP*+w=q>vR+RGg@iBySNqQphF%~`Mb3bL%~Q}Z zG}{pUS#;ca)5`Xd$=;ruz8pG#kK&uH+|PCk)h{MyA#Ya~NkEn7d+9Lx;2#Bz-uUtf zo0lEB?BIO{M@y~P@*2))z;{aCdvnJ#7RgHU1w=*3m*)bYuIZrSy+Cc$I?X`750vUC zNE>2+T(NLW-^Hc)e6hVff3#N;^kZczf}KA#FvrqG53_W;*+Di5N2eu=<0K;^=K}ui zBjh}|!{rA}t*BpDygm`$Cu$D8Q>!i)y*I-)fvQWd{Wg(8`u~<#w*yJ zA$%ukwGU9g2SCE=Sg*R0U*2c74Q4Rba+jkv-@XQozl=G7_8>AMGoi7QCvFH+M#G6*jn35JHI!v1Iy~Wy@ zyCW>DvtOxjZ1pe|Tmr!kPT$KlQ{||9hBxHR3=FL5!;9jYBgsl>VVFq#(6yNt580AbSO2|e zk9=n2U&|#cBW_FC30#v+D+VGks7)UZIpLMV*r-@$cF>FiEZuxem$+8zc}0Z> z^z@&ag$Z(rl$3J^TyKUqFHFDqTUTP^_)W?;(;5_*Lo7||Fv+N`HKl7$Ir;%7+Oq#9 zza*;snC^YBI)lz_-Q8gskgN8m(w>)u#LXM2obHn`e*`e0D1(peL#=n#i>y6oO)24B zps)f&oxJWpeF?~n2=NRnR1J00R*`YJy3i^0w~)-UnLqAWa?L_izL1}g7dmgP&L#!U zRn*3ZZhcdo^J3^~G=3~v6xwuD`xqrp0VpNC4pZ;IS_#D}54W3w5fx5f8u805c1hNO z!u;lJK&CJjQ0C0@sAHXe1srWw!SPv?(8uBBcmW^L!6D@e;TG zE?OJa@v=*(@FtsxVR_I_9mv81j7}1-b+Wd$SZ>{>CYg<6uivVo%yB=bEp1j!HeV@j z8lufDbveMiY|Pd8@wexVh5XyONJ4&Oql;cz^7I&}VjTB(z#^yIgcthSG-R1Eo5zq#0>6Y8)C! zEq>wkz*O+CZS5xoBHtSrQaw_1-5VBLLI0B2b$`L(#y~|WU_#rS0)iG|^Pnq5#@(P8 z2zI!`WE_!E3E*i21F4Mcqe$fM8_I{*0fMIj{~Xi~FXiV)=p zB1=4Gd0?%jBn_%q%QmEVMsYZ_$j0 zF<=(c+ls0>A|L&Bv!Ib1z1CXZL>`a=y98bLDqUua(i?@9rASn<)$V5_LH5&M-DS0f zufXFp9jm)C9R6!W0;}##t7q)6+Ug5-zAjy&i-%x01bC&z4ENn_VS)>{F;6k?uY(jw zX}kMosVPD7g;;4++Y}mvAl6dd1O#AK$|3h4oNzVRrU;j<{Je$(Z{0eIk%s37K+n{7kD|Cn00qPrS06E;NlDqPhdkG zmcOSVpEgMv`a|OGv{dtajbNA7F8Im&V-(z*f2@r{^yq`JR_$ zVtb#La09AAZ=eE0A5q2c`AR;WnGa&lF-&u?xN<-jX;rqiX#yW9oHZZvOt*~9zAK*- zLhmFYkIBmAF(P^WxBp51DEpPd;u*?LH@ZLWBwMZfRp)(l9?SKmGxQuj>D$#4i+y*K zg4T!r18})9&tYQ?K4sLt?*PZLYn`&Fk1cZk+*LA$=U@d$J+BY>>To!AgeZyGkU;z4 zA4fbA^#wldheqqxYAd%e*dE?IC@Z>pq#6Z;$BczokHLn@@|j@2#Gdpo2fg1R#2p8w zRERm%&Uj-17_zKIy&XgGkS&u-AYM0G9sfS5`QR}`v^*UTtPBpFJP!vvNg=-XLkkTU z6T7Fy@&awWx4#wQ7BHJ*)unEjHm!*Xj5B~%7U3WCs_Fj9nYTKTfiKqAZg7(9VXjm%{e%)*gX~$&=u$A6w&RN zct}I5>Z)I`c^%^!Yk9{-_r5ltO7ATU6>qP-AG5Hqu4@)>a>HrVff*{va-5O+9a|COgUhBA5MBMaz!{Uo+^W?@tauioIA z^u5h~BNn-&!0jQZMw`D7wJ=df!zEnxRU!g+T9HNP!RF4`2EG-$^4GL2PUbPaFnZw- z^*_(7!Mz|lr+c&2%$He>jW zG#V>EdO%geduPM2n50_Ss-?b)C+DfBPEKH)>5V^tFBP3@reCJY?tkKf1i+0 zw0}3D&hEoph z6tG#cc!0dbf4oTKh5qC7@Av+GMZSj^RfKW${yDLTNg49-XRnqW!*v>erR=*d0VAh_ zO85fx@P}Ai`ArS1U`>*FQHi3x=^fFzGt{`{HPsJ%HzX?HG@UCAPRFL zt?6=HOKV=XBg}1jS{Ynj7o0$UpJ@GKiFs`Q1L%{667ejFM$I-H(FV*`YKy&ekfrTt zNdHs!^0ij8R(m>=^{Jz0AJfl2c2hgE^#th8Dnf3)Ua2ER?`CCfDcVmyia-_Onk97W zU}YL~zfcuw&FpcnvBiiQ&S!Z*lGjd8M_M$MJhF&<798OCy{xlEj!515`~*SI98r8` z<5EEppQwZ1*n{O1{R?Ft@g#49DN$?4fvjx~%@zE^7z%uj5A58^?3+$PH3#|UNJ|yC zjy;t>gL`-fj}K~&KW=+}Epwih)@6Kz+eg)A?{*z%&a4fzWdr%8si(!?lfz2DhcTfL z@t;*SX*mUn=@5%Ec6UPe|MUs`>#h0s>t7GS zzh99*N9^mmUu`xjc7UZwH{#m(&+l@Gc`un1b`c|oJYEk>FyW9R+#I2P695F|R%ku- zMZc0ynMfK~WJ`)`r+vB9e`D*N<@=A;R|jJrCjk9^|k%FZ8fe%mv7hy&XG;z1XVxZ-e%_yh@EL=W77ZmRUD_(Cx zD;sqEn_!ku2}9&U;$t@dKjz*$p6m7hA3v3moxPPk%O+70A~R%fva*t0Mpj0sBr`ir zSy5!mCX%v8wz4TB>-V@`>YUE`e7@g5e*gS_=Y2b;-ZWm%=XG6=>oM+wt7`uB00@5H zul6kgeSD;()q9L3f*KI?1pl0t|F_2*R^p{Wu~HfJ1V9i3nAbq3J@52e;g^nwf4$pN zW*Wa%Zi)^rrIq1X@q>dc9K9Q?@nE* zGXlJ=Vm0l-{YpF)dhT!SZ-jD($R0V`&#QmeC)WN!W?ed3SywL6}5AFfIX3mMlm%bF{so zZXhD6Pp!GE&@Oo-D9~l08~>_5yHq?cg$*eORuGZ{5jq+Rp92EjSJ;TMa zJ6QJZUgWns@a@95tUE6igI?7 z0JS3go;2|F)3Yux>}gjo0tC8cP|laliw;sycO$yN56b#d4%H+h)4gxvz?X4U!a;me zAkD`w5$6LF1kmhnQ8$^2w7&JtQ8n%lSYj??awu&>v}kR`Kf^vu2Le^dJk$x{Huys) z7bR|{S*$2?d$4(@5e3!1mG6$*l0>l=yb~N5hQwUpluVs70f@f7@#)5i#Pn*(TK5Q2 zUXx^b5z9^9HBZ7E$=Vxuhv5%F(fQKU?Kav$qbnz%`$6S=Mn>L`xMc899RC%N$@^Uy z{&~NnpF_`VF8J0 zMuN!iC7m?bJJOJVJ@4T9Ydv2sI9s_!}rh6r+2Hh1qJC}_YZq?tvc6Ek6fbNWPIw(W9f&421h`hZ$X5>2ca2HyW zz#gSeo^(XZ3A}=nwjTt;=l>!XwWw2EwrI2_)nM@58jU@uiVW_OP(7UhqF6f2e+X`I z=wEgpN`l#GjzKX#s{@TO$3{&@LaxleOE0)_8;tbXQ2Rt^ZX>p!lv>aaQDp2r+) z;m5Y1%?q*k&()Kg6K@?_Sh3F1kYXtC+OMo92~f5Fe?Qr6l1KNmhrjC~~%N5_06H_OV_~x|zVKgs1Bc zXkt+dp3ZRq*AYK_1L%Ec$#pUzdoReXSi`_PVf{^cb#s*>W&^_WOhB-_iuzPFQu)81 zwjI14$fgwLEd4O10FN+nhg$yIQ zpO?uj<^?)BEAD(p{w@5=Aa50_XVM^hc&mgUZb!w!JiS=aA##hdVGoIqYDqXG4=S+l z8tduN^d8rHUg!{Z51TlYaWfqEE@&onizY)Gw$Sb=XChBxtyf5H6&uvpg8q*|+&d=nq8hwsB2EW|M-G3y z2&yrp+>Z(hG<+r-gd+vZT0NTw*V$l7Xc1kvA)Sv+StJM&bxg8ZY_+q&=EotlbFnyh z-o|%`po~0>lVw~TY$nhTO-lq|J5_0owPP6b0eF~5bzW639A>?B{ZJSbG&1#|&S@jp zE?}mg!S&q+bc9mSf^m2lKR56O1`bJRpRh)s6dGkT%d~EPh#Z~0Tun){%VAp}y)Te0 zwv4=I4ytj#BWzqx_Eo$WOHlXxlg&#+bQ2eBzbIGM3sG9wJWQ#>9KJ8ei0?cgpkE9} zxlX5{q(td{DSypMrjm^LHCz`i7-CV(G?C6FUBf3J5X?LjcT3Ii4l^`fCPE28zOnWknj_p0C64_b}qm2!Vdi^EQq6 z_bdxlX&7z5k)w0n9P6LMi)r`7&R$Pz3&r*CClzM}l@y5>PkpDZ+5oHa)k@#3e3xP5k_!l? zA27-XEMAeLnxd7>I#{_($4ufR$vvAMAbIl1_Ml*=?t>Jq5`zmI6YR!5q_gg82s%XisM4(qNKja`3igr6gtg7$ zg>_3Dlk;iJZQ>3pv-VH;5n3*Wse2S$^ZaSZK_zea$VjPcI{ zE5FnAyHkr<*%&RZw~{qhFR0FYBE>rG!nA1&3n9}Be;8|R_SX`=t=&CgH?oxtOX#02xQRAzh{#j{IP9(~H1G?k1o$a+lVKklA@KsSDGs@Uu7j|_(W`i{bVBui6BG<&@+_;u zvaG!Dp^9O^m;`54b<7*Bn!d~GUIipj;l?&MJxHmQr*?!@fOC8!VKM1scK|^z)-i$* zucQ_B#vf26EU3>R^E`r|0I? z|E27?t$);6zsoV#$h}7rSF?aj(jv2*sTDHk*x7AE!G^gTp0h#!9K^SicW9hF(u3ZM zoM{*Rw00-<*$^B^|1obR&D}8@Yhb{Qz$FO$D?U%f-nvuEf2|prd{F+d@GUGm8bzc2 zkeM@{!Ucjd&MI~&*q)+DNW9of!AnC*c)si=UX581LBbKh>1xn{Y;`ltnUe!60Oe0f zO`Wyg0;8)b?6I?66BcHfAfIoOS~|C0l{ZjquWRA#$t9Lvx%(Ly^G`uupyDb))7fxi zx7|(Z^1aJp;>+vtW_*64r^-V&QA+z%Vfg|~6Z6WUu{W$kVdYU}$w_gSXyIxjdGah@4drKb*?91taZm;XVkWQj< zi`T_%E;2ELB-+0KuZ_Rh8S86ICpnD!Z`J1S9<@4P0n-H5_&Y47DlZBONR=6Zr;1H( z1npFX;0_Ra&{cT%;s3HJ-u?tf62@Je<7hP1={d;_`eX-}2fhP-eC<+N7pSv1Rc=m! z015d={MR5)13*|LxDgjGo&jWr{@31*+9jTR2bpE-qcj@ZC@tqxH8WW7TvU4c`7PMdH>PJ!D=6cy7xfkbU zz05Y3Sg)#XT*7S$vgs`A>Wk8?@s}0rnvW63^)fk1-|mv-!~5wbV89*++2d_@oS&3+ z{dIRNG6Y+*o78{Y6dnMSpXl>cm5J_=*f{fx`Tk%vg6>O z!w4zfyS;5?uM%H&wXQ0PGnzD7K;eJiQ@7SW9@!&a{MQXpk*}Wdv|Ji1tT^$F%)^NO zN=n#ueaa21Qv017q?-*wz|JF#00F=2eF12Ryhqzg_Oj}9DWXy{@&^SC+c*w6q- z$iQo^qjsN5zZj;kcbhf-jRi#&uX*j>&InX_`JXg^XTVXyn(E-y@#*w3U!W7^EdbtT zRJR4AG(YTjmWN6BlEOY}YH8hXCC&%pmz%LSK#irw9=f)F1x#_bb?j1-)Ml)qQ)xDY z7bH}>Y=^xCHW8a3ZnM1<+5-)v?pO1s0jEG4)qmU47aBRQQ^Ur_;Qns{%<`cj6ET6N zPQn+;uL07BEtq|R!GTgJf^2hf_Lg9@c&|`G9_{#JSN6yGj69ctNZ^7Lt}{R7yNsVN z_uK-~JM(G`6iJ_H*ZmVVBH}u`gcrPwO-qf#YvRNzcIIgc#3U`QnAXF%~QH-q$BrNDOrEAzsv?rxn(;>QIAojYFfJ22#$u3L4isM|X0<0^ zG_zzq&^6KgWP8p=`bD09adtNQ`IlzMf)>z)fQYzZt=Qm(dll&m`XzV~n+*J=A0 z_Q00)N#6*mW{w;^pDu;(I`z+%371^sDG!53J9skT=Kd1H{8UwF2-t#Jp^!ft0U3?>_2kj0*tzGg%-9H#(2+VJ+blG z^Ycw*5`;C7@jqftSJo*g$r>Nm;-1Nf1J#=9qe)gaq|OZ(5^EQ8<1FkT2IV$ z=0E$ch}mz4bR>R>>PQ=iV|{R#1l6C_XrO3JfDMQnXg&O(@qQjHweqy@mHG=nf!&91 zeS6{G54k#^#iBUBw4)8!Q{_Znm5fY|XM0RV!2&@hDEdOCvcGgvIx&ZQ#7m!m$r)9OA6dXJ@{KjK z(h1O|%<5`+hoqvRgW+EY8nEd>*VPiPuEb1gx4!F|*vWhze7(17Zw! zy;TfA-PE6Cl_ zSiLfEIU)>7uEM-3SC8wFUTeG+k}lxQGui`1EIGeC6_#sD5clZB0)SBpYe?9|Mf9Z_ z&TAcjtZw>#69;vu%h413ADBuB6K)b|{t@SHqB!TW70%uy#Q|D)dBO`jhGVTVW-5Ig zdMc-&Ewvs3Q@AE49LnTtYY*fPc>NYPY z$U4ASZ1&qXpkgk$^3>MMUNkVEt5*(04U~!#;8bFnM1W>wMPaC~#v4Ulu$&=QVE!1> zJdqvUU8a5x7kAfV<2O@HBx3!8kB=Jz(4fI=gp<^u2} z?&+6YW%hVlHz`^HcmFLsTH3MV@a*tg|9W4bHGB;Tz)qnIccG(XJqU^*Z#@?Ys{Yb% zq*motJKL&+(NqQJ=9wemG)C%R+Dm9x4J}C$inXRZCQ(z&Rv_0?R#rAKNnI}YIb#aN zYhbLUlmcojXMXHP*nynRkc*2vC4M{C+agt-c3e^+C8+>H>o&uQ_?|u?vuJoz9OW-k zO3R%RdzpcKH5NuwH8W~M-yn+{(g{OH0h;-PFgXI7*|&A{elX`WS*^KjZB0cIc`S@f;}XhfK^GMf66Lsol@I?thO)3h3^Y`V z1E8UszO?J*X&dl}Z7H`VJ)Ew~q-B1#TDQ1d6h?W4#2lp!MUZb{60hT}qaS+bGf(PX z7YVTI;ihob0oHSqCP8XOGd%G*$F>-31Mk5jtb*@Fp;f^U0DRD#cG0%BCRjECst^KR z{08r7vx@?wj7sY%SD1~P-m8Icp&m(h6XZBbeo(hB@c+f(23ESwG3+zBNZWQb9rP}) z%=f#4zPOhCaSL{h$!YbMFK%Q29v}BXSSGYpfU|_C$E4mwm?&{`&GQ~m#IT0%UxDcX z!P=9ZK|9iKTot3eR9G{y-uTA^yKxiCmLmZ$wx3hU#k&=e%3rCZm|g8`d&;cX!=? zVp@H^U-Z|rPDSs&clKNTtZO=&PNos-vo(q_JOK)Gp380!hAJF$4iJE#BEQ_7lAJs{ z>A84J)hvD_zQ7xfe}I_gr=Oum`naWZ)5x9@Q5_f3IHvRB^j)}Pnru;b9fimi_xJZ@ zPIPcY$BVIRJaA?FVk2k(^XI^{4^4VxJ{me%ri%7--1IK){CGvSO_?S~Jkwu}34%yei zm(!}cw#3=2uv%EqD0{YBA=%FDs_41-eGqZnn zZIlid+XE*CF=#mYpT)q(E6;&Mx#;^KNQhe;)zj>e!TnLb`%`JzHxeE}WBGqR0t(OX zH>|YKZWg*IUga>*NqJQ@N=Sa&R)NV{_f1uFO(z^gEX0dT`nejY!uo&aWr%wJh)sGpMyWP5VO1Uj<-;J*|XM=D6Or73k zuxDO{===9+-M5_7f-L%m(1IU78gFs;-0{0D=%JR7r12xvxiRl8POGSew^^iXij#jL z)~XWh(s#N0c(nGubikvz`|yYdAlb9#jZL4*PrDZ3)3l!VJa5wGzdeE;%P&ko`h=0m z3kLvgBpjj5X+OWcRlQU#hH8=h=IF1YZ6ZD`?GCkvKw@HI*AsOGYV8o*HRdo{V@?o9Y58?IW6RFEGe#r+e`)cBhu+1Nyc;U7i2>hS3S;ye>iU^VSmBgSS&t_=X<&5j5n6GnJ~x4c^$-eVeNtH-Wr3H^!XCJZ+O&TKnS;i)H4g>@7W^T2 zs&-YgS;RmGogXzA=K65I*|$E*at0{520cjsn%*At;?LNZdpQoR9E zd@;Wuy(>va`oEHCat~o4gB{MUn(0+h5s_oc8eY#`iqQDkLnOHKpf)^EbH+O!i)R4e z2WJj1DbL!OVBvRf8N!JStNc!L)X^|~#K8e**}v}mZHC?090?EztJi(J_$b(}>+z_* zeoZbj39>m?h-LsKY2E!N0~=qUfJ4EC9<1}f%f(&{nr)y64gHMestcW#q>u3CV&2nw zR@_I6SCm5@I8<*vuP!w8Fv#CtXZNgWvg`4;Sis(qZDM6?ddKn%vklp_sE+nhS}gi5 zE=1b=TE7RB z{u>)hq;rRq15SaODr(%L1`HCH>SSl>soc2=0$V<2Y0oi`QBsN8ubJo0Q&^rHz0?E? z%!hWclF9q`@1eQr)!N>4WRFVuuD3RvNmJ{=AJkO5$9b}os|n!=fH*VkZyJ#cTy%$_ zx1#5V%mD3MV7n(2HXah{!n`7>0e7Jjq`WU~r#5-sI|*hAdihj6b?-v@{itL0Mxhrq zIERbIhW~yl-;L4G1%4cB8WGzMz`FdP_5iG7;*5H6fQoKt1S~)X^ooQJyJdRTWAef59!M4ClSDRw$!0x$Y87TOq<^KxRSP^* z*GK??tPxXf4o0qG4lhtYAS49c#?8EtdN20)K?H9q=YblHUuePMa>2*UXb?g5CTN%5 zr!GROF4*F=>=&X-}bF0jpHY5p^ zTelQBr*Q|G&nt!t^&BXF3%{}_&9xRV&R>BnlDSyhsqF`ev%m$^u;wu=0v<>9H zM6D(Ykd!7RWq*dG_4Jj?_bM4-`;L_fiHRW^D0dGQIKUhA1(+VYe{V91`Zy{vT_IAB zWoBo~`$*PK-z9(x3`)OKbU85xU<39;OG3(Xp&U|+Zy=x6eW_0AEh@Z0VeixMaCDZk zoLFWb7RNgk%EG4ffmR$GZ<@6be0_u36Bn6T7t-89SYMu-a_rTi1btC_kp2c_=_S;1 z$k}f>=s}=RrKR6%191mNajGX37lgzDKt>ri_v7g5X1Txixfr;G=^ERkP`N;d+CUIB zCMPDobTx%6k2hvDwyeT-nnUi~c_4oe$y*<8+(A(=_=bl7vT0QVL@{1?Z;$mMP67{u zQ|;l&%T0G73CuMvi@>D=7d(()>^M12NElHj+##jq!%1_>?dftIE>N&u+boaOvk1l6 zM(X3SiEV)M#{1S*^5h6de0%Y@*jTW)R&OJ7Er=twcyAG^my6GOsmbDkgUT1D$%X@D zk_Qsy2+1|f-h^>yr0O;h<2@t{+<2qM5_fwjL}m>J0esh41{G~A*jJ)P-}Qz%1-mTR zNfnc$VMhbYAPJa5gDe_o(}Ac`4B1H9vh_TtAL-dCbJ$ufVpfC8HYm6jCsh|ow^-ZQ zu%=&zk^+aJ)C}=>L(%2CFSO))=IEKYKw5~7;F%eu#!CV`Z2XPyUFt|5|EO!*7gPkO z%I7?Kfr zMi>gM5KH_bj^GdpY@%4nV;JG#bW^u6eKBU%hF~xWe;GSo@rD>;XhEvvl=cyr>Nc*rKUl%alpB%Es zrMWcF_Q%nTi^2=yv7lz~7zh1dfhI;l?7eI6z0&WRJ?5Fw61#2`=(!en(} zHesTDLN~?|yCb>Q!Sc%j8d zvI!3VWhN>hW=zw*scMI#m3@(14+OcyhB~HKp;Tbza7LUObJqjt?2|pu&aU6~4=)(s zIU@ja?qtgZi-FiSmu=R^*=u4dh)+G826gxn-z|@|0MbNuEAn2D5bRvFvVe0>^Tr}l zblsSOt}T8a>Y%@tVitHgY5a%sas7pcbjK6c7F4^FNy~c7HEkbC%X4BU=UIs|Qt_s8 z>9Bs$Z12le-a9};dMea+=DgQ*YMZ^}f!q75d~MU|$n4I|$gr?l44sn=d}cr~_xAei z#8)~b4Aa>VIbdQ5;a)Qv4~$Cj2995Nd*-#<10}}7SV4I; zDvoy%uDuATGt_h6etQmrc_4MDJd`iW#jvlPjhCJ z`=jp@W`P(!pCWkuVt4>ITZe2*Q`76@wp&HVN6!T&3JQbUtW*q7xv)%I?KbhR#YJ2? zhs%GBedwE)6|X(Beo(4}JiiG;`-eZ$lws}AKQYw+N+fxCc}Pk8)}*La&HOFU9mp8e zHOy9e>M7seZa+w4C6qgY@6k!?6QJF}*aa(JF0(BL?l&PMJPIHZ^uysO4RANqL01r< zwo>500#b_$DCir+rha~DxDHyXD|O`R?YXnJGb9kxbuOdg)Y zMAN+)P|ok@P?)mm>&i#W!-CE#e}AbMIlkDVJ-Lq91^Xx+f`l*PZZj9L{O)tApP!nx z7EkK2On|-{0Qm%M=M9z@fsKsqK^o^F0I)fEoLS9qB4R1*0&S0hJfc_SYB74YgddLS zgfm)*^oH+ImeDC|H-I3(K5G=f9nWW+9=#?xZhFjP>q8Vx$_=JIJeV;%nB9fH7ryJ2 zS^)m2z#05q(3i80ck3c)rC8g8Ai^uWHz_JEPA%wd0yPw|p#YkyFhGZh-)_IJ-}rzP z5Y3QLbf{$z1PiQ5@IH|BHn6>qu2qFInW0>@Om(OnMT$ z9w3Ga)J9BpCy9&BI29S)IWluyFd3YOX>J}pMWZFs#1iBVEQ7w&*mZsjW$S!-=^h{@ z!@NeWeD^|~5r(=e25DlB>^ZTIler$;E3O^mk_P~SLqw>F?JKU>DR}}=Obwn`O2&S z{|jLX86~FvrEy&uJQ$#PmArz{>&d1pRzG7(~K^6^<7)2~IlH zfM%ctF_jSHY4jSeGZ2+pkY7V?*}~g!a%8;9>$^bQm(?f(dajb7 zzHEB^EBp9CGiyk4EZ!iY*wWz~bS(oKato$I1wZ8M_`u8ztm_tCV-pj@abE=%*HzoT z7{G2>e?;&nK&j)J{m?rDhwgEoK4#(HuK^*SF#i^mD`dDBo=&t{O-#6reB6J%hEM0= zEfHu;Os6(_9t5}{;$U0zYitFCg$-hC1?si#f+2=;Ysn@h?20R4^ZuumGdc31b?Z=M z3ZYhL6>W-&}b3k7hxvGPH7qjW-NG>9FeR93WUL)?Y zPdNmnZerL}f8(J~M-otXlPzS~3#f+h3F*cE8+VO3|NfI;kcw%;^hv=;CKsKSuc z+tw%+U8-w(#E)}W)5YJ;hP1>ucW>{x=+P#a;-~MyaEEL%s|z_VgJ3L z$yQyY!J%oy@e*7G;2pKXSg`htfRYWUixU5T`vzhzX=!O08>eiTZa-v$nQY4XtH|fl zsNQ(?5sM>CJQGO35uR+@U_B`pdlI%b^p!?l%>7s#Il2${b?fTyzYeQ=T<_}nmDhpL z{`&wbGSV=AhY_>)$4AXi(o9M~i8O6z&L*#7Eop0*zYlCL(QX0HuT$JVt9>e+bdBAA zfS_d)yc5I!AG{L{M3Q}W|D|cLsu>>@Pe>A!J|L@|4O* zp{(z*msQOmK^IA?xZFhc928l+Vq&yk=s>L7C#51B>ML~B58KS8U?@%PVU?wt51}=M%-d& zz8$|DNWZ4O*_|DEHO|Se zSvtL(a`Tr&L7(y`xDQ#@G3CA6MC(o3n5R~3UgW*1{OAS78c%KU424K=cb}L$XW=#o$6;w4eo+PT|ORb#CunItV2fM)i;-lg8fG_HaLLH>iw*!C)pcFDbmn14n(9-XPa9NRy(O zP6O2N)oDNTe7FlM076<&LabwHIS!IgATi0yeIiN>jBufxoI=i*uT!~**!0O0z-;@7 zi2pOd`3q+!@+&^0Y za_xeY1<$N^*C%eQhWmFU3Ugi^m*AT>ge2^{Q z;v}|sqXrNnQ)ZUk!}QJ{zM7V9T=V$N5kLv~B%nGD1D( z`$JxGD!F$$V0xa77{V{C7`TULx3#ILybjdHFkog58gu-?l3>s`*==Oc$&~e)t(hQ> z)1`qXiCg*|o0>puD3ir^8Oi>9MOH@q$1fp?p4wh%$QGukhoaqUmayxuD|i6S_ZnP zE0?q`rJV_tTI(GzDB*r|EY;83d-F?;Y)mEzA4uCnmk$&L+x3d-NWE28L<8`IZQA8J z;xB;kHdUVy!t|f}b^Y_vl)c!(3fc5C&%qUzEO9tnGjq}G@jppL_z?TZT-b7g9a+O} z4FLHsP>7R3BM8N#TC&knPA?D6x`h%$rGWbZVO${?6jLb(*p8kyz@V5`(T%y<6-oc* zmX?N~+qv_79KP@QbRw@T;hkJoks8L*F)@iIn!gLe)HmS%q!<`C8qh9B1 zfN~}F=i%X9u!RB&JQR2-!md*}p!CV;+GciV@VKD3ryE?)Xoo=eYZ^&gz-l6RVB-%n zq}l#+mKXU37m`G3nxL9wUKb=fU-N6jiwL$Y*2aU!K#yW{coF|>0$-x2JryKK?>iPM z{e%dKu%QtC%{tY08POj9pl*5Ceb4M3Fjoxd!y#Ot#C$YjX^>p1jNHO=@OXB0^I5sr z=a`UcR3|AsoW*|Oy9XmQD;|T`3(1qrr*mq)lYBaSJQB&((7|e>W>v{Na|up|l3{>y z;;EC6AAJCcC9nm$3pSXmfRQSNt}UF8KrQv-G{V*@wa!%BuP0VJr0*C{cL74`wB5%? zKq9ffGh4H=`4)M*ZU4ygw>nCb{ra-wL2?kPN`=uKNMnH_GH}Y1oK0>4Hr<1 zn=%6$j^9+RQdSS-*CHrP0~Ng9TeoMEM00I*Cu$j_3y5T#ABSgTRIB_grXWP`^z(il zP2_9pZ~NS#1-1M9YUg_nbi%junlJ8&h?u%DF=iuU4-T9}L{X4NP{ctRVGV6O z2oG=)9-efufOeSAnWG$@--FasrM$tc8ku?8Qo=LHn}HV;ObQ5$>J_$S9m2udU6krd zq~fi!n8?XT0ZJTXhFoF;gDT{1;w_Os!j}8BLjX)Y2{&`~NnRFFbq46M_Wo7YE^MP0 z^3PFXwG3?=l{iiOhlGH+?px%;WgaS7QK~qR4<2{1>o`RCDnB1RbHhmH4Wowzy|1-3rx?tKR*Vzb$B&D#SU0!F^PopsZvcCA=v{(=n)hHpZR%ezA;xUZxm zNq1FG@NhqO7xNi+E}WlyHHxr6pd>d^A(^$Yr8sX?qLJ2QA^#?tHst>Mx>u@ZFj-sK zlkNtLSVRIk{i|oTmtpR)6;|&%%!jO1lKj^8!arR5?uM9FN1ym*BU5@c1l}orOlH}pCZ&3muO(V)s_=$z+*8N%*LZrc-yHR# z5U&#u)JtA4lF?0d)ja=Ion$+Y9mchVtan_74|&{~QOQ~QrtsiLLTmKBh?hyeVsUx~ z%R$b%R;jC`9?h zFS|}m-(t(9;f~+_E&^(<6^_lz1gs3^W4#B@M4_zOk2Vtdv#bNOd+-dMe7bnN;1@)AkgM zj!?!Qd#O(Rgil6+AS7yTcJ)y8a~UAvVx*<63fpsREE{&Ui>=pn@I_FQbX2Q#4*dGK zPNsA+F0J0?&5?RsG$w+7e%bM=gNSJ=G1`QPB1K`PAon7#vFiPVXxPu)ym#evamP3! zzV_o6<7ZX0sTkU%&xJKjGKGEEe8XdZzg109QcjAX;CY|@QWiaLu8!C{Un072(FCv8 zcwos&klc%~1>)kY=yfUaz!?C~gAD^qR%z*@Q3eGNl_TPy=4ww6WE~X`*@k6|T-?uT2$N#XLNIOK>F@z%}|G16>3d>fSy%{`Sc`?q8%!`9AKqf9>V7 zOy>{BU`>2~sJlQ8 z^x@-27C&AIaKRd0JVfr^DQ^WPO-x(WT-f_n%x_2RWr|054nKa-_MD-_oQEG3rWTR< zHCKG|pDs1oClq24urk9Z7QRTV&UvXn=@2DTt0;rNMMI{taQl{i!{j>mp}JRk9@-5X zeKgju7dTrs&a&Sf;*ijVHX7u0+B!Obx(C;i{PJ=JWn@+mqXTW$%7DI;(53(If>IbR z_nEigT?`FXwgOcR&|^oY$YWjeMK&F&^iCz_Gat;u9erK(p&Got`u-NkJLAB)ehBB< zA&TIa?H-_2U^}8`naeq9wS86jBnBXqsVvaofGCqsm#`kk8-=o4j}r)?s+E$&;?YLv zh6Y~|s}7}}W4fAg)Tg-(auTU5IFs{c%ZtU*GFPZ*9&39QiME}V9Q9m_^p)bpIhQ-u~v*RDsDi$l6r~_nrLlNvkuLk{&%2=pE?io5=ti$X+_aRa<*# z8>Vn10~9v^8osx&JWjrwGxX{ES78&M~nMp{VL6z|ngQ^#~dnf$yJl*7%PoHs#JoI}B&7o?rXl@p>s?-h{! zeKWlg2VjeRs@VNG3mtF8xd#Qr(o)FgD+0XB0T^Wc{!}rvvHIh@@}Z7jhaqF*s|(Rw zZ;eC)qL@z85$Qm9fR=y)GDNS8HAJ(`dru%2o&*i})2CQj;pzc(eEpci-B=#R4WjD7 zS^y{=so)(Sd>*OQaqi03SoxoPS&(eon0TALAMrm62uuQ}Mzi* ze#r8Pm(4L*Ju>nrG7l&mwelt<*qbdd2wI^6B`cVnmbY}O>h?Tzsg;}U=!d;hcO~6Y`}a961S~FaFPow2UN|>^JfnfW)Z#05zebK zdtbZwm9@CgUW$x2Hngv}SR!vET8!@^eBg|@-ch&~XDrDLc~ir<%DTma#D=&e`}5C+ z;}&N{5niIvV!+5^!e5lWljhil(m+5G?3=D|Q9%`10Xo=edCA>3D5igcIrI?FIHk6# zVJ@L>aD4&f)W7bW$w#eK@Js}OG^UOnSqjPv-B_>tv40s3V)XHqSf=(uuY+k$Ase8a zawhsCkA4c)(kS|l?>iZQc@TYenjDEe58p>R7B|@o&UyEiXcZWZm;0d)3wy5gnew7U z{tI>eV9{VX!v|(1E6wML7z6-LvC)+Dtq_9$Fo$I-*Ago{ZPqoZE> zob9`Zvw-V*rDJa4RYXY#ADJVb(J=w-Ehipt44NPCklVi0LW!yv##vG|LM_%`+Ly#0d54Gdw$?cPs0#g(sLox@lFqd!hFq+4>zuZ zE+z{sgh$-JqFJmQ_`5CR%*VUw5?%vuCB2iBrQ;1&5B* z4_i*=zay5#crQg-JgKPg{qao{VN&Ssj2WSp0}RQwlOLu+RM1kBU>{Wqqm*hU^yD=~y0`12Bhk&~+{ymlDqgz#O!vOl;b)1ZAPSS#a{lTkzD16qO>q3#_y z(+9Huhez;OuM-JlEu2`1eB~GGGTIQixI0$uCAo6y(7$%mm9u0b0g28LvA>f-%0&O^ z81O&!1@-!U4>*k+G)}`gJiaZjAPY4;^y4QX709bsqPx zka8Xv8AYn`+x+{P+V+YGZX`s_XC`F$%de$5ly8Zrn%EqbvwdvHlz z1aoe+OYa!&(W8*s@}H0j-fUh$Yk;_y!JLQVRj0;Va8ZWXqzFf~t&qwzqK2-(2o!r- z!#&Q)0Nu8t5 z9t`=i)#Fc^d(2X|SIW@RK2`P$KVaS8gl+}QX-9zyZ6I_PU;=CMiU*PoGxYEf6Kl!? z2MIw~ZVe?~u$7}e#tS16(^u9+*GpI$Agm?>V<~uq;@aouF(4Zy5>TNEwh?J+(iQoj zPf$#>Y5<9OcV5*uC>1S^(s*B7F~)PqW)=MFPlv1+Wq@Ns>mFv<;HyW){s6cht+_2F znWr8?xe@sYw#nSLUO}3?#FM5+X}L)C$zFUsA93xXn@ofE8$ZdFhiOcDW5)zEc`*y~ zYd@h?LLm%oFjuYNeFdd%MQA;clEdR<7eN9H=AJ&dg=F=&0Y?xyW(^2tAiW`)%B*;V z4al7ULU0?ImL!vn9^KoxI@zM_yTz2$JDXYh3|0Hkz=R%_w<`4PUK*8N3;EAufr|@# zqoZUj;3}ea$G``9^#bw@uUDPILfx0FeHN){xObUBe|s4;!imfraxPUfYhIEv=~6EVtUe*P-r+LuK3I{f`yk#w>f z3(3_1NI>Xy02VQLkLKpSi*U0u49hn(oiLddg>g-Cb>-gd-%sZH^u8lq#yJ+9%$MCy z7l$7R)=gPhW_;{sz?_yOn~_h&-y;suI}?)c>1_r@c6O2KtxE7Tjtm^z<#S<5=Q^Au%$j((?B+pM6H4X>#F4Ch}A*s2b_ zR~OdCbRk&lTfEAWH+=Q)EU6qcKmeg@5hNr8%?$9_CIxg8X?7^eSZNEdH8F>#NAU_l zWIYKXw_gO;T7_alTVEXlcS;$86OX*#$GHZ!&pu3 zr%Pd&en_IOb?nGdRR5jVgfrUiUc*Q$d*0IGX`P&)v0;YJ!dCU;lyLt9yIDdMS&ffx zGc}ZH&jEyp6?wB%JAX&y0jp z(R3bVF^)Xp%sn}5ivuqYFcZCbboPStv%SVP&aVqn@hL+oi77)n<)$Ol{BK8WtW#5l z`sSR@BsR-dR8-tk#B%Pu1aO*QHeEWJgRFb*9v-RJT9SosXf%N--Nw+OUs~Voa|TR4 zOEtyz{50ZD<&L*xUXViy0sQ)f>gvCyRAVLjJUR01qxS7mSy)>92w`dOrI7_!=k8ve zksVRVCUju!;$|Gk5B{;}8KUD@Ti6~hUl;gVn|n4+Qr2qPk~^DRoy1soFYn%|0{h#? z83zPpCCbOSRn!~B_+Gm?yt7bl1mh?x*~6F?Q3ok$x6`h4ptb=4AuM8Cw}f?;9z>Gh)TKYn1FKhZeTT6m-vY;tcz z{e7_d?l6N%*@{-?kzW7cGvA{wwN#4%l6O~u_Rd!P)w1``qZ)NAc;VB#hU?Qh_$WMGYo&Q6{PuY-{3+c#r_J=19W-RIH?58sdk1~JN} zIeBJfCF?WaKR5?n)leM$QWKQ+^V1V5{u4xA#C&Ajev3Co)}e(VhZ`9UJh^8f2b`SO*v7zz`9n$$A86%+oL2HEhJ0kmzlY_x-yXmS5NvtQp?iufb3Q^ zR}eDAX7b;D*k+x|!`rhresu4!TIyH&kqzW}bvvS=cZ#;??OOlr?na|Dqr^3=RgM)> zSu<}aYreGsDjLE?UD;8oHcU3}2q%UGKRPLiuKd&;P`5eDe}fG_z>&cBi;0eb=oNGQ znU99&#QjfwUzoBqUfvs{aw(IU^NRBn4Q0-s12@%BT)tu8whFL#j^-+T;8=-2IkQ9& z$w{mU7Hvw&o0rYdbZ^Co+x&2(5bO@wH^bLwOI*es53r`q?(I}HfY<<|EB;Mfm?dwo z_E`J8VavIF!eBjlM2d|`t}VHVpD7^IFn8VEM?7Q^A zkQ=-*$xWtX>0Oi6br}&dU~F#(8;tjM3vjOQO)KHSsnp+tcL-S1lsw1AVw*>qJpB<RGkLIQ$;GRUc2vAD(+o5;9zs@<1os65h74=YVe0%F{sVgR}GVQF1H^ za$FQq=j)HpXha&9d6*xqS5ElrT?v~gF**HE#SL+tSi6Kota&50v`E)WwT;;?UJ%H# zL+6v`QD_F4AbaF7OJWrUNg62IQVWIN7k>&xr}bX$1UjwjuK%Gqb;7ADP63RObTW_)&!j#L8@QBp3uJPw)2% zXuCfA{w0WHY)Fcf)GBG)FceHuzZWV%Fv68x+@s@tsnn>NR+twxX^hQ}#nEU~C}{Vs zI5m}NF2zf&{lKjZyCZirbakn9;w2KIu;#1Zxv|^60LAb_L2Q{JGIZ#ncu3Xh2|xD2 zbKg=Ta}pn+xn?$&Uk@lp5g^QuS;@=$=*d3f^(G9^II`X7zuj0De&69MOWLgE(Xt&F zxYq{D^AQAqed7-vlzy!aqiLjVCyP`t zTC~{Pn1e#RdE)_8`&sd)(bceRHsfn*nXUay|031(*}YeJ5tDZCY&x2nfwYlN!KmiW z`I+{^lWbOj8Fol^lTH|G^=>+&S3)k9Bc&`2?c5w*8juVS4U;pJ?$zDf^?U3HzJKlw;&QC4T1_Hh;&G&bSYgg zq6j>QfQWQRNGc+wASodwA&6)02mQtOowd$d$G_g?tFrICXV0Fw=9+612S0xf98#gS zKPpIoL9zW8%_)YrK2!w!fU%q)KwYgPdHFne*3QlWxx>{LeL;!DRs2|;VnI^+SFgSV z=B}(4`YT@l>norYZl@|D1YQc%@Kfv(YX@oePRq@JLroL;_gNiYcP$(TF+T@XU_|;c=ozL@%w#$f_}kM^f{i2PyK>(B__=o;!r$&w%Hxi9VfSXgSu>dKp-vj(nF? zINBd1{9bQ>zV|n)iRZ99I&d$2|HaEU_4E~+yT89<@8P9q6-UP1DB%?kkuL(dD52i1 z=NMEN$$_Oj7WZ&)afkj1JiZ53{+iRGm0a;*D~6zJqxnZ`oWEbn;vw0oLAV$+VxOe? zvbx&p2?36V=>8IJ?s_6wgs>{mL^Nq1Grzn$(^^|(_v70KsD;+(%*7zX?|>HFy;@BC zd9QKrJ3vL`1W5|Nmi6Glux<^Ff-io4r+#?>lF?u(;VnbthBa*U@WsLfd#3=Bsr;dLSaLjI-KHzBWrKn^pA6;L{V=kx8`4{ zg|*E9D1W-8+)fxvwPgsb?vs7`Lt1jweDqNn6sgw7Hk%@dnLD$B=RP^)0(wk;qfb)s zh19Fi`^&}jO#ank52#0rvRX(?1WlR(ex>kS*>FT+1^sDQY9zNLGJei@(HdTJCAMeq z)VxvH$*HI`@z(Fc<;MCa_5xya&cj`rN%fr!Y5FaZG?3AOWr45?O}>qMRElS%H~x4~ z#Iok#sPOf%p^b}Hp^59tHi*gwUQ`AlPGa;rmXjD z_{EDC)jM;278F~tVrk&#WFAn5QCNWD60!f15>zJeyv{m(c=`e!qZXxzv)0qf_3E%YEW9^ocQ}y%9Wy+J>*ZS|Nm>2}_R>DZx zw6wG_lFTv99)(xevlPoxZ;pR&vAn5vD9v z$w-@MW3w6dDY6oZLY-l_INhmTmWDwyhU~+*O|pZddi&e7G%7+-GEd%@b7_*Y zsAw7+XGe0<;ugR4SnwSLp9H%g(94r@Um67eAqE+OdeJ_N_6iUdBDi@l6dzCx`Z^+d z6MdLhxw3@6%X~gKs~4_WF0sH=aIio{M)neN7gN#^SIX)sf=u5Groe!ird&00 z{A5w?9v%g1KWU7rnsi!hz&WBlQK_=~fHUhE9k&HGn#mRAkofN%4x^0!W zDv$265?#2$*2#MFRsd)7=7%#`$#LBh+ZNi zH(7Mksl9bmG~if_wdXVu5fPX=Op#Wr=@o$(@c}Y=_llmJzzc_ZX{cG{0yt!4K`}f$ zG=vKH)j`gwUHwiL{bIcSerJ7k)d%J(fA;!Hq@B$z*A*Zsf|Vw4r*0-3rYX*%Sdgb( zwi7~G(pSBTc&kiQd_v#$lQ*i<_n9%s0gGZyj2!b3r@K!!*v$v6bHqAja0=CoZApK> z9^Qxa@zQ*(dkZ)r>>AGfe)7UXobev;*}{|TiScwIxH}99$r?T6rl!J|f<2xZ$izQ( z@vetmmZF?*Jzcy5fiqzo^} z+_i%;ogR?l$AyT91dJG#6-J-(=aWJ~b*a-gL#0>}^o+Qco13HIcD~%C2f=9LczFfK{K-Qk`gsp2SVyn@vIyowxrOoh~-%u5G6)& zT_V3nwWpt+rnM_;VZxuoK*G+dX#@lBEv^_s>z2*QcVpb%Tjw$^Gch$Wu{%R{fYglr zc82=TSyC8CdTo43Z`>&co4uiOw(lvqZieT|^OwI5n|>eef7N66edJqUtB_U2isb=A zBP?$qpWXin5^yNhZYCfA3@MnDvhp2UMoJ_u>ahMaHSOswGN8R=Lh)N_heC!;$4SdrlQ^&c;r2rFgT z&Ay@eX5m)adHfIV^c<{i{eCKMfda?4Dd+%B?A&3$XCp!n?7NX!{%TTBW#588m-4kVZsUxYBp; zj*_3I@Z5d(SKJ5gR|?%r&!Ko@BZG46#B=Nm8-xo~bossIyiYshk4G)FYM=%P%%ioc z-E+5Wk~Qk{GDIcPF*en$ACko;_tDhcRJ|9vBI|aaU4Q%y(Y+WDr9oQ2%Q;USaDk8z4$`#>zh6 z1nnU=tLhb;utO~6?5m}MnARC#Cc*;37QQenSQ%OMiz~ozhB7e}X9a#=1-){%I~47w zrj|#3MRaTY@2z7`w7kndYp=Ga<8#A)N~@UM#&|`(J^FQsB5f<$yT-5xQ>|ED{iPwh zcopvN-R8@u>by8v_*Ze1Xw*G>I8c#-MI4c7f)nhE)q@Fn&kJHaq6Y5Ji1bBtpIL$* z*nZbkDR$5Bej$xV?r>qeqOl!=H}+zH^vTs{)C?1{6n&L%o)*GYt`2GA@(LDPtD7gDAQ#t z{StRTf8q4kD%=GD#mw1Hjdz(-g-?gO-fa8Eu(4iDrgYv(PIi#c#Qdm` zz9|Jeeti8w;p^AFI}`A#CiVC0igV|@jBy&&f-R5Ve{Ur@pOkmFnkUO;#6M+PH>Vfp zs6J?OuR@rKj}5KU<9UL`Hn!c?hZ? z_DB1hUW7@ZxaVOf;w!E3$5W)d*x6xs)AF*3+_}DJ5E*?Faxx3{7_XGZA3q%)rHS~2 zlEn=QSM#&Sp%hBL!ko1RC0Z}zk5ee^{XivucMw5#HHTOzb!qv)`yx-E3JXoZyD#U% zp+1UXfA?-B2vR_yCO^L=HzRU|A+&kj2IbZ;?drgNJ#w+ZZo0u+@|rA+-VWC}Oa5Cq zWY!wDLrF-(MDi*mA$PY9)ID=bLJwG`BF>^N#nJ?YV>uHMCgsWfaUUKR_gIE}9;DC; zO=#b}ExV#ryk2$_RYEYbyt1Mt<{Cz+0Uzc(w;}fO-oG|^8TBSJ`h38V7kdK(9DP-= zS0+o&GZhtECw&%$+uz>b1g7#cC`Vf9KH7ku$KMd605#AvmRX@i;!Rdruh8eMk=$b- zO1`Q4t=#r!mm!MtK_Q^F>H6c_<&VT~k}*A)LpzN{HYbx{3H!55_=x-EaKz0?F1u(@ zX%T2WK~_By{y}5#tgyBrdc)=BspBMc8|5g3$1TTdu$HuspW)aK(FwKX^ zmy5|qqqVivVBwJ+4HzAs5{F}a^K(eAh1G+1A)r0^t*(no!8Mrmy+$?F)sf{}x8k9Y zvL$XlO0#KsB$Kl>oQBHsbJxLJNkR-4PiZRThjfVjY`z*Gb%@>vxQ6>5uHt!fz{_AC zgVY9qZrukU0+7KAK$=y8jXF%$Z+|2A_mPS1*G0GQKjRmmr}(FH?FUHl7^U6u4uiL* zQOvrZ$S}-YQp8v)A*NmZmGTAgz5i<)GgnYJr=Rr;)VciI4bTKKmDyrfodn}`nZ(X_ zPn3z2#YkKixkWL6GiovEPoF(Qy&;9Vja+mDBL(prcIz4OF~OWCq4^Lk2^$9Q;!W}@ zngQ?E+;D%-LUjHnje19cppscX4?b>L;5gT*cZ1BP3jB@s7tTNqT^fBKj z9$g_!i;7?()%Sr%bfc=E3dVkfHjqKsT=jOX_A}E%-F_#mr{Dmf|B#MzjvA%1dA!yD zddD*>3XgBk_lS9}PaZ(g&pQ5c0Hl6MsFZ%)O`{kw$xnTE!wn)f^8O)uwoNL*ub3%{ z8y|WS4Pf@|7RL_*;Q>-|=S3Il-xR&ybRWbkzQW$q3HEqkU4S-G+DA>t_l~>fO`6eW zshKH=nv=B+#U2LhJ@Px*RL$B;wT+{C1V|9xG6dcJ#*3s-a9gsES7xa+Q~G_(LB*H8 zGFvTw7UDV#}FPVorNMsM5thn_T5}D~h;R zPEO8d#735m?6$Kg@~l}u@vXFQsMMC-iHsa(o4zt*uVN1|zy+y$Fw(<@meMJfo2GpP z5ka)=RCdBY@dkUJe~T#y5%5gQPx*fTs3&P{VUc}GyBu`8E{Oa2Kxi-KtD;K~{3lF@ zd5;xhh_}6cwez|xtG(CdtHP{Lgth+D(J~rB_>l2LRZmZ^l|)rbE5Ggduh0K6^jLEyz@L4rpcaj)ah z7@OmrJDpHk0PY34v{2?J^z~-5`}Yr10N{kKbvObSBlE9&HNj>J|8zX4a^v_^!5Pfu zV?$1=@Xi;ydX#5~@W*-U`;ynBzPHU`?|=mtzIH6!V$0kbG@3S@;*wv{Oq8DG334Ty zQqw}e%iv&(d`*USX(XtKINL-EIedx8GoGprFK=6k8^{B2&yh`$b~ zuz);HMeXO~&CRb|V+#qj_YdaH0)9NRd;@B`V~Q#1Cw|q$-hMtz)#g$%|d)iH&+Xt5Wy1w42=_Yg;Jg8Hd6s)JABZLjMF&fSFGj0Fv>Fy2;9qZ79^i^}#lq<&@;BQFL~O9=$f~clcUcfdJD9y9PNp7A&Rf$qV19S)>Y|I*H$I+u+ynjkU!3xt zHlbK-C$GM9%2wNB`FV1sgEFXoy@Sa|8?&tV5p6(o%uL)C1=z5vAE+Ku_C4?Wa;R2n zCcZWFvoOm0?IX|{l#I*_#XD<$$W}n&9=LXU0%-wQ<>^sC0%;-J)&6swXF zT;it$s_Ye7_ipmGWO0ZdvAkc}JG1Y(Ro0Q(-lYu>nXut|8s0oPZKokBii@^b zcTxdft2^N1b@ePula=Kl&tz|K9{0dMR|GukrRbp4MpRV==pV0>7Iy3GC?0WSUE$m zXK8P6w~6}9Mmfi=#*(%5S-RR>Kf!t+MC&-TX>pADp!3^a>UCtFWmL-TQJpp!^eL)2IB;2H+XB>5n9Tu^{50dwJ!sZ_WjedeDA<0*yd(FFXiaUc zt*;0unhkMA?SBcMqF{TuK|p2H5=n~R^Z@3ChphMVO<{9%tU;LSr-+W_8>e3Sf7`U) z!tf!h&er&*b!nbll{)syu-qgSVG>Q_Y%|_Ta6!M!#JJrRXw2PYOp1Gc93sl(-z(o0$ z;{w@xs}Wa>LYo18tQ~~{;UIrCK#r@M)ia7$TOw1I3N*Q@l+)0g0Ys1fMYHH3)Vb|8O$~t+5B4`^~MCXQ; z&xEk+iZbJbf4@z(Fico>isP7c;MyxfXTUJ>7>OZ|p<52@2%%hl6%cyOFXNSxNj7Fr zd+fUX75v^Ok#aY@j8-C5++WkNB}L3f%y7aVFaJz^rc*^(=C27v^k1ZSREDaVEemUGHKv~iT3vLxpbilx!={3#;U z911~e)J({8=XrT;i;H@}HMac^NuK7_B%5oxlO00ro3GBr65uLb1jD~kE;$-u1u$Vdhi~qxj6wpZwd(#96*Ov z;5?tD+)SwVBe@CFjTJ!1JvX(REeieIPR>!Veu?#@82U~ER128J1J&PgZ?#d8RSQO*-kC&U6r>Q`3lCn0_yDcgM>0yx(M zFYRN$nE~3jRq0!6p0^yxTEUf)4jkz`&O2mdHfPoJ^Xb5gS`T?H>K~SawdOUuT_MO{ zeEro&@T6(%hhYY-xNmK|YG@kuB2zc`cpyAMI~OE5)m7eOAj$G8W1^t}@ThC)9%ij{ z-Vq(kr#V{EL{o9Pj+GcYXj**hO$#eE{Wk6UU2eTDsjstW`q#Qy#~~K=Ju4+8B^YS% z9#>&MA9)jNIt)fTA7<9qA9L^0@1C2F_!D6O9+u;Rz&kaM6awWvYU$Aj_mnUnDmkv*P!lgVpvC#D^Z)W1x z+#NLaw$s!=^`U`5 zKseVAY1>jQw)6I+F}L+hE!>;`8;cRshx$lPaAF7On&3JQ+tU5|IMPz@N5#9PFiil{nato z8pDKKz%GA(!Bvp-+ZSF)$;r>phX#Qm0kd*$e*P-wNc$(Ld;>>7?iye)u|NP#vrATs zwDvdg5FMYxaSpG`BO&)S2%ApD{d&uF%v`HEH!y&p)A57;b5yzNwiWN#7dYjoR}8Rw zh~F%6;GcmU?&gU9>7d<>irkJjj)3I)(DZ5;pmF2oDldCs|zV6|;) zN=-|(?VS&wO5$|77+gc3sy-MOk%Ks>SBVs5y0cTH-+uHZhkejUk-8@0&HvBArICb2 z%1S#~<3^$6CJi+kgR)j$)w`UTQNgKQg!M}00cGo6AX`7yo?&sm5EBP{yt+si0t~MS5 z)GPaqi9xEe2CK-6QN%fgmZzfzN=DUJay3T{ZiH7b`iOsQ ztZZ?VYm9xL~`OK3GSOXO`0;Hb* zq6>%_3O9$@S8u07ib_0MTyV&Ech$v0O`&m|TVd*9>p8%m>LnA`Z9TG&S4C+^F&{$O zNLqK^xnAg;vX-nk%9@UGs+K;yLgKIU7jf64JRraeUKg5k$0uHF_wTA_7Yx9+2_XW6 z>8}fA9N3764<6e_9V#9*t)obUxpO?#o_rM3J8i^8DljkR?9TNzBILf|EHm$DFp5w{ zxy;h(_RgX5rowD)z3pX^XH}}>CmB44W7qc2#=LZiwipM4cJpRB+oBpb{w$_4KGi`B zUVq6vGSPt+T=dJ>^W}@xDkaO}yUg_aB^w%mn(vek$}~3H%wM`1DC&LPrLhbd#*m4LUbjzZG`@ z&hQe5`G=rG(hm$cXu}hLF(w9&sl$%in3>Gq_z;m>@ua6>woMmZ_k_o<27(wGdt1EK zSh4=*I1gf`_d8bRboIpFMoZkyHTh?_ERdA5C@bl}4AZ>f;_(*V$%$RPOihi$nl&NF0$v*h6aqrO5z-;0Q1==q1XN18?+&uy}_Nmy$csEn3ZgFcgEB~jko7l z{ef6M$%(J z8tDE3E1>)9_!jzBwZpBlyuP|*R#J3wt61bo=mbZ@f5&ijavhzDhkg0c?k6msbI{IS zUp!|;K$is5uHt6438fD1VDzfH=av%%xqz3aM0-;p%Ux6-PDNnO)@=!SarOkXqSy{Yn+=3MCgys? z+*~P5VkE>I0zQGrIf>5$s$nCL-B=U)RJo>Mf#O)n5aU?79vhIZF*p4 zL(k>eHG9|7G|(|LP`&IbVpQ3&q1{qqo6XiLsy)vouct+F^Mr(ic%|wi8b5cm=U^UM zizB5|ICt|dKti`Ze0ubTdk)BSV;_EWy%$ug^W96%l(=f|aV&KuHFf0?W-soak`n+? zG9S^I0Sd_s?2Q5W1b>*mAyn*?qJcpVIoO+c&a3t-%g9eiQAJP#A7NlxaTWz^+`(mJ?qvAJ_GkdP8AWCZ9NKlou3_ z{_PQ!YF#>%LP((={XY&)$&A_#Mb*-Dwd{1EyA1nGZCd?zxzsLd$fFS0&V!J7{R||{ z9OVuC^xT$&hmW!pqq*Aq9O zgrzN}?h-if*d`{KG;P_I2CXDBgXHky##dpgK~VeeA&y6>{(h{^^Jy{Tz|U%Sh&G$} zPLhc^@|GpD{{zbRf)VknPk^tmNQ~NYB|XG-W@R<*u&DZc14J@T?w*ttpqlpHq&Nv)sI2%ek1Sa3q$ydbrb)8qgX;;x7e{|dMG z=jbaFt*X}GsMaohbZF%?Y2DS}8Zi@9B%t)QKcnghuu4=!=K*s;M=S5&t0t4PZdQr8 zS+YOuFO zXzV#I0LVYoSx@kA#)tqDK!&%cq)V`y#N9Na!3 z1(aj42p2Sn@QWsQp-aYwqoyxmzobrId*YyW6^_@rj(k3@!S#LQHUxNhILX+}lI-0DD-(F=&`i%4Euh6! z88a1*dlj2)vha|@pMO(|q>#J?1H9w)-;t3&;t+U0yG8U*W?2N-M>m_z19U+I@rX6b zdshO*dy)+=abTNdM~m8p|J^$z6ZMb<Nno!6mG9ik_Y@g{C&?$U!AjA_BqsU9!pg+c${Ru z{ZQw9fsho58dl0*_ZN;lz(>Hu)~ofON6dcy{3+ajnx9S4jQHzh$p6?t4_RY*UR!e{ zC_!pv0z=sXe&UKx=<^QagiOOXt`~lr+g_3i@0dk^roWjJx&m<9DgkSa#<31}^UpN->?E zl=-SK%;3Cuuol$Zz)9-ufK)x6>%ZC^zn!={42hVVs+w9?feM%XZb3r2d5t%exA27s zK8=iAxq6?L+$zWD{*Q+U-5S-!Q_BD&s03Il-3s{$f}%dz{PsD8V0(2vS#p}Zg(3Fr zjw{w#zW?bk&=2g)D68H#8AXu zDU`~@c=@dLjMtJk(t%QN4!G;jnMVO~&BTD;=y8Cu8dNAGX^x<`Fy>u6BAgSSRCHv> zDk#xD{9}YIUfgNaWW%&Ny#F-8M3R5IAKhepF7KAO-#)p@LA=65w?wA zO^RMd9!npZMW!-OfLQX@2-6Zzpa@-jlIlTY1V+5B0TMF&c}Vp02faX`QP|p(S|C^~n7)s~_Irp?t0R^LO&w9@ zro^>R|Nl(2SPeHt$wZRL2OaKkSArlRTOyuC#fwE&HPBaO7O^exgKAJxVn}su?Sy4ujU|BYyuJ( zLW+bY7P+I1w)&V$5Nd8bv;1|-b<{8Y-a|q9<4~~wgxA#9ayZwd9F120a}D+K7?s4#tGd>)3? zk3d&cd-x;Qecz-I5fWN`Ad7IQ`?J0639kQ2h?Vwqo=6S< z-C#(u(B`WasZl@*+F^9?P_fRNKhKQax`>4PXg534=C26VZsh0c#%~E`=JrXOKvB$q zGAmuPTFuM#qE!B5`Bw8LP^6WWgE(@hNx>1SV>>;rmKXJht)h+ z>s{J1Fxh%2T$h%~td5G=NDm5&im)nVk`N7sn?gkJ*zfs4d89-q^UfK}gX_@6;sCPc z=d~S`Jw5lJ1xk$ma&Ox;pf*A$=LXGXUC9%4h%dH^14{z93ai&$z5v>ecVVe~umt34 zqd9&+_*!ED)XeZsnC93Txr5x;e?9m}J=&E|iyd9u0!t;DqHRjak}XWKIUa85z6Uaq zNE}V3)cNnXYKrFYhuai?YMQ9 zo3M>rxsprn_`*|`_kg`y4w^$ka!J6DWL+z6A)%SifiB+ZyKR|B#~#hw0c02m;$qQ+ zjo(L$&=}(mJ-#3ln(A$KVcKg18nJ@af~!9Nx%@CmDh(mc(jn1UTh0$c#5mPK?e^jN zCG&dia2iYK2AMyPY;F!qVw#iT+a8t~W;P^&^1$i+gTkQS8{~GQBPpbYLD!!gwq-wc zJ>S>Jj4Yg9SQncOLV=-TTtaG_wn!vdiObiz508LVDD+?q#?7E{wksi!O6xME8AI)- z-aLCFVMy+vgFu882SV8YOi$1unNP~*`Av2;8Ct|nhe;B^PLm_%;T&mujPpbFRjAPz zxCs&l&m9wQ9^#i0-n%?OHb15De+z37DXmK#GSE3GkANfL!%quchfl$FcL zU9dO5u>qzW@DiyMB_IF%*d$=)p?YKB)qN1GP=MaYQ5BYs#X^vL=vx@xY5*t(JV99r zuKnv1WDJBN1Huu)!D)}#C@z};9~>ksDAL(;xcA!gJC!+KG0T;l1U9Np4YGf_u-dSn zW*y;x4(C6Gg|<7?6Lt4P?-vp}J5ii!-98z5DigB>YzAErxxuVv@p;4m7~ih#qq`uTX*6X0dav(#g)7XwDsitRs8|iw>X)f94k$Fc`2izjLadC0bwefhLk6l7SVtovyG%YxeHtT;Mz@^&H z?kqG@Y}{7=g1T0gbyw|deHqM)j_x-;9GkJpneDdC#DPekbfCM2p_L9DP2@-=Qe`fZ zbR~K(&`=M&W_!Q#sN@vT^s;67D}qTy2yqj~jAw&rrn+YX+ZBjpE~gJ@Exx1!P7)f8 z{1ZTzs8Qci24fcmc3JyCx+WwfP!$5-A_`zMSCD!w8eF#fXM0$ z=^95i9fnUsZ97*U#*u;K1zMX<+1pIK|Gt4-LR2gYp)8ibeurilc|&tOZ}NW*{CfMV`g zLg?7RLb}WCqQ6nwN|c7plN_%+k#YL^2U^mV-@L*Lc}z`g(Mg$DM0HZ|c}-dAOa2+& zRY)idEhotSr!H2S;2UviEWRA4<5V)6UG_(U6!Zg^xi#l7s}WaYi{8y>7hsS4@jG~3 zDHRI!SC+hy?%jfOS8@n}{7SHPQBwiSqm$Obs+yhdp^aDyf=KONi+!Nr&25VGZ8$2i zY+hrL*UpCyRPY@J7Gi>5$2V}SVdQu&3Ncg|B>F7bqAG~z7ujMj0c0bH@Ujg$* z#&SbL!}GFLcm2g2-#Z%OxCkt?bObckfY0XGSf&{nf7h!kGZt);7{cX){|v} zRK6}hhlv%hKWIU{B>Y2%<9kb09r^C)8A3snE6SuhT&mK9ur`3};fII+l>_hMDa{F* zniQUtoPiF+5lc{<5TTy7GJ{igAt$*#Q|V-jwI+K!ZU3X(g|#+k?F}Ivmj$^ywSl`j z{~gIxed&r1bsA6`8#zSy1!xC7o^o1dTSGjx(hed!qCgAYp}!^{$0PKfk4d@OA09AL z{pM~i%x9oOB$O~r9Fz?*IW*77=6biWqy6ZF&*`0`>nLZ+-oKbxT3d}+De*sU#>yRNacR0AmQ1w zHZC9x5`d7fn3prH_L{oaFD?MG|Eu@_<~F0RxMMC z`5#^*j8{q69Y&bYPoV!QWa=A->=WS9*(?Q+SICGZ3%+9;74vyYlUdZtV8WTh*Oc5@ zuZpm>(C{8Q|5r5#6u#wk&k2#%qPSN&^i8;;flh4?m!hSoTtJ z>#Ahh`3}-=1AWnEyjZgvfrqHH>JE==tp%?dLS z%(`p*rU>~Nw6CG71(OWPcb`BCbvSQ!ahx6ebh@A=G-e~aV^qBB9%!| z+w^M<1k1)uZ$iS3m@=@*KlG+$i$E4K;Sq8f&IPDT^xElFBjBomNh!rM zKBZ!=TQ#QA1l$U4``NuEXdK}9b1}qv>T*)We~=?tifMjRQ`4I_a(v~XOPY92Jt;gU z7hB0qIqW2fGQtiM&{oZ}5HAJk;;*Acgj{2zdFeE7{&ED(Hhqm6? z5ay%7nxW$-O%MvUf4&f_KS3|ER9kj*+C^$Ne>+TU>@hkzPp$ zF+KVa(fpS$KlteO(4KdVshje-7RUK8i8YNZrmNiasHu+Q%7C`3L&r3eoE;7hPT%RW z6kq}Ul-OQn-F-3k(8ggr=gsJq3)Tc(&CfsHT5NbNbehGY+%
UB72%fhmj{oTk2 z%st+m-wMvO=q|`tWEe=iK$W0esP7ad-dA$^#fBYhBmC-rq_E&LSx1^{XNVXi5K02E zgdfh`133j9hAqp39%H2OaFsg#*Scqu@5IEk$5yu%Yog7Bov0bO=Xhb2o=c`w7&7xI zSE$f2nL12M5#8k>UA|xJGcLtiFq!8|+gBjza%TklM>}Q&sXSWYV{#sjZN4Yf=9`ea9Y;0iBJk3dP$ZNVrH2g2G!re^4*3sjzg#M)8~b^nj0Q z1g`aHM~s5>4)D}>pdAQ4Q&E42W};p6>NDetneOH)W9Zn1K^#5>NVpy(?z`)>dWChk z?OBo?bd$41M!G!~w0%D^5<;4yKO5AnL?*<>^9N=u4{b)2?ywDE1a#cP#P;r+&HUP= z_Ss{5(TVCsK$a##7Pv(N2B`}oB3WLu1+op?b{gG%&;lAc;Fx3aduSCpb@!$Zf5708 zcNwl(&OVQxeh=95&0w(41UZ9jzpd^wXrEX#J8OfiYtYus7=KIjeU?b*CFZjGHl z8nj})9{D&Tj=jeMk{-%749aLX4lGUzN=j?ms3jX)iUDAZ@XOMgczl9JSEg5_vtw%U z$Spt`Llcz{kPcdbP+>uCuXQD@r@7=eyOCaDYPj>0 z-xph@3Hyc&36~{8K;#@C#MwlUB~F7Nk3}jwtyCKU=wmEd5YyAsiv;^|dB`(`d(p}o zbD(eMQ|QbSns0lGnH=NBhb7^;ex0A~(FGSK3DwQ4T%10TrLm6z4F#a@$~v)mokP0& z4pbYM+cJeI0pV3;l=ZsXo5mM>PybTI?Uvv$0Rc-XpqZ=(3QqzrIbBe$I4^Hd!tD17 z^bQ6JbM^2d1_)yHy21z@*=w}IGM-UWnGQPby)=^0_YHa`Lj+yizcdHc*Gm(!GDl4b zo~&4V0rB7|#RWs$7Cma>=g;S->)#1$HY&d!WpCJSR4GT7`2J*PYe0Ub*_O%{a%t#U zhG1oHgHs!#lmZhy*&)URtfY_kf%x0Bo&B8wL|yh|)qyj( zD_*i~mL2<@3>Ywacq%jd6XdmN`uOiDg)vz_jXW^*60Q8Qva}Sb%<9!_vw=c-zqiPz zLrXIh7BT|g#JnV*Ppb(0Mc>6}Oa?g@tD@8uZ0sGsRnlfpoIdNa^znbTW6HZ?-L`GUj4abn++)Lyc>1nfJiWJBDAt@P80ttY$MOmy}vZ<8w=RR^@;3^j6I00|Ww7dMK#lU#bMV6#_yxAZdGmFm}&zHS;4rL7;Y0^!BLJ zg!#q`M5p1)ckZfgPz7)*JQva2ey1H-CU|IMnZ8MsuuKGKerDYO3iei5-rDJ>$cc$m z?arQhiplxBlDV;bdm-xkM*?39#jjE4jBaMD3rhS?n7D;htI#r!Txp z8Lk%`SP6HA8b>Y zy2w;Q1NS@=`I|?}lhh@on_aHF@;6-0_Z-l^3Hm;a|rvrtp zwZ?rTgqTlY9|gu3rNQKYPhifF3dA!Fi3Vrk*?)-J{jB>d#ve) zrI5%LCBxGA`T2cT%s%@-L-gdE)y?tS70zRo`hA~0;*Uz98yq;-!v9?Q)U1!U3L}2r z$kV{YN0}+~PMOx-W%1yKe~&bg9_tf?tjlYuisObn*Qf_PiybmqUkMr!w#;3iY&aHyNd8CqgH%`3rj33o{nsfBCesn(2E=1^zNYh~B{}kN)U;9}X6yz>ADfOTxAUA5KyB)#DuPgh zp2jhH193t5MwOMcp~^v;bM_9N)A7-Pi9y(61sRaf!K~j;OvD6s2}d-mf@T|N+oYy{ zB;%48$h5+1d}C8;XrY0{g&7wzBr$N$u zLWJ}l-f95^jx4nBYIY{^BB+6pM#mqsjO^=UzK2M-5ep+W_GVG;JFP-MumEL>`PJ*P zyNG@d^t;z-nXXI#sMGi8h0|Vt#4IJt3oS5mNV_P{qy2K6%(~?2Wn>Yo7Z5~4dEM;- zmIo+j(Us##xlGGCr9udTcr8{p6##pu4W1!N{mfR#@A^PfI3I66ACL>NL#m$i%X~jF zw)Cgm%?o%9uU`U;z1L3?-Vc0xzTYv%>U*kT1rEKDlP-MSrnVkO1QY2X@aW zc1n9~Sa~0q)*LP=`9s>-MaaDYnm!(ru3b9f=+FK0Eg(Sw56m`_cTxW$g^k@_Pf9G0 zXdW#$j|sc#rJ{}*-dv>%GHQ??!Q1ZQB6J5?L%}I%VretGMd{~01g7+MD@xDLZMI#b z#_F=sdl2UVP4@?{6UiI*-h9`|5FYZl@TUA-rcl=c53&jgP+izWdP#7Ik<&iW3V={& z8hGuS1kB_NFQ4-{dnGYcT*~@xYrttFjLmEe3%{2S7fp}{2}2;xc|A;H%{Al&bBqkkQy)LaWLGkCt} zwSFIn)Xm3avCY5=!8sYBr4;_#Bo=7{%vpej1dXqR_d}>zgi#b}#-;EW)$jnF!c_6m zDRN$3UMMHSFVW`^)qEdjM|92>si4jgX*1>TxeZF?PM`9cjT9BF*Rye)QoMo)BF;E@ zej2HVx_hNFK@E6VokybfvFPU>O<(KTc%gYh`+=JnjG$3j7bGQ3pgHWLKc%Ohf$V(~*9Wp8C;na9-&Vt^QQzix?elg@o0o9~GhEt#ot+mTbOOntlX7QZ?(HI-C zDs5phgr*D_{)-=2n9j-y zZ??X$C_uPse2cQAKl zXvuDZaj)8Kzwg#7c334jmo6c?#v%(p+P)ps1~x>~WjB+{K!cNy)uHk`K=!}|IRWCL zBHgeN<3E5pKp_-+6mY`zF#nOA8HCsE+0&=Wwcv|OWuw(tgsqW`Hb&FTjQ++&HX4jG zlJga0g+q>>o)b7VY5l%OKDZWV)?|hyAptM|U7XOx)7r zlYPKHn@s*Y`c4@beK+w|>#Z_`ty`PWsT#881Nck2jjOf|s{dG?CRk{rOI*lqV zGk;B$YXTKvw&7PWtpgq|#<7@7Ks4Ki(L@=y*L~orx-lR>jVyG+rHPULpHpb*A>j&e z@pG_4bhTtw7)Fm}`I#|^;;n5(1~;%JKzgRJnUe!HW1avBiPgiI$$Y{UCbelWUdt1e zWVsO-6(LjrjX~k?=3qSrP1rkGaiAA3cyXW?2S$+j!{ge`-ZX*zx&qX#54?m|TO=a4 zK7cS%5HvQ8yIoRz0#F@Hp*o`$&(xuOZyaPt7tJUt>VK*_rDCj(5p#t%Hz0YS3z-GB z0U%lp@E(+Dkwqy({3Jq*&gUTx2C$sSOF@8?S#QHs1tFS*q+13Y1fLOvV6RFg zOw?jA+cPJoeif3(*fuY zTM0dvm_)EFUYeORP6ojer26GZh!trE-9ix1?d#_U>o}@FL;)q4nhY_DwkKAipW_Mgv#%tCb)F7?6l6<*T9es=+|KB z6C&=*ZECK;mF3;MXq!x71r%2itcCMnrhZmHqe#XYdjcNiHqVia_vkF@KaU`h3}*I0 ztv%|4v$OO02yAlI7Nj%05>&u8`G>Iyh{%OW_{5Ku|xZ4MpmSYSGD?;uoyKrO-pv7y#;8m*tm^rg{97|~vm2}HZ_@Nk69^AF9e>XD-e zpf*PO`avH`m03x12>V(|O#Xoe%9WhrS&x(F$myK?^)K03J+BsXV)S@?z-LMgO;5{% zK>35~6mG*sOQ2&a^5W?3g!BEzwWFg~{Wo?2sf=PdaY8Qv-e@Q&m6QrhdR;m5fAy2> zrQ0sF{kY+zWJ97^asAgugEI~6b&aeOl&iC}iGQcjcti?Hb9zWZ#ry*LJB)#Buf|Gx zdRy1EFRX+IKu-9kElt+Fb_6pOt*#x+K(m+tM09Jo@!wzr+KhOf zKyk(fukSYOgZI0;IE5feZ<`Qb2`t0^{RDXUKv4XD7<=z{uG{v1ydp`m6Io^NM1`y} zGcvQYLqcRLBQmoxqr_#U?A2Q`vsWp~$jVGMWo7-2^R02+-_QN|JboUJ>yP`oFJ9+3 z&SO50=kZS)k*S}wXxE}Qr;Z!dErnR&Yry3c*fn#aj56yjWUpi|JF$%@ju3iC$50@J z+{~lAVvt5{JiK%E*E$}$^P4T$J6&=Bkm{IO%e@njybb^3NM5tOE2a}XxJv^&K&ad?tL z_21hfu|JderdgyH5NVTkHATFB9#8rEkxfT`y9xYO_Z^l)6~{BGg1VnGJcOc@B)0!O@fUBywR`ZOmJR_ zfWXnKc=fULY*Zd}SEi=t9f`p~{N}Z_jQw7V&w<(Qj7_ZX^k1vfgI>@BRx2Bu`jZSM z{r{oLf9sKBOY|k+Y>oxsD2-D7V17-0D+QRNM3uH2VdQ9`zz5(sDW)tXRdEY_Xe=F7 zu*heyuH?RI108Wo_3dYTgG7;EOMOU?oChA-2j zfh2y{>1!RRN`0U~+;dG=`8?*4su5450xKR9GuOZH^t|mIp=-v9L>s!FJ_%ymIa-N< zzCFwCRDqqx7!8<$Pk&88{>TLIC2slKHeIYU>(wDV3z{FbmlhCUafz=NejM!~)0`~9 zqPL^s1>zo|f;eyE|P^@{R@oO_7Q6iQfUF zVO?7SfL;OCyYKuzK9}fg@PH2E#os*w15=a|+D#DElsu?Bc<$g@I9nBeG@iry=7}mD z4@HYJMxAl|39gG)Zh-i;nk^Kdyl>N0a!OHZ%0>jTzZIww5JU=2fD z);&z?NvPC{K=_nJa=GtAzyTfLK!JX$oz+e$f&UYRK{N|WZw2xMSx|JRI`I7jxaR*q zcB+i`tYVrGid-6>dV71pz5}iStYo3V8;?E*ZdT-q3Yg9SMP59OEMb?y5%qy^Qt5FP ztg10+38?Xd{3i%@<0w__a(W}Was56}pco&hZF(@?mM@NlBSV>yh}d$G;CsU7|ymj|Z@sXq>g z9X~<(Z7;v0a0=H#LsOF_0BKXGq-D+9&A>yNhGIv~$LG)qDnK(ie#OGmQ%tsrWKD6S zK^vSPV7il%y3czd?h>I-Mt*6jD_nKJf@lLd4tACZ``4fjR=0jOY%(B`88WYGH&ON3 zVmkHVsDKv)vkD3ppI7g@uFMv9m}XO4{_E9L1UwP|cqTB=?6Aa0TkqIDJ0m$-9gjmY^cF5;;H%bs;i-ZtFTd@UvbSZJ`a5 zEnGNTpBDT9Ya|^B7x0dQdRAc#hQo__49+5AyKj~`C9&v3JUKFP@(5IkH{X=MhS;P) zlOX+HQY(#*lu=7S zkY`KJ_n3@{5k)ePE(7&o(FZ*6)1R_;=Z1HV(x^g;H!X#Wt%r6PWBcTs5ak`&R%_`K z@5JEceI6JHy-g2+|CPf`_aiU+Sz>c|t(s4tK6UHQbm-Q#91)Ob1Y?w811%-gW$fd? zrEwQBze}N%IP`D)vHyX=rekJ!TzWx=);ARc10W9|*^3jDtR^k4z-YzHG;i^i2s~!!$ z!C@u_oIFfF#$CTD^IJmpf{IQ>DGmDTASa5!bi-9SQx-yADD<-5sRFm@FxJrax9^42^Ypm*JQ}dfW6`qh2LPGOs}MRQxOqKjG7x%Rd~ zM8(th()u`F!*66l%lo&O{CpKxp38N|9D|yj_imn_>;QTF4|goYY*v2m1uJHxvR^+4)(``A`vw|;*?TsSd;8_Sf&*sChWs-C#|alkM|`p`{o@bL8JS1CBSp`pj}u%caerHYi(< z=rkhdUuOhlvI7hSCFDfpb#zii2V%-Yf-3eLATEtld?Qc@t+hC7dYT}Cb;eI!5=N3c zIu@_9oggbzvoS>VOR5uTFh0t*5+xIz2n)}bXc8Pb5}R331WvBrR~hoP=GU&i^XkEG z&ivG&QhqxzE`6(&*a=!hKxj;p`8H)h{$sS;ldaLTF5**rR}M{FW?SorF^dn05!F3# za#!wdGvGrmbn{Ku&lVLgUt5hu0M6Hw#P>j4vFtPdQJQk5^$t;(*ZweXwhlc}%K!cf z%)teuqEJbAE4hcnCS-eG`-=mHt;Iv95A2=k8OCL7W^Fu=FrX&!8buKx*vVJa_Oj|S zGX5U^P~~wjFKKRRxjjLm14;Hfcfh-7z4qvo80)iK!o;wmyj&|Y{KgC^B~Sr|vq}@X zeNLOj0OV%+LAWG@GKH;z{b9#lRHhw|f}_B(+4-pI>NU}BO8VtY7$GVH%FO2T)d{Gh zXe9rnz+8C)OftU>>>+q^ZfY9Bz}i$tt7Aitk7#55ySsQp5qu;HzoXIf2kQLW9wbL z*8|je4~Q2iNdD@(EfaC;$n{G%#5E$PKJz*R$}Sgp{I_Ta*r_VOxqy60Xi%o&InZv{ zmNA4O#kToGXZA~+2Q{d3FK7!aKe+r{#gHupX0zUS*|R5BrkFM7rxzBW5^xvN*qWNL zbM@MA&#yy1aCJnOcfqN;fS_tbg)fs}{q-nT>ezxk5> zXR-^7I2L0F<_${Zg_ifpBksz{1&$m}tDsE32MHK3SmL4KY)L+VihXEZk9`->Y^yk0 zCgbB-f>@4d2yqRliP7kcb0d!=V5V)WBID#er00)2NkWMwppnmLwlP)7T(~6>nsd#5 z1c8G45jrjqmm#XMWZ#t3b}95lP7Vcm+q%^VR@>ieXFEW$;Iq_MM~&1Tlen-lQhT(^ zxu6hWU~Rq`XW4vo^44|PS{EqM^IKfp|F72|2$8Fsl_SpolPFC%pK}X!e1TdMgOkyD zifFrNs3jpKICtW$TJY|NgXD6$Oy-DzCTT-5I}T=(gt9U+?0GD$Zum;}4rsJ89TI@H$+h(G`r55P2vQn?RJ}H%P$tU_%qa0 zcf-$65+Xp^8&mJPEne-*hj-0!8#Nl&^)q3*?!Y#chgCZ3IgPTfu zb!%5G$JPZBo5B8|zP*PN*wlatv4>bM{rdtf;Q|lmANhu>1uQuKN_GG129Hi&CWqb+ zW$B$KZucQ)Gq%eN7Ya|93M?7FfFP(7hn-}S}W+~xqnSfmo(;p zX^MawR^3VBJ`px8eh_kGG!Dk5{t%HWNM}PWsI08a6RGhN$Q6^e67Vieo_%=|(Ojy3 z$COr9KEDylbAH^?!1QVP_(IG^F@EGcyx>doBg~ zZnD40`@cKVA6-0ZR2!{l0yJKSAjB;Q{SZzkQg6H^WtyuHfWe)+O1(M+)gL~9VjvI) zD5jI3m|%{^;p&4AWYbJ*p%Aykh8q_S509()ST?{%pqCwfhG9nc=wPuz5$JueiwbYv zzkd%M&-}-fi*ByYjv2X698+SKn;Wk7Zi!-{E~89mFSLSmEhh!@U-inL0lDJr>^AoS z{ZNWAaOw*@vI<`R&5^Z$_Y55mx6U1VxNqM~uDtZ6tLQS8U?b9PiAQLusQ9iObfAC^ zc$Y?C|39O$^zo(aC~NSiSma-727LKEbv3vdJ4Yh2+?V_SIZ(cj+6#r+TDLzDJgx0$ z{Dv5ddVqOg-rm*azjopyLzwqEmQD z|7N`sq#I0=ADU{7>Yk`k(u6Tm&)7+ui10`w7qIzD*Mpq6tibmm+>0^HL%gwAh=IZb zx4O{Mcbpv8j;JH6c94#aI0ATY6(P_O;pLo!hN*ls*gj7^rG%zn3(wg;`65?v;t{K3Js$P7*~={y`4p5&M?UzqUrq zNj0jn(^Z?F9hR>fk1BgkYb3YM9u$-ryxl|>PjV1uTJ2yl7e&X1crOF?6DrUAK6`(E zpOkSe_?mn;l>=?R|NeO5@!wL@4;2n5$fLi{sjY&y+G`dO8`EAgsJlB8KrxP=Y00UlO@DKnl#w4WX2T;v( zJkJ<%A6Uoh%N z$Vq%AeHdy0O4xhXODW_46uf`k!*i&#E*xV96m#QA#y!|svjH?H0YTCdog8aWZeX2> zlFVt#zaRYg;e(IhTTY~N0w0V6ho>12XRjz}!_<_U8}eXFR4rx>NxV93sf@P@6mzEy zUZ2GWfa-KgpjSwOn(?1=q=91QmrCDs&>Q!I*rk36n=l9)jG9(l4W?uv01x@w^N5kLo=u#zhK|dS`HTz!c<_6l10{+*IR|ZEWW@a{ z%vblq76QVLGfN+nf)Zx?!3Q>6^l6?8@aXJ(rJ89d)K6&oDN|ZVD&2#`Azs;P5*~WAMkIfcYv~7vVs#8-rO|i!Qq6E7PCW7aww>T`iY& zc;>xw%i&?Bc&=CFv0)Y=<^p-WcA;K~JQ@}}7pmD*l1$5w`()X9Z}!LY9t4cno*wxH zDFka&E@|xhoff7XS^wi28H2US`0U>)E7lcx4av=oe5WKw8_(Dkf^QavRZ zfgX=h6#(447NG&XDIMnw62g=9@tN??|({e94I{~ zn71bilao9D1LW`k=W!Kzh?O-)M*iN{&Rj$6+1xq>`xuUOg7S=XM3n5v=OmNdpP#Fr z@3pnmw6-uDvH4I9JrtNG>Gu7tUCV>w7hzgL*A}4)HzuyS@3&4udH~&QWH~&CMLIcE z9>WSMN9U6#!tjK(uzm^rf6CC|HpF5L?&GMGXbA|pE4jahB;Nbij<9Gq>G{@G zlK2AC1_Gs?1lTjw-UoJ1{sI$T&V;VJg(yuxWCcVVf|xtBxeSH_Ss_hyDu(B!#g&HA zsukPhG-J7NS~L=6XX|T|_)@S6w{8*h%&3u8u$A|ZG=>I))P3mn!mOkkZmjb@fW~=( zq#puFkGBLMDC?XOnSI8?)la5OH(AXOQVM~%h&zTtO zvjnSX@=&<@Sd9-(2TV;zG6wx2UjS^``z+G=B}`{}Wk#_No-!EP~xNd}}=s^e&55X@uOu>+wq_Z41+wjb-a&~kt*r_k^!5lDN(7BD5;RDu(Zqa0c^u~%PKnjRh(Yh&4m83X$v)BqmCiN*8HYF< zP2dEtPJ7eFh8vJgZFmz(AknX0|7?Uh z-8K;4dH(pItfms~Cf*36Q@;aPIGCoqygb(gngW{#VMH4A$0NCE@--@CnTH}9O%g#2 zT*<~E4Q8Zm9l+y4zRAE5A6<13mUvZcI(q z>!C!o-TMx&Kya!Ydi#eBA;%V?3I0&5+XoWCB*0M%({4m54)jHM{YZ1;RDA|jD+Z-V z^yivc_8zFiIb7Cs7X>~=X0jJ~dGk|KHMjP1Sa1S`zl__Y&IEw&>&v~@Kz_&TA$JP3 ztQ=^5h&yUJp^|IleJ1JXf7=c%q`cL|S>iKFN=l&YklZHCkMjC3wKp4;i$XQ)H@8qb z;KJr0(mCW%a{}#Hl;Nx6t_gK1F(?rwk;JHB&*^FzE5%LILLF|(kOtGj^sIUsS%eS) zMI#LJ#Q=&D1p~k6T{$$twaCuPyJc$&-GmKQjsOHeUzAP*^cXOq3{huugDzTFHvlyh zNiMOw(a{u&a5<}X#22vD^eXtR>>$ebIkG%>C@!@A{-(V7&m(f!FWPR994H30 z^$xVDE4LV!3#d**?;R~IZM~Nh5?}N~xumRLG1J&@dMrX2hZP;1w3(S1(rcVSvD(mX zJ_|Dp|9*=PCdBRSPMs1f44GSpeRS)^9-lG8n@^$vYYZj}is)dG00GxkX3zZlJKz0J z`kS}Kjqp_UqZd62(=d3T`}g;j0DUBSiaiY~i^R{KL$V4TADp71F82PDQH_Ok%^Ipk zucGPW1?>zWP3er`o4o;peXtP<8JQuzx>J6|vO-0fD>}`?FfDkzq^lL0AZ%Zp)T;Uf zLsRd6#Wkk@YyXA<`U%Z`-4X}ZZCZ{N#&y}*_-gmo0II9unQDBBy1KgX{$182cKbjN z?nVm{`#8J0e&^YbJn@NizvI3XTDf}uYd@fz6Uv?fp_g)^P)pn)(+QKO4y_!>Gwt%_ zZ?eKCl$hdwi?#EIG_HbT-`iS91~>MeR5oZ26zAv`Ba*gPbwjYZA;_J*tOJM~uwOYl zzf8naq&h%O9H&zO0-BzF-N_$&b7jmU{wEvCT`OYO0IDf{7`5&(AYDXU-&%J<#AN{B z8%dNg(A5X;_rH9W&`0;Y-B1OXE@<%`O)AfQ@uKDP2xt@V#Jj^ry`ep!KQOpI_EZ4` z;U8>o-O7Ur#kps!vB%xYqRfk{3yz53(hzp{jg5`akBJc_;UeauVwG(@6%d?UrNsqx7<<#v>iw{w~B#d3@Bhb_j9Puur@)D ze1%z`LtZe^23MafD7N%im@v5QQ>c7s_}aPG8V$AT9b-}#qNY;8!D`_$tPA9Nu6AS* z2#OXl{fO2mVbH1TE#l0QKdCi@T)UU~o<~)PP(+JV;{Q-n0O}lY0J06^{1-n~S4|_D zE>B-K7Cj0s5Ip517`k0C{OS9g>rBn+n)du`hAz}Ht2om+=91eP`5@AIQW3WErMhoo$k%fxyd5o6mdL$-ph)jq&Kh9%e8cb@MO}^w0SSKPxX6IT1Fxofkj_ z06xl!k<}xh5Ac4w#{3s^MDuSrEyJ9 z^w?9cbq)_3LAGD8{Di;1KMXYD7_!|&q3eB-`B!Nu)WR9Jf?A#@j1V8O_nC8vyJmX& zseNq)LOIPDKI**%A#xHU%AWjhs;JByBA{ODsOjmOv$tXasRdfrb#>Dlo&_4!UyOZB9P23QLO-n7qQ@eG>!(S6<1_yJapy~Iwgb)TE zEbqA`&=hE06|z?R|3g64b##I%S^KIyMO;b)M*j2bWsYA*uecxso!&J(EMcYoF>Yt6 z1bhKGhB?|3C&=`x0qCH7!K!e#=K`Tu7@f#G=vNQGk>mz`t7E8oyIXQirop|tn*#vy z|J}q=9dJD2lAusa694Z{vmGwDarQM5tCn}T@Hm{%EEa6)4?fSTlC+Ep7~gjv*W}0X zh?t?Aoyo>EjZ9_o`~;ZpbYS%Z_%1MVy}-|MejOE>jydF_kN! z;Y#KDD(?Jzd(13B4zf^t8Je6vMoDQ1^BvuypMnk}{RYrOx`qZb+iwgi*%cLAsD?Zl z2ooc{hk%{|Y^u9eGcUPOZHnU`Q8nL&9484M2^DLqy}D% z+hhlT{N(pj82G}xpA~lm2NfJH2o5@Zk3U1I|FfwJ_2;>Kso8Ji<@ahr(dhL|dNk#x zXu`!$Ft#0$OCDnISVZgur_VsdbBkud8Fb<>G>I3wFVp?+Z$3|_^cI~0cI^i?6DevVZQ#$-5tMUDli2R9)MR^OO8}cYw zT*}!CcWoo^Lt?|sE2Dynl7=GWJ3Qjb;eQOAE9$o;J``g9oP04r4F!sf4v&O!DZ^wf zAL5wGnLK)tqxUka*5^~U_HpRKPEef!PhI*xEdm!p=@E+Vn|#lv(1YjaEr+%MI9&y( zphvUH*p@Nm&!E&1H0}{H!;q`bFcs{nQ|Bmv?)oX)KcP8cV5R!HyPt{f?|lwa$vt;0 z#~|ZQW|QR61fe#c3}Yz|k^c}K!L}>`Z9(UY9?6si;>_!_kA_dS8hlWl3Q(QWuj}yc zCw-$(wsV@|=aZlx<^+ok*R0OL|tmay;-THjU==tA&&O3h{8$YVnsj_qmf zYI@{&t&LfshZn1D_-1ltXE9LX8em%y*>1mfU?QK%D6nXHZjB`aAa=LKQxoWoY#RmX`!OkiYTSk#V(h>RC#p@JMlLo$Z5^)!4H#{>x8*=6v+bKyXV zbM#!w7*wpmop{$VzXjUU7&6=fmhYA~d}GC9dgs8vRDXN+B*`tc-{U}mn(1{^m=!bB z1|vJ**kOVdFe2*KfV zXE_np-P7}(KN77gX?kjk&xp_S>ib_84bP~!BlGheAW`uKpp(szPY-~CVP+v@(9f7P z-rkY>r{Xy{mk?_W0?g{P*V2)|rPFO-&p^5@^q=%Vl(Geq@#aG`1OgtVyEA-+~70#+M^@0ZhiG4E_%Kne^r4e+Pc zd9Do#o;~Zg85atLlqQUFK5~hBo5Ta&Mpt9i@8$8dM%5{jHXUzxbjEh1ku6p!?{^jC zNVqWKz6LVmT-eCK0NPYfdNq}-deUcj<71l-_Un7hK0lfG2UoH$nZ*@E1D52|8%=; zl5W8*Q|F28wqeiY+ec>Ke_!ziQU=-T>OSUhjxFa?nFnhgQD_ExI-_(5AjD ze2FEz9%un^o~ZN#)ne7w#9iL<*&+ZDGq_%px924nHmR*2i%2epDG;vJo81@;%==k2 zX|$S|on78oewqrVcxcG5{hkLvc0lQ*D(SFgP%f9by`xV(8|x=YtRSc573U^qav+p{ zFHes;J0&6U1wAO?1jvO~kOg=IfRZ;k)9lxc-Vpia`XaZa4|s$`A-x>8zEpzdfTLdg z@AHVP`gql10~9{i!Payn3R^?J>keB+eNrO7`83qNU}nrXqzad+Hs>ABY@Sn?6-!nb zV&w!$1pD}a`eDSLBcOha;8U>f%?ayekS8fOnBB_l9IG|`rXXrU_(x@a>g?d4KD#lTPSAO}q|8x82)yH-TzyyQ^nfNC zl{iMea}B;}p}NP-J-6ze<3XDQMI^ruVp1%6)gE7S{6$f#d?! zF{=_Gv5G6vBVWr_J?{-^r%Q3?Pvi6+4UQ$;rJSx(ojPjuwOHqHHhl-vuk_9&36%tO zVNppEm6wWU09z3d;l~O=eH%nB5<0l#(v-bT&fOY#wKCJgWO2*}v~eGhK1!!W+ujBP z2ONG9NUFaS!o2H_VF2jfs(iT$kX&&3S-__h+F2I{CJKHlbtkB~wLBYc3=Iy-09S&y z`=r)O`;p+x#N}rImEKzIm)HR;N&U`EbJt+QQf8tiHhGyZ#+0dGFNv1!Hm|GS68kT?c+?lsO^v_yM`) z9q4x4g=w}<;98ds>D?U*6XZ3j8inCj%rK-mda}dlpKKPzIK4XF*EgQJ`ELP>nPZOu zR<9Wtc(*sxkpehui`WN-;GWf36HGpM0e5mMCIt^P0NSx63g$ZVzXs-WJ$^6C(ezMa zMWXjm@F$`Lm414Q!sX0FImLr#xFxzWlzF-J#XP!Y`{&IIqj>i6Ht@U4DfQ()Y{T;@ z06ZRAcOP9hGnU>;ezfC(B_KGV5r0fOvkxZrGCqM|3F{!kMxB8cXcg)dZx1yB2SDlY zF6^_53KDa#YNn7rVN62$1dv7T_qNEUNP5j58N@AqG&-CMO_$kiXO%7kl}eoc%cC6} z(aDNx0UpnXg*We%hFb2L7RpX>Kfxe>Ap>V#jOJSx&b?V|y zY_#L5%>+xo4)=?BM;C>HPq4hYb0h>jjoaO$DlTy$d(kum0a}KiXzGj(GDGq*fC&pH z3&`Kq(Vtm79h6c~U=Kt{>tR+}V4c~!0siqV^Yr%(KXpV>MND_Wk6QHvgyAOrrO0Ek zhb~If@8ggD39M;tP27@CihHG@qqfgjnbYWqe}E46+O(EvamkK;>)CM^Ptvvi@wCoc z*9&#D#CW}uMlYV(@N=4)xXI!nzwxkySU1N>VatynP6grE`EV^Zg&RyKE+!1$(uD}$ z{vm2Lo+t#O9w?FA_}Icg#30~2{SjK5Mtd^)pw%f=2RvQqh}M7KH1m3QXA>bjV6nGg zHVt~EYj+I5{E(kl@j845e>O^y_YJeU1ERb6bC#9uOD!SkN>W5U7ulU?=S#ckI*DMh zg)0v1C3t}$TFeyFkwi6#++Be?syCub)^u{t?xi*%tc6^b%7}0tpl2FqB4DLzN!HMc zxOHBagO(`y&h(3Q87mifzU;uWP>x&$#SJ$-NUy-SkGs&$-F~mr9!f6Yt={c=GUWF* z+Q=6u2%^HGBgpKyd8@Y^a#;59@f-`N(aGy!SR7XmA(TtADGa!lyBjEy>l_P9;f}ku zNuHtT?<#-DcwUouKKrqov#0WBXKt;>f3JP0Thr~aH8`;&LZ?6^TLsWl0`i=4#wJ*k z{Rf%jBc8-EBP^w*qOe^Bn2{f_3o0yyVWkLWO>9L1bzbNb|!f+ zl#QIe`@7UZU?ya2YriYb(WJaLrvErBl_LMD>E@_Lo0nA&>*!=rNto<)U%#G7sy*OUMeiJAM=0PEu9lPok2MU-RnS)K}? z&A2JKOa^^$F3*sDyWF0^U%{lyG{;5R7W>zDbj-YUE6UcqdiBfRk}VYPH30pjA$UiS zj}NeT0(f-fV7_Cv1IuN4dpy$t1&nDRtTbWD7#WX>yv>E`T?DkjI(dYV06dJ{_&iox;kt{7Tf=b@GGn63{ z>B@B`=`Q|Ge3MEEMw;SmbL@YXdY#B;F3L+8210A?UUpg@ORVUGLLDhf1^^@%2t)S> ztRI*k$cGXeARS(EN$5RON%n%^k5M=l;a^Uyp!zg2eI5~+npe+S{5E~;wt$C-*gaJM zxO#>sY)04R@NEF#5dXjox`H?mcCwByCtZeYWDg^BR0g@&R z#s!E@paP&He!0FLx_KcBE0+VRK3DH0LBfkfsD6ET4%!VtaF)fAx*@E<8nI{^0F{B2 zy^#hKpYfD1~KkF#3dwy|(Xg(^ADJpdvuT^ch$&ecbX*ql1Dn++JCGScicvK43u1HdEm9hJc7RN`=tk40C55?-4xUT zU-JWi+Z(F=&`}#En-;H|1@L_627}s0Xw6k#5UU#><9M`D|K7x1(Oj6)PS%cVyZX7* zF1bTqTn$LQyf@m6ApACjW&43!ZFZh0ltz#!w8r^%W8#)|WHsQv8C`0X>nfeB0PjXux>&rQi3pV;c{FBz!I zZP)sRo@4l-;)>LO;>+@MI>>lN<&xWrawtU+wG2Eb9^2svsx;}B;EvN@Ar)==_{WK_ zeu$NAU50uM!!SFPj9u2XdU1+3DHRx?UVDc<(wIi@ zR=o}FbEq?!Uh-|hs=Pcx2N4*B1&hzj*js$*h@1N63#Y4-7pWzUt<$&bOv@0!Xiwc0 zN^j$-xW5Dp1uY+v7fX=L#ef)NMdcaDQ_=Cjw`qlzT<1%FL;`f)0190Yt1TF@U4Zqf03#x?gR9bDV zBsU3Pd@>UAh1Qd$QpN!}vcX7{wFp*@(5l}Yr7EF|6;=hOkzf5^%dHH^tk8p+3K137 z;-Lm&sfU)0VKe~riz7bn9fN#iKp`QXSe}6~tG9{5GYC>J*&HL1 zPWMFPuAC|W=l&QuKbb4;5nRH_%;iszW(b+MLhT_;aYxK`=E8uYe^+`XRDIO5*~2*x z-X{DU-b%~vh~JKJ{3ET4*&Zj=)a3laG6=oaBx zeGSdZ$*K1XMU>nZYmB{+BVNIEe}KrxAn5Lk0=3VIU?*Pk<0dwoxgo;o_z&0;^K`6i zO27a+Q{9(T9e4bpY_oUEDhLbhio*%X93bXS<~JwUc{&00BHx2YfWs+}`6?=gU4|5* zUeR?cgp%qTvl?{KAAEEF&>0+uPn{W=y{i~(8VP82h|jCgw>=|?=eso^)GjY2>WMVT zhy8n1rDd!Hl?#u4B*DNt*tdd*1E?Z#Fjaj~xp!k97;ohsS+?@ATwR2K(sq z&?H`KsB}RD0u6OxIgHQ5fXwT*5hNRc-+=^#uXd>NZrXlC%DYm=kagnNTd0nV z%)!a@LYqE*>_R8FQr=&pY%SzdXAcqj+Yk~S6B6toZ2fW}EXtn8+L9XDpr4rssr#eX1_`u>2 zN)crgJ1X-)^4^N0n+ACIS#-AnZBk`P1pNsfm(j1|mHHXAeSY zN+^BvgKbBAIVjVFH||5Oa_xHmSLEy!m^BgEBw<%0)h(|2J;o%C)9A22QGw1-%q8)_ z8k@Vp4W=1d5_M`BalqZs|IVav0DC~qDwE)sZ(3qQrkmJBN~Zz9U`hNUpl&E`pAv+V zn*`XoZqfA?xY%ckpaBDO!-Hhgw5*|D$&|wc^3|p+N}gpP>8ZaAiVql+moHbaMJ4wy zkS-{kbHo}&Kv}^xKPozn3w~loTdfhK+^Hxo$7c{Qae#LIGOv2WXddt@+;PO_L_XWP z7x;=RF(XNUJ#Spj` z#+x3MD4KB)S%*#e;0zF(@m6~rIj>^aS_Rq!&bpnu5%SmXi8z(6X0TA4xL#PnalhiI z&r*)^ndB$>GS_K#iMh{b69QsYdwfTgY_av7q0H9R^;jf@nk5S$UDlZ zrIK)wJT(0X>;ui(u(vnrx%qC`1Ke*Gn2tlb)CYi#gxZ4A49@h%p<}FBwU-In%K2Z3 zP@HHU1kKg3oB};^67q*EFc9+Og#OEE%*LJzBcNiahj5=mIfvla$8Gx@8c-GNaZ{Hb zFemOwu^^ISRQ^p`L#iK|5<{pTS{Cu+x-2yuH?uecC?V`Q>^(KWB7&|eraA!pJXCGv z|5BmHK-mED4#0k+boUgP$u6k|AxgZMuLy_8t*eJZlkaYNK;yYd3><&(4a7Nx`C6H0 z|LO~5)!-ZiVAtfpSj#Gy1IYtONlzU-Hksw1!u|sf8OCv2{7^aCkO{4A3b|OlD*qZA z5w;F%SN0##s#AHY&-dS*iVq32qhP_?Qqz0L@+%N@#8;}=F5XTw%`oy9qiDx2I0$#i zkzrxqRalnqKO_^VCetxDSS|?cup!HC25Z39f(YDjmfOuA*<$A0v62e-!H~DnmPG(> zd*;`2lssCFsfJHG_KUPSp$*dne?i#w4P87}f647K{Y&^h2`iV!j$h5too?l$S=Y4^0&=tU){@Dxzp_ZSEDqU z_pp1B{y03$5G=h&ba4Xeoie|V7Yr&SyruPHnz}%acNTVc_^|rjQhaAgrPrkjYU=~m z`ISUZ*gAxc`ivYhFiwPd1@Qv~04yXA+gEo@bN;aZ>Y=oM?E=A^=2#+HXAP|?@^->m zlx%>xd zFxAg3T5sgwQmClwfv6tzuL?9Dk2F=cf*M)elxPLeqFNGpz8|6!mT?!&h0+X^4o|>a zM7_0$(08@EXXP18IKaAf?o9g7F9L5f=bL}s2p}0oy7v`ZWJ4ws9>=;m`wxYAtwrEV z%`XWmns2Zt?`PzWlK{=({Oh5-{&@!Pbsfebo2+%@_eldCLkmW)43??Cr-?a%5-h?y z7RF$Wta-XPXO)4#6%uRkR1D zgC%bx^HFztm%Rs6_Xc2Dr+#!jLLeyz(WGvX;f;kuM6@-8&1UfYF>~JeilR@!!fJzq z%oHMJjNo+VDiQSWnel%ds>8e%v?}<0&B(BsSbT(w$3Ay<(Sfk6c&PP%yJ-%vq zm`DfeUfH58?)yNC(6<^TH&O3m^`iFPqXQUhQyoyJlwRE;i)GcXDEK!vj33Y z@*Pb!?R#>jp4VmkhHzwd{_|ZQ_ZQeD&%rM+4rdLCmj&RFfPCN7YS z$4yIQ1Sp5~35JOaphl9n0Wu5)H+4}pJ9tLgp#M$Zik&1 z3T_*-5Fyc`V5NS{N`|ok#%`0r!T<`tSvzu|KkbY2Q%E;rGyKgseULPkaK#Z3q+Wfd z;K=^t<{xo3-)5rte2l=8hvH|)$O5C8r}28@F5OOJ7v^d$S+?hm>n{uIS?hU5T|T_z zi8A{o`a*&Aj{TS~H~PX4;`IBzUY-iF-(GjN_BR!aAST9WvBbp&_iMzb>bA-@u6n#pRjf+xI_v^o6jc1tO99QRl;V_`RzPLgH%``ccQ*3YjNZgUlXA>) za`@ZSPy>g0@gJ`yR>0htCP8v3OyfKj7Ax(ZU0h5qv2qUB)xCu$j-pF6@ZLU(LZrhG zB0&m!a}61%yFiC-07mRCMMWMYS{C|Ci3Ls)Uw6f~fgTLRt-M3(*87Cho&LbxYprMF z;TRNE`W42>vbPV!T{iY){~=~|yUfY7DJaZ~NBjm^|J%#dAbxkwxLOmu10E}VCT?D5c;&(Fh%oJ z-EQr~T0?fb1Qnd~*4^BG_t_;tF5CgJc%!dKz(W}yLHG6)#&I+YQ;fjyk(;{M)*=%q zjFaV3#(f9xYD^#(?YA^E_x?N)!2A|NukT5m7F8flaYs*2#pavNVAHvgdmkDEH1WW! zeV+?*ycJlI!){=6xdoGxTOq_KUFNm*y1dqDOIGhmk$CXPi{e~W-UxaT$k7z2eZ4Hg zhL3K|hT6qnh}Y)+(?=_e#^oP4zgBq3tW;x6{$HyDrfhG2WDASVSZAo!1fbySk@<+o ztM$d4Ub3P)uWpzYYYU-`np zmHjM9D7=uEwwm*uSsiH!jQyWwx!&qD-m&se%P^~A!o;o{;Thrk8#WJuqO-Z%lGdpv zZs|o{J$vQVM*PPlD|$N8Jceq+ij(Ori#JbBms7>^_TMyXE7uk{KC@fb{c-0cU3{M* z#0<7yaZ}L2XC<4_5tttD!z5eIO59e1R7mC;@er_*@#ZJ{t-Rtf2Jhu@%5*tc% zm!INiWJ#@>seT%h8P_@N5$uU&mzwylU8t_=hW_z7HKtHr8vVWP=jFf8QZp^kk)GAO ztzvd4=v*n$g8S3th6o0pI=^Uh{qHy2f8Lxl-9CN(S2T54vaA-PtQKH|J01S`hoYRj z=$)kpkKg0 zx%3^|O3UH?%h~E?`oX*AC+YpG26ADDfbx<`znLy0JNcLmNKlMQT$>&ds^MNzFcGEEtG zv+&)I9T1>BP^jYNswh|D;U@Fe25Ur-CqRdBegMAgEVd*Yw0s4?(dm2tJKBh!PNB}orEZWhM@S_aUSZy;yyx8Av|_PWB? zHoj<{!EnGOjeTNavYPW~NG^kE%wT>-Wa{3|_q;A4x({R>XZpf^#;qitEx=Ie5B-*K zW=-!Vykj;@GSqk>a`vTXhdAl_`LZj#&N&vk7>nH8paict@nj5_%?t%d**DW~L2<}JvxLQS? zjCu1_Dy6baAKGMtqjnqh)?ZG$%+R>k5gfFxx#50CdMe#xYdXE6mO`QFyiyGBEtV-V z<5VY`I_Zr?5LtMZ)sMi711p&WdZL6=7t@dnBNLP0DeR=Gy)E(Kv1)ailCC>x3*S~;guoHzT>8&&;FyJ z?h3>xL{0oi;vVywuvS*ys)*4iIJ(vPMxbn6Jlap zGmoYk45ykYtHNY3{8sStk3z>vFTb$od#MXw)x3gS4RrjPEk!)HV&6^eTQF1;FvP}h z$?Y)CdbMNKk<+sE7`)rRl0i-Pup}B1+}UG2}K=BFxW$aq0C_d zC|yBC_dr390lf0y$AESksSAWWF60WZPuP_Ghw0xZEb>9V_HN*#qFl=or^3*fzV6c? zvfMY!-%}8XC6_}Ghy3~sfeT;62aFjTL&F8B=*(g>u^MZJi#C@{GNr#z`hg7>MaFk+ ztLrw{O^N;GnMgTq=ynRFI%eGrprQZkUcfa7;EZB1Mr^<(vHM-3SF{Y`%3Wi-ERRzZcTQ0u zyZQ)8OGIkI0~agXyy9G=m~dO2_pSeMP~72lZ6i6bx!b>ad|hb%=g@94lNFO@q&bHR z?Lh_+jQn-sDrro#j*F@O5=)#J7nR;cRf1IQm6C&MyvG_&@}^9hjyk-0?!5ofVNH(x zK8mV}Gg+B2S;zG@O2oXkJ(M>lzGD6voBWZYdO+dw?DyT&?Hgj>pKf@$y0}`L6WP2Y zK13X}w)wQ}ou?Q>M~rQR!0ok-D;wPLH=SKE_O8Wi+~MbUZmb!_Hp@L15A{2*cZ@vu z2_^iaFkZ4G_vCiM<$~%TbMdiBMsaqOU+9NxXp8v6QcaixhdEllbZKCuzpZ%;BfCAPH$`FD3Q z9Lcrh^_~&RkK*+&8@|2MB9hfyCYKZz+|6TE`1~_tLDAf8)_L)piWvOrr{(2+cPZs) zsulb;?aqG)SM|KH6}Z@t~$vF3#d%7SDmUNiG>pFOSb6WEyV*%T@I0?&KPtZ>)Sk0=Lk=1ZKRBcWe$ zacq*Fd1iWI!`(>56}G@>Zs^J~d4%8fO;#?xlD?2Uh)wZ(9bT&C`7eDsH^hqJFE!kj zHdsct#m;t@H2(Eg*E@|D!RSA;AGw;6f={^b-bWF~$aye$p2Cw;p+!@K&E`#z-L=XhMV!rO3e zO1L7+y+UcU>g*!-^6~TAH=ovxGthpGp!-@9$`oI|Yu9G^n$)gT-89u%QIDJ6CDB{n zZl~CzZJ&An7~0PLPKU6c(lcqM*o~XWr)=5{QCyIW-u*T=86MnyrJ=-TuIU0i*VfLw za>?)R3FXEbRdmIj-!E)f>|b4{R3<~ec{Vxv1MZRHG7u7U057Dy-~=iRC%LF(jQ8EU z(HBzlaU$6zN#P1SZU2BHnFL4S-|tKBpPjXVK?I3|_eB@nJE9p+UKM;$qiPG##evSw ztYb6vPXVg5en?{7r+t51^Rp|Z)-x>gAG^D^A<-*6fHYk{cPA4v*8h*K?||oe|NfU!MkQHE zvdI?NqUzwmE&+|Ozg&H5a%5r^!hSO%8jvCH3P4b35UeT7tUeVDB@Cowib!b9P_UpJsN#pqy zGFc8WTgb1vJB`_cWAAiRD2Mmi2f^ zC=D{yTh@06@6boezDpOfqimx&Eom&Ep?$(!bcf~X=*UffpI&bAqi^v)4ov_KeID)5 zOuW~xv&}jlzkK}JCB&wqs|lOecnx#Gs4)xgvJd{oC)N~Z zCd@(;JEDG}O`WIh>+Px{UR5ZXGxzUM%;p-zA6SnQ;_(#g-*vJ-%ON}@W#uTX$Q~T? zu2(IfVS@3}Y#1K*?t$}j)k)D={@e(|z7IR5Cg|g@B-Ea|R&RJBjV<*RI0PPq`*b;X zHwh*69a|-J+O-Z;}IebGTS|cs$j7OK3GX#OHY!_U06nlp;&96=3>v{V?cB z90fhZrxg|08x%$zA88l)?LL-zka{>X>Uk}5?IBUxM~``0f!flPAi!9v+) z6b2j-vv>NX(4p=vD|@M#NoeJ{*kC9uD$3#TI2CR`bWd+xM=@KPl)G;gv>u}oBhcPz z>^!}aH@Pbxx>C+%l)4>i+gcj_y|Rj6X653XDzi-?GlOnPN?me{e@$U3ks5e1;@z$E zf!C8I_V-F8_6cTOBAuuUugI_AN9ATC$GiH_~+F^P#K!}uDYV>0~tgj8k= z{|3Q@tX9~=q^GM}#1;PmJfUJ1WCI}rHKA}3{Ue(tv~TCa#31;#_n~i39S>aXz-f7I z*6WvE|2m*6UbUj0kC!cEH#Lh_2_TeS=bc}k4KBi!`G8>nbRE9*uK32y7pf{9cLeDn%Pj>s>RNk5w~>2_v8LEpD*I(IHQ z`9%s1c-$dY{~yHV>&L5$`tTqt91TX8;{_e%+P|L!G@`n5ob@&KX$^!M(L+L5m#+|V z&ns;95P%$(8CAJBJvitqR8-`MG$Bn_USLZaPt(eCH(E55hF2)?w^K)dtj$R3&KvA6 zBw7-$Qo%A;C?l2iz_Rf^vZST|zs_qW{owWFdue+m_co5#a>(Wi*OLmyevtm&VZ`6g zl48PH^j(guTJDncdu(w6ZKWt%2-I-?$X_+Nmy2Jp^k-YUk%adD+0cd+Y(XE0$TtdC zNWA`-^Y|wpHA#s-pvxyFIvTV^!Q8IFaMhJ8F6yx)gzKydIGC2!6^8JvJkhO=h(bNr zu#(x~G5z|_Px#OgvRJs%o6)q_A5^K$5cJ~K2~ClLYftI6a@?!m|0MON&P>RvM%Uw$ z?!$JT`p@vD*#cJ`$DCPJ!ftV^eW43i!y~pH%s@N}a@7xqxC6e*d{Qq9d8V|ZI5Vg0 z?Itm`W9xqE1dpyiKAVEzP!}B^v;4m4Z86J8`|gilD!*4zQ!aQm@tl{Z5si_&u(R;= zptZzA(-qRv(HZYOU({2&=@Z;dWl5{$=Euv6;GDz5{vQw{t6un37cy8aI>gU)jf}9R zuTp^)3-)1!*HRi2NE&A_bGS6g!(xjp7z@uo7ssRYyq6^Y?$(yYpZJf%0%-LEgne*4-Ak$lWu$UL=S6zI{8e3*KZHc_(MCpj(yoLCq$L}pc+(P?3 ze8R7Wfsv7sfnf?CK2 zv>>E{e^M`EYXB@)4+3deNnxQSmZ072k}awMI@Poek5BX?k&2=YK_N$x%IgS)jM#!7 zllyN9wu=&nR_k4PeD6`*WL4U$mG8CgmkqCAb;YdItDdO8EKMWZezRfgn;1_&%Bd*p zKr=C;gKc<^+lE5v^^OGAu{kS0UT|XxBG=RE$Z^Me9-MLBhM<3H%5-Do z6gM~b3IPUHKtYE9>{8=cQ}{oRnF485X-cxml#4~{UB!B@o{*3b2rG8JJ;kp&r|}ed zL}WyBYs%dp}Us3YS%0AHrTuY2w?%{ztP1yKf*y3>ljqG;V;4wNt3=cm0cEv(=tR=Y z#cPgAym_^|ZUYV(+^Gd(gHop-hD@Yl7gbI?oBsux){^{Rt~oatdri6euEWKgTDgYE zgX|9G#&>F}4a1#-Zgni4Vhlllyp8A==Xo))dNCX40~VwGUOUewjs4V&gMDeElHZ}( zJ&l5k{Il*JnD2F;Vb>rAV>-)Pp`$^5n|_9S#pelPq&4Yvmym~~JMJDd9Y&2Q-h%qx z0++KgCX<@j$7-qRvce5d%&;Fc!x0SO#kk>Wp)7>0gKPfZqj(#RVor`?`vii1a$)V+ zmN*VvkL&_N6q)2=ez%av>x|my>EpYH1#T6o*L!`vTaC+w?$hVb5;ivR#c31munRB) z>*cw_G$PaJ*5OS=;J?Y=esFD;ylN%)ZPb=)eT;1M+Xm`}tO77SZ0LnA+^F||A1Vo!#Vd`Ugd%RV%rSd6NgEc9UiaMnKy-%M0C8;CGf6s@Wo`y3RO+S%6TaZBpWBi0HKkc+TRe{HasvPEvsmcWfnXmc$)BL1Q zSNH-~{clbi=_GEf2MIZ~ggZXJH0xj0UJ6*Qe^Q2ysol%xu93x?tl^B~PwEnXKWeq^ zp7okGlB=BDt;|JTQaM#~WB$u+LEfwklQ%~OBhorSqP-vCIPn>0?gWNR(bm@1FgZ0( zq$=m1;?+Ba2PxWvF$oC??e}@%>Y}ZucnVtWE}6$R7YAsk#bjs!ztJO`yn1`d3p?XJ ztOC5BL_?e#cc8S(F5)3}nxE%FZQL~qYkFgPM7u=pw0VbLz&m($m*YTn-s5RFb#9dJ zDeefwWss*4pdwe-&N@hUr_Ed=(mi3$bkIDwKu(wDZoqJ%RUOxy3A22tFFH8m&cIKi z12%X0EiIBCPfk3ZPpTwPCDg`^L~|$vp}nv6Z^obzH!<}Of2s(O>zU$t__N8kEHNvYnW2!;#3WQFz1W!`SWR? z(O62v%;%W0vQ`+<%|++l&(1qTW6#O6Gn_jy077^0Zx+g{aEOARcnl7?+Hv zvdgcN0wWom%Ig(m3iGX<mEr~Ir4QWgQ;p$?9k)WyRDp*Ta(9|x)!vfD>_e)_7HKN&pOZj}0Vc7|i+}1n96oODu+4l!Sb-XGF;Nnp!WzVx71#xG5Z)}2@w|AU zA8!FTI11#?c%2ILIM^AB61Wk%3l>phaELFinov^fD!7~AA~l1NilcX8gC<-7NINH} z-l*sjw23zEP0E>UJzBH_5a33jy{(;P{$qvh5RG{URxzzmt`*pX$}rL6YYVP>uA_ z!g5eTpvz76hAlU-37o^foHD8sSF}Ph1^vQ1S~O2$)O4bG=|6ajx&4UV%0sTIODSxy zh6|cHhZaQl(hukkh*K&neFp#m?}Q;NN$?G9M(0tp|3|9gsb~9teSu1M~gjGh)l4U8JIxaYrJ= zEhR<8Vt;=4&vkEvcVbpjRt}2GIRn|2$?>`-lx|#);fmgJh4tGye8UeuK|{inRR+(m zCfF5thJn)6cBCK=C$#GRx&nn;LhG^6*~I<1M6T$C!XgqU*gdfYyD@IeV9+0dC71L` zedKrw7Y5HZC5p{ye;_uPsSsnhj3goNNd?_%Qsl%;n-pka?d;aFS19ZgHG7PXi1rda zTq|#}6UpZcZ;G$-5tmUX3(jHf@2lDs_Qda5Sg1Tz zP*7-0e45cBx+E+qqxh%?q(0}_A3Y#cUOd7A5KJZ?}UnT&XwICe)X}rEleW14*U#lPPN`rXW$zN9_ObJjy)no9?r~sc!!xcx24>YDwe<8H zw%hOLd*OEo>w_o2p?3Ui8+LW8RP%&9o_;3cu_dwO#WZp>6}YstcIf%dnk20TCn6(C zh^$RbCCV@{fG9853)~mkhkRE7Rkll(AkdF3brK6w=ZRY?MbPwDAiykGRU#luevOw` zn8V_j8eH58kxa3sa z6n>p`+Gqfc7$JsMGr4JSq6oBk0q_-BWozc3F1h$C+`7wr(2QnE<2qMe8p!P8pmJl1 zZsZXy`&qh8lJ#^x?Tn0Sq?mtA0c)x;tkmno!3eg5fnG1C6a`3=f08;gixIDpQ6|2I zn4vx}jrKrggh(K43kGv7tW%siZF5UcuN=0oGtDyH+PH0Oc{)<;9W1yQeb}WqV1cFD zHw7bdA)^^Lh`gvr{zVW55?U?8!VZL7n8A=;S3X!%M(}f)zYyG;;tp*U)3di&kL-QB zVJp_OL22OwjL=s?OTu2JMF9HRXk6VDbPrJ)D|DO zs#kSim(_N9Xikq`a(1(g$C5;Jp8v;LCqFvksKk(nORefBBF&hwV&mf@E@M1iyGTJ1 zF}Y9Uwx#u#O!R9^nG{~+cbk^?PJY+Gs-+1mratg7bSh}LHznjaA0C&`2J25#Bhw!Y zJof@wlIp&7vBPY;0z+8*9jePXnx#-|l=kel%S;L8~TU@Rlk~o-Be?k z;0Z;l$I>w@GC-CsK-nWuMtx;fC3^EtMWda_Bzck_bY)3_3B?6cI~&+F=#JJRnZI-Z z!N97GYHxvawH+zb*f(~ZY77DH<|f0X6aYLh+1N=Q0YpH`(C5#ekxnu4j=n>m^e~g* z^mcW<$tnM!rWNI~_Ep+!{Z`mb-*DFB>4_PG&JpxmNnNAKvo2K4d-7<5CNz5**9iSN z>*u!PL>C>USia8@kqo|)O`T0Qt2>FOb|P|`9c$tH_h98?7)(5HXZrP-=Nt#k&3Y%& z;?qOpe9xhh2%e$4>Uz+PEg||Wv7kwyqV<~rL1B4Qmr=WRj!7)D<_LE+jsR-0ggdaY z8MeMk?4PThX^Vwz&1Pqxz_vg|P#Z^#WCf<%M`t365SxI&S!JOjb_batWm=+Er1a#-?@Bp*T$OZW7`nQ&rPi=D;G>#n zw8A4v?&y9?bhw8=YDd_%dogng-vX47&X)6&zYX)$hG1V%dR z%StZmpW4;8P3zLEVf2Ekg^4BvpJ}84aufWCm;fDySsi_?O4FkwnoMz-NBzEliX@WF zp?d2^`V8AtS6wjrT^O!}Mj>(6haYKB`7$O1H_;9tTdD75b0FQw>%YI@nf`M|WE-O8 zEJrz3Up7@(2+;}iCqK<4@WWRDA6Xs7WG67-jpCl}3J+YNu)Z|no- zE;9-EziBl2M@h+1_%EN~dgEy+sc|gr9<3I<0FB%KJbW7DAYh^dSYl!RMoZ2)vi2#y zNdM?4`};c&KAqvaB=}I~|0QweQ4me0OC$UFwj&(b?QHr;7J?NXYJ z3aj_#j@3M!kdrt9N0C0EF{U#@<{3^#gbz+lh5>J_nJd|C~Njdb%XBF`E z$G(61FQ!tXDC;!AjO@$?{ihiV*_&kSt@a*Bs`;OXg*&YT=wo3+tj@esWH+dzmV!>e zoVCV#-EAQj0v3QqcMf(t4v@}s#JA7!TGiW(vj~$L?A#Jna?gr$88|kBDt8@*pyZ?U zT2W_LmC*RI>GZQ?L93^F&OpN z-_Pu4Jvv!LZElD)M%gp%z{EDb(RqV z0e~Hhb2(@@!R)n_%k}{8esazme_<8*DH_}I%HXnV3V8{8-L(2EF z+TANQXX@jDIe@z%7{a7gj#7nZkKMj-h)a2^@s+IiydUVH1FkQ^wDfUwYT*a+)V2jb z2-J)=NIg&-yIDT?qTl(eC&?{wOn&h;Y%Qz-7p$3Zot>`e|^tLiCz)eMsBE2kSfa% z^!wnEw!?yq?X@`=9gW_262_>Uh2N1ViuyGnIj6gB`qf#M{2b%JU`0v}t}rakn%6cJ zRFGwi65G+j{}WtrUQS1aTjH*|Nf>Z`Ks~;fgLJAgRA=yBsd_d8++n6c^JdrHym@2K z#S3kM0R+xDGhT)DAP>RA8d)zEmXxf@ur38B;e_n`gnhq|SS z${C*Ao?hc&P=-_-?EQ#pdUGYouLerWDT(LjkuGR<;A)XX{R&^Y=aD&-ojeW7PB?pk z2!=#gS^lzPoKdism`lXu?lW7u>7Y6!jdhYEl$ZV{=RQ$y}1~|LbM<>bk{e8=WVv-+y zsvo)NvZ$={I~fuG>=wGe#~AX!V>D&eEAQo2=pO74GA@iw^@9&vv^+#jL~dTWy^U+> z4M*qvdL3SKw%HeBJ5sOf@TN^nu!JvZI#xZL3q7r$W2)mUJJcDng?-!Dm`bm|!K8#G z@U0k!1xws%%G#zdMqn?5czEc=*|Cc1nujmQR7?77a6=7Ta%#< z)8H&(9|TS9hi_p@DZcxVXfN4SAC`f}4#`kSUb}X!v8kUbtZ5i^u*Vo`373djo;5Rk zn!)kGZS($Iz~}z_Pb&#Ov-W?zAaZV!H`Fy6dkw(?t!U^isd7XsuINVLVh-{G3=uNT2_I;bMi==}krnP@Gw(1g&)LwWfeK?JI+*=qVf!-tR*@`n8LO*a zZC|?roQw4^MVV zeOGRj98c@riE^K8s-qj)F7-*BkFp71q73&vLB0thyUS=o3;6%|^}_a4#+5cz_?YDw zm-LkKu>uN(t17hJuI6Ed9EP_d^RQWML%d}pL?xsnpF|b1QA7t}#tXY}jca&ty)o?6 z^qAUllhqqH{VfKIqO&HSoi>sJTooq38TJkjcge`+PgO?`V0tFWv(GAimB9@s$s+?Y zFj5PprM8lCQZthNR(p4E(E0qKC?GI8Iyy3vM1YVS=}^JEfogG>I&|AW;ThJN{}FCq z3Zf8VI8Jp8qL!`!h+K<@29et5Jn$xt3&n@!K*Tr7{c*~cija&ZWRa&jZsf#ZlP^u) z2hfsm0cpkN;_{|7etB}`;8-`+po{`2@GRlqGHCCgR`{kk99*apAxfg5hYnK}*Q;)K z$jECCej5mvS(+Qf9=XbN@2aSDBLYfXjUxR>+$Ynb~cvm__GBtg%<1 zh!4Twd1A+j;uk-gnCcSG}9K3I|bLg?GW#3inH&MmvB! zTCPoLB2%YGv`3+6xj$dr)g%+rec^T#YAY%-QZr|tVYy;=T2utB!;nMnh2aC9yw?Ox zhXft`#*aQuwEXXvi;Bq;W_X{r19G=h)5^!XA20uU1$nU>{(T6#n7Iz}6qAs`e0aZ% z6nB}Ay4iuRPTW_aTs^xmR<}5mHJTV|OY*v_3TjeW6`Mc&+g3An9^l|kUa5bgH!c~ND1-?fVqWyzD zB_+^oDFXFtWEa=uUAM-UKJU=8eSb^svGwx`hwIgg z{MD5|$1huumY$U-_AlXYH%j4)1e$-*j=_t(=jpp+q6~>H+PsqVd~byWEMwL6(k?EM zR#0^F_f%Ok-N;{TSGlT4!?+S%!qN2Po=N-kdgnW}=S+^_jgD$#-;Y<(N(FBBmL`-E zNt4SK=8G0BuOh-g6AsKSIQ1Eh6bXZV-H|`WXjd4j+Ei2dOF#CUel@jy@2VXt$~ttn z?$fLW*S$O-CRuI0gk4sq;9fVV*HRY__Nt@U4OA0h?W0VPWT$?FDZya|xbhL!XE065 zosSmyw?C+~CtPPS@l6zDZ&EioBdXF2WWXH~GB9(5v>WR9{e!fr}+M^okX#q=I2x9o)VJ@PG_M9$^T3#PKW3 zk%sGUhGlnHhU5ur=giLDqW0Xli&D}HLUYyQ_$bhN)EfK~@2B`tp?Pb~Z|6KwN$aaC z=@^zbHl2~6Q%3l+WZi#sX<-pSlbZkB4?|Q-Ul&DBjNW5iwJj5sA}BfsCKc4fJQLk- z-hZ?5!y~KO%vwwr_&C8%V!jqL$4NbVmwjlPUS+@E{(&!V z@>rkGsayCI7sa*iadkz$;9j*<{y~}Kwof46>d^!hTwL%~8*Z0O6CXjgX9J3NMp!lc zCNDpo%c6a7w&%Imt`=3(!34D$$TqtCJ7F7XdRkhFS}?5B{UHBws_So@dJfq^)k-uk zg@YxU!zVm?HMDr1c5F<35SQ_jo9qxx(PZ}1r-h{%_^HynrlE$BF_LrR5v>;+Qh{AV z6Xwh+`T9%cxvTO)hX#t3R!;_ z$=l6$_MddW{x^DMq}2rIEUBe2tS2G%@spg5d&%$^zTDsFQJiv_YnF$a$DPo<-qe)W z(IpQx9qtIe1pQ6{4y&Bd+`>$|#awF3J0~Zn>rigy!+QXnfOk-4 znSI7iP zH{UiTw!t>1?!w`9srl+2#`#s6tgAGah5-F`KQ1jJ;kmq?its>f)TXDpWn!aaKEnci zaH4o%R9B{CdAKbjQ`B%wUmAAK5dO}fTTi+so%Pv~@sqQx9zVf-VZV!XLSi;#Sv=Xi zDV*5_;aefc053n_s)#BqMZzbbX8}*H>l_w%G}kLq*b+Z%stNJn6cJ};ws@0fw26Bp z&oI|&J(yv`1dX&Wyz=*-;mshWTPEu`mI9sVH2MfYM@G5~*aaSa1SjQIV{s(-D5+s4KNn7!>z%h<-KxQNSF3M8v5PZ7U zt>=DSvHR*R3g;g6swr~1W%nEA)UUQJk%|#5i(z!{e!|sr>3MqnPua0o8WW?e8Va?x z(OFM@d)4YBV&x>=e+4t$CFn;-&Gnc9k>d&u-(}%e$ZV3-#ctZawSu%Sk^|~GJm#8YeQU- zX+bGQJnUmd@(59nSXY*V0s>4f-AR|94BdzFe8U4Ll4WJFVb^(ec_J0E)^mAu}X_9f9C{+A!< z26g5I^FYW{wUrFgllvRM{Fxd5_E8|2A-z2?Ifmbx2~fY zBl~1**83pdtN3cSe?@jKbgR?jYfr;k)JwmM!hLPw_dM$PJlUYuVq=&W+RvJNxxLNE zNz$W_D2@5=gxc(#*$Qj0+d|>@bcu-34^b<0w z@)v{R>-pRKFO5IZ_7|CL*GW*zqu*Xr_2q5rYDlfS8GggM80sRt^bH2q{KwY>2^@&Ai! zob<7oOR^e&qqrG!T9;SYZid&@xb*V%(R%GOXSFac>fF z?85sSua-H^x|U~hYfoNp^fvxeYPmJ`WMsxFa|=or#lk+4NPhTr1xo|l ztSQ((Ifl|=Beb}-=_f?}P>-RjV0B5-XWC~;m}F*5qqOfZ0cc!6RTpD^rZ zG}B1#j%$^;E@no^z4#&t$+oAwGc{0B7iHKQWJH}}%cg%R*+b$LaW{y&$=P+}iQ9Gs>uB7kA%&i6@V8>&{b^(dV#pmY{eyei6kBym zxoktFP8N9WO8w^%#yodTkMGN2idY`MDqMVC@@p4L8hb@t0U#SX)9LNf6Q6id?%Af_ zBWp<_m#M}p`Y9jf2ld$vE3VkEBkQkMni$_xU{bR8Sb4T2#Gn2_ZzJNh`e=L2!ora5 z40R(09*vIEip4#y{wMeN5^BsMqE1&()oz9GqG=HLG+uXcRh0lDhvg!wGxUwE^D zk?9V!{#jj?p#SI3Jonr0zkXGjJA-kf3F#=b#5c!vYdtp0^xuUQlA~v%5u!Z8aJ#c= zd;4V0B111yy==AF8dkb$%wP~t(^77|C>EPkvauPlGF;V-7RG(JGzC=gFw8KyfGptV zojWToMjc}jk;b}r*;0q5`6*WedLhlGi&~0FUb(k%C!j8tVz%QCY4t+(m52bfPMVmX3IGO!vCxA%A$S6wIeG#nuD2C?e{2D!3PLMpQzhaZI{4c=8b9Er zJ!=bKwlBRpi#TX3HJMWSS?qzc^PexuoOwkq%O28Ip9_D&a($W=Gc3eaR741)J0)P{Ev=OtEp z#u1F-?v)We@;}I^M`)^z5e$0~F|1xx;ntM7_`d!>UfA4X%6ojbIM;y*ZP)V!deFwp zh8Hvp|80gQiq%~ZNo|U|UN-Cq!%n=2hmm1U%~AuRi0mXx)>%MJ2eIY8tTHqUUoQPkzV}Q)(%thIf7{}U}l=a`p49M zWw>0v8?&WoR2e)1EjJ?o0m$&)p%Rna$da zf&DmJYqP*V5!r52CHA>b@h|NUJ`O*c24*4q01$E75#9 zb<&CPkF^=0T=WX!S|M#d5vl*%iYb{w&)B66N}rSg$-n0Ps{IA;N@^QKQ>6r9CL5n% zFMmgof%T zVkOw2%OeB0ym0EcWWCNmYN&p~SloPWXlk32H z1mcm{d?((ei+z{uD6yuMUCPn>3Xd1T4eH9Pi0`^YK+`}Eng+}L3&jp2=z^y3{_W&P zt2Zd^;~q2nV$Hu!3ZRQ^-k#W~(3iUO7SsZmMwT1|GW@jQv?N>{#XRcrd{%G6;2+nmvA&Y5!*bD`1vpIn+!j%|If zald=T7}Stl!eGBwad9b_tQD|^U9@$G+G(+$`ZyIXq*4!%_HXha{dX{!G^Iy)x}Zj( zR@I8epkROy$Q7k8yGSquiT%@6IInubylhqXnp)j6gt!O=+_O5vjkg&)X8LaA>)KZR ztr_iGCrGRy)TNaZ%{%0z!?b&$9Z9~tCA!>3&X~XBj3VtpaPDE%(e=Ay+m!?fnF7cJ z)mKSlIlJlFjm{ z*i$wZVq&OrCE^AUF+-47hmLOOO2dDu>rRt4F10vG`-(av0!&XL=mqUGXb5xYIY`RW zqf3MY%+K}m-`^DRxO~?$Kj_2F|8IJfAM~R)(Luf}_9OUOsu8xO*C~46KQv{ z-l(!xGbyN46Tz?<@-#^4VQN@|UxEnAR5jmvDzRU*_we3QRsG%`s*O~DcV8H0A%(p z*Msd~IOD=UUIwx%drW(Eb4D&p??F0yNQhGBAx;6v$Ir^PR&ccV%5o zm@rv7F5gXdRCCEJ)PE!Lbvr}bdvQz0r~`pNNCi236=#4gG#V9K_}#M^xI~0bu-LUU z>N>KdiOYE4iqOAkTGPycF9jj7cP2y*>JQbc*^xR?^?@GX51#w{ z%Y(WXoyPPAq)-VS=BHvAk#)p2kk|gPb}0f|z~uh)CQRO^bzXRRdDSo`Pa^;Z34MoO ziFVAx^oH1Th-Rx>ey}#=Hrn!k&WTUhIGmg5mFbq*jzoO-WW(WHjkbT_&%f-e^Nodx zjV7}u?@uf(e1+TazFXNjr<%UB1!oE2RsOGm^I(2c`?=SoI>eqQl6I+4go{ z^}C#2L{aZ_uqO?Akk5bNkLedXPgLeAPIT0Z%&(S&&GljnWU??_sk{6r?qGh0lQR-4 zW1ZE3b##hDex(U&pVKUs~E z5DRmJ5uEaei8o72x%!0()O4KG_8+UDO@dVa|F!ucpCh?qk#EZC6HL82x3tt&WzcT8 zA3+cFV64}}mBX`f_&GF*@Xz-m2|PV{6bYaf{Zqz>cy+wR6?T<@pn*O{=;icgfFA6p6!<`n+dqq6yN<&tZ(KDr5iU$p?S#BQfOGA*>s7j@Sp0`ieh$H zb@mJwM_JTw*X=jkuQI+`#=k#u^YqBKVO1T+3BTVrD&cBKMh0Bp9}Z;Gm@4PQ0{esR zRxiII>T5$r_IXL>o!9NOItW(1uCnxX#b35K{WBOQ{Hx0!)HGfHC1b^d9DyH^I@pIJ z%s6C<#Y74=IJ$f&Rz{=^|g&{Wqan-=3ef zPmccsZvQ}8|7&nC(7zyFe@I0bdRa*yb_(>c;c9^kn9zq=PGE^@uMDMEW5onLb{sK@78{pkW83WhW)>=C{ zT4au4{8UK?!KqTC#V6*lrk_OFoR46T6Sl4ESekdB_E&o>bf4X%hQ3_$?l`oM5m8{K z;xO4o*HyUBmJK+Fp3y25z4vyEVWrEcz1#!(FzI{$MDafU_NYifr>2VUqq7ThLGvcb zQrV8};O9E}e&!d0wrQ%DtsG}fI#o9DsuIis>&Pi)gZ@@JhpQMAQ>oKN2JC~NEsQj8 z5pxf7+g4MnpR;Kl$T;pJ*-^_D9VFQP%IS(DhKkXbgOL#rbqM>@FDtPZ3DBzvh`elm zAw3y?f}YuA3c1hm7e5(o_yK&19?Z zOrt?n)63~QO!5Xe8QfKZKW0xh86H2;YdpO@_1^=q@6xDB>a5!_B@I*CDY=KqJ9Yr> zHBgS@Pukbox1QlpJBdMM1(S!!u9*v((F!vlA#REMMwJUo5Ql854cM;fxSz}tmzHjT zPJ$_?H_ZO3&cG-r3R$cJ$6;%DR%8=yn}c%q4ziu*Yp*q;$`RiF{)WrN`_Vs?M!=-I zoveeDIURI?IIC$ro@Rzv?P);BuS>nR@oRXRKiBBDRN}*Rm4iK{Rimp1k=e7MpC8b370>i&z!q?^WfsZ_$=C9MtPT6CnN7Tjn$1(Em zxw;P8({{3jH9d54YVkdlw7#|`e6ZCK<#SKd$fz1Fb0#}UZ9P_H5NU93pvtTHS3y)| z1=3$E^5p?62b0K$qXu=Z-;L#mfJ740b~&UvgON`?tPO@_4s? zZMu$2;&Dv~;B$ZZugMpcHGgAWFk*#ibI=LLp>uv=LSlFj?Q1k$fldKjtre+@MO1_L zM)EJ6$4d_Ag;KD+Lf)KOyNDR3qZv(;Q+aJ|c1u4OqGLO5GXdH2kZr+1sx_QaBR#^5T=N+5_0os-IPOVF+ngmIx_d8s zIvpMybkXelKr{lW9;k+-6!{3|ZvRWaCL8GMC=HFO6>wi``f#)^@a z^ExN1(n}fx%>kFDuGF2rNKTHdSt-TaenOgIG6}FUwT<;BD-5UU!jz>;2fxmIg#+BH zE3okT0bE}T)MXK?B6m?7Y-GMqc2X0nGDYYnm)Q(aI69K$bTjn6)phKG#)1L#4+|PD zyD8|EqWjBmV_oAE!QemW&%(b(gw}ze#-2l`#m)4EvE_MP6hM4CCSCPOmD;hyKpqlX z=sTqGA^oD2?9TIknWxoZSR6rT{dyLG^I9g0=keh0L@~NC8Q4| z%Z^!YHSUEw*jV&A|L_p_?Ujk)pnQ{6ZyE`6PJ{Ush%bycz0fZRs%Hv6;-b?8gE&oz z(3Kdwm$DMBtdt5iStlA-{|e=Of3MHr8*M@N$;Ee9R2TSm#&m$YvRhC&X?SjY7lCL9 zH+j=|F0@=B>lPO-x(q<0Ja?L5I{9a*J z!^BW8;l5kD?`Ume@JV zyV>twPgQ|@vgOk2P{?wnt;F8UFe@^3)!yfy_TFytr2FkTd$}2!$Gu&l(*H5mmf2WF zBr{2_Q=F&*vNQ@&XB=+IXq{B)2V^IF-#yJ;^7_OVttF68LnG0jz#?sLAetI8BGg6=H z$ji&SlV)Q)_T%K^>+9=dWPIih!-sR88+3B%?R~cs##~n0_*VB7k(omV)bHo0{^1IJ zmI7ZP7{r8jY&!I1$M2V##TR={Dls^WAo~$vgdvm^IFvVop<~W`WgTCy3g@n{4*4`aUB*Qil zDM^hJR`t^>Fo}a*^A7Er{vrKFQw=y2b&cC~_ zzmxkZr6M+4ViHJ@ZXb9lx_mM}*W}5JFd<$KaTVFLTl{H1wV-=H%rx^{Hw;9*a}}Bm z%`(R@2b~d@L>fV>j5ws6$WiW2e!oi*63c6xoD9R2s<%$?f*C<1G1h>n+U!@k8==e2 zzSjy!D?N=~4GTjZM4ZvcY#aU58zsT{hWI#>bD3}%5g(8yPk7a`A2;M-f!^6-1-Y~q zncbs_{jdr%)XRsHzdmlDMo-QeL&k5mc4tL7!le2CLE1(S;-qB@R)+!|2JN6<5K#rH zEr;<>AAQbd#qxd&MHf+7mO*MmDTDV>>Q&qLnQe~zAwyZBvaeiV3C!`Tgbifbj?MUu zq^c(eGhy4DJ3af^wl&@j`wyO2vLM0O1^R29? zmv{#77lmx{#!ZI-hZSMzcDj?g55~deKOC!Eh*vK zS?1h&uk}bf;BVDrp86vlDT+^8s^M%E==S7%pcSY3(}Rs5cJ$P`>*Dy%>7cn$H8Dfn zw@l_%6zSK}~v^K#K^mTu0VzX9Q!I-dV?*8houcMPw zHdAxqF$@iHgEn478cmgmz+@#h(A=ck4iwP;7>Xm7`?w2bQ%uF88AmQm<@;IRQG_;M zYwKwcbOk)W>{?RnHyJqSJql{9rhmIFOe3E+V)Y!bW9TIJt9e1+%pyKawdMR}FXFBD z*t;uwkmD24i$N)&r9+iP!zs3_0~b9XkR#I6iy~sq%FncQg$r7oT;z)1vJKHumS$v{o_ZJtMJ%`4q!wWTt7(rb($g{E zCyV-1#Ux163?T8|tY@ zhnuk(x)+yo4D{6gQl4n1i&SRX$y@`(%;NY^LtZLCKNeW|+- zA_Mtzb0M~Odi(n`%9`Spv*F^CCQfs>1DDGM;|B4q*^8ST7t3Q}VuXHFs3|eO7&wkE z{9wqYB-4ytehl$IWcSj?tjmz@0uXj;=#jL6ffR&Ko@~vLwUHm5S~D0CKVU0Ym!=(h zAD3Iw0#2fbiEkYOu-_(a*N~pdRmk^tr1!t=oe_hAc>y_j}?>T2`=m z=l_aN&YjmVWYyEjTOsngNrvZYGzI2JCBx{fJ(BXkJ{v_{(6qI-^l@5QTc19_4u)C_ zbe=82=AS-&;yQ)#Slw;+SHmY^TdwS?sw$YAZNG9QDj^{Of$D;Juzny`=O!-laDQ?+ zF|S>E`s{az9Ug$ZszAFERT_B9Y<>Qq_0tsYpUrSamu5GS(N~ah!{#BmHQh1nY~D`= zGDoc<^zwj+=en-|;R?gLSRjZ;@K;=b%;{mgdnVV*fA^R$OwawnnJ}81Qh?3c>Y&3F zt&mjW=H}`OaMH{fX^KbVW89F-6!(yq_rJ8cs#E1IkV~O223Dy+I3zP|6hUARQP)k`&TJd*WznHPI=q1DR4boaGNn1=%j_ zsZjNc$174Cga?6+i83sAk?Uxgj>Y;gQi5!%5oOTR;qYRM67KmL45}OuPr*f%Qx7O>VO(gp<~V+%&I$Qh zSl*@su<9*wwk10jGH(6rk3J(8^clh{jfeUSb!T+Mo<f`@pQL^&**=sPjjD=od$GU9d_cCY;y{l(|Ed zZY9G@tZ^4L18&xvNl{$DNa=tzK(IOV(s%Lx0yFUd>vkT;Gg3#UGWtHp z!1%@7oQ2_36c_&Wwfi=b4ag{yIR15*dd2?t8ilLh`HhrpuVB(f65UNlAWjxDNCg%r z5uO|<0G&{n_qtqgLwr&)7^Bk<0#Sji8o{fW+tH5Ma9@kweMgcOPycIot*sSiVBf+x z?Eex^Fe{i}Soi_!T?K5YZr4UVfr}usvU+LZAU}uKdVg>G3{;T1E{bnUf7NTC_dT2q zCJDN}@v1l(qUC+%IOimV%hZ47xcS>JQ2+Xj5QP1cjb{f)YE}1?x243?N15fX99Ds_ zBWvYNK?GQdl^K3ievj?7RQV{=|JUA^zEjzLVQ(a*!SGPYOe9lMGE|Z&k<2oM$`BQq zDrGDhD49Yi5;B!BlCjZLDp8p$G?)|0P~P*}RL}D}-ap{|@cPivv2AKYr@ zAZS<~boJ_0=~u?c{gt$JUwD9a5!+I`Mt>S5HJDip0}9`NLJloGeFFoR4d_|36ZLcS zEm!Yhf%{VM`l4m!=wx}D{q>`(_wT>i@^kbRx~0S7oE%@h_8{#JCz1cP8L3`Iw*bYV6XK|t$^Dkv!bJAVnWhIBOjLe!zKaO0KznV54} z%UypCjWf5+Y$wb)wsEfr^+GxU(hMUE)?o@K%m-IbHZ?Z3d49U;8m^?a(2DVOV`G8$ z)Of+`3GxVzBjF%R%7eIC)B?L_ky8-Y){e|uedHL*V|jM+Ow8?{>G&=$BI@&XWz~fK ziTx9O>O{2xDhK^VL<#SvPPwU{HdS%MGwhJ6?0~ZIeHCOPI`%J*3xqF@;XBT zvH6Y}L>byTE*Sn$$N>(z;y~FUy>Vld*s8-04jf!u@o{kx8x3>8qAgdfv${loz|paH za4_l>ou~n1Ens7C@2Nv62?(dTEywes-;l;yncURELZ=faCZTgiR$aFIt9DCo2&r^J z92R_fuer`cksbVBAD_Yr)Hr{Af%sX1Ajri=g2^3VV^FMSZC@WB#_?=*Dq~I-1J7}5 zvL%J`qoSf<2d;QfYNR%A7B5NDGBRxUAQReR$_!z?=rk zglUy$z}$lGBXzs|L<*!-Z9K!;o9=mo83I9e=0+v45uFOl8NEV;&wg>dd>my?<``-X{2oE?MJ;zEltLTf3_4aA@@3 z#dS{Gk;Z=`?KZvbenZ|vC$Xl{B(Tc5b?epZ<5_wU2HU%+N3=3%R`n?$oDEnE7BC<( z=1q+y`vokq0O=O;1M&4j=pj*P75eye{CacA30;g~C9&%kSut!}w~oJaUS)$`m29)b zEj(JVOl(&qx3smjy?d9K_2b3s+j}xYW?Y4pRkJf6kAv!iL z`k;}F%cncp++Nf$FI1tYGwF88?O*9PuZ7n~*dxq?`$VAEw~glVN1>d5U-am8S@0d*=BS zv=%vc_BLhOwtq6Pvhtl8DB69%gAYdCA3*mQ$rA5CmiSiZZ|p5PMSN#tV;p=@|*DvFgq`L2nhftlAyTSoLnydr{ue~d^+|0W$k z5JO#-x7F1eDk`U+#v4Hf1*5s!o{Qgjc$VpG79A&Yc+T{R7vOz>PHc9IKf349N0e5? zHNsxLdSF+=5C09aldW7)! zlELGH*mjTAucldPBn6_RazJbgA}I-bW3kSPq!zd#k{;nweNbkd$C zb1Hk&(CrT*x@Us|IeU-Phlf<4RT!*68m#qZBWTE$8P^)~ zS|2!|aWqCqX5BiLUlMx&O1HXppKGhJ5IDP(n{gs0G%So|BAl`hvGZ=#$2xp6JeIv? zFCkihq4%~P%l2W?F;QRGza^ssp3dCd+_tOwW_r3qYvJLVP9Hd^lqvL=HW9C@^Utxy zm+#0Ckyl#z^ZCrgR?-1E#sl>il(Zxw&a%&nRe&eIs@#NRv=qza1v;fGzj+fkrK0i$+7%@h4B_m59Gn)gOkPfvUK`c^#EUI0}X1?U*I zJ+aWoI5s9zhK;bJoy(LC31s2n3=Uq4kB?lKsGMeGSK)7q0!{%`D&-&1Njg3>K^FCp z$OL-3FmY12rj@8&x&J==V;fvPee!Wq`gsT%{+jK_yF?F{Rb92Mi%swzH@&j?>F;*) z78k`G8k=)9jz=zuw!Mz1L-{a8 zz8Z}W>1Py<4YqxGb(3NKe47~h-iX}XbxopsqU!1U&1VDtP*7+bx|H)e%T!QSDuUmO+eG==-TBFvCnX$; zg$xBW?~6VLB6ZQ3$w*IcE^vt8YNk1jk!FYA=J0oWS~)m6wxHuad}~SLCCIGZd;cEE z5P0ubkFGNL{&+acOxJfr+e*ucOPe5M<2zO4yE@`5$A6yWsjkhj9cj+?E-gig3-|*+ zDmEvaDtlN28_4D#CIoBE-rJC(l^1Ry&Tfry+Wtb)K8OP{@)z3)mn~ZTkf9g}3gg(1 zHx<&Hq?H^p3$f}o;aak zL;n^$3AEC6GtmPH@bL0R?-1CF10UqGv@OFZ6DNLEl{;SoM1P!+QRq(JdT^|_iO7<9 z(LyIr^Ua&@dBhmS2oLVm{@LU9e9LM#zsM60IXlvBeZLz~WAPoLaq7ZM`G0HfI`Z`* zfXf2yYSu%c&K&)=<@9O`)@-P=^<{kVp;hP=ix$gUv(6ESm6j?M=2^4(3mGFY&q`Js zxA)s|^TmkbY1K(2x4+AyRx-L^n@7}rO};L$8P4c1maF(1qtZ8C zLrOwleXlSbo5tZ!<4Kaf+%d624l2^vm_Cn>0YhDu7bfdfOo_X4rstmk;xX!f29YsJqaDswsVojIz$?S z_a@24!Yq^%-u?S|Um1H-H3i1+oR;>C`P;Dw7_hGAjqN{+#?`APEKYpe6tds57OiNe zEXs_vYwPOS`h7YjuY{QJtb6;}Tou}bL6xE}9fmSlFQXhdr4pWO#or%j+>nkous4m3 zksHn$Pagbbqxyf{Zeq2l9omY|Z^#yjx@a)4;1}zTJ9QfCS*g3sxK@}q5lUF&QLb0w z;y8JDj9*=rUvM3xtSkNLTsx)HiMJTpb;REOQ-6P!_)<$fqGTcrhbPuJN`L# zwEykbMgtwtIm*yZ{ww$CSfHb8@6FpgdF=kCBNJTXb(mRIIwa#va-hpNl%f#z$<&_f z)5G$|Y6})7+{s%{KV{VU3&U%MZ13v@K4QaK)uZ{&X6$aaw@T8eSZI&uu7(>}s^Hk5 z3dhxJWi(={v`wqeA)~*OaB%cP$CS^2Zo9bie zSqpc128E9HNaU3Gn{?o?=w>G5R`gzx_>td!& ziCiq%lVv(*5WIMu{ilm#b+I1362Zth-d?D+K>#EBjyZIL<7YWd_WTVHRl=!g5( zwmuST)T~9?L9Cx4-W;Nj!7Eq#sAeAE4=^+aNCrD4LFYL4+dl;lk~uZFM-FIn!Ka5K zYNsVWA7?Aem>ROVr9LM1?IqEzAI*&eR9Ug->c}x`7iTnW2_M+Jaid*E z+}DbI`fCbKfqTPd^3LN+gOGz|;xCaUl0s2q)yP!;Uv?kT&B2WsS7KwOn^;6s^_5AJ zkQ$`TjRkpEtO&JRdvfB2Z%OUc8O=xrHS6TsZ{>mZXXBu#@$}iVnhw@DM8AVhQ=OmZ zndIAP2P&ra{P@}hU=f}j_Wa6vdz*DM3$(fK-n)0tW^EpvXpK2dRKD-bucS_im{)J! z?EbKo+rJYJ!`Ih$+YrmRftc)s^D=cuwy)M`1%uA~Jp%qjKB%&+&{U;g!M{dpq_6TX zFMaD5Io{Q)&SXVui&r{Yxu}TlpEw-cx zMiQ|pMQF8F`tGTN4J$BBr@50Sstv+Fo5Oe**rsBt@7(EvpVQV|XuGsQEb_twt(K?B z31B|bU!nUC)A7b@HR~-2tak@UF=k@kZEvlxq@<%uz7(ZB!s!*7i?VHV+dl-)>IY?hE7@eBNJyOBZNp-fvvdczetG^@8g! zChgSG$$Y$`rdK!9$XH6(Qf>2!tlV6ehi8`Lz82S?cSc{AMqNWRVpt*PKZh@*RIM=E zdJ0LpOup>MY)4qS4U-Dx@)zIJ8*-cDA*WQ=q&-bQG5Vs?53 zY7)}=sQFUYB4DQ3PV?PAaSy&P-k}Z_uN~pPgEL4U?!Rai9m-ID$bf}>*f2}8=r(yz z7K|Ptbh2-H`=dbcJM=E$O4}y&+yI=vruelNSb;ThZ}aVSe%zdF_BeWUDHD^9 zj!s>)|0RX_Ar~$Lc)hf@#8B)V+B?=Ys2+ar*oDm&CLt4#n)>0^LZTS=L?05^x&^*7 z-+gbARl5ltN}{_w@3sG5{9rjC$1Aw1Vfxe|i~G`xn)J+URm}GLu82vx-FYWv`+~2Z zDin5g#IZ8{I9fT{(>1c^bo!0HlU~6gp_m+GLLYYL!$^08j;47HZ9;*~n%r<6W5;2j z_Nn}6+ThA*dKJyM){KP{4% zXd&@3u1>sVqfPLkkLtb2Yo>On!Y@uuO$8sHj3(r>+Vv;H4B`pTC0NDBR}Xi-+z1((aKL|b(GGROu2-BZ{@>u+Z?P(2nZ|s{(8Ztw{3YE# zogR`fn(jG4+Q1cm4OlHSpiMja&zCZdi<&Jt7&s)@bmd{*MNaIU+Fh)Hkim zN)@lZq7OiYsS6{4-#8E#JZ7}^pA1{^YXPR+$2Qan(qaSI09W*e3K@tJQh=}T%;(Ps z*ncrzyL#2gsuY9hyX&?*)XhX+zEkk9-VP;>e#p{s-+5rQ$_B~MEX%UV!IGh9kM(zkUw6v_O$q(}rDu6C1 zfW`93NB3vlB=r6`v<@IR;A>{gK|*;CTDgqZC?kszZp`p62IHNs>1F&ZLhr^C-wcF& z+td_o-rd@I$R(a>GHNxy(Y1s<#~<&tJT`gs9@{4a{%dQ0=y!&%O8)%zc|W45voq`` z$KQxA>qhJ%tq&26^kf77>8?oB#b^Bmbq)6~@PB+XWpkr8@fd%%U{-SGT+7Jemq`8B zqqckZMWj@=%GlN@@u%M&GK*orAg33U)CIH6FST?B%iV-|IdH<((Mo zbv$WV_wvSe(DT-GZcRXHNa}Hw(!C{2Om&iBI@;RLkYlm67hB}Px95)I<(-Q9V2G{W z6%U8;w7a`|db(6Rm~n%wtn9jV*NyibJ9aEUXS!BT%==la3>-|f5v`%3M><(Nfe?u+ zJJt7?ra!cdBoi)SJTvRK|(`6ezT|k>)Ir(XvrPs4%5$9 z7?1`t_KgkMM_LZm5mLV3Gb*1_kx}}I*R+_PUhpKCZ6u-qRpf8Og`LnIFgwG%%(6n6 zM)h0c7U!gWK6{%V3hH6K=O-t4KZaRg4b-+e*dYtwm~J4X_{bJb^-W&SJ4SZDjzx#) zdi(n7B!-NqZEY6l zvum+CWHKGkJml>Qdhzz{UE8`SQP0p-8LyzqjrkpgUY;>Urk{}=Xv`VcKZzA&B`fF| zZt&j~jJ$SCzFxgK@zCJtWobj5j#YJh6(!4RtqO#8YK(QC4sjD{qpOTWxa!e4XuM?M zgx9vE!c@4j#^&-}4HYchj@o-je~e1$dZU@o6QqEqS9>0g!qHgXbKl{O+C#*+loaVg z@gnVEP_Eg&?a6^2->5kKee^K`f{6bAdKcq{CMvv9lZR&41)+HyPt;b+&EiA6yBOT*A-Ss9sjMCz_nxj~1USwDInPRh={v|A;qWv8}wpzrf6g&ZQb zIet4OADJ_c(5E)azj_RI+$$-8UxJBfT6?vorUpV6rbl{Gj3Z(v0hk*X3V1!XT+{er z5A5r;EhlZR(-|pocW!iQGqFhdf;}L6xWyeqyg8yFkH6qFqm=SFO}B3&xFn%$I?z+| zrXL3=*p^d-pn!vbLSGX@;dq)OM|3MPGV_fEqZ2}f!V=7k&mI?DkzQW9_r3qAy*zQz zDdUk5<=nS4S%I zkx%6cexCz9c0eNyO_`&|PSlbp_b={gCh||2!84bm8+7HSf;E5ING*4$WW@nW-qdUF z6JwwDDZn?c5uG}{ZLeMlszjwC5sWzBwTorZ+VDkI;telfh7DKEP+0W0UpsSVe)Hrv zRIhCtco^=$3J$X$V(A4=LJEqDi_21~80=rOs6+mZd$+5vlb4s4PI_`hVqE|1+AB63 z?4#E<@m+>MX2srzXP!J6_I>Vsai!*xKFP%71&clPXw(yWw+lNY03W_`DJ$Xl~}_X{jB5de4K%}E{o z07K1=d&AD_jjPXaMO7#nuLr_ew{D%BoXMn0g)55JvQBN)S|!t11>Rrxc@XMC#WL@j zUu0}toLJhhJ3@=RO+q^3MovIPk)GOTAjRU8&uTTs$#92)DoH)Zyd$l^nlGPo8}7CR ztSp{__rBY;bVB4DSESzKG>TxrftuI;TfRMA?;0ag@+U6QXnhboyBpnL8gsEB{*%a-X1{#mkZA0!JSUIJa1@H1Ypu}$i( zn6@NPTajm@D%s#Cgqn`j=;+)!KVA`^fcLH{E56 z{r0temKz!$FgA)~?bGyU)%(33M^YK3e6Q^KV$*2ZQ21_o;@e2N*1IW@hyM=LylRK< z-s$M@tD2x!)RYh#-gD7$6@ViAiXF2_=1n4g+OR(i41M!to5s1dpvyocJ~KT%jS~fz zi6G6&$|`HEi($e4+`VnlD;LH0 zatXp60lt?wDMipUmG$0aD6?JSqITXPKOszMaGi6WA9yZw^ImFbZ8d+9xv+_EZ$>th zH)6Oe;>KyKDis}tQ<{a2)Hl6ru#n>jq_Wt7Q|@_9xLOAqzbg_mdv~Kz{NU=GsQOW3 zZR9*Qp7!^r`SOX?WKQo;FZ=6zzYB#-H5#)}L^K8MEJ$srPi z+Qgk@0#<N~uZcaNG%wb$_Q|Bqns^_D&}M2;@Az>Gg>m>F!mT*%tZwxZ-yD_acm|>ACWVOl=*$+ZI zHT^H?Pk*G>T*J-1aU?SLr0sHRCx^@#DG7C<91SfJADAZ_7qw7mc{QTgcLbWgY)loo zVQE+^rpmGqi}Yi*4t7R%tNH;%LU~6Xa;#j5%5!uVx30XMogL!|iV28+GF*;iUjQos zxt`)#65|DMizu_T+9(9TUt^2FLPguilV#|K* z!eh0SjLS`Y_lxeYtuwsG7EW6GX7gJ5nd&PU`RSI|TYWNQ){?nCD&n7_t3x!O+^74J zB6pt?VC{V>AV#O83g7YOmiaLp|ch zbm^nkZf@6XHPGmoUd-@MB#WB$d4YqEg>2X(M1&H0z#ks<*6K^QH3`g?-oI8OOE9FFFtLz5lkZ%5&nuUXF8| zzHX5sP$9a^o-fkP$)9oz9bABN3r=nc)ql~IH4-ARn9yU<-9v4|CuxJIp1=#jQF*1} zUv}RGpR?5H1cAf?A3D>5PR^`Jl0lKGk51`5h=#`5mhH{Wo-;qc+dFe5ZN~V!qkXpm zw{(}?xUnB8lMrvE2WZe_TC$|($;w?&b1eJbAyzVP@woT_s~oHayO=Rjbv3LPA{DsP z!o->#KzP;CF2aPzk910EdeKMooVTxgQDW>)TZIPfD( z$9M9TE7$qvI~5O8s2XnmX}3J$mv5>+=_Rxv`BCXJmk`~D{*HMKE*N#lZPdD4V~rle zr|3=f-)uSPUV=`iH<$55iLk(Q#}Ihj76?kWN=flOn}CBELCsYYH+Aq35P4(G@3&-?goG(g; zj?wTHU=uCj+}Pi8r|<0dg}Ls7SPbPp`B`R7&oBdZ_~CV(tETyOOX$^8HXR>+ryTZ{ z31O6kd4(fp)^n8~7|qJr{-MT8+E3j6$Om@Mobp2A^swkw`5Ikfbx z%b8^(=7>63eLL>u6!^9j2`oq-E%n*kYHWVD@L5FljiqlK^)l&i1GkQ(sz|Ol4OFqA ztUM`7Y9`Cz-ZJ!jx`8|`Glnz}gfI@S-zX)Os0cD`X|G_JO3CrB`;Nv--=;^F#E@6r z{J!7~xXyo_C!rFelr!Q;<4C`^_%dsruud5Nt;USqH;~9bv~9mJkq-<$)got`9Nd_t z$r%-!70!pAAlK*rh-8DGbqoDjI5u!42f<2{a6NA$%^|b8sN=*z5T%~C?}*)B6@u#f zHe(|>1h%B(PmnJsxpAoE+BKf$4G+_^vv1O}Q}*3C+`3Wz<7C>wMli%Y`1L-&Y)uBv zt*G$DET45wq&R%Df11 z{gO)sd(%y?DK<1W7a!rBXL16zuyfC`_NI=G+l6mGeza>=?|O;Deqzi~M&jCt{u;>E z8ChAa?OV&`;nj6{r-?GqC9YYtpxOiYa5H5w)A!}n|VpgnN8Pr>| zw>SAkd;6Bnn>WkLr|A5bswC7#l ztEMKQv#!}-1R{&;v1jkZVIvWl476e|M*4Z@&f)L=T9`ejtO2z@@vG1Sn^;rDAw*V~ z|IzYRwN9u8mzP!M;l2LM(>&Z+S*HWKqZsTx6p`}b5UN} z_df0P4Cc^4Wo`1A(dRXM+4c4Hpu!v6+=Xd2BQ~!SOx znH1g)v$LP}5P_TdhU@MKR!in;42USxcNC&;^{LPE1J|Ap}_GY?29)@)ot5sAj$lxLnAMI!Bf8BvIG*}O_z>*rB}-O^y| zBX9?mPI`wb#E|FK3C$vsiyA-CmzQ``A6Wpj^o_66S{>icy&@yNf_A6grr-^N>*g~s z*pB@mmYh7Q4G5n&Hy#RoXv&YI+kGS1Brr(ridpuPRPz3+rOlBvlpZ4k1HrTV6R-+3 zU(0NA6<3L8qHTN6()1k{E?h8t|LQ^GckUG{VlYW*YcydC%sw|V)ehIgQ#CP+Ou7JSO?e0OJ-S23+pfy9KDBweSKgjfZCD( zB2>-INQH!q>@3M%O>w^)*hKnBoNL`A{S35Y&Alb9+p(#bmCsSRpVDzi7QNcZY^h4m zM~{S9RE7d@hK#u& zCXb7c-wb4hFwAA_5q(YhcGn|EboY#>eM$Xd6b_TtJd`Hc+c+XVnS}KD+-flb%WD(h&MjPO@Y$jv^$j?E&wgQ=9{NB4iqcEv(( zka|%=7!PpR$tjA?g5S){3}@^3wpBYZ1BZ|w-PXK7d0?nw#-~}GhN4xgFWvF_wJ^ia zl#SSV8#kuj-ig#&lTgr8E7L6VqFve>rj%=dAktoSA_MT$SYYCLJt}ALoef+||CrNu zkg@ZWPERKfo#CCmG&0sW1EHF5zP`R&-*g`VaeD1! zu{b99kqM3itdvj+6lz^BjH4hPrsDe`O)LWGf%otC%AAcVnQ<|&R}peRq8c-7Z`jFr zO+a>L&YlxW^0EV=CEl{r)E%^dN~iQez1TJND*{XTqx~^$tTcWFus+Q>drvDos=0q# z33=_9YuBRoi)1vR+G1~i^Uy!^8QIypAJ%?cK+!mJnt`cyuR=ATWjrMu>*)kgb~X77 za*pg;yLU%>!RXv#GT3e97!}zs_$X3(ddtn&fTya=cf1giBaxT=cO^lTVCGt4%K(z8CA_OudDfwP zHKzJ?kS+Fst=JQ`nS3+b<6?Jw5Fx`&*sNHKP*HO`3y@vg-LKnJ$;A1*ou|{Z77kpS z-FfLFgs*AB8dV|eh$BF*)DoLZ|Li9DVfNc_f*6(ZlrvEGJj@u-qmAuyTby4aihSrW z#ZT1{j{QcV4$}DXtPM^8>0Vx5$8)8{7dl6X2gc6y-7eYnEA-O6_)TsfFI2REv6$GP zH*Z{p&0nqB^>Je9gJZ3;4#?1rknhFM-@m_2zIk3T8s)p6ETANt+1uNDdzW!d1vLPg zY}_bZWo&r2|3*cS&$s;;PRV&wkD^gd=oe-3`mfF|*N6lSppx$Q@CdeQpkgdmqj>&Ds{Vss7wh{oI1I%q|FytZUvv*S=dt zwPh?6jS>O^TME)2>0|6&A+mHxq03h%H6ZJL`N!wAwtxmGS%xiHL;*Uivn7KPH41R&?`UfS3RJ)kVHh z;49$Dc6D{k^s)KLj-gZoFm9JGVx;2n-qHlP1irx=J|YuVEayt|n3xRCEbrEQMBG!2 z@U_@h0N3C91tVr8rXE&CCV0em3e4_lmlHjV>sF9!`SF(5GwFGO` z20n(~Cnx-9H^0CRgl)143N6U3i)GD2qNSq(8)gf|j}dApOXWitz6=dT|1)3UvUgBS zQvHKw<=p;Y;ma7;Vmhg%d213)zj^Hb-d&uXpn3TWbNQu_CK@u?wqT3opzgdV*XDcgZ=Ax6jPkg%!juXg&U=UX94Vj+>Q|rikfcyCFi##jN$>_3Mpta&lX?NNl$h zPe(xop$5iy)#Xb)G)L9r{%Ho=U>b@co5!iB8=lOyccXO&UG~+&LFL`qS6f-BRA?ct zWo)Dh|IkQpK3LXaD@Hq2y`*%R4kQ zbg6rdVDI!@?9Jlt?=#(7m9Sl!@{9 zS8Fi(0FGT_&NM%L`tKp=K-LWgKf%Eq`3TgAzC~u#EF5$!KY>HKZdSL86zK^Da z?j!K$bUDo>noRdWtw3;L#x@n*%|tuUY;Gb0fuhj?ZWH4hW}6nt7aTeL`}=z}pQ9~> zqQrqjQ7ejJunleUG!zq@!B0`tMJn&Kj5Yj zxn;P$0IG_eiRl>r{060OSOZ5`gA<1^fv}!t{^t2v4InIJ9t8MXIN`PsMR&lQXa6i90v{^+5w!3(_oZE<*7;f=pT=+#9i)_X|qFn*^j~U|>MCxa!Fh z;Na-q?~id_V<*w+78}toSl(D#V-Xdm5RI&e|1mB)r91M+hZBGDU)?-koE})NyFwFv z%KXU~q-tCi!n@UJM#~5nz(>7+<_niD)qSb5hQoASPEXNIM3Em+D!#nxXKJ++aL~Qw zxEZFBoy)Y&ScQ7Coy}Wy+0q9q10)5;*`=(-6eSq|R1-YBc-F-TX?nJ^pj(YUnFNdj zAkA7L|DnZ;Z)2B1@& z*9M6K2NWb-oupt4A`?_9fg7m1N@{vI%o>nf^TF0>JVd2^WOSs+YL5;CZlMvOG&=e; zeredTU=i&HM4CSRKFx-A60w@3=_86?@6k7Vj@58HNW66m(0G^6Qkq4-9}^#n92q{5 zNZD4$;-V=Q)IP*!f@cC2BLfb}8ZRyib2?Ze9`5d0Cb_37#3T)cBODGMY=y@lh zbv9q+Z(G0kJ~}pXP-Xy|*>oMgCC!N%(m31M2@h%UJC}Zaf+k8OryL4ppWBb&_fQ~k z`#Cvg^eg%aI_VJcK+mAF?4;~!K8jyEt_D$P58J*M4Gj;hO8A-Q&d`bx-QBB!vPf5q znT+G(Tl4T3G$pLcEhKAC4;SeXkffj>dQ*Tjq9;xhRX(Km#`@l5o8$@%iQN`8!x|{O z#GJ$-JR`KojQpgbRB!*Op=Zx5e>LVJHs&SX%HJ8J#kh+~CRm2;_;e~J6eaP|Mrq)M zi){`x6!Ab5m-;)(N^acfg7GjV;Qp#uXi0Y;n%%>)87N9*%n+*GHP3k}vG=J?arRTm z*3lp{Q;D_-|CKF6p3l2Http{g3`@D*f(pZZtnFn-$2D(jlcb=B*aA({HhpDmGMSNH zG?XOPJlZTg3!iV4ZAS-s(NxK-f54}E`^v4DBU|mV%8o2Ng;JvigU^?X;|R>s9dC2A z>!K_Vc$ZG46iPVh4=SFN>OrjWEb5#s9zo6CvUy0cK0n#y_*iUVZ7G^<%F{Mb4*}V&{DPA!i&~ zIn{Uqm|0__!9)1>y^v{j-32yHZ{NN}@=bOxzJ`)0-uOIJ>UsX50|$`E4CR$qQfvh7 zd5}EKZcVH#Hi#>AvC9eR=t>O)8*x5WoF0=uR(d*kw<`p2dtw`8T30ZRoslhdY0k5| z_3kvYvMbd1+FZ8VUlFSWh{C)5y20?J=&}IEcXvlVpB(F>YJjb#BOkR+cdG))Vs2F) zAq|JT8sN*3Gb(nZ6fhbVnM+fNTtGK^!xR62V*tpgR7_NDc}4$WvtFid3T+`G${X z^`)RAhBF9BCceC3HPrlFD_n2{lpT!KW9UVT?2WXO@{=naKrQ7g7yDZTa8BM08 zOKW#zGQ;@-3~cfGk<->euFQ|V*Pe{IhHvh!QsDM z{gb{9F-UEI+?goR(Xgn>HVH$VIjP79)7N{m3V3pw zjV6i~+d5eWZTJ%Ag~I=HabJ+yc!e{)dOi7=bCHw9*L~cppEFtS&|^^7m<)ew?`KO+ z@$a2i5E~z#%tj7}Qb425;xQE!A6H6^60X!ibI+cS@b6cl9k69HCKCVMYxnekVXaS;0t0sU%0@wm!RI>c{_szXH^6z_`do7e0o8NYP?lr&Ce=YFbYm{!{ z@qVx5+>3ljfZ@OY{}TTnSVh~lM4~D>({t|GU{kG|dpc;9u1UcZgSnp!&bdbp%c&w+ z>rD`hKF{ypQkn+LSWJ+9Zqpu_b&)2lsMcm$L{5JLFD7 zwf=SCMF-WaiT#tUxmjF1A%}PRjldb7vj}65N2=4JmWm3<2PfX!gNeL&4Ofef23Jl- zyr@*%hH=8KYCOcs{_h1}3<;@iPv&FVJnYwYo`j3K%Sax$?kgXR?*Cr#Atc!ch3U~b zAGJx3d|z!+dAX%zl{b=lJqmx<%xK7r^Z9wAcpW|7%QqjJV!X=ls=S-}|Gsy0v;gl# zdj;`SMK{SutD@AWEm?j#?KKi##Yc%1p8Z+&Sjj+)*>AzeR7TGssX>r8oDtM$Dwuf_eWDIg%TI+B(HI5Z-c55 z6@(g*&rh^LRuuXG;ftJ3BNtq3`S&X_e8f&i&5^S5}$KOC^PBCj}1RSnADMlA9ILjj{JbY)jfZW&U*``^9L9 zq8sPRmEEr+wxKjg)Vm%~H$gpuMB@4~T2QH1+Y?ns|M%~hA7LWxg^L$!+E?czRddT6 zDSUBq6%$-?M-q{%zJ2o<0lBMJ_cTx)GW80jstx9)E=IJrMI;k3V;wi<#6rs-&#WHD zmgBIDw6wtT9_m}kKYpga1f+V9oOI=^?R~=OyqUnn7IJOxJl<9M6LZt#rbs3M$S?i# zM<#)yRGB_Jy*NFhAp`u1hZfdqLEaL=yL)#vmU;K?I@k7i^wV9k2>x@{C=&sqv<8@% z_LXcXq02f@?STXD@mY?))P2lz{GC6*LgJLqo!Vc`Cor+wikbmge7jLEm>3-#4OBudYx_6 z3AWeEm$@Wj(4hBlISHaj+QD{2W5weVx~N(cQ{(pc_5(%kE)YM6LiC_9b<1c&S{?Sx z!tw80=tc7u?Bw9!APJedjo8rHxfKku<;{QYM(KSJB#em+2Mpv#cD(MVj05nMQRB~B zB5x-{9CB9arZ|l3e!c`G5=eevY{Q>->BcSys*FSo4}f;3prBftx?i?oQ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - RWS & EGM Sketch 4_2 - - Sheet.54 - - - - - - - - - - - - - - - - - - - - - - - Rectangle.269 - Communication with robot drive system - - Communication with robot drive system - - Dynamic connector.271 - - - - Round Corner Rectangle.72 - - - - Circle - - - - Circle.61 - - - - Round Corner Rectangle.77 - - - - Round Corner Rectangle.78 - External Computer - - External Computer - - Round Corner Rectangle.79 - - - - Round Corner Rectangle.80 - ABB Robot Controller - - ABB Robot Controller - - Round Corner Rectangle.81 - RWS Server - - RWS Server - - Round Corner Rectangle.82 - RAPID Program - - RAPID Program - - Round Corner Rectangle.83 - EGM Client - - EGM Client - - Round Corner Rectangle.24 - - Configurations - IO signals - RAPID - And more - - - Configurations - IO signals - RAPID - And more - - Round Corner Rectangle.26 - RWS Services - - RWS Services - - Sheet.86 - HTTP & WebSocket (TCP) - - HTTP & WebSocket (TCP) - - Sheet.87 - Google Protocol Buffers (250 Hz UDP) - - Google Protocol Buffers(250 Hz UDP) - - Sheet.88 - Lower frequency, general communication. - - Lower frequency,general communication. - - Sheet.89 - Higher frequency, specialized communication. I.e. direct moti... - - Higher frequency, specialized communication. I.e. direct motion control. - - Rectangle.90 - - - - Simple Double Arrow.91 - - - - Directed line 1.92 - - - - Directed line 1.93 - - - - Directed line 1.94 - - - - Directed line 1.95 - - - - Dynamic connector.96 - - - - Round Corner Rectangle.50 - Robot Web Services (RWS) C++ Library - - Robot Web Services (RWS)C++ Library - - Round Corner Rectangle.51 - - - - Round Corner Rectangle.52 - RWS Client - - RWS Client - - Round Corner Rectangle.53 - Message Manager - - Message Manager - - Round Corner Rectangle.54 - User APIs - - User APIs - - Directed line 1.56 - - - - Directed line 1.57 - - - - Round Corner Rectangle.43 - Externally Guided Motion (EGM) C++ Library - - Externally Guided Motion (EGM) C++ Library - - Round Corner Rectangle.44 - - - - Round Corner Rectangle.45 - EGM Server - - EGM Server - - Round Corner Rectangle.48 - Message Manager - - Message Manager - - Round Corner Rectangle.49 - User APIs - - User APIs - - Directed line 1.58 - - - - Directed line 1.59 - - - - Cloud.248 - RobotWare - - RobotWare - - Dynamic connector.255 - - - - Round Corner Rectangle.111 - - - - Round Corner Rectangle.112 - - - - Round Corner Rectangle.113 - - - - Round Corner Rectangle.114 - - - - Round Corner Rectangle.115 - - - - From 2431daefd55248e889be8efa637c2a6d0aa0537e Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:37:50 +0100 Subject: [PATCH 02/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 2d0808b..f174d62 100644 --- a/README.md +++ b/README.md @@ -15,7 +15,7 @@ RobotWare `6.07` introduced major changes in the EGM communication protocol, and A C++ library for interfacing with ABB robot controllers supporting *Externally Guided Motion* (EGM). See the *Application manual - Controller software IRC5* for a detailed description of what EGM is and how to use it. * See [abb_librws](https://github.com/ros-industrial/abb_librws) for a companion library that interfaces with *Robot Web Services* (RWS). -* See [StateMachine Add-In](https://robotapps.robotstudio.com/#/viewApp/7fa7065f-457f-47ce-98d7-c04882e703ee) for an optional *RobotWare Add-In* that can be useful when installing systems on an ABB robot controller. +* See [StateMachine Add-In](https://robotapps.robotstudio.com/#/viewApp/7fa7065f-457f-47ce-98d7-c04882e703ee) for an optional *RobotWare Add-In* that can be useful when configuring an ABB robot controller for use with this library. ### Sketch From 2ec8dfd93c98ce6bb1c1a74474ee32f8df95cf38 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:38:08 +0100 Subject: [PATCH 03/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index f174d62..9e4603c 100644 --- a/README.md +++ b/README.md @@ -19,7 +19,7 @@ A C++ library for interfacing with ABB robot controllers supporting *Externally ### Sketch -The following is a conceptual sketch of how this EGM library can be viewed, in relation to an ABB robot controller as well as the RWS companion library mentioned above. The optional *StateMachine Add-In* is related to the robot controller's RAPID program and system configurations. +The following is a conceptual sketch of how this EGM library can be viewed, in relation to an ABB robot controller as well as the RWS companion library mentioned above. The optional *StateMachine Add-In* is related to the robot controller's RAPID program and system configuration. ![EGM sketch](docs/images/egm_sketch.png) From 9e59018cd93b5a6c678f2234ea6d9f5d8263e378 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:39:30 +0100 Subject: [PATCH 04/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 9e4603c..12fca21 100644 --- a/README.md +++ b/README.md @@ -49,7 +49,7 @@ This library is intended to be used with the UDP variant of EGM, and it supports ## Usage Hints -This library is generic and can be used together with any RAPID program, which is using the RAPID *EGMRunJoint* and/or *EGMRunPose* instructions, and system configurations. The library's primary classes are: +This is a generic library which can be used together with any RAPID program which is using the RAPID `EGMRunJoint` and/or `EGMRunPose` instructions, and system configurations. The library's primary classes are: * [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID *EGMAct* instructions. When an *EGMServer* instance receives an EGM message from the robot controller, then the message is passed on to an EGM interface instance (see below). The interface provides the reply message, containing the new references, which the server then sends back to the robot controller. * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the *EGMServer* class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. From d803939f7939e27576746b5806119501bcb26192 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:40:15 +0100 Subject: [PATCH 05/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 12fca21..76b97ba 100644 --- a/README.md +++ b/README.md @@ -51,7 +51,7 @@ This library is intended to be used with the UDP variant of EGM, and it supports This is a generic library which can be used together with any RAPID program which is using the RAPID `EGMRunJoint` and/or `EGMRunPose` instructions, and system configurations. The library's primary classes are: -* [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID *EGMAct* instructions. When an *EGMServer* instance receives an EGM message from the robot controller, then the message is passed on to an EGM interface instance (see below). The interface provides the reply message, containing the new references, which the server then sends back to the robot controller. +* [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID `EGMAct` instructions. When an `EGMServer` instance receives an EGM message from the robot controller the message is passed on to an EGM interface instance (see below). The interface is expected to generate the reply message, containing the new references, which the server then sends back to the robot controller. * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the *EGMServer* class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. * [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from *AbstractEGMInterface*, encapsulates an *EGMServer* instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. * [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by a user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. From cd11f30ff7495d6bf608d6c462ea50996eb4c2ca Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:40:35 +0100 Subject: [PATCH 06/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 76b97ba..9503f90 100644 --- a/README.md +++ b/README.md @@ -52,7 +52,7 @@ This library is intended to be used with the UDP variant of EGM, and it supports This is a generic library which can be used together with any RAPID program which is using the RAPID `EGMRunJoint` and/or `EGMRunPose` instructions, and system configurations. The library's primary classes are: * [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID `EGMAct` instructions. When an `EGMServer` instance receives an EGM message from the robot controller the message is passed on to an EGM interface instance (see below). The interface is expected to generate the reply message, containing the new references, which the server then sends back to the robot controller. -* [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the *EGMServer* class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. +* [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the `EGMServer` class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. * [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from *AbstractEGMInterface*, encapsulates an *EGMServer* instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. * [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by a user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. * [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. From 9a9e0a9de59a6441dc81dd99d6238c983b116f50 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:40:59 +0100 Subject: [PATCH 07/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 9503f90..441eed2 100644 --- a/README.md +++ b/README.md @@ -53,7 +53,7 @@ This is a generic library which can be used together with any RAPID program whic * [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID `EGMAct` instructions. When an `EGMServer` instance receives an EGM message from the robot controller the message is passed on to an EGM interface instance (see below). The interface is expected to generate the reply message, containing the new references, which the server then sends back to the robot controller. * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the `EGMServer` class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. -* [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from *AbstractEGMInterface*, encapsulates an *EGMServer* instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. +* [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from `AbstractEGMInterface`, encapsulates an `EGMServer` instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. * [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by a user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. * [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. From cec57c5353c688f05fd32171f33fd6be40bef1d7 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:41:43 +0100 Subject: [PATCH 08/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 441eed2..67f9cde 100644 --- a/README.md +++ b/README.md @@ -54,7 +54,7 @@ This is a generic library which can be used together with any RAPID program whic * [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID `EGMAct` instructions. When an `EGMServer` instance receives an EGM message from the robot controller the message is passed on to an EGM interface instance (see below). The interface is expected to generate the reply message, containing the new references, which the server then sends back to the robot controller. * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the `EGMServer` class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. * [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from `AbstractEGMInterface`, encapsulates an `EGMServer` instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. -* [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by a user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. +* [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from `EGMBaseInterface` and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by the user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. * [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. The optional *StateMachine Add-In* can be used in combination with any of the classes above. From d96af5e8cb3669992ade319003c785aa4910002f Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:42:00 +0100 Subject: [PATCH 09/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 67f9cde..7892914 100644 --- a/README.md +++ b/README.md @@ -55,7 +55,7 @@ This is a generic library which can be used together with any RAPID program whic * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the `EGMServer` class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. * [EGMBaseInterface](include/abb_libegm/egm_base_interface.h): Inherits from `AbstractEGMInterface`, encapsulates an `EGMServer` instance, and implements a basic EGM interface. Can be configured to use demo references, which are intended for testing that EGM communication channels works. * [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from `EGMBaseInterface` and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by the user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. -* [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from *EGMBaseInterface* and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. +* [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from `EGMBaseInterface` and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. The optional *StateMachine Add-In* can be used in combination with any of the classes above. From 422772fa9e7005e84a1199878afe0b4ed9b22cb7 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:46:17 +0100 Subject: [PATCH 10/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 7892914..52b7ab8 100644 --- a/README.md +++ b/README.md @@ -57,7 +57,7 @@ This is a generic library which can be used together with any RAPID program whic * [EGMControllerInterface](include/abb_libegm/egm_controller_interface.h): Inherits from `EGMBaseInterface` and implements an EGM interface variant for execution inside an external control loop that needs to be implemented by the user. Provides interaction methods, which can be used inside external control loops to affect EGM communication sessions. * [EGMTrajectoryInterface](include/abb_libegm/egm_trajectory_interface.h): Inherits from `EGMBaseInterface` and implements an EGM interface variant for execution of a queue of trajectories. Provides interaction methods, which can be called by a user to for example add trajectories to the queue and to stop/resume the trajectory execution. -The optional *StateMachine Add-In* can be used in combination with any of the classes above. +The optional *StateMachine Add-In* for RobotWare can be used in combination with any of the classes above. ### [Optional] StateMachine Add-In From 8ca0365522f461e87d0f25300e4e47f88ec7d690 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:49:36 +0100 Subject: [PATCH 11/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 52b7ab8..e3b5252 100644 --- a/README.md +++ b/README.md @@ -59,7 +59,7 @@ This is a generic library which can be used together with any RAPID program whic The optional *StateMachine Add-In* for RobotWare can be used in combination with any of the classes above. -### [Optional] StateMachine Add-In +### StateMachine Add-In [Optional] The purpose of the RobotWare Add-In is to *ease the setup* of ABB robot controllers. It is made for both *real physical controllers* and *virtual controllers* simulated in RobotStudio. If the Add-In is selected during a RobotWare system installation, then the Add-In will load several RAPID modules and system configurations based on the system specifications (e.g. number of robots and present options). From c32aed848b6a588e86078e69a0b91bfe4846ad38 Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:50:47 +0100 Subject: [PATCH 12/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index e3b5252..a1bb935 100644 --- a/README.md +++ b/README.md @@ -63,7 +63,7 @@ The optional *StateMachine Add-In* for RobotWare can be used in combination with The purpose of the RobotWare Add-In is to *ease the setup* of ABB robot controllers. It is made for both *real physical controllers* and *virtual controllers* simulated in RobotStudio. If the Add-In is selected during a RobotWare system installation, then the Add-In will load several RAPID modules and system configurations based on the system specifications (e.g. number of robots and present options). -Retrieve the Add-In via RobotStudio by: +To install the Add-In: 1. Go to the *Add-Ins* tab in RobotStudio. 2. Search for *StateMachine Add-In* in the *RobotApps* window. From a72264f0906c1a519bd3ce034ac9cd2043e66abc Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:51:03 +0100 Subject: [PATCH 13/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index a1bb935..7283ee1 100644 --- a/README.md +++ b/README.md @@ -71,7 +71,7 @@ To install the Add-In: 4. Verify that the Add-In was added to the list *Installed Packages*. 5. The Add-In should appear as an option during the installation of a RobotWare system. -See the Add-In's [user manual](https://robotapps.blob.core.windows.net/appreferences/docs/2093c0e8-d469-4188-bdd2-ca42e27cba5cUserManual.pdf) for more details, as well as install instructions for RobotWare systems. +See the Add-In's [user manual](https://robotapps.blob.core.windows.net/appreferences/docs/2093c0e8-d469-4188-bdd2-ca42e27cba5cUserManual.pdf) for more details, as well as for install instructions for RobotWare systems. #### Notes From 229760571d975b5d86412f98cb1b2572d08c796c Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:51:27 +0100 Subject: [PATCH 14/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 7283ee1..dbc1085 100644 --- a/README.md +++ b/README.md @@ -75,7 +75,7 @@ See the Add-In's [user manual](https://robotapps.blob.core.windows.net/apprefere #### Notes -If the EGM option is selected during system installation, then the Add-In will load RAPID code for using *EGMRunJoint* and *EGMRunPose* RAPID instructions. System configurations will also be loaded, and it is important to update the robot controller's EGM configurations. Especially the *Remote Address* and *Remote Port Number* configurations, under the *Transmission Protocol* topic, are vital to edit so that the robot controller will send EGM messages to the correct external destination. The configurations can be found in RobotStudio -> Controller tab -> Configuration -> Communication -> Transmission Protocol -> Edit each *ROB_X* instances. There will be one instance for each robot in the system. +If the EGM option is selected during system installation, then the Add-In will load RAPID code for using `EGMRunJoint` and `EGMRunPose` RAPID instructions. System configurations will also be loaded, and it is important to update the robot controller's EGM configurations. Especially the *Remote Address* and *Remote Port Number* configurations, under the *Transmission Protocol* topic, are vital to edit so that the robot controller will send EGM messages to the correct host address. This configuration can be found in RobotStudio -> Controller tab -> Configuration -> Communication -> Transmission Protocol -> Edit each `ROB_X` instance. There will be one instance for each robot in the system. The RWS companion library contain a class specifically designed to interact with the Add-In. For example, to control the RAPID program by starting/stopping EGM communication sessions. From 00963ee89449020148a29d65a15876eb872834cb Mon Sep 17 00:00:00 2001 From: "G.A. vd. Hoorn" Date: Fri, 7 Dec 2018 12:51:41 +0100 Subject: [PATCH 15/19] Update README.md Co-Authored-By: jontje --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index dbc1085..9d13334 100644 --- a/README.md +++ b/README.md @@ -77,7 +77,7 @@ See the Add-In's [user manual](https://robotapps.blob.core.windows.net/apprefere If the EGM option is selected during system installation, then the Add-In will load RAPID code for using `EGMRunJoint` and `EGMRunPose` RAPID instructions. System configurations will also be loaded, and it is important to update the robot controller's EGM configurations. Especially the *Remote Address* and *Remote Port Number* configurations, under the *Transmission Protocol* topic, are vital to edit so that the robot controller will send EGM messages to the correct host address. This configuration can be found in RobotStudio -> Controller tab -> Configuration -> Communication -> Transmission Protocol -> Edit each `ROB_X` instance. There will be one instance for each robot in the system. -The RWS companion library contain a class specifically designed to interact with the Add-In. For example, to control the RAPID program by starting/stopping EGM communication sessions. +The RWS companion library contains a class specifically designed to interact with the StateMachine Add-In. It allows for example to control the RAPID program by starting and stopping EGM communication sessions. ## Acknowledgements From 5695ab063727784b30befa1e1ad23d231ddf205e Mon Sep 17 00:00:00 2001 From: jontje Date: Fri, 7 Dec 2018 16:33:38 +0100 Subject: [PATCH 16/19] Added a few clarifications --- README.md | 9 +++++++-- docs/images/statemachine_addin_sketch.png | Bin 0 -> 164640 bytes 2 files changed, 7 insertions(+), 2 deletions(-) create mode 100644 docs/images/statemachine_addin_sketch.png diff --git a/README.md b/README.md index 9d13334..3ce1171 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,7 @@ RobotWare `6.07` introduced major changes in the EGM communication protocol, and this library has not been updated to support those changes yet. -**Avoid using this library with RobotWare 6.07 at the moment.** +**Avoid using this library with RobotWare 6.07 (or newer) at the moment.** ## Overview @@ -43,13 +43,14 @@ This library is intended to be used with the UDP variant of EGM, and it supports ### Recommendations * This library has been verified to work with RobotWare `6.06.01`. Other versions are expected to work, but this cannot be guaranteed at the moment. + * **Avoid using this library with RobotWare 6.07 (or newer) at the moment.** See the `Important Note` section for more info. * It is a good idea to perform RobotStudio simulations before working with a real robot. * It is prudent to familiarize oneself with general safety regulations (e.g. described in ABB manuals). * Consider cyber security aspects, before connecting robot controllers to networks. ## Usage Hints -This is a generic library which can be used together with any RAPID program which is using the RAPID `EGMRunJoint` and/or `EGMRunPose` instructions, and system configurations. The library's primary classes are: +This is a generic library, which can be used together with any RAPID program which is using the RAPID `EGMRunJoint` and/or `EGMRunPose` instructions, and system configurations. The library's primary classes are: * [EGMServer](include/abb_libegm/egm_server.h): Sets up and manages asynchronous UDP communication loops. During an EGM communication session, the robot controller requests new references, at the rate specified with RAPID `EGMAct` instructions. When an `EGMServer` instance receives an EGM message from the robot controller the message is passed on to an EGM interface instance (see below). The interface is expected to generate the reply message, containing the new references, which the server then sends back to the robot controller. * [AbstractEGMInterface](include/abb_libegm/egm_server.h): An abstract interface, which specifies how the `EGMServer` class interacts with EGM interfaces. Can be inherited from to implement custom EGM interfaces. @@ -63,6 +64,10 @@ The optional *StateMachine Add-In* for RobotWare can be used in combination with The purpose of the RobotWare Add-In is to *ease the setup* of ABB robot controllers. It is made for both *real physical controllers* and *virtual controllers* simulated in RobotStudio. If the Add-In is selected during a RobotWare system installation, then the Add-In will load several RAPID modules and system configurations based on the system specifications (e.g. number of robots and present options). +The RAPID modules and configurations constitutes a customizable, ready to run, RAPID program, which contains a state machine implementation. Each motion task in the robot system receives its own state machine instance, and the intention is to use this in combination with external systems that require interaction with the robot(s). The following is a conceptual sketch of the RAPID program's execution flow. + +![StateMachine Add-In sketch](docs/images/statemachine_addin_sketch.png) + To install the Add-In: 1. Go to the *Add-Ins* tab in RobotStudio. diff --git a/docs/images/statemachine_addin_sketch.png b/docs/images/statemachine_addin_sketch.png new file mode 100644 index 0000000000000000000000000000000000000000..fb6270019040c06ede68fee5f3e78d235d253934 GIT binary patch literal 164640 zcmeFZcT`l_w=PTBx=6T5E=Hesj*fw)c5e zg)JL*Z^YqnTNKaAUBKZs)Z%cz{PfFD@Ru7|kMrSwYwRy5{DFI2$1w`O{A_VbXG7BR^;`R?23)T5x^LRwZ_R$! z#wv82`!f5Roqq`(y}a{&WZ<2@XYLoXAAMrOv5RQB*?Ds(>%#Hl%G-LYdxf%bCMBhn z``1?P-*5l8)8%o#`I|Kn`kU16D5la`m4`Lti_=iM5e8LZB^ z(d}~>hdatGEs4WrHAYK14Gj-Vo(L5*^0$VY975MNNNm`!VYn{(p{I2D#R<64X6#1M zsi~<~KLzOO>iV$Ya3`%-{x~-`2Y-}sn$%B$Ij=QkuEm`kPf1NZlj+$^qq+a^#}QcH z(^J@0d(rG7XY04(aH(+?8*sPRqs2dUz-IpqTbh5&UL0=s3-sluMs(A=D@((!e}ul& zRY2Eo`H0QLQ!@F`CKSBB5+egqNlDW3iZU|rFyUE_9n8Ye{bG zYPMZonp5C(+0Uu`(z&uKH6_JVkX{=p#^o{F=v-rG=H?aMBm7aOUuZC6I5#)<#HVm2&pez*eePUzvr1-G3h=Qm4=OxiBG|Q4P-RElxpWcl#>YNP z$GjT{yoRGoe!=zLTIBs1*V}}&mv}8GSv$=k_Qr5lGipWG1_MOy5F#SYa*f(7`V zsjR9xm%_fE^?(pB+jtQB-WF=0+Gp)KN3#z)3Omx2cI*psRu5uV@ptY~^u^&+L(~4i z;be{&m2&p$_U1cHZROW73HU*6D#n`6ZBH#FIt6$?czL}hQ+BBH%jBQWj2(8w?YP&u z<)Z#EF1{f4kcSS6zE#rnh5ltH>6;hb3=0k^`kw7OqxdiFEo6m+gd|>*h`!_0E)&yc zvLjAdFy_XNxSQnbD@fwAZ|@UkY@hOA__zKhb=YhD^@vh`X6C z;N5t%T`$MhI-ls^UeX7JUOjUYegsa!b|dyC7=_hMuuj-!*~gvR z@Rz<$48~k;Y`LRp_l$u(#n?QUgzv9^%SXi~_hfYQjco8?f&G={?U$cpennBY$<-iI zD30_a5zCAW$x(~?-`$8qY!+(AB7JAOGT2<~?S&bQW(?WLTe796OHG2u-Fgupn;!mpgiC>RXjC;L=RAF`rkXzXUXpB1v|+DHCf9FTN^26V$bPbS zYx?sTXXPDn`{fUmxwuNFi;Sw?AQtV#PX-q*h%zq8-)qyBo(^*}mQapv(md$)uxxFW z*;F!Vo%e=;k|DTgV{F`Xz$V=7*S{lN$U0Xf!ZEzm^tw$QyGr*oB`R4mMJMzYPmT?d zQzw9xm8qq>Q>dgrnEj#;Ec||ZPmliwj?|Ac28P)O;|D=Om_w<@wnc$aq$n9{>e1^? zgoklzlMYnUou%g`%{Nr_m~_XQnoiZb_Z!78dGWdPv#i&uPfuOl$X(yXSyyBA3uK2q zWa8Tr!xf?Kz8@3+3NNR=EdYa+_39aGaXblQ$=h(Zvn#b9XqVF`0@LGM`-J98vSLC` z5!~PMupVgVBDcO_V`gOval~^>FYK2eoY9V#)u+-)i+>z3k~3$>#?Mh$mB6g|^1X_F z)7rn{kAB=n&01mwr%MfkB2uqX%&X}i@5nZfYEK`p!+#nZNsBQ#4dU4^ujsqv%Ye0> zIYuAXQXsvIajuaTN=@i<86v8-X8`c`5JW5KYV%rBi`sGdhXs%C7aG%WZsKiUbK5+` z6VR;Tk9!XFqzL#dhUuZIe3sPn-p#(F`i0oESI;JgS8)nj+Mx=NRO zcFXUeo--CvrrhzxM^th3wwJRsopNPtPn$|85?|c=IYR}#q9Jy=vuw)jDS(;7QIdA zyPJy%x?~=%uS%fum)|X?^XyI!b>sEi*n;2IqA&GkxrUMWo5rWZ!{Z&wl*Be$O)FJn z&BIR)3Q3FCi+IaCwccU$_I7(qZgIx7;g#l+q(*3B%ftT-B3?VxFznw8RH60TVB z>WtDM-0j0(+DrllH>Laupa)3b1CbekewXgAb0v3!*+oA$DscHl``^4rnj3E&*MGs4 z41eUIM3!8AL~mfPAN^o)_f}Z9WxoZ z>E8YFM#hE4?DFTUW5;$z2D7(pV>*kOwDp`4 zMLD|jeKWy9nSXa_gMc8iW)vX(4sk}6jOZA%tpfZYvKF_Q*rW`%)PcdNzGGj6_jCrW zK+?_0sU{TZ%C;f#7`*Q?z~|k7MXgB`QKl(UP?g8h9vr^&gmI^$Di+1K0C2HVmb?)PE|!^+-ok&*3_e z1tAEUQ=XYg)%X^F`a?h(%%D*ylwQnnb!0Bd(x>xIkq81rsqw3PV)rY!a?JCl`UdcJEIA8QCeE^@z3eMg*YnUu;Pp3)G!SEW5y zM3Trk6?OrTI3ewhUF`8b^+1b-GNoX!4u={`^+^=*rBy%stIGbV-;r^;sUQfJQ zyrF9TdJf;zsX&Hk5R0gO%Ar6H|JU)vhms#z=8^ef5>y{hsv#wn&FX;TtOWNJ-5Ucv z41?HzhzCIR6*DMcu;l)J`41&y`{hrh|Gv7t&B!W0h&V)4`9E#b@B93Kt8QzX&v=)K z!G*R?aA=e5fCJZ7BwQ_)9Zvsv9Nq3Q;ZS~&v+X}t3=<6G&peFl3YQKh6um3Dqs{76 z>I2Gq*!|T=xrrw}or%?Xzv-*q?pM{J*>U!>$-IfPCRCP(Qj*UzY)!4Acqht#5UY)#A-n;0EedJbQLD# zA3M&|tw=y2_p5+|+4qJJGVRa&YG_-~mzGR=zlhA+Dn0+3T=T0l0@CCE|E<*^Kx(D} z(&QT{zrg{$&eeS2bls8nr3m!0%cM^#1T&`q8T*0j}u& z^~$(Q9gAeQp?Co9qi*eFFXorT==V8>l=-7uRlOZbEB9?Vz;)9K zcm|3ARk;K;1RA?BY37!xX{>AS;e?clWV36bT9b-5X5KSdS;u}4Z~nNj1Fcm~6kBU} zqJ0p1_s%AmV5aawsmF(Wo0__{#P0|Ub!SNh?ZlgF)lv;fxiJpnSvZ83xGA|_zq_PZnGQu_S~N!Qx*bC#^O z?Fs4$7)02_exRN68l4|<5%%2+e{ROzR=#!Ou7HLg_!aP6)2n>UfQ@tBwTixwPwijL zMt)noa7@Escu?|fL@U8!M!VL+&C601B=mz!r5Bk}8PYDBQF!@rosn~`xdiv@gIcZc z{yzI3Knj7eysE}&mUHB=9waTr&#x#;7VB}h)iF61H#;wUeh}bfbB7lFcXHZWUkqh1 z9@xxtoJZ)@@0^cH5>KQP5%V1EDCRBTb89zIPsl7R+}m_zMzpIKQV6{rap|R#tNF@( z7us|=`G8wIeba^CDIu$z62;U!9>#i|OP9PYb7==?eze~G|5g9se%RbAh&*2ciJtUg z>^)P>2>{kz~HtL&pox>D0Xnl`RJ^ZdRg9pjA6aZM|;kTklv}o{fomh zcpy{-PHx>EplJMf=N<@2M;ur0t|>q*-sIF)vAN*J61%a}k1!QQd!XTAWv*vpuy}wL zSCno7!6+`m!xh;ThQFKl6&_0$I1xSGE{uW(TB5rDD+p2Rwz!{Kk2@;*{J!FmHbDLH z=C>%zEHdSCR=G|$EL&?+6%|UK%nsN`PXzD+JxRPk*PSE9O)|tb zELMM1IMVn^@UH-{n=)3QnHb_ojNQ1IKOiQ5T<35Z=W6`IvZoXGxUx1EY?cZpWJzgg zxdbeg`2*AUzeX7?g?NaWi;(YZm56gh75%k@MF-8`h5xk8eI!)H>ll_MZQrY02jS8k z@;C)9kF17?oG+Q*#0ogH2Jy2;P&8 zMA>~tP^oB}pj69P_Kl~`rWc%@0sZzWk)B`Rm*&m(1Bk2Y@hfM|hd_;%xRU(OU7eig zY8LuZZeV~+1h7EuuA1PtT;xi#c6?Hkrqx*xSrKFdcn?lUh5s;<{h~`n`18p9Qmp#h zwYV)SaV$ywUCv1ls4~d^M`Y1jdlh_DutDI73?9 zCsaA-Ht*lY*&i=tuvqPvSy(FK4W?@1ZLnJR(bCeYnp8X%zp&|R9RaZgkB##NNk?Zl zfEA;4UwsrGWB85o)_a^#DZTGnwe<^%OMfAw{=F76Y85cqO$N&Mpc?imMKoE7rgN)) zUx3sFyWFd3dwgWShO+Fy7<&(tw9PSh)J%>)Vwke%&P2@QA7OS8Qo&djRyfiUaC@(v zW>{oXE^9%2P4zx5-Nk>^Y%g zCYj{fo%gCf3uD0VjauDeaJc@fB*eW&$rbwox**s>VQyLUd`^1}Ysp8~$)3VU=~uQ) zf05D-b*g0_W@uYHw1K*wFZH>vN%Qb#o-xQAYI`0n_H$Di?Jt(N9?wcX6LZv1o07>B zOh~fw$YzkHYB@P2&t*tE*&N(Cj>FaQqAme^IAT#R06zb(D~&LAr8NTo5SRHsaGQu* zP?)KchRT~zH0$)81E|)=(ypyFeerBUutzD222OmBd+=tQU#{!iHFt9Bs1!z4)cRcZ z3+>h;33zWm8YBKZi2d*VUQX6K_KCZ+w`xykkKf8j%QxPLv$!qjjeEKaY7G81REcOv z#lm`Ir!}E6#sah+_-HWunttznyxxt!J|ysaZ};e1ch0y(eR^!a(4QKC9w97K1*$yM zF}`@5EnzX}7u;@?)Rl_4D^kkaY#AjQipIAzQ3O;@fl8t;kALERc^-ax#(w!(RBYU? zP?{WE@{4NeF52@=xMM~8f4aSXfWboEm7B#I1BD$Zs_uxp0@bvAm!<6F09md~haM1m zu2yhT(N~<;FnYhdt?mrN>q`+ai3ykIuJ|*q-*q5Rp--*cQ`N*|=21C1!of8Wkc>${EzqawNsSDS@@*wUUQj0m?~{3HM&ZP@f3>yS^5HG5G~2t zCa3c>#wI#*GF?){h1!km0HtZQ)0qi&60!FHu5Y2rn6?E}#!SgN>Yd&BPMI5qh-cds z0t;X8EdOM#CQ21CAb3hMa;xxiWYEu3oh&{TX>BKeFrM9%=b$U+9-E2qj ziRNl1ee~eK${2gfXf@Yegx~F(^vGr$1T|PsC`k8Cm1p;YZ5?w$V;N#p?AZ9As>N|}dfpL9^2rlaHVBey&b^efajNUoimjr6(wIUx)+hhE9DsK%V4b%nKSn~13bdVx>CH{z$%%CGgzaW zg|azix0|v0$LMCM*=s%n|k`Z9sOWQ8|-BC6hs; z3u^N5LqcsV0Vl4};ue}?PHRiWe@ry;UQ=9|G#4v?yZqGs`uT({HTY@+$4VVas%OgC zs<8!{*psyc*?=GS+tBfx4=QMX_j`ByJ?~5NXMr8i)_Je%o-=T=XWW14@ALj@vw_1( ztf!hpqphmV@d&XV5Z&~cw9DM4!`pL{=z_Ty%j(tyb(936oKa-s3nB%GG8HcM z{XHi_=WT&asV*jZv&?C7c|fFTR8K!L9qapyw{Ayxgy3a0DSiuDoH*eDX|SqDX4GKg zqvhDiLc5vz%>2VPH0jxDPL||IHwJW>nwQkra1Ckay~?vLP^?W;1Q<8o*q*+9hd6FN zLrkF*snkA%O@gQ)0rzfEFe9=I zkaK?06iOlCj{Ma8 zjn^ZjXU9-TM2#ouv0MHTP43>to$CDs4&x6!22HsZ2IxF-Uv`+ONm2_;W7FEAB$i1Z zDjnOXN+utq`?*Tn|7<(In3<(aDV}Wdk|l!WSKXR#55Zr;^*(M{1_7Oa#PAoQPKv~T z7$78bwFR&hP1JAJXYH(_E&(Nhbpd+{)A3NFs580W2zMtu@)+i75-KU0%!S0-Y9x4S z-&ldTbUT?pOVy=4XE|M}zi}CIum`D|ijE_&wb&6Qo^O>@v$GJr5ZVvm)olVM7 zQsh?Gq2AQ2#EeF#>KT#7W4!5V@>gmbT6y%07EW$-JLGmO+-f*Iaq3W=j7R!2`Os*O z=Tzc}{;6lmp7ktTdvQ@&LxgKT-+oe2WD_toR<$R~bJ50_9GdN5M$~Z>Gb0iyt`F$d zzh+KN;rxrPFPXe-9a*|xJvuU@^Fr_RenO!{McFl=`w#*w^E$b8!6%tRVkFi zT;tecfJbj~wCws!f<%1W)qz9)P=nfDiYl}F85({*u}LWDpeM`Yu6onvG}i8Ud1vOO zBEGzX>ggstN@viglF7s;p&s=dD|%QZ6Cv;1W{a|f_O6r(NGuOu9ysG@rF8$v)^M6d zD(TPi0{0|!XB*$VWa#0bg6f#N_#Dbauw?t3@9b;wOq*xxiJJ}5k6>Qxt?nHGo)5gf zFTJZfeN1030&llI8@{%r6iNg+uZN@q)jhB}0-4S&^-t2_=ZU3p_pb zSBWs>Q7AxSUDEHBfR$_<>vmzxY9$N9ZXP|zFdc9TSsva8${ssZXY|Zy`0kh(c=iBZ zRrrhWFSvxbJA%fzr_p_S5E14E80wC`K|NwQh1Wm15+BRloc$@Uhm%*}@wmW<4<^}_ zGTTb7jn$84h&P!E)d&)paJfqD$ZE-$OKEkp+Y#eX& z2zdEwCWY0hHDC8RPa(MG9W*Kvs^76_&|+Ch9h~0=ymPKGPMmSNPnlBwOsxJeJD!OJ zDF@fvycnoU_$L&~VIZ1+d~S+~S(P{H^amr#fQ3)dUgN6kfcVDn3`ht000t|P{7tto@rjy&PC zLaj}$xx=VL`xW877B5QtzqSg{`mp{#R*XfYFyyNXKnFYjYV*tijN|;EyA^ez)t)nk zl=oW=8sXc@uoa9bdEW0+IDl%>etAa!MF0xXL;t-1P%{`SWFuY%tq*to^w0svNmh}y z(vVcOYm2hTGJzSGq5S=yW{~aN*0|}T$*o&9h1c6%LtH8NykOu>(N(*Kp?mw4T#gp8~? zin>s?T2A{~m3wSoC8&=4@VjH7r#`+{^s&4TC^$mEFLtGdla)PxIC!es=hGv=z< zf&c4Sv5GQ=2p6k}UQhYlxXh=LJ0VB?N5TDDy=kT9jP1Z1f)vUZZ+xo;4MxrU?-@p1Mw(8Bpz0D))rDpLZM84q!JqIvz`x{j1pkl% ziHTq;9J4u<|KG_aw|r_@zP+Y6R=xy)EM&&uWG%j)Gr7E| z{RTYvgF!p56Lmzkli<0$B+lUFMr7x^lVfcyUhQetYhV5|P#S}nrb~)I5Cio8B8YDL zrGHyTu1|j5=?J>S3r4aIK=F+4VkIH7%R# z9Z;l{zC(LGCh`l`B}a8FefqDP3w4h|rifX}|HkfTxJc6yMSr$wLu~INicu1Q{QTJA zQe_-K0Rbz?u82}h1=7Dz;^}<~cK5&zhw(>kmq!To$^Fi5&>~)UyQ#65O$gVZYT`M+ zCqP;3_X&?+*)MukR&CvRxw+wt1BvOma!{W8UJCia2Xbk$Y!!w*VMCazGqh#2oFv-o zOmqbpKX3HVDviJM6&Fz)-#nrJtv!O|^&`7r`4=z3zQ>@1n=z1#f1|BI;`3Gqeo;9} z__y&x17_fs;d2Nm|F~nhn>K=pBw$9K+H2K*J1y$TtUbQGui$lOW`%>@@Xo+ue z-@X<%Au=mTzE-H0WdT|*3gldnww-dTgF+*Pj-M)8RE8 zO^As2{-}HCZhnuZ-y@43)+y?`1X+QnwgWx5F>N}|IdP$SwLzYEfg-At@_PR67AUo@ zh~qJ1a-O|aZSL9;ya{h}|4C?#$OuV>W5z#MaHsi81=&SY;hcFgspnz-Jl$e^aX`r?$* zb$ZlqT0AR3857;rM>HncV`dZbuuc(WdaR&nRZ(yn`RAF`a|fvf!?Ka>)N5{T`SWq1 z1v-t0x$?GB)m7sA5=5ccq%9oY)`0yHHSI7fz_@_O+35Pqz=Qs^dEt-gM$Y-4QWi4; zJT9BIG5vHb(_0qDv-{}Bcoe^c4}Vp(-kcGu~LGxWH$z<qjrZx! z2ZIS0T|W!%hR|>95VR~N0;R*T-3#37ak_j)_c{CjEO#D|?(FPLf2Q_XZ(7;v5L)Qo zi&xiVOqsh8qs@uGIwki^a=CpgegmVQx4Ln|T+o>=Ng)L+8uAOj85&2A(Oo-qORb&n z3F8GS0|F%Iadj>Y5Kqjl_B;lcHignWc4RP!%gyCOQLDoGQ7(BFH9r&pRvo(8qS-{2 zSZ|&Y@RHF|O~+G)DtinTTaRXAz56YeG(QhtVN;K9zJX;1(g}D{Im92#THqPG$?yz@ zsVTlj=F;LHC#bV#Mm(kvm<9c|%=_Y*ofu)#yo^Vli-bdN=Y&-9KG;!?o~Njnj8&;| ztVt;|YOr~~pf zH+gGN;GEv~JR4>F_i18ehXKiyKS{YPykU1Xsu)SV!vHR+&Zt|Ev+KXu$g9*PtQG(* zo$tOpccLua=+G$CyoM1;thJ=T=CzZGoZVOZ-Uv7k4L=T8{t*tXTgu%~hvma4gJ+*0 zXSnc?ItO0$YiHL7I^Pj)vDjQ)u$PlX6O*4|#f;w@T~BgXDF+Aarl!)Yz| zPA8LTP8DL;X%T5ylKZS|f^8fMqTe??rzv(Y9Km}G9j|lVeB`1t++Y8BSg7?F>$d6P z7t~@;?4c!z2{p>@A!5(h=F*RpC^6=l%`;^UoBJTS?@UOfBC*_ai2Zl}(LqWCLuUeQ>uEHP77~Yk9-Rr?#(K^`rYm44c5qNU&nGy5c zfYFmlyx5vvPs`qi?6|9$?iVFysRMtyho&2NHif;mI>n#r6c7P>1sJ$@dD*xTQ0F`O zO!BOQF4EqPN9e)Mw`P)QuX!_4Psg5Aqr~KTF1w~3te~qwX>d=HWWDC&t%y(`Z8uU^ zZ=V(T)%RP=>c^cQ+Qm51+)@$wI|PpJY7b!_ZJVmQB~bjwpL98i7;-ryNT1@ z{)?~np=U(D-9=(dBhL-Kj?g38olieh}d74;HyVIzcO;3$XmX6)}5@Dqb zS(%v0fGFvD!z+)a8Kk&G@=h;#Q@lE*b&&5ai6KV+nX`KNb@%w3=iaWf8TB{mrz;HW zfrVJ4SzE;jOrJW~&b7yVQ*>SA=lvX0ZS^v*tyJhQt4$dMYFp+PbunsLjF<30VuXix z-P46)sERht#`;c{2Q9Px&WNd@ zO#+_ra)(1W{WH-$hrL?iQSGd1LfSFWv!#-wb0eGe~s*!=T+wloF0N>VdtKXWzP^yFI}D`yongPzd2(q}Ox zUZX+F8$@LO9*q$eT6ddT6}lJKaGU0lB`k_h*fm$m2M-Jel`34Qhvz%{ulW9MSPNa9 z$3CZ}y|-(Wuo>W@REkKr+vWp;sW<1t%DxT%0K-Lp@$+I6f&SUczVm9vCCrsXp)y(S zpL{GjMH=BGgR?yY;35d3AH{Tx380HRupCU)F(&2 zT4PH=H$$KQRgdzigQJsE&U*Bq@DE3<-oAZX_Zyi^PKV=ai7NkdXbKLP{m*f)|8K{= zE}tV!Oq4SA#0SO{(v9FiP7`KN8pf8EmM$(X@Yo4m|3*}d2OiJpczeCQDmpqE4#J$w zM@MzwS`z8j_zZct-sZ-Q$*HOG`!eO@?KwF)+FDxX=H?k8N=iyX>)^Z|I^k11tD~zs zc6`WSxIUI}bMPGF-te3o1FMIjemGlN}oabsv!?9Xg4*~u965J3F7_5%|t zc0%xA05dX>%N4b*QVk>5r@K)+D zsDblJYq9-Gh(-GVkaQ)ndpC< zG=}q?iKj6@I6Ahv(+DJ*2G)HBt6wXkudUS?t5Duhn>94*ECwW8G8tJ?lPfo#^HFet^PSNIeEj{y8E4-$wbV{moGO} z=GqTGKV|d2t4rT0Cww9D)2HLdk7p1(z*=Lrz;c7oeGeAX>7Hq7Mwc$-+J1fyCr>qd zEk4xLC{t2c+1T<~XrB*E>*-CCK$)-5EWI_OJ^f}L9))^I^))qe;nH{D9Blp|)o+j3 zWLNG^E;wMOyd4Rn3-2`91&`$G>*?jgjo}}f%^JK^cCh(Rt*r)Mw&IF!VftQ92b|8% z&VKh!TvBq+mRo!VE2a!5Zaav?fY9}@Mjy0N)ykfp9+*cUY0mEvO-7Z<^CYHL+mbJyZ*%g`>Kg2%dnuY?L1Tw9dB z5^X9$j;ch4hhNgw&2yaS=;<*mfTy->37FLN zB_$=3lanFLsIMmqs=41BJ|XC(pU2_S$s;*M@89RbAdb`g%9Y3)7@6;6s`topxaBW& zs4-aPJMV2`W1hs}qShhX5|5X3nuPPe-4FJp4M)y8xsScsz_`n}lv1sBWKV!+o);sV zOUB(emYU@plVAq0V`B2bx@!&Yoe}2K5gMtjvh$YeNrXX@2M&(U`emvYdu3(afvz)# zrl#C0jeMDg|1!wCWod6u?(O|e<|6EX7hQV3nog&em6a`$hvS;0e~lHjZ+j(JltF&Q zH^0a`7hJIbRl53e9VipFRrOS^?O6G&+b8^^XZ{l$5k;okAq~6|M0C&)IW2yhB zx0>UqD|ys#fPSXlhs{N*JF;@YAPG)q{{ccdnLIHym6nssKD;)R-8afQspetsZs>pA)6=jM zybME=tAXabDM&ZkkvF7tt=tBShWExw&_0(tv$C?@=z6z(iX9*k;m}FGTT>roz!S~J zrVDzXeK?rYFi~}>x-9O2>@T~fW*n`-x95=Mhuz#FLK3(f+u-ZrlAjHaxk{itC}+aK z_VnG9v_(o?K0UFmr^@uDn+uhs(Qhx2w~0*vET}{e6uE>jE=(1i936pYep&v-TGoA` zQ*@JGs`3qbFW#}|%d@(sSe95~Bb-Y`!M76}^CmV$BzOwHfPnl7iB~)_x#WgddL_#C zJ<~~b_J-SHC%4x^G|atupa;(P+al<^J(^A+5c2YNM~@`NEY;NU5#5|y?4LaeNvaWK z#C^bL*z!Y&%txvihV%I#gW_g!dTLwjQq2cRA7)n_%hNJ5HvZk&f&v0Px%NCg?w~4U z61Tl`3JX1I^wO`l9jLbJq=biu1Bh^OaFp!X4kyOY0sEtWZ{508z^I5Lb@;4#Y=_IB zn}itMD6m3-^MqliCm<#q;Br=gLt5vMfgWrD!?qJJnL18_B4)~^Ga0lQS(5vQ`4T-d z=IZKdDwR6@>1W(iGfWIIKneiZ4vCMu^#w}`x;?mWaDOY z_f!QNAEuXc0~zGoOTYHDiU zJ=hGoLl9x>=;xjm#v`-%X8jT7IPTh^e!T0#bq9sdoX1wVTk$T@nL^{Di3gIgZAY}8 zbMrjTVSN59h)b-MHih+tq4fz{47im_EnkXu>f!(Nl$$47jl@a6m5>dJzTWz}G@k>W z?S2ldqt|NJgrN{@VewgxqbEL1=eAFjZjTH33y<_$1i5&;Y!3jvGDc`DDnj_QpZlit zC)JY*rqq01CRB_L&(F)}y;<(cwTEaj9lrs0c?P+d_)g0FJR2KZ-2IgPJw@f+ZG%>W zb6iri4Xkt6Rz(oauw_`=*wlkw*PLix%j9Ud7-L*|_$KSj9sCg5>=E=Th+dgJ%Z5Vu z9C9n9@xl>A23Pcy>zM+B>$Xh0U=L5xkfIaf;_q&aUTF4naR1=sBr_fB^ESR>SB;uy z7P*9{oaz_`+!IWwRDBJu_-AC?ws>F1)0B7G%0`igZ<>?u;5!zB2<$e!R{*n*i;4BO z;c%BfB0qn}g!aM8`rMeKs?gZ<58*y(Q<}LZ7y#mIy;(q9>gwwiGQ}Uel~%m4cbvb%o$x;n?!xj36C+FM3!#pB@|hRLu}%+9IBa}YB?v39?~U@dI$B|bifDaCG= z z@kMeSf+!`(&o3vbGXcg(>u^kWVYa;JIXht|zS(}TDnz^tc!?5nZ4s-#f|iwHnsO;= z52NGGZXz!+m7Ef)Sz2=CumlFP3;AcnEn8b)diSpWob0hkmLM#1J+zKHd!77cii`gI z&)vu(oY#V{AlBFL0vvhdr(}<1CocMqia+WPeVox>lzc#VeVLuW%7W`nK|5&(3kh*0 zG*0Uo>87xqc@de+==~DPx>;CQ7__`|1E^^p!(nsu-jsDZ6C3dHI{ZFoWm@SD!=v>+ z{V%&9+yE)&@B}`pjn=sP4G3V+=q(rHWt|a~aK`kkCsme%{-pN`&{*`&7K=MbFm~N} z4t&=L*KCRm`FEaq!B3bcN*Ix??MRRHbadK)m7WHGr^+Eq(gBuWVQ&7MoZNfPF;E@! zl3I6hf=xhQ91L#l4j6`_YVmY;uDyk$en--H3gHcecSlNgoW+LKc$N6gHy7gUCG;mIUOSN zO3m$xW@028%O2wP8`yxC*qU_{REZp^0k(yur_GQKu!tJogV1h2hd*-sF89aFh6^*| zT~*Ptcsfwmtp<<_VEC*H&l(R64L$$B2iu6A@8Na)ll!A{5&eu^Lx`S%fnOXO?)J`j z*wWJ{Kt1H#w1@6&kd&Qwi+td%{kfGtc3>m zT9$?Ydb-DepiQiHqfHb1eA za|AIWKz({HwKK!$UGw6Ha=8JSfe(zCFQH7@H_`XO*qW-obY{pxa3L-WmQJe4sUDGC zjnh-lZ$G}Wh zv1=P}@6^!NnNwfCmgm9bG|qSdIg5r|ofbBqCvscc63D-vKT7_xlb~xgFE_wH5bPvb zkL{@m?Wwm3>Tnho7IA)j_Mad4w8VHtMZ1p}VN)MQae3Rd?kCHK>qo4lbV+k^1ImL5 zVtu!dI3Zh^f$d=4j7;TfZ&oP&&xSxl+(6&S9*JRnEObqQ_R8(aZe>H zYwJ>Yq0?=Q9xr72`CW0c_wUS@XK~@a`9zo`KLMBxuXD2F26p}q&1Vg;ECxX+weut* zEAw1Vo_IC6gM!562=PZsC}7pWE3Y_00Y9EjKwOHm;UllLIegrS``F>dXhv5!-jSpF z0H8(xEqIAbItp02*4MA|MPwf%*UOMbH`YdbDWC6IF1Hg8)zQ(hoo5FeLZdpyL0v!% z8nZ%RRtHZ8-mAiNSQ5|gKe7X2j-4Td*;}yN+Z0_ry@&p(HBN;1wol#_`+@XygnL}$ zXuS&|0#WFsHMrZ`k=^KCgH+et{GdekotPQlx+xNCr^NQ~hJsODj*bIQo;>M;{T6$n zT_156{rK`~YgNHSa5Rz1#eGbAam>aqF8?nhuZ=icB;?!2AtUxTOs&bGolk$ZGf=U9 z1O3wQoell$T&7p9{9d;mhx0`_QG+~$%*Ny`BGl%(G}#MQBXXu2XFkUIeJCg?E0d2p zxLTuakN{5Em>A;HLX`m6J!86&?9FIiBpb0REd2(Y7U?7dhkMEi2y`-^gM*_6s88JS z23qFB(kL%wjh>lw@wOFpK%8qv_I@?ArKM%$V^u-FMyZynTs*%~4tqKEHwYs@dF`s; zX6w<-9)gSk$q(jb-6^_}-d65iF*^u!dQMQz0AAgd3FQS*OlhW;mWOq-?r=K4A&*Oz z%D@eeAshIjgmN42wYb|?Fmp+V5Vd?MoQ?20bCD?bf@N`n(H8D;j)Qvl-3u@gbb#ih z-sape56a;Og?i7tcLpA=s}d~#Z1nyBfQ%@nrYj4jBtC*ZsaMW)j9gmpFI@bafaL~U zA}UTbY&lE8=dAi3%SoNm^`X9IA&Lhfnd1(tFZ21VGv7MI2{jp4HD!)(a zsFza58r&H2V`ai_w#@m9HryYB3Z|w?lAa>J?$i7Uck)+QR`KIKoZtaQuPqPCZfV&<^twyfx32~Fb;FA z_;z>?&8+F#y@oY(BRM$$5l3t8j~$wZ zABzeKI4oFKGsXB%5YR+S*XD*9$ju}byzl^u31tUW0q{5km0_x27hoNYkG9MX1vttq z!c;QRX+_(HADn`EQ9tb`T(LS@`)F2C5odSXNh2D`m~fDLW+$f#n*fP2mWFDKK+tIP0egO2XG707&OOK- zG#E1Fy|Wbc9PFN~!Tp9_w088KfPP|L<;~$|EykG#xj)vz*biK#A^CRw@=;fDxOdnf zYrxGoradDNpSYITpq62=J@9XrtD>rGclnPTDa{4q>V~YUX$XqEjSseDEmYM_(O}R= zfL9Ls$=6*_m5RE7!<|K=GzNQnFWR|ZQ*^h-IUw6yf<`}MA51qnhXANMgSBZ{b9 z4||Et>2EVaAHZwrC&XeF?z(;ooq# z9kI>cMVz&8y(=U37O+MiFAg3eZQ1VNE>l2p)zg5LCcpOtbeD|FL9N|WH$S}xv zJd*eN&XXP;Qnj3%|Mnbzcxe`TnOK;W=#AavsWWnAwK;_%b-dU$4L6ZV{OV|HdlVA# zGui|}+NRQYWw`-om(HmYZ?i|h%EbBBtQ3te|7mS)eWqHp;o}|&!Xn%$LUA$G1S&~= zDL=22GH(Bx4F#7YttV|5cfmU(w+EWf{Q01->sSS{(=d381E%`F;hN`tWAlIUut*-; z9%wgH##BCP_Q=oAPh1G*Le-ng7oezch9KIoiIdmSl$*OBnA9;`s zC}`MhnH`(QZX`s0`I2$p9QgJRLx4P^ALGUNEe^AOz{;Jk<%r)xp~6g zzS7Gw0#j3kf^zCJWL`(X0UFJ>%zC7ayOS8q+fTGheYWq5YO-)~IZ+3ozdB0nhNgjH z2bKYcd7bTF^hpb_SB*t3uJ?7e_lQ+>q}-ADQt#t{4Jv9aJz?<(>OkUGV9;H(r1t=j zXF^)0b`47qrWq{TPfXKhZOSYy9>Hrje;9>m0*rdk#FBq>dth+ITm0UH=u@Di{=eX* zLR*pbD;^sNeM)c8duR~mRq?CYq*7l^6TGbMK;0!UGeqgb_JgrBnrxYEB3$BsFDIvZ z$cQ{)H#BMw?E`U(uL}xFNlQ}*5N$}i;Uu$!2WiV2&W?$bXTzhT{p?wBCnYf>La%3= z)d6H$SIP=*HZZf3u$w3L6nJ%C7A)u|Y(W{&dpMv)7%q6)_NTX3lzz{gg5Aun0hFzD zfO6L$3)&CWDDNG~#D|70iz5sH?whVIy?=`{W^D zsN2iIpa=9b!%GAZc%js6JWPo8C(MRBxe41}8SGC)XIX|(@AR6nXM3PV?e!k6gr}#V zHqk!-FUFZbfoi9Tot@BFvZv8>fidF%_sx&FG;eqPscG&Ub3<|s4c>zWv066m`*# zbu9DUJNDski`p!9qst3M8PTZGM#Mnj#~bg3)W-jDWzZ6Sme!X}98K)`~HQACwEv-dvcpdD6ok8;X#^j{Xxa z%n?~aacXmG1 zV8<0>9aH7|s7U;J32HJvwXMvi%J&MRJz=sTjc0E%`2Tgi4gD%y4~;X`sQ0T?+RMjK zt=+C=Y7ZgJe!@siuS~P8b2I^VDFYW*!;)u2(5*s20ypuQl-7Rov5HThw0^jOK4f7& z$(}^Yhv@5!YaPep-}k7>!o_4*^ra_oT|zkgD1;3?rbf;)6wwyCx_p1w0;(#*7U~1o zBGV36eBFKxTE(S*O3$sz+RCcr@aENi<-rdmk`=S|vf)y8-2+BTmKkhca>drlpgd~hT3pyQOxW8}TTZ6A+YEnT+{6}p@Bl29hYx<3?GV;pO0!0kk{Mo| z(SjNAWniMZ$#=A5FQgR4A45aMzKjb~PfyOP&VMFb%dq5wYg>4Kj zR2qKdqUY9$;qfHd%!OBVd_DGkf)4lISCx^AWJe47(;Rx7C%&x3U!D8XKM`7+nUca) zv{jpN%8rQz#CYOVrQw~}4smyF(=^3X$14rXtj5o#eH<9NZp6;z91G=-l1txYQVimsTzhSC31)%|@3LmJ3<5C^HR_#(yWW z8nr`b^P$_GuvLwb;!oX^p68(^W(E|-lLk}C_rpg9@Z1iNvJLn1f0I$~r&PU0-7T6U z1@WRFoazg|cP{y>ZLw@4-=|cwjHRW-(R;v(cQy6#Nowc#Q2Af1x>3I6`78B{kfr!H zycsU+lP)z-(I}#dPG6yf$HoR^ezWr1KpL*5u3zdUTs;Gtee&`>U(ZfPLXi_)-Hx%S znMla+UvlG1A(^@3rz0f^Sr@ykk^LgSX;--7R*(`J^RfQn4Y#%`R`{-ln#0mBvPJ7B{*c|7(}PL5G3PQuuwDFAw__>_#4e$=4!x#>u#8 zf!FY5rHV^^j5oGz@);?$pvQ$&w{aJh)m*hb!mLAN$2rqd*|l0blR1A zl(3cu1lpC`F}x=5>T1D5h?H=EL)^}PI(FIVkp++xun{lT3oPu263^%WE?op7}?lCjpj{4uiy6z#s# zd-m5ELk3mLCJo`~GH6|GMeDG?@OsFJQ+6e;taTCA3iH0NGC?SWW<|DiN%(^jrRag_ z;yuFlO-p8x8y}KgrilJ#%Uc<{l7c9)2xT~mBoRS^0;Q59mI#QXDwQ0IoP&~zC=!ZL zK-D+b25ryjbMO7m8*jYv{b14+{Q4pPK4Y(~bOjVVbA&XS&wl^6KHei6^)UQKoR@Hy_?*GI-+uF9Wk%^C>E*a9;`_PR$7#6Itv*pNHCzpd*}7#`WU zLr79CBWjflXANjUHiIa_859QZw-s{>Gg+D&+zaxQ*8GKf?uyTM7d%xs7 zz3(dziFz{>XHG?u4&>jpO#U!cBm?lhkvSowt>^zSULrA`O#D^ie$zU41%isg zXWOtT&GtfL@J5zAQ$%W2g7%L)`!@=-RIUv%vxY3ui^-=ZBe`>oi`N#vP#k6-t(lXd zeKV^o4^Pq9agzpxp1)PB7F-Ywj4VS?Gn@)kD(lW6?`K5?Dv~#h zsNc-=p>pbi_SJ0z4t)Dl#=dzenEoTiDo!I$pe?*CQszhYSD-S5Sq9(vWbHQwaKkh# zkRX^3Z+&%WhLfUg*p4^@F%a6}H;;q~wJy_>W_>5Q`1A?J3k+vXiqoQ!HJpe)nBNV5{2I;Pi10(CsNCmAB*y1@}dJnkV6a zao``_n9*^of#UlLz&pMCZ`q{c8#jL6RN2bl5j~IWg~k(94-c3w3NQ7km^OHxU{3gy zc7igYs*f20L}{dRm!#&i5kb>XS{%rj29(D%-8ZppDPL>CyLJ_ReAs8$I`*UgqMMza z!y9_o$Lnh*@^R0MAFhCO*3!I}STez!n#Af6tN=%6812*#>>UCxkH1G>Q2(qd`yRQUfm(RU%C7PFeC|=H`II+QQrJTM1EG#YC>I>^I%~pSCiUdKi0`|m_f!i$8b#K=ye22& zj$4OM_o-nNaQyHQD3YOdK;;Fz%-_v~Mv|ZXDCGq5WU=Yxo%f2hk@E9vGW{dN7H>xz zB{;t$|LKv5tQ96V!B@B(BdKBwl>vke>R(4_+%w02IX<&)yoRo4Z2a&qf9gIsQ~1F) z?~J98!2#)_NAN++M2ChX7k0l`!;yrHVxOvZ$4P;D$s2BGVfuYuw&o-&;-=0Otx&b3gdpDD70JMd7B9Cv{jalngp2Go@@7uG2^h_B1KR z0b8m7H{oU4o6f8SsX}?bz!6fp`=$OQGODb|-YL4UrLy=e;vR9+bq#w4-XpU%}CGY_qnjF^j<=C->!4BNHF~U{ylZeh9GlflUD&ko_&vAbb0`vqqVf-6 zC={YlBuwWMS&D@3+4?{vjN*j3wSWLdxm$sJ@Eq)QRxZM|0w%el{5M)%`gIERUQq#i z*S+vp3=cIEh~dTX4$GgbqM?VtME@A*Ln#OzqKR!O7lZUm6}V-B7LO3AOTT}vsJ2$U z9!T9ie1bANa~cBuL_RN#>fh1bD}mf>@6)j?tS=OEUXd6weOn`DSTZQF0QwZ#uCSmr z7u=i(gj{N->p(6C z0a^i*3Lr6JArGaetNY-GJQVEll8(ljIIKF7OS1(sTp-hmd;W2_1l6e$AcuxZ z{^BkubyK} zq#*~4Dqhxf*Dp@?Q1gYIew^thq9SqE5TJ{HJ*WUck_Y;UT_YM&V~pJ!12{`hCE6t{ zRUFj6ji!K*N7n16g8jJ?A!~bPLZXZJ-=>4Q~=-47VP+h7id zlm}x;;OJeM7KFy8Eoh+e$sV1aJ%>x6^!8U?J04)+QSD0`2q@jLTtWWYOJsVC-Q%s7 z09dY~3N?