From 2bef8f2cad98308fccbec526d3e42b0fd41ca174 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 13 Oct 2023 10:32:57 +0100 Subject: [PATCH] AP_HAL_ChibiOS: add support for SpeedyBeeF405v4 --- .../hwdef/speedybeef4v4/README.md | 100 +++++++++++ .../SpeedyBee_F405_v4_Board_Bottom.JPG | Bin 0 -> 106199 bytes .../SpeedyBee_F405_v4_Board_Top.JPG | Bin 0 -> 146093 bytes .../hwdef/speedybeef4v4/hwdef-bl.dat | 43 +++++ .../hwdef/speedybeef4v4/hwdef.dat | 165 ++++++++++++++++++ 5 files changed, 308 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md new file mode 100644 index 0000000000..78405c6229 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md @@ -0,0 +1,100 @@ +# SpeedyBee F405 v4 Flight Controller + +The SpeedyBee F405 v4 is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + + - STM32F405 microcontroller + - ICM42688 IMU + - DPS310 barometer + - SDCard + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Top.JPG "SpeedyBee F405 v4") +![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Bottom.JPG "SpeedyBee F405 v4") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI-VTX, DMA-enabled) + - SERIAL2 -> UART2 (RCIN, DMA-enabled) + - SERIAL3 -> UART3 (CAM) + - SERIAL4 -> UART4 (connected to internal BT module, not currently usable by ArduPilot) + - SERIAL5 -> UART5 (ESC Telemetry) + - SERIAL6 -> UART6 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R2 (UART2_RX) pin for most RC unidirectional protocols except SBUS which should be applied at the SBUS pin. PPM is not supported. +For Fport, a bi-directional inverter will be required. See https://ardupilot.org/plane/docs/common-connecting-sport-fport.html +For CRSF/ELRS/SRXL2 connection of the receiver to T2 will also be required. + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL2/UART2. You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL3). + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The SpeedyBee F405 v4 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. + +## PWM Output + +The SpeedyBee F405 v4 supports up to 9 PWM outputs. The pads for motor output +M1 to M4 on the motor connector, plus M9 for LED strip or another +PWM output. + +The PWM is in 5 groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5-6 in group3 + - PWM 7-8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional DShot. + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S. +LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.2 + - BATT_AMP_PERVLT 52.7 (will need to be adjusted for whichever current sensor is attached) + +## Compass + +The SpeedyBee F405 v4 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG new file mode 100644 index 0000000000000000000000000000000000000000..acc3f8d957bd7f0a08b6ca037ed3c0e31f47b6e5 GIT binary patch literal 106199 zcmeFZ2V7LiwlBO95y_GyXOIk%B-0?0MKTBoNDfWTxd{T2g9HW1Ig8|sWJN?WHc4{M zsez{X+L<{sbIzR`&VBd3ci;DHeg###YuBpvueGaI+FVave+TX;$|}eLC@3g^C-Mil zUbq95@wB!80A*!>4FG`Kz)ciU;0CgWhHNN?SpzqbbrfV>^=1kjP! zu#s&EWC18Qk-u*LsQvu>MBpa^KN0wez)u8zBJlqr0#f#7UP!*t;!uClBZ!dtLPp%p z-|O!a;(w{5KHvp_goHopf9Mpq6Mo?KQ>XZUQF?yz{1btn2>e9gCjvha_yYmn`@DQ2 zJoiO-_-K*8`FKS5d4a#W1^`lkJzxg>P(ZF1ut=<2T^&WZx$RxJjLjTO%(+Y*?6^IR z9l3e9?sEfTAWuhQQ?R)!t%y^DyaIQ=i9iy-SiE_2gMh&h{Ch^Rl3{jCSG zB~Jg_Ts%BHxIFl{9Goq=d4z?9x$pCG^YU^cdvLmV*}EEha@xBv{5HTNa~D%*Ye!dW z2YcEd0~(t+xVehcySZ7LiC7q02$-0e32>Si^OW*&Cw!hFeGvzk7HMcXjcXdIc!NX0@{p+Ovt7sx2`km-s!jI$;*+)d$ z+1%LG{1LK9{8&&kOt7v z&~BmKM8Ac0>oz+2ZA^SDq>h0}jCThcpOl!KjFgy^go2uxj)IDbiiDJ&i=K&vm7Rl~ zoR*u9n~j&5jh*esASmd!Z)0L$5@BHxu~Cvzvi;Ma>ka__Hmd&3I#d*T;08VlDn80} zH$a07IHDm#ls}@BzkN_{px#8gg?<|Y6ARg)_6~3Z1r_ziO;j|ro5=ViiXZZO;3hsA z0UeLjEkZS8bb2Qu-oW_m+YAq@J`k%9?=$k5I0s>1-X$R=BWJqD%)-jXFYrK6NLWPr zk&LXIyn>>Jrk1wOQ(Zk%Gjj_|D{C7US2uSLPcQG_7a^fxFT*1eUL__ar@VfXnv13UcvK@c|HUAsfMx zbt7(MgdAYWiTGLm0RvWRRx2PUg5_V7JpP){08EygpXDDh&{Nd=OEF@_;iSvD@k82v zmcPd!IU)J4#YkF7{;#F)uO#ySrEB?l`F{`L-$d$v+eRkcqyFmYyYNr7oe7{O41|_Z zH(!gM{g}`Zg*C%Sqts*EzDpOCYalZg?mB$cSa=N#^&v#Su{i;vcsqk2gg@wDRPJ;& z^BMrrz&0u*B7kjBJ^wXu4!Z{Wlxe0@A#gZksi5J41@#?bX7n0ZTe=3Q_#yVz*TB)i zH4u}!w4R0A_5TMN#SHOG2E$EFr{=;$DBu3X;hz9;I#xwD{vAfEKM)b<8u{Y6dv911F{JL2t&nm-5J zz+H$Drkr@toHYZ}69o|{ml}edHq_b0D{>YBwCNtdl)b+sd^0o)_i#i>y(%L3TYII~w)cHvG53^@$Sm73`^Ft^>*%i{mA8CCb<$(u#EP z&I$Kl+cBx2qpt#I#bR2PcKKjxn(<>8Lwz%1Bw|E1{D#-pk8%A|o1(GOl2m9#4cEYn zAecnatDcpf_Z_mR`mZuy*ExImTxfduvwXE>h*8?H=$&O^lpT4JC5()Wrfs|=Ze*9p${78U&VhC|&L#G_HzYYu z64FE*mx4MLpJ_As6;em2V%74{*r&+cOn0F}cZtSbxxG`xX-ChDxL;iERwIN)iSFwT zhiTG6toj&jb;cthW5W8+C_8aHu&=ku>%(0|2Omx8f$#DeveHiXiKL)!=oB;t&E}F2 z%Hb!~$x;Q(%sPs15$f&NMT0`^ZF5I=%1uLWS&@?_ks9F-kYGbt}~DQGs$ky^#Fj6AJM9*M-zM)diL8o_qP_ z8+yFCHW$(5aj$m$a#YjW-c)$6ewpi9?2R~8&2MZQ-OX*pXHjF3B*Q>0MsGD;ClLvm zsH(8pT8Q1TULIqr)6ey|;ic9Wg3l5k%(BKD<1!Z@jtSkwnl@{w&Jg|{XU-TN%#LTm z7Sb1f%&z?CsR8)G{W-!K{npN~p#t`3t%(-Fd{~!eq=LcSFG@0vHT5L;@(c~Vlh3OX zh$usM`YTf8_6s8MLY}|#!SZ=oSg#>ENa~TEE@fdMmY}dDd8>JG3y1L8CZ^`{8+@6SV@J;j>h%1#)oI1p)=lB@7GX)Jen{JwrtjKP7b#)7}eGr(=m zokQ$~KI76%s>912<1t^Yg?YRg+2F@Xmd&X%Tm%;3QjeaCR6KE-3lOZCzq1bgoFJEH zQ|B>6Gq3LzoOBVW&2_>~fqm6r`ShQbVkc-9l}$|+CrEjs2*6u-`rZ^ZeQsaqa>UQU^?JxNDU1( zw_BKAUwQScNuPzQeBM!Ji#?R8Gl*|mfUCWHWA64>JI)=$i5UhNqPvG}Gkwiq!8UZp zi!nX80(x`{%?qu7X9o0aQD|}9_dVg(^LJ=Njj(e+64?)U*`k=;3@{@jLize_^MOdB z%7Zj7oEf&B$8injH+>?C!HWjCXR2TSgXF?i*q@YNw(fh{nMuovpbSkR;W1@ z+}(w$?XZwstBI!8)igWtknTf@hkan23$4lX(>Djb7TKF& z0kj`D@JkYWR%AU(E;3(ipKvPI8c3XOJszvu1~-#Q9`SS#(4iSoFG(Du+>10XxAuN} zIth)m@z#Gtjg^+3V`U`7(j$r8u;z|tHZ@Sc zc!Cf86ZyK7q{r95`)_)i>`B3Euts-{Om3N%3NhWEr-l|Jsh*a%Vqov>zWB zMWyK0114!}J?-^AUGzFRS-ZX@?S_5$l-ZK!D3@=pvM>uVJS_LsD4wcIql{#j-q;tR z2r8r%Gh_&6!|{Ub-f&_nuD(QK4s$Bd-!;>tgMkt9ao5fO2(je zA5rO7uDdD0GRA31?(>F|lOxA0+KhqP^zO=Q?C*|f_R%6UU~~;k|1mqnXMHg*pROeu zHSHo)kpU&J3ehHcRUGeZpKXwsbDOI1s(YZl>HAH&-QNW6BP}T(gM^h&G($ z{rA8CA>!d-Ny?Dkz{Pa+;p0J5!)g)N$oF35c6y?3Mw=3zjP-BI`jwhoN-Hc6%M>el zx|Sv;nPPp=GRT(82P3CCcW;=+Xn5q4@Czn;<4hke$avkhzX0e|AJS>?pn5g>{nJPl zcFG{8`DReQwVEUuNh-U6XSLGA%@69mSTCav3ijhdLOQ=^KfehuwgRTrXNk{JJiRj#Lx z{zPHD5%J~&-l^$N)mTat?oy(~pWcwgxCeh3o^J&Y=JU6))s4f4>nMadKYOl3KG{n*4%I}!bWS8}UzM^g0f zo|8S{3%c(oKbRWg=Hw-w5P=c+|BPI?Re2T2O?J3S8iOV9EeF$dA z3%SDt{J2${8~2m*!FD*yq1I&%&$%)C{g1LWl9(Hob+lvvmnKlyUhc%S{sGRhPHIa0 zsi!uSf%3t@s{|qf1;&$mS(#mW8EHkchMr35LBkG|1LD!k_vFc?CuE>f4}AjTz{NQM z!h@o6W6#IZ^bhV8aP1lg=0;!%y`c@n<9N87Vj5Gpjz&#X)x^6gvRjNLIO~~-B};=%%q$Q@TZOPX;S0D3kQkC$G*)E*XH?AM%3h4tpPO|qW{*SKBE2=MTSWA zUle(3YaD<`P3FJ72#gyjHelyH4-%Qs%%FVl!BOxC{eAt7+Vz54f^Y`y%%c&9%XPJD z;P!YS{5TD9L0m0E%hSFjD^XTgVyrq&%TzYvY=8R@Jm(BHw3SaS&(Ll z%_zcK`5N%U{FW2&Kj|K}^nyqSCod1emO$e;w(l{oD-tIx(yjqIP9;P$-pb?KkiX`S z6(#x)Ac!EH0!SZ-_`PeOEyNbN*Uj%o>p_MT+V`^Meg{r_km!HJJxg8g&kv7i?7HCW zPv+*>tsbe;KB5AOt^V3~^*0~Zf7Rdr1??bi!VG$nr%r^jJpI9(Qk(dI-*H3aeeFOL z6DWi{QCkkqs6Bu5#i$<=O|u`b4;d1M&^^n9zUDrMMV=D-kRSii11ZB8#P#r_ltUtj z&GYuPMLc7js!AC%NT-b5H6XSE5BYrrxzhqHgg@>7Edy9gZzb0g-bQ#1P~vn2fgkA@ zP|C0!tmd=l3O`hJPq-VwQvUIGj}R*cV3xtobq#bwx!zm@G)+k@mY2;RKyk&1xisNZ z?hdBf5laQI?1iFmEGMzH4OC4KQk@sw@VEy2!Q5qP2;)Pgs_Efpa&XRA+zW$iU_Mp) zz_hC^1#-5UGGTQM+;>*0no%?K@i{2$OeUdzyn5#Ubw>ZyhmvbxzqN(tYHJUEOW>=* zhNey`(&=!v4>_xB-zOcu2C$Ys%+Ix510AN4)JZa4g>ddnbcpxmHGmRrZAC*O#{aZ8ub)=eq{v5-`=wu4QHY(1}huo0jlJl<)_Oqcg>Dby0X zQ)Gn6I70U8;eywIO6J*O3gRwulxtw)2m#lo(anYTAkmy1e#Q*vL{hp2M%S)jxrn=G zzjaYNNdav%;~nM)2>S7CeO7OsvH2i`s(XOSCq`^MaEN zqM@usTlAr_*oE2X^y&Hpe}BZN4f0A6DzMwhkTH%ptLgaMx*$-~MLrgKYcE$ACU3;T z>EzXtxfl93$if^ zde{W$D~8=8q?8N_r2gt)S5i=tL?crBmxV4rkN@A&HBg8@(od)h(cv9dFzVR3Tm#ha zuYm?gk`sL!=w*Aj%5X+9mIcz-Gve?F`7u6mKm18!#%PBJq23@PL1da19%0gR>~%bb zjL@c~u`6Y(4QOhn`{b;{5p&wyJE-0Q(n{zl^OfE2edBHMpjvOPCB8?ruc7E6uV!!$ zcnXH~aMU5Yr7md4BBU$Z=iBQW;!?IWy|u2zz4(cFyW^)v;Pw;~uQWSG*DS)XgvUhG zB0=m!E2H$2{_LBl-ce_v&}o(W1eWa9WMXZL=TGp%@|DZ1>*vtl`#DIqw=`DOUag#_ zc?rK2GwL3$_C>lH4&?=mbfU+ETUS$*1vY#TL2EwK(v5j#>8dt*1#ggh_U+YdwAT%E z89R$dWG3u!riN)Ta)v;eQP@`nYvz~bOf5|QnU!2u8ZdJRN- zo*eA7J+*R`&D0juIq+{RuOjgnxjl7&EoTyIi`yQp{i@5mMU_miR}z@{bYEAl*f6JP zdTmF|E~;NTigt76xO~BTa_&KW!)SIxePi->ui^f0ABGqoFyS_Ls9lBMJHVXpB{1Mp`2r0ys8zn?t|p?bjGj zTe0y9!NI;@Z^}uv{-*S_PXQs_xeNjy1-bm|SZ$vx?=LAdzEH4qa=Wz<-;5JmBvc8S zsHq>Wwca*&qIytjz#n^Kk$TSf`D_UQIwSS^t%zp)xWJ+jcL>1r7#6*tt$cS2ARiCn zkf<{c&N@;CYeokdwO8=c#Y}=Nbaa@(yh@TRQC&?E%b>k$mV8UM zcAVg=3ns=BDdCQFo|#EJ!@&JMy_OLYwYx#OH^0j*_jcP`s1sdD2}DB{6lWu1yQ9HI zxHcYwar&)g$#d@V32tmzD9MZ$D0+81eUw{ccEv$j39GAf_h+Q)9-Ig5s|c-))UAvu zXVl(`EE-~!x6K$?Tz#l-I|As2AEV!Rvyh2nqbIPle0I=V7dqJS##~#QHk9N z_SDwbD)9bcFB6SzW2(h2AtsxrFJ~4-Y;|kYI_%SVPw2rWd;XEubKUfD)uQL!5yd`> z(e$!W&y1j9u|jm`mBNa-PtHU*iH?QwNIXrtlt*OdGASMn(3f&8O5J*26MNfWlTVU6 zUs-~6XcvBP^l_doUB1shX?$yreRN^OpysmKCoMrPv4Ox2G}l+_q9?O5^v%uTj^UFd z6(S?c@Y(ksAN$rDD@wS0GY%4W{4gI-GmN)@+_&;JT^OxaB)_NyfM&&X@;n_DuUbDS zLGE;O&K#V+Ml4*!jQ7gg@uy=wj(2^{z1X6DmZDy4lKB7=+iwJ2;NfJKUD@U&I2Uwr z(;1)gFo?G`tXNjl@`Dn-Lxu(kHnDRW(1DPjTNYanl{X|3x@&G
ThGSusY0WEsK&U8ql^!!?=!H~nedu&_jpd6`lR*iAM&QH z^3rou2hoJL4Ay(^D}4>nu3Q5Z!RO>hN1!v2jLG29QOM(Q5XHhsM6EAy^qxrEII3Sxy9`e(b4yh9CO?Ws?IMSSyUi01l}0vZ%kF)hJ3lGcE@w!AD!t&!b;-6%AsUqyU z6V`4nQGD#v7-@(NnG>55*4)x_9G&+1pUl%|x@WklyKk+7f^osXwkK4P_ri7)KQw|)Ti zYl&vlmt~k|*tK9NHt~6-BlCPaBcwbeCxR8w+PM>7Digzt3t`LEIW{`Sl0gQ(84NsW z&PpJQMsL!M76!g<_8^bdLh3tz_2B>KEqIwfpW)5mOxQ`vRTsQ8ocLfy2CnEIb^K1B z$0{e{+@?%qPwLH=&2|fBqadW#!#3@NzU*Kp#)Div zBZ7$|(&>P(JzQ|ss4uH|{(SxniC$C!EiK2{5Itp-b7AmA&V(4-MMZA@Cce#?wnvjI z@1s}UFO~K%N#kUNr!Pj!U2*iV`pwgN^g_Cw8Z1Hz=C*@6(ud+7^14|-kR*xAvA99%8SXk0{e?Hj>ET6C@f@E@{efT^#R8?W#!?Vq{-WKNnFe`!0W=xT-);W?>>yX_Uio z)l!P_Xqn5$?9~P4Y`SssgiI6G^80vN|1_V~aB>!{wfH1rja8R#asn&^QRu#WCKGUs_{72G`uv2KWW z2YoX(;t9+4)vgbfpxmP7jpjPh@uQKoC0#&<^kX&F#fP>G8?#`{T?q1U*`$Il$_UUT z?{3`Xt{CEJWnOOJ3!U~-;e55$*o?*c1Leath5govu3_jcUxa7TZVmTKmKPuMY}5+X z8S1ZrEuFEv5Hi!iO=SV|=osR$Obg;!Qdv=Uvf1jT(zI5WC$GzA>L(Ih=>}vW`I?AP zqzRh&@fz4$sC+Mg!_}ujmu#5A1WCG;a73#!F2U+A+#k zede#Ofe82p%I=s3eX8)HuCZH!AeoLvT-O-6-@ocAyj9HsTIMN&w6uS!8MJr`={Hrq z2D~6ifc5ad;oekNeS*UH9k+HFMCdP|yY4uY=c%XJG>&VUu;LXnz3$ED<4V*q06RIj zA+&?{qNccBnTz~dFVgO4{Lcra^ zy4I%mb`vQC9pBJ-8a3kQBPwM813y!>_;1VYjTWW}gRG3H4yXBNJ|DxbY6N_`sENm0 zj7lrgbM(pb#hNn+m=H(QoozAuMjyEGJZ<YC`PaF6?~_fg8RfbWC$5iXc1Ng#O*?mMFCDf|-Vbv^2UMEe zeCicE&fgxQY-hPrfxo(rSH~)cxQ=96U>y<(lU@Vl-^I-LV|DhQrfBWI7%|!?!5Xq= z<|aQALeT9Bmt|sjHgvt&es3~#p`0eDavBChxGkDGpF1CE__&G`O(=ZJ$Sl>R=)S90 z9?3yyCdc*NajwNxpx62g8r!u;cmqqpcG(^^kQef@0)e9}pe#X_lcDFOi z@`>~+8|f7KeD?Xnu$r@~2PoQ$zr^{=@YH&u14Z?eYq|Qo&ZtRCjpM_B4Iw{Ddb zF#S>+a+ewXXZnh^&Wg?0cK#ua?!BWV@tHEMY->vMm* zV?>QmI=g7=o%34d5mNr+%SWyKm!&8CK{%RGX$^tL7$cQZ4#X|Sw33nQYDkILGXQi*ERjBa`_{4mm=*$u&yXF-S#zH4Cpq~cTKtZ8Ru zv1jPKZq0Z_&2)oZ>KOm+=ti=7%3bsZnj}}_71EDKq6PwI@%+%Q>k8i|(>yJ^+*7}_ zE}rk&JLH&6GD&h)%rP;TP)lxlZ5fz{hLz~e%LxpHSMHfS^w1w5GBygjFHg3Y*;!N= zY;WgACA+0`Ky?+dNuun=p(aPcbqFjuGG`IjlF23{YMv<>_*~#Ku2>A$BLnUiy!_gu z28xVvJc5EatW@Y|O_-|)0?5bvBiFzj(uplw>##v?ewxl7>r*~!V;lfY!OwX?dqN>u zM#a~m<1LXwomK#=)~c(Hs(QL4|DLxyJ|XYqUP7WdMyJMj&0ggrcuVIX{|MEhwahgT z>&u<5Z@gBQq5NumBFMN~D!yuu7 zdW1+$Q#n?bHzX`KZJV8a$nir3R|O-lGS9Z|kWp3#byA5Yb=P6;bSHZ<+vY^uto=1G z@Ku=cL`WqpbrNb{+iY5}>Es0+oXOEG*ENmhPLJx_eYa6R(LAi1DiL`r`gD(O7BTI^ zxwMD48~<{XnG(^AJ z%!H+^TI#@@k42hTa@wDW(f(Dk>VH0|Gs2DAfxc2b5ARdM+vne-@S)AQTIQo1YjG{_ zSWU+c`ObC1Qdg>b4?m?TRIF)JH|4v2c^I(;s@evv%|iGP{1DTpkfA1oB^=y+4d_%E z4bt?%W7;b;w!b|2(XH$syCHp!zx4{X$LK$y|V%? zw66zCJp|!{c`P5-+ghIvjy%NUy}!$zt`Dvx@r;;$!Wn*IJuoALxUG|XB~+PR&S_j# z9WgN?5J9TSXq6kH)!g^0 zZ;>RTV3^+B2zSFCR73VeVp34;E~H6x($CHT zC%?r}U$&};Jmis7K$bi4IvHi25gx}bBOw@?oL~0X|18s4o!2k^KAM3Mil-fLcs%~t z)htzp;Q%LfeLe3MqX_3jYT+fj`r8W6po5m>zATWZpEFn%x{>d|w#b0}-TB3`U{l6o zxdvnOGwc&|+6(gMP7neKYN+R=tVOssr}nHuU1q`3Rqu($h0cJEd-c?u64--6MvP1S zk$p*5QDvQ4IH^O6kihp$YWTgn)ad$`+e=tf!-w{DvFAulfTn0^p9p2iHHq>5fQyKf z1BDVt6fyoS-SBmwd{(8ypJ{}DvTcmN*t9;D8hi`eWaunF*r+!^7|J#SHCQG$Xv^im zuJhpfNc3&tjsN~dgaZF`LrsGlE3J7=hIRz2ikvywbBQ;3Xo`v>P5X#)^V|<5hEJ8z zk_NUztx2rnmc%UUTMb6xc#Fz93W$-><2MC0Y`T=s$$(8wYJKW46mVxIev91q({K56 zUdegO&}TOe5U9dN9g}5N^EDDF{A^9TNltd$2jW!(bZ{h>JkpG3JReA}mSgaxgqGiG z_eH>IN@0TPN}M)K+VO&YjF!$qd%@e@U(tu-e8Kztn;7GU3>%y^5s)NgBm^tAWB!;z zU2R-*A3 zjdye#rLT|{2SUtTZ7d1--y}~!uxA;!u7RvY$UHKG6%(}J3?o4Vha*X3!r3FLU?>Z- zPkPx0LERq6oIS4fm1v^UST)_$%ua4ptI2D?WZc)1vwWfhp;WR9^`^uGjv=sTZOFjJ zUk^9{S6PnINmipq%BS^Z;lA>`;t1oi?Ysq>MmlhV9?|4!ewE8I1^g7Qy%W<&E#eB+L!4B4i zX=Ggk&tmhQp z05CV`uhRL2vlUDxD-8uzKYbv%NiDS{NfrBdH__}j!ZEG^sj+LIT?IkBsxyxPM=97O zn40&Tljq8&Rls7~eSEQ$FX>P2D+s(=>O&nX%EHq?uFlYRl?&XyUxenzV*S$m1(*s7 zB^btnpM#3h4s-XJPV##K0;?p&Iw2te6&)Dg_w*a9?0%NLe7b|YDKWxY(jvi8$aRZE zu3KhD<}uZ;>xRVT2WP)MCtj9tc2F42u>|O9pOp)72WGg}c~Mck03mM6y_b&fp<1GO zN6^mJnU@81>>ljfcX`dsodm@2bbsHuj(Dm6upxC_bZ>m&+`Iz(o(w+S#aiY_n=Lvm z_0*tiYI~r-AXevu2%->E+S<3{5mJCWd3iAmzY(ESF78DlSPpEJ?U*{Jba__ihS(dt z`P@KR6$BO5A~J}^;-12d2SYAytmmdi_IVi{-s3wyoqBztIrV9pK|E+5jj_LeexDmZ zX0I+Qmk*c>>*NjZ84uHque@MN>MqAtzf0zB)EYR6I#FgNK{5_kVjRfRJ1@1*E=ZbT zbV40^iFehyV(v*33Cxq5o3?_Chjo8#S8NbZU)p~C&WQK2VN6+@O=15h& z1x=fX2A%YYA&5{uPQ(Oe&%s_js~xH7|C~aCOXSoUv+WnKT3xyh`L@&XB zO51Ve6|jyj$r_mGiesu9D?vM9Uax%(q$qQ?TC2!(MgD`Pby?kLZLp*T>p*GmL+A z?3&TBmX~BekAI9gA$XdaALZdr*yrTH@~Me3*bwI+a^c9+;u1lKhuyO>UGt_j(0`K$ z`klM;aKm4(h?slAr-u$S1WDRX2pl2p0rTG6grRX5JRv0Z7RTfWP{ z(;t@0N`!J`5x!Vj$_e^1GAkAtqbT3pQok+(hRJo`oe)V{hSroZHlh;7XGjU7k2EBX zTJG0J)v90{61dCz=0GATi)pkf-fid^WYp$CjRxuSsyOQ3^Py?Y&}_O$>)nB`|xGk&ksD~%UN1byKo8aUiutGAdcsBJ{fGI zEn;?oGS2_fqW-CU+aRO!$5s1JyV$sB-XtGp9}g5hn-aC`f5pCCK6G>|87uk466wyn zk~!--@0U4&GJa(J#7T>2oCPbg5Bo7rDJRMW67REh+>yO4zLiNRH$9xh4qb0hN>G%; zW(Aia`ra{vEdEh%KF9l;PJHa&s8TH~!d~_#CHE@Y_!^MdI?p`Fy)x{9@Iz=0Y5wE- zu9|_ve?Z^WteyDXDEQYEY=wVsthOJsXVd$)ZHTacLJxO?Jk+++x=n_OA<;#OsBQiO zi{hOf<68B)gOVFwecl_LW?IEM(TWM$PcDoK`@a-$@dhgpV(LjL89np*@ShEktB=(Z zjh1)4o7r}Z%xJ%|0h(o;?H1V=yNjdcvJ_Qd^4!QnfadDpF>YPNa{B^pI|2?l>!I0? zL*{GvgDw{XM4;>mKi-?U1}>3C(L6GjOA2y@v@!M~fGw*EB?JKlvW`3weASSN3pm%n z8SD*kcij926_T6(02y@U15{;^F3*zu7~;vmOeg)$I1EG61MlzW+V|I1 z=AI%@kpT+Bx8P3_+?G2JbT^KWNp;Ui&n{~>!Aj0yp>U>RC9}@sM;zQa1G0lhm2Qrr zG#k1iXTjXAq5@6Ho|aJ!(knrjuSUzgIYbhkZitwfkXa^sGT`^!S%wEQXN+eq1r04E znnX3ElO;7pc~1^$B(AA(ZEtw9zlPi{(?06e`;z0R-AlT|aLW0S;gG(SyC=2ODuZyW z_ICdfU0{^g?y@mN!_aU4uGE9ra^*RtuiePN>6owj$9*N1^|Rzp^U`dSQ=G){ore2& zqnZSRw{ygXMEr6*#0};XR5lEl}e?bD_CJ(wCO@! zIWF&h&*@8~KSsI%!nQ?oWd_lJmn65K?62n0WY?x3bx7Ay)K!{LR0K0LF?mVwV8f*~ zpijbnu5>SIu>@xHI99KETynCqT!5)I+1hU60lO19*CN%?*ai7&nS(w5R+`TM>)hNT zK_z98qSi`$3ws|UmxZy4*!+pZ}oWhMfg(Pt=-SuhOU;Pt<0riDcmZ$kHRMO@r;uEJiQ=dOZ{js2~&Z^`jHj- zCzZj#>8Jz4kOPv%d+8HL1O#}*pZG#=Zt(^D0qdf||NCh_9P)Y_C9Ei#yliXkO zW_-_HY<(lvKr5du^GF6oOBNvAh&X@*9C1hx9+*}5KZV}2b?K13*NQJ@o;7HnAXf@a za>M4kC#sY5+Qp|%b}Ydsv5lEg1IFf_AYd8cN&bL=N#%7*FtnAR1=5FL8R7EfI(3J> z;2Uys!tA3|ZpfTt-7);2XAYnHINzY9pd^i_7(?MhU=od=mo)dV1jT*EOQIlJ`cuRE z4Ax<@=%wfV$de7vW-v^rsxEqGmn&H~Cu#g^jLs_a#h8xwX>#32a?6tOdgG3vvRAFP z(r4%$ZKP6u{t$+$ptYcljk1nPp30JKL|~(F4qi!1>)2WaWr{vN>%8yVTUL!t-nmc7BUKDb zr;Rp^z0`~=xqnN|rAPi^^|jPB@Yv{6&c5fDIMj)^E6 zLFW8u8|m4vv*UJlYvVN=mf?(^kE6-VzjW1;QJ*lr!ptt;y8EEsozsQy5ov#fJEf%q zM6u{%_cdhY*k4NsI-I1`6Y-XREc>QvWzUvZZuDIR{&3WH&+c{ylbw{OHGA5pX$5Tx zB$FiEUtgjNl~a4FXSb3x*=@CJw@aqcq{Z zoXuX>MA&$_pY7*0k}tMm5y3Y5=m6%5uNEcmra$?cTn!HIF%(9IRaLD+l(W*E$_=~z zRzts18m%$@%N-r*P>KRCLXC*$#nhgvvwr9T%fltDHTr(aGvX5-DUgFD!7CSsWiYp5 z3>GK#1jW+?(g~gyGJwzcbmWxbgw}v_l*C@Gi@PD+NJb}B{cC8p<0q+`P9x0+;|nYm zx(sZN9%EuQakDV)rxA++NfLdm&@QnMM)LJz319KTHH4qZHSiV9DT8r>zp+KINcyz% z@x&hK?T~Or(?A1vq_C0;ywx>*KPT|fNQUS+`$L`-u`q4i&F;JRKcMx%tGXjOCLfzQ z=DIAAe%#YgqHq87owxobew>UMm5Xxd#VH0?lrzWn=dwJvUY@PTem+VxJguaZ8SKIM zS|SP6o7T5~hH=50(39WE}u+mef4!>diBOM z;;XEYHSq4m+Rc+n5bBpLnqW?54k-LfCpIh*dyI_>EpdiaYLKi z!>J`k;2wGFlUT-#r&A}NSWrQFNDGO?liWb# z(HLWmk5RHCbs&p?S9{G1|7N+Q7Tl?g z)TQrZ73DR}_~Cm5#txzB2j`of=w(y=7Toy7&+ zrcne28}$#2t+>%TYUtWNF%6|e!KYD{Dxc}7EG8MjwC6C-bzbf^Lq;`p+c=vKWL8#M z=D3vlmoeVY+SB2)Wo<_QfFGLq%;sc$s#|*WV3&fO38{XsWVcVu6N!QV)>k2nZb0g# z8^_R;HLQQp(~h31dj z3{@lQb6BKL`|0PDKEW4r4TUwLmls;JMjY^YDh;AxbO zZQ&c!Vcwra$Tg?8iiLYaT51>6iXY4iN*6dOSow71#JT2IR*LQaRm9|Yi z@PO=IxZ|&#RHQb>BH#2sHaZzXp2@w)jGchrvT#svW8%%v98KUbvK~V1NXZ4?yLkAD;#!|O0Oz&`M1iE0zIPBJIIdlX- zFpC%LTsQsi)Q<@e&^LrWh&kp#Mq)S~mAyG$QMe!n8oAmFx;!8b0{zi7>)Jl`PA?a< zzwplTg)mbm#rV^1L;@`dT~C$yzeh{eY}_OjKZ;tKtIFQLS_}85*sQ;;EiT~_CkiQ`^zaP^uZLQcDD5L<=K+) zj1V_XT;Q}qADPdeP_@8)aomnPEYt(Ip|JT!jbjW|$@*znZ(`_URcn19_b*tDgZxTW zG{?)1!2*qAW>$;VcWJe-s6IR1LT@GSePvy-!M6cTqz8K?29?8^tMQNyiREJm{^lLu z2cr)6+)__P*Im!^;w&K-sxRs%9fVI-14K*M(|SMQ zWs;k0GJ~?Mu%Wec;^!hW!C@<=#+0;79{JjCublq=cG}ICvlt*x)F3=V7SxgwLGrQ( z7vmYP*H`r$mg7lHtuUh2j>`0}jP%B8FUuLaaIEc4Z%TXkc#*}SJ0(TmF=eJqP@(jm zuoV=khjXM;_Zi5OFS4_z#B7c$_KBpocY0~xbQW>uk)#?Y{*4C3xYFXZf;&U zc4z@OW=^$Ee|jv^SCnLR2noq|c` z0}>U%If6!La|Yci7wDUC1&6JJ>{T>tyJz7-Bf(i$llcVi7NF|KbC|iJ2J6KW{Qymi z(YsAY39J zbFD9e`fY2A&$EqJXHTzzZ+q&RO%wceAig}0+u~uLAg?Pm4%*&c6b7BJdlLFC5^_ji z)tslC5Fe=o_$nZ?vg@Nc+>oZEs{W_9kashLFt^IG;fbf?!@&&LLAX-XwI_x6X$$F! z;`&`8e#gp5sc6hwQ8Z)P(cQ(=X2j`IN2#OoJc;j$=E#2*{xJveMvVV5d&^{q`6q_y2}dpg0lt=B4cju>E+)DJwm#vUF21H zE~lM_q{f&M$jBz&O51rLD*%=JFy}ok z^xSILEN;p3T&~>HGh*CSH=h&twTw{A7 zKdPlF*cptik#=k-EV5k#e7N$b;ug@+$MN{dBcDZGvB=#{%h6q9(Y|RC2EK|o@B5&R zTvjZ;&do2~{>S(Y7dqL#jutA|8%(6dh|$>WK2yW1dn->kPle5MMafc`8+>bQdtx0G z^6(4KNDhe?Gw!%ch`d949a}?v4d|T?kF;6j)V%pd6@cxU$5L1ld_q*CZH{v|dWrO$ z`$jmbieUSpArtF}(TmVGS;cA)i%9PWeYy<5&lVGamsRpLz+snfoo#qSD;pUT4(a=< zecVQN;a?PPA4#nTaf0l{E8@$^s2w9mWeO1-P}${PW*t*UY5V27R6S&}|I{x;Gk)!? zLX_C?)J%R&s+A~|(*8!Ro{#pz%8M&qa7P=h{MOP&XEn;p26SkPk48hXp|Hs=`hqcju+lEr4Ez(ll(iV!l6em!MQ{1%$io1KD z6n7|4C|2Al8mv&2_F{gQ(l&V7xwmRh*L^lA4)nZ)& z(6l0i){R25rTL31r1G{7mr&2^i`4ZmXyIL$mDDSlKzp}n&`L+s{Xe`Zem z8^odsYbQ++Ca@EH>atrf?Tp;(LB1^?26$|vJrbimwtP0MORX!dW76`0Hfov)o){d@ zSJA=T4uf@X=Fxuc=#ySGtgI)W7nKnMym`&iVol#xKM6;7=VQ*JJLaS-c{?)%#$C_l z3k~38d;t`^pGAvx z^|4Y+^YgZzuby+L^o+XAi76`MImK6S7Wk9qkEW4d672ZR_7y!!f{4CwGqAL}#P!}N z-vjhoA7?j*J7J6DHL}F;E+=U&nZQuTpho1H21M0*tSFE0yKz?48LbloI=9}BhS3`P znjPSNoLWfu1&fSre=KGj*o3i;cU2m(MCBoP^ycdUd0E~sf=+i`B39ZIu=_x_yIW70 zYa*z+_Eu>YqlVhgdCOD274QqPKqvXBsnzK2fA;mQiUC`8AWl3u1#?wHsa`ebxHOY! zNq499sW78!p}w@OT^+1{tk)qcQ2_@opR?PcK{6fMbs^u!>b2!IQs9mf(aQTs7J8Z; z{aVmoY#Og zbbpcE*Oc#^I|&9kOpRRiIHer@QsUH~)ZW8_XCZ8}3@b4LGX(ebZTM#BO6Ow)=;%2F2;|y>0}> z-a#PKvjKd$1G8X?&|mIPq-HBg$B*dY05=>-_|O>d`(n}TY5| z!iJaxrSp9vHiA*()t60`q_7y@f%t;yaL^)9tS0F`06@lOq?440bqTp&t~#`HwDl+e zNSBsr9KC-!(?@~xQGmKu{uZJN1eH0^C3GaCW`_#SBP*MZ`e}hXCVC?N`j#BUp{)eg z+Ra$rD2RgOt!?wF1%kY~h92ThQzyM{nTmS|b9HqTtq>WvL;zM655gYKyuKGOzkXIe zY%r1)s42f7@%}^5ya6#&|6_B?C({YqS{c6QT}8GmR#R2{Cw8pm3UM&ep1|`8OhW6| z**+CgE)9}p!LcHYyW9mFcy8u=Lnp33Zg05bud8E03J^IGGA?ps}=C;)ezY@pCL!U$lN-@j}a~ z)Y?yVx{(inOle2=+OyxFfXi|>9t277!>)&rP@c+5rxm+pBSnu`{I-_bEid}+0q?K% z2encS9yz9Y!wYwg=t`_$<$0wxEs~luUP}G#zPZlml;e=(ua`7obM=CgHqS~ zs>3Bj%3QKypgZOOgnbv4P{;i?`_flMUVR`j%qWoYbwb>ShDPFxF&e{zVwOCyG`n?9j1>Y~w!w+gJLL1pb?J*W%D={!d5(`f| zy?|}dGyMMQ))o5Wkh=#Q&}E>`2%+xpmk#I#sUWEO%sXs&p23VBIH(RLg^fI8Ab#7* zfpNXr;4Na^ag?Vk>_;BXKg*>G;cXF5=+T8!bJl)UGT_+JsnUP)Bw>Se-TS=a=~G3v z5}!Um2DI+d)?yIt6+Vla7;W9g0N)}15F_SC{RW8vGK?dDWh39Za74KRX}LHp-$>nr z{qbvR_jr`n9icRap34>2Ow=SdgUFH*6p+v9tr0!gtv|QmtoUPXnv8_+eIu<`Je-9Z#if01zmo*N`i*c#7JDdj29^p^_A zr_8V7tDWbTL9aB8o=79x@&RZxj~FP-eC>-EWW!T&D#ZSuet)F3NcIQQ4Mf8fqKhr?$*vL|IwM zfvc=>OI}EAbgw;-h-=%4GqhrOtZ|30+kAWhvo5x*B0aRt#VZg7EBl5nPd;Qo-v{c; zJeCv@LjhEGf%ntJ^u8MVSr}2qIBt7S9+-3-@5Xnz-yb$9{K<*C{>)wlZiyAFwxG0Q zL~-Tb*;oT%9Wuv50Bh`n15Y3!)4$Y~}*42vP|JL>L5H!5aH;ip2KpZ^AZX!6D7 z5aO@3)l*uchUM4vX1X0IVM;?F`}G_vV8uJ5&$`sZ>7le{s-!KTC_Pe{yS1)O$5Dts^S%_sLj5{ zk@#SY@4HGL4;t(w`{E&n&k6#z>f^Ovwo-;^d-1sSMt|2Mz3nz$EI0@2-DttT@2$)ZL!(UyFjBA}7qn>9CwBBF29h2z@B5H@n=$@3OuMa5 z-(_fDN*4UQBCcnj(o~0Vi^=;MNXxCQ-^a;>7Pn?0W^dmz?>(7*LIG^eQ? z037$8p3^#uks7{4pwDc(-5f@_Qw;`{jZrKy<5AypYr!vG=UdTi)+(N#-X4|CmB~?_ zV56z2wy{G?J3*~zIr|Y6(WRTSW%7pA1=*TONr%xq%;jiX)*@QIWtH=FVzxDAB!)a{ zztB9X|5@+OuY*KU{JGe55GS3CyqH@&Id$ctN{&}?fPbSQYd>ed7R&5P!HG#mks#Yg{ zmts1bi$!%G8_^dn^WPEFVdIw zNR*H(!ss!DtJW8*OHtj1pRBbU56(){6@8&HV~4x~J_eSr@~j`!C(ALC2KbX%z|+@8 z`1CId?vgbU+7{VDqzR;k3ymPF~orYA=w&FYyCnv8fi9AghRNn?v#-p!$Er){wJE6y)ue3V& zZc3@2`KtFkB8gs|eB3GXGwxyLig2QclxLaI6Kj|oa4Tx2JK9@%7loL(J4YoUUVPj~ zd&X_*kLj48Ey{&R%&1(?Ey&U;Y84-QCf#bwAVH@pXku}8&?+u5GWJoo z`mvTk+j2Cwp1WXFyT_d3_}XU*oqaZXSM(!6*~e;`IpCp&*2h=j@NRP9MXKXte)*Oy&C5R;VJ^O!XIrA1F4D0?M!D>>BXO>}=-t$5UNvA}3Pc}DeG zfSqScd}Gn}c8$Q&WRn`MnTM3Qh?$p^Cgh5MH(uUz-w`3U68m%3ttxXY?*cR_M z1fHbP1Bt@9I@6lg+Im>5*LBJ8D*m31@{$MjuFSi!W>%^NWHiZsL>~5f#6%O9zdxRn zlGPLiki%IiWKZ% zR9;eM-ie8*3=<{Uy(XJ2TuKNuVr#R1IXNbdJHorvr7JC7wvTp;?rYrM4cx>& z*Yd)G@F$E5{|9YKw{J+E(mLRUme_iS(2ws{ji?<^Umv0n{S7M9A9qccma0FkDcRXy zN1bsI4Nti6Zr|VqWiRP0E$qg!DC;sMtam;T;4h;)-ugtM6nxd;e&PA07%~$=>q=$i z_e1)Z-;gx@2gKLzI(gWw3Y&Dtp|v}Z^;V(ao|f~T;#?IORPwP z0+CU9G}{`#`rX;E)pHrEx~?uIXFN@x?)(vj0|&mq&4j84S@uY|t5$^46TOc*uc&&c z(~Erlf({&S8E3cR%@Sy)nkuSi|8^FnXAU4+-Akye;+q3@PH%w+xe_clxG@P7eO31c zE1d)CPc_RtzZUN783rETt%VPckv@xY&7a5Up@^bKKCk)>a_TtYU0LPiN!Jld=lIm1 z$bjz(K;j_MOQYLutq(wa41{XHK0KMnpJeam@O!7g+IjQknvT;zDVXY7bjcqseEX0U z?1bAoa9j@RaTv701fbhfMJwg&uTB5h?RHx=h~?+K2Ks30a#5UjGLV_&%U+(VW~wTW zh2V_W^)~mUC8Vbq-SKoNKTlPQwVA#B6zShXq`lpklno;xR_6JxM|Umv{aVtCJrYUf zyqf-+dG1l@^OKyDg_rbj0nC)FE3>r@YO1NA^RDI$AKId*#`jA4Q^j)dHyO6ytckry zVuX1MtyDwHOw0*nyq*c0-fB4`zIJ)h6%<&^+I=l-^K^puacWcYtD_guz;%jXxSFPDFkjbAp5uW*PHlj>O2X*K~H5M zi;$ZKWdQ);^Mi%}cHs+{*xgx=wmkN*S3uy0+LhLZ=GE5)!(AMGvn3z8n?!PyKl~xT z%m>ULfFJPIZ&0-|x5R2lh|i-HT>7oxi=mU<2N)?IH_b4`BklTVh)&0agoxuJI5)xs zXyMJMamX%G2!&kg)%rL>lb5+lA70M0`TeWTmpL9k9kF6jBZYvB$)LM$-oHVRWXR=R zYj??*^8IlGeZ_C)89HJDXzOO^r@VL;6;jpXrE?cv6YQx|Pu&`;7&6~2V&!|S&H4*p zvu?WL#0jB~1SsCV>_H-+{k5gtENi_zWJTL#ffw>I*FerEkxOQgCXBF%<{Qz7reYC5 zkIADB?y*>k(!+UZ(!rWdRTsgkBquvJTH@d?zzs{Po|>lK-aVQNdPcrln1xq-x#}Lp zi#;opNnk{1R~%UgL5$!!KUHGw9Ar5WuHs`k;WUGUZKnLoV$&DxmS?A*#dSgEZZk>f z{h7u*^i1$l#Sn7Km%nt+iuLY5vh_??>-%3jcK(%?`Tw--|03w%UVY~`^I+ekXYV%% zUY=UCtLx$w)Y2nl;3;*Mg-3ii^=MDl)^1fNE9IdqMP#trgzD^ESzg+!QJyGDh9|;3 z^V8_)^sQ5MdL6KDp_s3zn<`TwE7UD#F{s;oOan6dB1pOwv|Yq^2Yh!4cviv}Q!iE&~mQmWcj}P9UA0Bpdc|F_*p=b4EQI%-@#o>0F`PjSJ zxXgEs{pFzr%xGCPVVvQJmD(yP)HflhL%gw-=(=TRZR+r-u_S*U4LscY$GOY-=kTCk zEWbeJX6RY8X{vuYEL2x8lE87=>n~pnnlGPnW8T(YEt1aH?J6EFV)1Os;EmcaiGSkx zPz2NSl6T}EzsSG&VUwD__Y{`jd8nL~vhs;>C{`O(RjMUQ?qqr`{%LdTzvjmR?PH&U z?!^M~k076!72tw+`g385p5~+?7sc`$^zUBGyv7CJtp5h}=NmmDpFd}2C6O2OODd3W zo?vHx=P48H(CV^$Y&GvkH8zNRmE4H;%@~e`YDKP#6gKNMN@ zSZkF%y56s`6yfT?xJb2Th^OQGl{>%9ASLGX=OQlC?)=)+{0XN z(iQSp+}g8ffk%NdmJ(;hNl1+s*I8W@Cw%MRH0(F1W+UPkZs2zpqdY3HO6p2aUweDJ zg4{*Dm!%u_WBiDlGTvQF=wXh&RF&y-2MX$x&6?LdHm`@GR|)`Rj4sgr*_$ z_Y9{umh7}RsKkWGmu2CT7B1+DQ_$_FMbOOd6xO6N93|RDz=bZ*nR6c^c=mi%gb(E< z3)DbFX-pvH^Vt$y6spiR_(Xy0?%MJK-0T^0aRxpEY6EdHO}K=N_d*PNrhlT7UXrEO8p?^|0)IEblKd z=96W&^P<`>83tB6Yf`T49Sps~4@+?DsV3;&e4yxgDRZPhlxAPq=tX57N-SjbX!lgW zw{ljd#}Ww9hpbm`1zvRAH3U$8ydK^&dgD=NG5pbWUhdOZGRF`~gwcx*RH@eJJBPD$ zDlN5-xp}{=_HN^5RGO+z(tL2uOuF##1FtA^`;=6xIq4w3yGIgJg-}^@MaePq9vr@l%B!Dv zDKqgQB@~3;pGvG_cJgiF0}G+(LI*$K_VXF7NYboE?R9VUE;qA`TlOKS@?!NXjys8r z;gWLPXM$Entov@lu35Np%yi-`@}dWdZ;!Lg^Xd@DYqynf>2V)`QKYCk+&| zxuQDOhZPWAAX^Pqx#v8bB~EcJ!EOvwm&VU>Mj|QU z4arEH&60)?iqLgUf%aIBGNl6x5%5V#>nt_US0M`zKp%kshuS%M@f(Cmor?L7|KYjD zOhmSrZw=C3HoL!=4!ndVE{u-@#)SM=aXDA)`VBu?qP;(*;xn)S)`nZcsc+F&@q>kh zatyR}uQaWL>Ql@hHubU}V>#mzSIeR8K(Cu^`D$S8dhr{yYH=^Kt2N9^tMe&!D^HRu-~^ULD{*fv@D|&j=_nu^GDlC1%4K z2Uo`+L;0329^2ocS;I?uq2}Q0$M&uJ&z5fPX;u7F_4eOpYX1OK|21&>yF&E;9IRWp`2HAy4MN2P-pj%yDrDvygE z{mFaIk$#kC#ZSs(J*?>QscVaw@gnP{Y0gWk3_Q$~@O$!Jz!4m3{f#0AMDw7gs**p^1NelZ?6|Qqwq&B(Nm0zG#p> z{Cb6z=Um7$sJ~{?wR&3%%l9zRoh(I-=g-!}9x~U9E=n4Ab6}tG?i=Ak)|HHI4grxt zOl5ZiHs>Xph@vwR5ew4W3`(ytN66-reX3s6f}S z4Y|>W995i_L#>V~i}OnzQ)2>!B|hXV%^T?S#&+3k41Z0-@iJ=;B4qMs-m3t@wBCdY zC_J*YzvcBO)V?qC_IJE9KXW3Z(D*V-U}*t5@{|t%OUuJ9DjhsB8Nd_ckV_=FZFVpt zY?X0qf?8(PBZFhR;aTbq9fCN(F@~?Ru@8g@>V`Zwl(k>gdsG-`SUoo!llh=Q`zF$* z2wHa*bB(mWJ+tm83M~1xADyWBN>J!G=<)6&DA%+VJYF~C#jChp zCI~8Stb#{)D~f!xl>!ep8Lq7fR=A1NMvCg8)Prm zZ0)$lstFt4=3ZQ!vnCjDW#*Phd0=viSgd*hueB%}BRzi<6s2XM@*MCh!c1Iy%Pt3N z4tq&(S1j_W#^%*+_%HIsSjfg7C!zp2=6>oik)iIRgYQ>hg?haL?CJ#a=vQFmu`uKm^V+^NA^J>(yTLu_jT8Ps7;t11+B_U+X)@S4yKX_82{?>3&&X_O=1 z6I(xv#DTb?;6! zY$|-zKzD*2rDoOri~nelE@VxFSz?m-obGf+y}Uche`{X#CePXj66-CKj8|DSJ+DMm zdxoe;?F@246A+%t`;-i$emZrSdeG;Fsh^g-GXbaJ3*`wbr~SO}ol5}tVv%W6K?PAY zO>Z$TG{be7J>3Gk`~&@Z}r&snTM2fi zZb)OqCo9VBBePP>h9Av4cX_s6Yy!ar1h4_|i(>!V-$3Rc_`7KG0QhBMoO4GDlGPEx znRHo8fHuJdPv3VX~dR>7wnCKaCr1uI$EZ7aZN1X?Qa()KLx{yP5t zbp0K3I^2#PfpOK;qURF(OhK>xg(_ARA~lL%MX|j7A&qqKLQ1H2y`peK8F{aTv(8+e0uZR+bxD8um_e%`>fmQBYi zYSOLMS|`4~Z64R8ueB(c_A{I9nOGAk$-9Crv*THa;=`tD4&tbQ2y*gl2|6v_dUn6U@DH)){~SU5|3nW4 zWl;E&Kfyx@03OKy4jz~h)+kv!U{3!Vc&PXf;Gs}o-jX8Rk z5k<*uevJK!BzdZWesr`(WE_wue zb@=7l@3V>!XN&DZFcwu2lRwi?dZAL@F2~|*;?vi2$qv266Q9xG(Dp%ik2nzO`0d0a zW#RcjtFE=PyXvc=-3@Yb`h}QTGy)ZxSKcK%Q+`B`7na0vKDxi8b-=@8?%%=2D*RRw zum`IYEhyC2-&s50;Q2xz^)v8iu^M{5zSt$;Y_I7c?t}$8H8hTwC0GS~?y?)e{qa(k zj+;%Qg7(Ia*HeaF`s1@g+7~fI*0TyI+^Mxd)!KOJs?SWN{s~<^Iruk~hJjq{)8+Nx zT`;WH;UPz}R%?J}-YI{vk3i;YazWW3n7W7l@FYQ}$11eoV`MG=h-R zl>?28xN_!r1b3)<{3@|@NFZ%%dxx(u1rObr5O!WYkT4vp@$SHwm`l_Yxs?K~M{}Q* zdn?rG4eE}~Dtt;cjjG(%MmI9h(P_)qkud*2-f^D^Fq{IR-;7}Wir3TEg(bV+kCnli zk8`kMG#ZF(;f|i1N9riIaFHI_eS%{-$b4F+x zH^0qhK^9K0k3@;K{;wp#psuRm?iaqb=BTIa1ke$uTNI#r@k?L+;cbv==~D7k&~C^* z0J$fPA~KJ}G61A;OOsjBywIY>-GtKFs0o;A@c}-w-7_yOmE)$js3}DDY!A7tkY4Xd zh>g!0l?Wnr>--10>hZyQ^8`X`Gj}zWVZ46_T z(Uq6->>qmdbj9ErS}fv4`zm6unYfd8z6pqtS{R=r+N$(G?>q&nKr9J7onQ1(aAzN? zjhr|KYSdPc0+#5ntZmD!`P`4Y=O*djy{;2H#&FZB)}HoxJ7VuTz{ut@efCv?E5hwF z-wh|azrcF9O8Cbr%G~wCp;sO4f}4d^wLyV$&ttpjXvJ$oRQifjTOta#wLXq()q3m9 z+z$X#7HvxjX*szLKN!f_J#Nd9VWX?@IGERYT4m5d865(e!jIO7SHdqT(jVU0unO$@~Rzr{d*mJj}qMB0BODE@1q z_8-Eqzj~O)Y;+HK&ORvT@>M)sHK9@1%Lp&?$I5f#gCO?UZ$qxN9wQkWw9>79Z|xy`0JU=V-XDSNLJw;iH0mFAHW@G94JX4m&W8 z;$r=RYw{CWm*XwJ&^i{m8GC?m62ypG{`Gxg{y7$4L9Ri*7-CtJS5w#LPMY}Q%f~jQ z1$ycnEJW#nbSLb|?#YfIUIJZ-_dVu$u)zCp+$9%o7=rR?z^uO@^q<4z9Jv4e05eB~ z-!x7nC&7r-EN_AWi}hy}BnaoZN=Y61#rSE)zOH5x&Ri)eh9BNAnh^|adpb1pI{kBeha`B zpvTIyz$cs@UcQZaqJ3Cj_wfN8XI$k;%KRsA2@&tU0NxS@qw1%B;JlCBA2W_`!yYidzx(Y4#2XRtJU731+ zt|SI*i<7?ae|6w0Ut%3(FR4XeKaDA9UNX%iId2tv~r`ylchH zD&*|B5wC{{N`{>a&mr|*C{^yU9MtlzJ zrx#ssSANiq;Xl^v&!DaS;fh~J$fgsf%0H-@dSFun#Z|mO=ohz%8h`$vw@G9!JDEMv ztdbY%vZu!yeSLzpc#W@n?fiYUfV4gqS_e(nr@|U5)`#{?w4RT)rt5)Sd>Q>~RDlj| zvhuQGzxF~{eSXF?a>^<;*up!}qDlha0={l)0qV~Rx@>u_PhNO(0%Ch+uQ~Am6U;s5 zRtG##*&y{!4e91v5t@5uI4I+zbsY6mw5}*FK=L{Ov{V}e&$xF6TGZTa!>r&TDdX(Ssj8sWD{Vjqu5S<`GT^Q zJ~nRDi~E*rC&ly6(`4*3oA3|wR;-LJSFdH_LEE{%EzT@N$q5fSJ5XY@^@7~X@WZ)x z+?EJ=c3cOksSM$_EP?in%tNOiv4Jd_)YdYp0x#3u6|*9H;Vy|dWv#9W?^fOPn0dH5 zmU&iK$TQ2(X!l@c2~W?WxRDB;vcYMVu(3u9xUlQ^t=?gPcrYmdn_7m*l>@8B_A=ot~zkr!{YtJEbtXLI$E53jo$=+*Qb$3<+Hw_bt)Z z=2}2TxOI|2+(eHELCH6Uf#xgx=k?8e=CqfLW+gVKkfbQK>& z1miV*$?_Syv)0zt%$Tp6k7bS)OZT$CLB!9h3cFJuJ^e}M=a-1vRhtOA`2Ky;hWGI- z(TrQQu^VLt)(d~;S0TBQj(I>;%O^YDlD%{;p*}KRtk?4Q^d4e@h}@M&eE9M`D6RQ2 zp45jUt<06YNhX%opP38H!Q;BbovmLkMYu4mG=7|HT><-F!=8q!`xIP7=_6=y@!P>K zH^McIp7L`^KXbAF>_kz2nT5UY!)QPWFDf^GgGwo{eJ#+3&gETdrr2$>hm&zTTzx*;pQ`Ezw_{YL2#p$K>u75)YRvyDDX?YttICN4Y9G%CC?w!fp0=39l?Xp7)n zekP9YRI=mCeg@6>1-Q+ZHGUCX4kn~71ffHJ=l#-w?+x~Yclb0FO5Ke{WFFCTUF55~ z#1@F24JKQ^tne-RdE@6&N{*3;vs^BI#hKJsCw<)qqmh1?1;tZ^+lp#daq*myV5R=j z5iHAP2*tJ`I9R(@K0oZ3UwZ(`wBNd7>j6Q11Qz6FA+4c!Xb%A7kAQZIHCNwO0fM0A zC9G+5!}7iSdkXI7Mqgwg5m3FA+e4^u~Z@M}v~C{CYZ5 z`?Gy|TxC_F7u12mH~{F4(b?9m%fU~7pKmbVlV%@I`~kUJJDE3_*!J;cQO`4(ELxqZ zpsO^fS`N%o;no5!x%mz(|=&}SPg)ety-|3hu$~Z|A_WFfEKasQ; zA35j-eBl68C1Bp7+5vO0te0MQo>==p!NLpN%ezk$fZ$y2{BPISUm>vnmu-xej23?h z7IS%Og8vq`{3B5L56>@vg+E3IIuGfu7awbC`bT$>PgINnzpi%M5BH?2o5l}j4{g~{ zj{xE5w@ufms$LO9JXT>Tn9xUT)D?`QzvCrP-#p>UKbZKV2AwE8X}6T27*KKCAds)U%S0;q;Qj2xHYYIa1gONcXnT-Z5*k!{&N09bmeS@lsEn0 zGo~^ormC0#Zmf(5w&(;}%5q6EfCb8T$xGk9FX?>|RntcpTo>SOBd~oNM(?ofQuJj8 zaEM6-JX5fyYf2=Hi&(;&^1qm=ee`U%HM$}zv?)Kd_fabHXyBRa<+(Lrn4O~?wN2d* zIem10m(UhuUc~bognxxDoh$)sKv2inx)(2?J9@Hwi|~vm*zo!d!gB+Px$J+El-}T^ zzU|D`ODA@#bjNS1h@Sigp($Qfw43N!bxW_jp5SKN;)Q8>OHtSZ4sE`{7ff$d z+|iJ4)7GYyF{)|Z`g0Bk=PpM^=uk?nUwrWw`$P-!+lkT@wAmBURCa;SgXSZ3l!7w zUH-Rh`(RY}hCPcPoGgax`LmM1UK}n6IcTS+bxS5L_g(0yGJ$rGGMAECkJkoC&lKWW z@NdwYsj_p*cQdRBGV)%`F`omcrw+qJ^PKafU)9=D<;@3uX``?^naE6(MIDn4@ehJ5 z(1XFcd&vglA7jpfc6Rhb|G=}2dKPXm3)17aAN`r2_LfVhC#{L#xmkB4vSLF^bPykj z0DJ=peN(~LYhb_%7DzWqr1LJJS$WxgUb1M);Hd0wCKe!Cxgqgymj6&pX6MrL=49HA zMKI2A3!y>0v=Uv(TK`0*5=R)yjQ_=jCiS|fLpNw|?~Ta806yaoxw}Y9P2TZ$=@O-t zy}boyi5lz|-WGW}GuKbzXUMwb^RA4KWDpopzv88N7=D>rv{8tvVmj+^TBk}*MVQzY zi{>WGmN0r-a<IpOQPJ$o5O28SUhl$@Y50UV1dwdSN!}MG$%wtqF00WMOAWPXFLmnPx+&{<9ouGTofOB*t`yG01%XAR(9e?UyW3mbvF}XDF)W1Z!DHuE?u+3)0kpaY zl2e&!oWOMcQOnw$P9hUmCEw1p3JPy<`i2zkIDc6 z7SR^bcB*LE3P9S0q#DMQS;J>V4l_M@b}#C>UrQ|G0X8QTe&A!X)|FN&54$y;@x?_l zUWQR4hxcjJ{AJ*M`iGpmw5$c6=+U*F&AXfWLNN~mZhY8)8 z&RMD%O<1}qCA&m);;Qwf);9Bmi{9`(4@F$vEky*~w?h2|%dy!WoH}alfoMEuLw$Z_ z5e$$Z-^qq7)=N?jB%XEY1kxbenmn&Nr_e)DfUR85r@Zk~IN5hhu^uYsxNLtR>lpBi z!A^*L!|^*(9^0-kg7=$pVzb5cE#=ZlOKgBSqo}7dV8Uq zmp#*y^mfk6TMJzhFiC_&2*3Q+=W;C4?ojXUNlZvga_ z6O75UW*VTrQ=@T8i$vD;sE9pX(!YZ#H#9QW40HFZyUlm5ofrOnt!Ld4bZKmSm<77_T%>95;iN3bTyinm&&>t~`Xb?sBZF-H~2f zTit+^#n;f6=8YTIQ&CE0l$cukD3h33k* zqdnur#~yiZ(p(q;Sm2U!J-W7c3KrTdUwBoZEWeI`ZsK-EMq1 z2w&o?qOnHN1s4K2-2(BVHAsxF{}IRtrPbi1#N=}MGy7x-7(L9tE`uqMby zQEd~Dt#}|bFpk-$l0bO^bRq+~P>b_$*?;!V|75%0ChFABC0$T6<^m76nuGz;j1c;6 z7kt_WJp$Th-hRCuydHDi8?*q7@BhA4`d@pZr9D6g#foru{U@V){IPQXSwJx`d*!uL zU{n(n&Ee!QL)RD}24qN7(Ic;5zd^LsxYY^`4?Agv!e3hb$bEdFp@SvC~y|A3z|m03x4eC!aeT<`wDS|&*nX0>Ub&l@XQ3hk$c|n%(eFrq25NR8i54n~%jTro=db;;gV{eu{*r#1*P3TR zE_;@nAl)#5oFb55$`a#$HtN6)(zwmS&nk~-chedydelTZ`inu{GsGX82IgbdFuAU! zvRtNmL8Z5^IZP_M`T@%6{8QEAa!+FV(OTAxsxpulQc>o7kTvF>?N1OpnhH4F=J0$5 z&9ts{U!s};>^_3)@xpiV=HX?-zuiRs=Ozbm+jZKc--};X28rqfzr;Z9bUz5d0U3g+ zgt3+v#Z(d)-nBT~yF%ory&pJb;-%&cNVzg!<4JnwUK$czy!&3nnOPpt6&piF z#4nP@{p9g$741HUTebU=U_Elz?hDZ5+$2TNnlBvY)KuEeO ze@F=@KczBOsEXn6>JRYBV$r`?UzuRz9B&!nANS9LzxnYlZ zd0ZCK5m9D!G5JYy6y>Q0+DaHU{K0_UQ7OG*h*)E`4^G7jqJOK@;dbNJ#KXFwtv9^+ z_L0ek**k~UD3ylM<_E`1?Tr*yIUOg~v%v*+bn(j58q1V8u~>$m(bjce#kp5lYc?9D zgI|z~j zDlI7?C7^^LH6YRr!XT*v(k&fBNQi`VGe}4dNK1E1m$ZP?kV6hIjQ8j_e(}C*-S@ut zuDkA9_m5d~7*2l9IiJ1vv!DHJGZJq)#!r^m?c5ga81hM7regr++AX@9 za291TiGFCx`ySuiQd6#57kl4da?fj}-XWw}WNcUH>dF4f^{bPSRJy18tg)a@^gMRA zEJ#k0#79A=b$kNrn^B%irr<$zm^i(sjl+t}oj#{qu>y2$-B@in7wb*M7_$AhzQXE2 zi4gGV0t!x zumfXcio%(W_x&=PGUI8G0Kw|v(mK1~0DxbgTy{gv@2k5~(<2s(t=#e_foFWWG z&H>;10el~zXkhpsd70)U6o5jpmi@zCf`8ddp`RdI*!i=8 zWmAI;HU|%HjI`*+l{Y&kf+D~G13Vue)PSvw0itEjb)Nw-!e>BIh>%l2S&9Gx!#r)0 z!8EfJ33&qhQ3gaR%fdFX(@pBRp>423K?A_KeGERv)+0KTb@wB!80o5p&n`Zk?E4@{ z^Zf?HlA4R^4vx%TbXN8U#(3ZBGzHXJT6c&+IO8tLzf2vFF|}<$uKkXzfLQUb&}#m# z-+o0~xBiH>82^a2wv4G!CCzjPyQT3yoViO^>9$mGvkDHdGxSY12ZGss~VXBW>F90?jL%jy8szD3X5OnW z|7>ME`yi4gjrO3IHr*-H5<4Hs*yVZB;QjDrmenlJU`GFZm+Nau$AOVIbP#E~OBw4A z6@z>s$8~& z`6?>_LmORaIqO$ToccCUxz(Nd;?3iW>9kQPh6+iEg*ku#wyb)md+kG!;Zu?y!+t?v zrK4if+XyfBa26zv@bzl)^dWOU_wsF+hA%g7tiNP(6Dsh+y-Xqe%EfcDvcC6Y1XU^@YaY?X#Vpp9KS5Dbj1iJN*2Y{T+VVlFm7_aP zGi_sLHqIg*(|kA0w86&QqHQ_90P<|jk&Fjn3qXQ=vi9oOS|V5M<4lHM9CE+Q%lz%5 z@h)?}kx!kOK;DU z$Rv9!xJ$pb^MI@@g`wFUgy8uzd$xHAd6d(fb*8VJ-7-5QinHTR!;o~}j^0FaBFCK{ zb~!>1!WN;!gJoC8fcyMb?g--tWE*qjt3uyUni=0mN({e8OW%WgJ6vxp4G$4>3dWM- zrUd-qKl5l z(;k(wHqq3GBc8RQk|gH`H&85@Cjf^K9}PRYvig;I|2=leNi2^lHees7#YIW;+@}5L zQg+RrHC4^afk**%KvHz%05fIX51F=x#nPOaFTyfl6E;Z1}bP zl>rpEsa7PL_lFC?%Z?s+m=JF;+8fOQhy=EMXS|@Y08J?1pwSh+s)}|;M(wm8%rxZ7nEfT&>QIHt9JaG7JaWoe zRL;4S6_w!ewX&F#w9!JF>9e*Quhy5>@E0KLB0{IR&SAUE&(5VH9r37FnxCK|ieR^0 zm+u6d)JR^7zyjD0UEWqAbFbDY6NcYhrGtM+H~$2E4uWnH7`GTpUkU?AMi8JN^^y{> zIJcYp8u0(=^W4q)74QF__>l1ZiV~atlPIwmD7l9nDxLhv zd=NmHU}Q{A0W+AO(o88-HwwH6p)EhiN}2a7KtKGl zo6R$VQ@L8^nCK0Tb9O&Np~ty6$FH+4Z5bEA35<3@mrHpdbqMgNbx}cof=nJxsn5N@ zoNZ|g7tZ@;8Ytv4zD@|@-$lr)S$@9Bw*YW+aiP7V4ggaTfK7nn+3hpgH)c0hu$Q@9%ygf16>)GxtV?3~Kx3 z88XCprOz>jkYS=xzrdz>(gQyWA(OD=H$aakcN+SZw~=EgC7BoWrE;})YxvVHl;6I! z?i-Z_!ywT2ysoJAsO?Jz!~3K7LyPku?x9AplFidahQ@KB(1{mTysLHLzF_+`j$G5s z46pD_aWMe?CGv35i+iRVeG?%}Y(Mqgm|R46dq{D`|89L;C-|VWnnIxzT8{1u67lzh zZj<==Sd=xr^Z|w=W_BM_2YhF1m8ttK6U17!REulW95y`kCqKlzQhT&Pf5lDKm0Dd> zyJAy(NuI#-1Hb%Tc?)5Hvr~^Xs3-RqV+#%=M)?YD@uhmBc9=d_3kxVAE74g2{&=iM zy1*;o13daNUeNC~0G+p>w3Ly+3UYduuZR?cxXkJ+y1lgFWLbO{u^dgaUZ({5cCeU6 ze{$64+>ljkw9~RA5$sxa*X=wEJBuE~5LoVW54@t|;eEadM$Vo>L%n!2T$g+5>MKJ$ zGhb_s@$TVC8%s*&XsvC&(b6|Ox)H4jsHl1qHRSQw*$MWO5IkiiJY!j2pvUNr^El2k zE)X6`uylDv1$f_!dG+d&)|lcO@`t|xj>VR-bHb@m`7qSf+T>^%zz+R@#6CEMlBZOq3Al;C2DC^UPKQ`y5p;i@!G=E9;r9^D1QcF=hcovj- zvXv>90Vpy<&jC+8@@^;)-@w4=Flcv_O>h(xLrL6oML6A(kJ2jZ2W@ia4W8^hzl*Qd zwv~D+O_D6Cw~Cn+MvdE3wi+nu4&$)AI1deqhD+L9kG^r3?x-0+?@^|TvcRqhdLz|y zq3#mBOrbTW*0=Ix^<=ZUm3VRQ_Kl({IZ>fXEvt;8b{qr0q!ZXsU z8Neq3q$@ixf*~t?@x{;W@e24pSZ>fq<6mEW0paqsNk^(>-0}2^tjD?is4qbdWZ#1< zGeyOms_$GfR_L=5uh%@6qM@c(YrYG-oc0bE2-sB94PyD>fzgy_`i3h-3e@sWw6$1< zWXHHU*-bgg7l(Y*o402=w@PLxEGMFu3U*B%pcYSw<$LtI*3ydw$&AEU-;aiPg}2SN zEHEZebcMEa-F8+x6UtCCw_#NE8)E!TR|ixAaLP=|n63af;1A37{;g!4jG{5%M;XfhDu6Q~f}t}1sTO?8N zM_-I(os1-Kq30bf9t-2Dp3pY*2Ka{-^x`7!oQG44NgQ$3t{)uv zBXO+6b~OEVSzCd2hx;&d*3;`zkFAd-d|gTnujCIY9;}LcCB+9JH_Fb}oJ?Icu?8=5Y{JuXz zzLQ4}nZWqW1n5>vwxHSkoQ6>N#E#{wTI(*p8RF%d0zLIkZZ2Murr=RU~Uw<-&=x@9vArl&lSWf zSxfVmmc<_gcKX^5U;h2)fFB>HHva0Uv{W!eA!iFemD(HLdg4jG>SMr16#T+m4Z3Tb__?C)*HKLn!VE+SLH2k zGA})bX~?nWtc_`=0jiJAG~XM>onj6j{!`m#>qlnKutiMtkys;;g6Fe(Tg~jvwWBAT z`*5>^#&LyVN3(0X5tIz+3=72rJqtirm~9_+Kwva&_yVPVh1=AzJYdwbtie09%No<7uKTo}_+jLlMYs&W>m*RH6l918#cQ7AW`QOkjK5gYk?10&C?DTU zqnYmRA<1~G{!K^LGci^gjfih2%uUz|;ozO#qdN@hItP5i!0DV@kNaXI>$WwbH5Wg{L6%-((PF`j@ph7aM7kV*AaS^lG9=3UTow@BXW>-9<;y9yR$NPLm-kwiA-8mjRCLy4hC-!iL;=T;xi zD+R-Q?o(*WIe+c($8#}S>I9=s%YlHbTO%WVu*^8qU4`65vuE-!3j%^q{I zPxr~3hba%}*9WyA{auU9{JR!;`oq6Y*Z)VH`)hw;jsGG3kWp6n&xu_Bt7$%9eeCzB zhF`Fn!Cz^p!{!vWp`tCq(mC6{ZKdlw3w{|J>_^cex1oSiY(1yTA#bU%@b!LVSGhFJ(^4%8yklXSXjR#YpJBAVj10a^~xwZPY6b5sl5fM z8Cg&`R3u|wp==X5DPsz!dGr%h?9l%OwyS*f6T}w>Joc|^kE4lE)5handy(b^#s-ue zY?0mkqEV`r6{xZ*`D)+DGA{M=b%1%zp1_Via=2Wt^L@S4>BrDS={3?=@r8pH48$mmjHhT z@OXf$`1cJg4}tJH)9xH{!}YH*`cKzC|MLKI*|`SYOJ<{r&5>s#Nf#^&&dT^$<;Ie&t5oBGa5 z`Qv}-z3r(#&MlpNv#KUu&Tm)iMjl_4kQEqSp5I!lp8;=7nGxKgeQ^}n%D7?VdessF zuTHz91rs2q1BWc$WpdBZ?xmaUYDcX2i-dEJ`6y!B5E94P4hrb$MIG1SUK6-7qCzVhHbe9 zo9DR^-89EkYWOi3qLZyA2dfE(La%f*>m?}0EeTued%Nb0E8(J z^(-9qQ&{GBmvSoCJa>(8!KfvcqNH}4R3&1HjnsF*7flw+B&P30h%n<`sST#f3y-=NOey=g zNt;+AVr?{ap7~^v=J8NnD?9bg+OlK3I#TuJZR_Q;Ai6cqski5K2&+8)g`W2tT2JYO zze)kg_h}bERa*Rh%XTsJu3_doQ-{KBeY=DmA}0rlV=Gn_emXmQ(zU;4dOJ(ZjghK> z_1L*5u+A7F&pmL>dW!M1SN9O;9f_PCl){s;p=`+`PV3U`)5{|_{PvEUkw708LJ{iH z2HDZ-U6zj2z5Gx5h$;Qx>K#spAM(s=)Xn=z)Gu30A)Toqg@uSE%W1pdrj0~^F10A_ z2o5X71%eD?WWQNB&}~?XQ3dnw?)hK1(jVUW@47#r4)uTUn}>}D@WK9}Dfahr2;fot zx7_`It1tVt4?L=0?zb)w!2Nc=e@sN?CB3?)c)Dexhc*VhcAdYycA)(^ezfT-?i*e6 zku@%bK9l4($618N*BaDGJjMoe8e_D$eLG`=&$;BK2facgBspem{75GS8PjLQ$AIM$E}BMB5er?&I_LFnzi zVVr<%sq1XyB-#G#;X}_Mj)vjRV69E)9TF?-u`Wbv zQLi+Nh!>0s$o z@D_V+8XQOCiN(U6)tb*(Z&QGzgtG_Z1)mV#qn@(ay=(ma!MT~a8z^Qw9JJCXlVyyu zFoY>jw7*+!Vtp=HPB*4md1Of3`>>gYpYivJ0^n1Hr(7yJZ`GhXfk!j_u500hl{+0%bX9iIT) z8T?WpyjN-2Z^2YE9)w$ij|VW90FwRZY8?ru4>{mvC|M!K3v<9Y0#u?dd{XLkHIw!HIl)Btu6hLHRWSTE?6wT*}FIsOt){l+J=f8QDH72#n!qo}MR^DrNo zJ<-W=38HEo@`M+_@(&rtfwd8QS2rNpo0{8)9z9*KgQz}d*p`+j=IKX%VTQ(t>D1@* zzOk6a4g39jI&luAVMC6A3x(FH_g`vt!@5M$oK*< zHt|@9rEA?jPodiY@-V^;^q&(+SN9uxC`_fLpbpbA((aWP1WKvBtx z7(^bgDTQzOt2Fpm2mn0I@gU7V){$icIYDoJGU4qfT^V?M;m93aH-VdALw_W92ygmo zuk~2PR$hYInN-3C+D!$sL9!x9v~E0Y2{oCjw53w@ebVN-&@!`*xhwe-R4*?wT;l|@ zo&Fez;o>hm2p3l-4KrhZf;=t%sOF`QIJ>9NclheGex9gqXdwae*Gl76O|cZU6K{HTR8uhYa~`qcrV`tvE9QY#Ufpq~ zbTvo5FohZ!o^ssB_$H0`+nIG`9%~}Yvi~Lb_(QtZw8RScnXZ9CaskVmx9-Q}ScUiC zreq1;@x2JFLE%fAUr<^CI?^dSF_}L4bP9lT!OG`%z%^BX4|HMDJ53L;D8Y03Q1lhw z4@=A}@KA1SL0Jr4$+5ou1la-a&(U#9OwJ$s$piK?0kpNass_NM;W3O{^e!BX@k=@s z0yvTXAMJgH*g~BZ>rMKV^-6v3$Cx0_P3a+<0Jy~Mt6c}J+b-nrsv>^>)c)+{$2|5zYp3Z@~k=G3N&G32|yUhRWwr70O>ou4#h3@{%k|lMr{I zfgK3^ExsSHcT)%Yg?8O2^t_botIf~2k+)e9%-og%J z;7ti&CiRQ`((-PJ@V@x<JcrQcn12wX{@oa4SjE- zK1@{e$#HgLj^nRragba~1MB2d+ouc@{pyP6vDmy&kE`pVIjW+oI+J!KJIDyadz#l)l3@nr&{3aqP>mjhCq9k7R47aAZ}Sw{ zvr27-eTS3kz|Bs_G6=sX8!XfL?X$2{gdu@FC*`0(wk%`kp~h2MBh@ zpuj|~zDyNTP4A#GQCd~JR+%`35F#CN);R9+mW#OoC|fPkz?wPt&sz$H`4-&Kq<+5{*UM6<2vY4!g)=Z9CogU6^9ke+;%v6{rzPm3qAQ%$P z35pL%1PskDp$VW`*8g_Smt=!EMS(YwL>L(%wpXZ{jh#iBI;Q2^PE#bnp7st{=kFa? zIea`IM#;Xd{ajDa+I@;rzvFF1<^^kV;#|xy&2C%(%&UZ3yW@0Z0TrZFTOY|9qKxV& z3F4BQMsSa`LusfdP)cW+cSi*CnxUvCKp_p8{sNK0eKSbxBj9nSy(|9ZyG6528YxRb33^|xC7(65=t&cP+$48AZd$i^*!B)BW1jjU` zjM8-ngVCY8Xt5PLetQ0$r+2@EW4_^haXCv?ktY6f6f3=6y6xrL1Sm?|Nl0fd($27$ zR51!xytn99+#Yd}qE}5U&PM0k59q6@F#PDS#Clx&ROYaR#EOp|sj zR&e{>oLd$3fl_u~=JP+|mBWolwJ_5Mr?A4^xzho&G|SyO=`14Qq?&r)2166W4m-k= zSgUIsXjR#K#H=5jRx-uc!L7itn+DtNA}R-2>aJcJ+UX}axpzWt5GLrE*gv$Wb0elD zv5YlM{rbBXSQ6K!Hcm;>g~Egs?4}m?$Su#La9+uR+rI;GG>ZfWwo>@|zL3N14&sHA z+Rz*uBCQRx%7iZ|WRK0U*9=#g7#g*!!Q{zIqf1H^Hm6hkJn=Qd-{*-KI%wFpr06Li zv8S`#-++F1x+}{@*XhQ)t? z@K`s-Dj^yzUr^B>XRS{at=x(8R@Z67d-LQDrMT3Y0&{QrHEm+olzclUh>))Fd82Bnkjsvu<(_Hve0)rOUQlU(LRpSs)qh)UVbOxaD{;Mo&rEV5Eu-jz{{ zmQVTcJVwnBE*N(Firb7g^2T%zX z)c5D!SdmjbWyBSg;^mURw5WeF7eS*Z!w~@n7xv{>o3#KMeYiBq0)DTSq$c z=!%8B*BUpg(gxua-^Smb3kMYe@VO=VKEbRpDz1yN{@JU0-jUzt=WwNl_4j?`4=N!e zXd!5kpsu&=cdIliwkS~FD&5F69|kZIVhsHzYO-dy)Zxb9mR+~8CUV+WAjyE5A|*nF zube@`74OClDLj*^d(r8Hf;e4DTHi5`_d1{Cwc{CRWRo00)KS~6f`e672Wcs&`uB`V ziB>$j;9(~&=q_KrtCnTh1>u$n>J}qvIuY$VacnS*J$Em|(^R}2N%D8C5|jQ*z?31b<}gyBXw2Dmy44{Swd3GQ~U&!MDMg~#OUA5 zVC2!#VO8{+TsLNQKuNlPwRY9$9^MVW1t|L`7eL5hg(TAT`#uoOnq#&C0?ct9+HOd; zC>5`QZvw3%olVlj13-^0Ih%fA z%3q~qzsQYTjQ0*#wQ8ePZqp{>y@*(DAx!;9MU_~e(Ku`6~ z#M?jXR*kKtZ?pq z2z4~pXHe_LREd?>WPWfny@ym!_MGu>aUZiH>tSz$8X7y8WvZ%CX62o@aOwOOB$IB; zEOFl7SnS>DXBMU_1gH(uh0I4YdBH-#%Y+j^JZ=%?3bQ;XJi&1mg(y!J5wS}I(GhP5o;8S@)9<$5xDmF+t;xOL=s-EoP^4h~1ZAx@~D>ye0T z>=t?@^;#tp@JTuVv(>uWNLpz8&GKwz2w{nBc-Mgk2}=YlQ^(Ml$D^(vufER5da_PO zq1g`nk#azZK+~mgjO(4%*Sj+^#>2S=S8*MWPA_ZEdHWis@o37hA7J=;xAG2RQgnj6<@0BKL)vK_9t^CN3JZG)(!7dIjQs!v%RmQn zVsZfe6w{Q&^(U)#Ho3_@lV>0eJBhQvoHJf|ZQHy>1@k)CW*vXhS%tZEmTU2x7AXH}#=FUC~*Un5J8iBc$IpRV4HzJ)Mxs1KRK{>&_E zbu&s(a|8s=aLr_hHXIQbDn;lEAQFXjr$2O&JK^DPcAZ^&`?7g+*RU*1h`Y()nXrCj z{3G}K{tBPx&hHMNgtR;iBI8zaLH1p6)h^%p;c_Rnt&U=TpH5NIen zHu%NTo1i{A226ab{$J($Wj@o2FCAxnoCe;Mmj|=GDj1H!V##7}(#!1y#7b7XXRj|N zpQf(C`{((0(iAiM7UgVT6h-D4NMH@G>8a8WhrWSfDVDyA|7NIQuOJ`a{t1r|UPacu zrhmN9X}T`%_;~9{xv^&W6$uA+)I_7w;@$Dr<34P5u1+p*LMR&&7qUYp^UiD3 z!hz}gMUb2`-ec_iYLMqM?p&iy=lrm7jRvGC>wC6J&qa$=Y0y1Msf-6M{@iZe1c{^| z+z{!tr%zL44xu@w>&F{WHecqUjb5f@*21pm^(Px}kaK-g&naod$Ekgm4_nie%tKbI z5iK(dW)`|H_}wyg`0;4v;m@LVjoer6y?4o%7EHB$lw@5SNyOZ{(br1@`VM+5(l;au zu}Oa;g0`GjKqy>{T&Fko-ZtX0Ixc?JSRa9F;O5)>qIVt(b2`6T<7Aj0=A)Cfy-3?I zF55J?c6?CfxHW9flw!_8H0k*E5y|)YR}HB~J(oS7L{9WMHm3=n36@!{f_dJ0Z9kTp>$e*)p5p0f{KMTMHs(eUWKXJ4`*y z5RWU7j2y?y136N8xt_o}fJ~c_z5*{TL{;BgZ`!3Z1o_$w6Hldp zVffBz=o&S@2&{dGJYE!OHKRUAT3MF-@A&`O6byNZclE|(Lu2CaMJf780M};v+w1=8 zS^f3>Pl?U^0_%rX2cdEIzd9C(rh@8ZU7!bXeX}!AfJBUD1yIxB3IN5F^A}a(P6LPu znI`9_e{fw1#9NMbTFyqZNMgf*BC}=oB#dto=0XtKuFi+P( z(qD|}xB-B}1$=ygYJQGV2h43iCFcL*BfX3p`lv2I%B-vvL0Q;h3@3$l_R!CFy3x7 zDzd8lX0q)vZ0AH1rT2}OMjhu(seY_KWvY~f6j)PP79{v2*#B0b;&-g65`eY0NRny? zq|9n90KW0)fj{x89r*(s+HV#3+eeTBv<#|pWti0C^4VBbL)x>dniyRnZ=F|IQeJ02 zM)2PEk+t28(pwZZEkiAPX- zO(u9s$j0jRM9tkmF}pN*E>SwSLO*Jh%yXLz8RL=a_cq)ayeyqlpEQ=^jg1)L%TE;7okr7D7We5kF_AU?n;UUzMu8_5kX(Kz!})M72Sr{?;CEf=u!^ zpPZ5iR-g_vv`Pc}8jDA#9Yx#76O#Dot50TxrF5O{r}u zh6buo2ek6Rbenp%YJOwAP5+U+i&xA|pRWNy$AvyJ%j$PfamIC%_A4VSiQfaYBy=8t zsITSJA}P*7nrTt@BpA5KeU%ioJlQK1^)N>u^pbwlN;J7gT8A-9{aEI{(w9d+{E%t>RkOeP`MhPZzs))K)slECj z8uF}-hGG&%iGpEn8mV`_+E(m}K(;brdf#vG%)?Y5oX9YCG`khEEV-PW=q%(GlkEM` zAL)dk?*-Z6FWeYNQuV6dFLBAM45iF=TCA02p+yuAi~=6BMx-9{y_IAbs~#lP6|Fv- zxdGASB7F#PNMB?`+RXHmR_7&>4YiS|n8DMbvis+-V9(4G+@7vtG z-s3CFU!Ola8-H+-?6Ax?^YW`oG1$ILdP&aee=hEp?Ff>&%95rFo^eX0w-KmIvCeZ*bK4!eo(0Ep!u1E{f!(dAqRNX4! zG|X^PewDKveSu{JXldvH?{VrZn8+rHa@KUyUD|$6>wa1@`SmTWh=G+K>gE%DoC!4Ym&%_bFhX4(V?ROaEt$AM2F=qaw+`nK!UPqM zKreNL5K~%1pwK~gfldv;q3k`dF~P*j0Eu1ZC+J-k z>Fd7>3I0g<8fzZBG5}B;0wcv`1NSjI*;TxdHT0>)Y|Ep)2M?npibo{}i=o44ld}z= z&P?i#Yp>1HAx+ZNBu1z1)Xo3{1w!K%@Rip_wN8om6*_>t$~tmOOlON^*o#zyg#avp%Uat~r_R}lo+Nl>-5+L&!EbzfSP1Ly0GaLragNz?vZ{wG(y_-KKW_`-RUZWKAOP|r^ zjDH4Yp;KSu8z*flUS1=)eP5*&^FoK)nu} zDtFipniSsWsKob;J;Kb@A~FGjc<$fRWd14Gm(C0D72ItY;GecInzapDy~xi-J)k|A zgzja)cM0#%{XBVJbv?tAqU#H*VE8ved5xJiL+_O$JyfOi#J=uWhfbj9lGsgLBh+@) zXRMZMHZe$sk8IPy)$gqYFMathxGxn>GzdI$P?DA&KB;p%QYpIw_)fCVOch1Nb zRkS|q-HVj)W7 z_7t{qS>ignLrD5fFFK8D-xP~H+RP^GPCSp{>|ZT+#s;4$ix##e%pc^;H!^c6D55S&A@^o(Y=cgsZq0ZM2%xltD?WPj-hY&1N!cXKSJ6{CN z-q8A*-j-7&Pqr`VL7)K6v!`X zrhzjXKbx>04L?p6QjV0I-%@pMpXa z<*n;dt+%`Up&Yak6QeORFSOseEBT{yG^J5&om@QOYwJphk93U10cw=R;rL45GOISs zcl8}b3i4`FhZXixiZV&F0Vt^YaPcxe?O`rkYc%8G$XA2`Sc+5Js?cc5m{B>6Kt(HU zz;eJ8%>A{f1BnyfGf@>*?GTPpnTAZYOAzwk>EHTjdU=k=>dG*w-JMBYGhW4E|7ybZ z-HZ^C3folHVYiDY$+IX+?2l7I^iTFp-gjKEZd*MJ+7)&W#!hCwuk)nvd&A9d!&12y zT5Y-8spcn*HM8>9%kw)E+Fzw?$`4Z?ep}Wj^XDlIyDW;GUSJYQp=+w#Knd9KGVON-W5YPrP$hI_Rx02 zHC8?bJoA#oQ|9BfM7iZD*_>xVI3g@dV;T8+mK*Jfi6heX7n-$lQiwaqxg z)NgKy-VaNKqjmS0?ic7}gwdZCurr{#)KcMZ>t7)r8b3X?#lDZ2(GrMiG3LHr=1RLy zX8i$WKdw@n*emPc;_Fi(pwNZ=RwG%2@Cwx@G}s>-9qK0-^24CyU7<>8P1;-Q&Ta!s z@#y5ZXe~?Z`f5Oo&8ybVrcj#sdBnT|0RiXgEp? zaX*<_CmPV(#qIdVXu*cuC>yS%P9N%_nSK?w{F4x8S7)r%s)8wED;ZTfu;)K;MG&oi_MmykN;To z7b^k^;iUd1F8wo^>2DH~Vb8mFm$odQqw`mdB%BwyT*J3mU4j+d$u_YBv4)lqZlZ?F zc50`KL;Q{mo;p|;W=AOPl4>FerKREV((euLMV4@izB8%>bvYXojb%-jgodB=-rl>^ zzNe?VECVm0kuZHlR_n*xh=qA>T+Qya-WT4l zlIepNcHzNwnHTG{mXMM-grjEE*w}X0C4c)_X$9FJn&lfz( zZ(2R+Fprq#(q9yVJ=kCP_RuJctVe(I)d42PsYKsq77~Xu8ls!nV;QwZxN5Vz>@ULd zh1s8PxWvkBTo59f_x3j5VwAy`(a;G>9Gx(Wko8+URpo71DDI(=&g^8XAQHz`K?w}WCEZ&0uVlEPmpmeeF6iHt(V)xS)X+4I;& z=uZ9MA+o=#SI_varMj9Z)}>Qqb$!r41S*9%|fS2t2ZsI(2AhNk4IH+L+QOVLZPIRmar zo#~}<%5o%-O;rWKYGj#tPw1bsh=17*ib;1;Md~&uF_OHV5ES!Yn&qT#D#;1FQOYtT z8Ys*lcGD8uU2$@^I+^WD`Qp@;z|%_pWpnN}vlGJ~7InC#G}&bMD&^;S?)YbsonEV@ z5(sW0T3-S6+VV<`#M99dO}^}c)~oBDgF9pNx(;DngFp0^-V4z!mp~r&x4K`g3RqxL z!a>K%8QN+UALP9YX66*+zQ@h?(B9e(VOq(?ER9wIJQV>+nEm^opz!?pEm8ZA9I2=6 zV_T=Yx0MO&da_vGY@C#;FJppp)t4Rk?YR2oFYQL=PdC+Y_V7e@u7lo88?%hs+Goz5 zLCR}01wz9Of_04rdf8dvk^_cg)tnLfZh2PjOtj%`qIKBQpz%^cBd)#W{Q7a*^^_rf z#TUA!C#;Z%-v@}4TW)Uq-L0w&TqIz_3|AbQ;@{9@%=ofhuX2Rx0@Tc?Zq6Dso@wPi z$Qn>&xvsxa!d zl4*je+KWVbnyCi%3|jsb=fQ4q>1U+_op;t?A>tA)MaIi7Yt$3)Xw$N@E`S)WxmH7B zeD3~e6|%r0;=%o_V^+5zF8E$U?p9owE4|v#nAXQYbS zO+YgHGJQuIc!FhO6r z@6!2*8i@8yg>c$nHzsdv<=kz`i@}oEIlRc_gpa8-5SuRMOr6jl@&!y2UcRM)Nn*zZ zZ`wo)2lUU){l%fAOu9gb(OI?<|B9D+>iEp+*_)#*7UC0*uV5@Gdi|@li}3yFz34ng zqO;Hmh+oSa03f%_4ww2jSVmq#)z=9L#VD%P{>AKcmQ!ar0w}o=K=tLAnOF3XKV`UT z$Aq72Oc3#R%cl8beQPBjZ8`9j;o8Fu3gqxkB@(@#8dnMMGBN6ycY+rMzU*9ysR)VPz+M& zbE7Gb>Y$rWL46HDc2_+Mlw9D&e~h;-MA@=#mB~6$!c)epqFbx=BzVK_n=X?D%({;! zR?#+YKD9!X7-zLpmuBN^+qm*x_43(4(erx=wVE?QE}vb84X?QS-rR0Eh|x2P@Z8R{ znOyi)orK>m=&X8GUK!I=vp1Ztmaz7k(PG^}xez8x!%$`B6@EAv7%s4XG1=hDb+I>- zUsD~ckW|dE3dD`7vI9@AE9r}kD&XYS)K^wc!7V1>m~q>>B}#$%3>AN?-4X-h7hfvd zjtFm))+&MQ;hyH69{c$QzL|VHpObq`jWvFga}0Fuyl8OBrF!6L7x^P@ad-HH3IjCZ)V+{=yIh$9eZ~L%fjqy2S zU0t{`?o5v~(*h-%?CKYg81&uG2Mg=(iWzSk;y<^~x#frYB-fFdVe{=cI9U9lePU$& zb+=pT8{CL+G$>89kG{S;Z$Iq>IzR- z{Wi>VENyRkIqKLMv+wWptf;2Y+bQ1)YF828<>cT(9;48t6To_BAE4UMJVU7^sUQ;& z@}(X@TGK-3Rbt!;)fLrLT(QI479l=P{``K`-Dt(DfijuktWy_A$KzsBgEo??g3}se6_%g=~bO zgQExZbmXpG-vLo~d51oXlO?bE&j~jze`pf^PY5^E`lV^O<#~pBM)rrLWG}hT;!kc! zw1J`>xvq~B1Cj*OYRKDdKKc*o)}93?(bLjLgD&p`8BUej^4%A_;-3;L-d<%-tW>NJ z8GAq^aBCRJ0dgI#w$`uOw<0r^i!tQKW_4;_)7`_`lh_J)=kOiQKvZB6w_6*s5Y$1x zwmL|sB1)m%LtnH9U%sS&tzceH*5!oH%$@c;g8zST_tsHy^y|K7BZ1%~KyV8X2o~I- zAp{Q|TmvLXBf*^}L4p$?K!D&LEWzD1xCeLFMjL4Qy+yL$efF8TbIx6RX6~#tf3O<5 ztGlX;s^|CU=bIre`TEzjb}BJS((9E2LDlg?_Nk$w4J?(|Qx%uIY z?w6XzOU&@h3EX&aaxTihem#;!gCXi#f@H}+D>Ip@t2w3#Su~Tr*n@Z~@aP*DH@*|_ z`VbI7D`mu?-O^G$&Ti4r^jQYoV{zT359F7lhT)gJV#KUjQC^jdMIWvzT=l5@ON0sM z;{A)&qBB<6R*+j8SU=Nwwdltxp0wh)7}&Ky zAbsPiyysm=oeMt3{b6ZI>U)EYf(c`D3!QOote<0rF|;Pm(RC!6QAbJ5z;k)kkpWC! zr%NxE17dC}x-oNYtaUDHV7(4!p_Nk_sKpiRLATwD@di>b@x&0$DoSsz-6^6kUs@DM z8L>!jW2I5fGSDX*pXNbC0^O&fHcDTzPPCOE2_gGKjy=XUMr<7-+Tpyz=5{HGWZp?% z`=8RJqp zw=NO5Elh9?7E;0uns43sF4ekyKLd|LNACO7KC-`XE;JjLT1DRC^=SM@x|^`<*DKV| zR9m7hZ#hpk>0W3o8S!nhAG_HvYbp2`J{d74E8l8Xgt}i}HG_m)}G%dlu1hAHa3wKg!jQ zWmcW+AI`aq7Nw~WTZ%&iwYxa2P^->^N^{LQQW03&m zxG?wg_3ZBQ6Tj`B&z8B3NH{=dyAmYhu56o)ZjDv7G0*#%;>RW5pk?^@?!R)Up^l^< z-9O8@p)O5#VjggcZv`Q0k>Ybv&H&M_#-`>XsOBPR95H&4dH-wA(rdFiL|X=q7Joj% zuML>mBE6bIwQ+y6$ZE&=7sxvJkU>1+TkXx4hc6a$EV#tmzzZdN;D2;jW#AwF_ia@= zY^%KhSc%9I()wy`K6$t33rr9Jl>uC`zd*nor7+ytNvDH*TSwPONoFv2fVx#P@SRBf zn^~y>0`1! zKg-+LqM0}#ZNCP8oRu5f?{rq=W<24J)u9QR`|7QUDph2CdA+b0#Clj4#vh-N#vK|{ zaY_gFz%{+5*r+mkGTxrXGxFqk-Q;zmW~0ER8}~zoWa@~)Cqw>)pmncl^%4(fMHuP} zegm1LOvWzO9|{cTvmG&7XAbwR>hZ>ntS^e~_1q{!H>@piZbt@39B2J`8p)y-IbmrN z=772|Sv@LrBW&CU>Pl1iHtoT8N6y^B-cUv>C%a{Q+*t6XBpTH@qju!hdl#IWo0R@= z1)rO|1zx##JB@2p{=WCDtZ8V+T<)id)3j5XaBa#;C42(J(tF}0DHzw|_6+@Ec(&6C zt4ajU10h9??o;ers2YTfAq1E2wS><2e`!%0$c$Ibfy;L<92cZhe^NP>?B*9ptoqY_ zvvEu2Z*;bCx=m$@e;xf!*xd{Sa%E<&GPiatgh#GE#g1GZ>yq}S6^psXPE1y#*3|_QQ~VZ^1u<}|5QxO~ z{o1qfr5e$|9a($U1u};>==ch@*AQ9v3^dfw*}bW}y?R5h7Cj7>($z-d!<1Wsr=P15 zTFbWCAqUiU0uNuBu5T5t$L&I#6^_Sdb@lXiRcZ=zRZLW3Lgzz>0~dCGVi{h8yr#}U z&NQIL+Qbg%OnrcT%jkxk#PZp~#%)heHofN6xF0pN7g*yQrlHqr=S>cIdb7Ja?ia^_ zbxkuDA2Dy=wmy#)mlVn!ubfk69p9gNa6fbL#10e8`{OM*lyL+@Cz9W@G8$)|KT7#_ zoFg|mD$g2!vS(cQ8oMEP$6WGwvNp58lZW+;>HCn6whea9tdVReg8pQV}?5-4Jdh+g%a>AJ!GM1IqP355}#ppXy6t6yrovQXa+tn^`U!Hu^I ze@xc-gJ0J7GC&d;$!h(et8e^lE;LW#!}Edw*gBE~s(c(3le3h&5usV!OZL<|(XqE} z`Kx>Wwike~AH2Oq6iQ?kC^cIX5*CDaI+l8~Ao`y83t%$(LW+z?E~4RIjQq^%wEn3C zhLU(2cE{taM*y5@V4qTyWdqtJ#QrOObe%3>R2#4Gx(W0L!2;8UJz{&xT2Bem(Gy13o01`{trFY4G}f@5m5Y=DJWS=JCoRbjAao9_ zVsxU3RO?$90Ly84rNlbcsIP2?!f!8>SjPPw$uVUq?^t5@JKvNQ`*@UCVV@G49kJdo zJk<|mrKqJcu+E^N`ZqI54w)X$CuS@B&N(#9$(e6{t(_M20l_Buua}XeAJ)Qjeinwl zW%o|6R~B3m3_nxGY12oh7VSFD8XDE!h&eQD{d_Qiz2n0H$Yog@(?$788`Q|V2`$up zL5t3{e9F&QY^Y(~kml|QqmXG%xsh(G7ph-;nPu@w;_#;2IXM9N=mq$nC(hhs7dfp3 zyQqTZ4{>tXbI!`=f>tKp5Az4;6M8+0hhb2r8jsP!U!3VS_C3D}DXa7C;oly!5kZ9; zIgD`#?cNjgjiWvtpK7F(B8TDm@7$c1X+iG?9=Go?Xx7-~0ZsL5TYC|%$anw(ph#8y zc4Ex^8MIw7{S4zfA~_NH5SRjL?&xOh3~vAz?X1!K^vdBVQl)**_sA)fgbPis`qbF1HbR%9hm7kifx%qhzpP z2CNP1vvc1?H^{D_BCb5tqBjP*)fJ~>O9PmfvG^EIK?~YLLqmu1#hj57W&$0sVa&0{ z+~3_7rG?X0c=u(o`8 zPf*;dMW!<>JP(G0U5k{l@oe^#Yr~am>114f3J8mHIUne`o zUhfUSE|sK>l#wK5p5hn%vL3ajRv#;j#TogOwe!4p=hZeaeG;axXzJPwEPtP5wr<@4 zAWQRy;}%57tUJ)oBXVLAsN+XjJ#zkfRsNASq@b~6G@2(N%nzd}}J>LG!G ze~jC2yi>z*dbg~W1d*jez^fLxceXy<+xX-2gr`puR&m19%WsP~9eG+{{uuLaUCt(i zRg^|boiY4Xvo=IhK;ysrHW%lXR!6V6llNseFcM4)kAH z|9idQe_%-Heq%@g2i^}@EB*|(7zH^|Tq1(s`~`A_#)CW;f8^klh3cz|Botw$ymnjK zzAT{`%zF^nvw$fUwMD`s<-BU-tWlk!(Ofz1QU~-+RMv7Uh&7<`Hblvjx6*W8mUyRf zS~nWx?}lyDS5?)%pSWGM;Ql06(`yqslvuQrys((NGHNYivJWW|&F7Bh*0G8qb77K1 zr>Py}dfMS#V4dCRC3ZP(L`e-kNN|s(T|#$xM-uI(EggK;#hD6mCkV)!=B$F;M9TVd zD(EH+$5DE|3GTf{<>K<1Y;Yi0Y|5)}E*wVNO)hDW^!fBcjZXHJ%rGNrXRKGO&55=1 zvw)UzrTo+jjH(5MXv7=mv%U;`Ikj+|AIDlXVI1fETa(oWy)Y$ifpRQrBFp#@g0EBn zqo|5=|FBWG*lOC*<~rzCbCZE+ul?5PLuFV4hSqkFqT9ZF(e(Ab!Rhy}M;T(dMdWOA z`>vqw?Do(X{LY4Bo0E)V5u9P{=VXU~=AZ7m24=IN8U}3$=hlVkN+WfZzvq$Zz&y`Z2pJ0u@l62B^q6&Exf zb@kP-dniiT;H$EBz;6G>YLRr7I3T+5s|Csj-moCCr@qVquD+}%*MdzGoNw!H6f7f1V}u|5r1+xbw$9Glf#(yU{?DOe?uo5@@o&)~e1nR;J5$p_bYFdgMcx+?pf_XTqKyjCb47MlivR!Z*ihz7M_2veuoE^(s{o#YuiW z?m%Un;z$POwC!X(Z=$;}(==JJps=ZgCi}BA=(_yVuB?}{YW-MM$T^GaAn!h;py}J( zl3wos{Z~}Qc*ov1?7x@`g!l#Gb8ViLNK}>a*Vdm%3_94^C`8@wn_uGIND3hr=gPna zEwEA^fqn^-lb1f6+S03mhp%R4?`U7{DyM&W+eBywwtQ(yB3yd$!)1`h`x!AL`EzOH zqpYb-CgY-w&H`t67$_4^?NJ-^A@%nCW+0Wf7`JY~YIwERbo^}w*7g1@#q)XxOX8XvH6>!Lz3G!!O)#tH;Sk@f!tL*&QCvj(-b zJQ5`&$ARkfnY?QY!Q##@`81D^C@o1`dtq738GmpPNDUUf0GP#nUI$qr@i9s6iYFs!>UKo>}34GLGS`6{MUlq<36e{^AU2# zwTB-wX{BfVg^kSYbUm_Vp+s{A(%D@;62nZNgHGSI#XjQ`r1R+^Loy7yQVbPYW>}Xm zEEjmK2B z2BXQko_+CVejJ)r@jf+8b>Y4$O@{MSnI7EQKx*==Nv-%35L!6ZBzR)+MRaVp3U0Ed z{PJkG>Dy1btg%#d6-i~>55P@>lcXU1y zOPqorn!zF7UqqU_Q`6eBEg#QBskMOm5typ5$uvsPPx6to zSIb%Ebg)0>@tp1bmf{~K$YljmPq4SO z6OWfan}#^&D_Br>v5{Dk3%um{Um!w@SXt(skF+IkP2eg?v5OeO}&)z>5E?Cn&lq#7+Nx%m`zAsE%8@|&F8ai3m!OpmC zI|&$41!*-IC{I0xG3pNmCb;9<;pL1N_4abNIMshYV|q`0Dv1lTnkn$GaS?r^Z1h0> zkm9K{K_`@T_W-8jhZTuQppQd$aqZk)CC@ zCr{tE9@1o=X1_b9O?6*<2|XQz9>vJT(IQSwZr0T>(PDPNB7y|!SJS@hJ$Gmu1@vxi# z8J08%aNUG~mYte`BLfcIb?HC$N%N0ml%&F60gjF5zuI@?T}AN!`n~_f_Y(f^&dGnd z-~aAA_x{gMHqjevrh}hy_j`vqW@Oya-apSOTLAgq`!ir5lnzwRPZarE{^&n5(o~)I zbOHPbCW@_FN7`$`vY25_NuXk+hN^w^0U<>j)M#Q}tZIMxU@l>Sf(y5`kc#NMn3V;s zKJFFVoV|KhtpD(Q4FMO~p|=&P&OFLtZwPSC`kuE~gX*28BnMn(9!> zfV|{7(my7fg!}Lo+04cd{%rn=kbZz-LFxR#E4sa&gKb487$Nmd<_)Ov`%3D96 z0VqD>s0g_8_~_(xWWXCnD}a+1;7L+W2cB4&*(Qd^w@An34b*-JoK zj4h*NoMZUHem?jV<)!7gMAgP7P`b2JDkRL!p?(UC2LglVEGWOn0~yEd`R%l4hlU+e z=|tTHFt;=&9^>?)ffzpNcAOB4BIHXMlDxfk2PAHR;HU=?QvWA7atIVb#$;_L11Zb5>wT^dUdmE} z=!f+$@F;Y*j!TNabN*VGiE)fT^&nY!`zJh_04D!|I%N)@`W<)1*O~=|pb8@ln4V*L z3NSl9Ym8BV6oDZdq7o(!V$kQ$m1@9zAW);clN-P1IsA8Va(i-1LIenbLZN$MlRb{S zU%y=k7338YlA`NMw)IdtVZDg?Sb#Uc@MF}G#N4V|JijR3^9K(Z znN=cV?-Sy(D^h*}mC04X+-g>ruorf#q$9uu z(49R@xU{L5iyWhCGdaQrZL(xebkAAbQ_aTJum>z#9_pwdqa%W-htmMf5hi`ahT*Z-&fJ#MQ-Sy*PGK1EyvFAt5l5qE2opK)t%e?Lf zX0>*#t^Z*s|4+kM|1ya6=W6{o$dbRW@;kz07`z1_OlAWa?mt3jC)|4`hJSKu0Dm6H z4rF5ArPM&bk+Yv^P$VV~n`v&-D+kRxlKrwBOBZ{X7V2O2Q7Kfp<1Smg^%rA}Z3e&+ z!M39<+u#D|QUQ>PYlN;c2XP=s*RWh5N=f$FQH)R?EtF9Ec{R*uGG3(ZEx}VQgccLc za|Oz8tG&6`vwoP(oL}o?0Ry-E+e>F$Hnf+!;NuK}w5M!S%}hSj4@@#Yn^n1dTwDWCB4Tvmiz;c?VYEuNOC&U(5 z?Zu~>lo78BYd-48x`gNl&ZOqM@g|>~5>%WD=1vrdXpCX&pF{>`^HH#X?o7eMETTn& zUAL2+G|Smn)M@$~EvyMik8&mAzRfMp2Jv*`k90636A~^B`Z_ut6?&#Q$_{_2702^* zy6w8gK37(HRXbUlQ(LcvZ~pou0{?D!XZv5$M5V*6EreUgF9o@~EUACa6UsZuf?3zt zijN8WpZRzf7`9ov-^^YLEyhfVAHzRFEo@+?Kz{ zdDKc%iL!Oqq3Vhxj9edk=EfkvtXdB+H1U9fX0Q|u=J1mra1YpMjpnqu0|iUEpc|@zUl;gffC;hV~=T!>7>~*0URZ)Kl!Mv zIu51oI6a$bfta1a$IrXa4sUvtw7`ZsHnlM=RtiUyid{-G+}+Iv@MQd{xl3-0?n{_J3Ne3 z#`$OtC*8EFL#l3SVj4UqkT36z5cH282L`}^0`xeVP2kcn?3)h9j?6hdgTZ^78M*5* zUw95@8_lC8&+q*nN#yH}aQc~Z6Q;@vK70oF=VxkYVt`esz4O_BM&AHVpih`DF=+VD z%Pc3^NMPJ%>2bOYi1+W8|K2`-R1){^*Q5V`_HkS?WWx6|ZtqC|;HQ6I;q%VD`(OQ8 z_2Yu}u>i`jfV~FfyrR64uh-Tv5wVfZe_+DBz;yN9{c&FobH_v$F4vP>(h_i1@It#& z&Nc*peB>Qi%0yVF+`~);inFu+0GWf|y!pM1nQVblL!n7k3aE<(eFFk3N{5^E>EWdZ zu0>7WJ?`#_i@HuEpa|1@@jcp5@E&PAWg$1e)Y<&E427m_R-(k{}b zD%-?H>?gfiBc-e~N0`IXa=*dNrrJH0<#TH1yNI_osB|I;8jM3>VgY%&%K^P9iOH-dHcbQte<^d8S6;Py6Jad+1xYE zo9zw-ItN3(i>Qet%=?yE4LMJXLx%4LKI@GX!^aXn(Xf=U|H32wto8>CTAF(sQ#@yU z#Rg6wIGoEIBuO7k zMj;g0PeM)iHW|=A@bwK5yf)TxedC&MNC~;|w9Ajc8+{q12SxjP1hfv%Z3)khPHvfU zP}bAsvgyVamF}Th%6;Ksy3N{Twh+f#V;88&4gn9Fs=a zI@mrluWxCH-XBfT!}1}D71}v6oNhaf4ojB0{1kn&JPl~=`f*P+3a)Zk!231*tw~uw zkeEsr5iM1-hH~4Um8ek5&g!|$tx!34A0Wf&m${g0GD>@NqYNS;tH${xjeF+KIdbcR zjO;++kZaijdt({q9>K}E^4`a&=xKsX1QFeuGfG<8`MA*{WU6D86lgg0JJJd6P>_|a z1$P=+yq_EM7Xxmy4E*Uf0aEvR{;P`WFA#OKg5!%#>{EJUx#4Q{4OO*Tv75Z) zrwj{~H0{Z5C_mdi6Prp=nNDju)b2c3bHC0shCT~A$D;Z^VM@MFPe(9SFuXkYW{!JL z3WJNp{XJr5=KdL{FF>5Ib42UVZ)chNMuQ1%e64gFx{7|23`iMJXromm-WvF_mN?}r z!UXM9Gyqj-;9hdkelRbc-$A{eX1iPKKICLYE>5e+l7kA6P(Yv6tboc5P}6z%FU!*T z7R_B45(xcMrQv@i2HfqB=ak0ID2d=Hi)&MsM`)BA{d$Zip?}P@L!C`u?ukUhy69yPaM_k5t*viM$I|I(9&`y{W_CB5!N)EfU?ST)!)P7rJp;J8&H-s(-`0xx zLPZ3kCQuHb6`iv#&q}LvnZ6ON2i{1t^lk|adb`gdL;*Obh~+IJ8Ub0g;XX%fj}T-x zi_UMK`iP@;Lr7B&6yD=x+B&CwgN>3uMfz#2Mc=;g4!K>kH_#7L>K0u zOI>9mtrsQAq#YtXA&aj@Drb(832{G=U|Nau%1u~%eyofEutwUsEx&#*aN8KIIb1*DC%Cx)ci(Bn0bK)`=4!yCusOo&I+Al=JSS?a)lXzZjJ~XK zw((}l>H_n<`)-xaiZX zHNn|~Kw+HU?#XnIU?E1X#LZ_Bn;%RH%T({!V&T9|%A_fO-3Qb#D5j5#lYNX)V6jX5 z^^5%bP>YA}TZDz@(!A8}6&y5Eckn3DMm_83UI92ume0_sq877i-qs!;7Ug*C>5hrX zNR$;USSxa>AE2{-qk0`IzBgRF8GZA7ZrJ6-XZ=*roYEb4YmU5hP7NXl!|a?M$9*!e z4ZD)Xwe4OR2lSM~)q%tY^^$+3vYhs)E5>+Y9lkeU%f;8V~Cz(-#ui-W)r;(s8koy&X9L zc=su1pX<($u2kcU5BSQfNn{nugns!ly%7xMJ7;oN9Kc-AJ%O@ME>*>5237U-4hi5Q z^)j$_SOe=D-~9zDu56;c=m7UlTEh6lpv6i+wBdycF5%+eE`GgQ!gt1-eq#v~sI!p| zQ$>-$wYpS>Yz;Exi9_u)tp2sj-U1)P&t)#TS+xl;U7#9cm3(n z`Y)sPL3s4Jz2`ZDfP+|U_rj*Lx28${WP5&l|3J1U`5O&A zV0E2-*T2gq2?(M8M=M(}-|EuW4jl|u@nx`*p+3W(`9a&ong~uRB0>lqySCdUc6fQxjJ!t_ zpsm>`UVk)%W35oD2#DCI<|@x*_yTvKPqo~JvGAH|AkE|B4}C5S$kFk{I9L0YchJfv zx#<{5Dm?dVKteDb4Y=C8%Wko2QH)D+^{uau{KZ(pOSY>oDP%gwlp%#L)g%n)sGP$< zxyRFJs}hkB(4N*E!$$y&fc`)Z*}VA|Xf)D9Qg`>by5hA&eu2lM*~QuAmnYUI^@BaH z;{uXTO|bNIcMI40EQ8sC40K|#u(#|jS3X}Xk6^wzM(aqHsLI$Kx4AYd*<%`G<%40e z3Y=g-`X%V+W@mh4r|pWf!*D#x$j!sJNM4z~yXQhf2rDgGE+RkR`>0Meb`@DCwMABZ z0mI1QXWRRgLrXY^hQ)+03FlyQ@92Fvmw!A;S}_ z@%)|RIS?wYuuO4B3-td50zC%k6yefSM=rF))PAGcH`e%A4}wg-n6Aj7`irE`qREb( znGjk(uzn;krNES3QT!kf*ZqB5Sobmeseun4Y@&Lsk%yy^(uk~(7FsD4V5xx-lPLnR7n*m@F@a3`GaWXNo~ z?6G!IfA!=tZt|(uVWatKGyzZ^?0IoK?-ljy*_*}$gWHCr9ICU+(ntP(CkjPP0=68w zjHsdp0dvuV=ayjdP|W$;PI76X`I{_CaZX37{bNvn>^sM$+;>nMhZ4S}P!X-6Oh@V} zKoT%PGsrL#?McG|sZ8}K;@K)5okxC0Y^s^-C#8!qv5cIH9_D0FK5ZA2T!}}9x;l86 z0bTvVKIbdSRr0R}m|V!w8I%eR?Yy}5;kCZj0C2}-w7f!V;_zZh=zW8^MQI_JL-4Pz z$Gw{ttN%hXxsj9Qv*;rw3!keX4VAO@X(lBNN^);VCZya2`i0mgNp5TnV@B? znxNB;3RPP)OODRdJbkKhYSpCDNJ)TuQ`pwaVzcpAPu-8Hp49`+nOP+^(G<_GcGhT5 zg%C0tBDVqZdQn-rUt=wdp^BS(uU#lztEv-D^(w0%A%R82AsZjkQZZQfKShQ=Bh#B1 zYzoe1Jz#j9Bzb+z_R2@80)%G%uH!aO6Vc@a{pBVM82bq@A0$NLz(G=5h$kIxN<4=kw{8t)9-De8TaVn0pHvjfbB?n$L^%gT2@{|(obQ4Ola74qj(Wy z_V#lPP9fuCVF5z(A&()*K$olELzqlnsHJ$*zSE}@OzjBEYHo!RKD3&XJ2_1$;2u93 zq)`n4Z}ZdMUKK~fbw%VZIiW{@<4Yk8LzC~Bulwy+*|2xNUGkXI8n0qY5k8`x#lp6K zf#xPUuCq!#4O4dVdk=1}Q`UyL;u#;ph_i;DzRNGb_%?ZxN&N%<(Qy_4Xfne!p)0SA zpu=6mwNGGwNXL#TbylW0jwIPp1G(aa9xl~tZj|i|+CKAdeELsd++8&I@BV0vY5dPMQRJ=f zG#LJsJn--S9-L5)koy)%+HslKQ_LOPyqV{$79O|FSGw;r2kS5pS?bg?tv;n$QVuad z`yl04Dz}NbV(h#QtSVwl$SeNsapQSau{b6AXAGof-my+lP4%YEP`h{gGgvr+46}9g z5rOMjaT7Jlxz0mHKj6;C7pFb-O9?mzJ5%fYlS3i|hh=6xXQd{}F zHli=TTuPkFb@~a6`f%;wA&xlK(|7kv%z1|X0==MGn_n$Qyk7N{zR@SZ_E3dD+(Vm{ zg2|Q0yn8#QN3;Pt3S}PLjMRg8ewPR_t#gVPS6S#YAF<4!!ZtOl2^Dkw_ADtA{v1aL z8g%Zx5YaJhhAOwF0%THFEmSDBo*&<~yURaYmqp+_C7B0`=m??4s=q| zfyseUj;GKw(=u@B&5G+{3Y8zj_ep*wAZ`7;RhoF3e6GPmyr}@~UNh`^44}i3ube>F zp`*|vAlE>#)o74sjijymVDzlh%kTRMHvx6|cNWl)inkhu9h3X)R!2c)8K@?Np~;iV zKn9#(PVZ-mwKd1D_zctP;q$0P@lmz%53jP19mh-1gxTKVP0&R|^9%h2dJnW;lO_9> zMz8t4{R<>tKKXWho{xL+$@;xqy0gu)HX#3kCnKT+j;{O=le#WPc__3MkzBYe>TocO z3*S<%tgDLJM9}*isyx=dU9r!fegCi~B-Mpd`Asto{FUyaJWPgOr|-?~{bAx;TBAgx z$=BnR!ylW85;o1AKh>cY`5LEBGc{mfV>^Smf4y|aX9Goy0Y98 zC!S>jWezaRj$uM$AF=YWgVl;y7{7N)PvkSTpeUd&B-B^Rh9o|UXxaKX{TB$$3^>D} z6|2$;eK=$lO0a#h>y`Rh$r?+YF=n3Ops#hAVtxB}Npf#0&gPonXF?cAxo8{AYLwxE zc9N9<5ZKIsrxd4uz&Osovf+drni-S4C1=?7no=fCR@Qqz3T-!DI>Qe@-Z%j5{tqvJ z2-gLCIR}k&u8gPonSN4M>oZ(83X~%6w)%LtRq5*KjmfL=Gn@qmxtfN+ol(-q2c(c- zVZ%r0e*Ej78@{-hNd!l~QN7Zcry8z1#e5)sxen94lMrG+Hs>8pQ z>Srgk^I+b(8aA(BbD~6$M%DQ;Cx}Ubnr+}x@G=FUTLuDjlk?ntAUnZ&^KsxNl@`Ht z0OU-!p-0ugc`<=2%^}~90CA)pl7Dbibw(4Zb%~R7DFXhN7XU)$KMvhyizWN_CYZd3 zF3{t|np-r$Eoz>P{Ec55o38y<}17kEzE!)%tw-*!X|FO@y*?;*I(*O8Yx&N{GxhR_e0b?@|zj&^p z{4(G&boYlhlyofG{O(^TVL9L8yoN_?QWX^gaV;?_mCj2g{qiGS_S2{AQ$Cy)qF$-! z_5{a#lcn8Shdy&5#9r?A@dLhop##1>tCEs6qe5aul2^X0gU`&B?yiKfLsR`-irjkM zCAdeYxb2~~^A%xLk!69w5c`8U``nLjXGnuhx+}xfwO@Rp z;XQs5y%zbj#8nq{Amd6<9y95|g?LYuPs$oC=B_dJ^!hmet04)ix9TSYsb8QUZEl{E zM<<)6psMlQ-(H)5201~A5CjB~2qyme$C0x0euaRn33DHZJ)tE8BhK95zVK5s9GuZXK*U~+dayB9<8#Ko0$S21Q= z#=H4PR_a?(oCYIRrKmo;$6+Mi-^IQYI#ya@^7n<;=gb=w8-YV&IqYvb(pW|xr_Jk2 zThb<;)H<@(U47+R{-6TIzBKTBF~Sh=HSB86D45a#_t#8yF2vUv{lrvqqguArF;?99 zY8se@nWEG_j%-l8*$nY?qPa5WMMSRa5bdR*e-I-xG(%`EiqdK!Pf@Be*| zgJi3P^c>A$$$E>%9 z8P*YdW|~1nul@^M$sy1!Sl@)q!&&BIo7VtLR~mhErgyYaq4KZ?Eo^eEV|M3S+K$7f zx_^^3;_GKJu!>D$CziB_;;K;jqvd__wFt{=oq?74w8sydPed*4WgDY~fxZm>2_IL- zLdEyl<0XC1WgQu)2mn=z@F{*F7o&%#8g)X!V;D)uFkWMs8-ezsmD{)PB&<2jHP5i2 z-3{RIaWN>~ky*srfkub@(qUs5!H$WQC!maO&5K6?eQ1;IR#@6=pKIPHKRh2nE6LXI zZPvAXW+!2)ue}3XR^q*65ug8E@$u<>bV5(!O0|1z_x(DDtpW(k2JfF~PWWM7P2<6O zq>W5gau?dWDeQz3HYjV=fQ%b_hkskSvp~)#;7Z#e^dR=M-K+RvL{5Se(9hwMZ0e&h z7S&`;^jX8ZAU6lq)XVR4M4c=e8eJHmC$*P6-5t)Mvr?HxrcARcY~083V)G3vb^&>} zh@-KLzp5f2w!$TTk5+YLR7nymZWk(Ygd~i+Z7Oksu4B0_-G(i*jWpvb5c_dXC=bY5 zfy?b*#stqAJwHJ?h*|Wf9~BcdcRo&l5~@7$-gdoLgE?rId!M?=h8E9i%Bv^LWl&^; zQP;jygZU`~Mw{4L@_Z$XAaDaP<|BxE#i`s(TlU4P^z_ujFUJh_kPk@JZxdU+YSL>x z{j|S#)wp#F4}z3E&G8eLmqNXKzqnRcO_XGX8ugQ?`6_$Ld0iMOX^d4p3-%LuL_x9{ z<4N6B*F>5qYZ?0z_VtWTC(=CwJ)2lZCc}eSWBTl(CCZzPP3l=}+|qoAwjQ{)ZWkCW zajwlNIk0T29}38?+RV5A@z|&;CybVZ%HN)xCeVq%D`%Ez7VgTQf4@4`kkaZ>aNrO_ z1@oO~GH9raq$~q&sR?5o%S*y0TQ(XW=KCO&NmG2#TIeIS!lBw>jb4+r2!X`D5Y&z< z9u=mRd~*m0jo^pv0^@GfN?ihdoJrofp;WbxPL0tMaVGY=9iyD(5Nr!Jc4l~@DiCo+ zJsod_H%{d}_lI~H&QyG@&=RsrY?5uSB}!cLjqef7{xtjav=>)od1@+j*;meJH04$B zkxFG1(HFGEg%Eck^48%hkh6>S*&;R!U4q_-=te}r!3aI%2jT8EG(u=O|3 zLZZuD znKRfIhI6g*J4^_h3mq-`EXhC2*hicgWwpY%XQ?f=Wj!+R6~lJ6;Lx(RBI_xMmk+D+ z>BGi6>>tU$F~y=2S+_7NcS*&+(Vxy5-G5+wqDR4}ZHwCf^%PD4Amrfo7^bN7f*cqi4)`$4iOKUpQ?%BBWm3Mv~IDvcJV;cGVYK50^!rF zo{THo$+8(qRZdMDNsMrlREm*kMk(0|^DF)ZY9&3EvUbi{{I#cDql05pq1!93U~pIz z3@Y^|lBCKdnXySH7>dv9FM!(q+I73&W%T;&<(&{a&5VA+wa_g`UTi{a#oST9o}k24 zS7V`9QVMEKenPH|Xwe7t{N0&`)H)w-TOuGJK=6-GPTOAkFDUm2+XozzmBqAsezd%- zMZnAIU3xo3lyj6?qtMmiKylWf`=qbfhQczCBb;?ND7VE$=&8+@d0yoBYrmvY0Kdm( zV6|KmX%@zGKO`IF6)uSF%NXV?@`=ZXl`8?asi~M7RNRl}4rBFgFHyr-ekZW+QENZN zOG=yPPFuQ+3EKU&+Y+*NQdq*7)m$FDiLpS{OD%uKFI=pO-3zWbw2KR@Xi8qd%qsdy z&^wN{X%cBn8!ZWsce9JLAl>F1m2AD&e2EmpbNLH|dsf1^*ILL|Jvt1Y&3Q;pD(VYD zux=f2SY-jE+6J^utBsI!Qz_b^4ET#z9wz-?V#w<_f1NSYjx{3M0omR7#ui>1Foobb z$HQ)APM5GTvS0KT7Lxbr-j@21Houn0d^>o8h($ScA~+$*E#hySE=XWSfBd*qveitL zq~GW1=dLw!0BQR^6hQ`!^bpb$QuR$1v9XDEBUWQ6D-i;|{{KDAYk;Ki&*b9YNygug z|BrPd@~?x*KV4nm9j={`>{V?pk=aJnQwb{auD{Gle|ry_#uh-;;+CFN!qGKSb-=SG zTZ!Y1THhYhdr16&7_IGE+awCmoF6p}wP&#OoW_o#WT;!M(> zaK*$PuHWNvvXzy39kfZ6mGlum*F_)IACRMuv%$kncIE5PIRU&|wr(W#9yi>5^-R|N zgRf9d)(t{$4FEP-_VH4uVuh!ZsVIA-TJhnqvV@2Yee6hOza3R z;J2@PhVk;++z|fu{D(l=`W$fECRDF)$e#ntrQJUgBnpza(DTr9@XsFzOTT){5Bw=T zLb}B{VE7Kn_ZHrSgAtv0?qbwCnmdyhW?QdCEzCX>{l2lDOL)!;<6=cq?9=O5^3CecN)Butblb2W8sG<# zG;LWPnt;i}cHqN_#@~H@y?Va$Z*Hr;0qdd4DH6cM!$<$qUn7{`;n@lk#XyGzvwF+-+RB=VGSlRleC0fu-o7r6 z_j}rw6J@35-1Cd`%Cs8giUZ)sHs3SQ%U&F7?ih286^qfAcDNIMPc!H(<4AJrc|aaF zfcMM1V6*Y07yuL`2wZZ_%=h8yI9@py+eLHprsmJ_q3o!8gb~nq#C6Uxa>obg)@Y5z z3@eoM9EM)L0Ybk)k85@FC-EyG{y3Sl_w##ThAqSN*8l<0W~2DJ$+0E10^B%uN z`xcO%t3FvN&LKgo2k}zw&XQhC(W9@&X22zKwCHIe3Ci9}PJ8ct(L`|p5r$P(Do1vV zLzyh_I?5uBhtSxtyaA?1Mes>1KQqM!$<%>tKUNYsxpP!Y0FPoNdlQS5olN?a(UzK8 zm9=%90<;8wKiml=1ac|QO}304MI@uA-#^goJo2WlfRvK#x5s|$CuigmCOa#|I6PcM zoaM+ZA;IE)i1bdiDZzx}*jfM$$LGn>g*JU7e`oH0baad#?K+ zhLD-@S;pX#%tB+E=}7lN!#>w{Kfk?+Depw_zk}~ZP7vA9-s2nIuk?KUV{MC)#<~QI4`+qgYPjXg_*ne!b0Eoi@7?TOAXoc& z3=lrmyVJg!s5@O{LTJR%T?G~24-+Viuc-7w8BxQOS{YO^0=Kyz?@^%HG*i_#s0zIJ z)IBm()TT|1FD}dWy?oRqlCtA^aNF+rrR+qbL|hMqH)JbRrh6f&jck~1E%{WLp!0e< zI4@S2NG)Nc7Zjrt5B-*gXAs?!#_~}o{Z+Jn9cj&jkett-ocz~0ML>XC1t_-&Bzfk+ zRn}fq)sCIr3U<;z2|HBf8fN_Q9ly+9sQZ48*E*8c`ck`v!d!3JV=%I-vqm&nEJw>H zZd;h-Cq#mE+DFn1IWx)08OZFScn~DL3tFc2s`33F?Y(tW99_CT+5}4on&27&!3n{g zh7ddi3vMAe1b1yDxCICh+}(l`+%>p`#$6kCn$E3!Gv9pQoHOUF-<>;i&Ry%?KYDeo zs$JV^SM9yu_j#Uo?GS%gKxV?msW{O}^JPN}k`qN@5DOsHJTc^ESs)UUeYGUs6lhhH zWL<1XNBg4bW9HmIJ<3IU8D}@CikS$@2)@*gX8Pst4wTsBPjqLGK$eBFvKB-BS z9qQNNzIOD%5#5}V)_`||EU~gD-(j?o-Kjs;D}(_JQ`oDnR-z^;J2x^N&B2x0L^WQh z-eZh+Xs}-QEhpmA!xrM%?xWk+iB{H!iWYVxn00vbNWq`e4{%+dV7t%YfrHNllOGDI zrxa8Ll&-~zsK2Nfi3hgfk!@4jtg^Rn*zVHZgv;R8Cq~ST6r7=;Lr?LX1y`!}OG+xg zo?Xj1Sga*c2ii%d#Kt?d9_$B$yrssjKS6jJuCn7|VZ~n9&r&FhWLPo~C~A1el66lW zIu+?INYoPrx+TWECSUR0<=auM@lrd~nJVL^kQ941)M;&x208;_`(T4IFy8-l+6D0@ zoJJO(dh5(AkiN}Yld4L5qb7~#ds9#zu(zk+hoC0C?6iF5vS4SBtSRYs?Y#q+WI(o& z{Rq7})m!MDdsr`DjPp*4wRUZiPhXIpz6xb5Bn=*%y(`k%3ChqiylwZGp- z)BJ+)uS=bKq+6bZ9bR+?=OP<0_-XG!ZXeY^LXSZ4tl3Y{`^xJY3YnHci|hiE<<>Dt z8SdhooiVc;?!0sxL>cs1h|Hny^cPCJTiHcs3wMeyU=9h|9FNCQJBo1O7%~cKtF5^A zvHg-v`{;V|4panAACDp3A(_=S9E%I_!#w1EM2FF^)G22 zi5jLp=+kXRcj#jF z|LTG#X&;XyIV(JAV{^ua_Vbq%$;6eH{=VnsV6rbt?ayG(=k~2+!;9ebsuK3%ngI18 z4cPr|=OSi*KP>0HGw6h{wBnrd-lV?S-eV|JxCIQy2oFH)Br6IAz)h|Xe>vK~)8xD- zgGT@Y@+RdryCmxy+aK5T|2X_l$-sYHQ~2ZX?~|2gefvL5_NPL@wE#DIs}&)@@DrqA zyEMqw3Gdu>IEbtb1$>5oyY@#zvwv?VPT@#{zyNdXpDz8W#pgj-@JcvfTgw;u)fswo zx(zZjBL=ia%Mlr*JMDet3aC-p5n+yp`3@M>#xl1ZGvGB==3D(v7q#p|84}eC>+Exa z(YFp#n_Yvud^a=l?%w0cAt}14Bk8eS7ty?_PPu}+av!W{KgrkJe^~d-%dU4tSclmUCV8@0EAFb z&mu|0W;9x%#Xa3F9RB^a+14~mdex)S_)Nnmfs4e}!@9<*J=&u;{(8@7_NcJo8VzO9 z4Oo$?*#;-KJ!|#C#q)!9(d7zp+hc=T$^PHYE`uFOxM{F1l3&zJS#elx(L9OV?rcc1 zj#zaq&qs_*W+O(XK6zfmq&FkRDZ_E2!kl!z-(d@W;(CJ;n;wf3rDEiJ4v36{sLW4}U{ROQ&M0YVOY)oYjeMmT`I?6^Gc(b>i0Upp3-w}C5Ml{&1sMW*MY*Nz!_4McPfOC5vjGRpaX;aJ)7r+r9C z6p(yHd`6`yq^Tm@H;an~9gaD0FczR%3+6j!R(^iD&ex?}w*1K*eN@*gEOzV3fPl8TNla?}*=_<(|6egtgfpU6rli4F1rH<^C z9UgmoKMFQ;o}86n7b(Rw0Iy1cR#!m90KNZhp-QcFt0&9%+TA~~i&C;lI76v?Xl7_z zBL#Z{N}a?^zkSBr!0Jwkgas@+7Q2H39ks9bxgnTCPEPm&F|^arq%5YM0wYrsrO|+$ zNC5{?N>5jKAu{83+Z~n%PFQJzPLTZ62kV~9Trt&SH)m`<;Ck>x;bc(-* zP(veURh3<8Mfu*br?G25NBj-OR;GbfZ}dK_i)!`+#A$CrmH?LM=L5_mFF08ODlSX zE1HRL1*6Jz_J=3sr^vmz>NBR%PPfb9O0Rk`nvl-$y}Ws^#Ai9bx3s$famW&=E;m{` zqV{i>eyduNFAU*!Wg`y)mG>6diD^j}3v zU3eYBuje64@c@|VLio+gmV4u=FH0h*7oHHC+$6PEq^V7o#^u;!_T6VijArj0BNTxi z$jo1ajHLG7UE3UG--=u!JP#m;gOC6Z^{(s-2ob*jrObuv@Z_>%k@x-2{j1!X6-;jO zCw;s)ePef-Wcr_lV}-*0bQ{&*J%J66!sq!XP1E-zSCIJDZ&ak473EmlK=!gV;PT$D z9&~PN8VgzR9&!OnlV3EDZr&1X58ClSrYmkzX6RSLG)m83#h~1;!wbQP^f}`mlfok% z$_f5V{u)p!Zjc6IlKz>bs0Fej&Q}t}0$jGjYnjVSgl;b51QXnt68!YRb6{o!N&7`P zILk-m@R}~{N{{!Kb2(S(<&E;b?TCrUUgT?<+Z-3lyT+RtKRDf0AD49IsE{f%89|5E zLUb$$v3FD6YH>sPFxVP4?qRNMW<(Y}=Fg0y=rMsb))xaX)YK(OF!P@vxNb%gWP-n& z)W&GbD5wQ|CELySzgE@!P;*YJZE?}<;RXcIyV}9`fesn&rO{T7-IJg;KQvi=$S1jD zEYkV)Qb^SyYfs&>5|9FaL~B|!D_Zdw2u;aPb5!gu738>p%c&`LyLEdy(7g^RrZhta zi;l7BD|>l#X}`&3a>dm<&`e?UfP)4aYJ;i za8KdrGSJGg`8i*nFGcM#8VMBKby<9|$x5Z1bgEo$>bokP6)&pMfdpn0wmZ~ki|i@v zKVhD;0W__dS>LE#c7;36!I%Koc1`4}6s1u#)|Y67MJB!xy|`U4CRh4bSCiQVo_-Ni z&)d7D@p_L`nm5NLtpuB?UJqZD6gwu%Rw#NOo%gLar@sk!TCMyA+Gf?8v7_!|(JV1m zs*Dki5dYZoBqtqz#lEZ17Mww7D_&RfdmDrx|SC~f-bLF?rd z)lrNL@OJM3_;EE>e2AqXH&BY`(O-4DPa+%!M$ zxrEckKt>t>r|#Q7s^IiS*HX^UB-HE806*?Z^nsG5LMF<(ie{NGjQ5i5glKBJbnK5B z1CbQ}nuY2RbeGVjyE|^9x&O8GiHZ7LT4Fojjx;y(qaQ@IU9sVAg9t8&h2f#K3y=+t zfm8*67W=*7f66B0M%AP7Rt^Qn%LTQPy`%c1EXDgUi2 zetC@l+Cc^qPvuDa9~Wn17BlwIOyW(aOI_3oBD}pH!h_D;btB5JWN3l*1L9pR0GR7z zjKcM${_SpsS@x|q8NfdPqawt9B}@M!SrH<+IQRC;ET%ouC(ch2_UFHZS3gzjN1brb z_zhLqcfI6{n=p6WHCD%w7psme3uP#85X$)7p#10mf1WKDx`hx1kRyNxifL8Cc?NvE z$95ZZt^SC4tv>AP^Bu{~yW00-5(Fn(u7Fz+DZONm&>j2Bb(6vzTNrL z@|zj5V{L>CY~;=h3fXz7ZsL7>lLS?i{cJi_+p-5qe9&SNj)Uvk(Ak+V?VMn%H?O0Y z6NTyQys1Xb-sl5?5}*b}z-$gzs-t9PsLfNJ#CY*X6A8~&0dWeWh;|jt!H=7mT^#Ay zOLLDzUa>LT<9bb^AmT=M7Fj21wAZU@bVX&CKbcHyg}9=mR6Rk?FLi8S;>v!8c2EvU z)@=&jw3gQiQ#wvd%-efpZZG8_Jg-zz7GGQXeCoq;iWieSefNz>h3kjXGD@;3)QH?k zHkA5vj5Z@LPEAtH-X2{DI>NxY^@eO}iOO7QmlD6RL1AHOXDqpqIc{Y&4sBWNjIW(C zFg9O8mTTc$PWw`~wC+29t|^Uz_Ay%e%B{x6r1856Z~`Vfb&O2|U)WBg zp(?_3RV~cY@Khv}_FHqJ`zs2JoL4us4pCxB!76zZ{%>{!Tc!~)=Z5z2TSklkh2EYt z0H82}ZaepM2kyqs%J7}2w06-x%SN5;mEZ2GkFRqU5~;)p%{kRM1QBMzTnr_?JdJ-3 zqLAV1Ht8>vai9)+9rc~YpV_up?kJRn6}03t>zUz^R7lS928Tr{!dq)p_5zEDI+N`UTS- zl)5V4zM9On;?H5ThL>2~_C@L4-xc1=Jp$;-_}e~WMQ-j*%DFWRvGUT9I}WGM5ZNj)jA-R!c(NB*CGM74G8in}(^U8RN}o6QX}s0b z{a4Yc`7jzkFC+pm9N2N<6Lk#b#UU=C(sw*F%H2xt4o~@?{n)N4hw>`b2V{>rx|aM1 ze^6$0Dt!q8frVy1?=8|z!R0(IN?ib0zfwmC*@oCQQAWA^1OlYjm$R$&9j}6%waMei zJ7>~C)3W8!kw`jPg5kRvB?}^+OO7E+{6Nuq2K(7HlGQSTOkT4JzM60Aj@Jh9M6+Br zWbY`-a>%`~+|!El<;+d9uLk8tKhR8C$D3KR4EUp{6kMCUqNm{ReLbz;9U+47a-Y*o zd!e@Wx+caH1!s|fx}NepcZ@!5OhU#6S!Y4wp4YX}Tm3@5Jaj2=7lpN2j9GVF&1A)W zqb9#GLTAxTyH=8IP@c?Mvq9RzDxotBtIOr}s5X<^Nk&K07b^C9wd-Gxa$CcCKWfV* zwxwu^lwJfqe$YVpAT=4;F5Hx2R~M&K0FZLYHE_t0?Uf6(soTw3KMXZmsFuP7bEIZp zDX7FSAcur$H3iDczA|1Yr0KPbL#Ljz>&@r7W7C`DGJF1hA{RF-Fe25@Pb{L25xwqd zL-~U%Q`yFe5+aQ{H#YA32W2Xc2p(W6QRE{}-FaYadGhD*lp7ZA*G8IC*G9xkeaZi< zC867f(>z1Wg;Z>FjQlnULCrO4UVG@C;4o-t;@i}o(kDe0(%-l3Rw``R^VM9-Dz`ka zywo(6jdUlcW+I>(0|TEyF}A7JZG@tzCaQC%)amLGVzc9d%t}&F_~qiF2`k=vQFPx= zc9V}au~x`xryOsc**lyB^WimGvIEdzg8w zKaI#G{iX8hge_LDY;&RO(>Y~xnxmm=c5SVBIn25Vokk+u9?TL&?wqJ7)uld-b^OxKybf{}NheKl)H5bM33-JLl z8)rH?gE(|1B+9+$Bv4x^6%Ihy>^1-daC*;6cEUnTa<@9YTmkaf}ZzfM}^o@NE~e>Nmui_FUcV+R&{xIiGhF_(|4a$M;xE{3sO zs-(7Fjm7t@ghx(pkiEsOC(d<7C&|4MSd*xjhFPsYVx1Q=;M?n+F6cfgLbC9aYv0`8 z+Ta@&so8$3viZ(d*;N_f$aK1^1u>iq<&;dwY&RE?MFlc{C=`xpbIXd>VN~V?NxCN; z#!w{SJYSXbVgK>=v#xK?Udw$O+^cx)!NQNW!8EU)P)d_u7M!J{0gErTRR*?Yh{$}; z&XXRD*wND@*e-LhL>C=Lx7YzgBl4G{rNDCvreQ;hdE4ZWBsHmz{3P_`cg$LHSfX8f z!f-Y+Mr_otD4|oxARMvK4+C06By-W>zTnCcT{<{Ux-~-950mk=N>pu5}2J z{hy${CE(GP8(n38co!un;xHJqY^_QR4{+TIn~LA<`}%~tMU19=NH0(K7%WaYM?wfS z-hicUER;6NpoX#}aNJ`jt$;q*`nDE|o$T76yeo-zOZNSpX5|Yb0rG?s@r zS9LNql*Z===_Iv2R7vk+4vh6xBJFgs{WI?i31*uko~czxbCaA~e%aI!(3TA4P%oJO z0ivwgPuW6Z3v>#0+IH0ZKr1h48_4X;{LLS;oWGZ5v2j>&+YyW}Z9^h84>8eS_bOdYdQFZ&e~@F4DetmJwt${Rl)tTHUcKl_Yj^s# z4M8=*EoX^d8>`X~{@{tIk#R7Wg?<6c59Qf@^0(7!cJh{11y{wL?q2cPB#jTuSYI*Q zJ$gk<81AgL%nNY`oivg?ES0@s78XITuTQM)#W!T>sji_y--9Z*%_KScnkMu|WI2B3 zN}nHi9C*Rqyqqcz091BMumC$^!H!D1>BiGe(t(#NZ!uAyi6QSDYNcU)oo-^!wy-J? zze~4s;jY&Dpyhkgxj>s-XV3uRW1UE=MjDh~#=#e(Wu%LyHqR&AeWWq>2=7xwprB0q zN`)%74Th!rvx0AvXP1F!UVf^M(Y)@2l251%^>Q<|H}xNjm+0^C>QS`F>)}1COOdbH z=59J*Z4BWjwVH_>cB^KF5 z^uz{6(nXlvhacBDHFi&95j*WviDg+-k&9??ydv2`QdCZ`WN@Bkzwy;G$b~eNLJ}-g zrc3+!xmPfE{1Up5YV8KbO*<4?#9U_*CS*OQ2j}M> zY4)Fu&?4gY(}<2D@`GS+i_pG=#|x$0-XyKDt(~ytgjg$YD6SZX2})m-HFmZz$OU(o zkeK;4A&VE*D99?aKhEsBFXG0FO!Mw;-XZ03$kv-> zx@B}}))@l+j*{!vzn_&i16O`A?Jj2%-J+K0)?0a#?!Jwny26%oGo0c!i-IZ)q5N9A z{scj7+?R9Z2V~{lX*6XAdS*Hg?_*KDW_2S?F8)O78CBmL(=hwNnl*>hywXtEz#$H- zAlr<|jA@{LEK>8N+?)8mfcH;O_kwjZN#AbcPQ}Z)w~?Ac$pJj4mr`qBarJI7CsWjU z4^z>_pnAAP#<&hvE0joEN|Y>DIsSP5HE>Av~20-%9I-g-U?p;3ky z)xm#)79dOS3oHrgpnd$`()3fXDtV;Db=(594j*zeIjbE+F!V5GRk0W3;MW|{m;Iul z5cJFgrksaW3M6Z{Xx?C0!;GL2Jroad%0%w(a9~Rw zW01RcI|13A&MT5pO39{ga@wo*k8{YGk-EXE^@S6x!g%GYlGI1f{b`l72dN z=u^XyJ)479t2d8oqwgx*N-TTGc1)Q*C66|;W$CT$KLg0l$Xx<5fApeD){z%wHLceX49scb2cEm%16eg!bvyf2cJHa(jl<&+UW55ZVG{W2 zj2WtTM2MGT-T?dVXEpbs)V2k-*{qO*dg5HwW1F8)j=`!e_4Gx|zc#ucw*}^P@-vLu;i_YOMOch^i z*z>}pUD*1&qB^ylDsm9Y&X5Hag{ul+?hcKW-GywNfR9TzC7htUBnpb1PqS~I)xmGY z0b6(ioH_HYe_kfnnbqOqqMoERThjIlT%p+fg6dHdO@W@i_8gQuZbv)h8AgzOo`~U| zE=6lNoZroXpr$;SYiBF5L+X)kHfIGN2=m0!U?o%(xhou9v=5sxYkEP0!0(CFli)U* zvwWt{Tle!)$7>N*7pJHsbkJQ}aV>y#8!j-ndlOL_I+&-8!uy!XnmV1Ye-rqM$Pk5d z%{B=yZ}E=nv&GtZ1}~Y`1m9h-wVCwTW(&>O9*I+bkCxn;`b27P0g)eD=myM>|V$UE5}bEl4{78>x~617;juaKhJg6FzSfmo4`Vn}X9 zSFQuV4+`idu2P7c9IWb&OIt_hHKs-jHCgs;S=z1Qf=*Sd;I;+ zkz#m0QadWJjGYtBrLxA>de6$uZ%=ZwLN~a6Jr1NvFUxQG4I*)!I87oo^W_UvvNyxz zi{*poLU5Z|z}sG4Dzuy@z!Iw3BbGlVE>rx1FP+F0dqg*U0ODky{lGRmJsW$qsY9OU zC#e0B=*8}hTf^4|1tv8~Y8}%j#gGSmhx#v71)Dh*59lHQf?p@ibJdotrlcQ4&206H z+=6Ljx$|>-(9Ki>OQY!q>-3i84voHH(SF)XdXTE+kjVW*(@9Sy`>`ReK!vXzVu@9K z^X^aXEXNPMDcey_bj+$0a$oN%C5^&!sH~R)Y#X9FDXbY2VR?Q>k7MNU9nR6=mcyTo z(ao7j^U`{vIzyDIZ_k1WBCL^A4P%hd3*pQqr$%*?o->m13)yoOlF}c}%Q^kUj-7oD zF5(lEtZx^UFv)h23Z6H~tXjTT-re0qM$CKQoRsk^#TJebM!Zd6P2AJ=C(rtXBXPhy zbl$8j%}dna1y|?ANEot>uzFh1uXvxuGgkVDXL6@Qcs&qEt%1j1##^e89-I2O7Zj{_oT~6l^PMAvGpmmR^A}p zCQ%TCOZWYc?`SA_ET+Q8jU+H7GX%#3S6-AdqC4??J3HEYvd%To)Dv+ceLU#d>mw>; zr%RW*0t9DLGArlGYxNsg#1dJ_3a;RdwLc+8MwCj!i;3PG5e&`gn#FSG)_fPJsIg2m ze7{#q=bdpkj%F8rmVx2y%@>M8q-{}UK78SP0XB#n=lA=nz-BI35gsGwcqm_aEE$k3 z;h01hCGG(ZIGf=-C56oI>rTzq6c!1|>h|B%lve##+ zy>ix4wnz#$u0m&uE|YS7>!-*0GizEO1)QwK@?q9rhZ@0XC@eNpm&shuzaaXHW-an2 z6mJRkA8QNrgo|5&J+|}{=FloURWrAtda>C$=1E}+b}lAWa(KR<$z$VDDtccV0th^u zk3zci0iBG5K-w^q7z$~G#&fMGNRJ3HlX&$|#D?`@PB7*|B^Aa_BYejYJzwq01 zHhb`7=ib$IQxZ;hIa^HMRQ`~mC>iT(5e3(qK;JwdA)khXaEC1jb`V{zbv?EuvMJ_r z=Cv(moRE#5Z=Cz2fqO6VK0eY0M>pT~ri=&HaQ=1D%a~x~I6FLRZ0vDJyyds6xboc@ z<(+uWU3Ctvp&Y0JEh{zj1i#;2*kLhWU^APlvvKQ~Vw5l`t_Zq)W2Q*N)X52WwC)qr zxEwz+L-wz$ZfcBFsBE_rcq!C-5}hImZn7Kon6wcZuf3*=o+F+gmg&uP*Y|_L$`Mpp z+*ng34S`kb@^&bIRt7CR35>LZGy>Oec6V)G zEYULqnq*gYean$w3ZJE!_i+x==1L;D&{L&4E|QN|>*Kk8gEbWw>+-YGeJS`N^sy(P zD#b9xv6tW*P5_+sd2HUI&cO78V(q5w)7^*3iX226bBP>M!t7}b$RkOcD;G9tYA1+I zozzwZS*aM!ISv`xkJt~{Kd3ugFinK4zaKXI{ms(MnnX4mDq;e5tFZ25Ae z^M?Gf0#8(daLwe41*vCEyn~!_q`j%L7(81jc-M;PUzGIXa^c)xC!I8afKeMkuP0lE zx%y?ulE1%%r7IWZP}wtHEMgtS?Zm4#xek@6v$5t7g$XwFWE3AjdDhqQpguz1oyuR1 zyE7%Q92-~joc;)g8C2CL(fn(3jgU+CI?{#ki+y#l2-(5d}Hp*X)gU^hB1cISg38#L!|WtGxFM zmssfuc-x+A0P=#!WsvT_k-ok^!d;WZl*uo)`24#(efEoe zA$o&+eJLl@>0+85nTK|TLrmm;{A%xU^v?D4?`@yx>n`-t<=e2X_qcV}=5om%xYtg- zW6sH{zBsq>HhC_6!Eu&)Z$=_shLyfGE(b(av)Io^EbJc}+8eae8U%x>O`}cG)GAB+ za?5lX($jA&MCLUNFsSb4L1SmW^FO`8cT6RFGg=~%7i~(A13F+PU9&rD2=i!^LlePOUM>0$tCjIZpdr(Schepw@}u&auq`uq!C7C z2YNEvx8Jv(MNL-+;J+PEj@^uHB$Z*N{?##s#5I3-Fw>JJMl;>G@t#o8zKaJ3GS?vy zvFLKOCVHEwrWOv4?lJ&7&KrZ3zkK%p!`=aii13dU5dz~s{bLaYKuhnJJ`*yn8109k z?0Z=DD&{V>(uy4ioSh7P+&`4`Ou*0cBjgfiv)#FKWiR+Di~&Eb2;d`LLQB|J*FS}^ z-5pt0Wi^$bJEz0p5WBJSS!ceH3P2{Ky7jU>`%g)t{*uDh%UL&)^Y`;+w*)irTVQhW zB;DW6zSGSI9KKZZ02|#f{EsUl-G3{y@fSo;9biL`^j@OR82?!N)3vDIOD!7?1y4aC zr^k2g|FgAOw{k2l+)`!dvP@6>VtB7%tSvXI`2(810xDtF!R(M$Rna-HF=(d2{oMtf z$7Ke<2HxIDh=c-z{vNV9Fz?5|^Ww|nNw-)Ip;kjLu(p^YNUz8RxX#Rpm;9;XE0=*z zkF=~f_~y@DiF+V#YPv0#(6=Pag?NQH?V?fFIAZsSAxe665|lj&0CgSUU#~BC+&XkV zc5~kfqOHEJEpB`i?)AkMBCu5sm%3OGkyA3OcyNCZoj!BOE5XCqvH&Vvde`LgLi)wA ztZ!V<=**|9iDm3`Z`!7#@T?9`(|!9#?;Q~RyR8L9Z!?J;Kb4K7?oKDWa>10LXKe{o zrk|vr#tLdgO4_MdYGLQEEXb5_7xS||e`{*wUvQ3MD^*`|Q$bdB)u|r)CUSgnQ%>n3 zqzvE@U{sGw+iSL@f=b_B#TKxP0ZZBw9c%S?HP*zGmt)q}?s3*$ZDl;6pvKJI89k~g ztMiBVS{#u<0vo#0?aG3Fe5LJcuc`w1xF`r`Ui-t?7jz_J`l(a1`6Zr(P>by|#{;7L zUYxzWNxCrDcePJ~ditz;XsiM6G+^Xs*Ab?>r2FoX{sx93>A2r26zBxIqy4!wX&H53 zy9#_mMu5(<1Q3__pP%tL`uId^hP$&9kLYZebOb zI%)0xI!%NMy;bLU(`qQ_$FV}F6BW_k_-;~lat*q;%(s}o=(6Gf zph8WzCR10`uk%t0tThQ!%>>LGvU1hBfQ`)#=gsDXYee|&5M_tpe}GOdUqy|Q1{e~d;FEt5izYzuaM z^8_3l2RuO|{YkueD%q*VOC;=|b}Bdc@&Y2EkWE zEd?t#j+Z5^cG%FVg{-pr*q6QNOjoo(q_4tkiOLoio-X|c$vn3jCIPGc8;X#B%*Uaxh|qi z8)O`O;8udcaPMlSMhRfGl%5S@CvD1ctM$fot$*^a$#hvu$6c&7X%@TvM)Q;b5BUKI zTN*i@k3`t=X-~(VN=xX7LS4+}rb_T?h#V(Xu7`^s#B_X+;4p%YdH8VuitNmVs?XaI zX^m9Gzi4mf<($OC0h=-LK*vYeO`894xzka4J52NJR^pg8ej0!x2o-4b)1epMW+0sQ z8s0?YZL2YxX3vV7-aC_4WZT+PFO+4H9YWo=Pl9ynKis*p*wZC7-L!5&&CVY+V)VY&_7^y(AoMZW}dDrme{s1FtK%gHL@+UYgRbl?F@WEy^d zrWM8j@*Kg?wq82o{&Og!NI!rD7oq`%CaOG;Tj5`YFFxJHEFoN_fQbU*?^3Y+MXSNw zh5GhcEBq)55TNq4}d36JHWTgZzq-hBCO$` zq}%8HN4Zo+bpW^?518ZbL2_gQ+1^gjtgn#)yQy* zrA-?4iFh8_%ONpUDuXaToNIPdWAyo~3}_)sJZI?sO;-FjgQ?l?yJlvQYDb*kw%A{D z{^REp)h(gJACX)HsZYNlaM$2IiM@*4_`1u;DQSVmil3Ox1)_}8qPo7Xselm8x2qhT}y8uCmK z2vDRX$&i6kmJisIan2zW7J8B?X{sfrmzVa)mFznQi&ObWGb?e2k>|)<-KCDfWRK^4 z2h$JeTMM_DcXg>Gzm9U%JHqH@SxXIwHAcOSZesUDi4mAbgaGXw+&`YNWV`G(V}DAU zzxTrfK$Qc+3jY!{&cDth|0%Ek5tYt=XiNXAb_WvqQMUtfr;sJBGUG46E{>vv9sTl% zFG(20prC&kwaW(w?%r6$fcy~l2^>_W*wl>A`lloBiN~ zi!zU@XXIl9t``o%GY=S$Cy)rLBmZs4=?3o|P&v3|V^+e2J;J8Vd!}y%vVuMed>RMz zZ-0X5uf_n|g$N*OC87+B@M~}n&{v3I{h=%LniD>tv}&NVq2J?$ek58W;OHy-Jy&? z2GpXc5U&RTKO}&7#n5kqoB^l$6Cqbc2Y|utF)*rp0M{Sz$bTCW0H8PFi0Tdm1TQoB zyI}^t0S3wX_dksgFg)?sxGXye1^r$dL!je-6<_%GwbR|eM^bq`zF+MnK!(M!z*_oF zx1z`2hiTz2Tf6`ClKxjO?>}??fBl93?>+{9yG9w8_{WIMb5}DCf(LTrTqayAqNV;f z?zi7&ng6Nl|Mb@VU-f+Nk>=7>7(9;ii0j+)Q8*#c@8WC{u>LVD)B}}1D^pZKu0YIB zv~I0KmH-+J#M*r6^aOnPi-)oX4D`-h2f)0R9u2I|>aLXTzU4zk`hX=Iz|n~s!bke? z=j7lzuEXnVs!M=@Vh4QF4E~gu;g1psddEa5f-W`zHv^ak@f&mHPbH{R0s7@sb4f06 zc+~ALQVnbf0F+DJ0TdY>uYXN>MTAMIDOz#so%l=fi z`Wpu1uYWY`|4!Fs`3U0t(K4w&^+uUU=)b2tq|%-Jwuf6Q#QM0~ zrY{3c>?cIuD1zGDNkQ8MS)qT?g7{}8H~&xW`=|Zp|Ed?4xP=bbiW9f)<)4+AG}t_b z^oHx71CUM5*Y^r7Ir}X$_2)(Bj6xXJ1+1)SVV$ z&D%{s`eLD^tE)}ht+lwYsz!6$q9+ZvR1lj!$AKkB;ao*flYVA@uu|_s5P3qr+~DV} zhF-Kj*#gWYFN%g$5A0Q!kk*c=6sg&bhOP=31-h$UGC$$lN-1AHOkON5~pb< z8`%}Q7|x3JgX7%FgWxaes;0`$aWMDlAak)zQO}yQgsf~Lq61i#*Q^!ZoFVNz>x$o4 zj&pAEh|w{67an-y$SwXlWzI}3s>tGEX8Z+)&1YJr;jT|SKF+uAD5pl?B9pldM~*jE z>ka_dkc5>sa>cn1myw;2MCfzxhQ{Ue(uXVNENyEBy87CeZcKOhn_urCHRCY+c< zmM6|1Y8P4!(@C4Cv!~nQ5G1Y+Nglq@C7+es@XA*8d*F)hXq6IaX)^Jqa>DS$@m9ks zORPeT_Mwje#wOgegPE0ZWtb*NyXLtUM;Fetk3iMv4EIX2*6yM9v61==QpQ9LCqCI% z6s6!!N-x3n8QD$}ife*SGsCT`h!>qw&+d9ACV5zcxsb-^U6aKDVKHl`R1p$-#WCiE zC(rXU$?YlmF~l5?7we}VeTVZJqa)Cq{)#a-aUsX3KJdk`y=-Z_QtXlsD#%HoJe&*0+|Bb# zjXS?BmUeR^ui=#$1_J}OhSmHV{yk_N?0~wVP6lQiX=bF`Py2>M$K8+b>9-;KVW@rx zDSEQaR1p)iV~qpAbGE#4IgRvDoCSMpgTXP8ZA;-@_;8zE>Ybb zDw>aa0Z5=fZbJ_(w_7>HHNO~g$-auexVT_%+=m87WYqVnUcbd3c`x8GuKmJ)4K1q* ztJEd?rBy%TMGVEV7Y_IID5^Qz`|64A#avo7vjS4Jcu_*mNHN1+Jx(R_hMwe-j`1Dd ziZUeXyGfMa z^2ErA3>8BMlpY1#zT#LX_~6vT0VrYQH3GIUyZ z!(y$wY`NyTrXW5JF$Pex(k3lQLwEd;7Jjy&gspcwi?=5ik;brY-zRLwEP$g&uobUCai- z=}vXZW;Mk$-(X+6lB67a8}j5#x>;0G6 zb@l27hd%Be)2elmTp^zFkbIe9b8}3*E`wND#io=^Q>zDxe-FAyO(A_yb%<$I`mG4@ zM&&0N>!b2`L%v>AyBKU-_W zWiJjRA?WB!pTSB5sJi4SbvbB#xr4XrngY3@Wrm77)X4SyBpKL#hx%jt_lX)xKcfs7 z+>`sLvWZ;`2+KrHWnjBI=(v15^Wf(Oq)vzkkL3mTT=25{e8VkrY&j?BllB8Z1a&Lv zSGVbiZ&6zsaeo|(Qn2DHN#Fb3PV?{j|6jHL{F2>8ChA%`UL(45M8ticQCgLrJ=-uQ zxxZXjV?WuZRa~f*410bsra@gFu!<>ZSC5xeBLT8&FbP=0;uWtNx2lOCCAKoqP_r|j z>Gu&>9;^cgGTr5WR34F=G?bTx)yT_0AjOdDS|OzPaW<}d5o4@urspi zCEH;s&tqpt?(BRJ;qWvnE@!?Agd-^0Z7!41l*U&#({z5a`qe`mdr`&&tC9Pg1jyJm zRxVxZ=zKca(w;SG=amhk&dP&ppG%sko@#?YAV}A8oo@6iKfXx_hOZBpT3Jby81mzh z)aqX8d+3TX^Bh%`uISs;;Z}Q5he)I+$3v>XW>pJ_Wazl?7$(y)V3xzN&*v3G*u&Z5 z5V}*40ZOS5$>$c=9A|Y}pj?x0!8AyW)#6!vQREb%F_ zSxfv7Vl1+&z$>8nxPOZvH{aDBi@xL3?83e=G3$$r9WNVg3?mkeVPXFrvjq^eBS)h) zIrGO4!4T5vS?cF#$OMX!ijnlKhT%!#b+f&6J4oQqSA&%%Nd1D>3#phEQmRQ>A6Qw2k8}YgV&{t_j z2j5JoId{>#n9H(!`0w;P?MEDp3(Qu5FLS^5OLvILI{|D^SyCuyuy$N)sS6rdV60qcD~=mQUe-P% ze5y2gK#|)U-21n20$63pty1mNVM0k7^?HQv+VOt6H zS2((=o%9srp2#_}dS zjC)re+2wnfG&%|AaAL(6A3G=M$$US^U7I7yLECxNw=LF>>W}+6v4uL{Q2fusD~G0({OP& ztmzEu7h)9E#?&=0?dQa3V>~LragJ{l(M+Opc@pUIMi^pY(2p}=z7f8Cf(nJids;66 zyF0T@C;0dheCI$lT*2(nd4I_)_4ow#Fx_($T}I+b?!P8>&wpoF_}@1m%&0msEptTs z-QUwxcD3%Gk25!<4DCcdB`B8w8A3WZ0cW#tK78gEQ}Cn71j2pfy8KEF*wjV<_N<|N z_<8!N{!umpFInMw54_pBqRpj<#tWz6Nk5&23_&`gt|YC%TO~h1Nr1ue!x0ge_R>{ix4)~x(jo&O(+Dfn++di=YVH2)~y|Mg|gZxIImfeY;awdenNWrJV1 Ug8wi67|j{Y{^R3B{yF=90Xg;*H2?qr literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG new file mode 100644 index 0000000000000000000000000000000000000000..020f1550e41eed28ecb0c4fa648fec6ef706944c GIT binary patch literal 146093 zcmeFY1zcQ9moK^rPLPB^u;2tj2oT&ocyPB6+=9C{5+qn70RjZ~V8PuTf?I-HaMupf zyq$BtoKI%%-1+9sy>I5tX?{gl^)6fgTD8`ywQApfygk_p9uUYcd zME{mYcZR*5|Bjye!Xo zS=cDR|7_2B*|~v#?Kc1r0c-$c;HLp{yL^|x+{wv~mzmkdk;%Z=*3g8>$kv+K&A^VC zh3Ppnz%S%xXJBMy;zVI+VrF3@KzGp4LPud?EI_BhA@^L)PRzvILdwIzM8!j1)yTuj zh{u>tNDvEy-;LMJ+Roa<$$-Mm`i+evubTkXZ@u$^`JX>CQwj1r7@P7czmWJ#4X`9Y z^_RK0y1FvCvN72@m@%{P@bEA{XJuw(Wdv(5I=b698MrapI8y(mgBK=_Mh+HsP8PN{ z6hAvOFtl}c5}aRs+;%4RKXa0wJ{LDYW_?wCT=g$1!g_a<{u@SG)&$-(= z{64&jiT(e()qZ0k_|tU$ojS1adj{+ler(|KzSe;rgc#_@^rW$zA`=;QFhPYhnXhwyvNFdpiq=0jS8x zD9A{tD99*isHkWd_wRx>1_nOPJo7n2&tH;9zUUHc*a0X z!OX_|l$Gu&!_%LgAfTe5VW4B+-Mx$V^bz5sr~mZlwiURKhNy>>hKN7~+_{f{cpu@m z6Ceizj>uq$@@JItFCTYCcR`u2{_uI`@RzW%ZCiOH$yuis{tS60`)uWxK_Z66(!W~yIA>Kzqres0E6;VPpuzx_s>W79W8l6$r zhEC0DnE!u>vOfs>D_t`HCL#j3c!>7_A>dLX^hx@i zsIf6(;7MlapXnbkKxU-KNx$Uu^S#0;*3J70Fgaxk@o1Qp3geF?zbP zl&(plohK*vUt;fvE;asW*(gf8_?9)C0Qcy-1-z4h1M`x*f0X!tKz@6kj(z^K^6!QJ zFDm~&&2;P&_NpEW*Nc1lFZjEST`>9wKdv``8*k9WDk<#i?5B47XK#HM=gF$RaD3VA ztQ>m)|M9bp2J*(>Eg)cg3p5Xsd9|EODO~N2pn8hiz4}XGbYtMxbHKF{to}#w&+30b z@t=i^dy@7t?)nPnTx>7eLF2SamVVP&BI_+s6uxK3cQt|%N0hy%n_2V7mv~F zZh;ch+WOb{VJpM;aPGovR@FJzH~Nf~?pZg4J%7~_VXZ-MWWKtbn=U-};`2RJ$U-R| zLgq|bnA!(OJBvje4Ww6zzJB^bsrb z7I|-AING{(LpF@CjhpQ+M=n{|2}jiJ8VOch@zv9#FOL%-ZPgrotC~=r-zIPw#CQ??**c#j-Z320j(2iipO>psj!m7MvAQH!uKpBv z!;A69cSran@Ww4nTMzL?{B`>@E{fEOpFCzcAF>*`veiptoMhmlt+zy9m3)>=aO`w> zusN1!qC|kd<5*Nk02Dk3B_C5lrMAAF)Smg5GMh7Z@)t8u#{uwi1d zA*qY%Z-s|eP2FR~u^$<^0|oa8gSHN3p~5YI&K&W0ywCnzR+b?e&5xzcpfcXj!M$}$ zQ4MriSUtw0X<#P{$e+$?yau!%v zCMfGv;FOmyJs?PcibZ@Ia?jg|_h^n?PV~~O-#fA7EMuIg9;CQpkc`r%B;!K_Ye<+Q zwqz#a`D-eRBQfN^#>pVc8$p_a9NnPaIFS!Ed|G~U3#?w^Ty6@bxT+!y!Lkl!y-6xHxdkrKOSxd)D{|_?%ll#0)=M|)mrwTkbH1>N;wr5RQLvdkT1}Gy zPDxokcftfNi{HCwkn|pBeURZi=L;_7S8I;z+n!k{aH|(gFu<(m%qnaQoUtpHw!k!U z{0!_plT>&)Dfg=Xs!iL|D#@p`K!0|Yx9KJ~gFDV7V-$p;4Yc>uREcQ$5 z_hmhU+@I6gq0cf;ay^gCHn@5bdK{AJ&%eZ0b|wIC@W zJQSpy^%%Wdt!xNKJ4|!b*%N{bX%}0rW6Z9L`DR^GRMMxKg7;mf_9|QeR!~`r@13U! zm6~!Ih#*&qlMdnuaoY!WzV|kA3h<7gzTnv!Br4@5qZn@#FR)~_5`5}SJ2bPkSNz7h z1PObVo3(dVn&#sYHh^y=eU$dqDGm3>^er%JZ*E?pvw&$+8xh=JB#9jG8kbKI6>^hN8mvy2e)$~H7wdOKc{yo_{U=K}Rd7etHjZKSxvX=6 zo;FY}rMagX{&5d!Ew=BDFYiGyes}pRH$LsLOg)(s#W4;BXt`9vF*;3kT#(Y_A-b{z z8db7Ac0sY*h2~gyv8zeW?5uY0j%AzivrQj0L+lZcSbuqBz~#O3mTsi~bdpf`ej}fK z{@nIMIpdn@^7+s120zYO9|AU{Jw%`C#d8iKtkU@NI^N$|HpWG`O9>*`xwS5}{XC{Irk*eD}@-tWvrrC_M zq76+`IMFy?YG^<_ZF9FS2x`jF_V!j;`!~v=C!xSl^YlwH+VM(RDdeuM{>lraYUIYd z-6z}9OW0?h8T^6{6i2*R+*e6?nUG0-}Z5z1gIkT(=g{sZzndob9{z zJfh2Yo-aA`hh|tooX+7a%yt{Qj&qEl=uZ_fc*b(dKZ2?vZkMDHeCF-iKBb*=3%qld zwU)Pf5p&;~sz@=WPOq=>K%kGtjJC>2;h`9vAN!5#t3<}eNp!Zr$1f8ZT8a4g1_7r@ zzfxGq>UKYimI2Nh1r^BGnq-{7=t4k`3e@r&5R1Nryp>B9g$eIzZSQ! zltGF0X$7>Wbfb9Tdu2&LnD8Wa&GIakVkae6)U({@v(;wRo|DNtX=Pi}8al2wspzz` zA8lrG$}ZJ~d|TF1H}%if(xxh%hkp<_3tb-7-U6d?!jFdHRv-jB!~(fFX3O5(v-6$h z-8!nko&YOLm*p#1l<5Vp(R@VsWZRz(4d;!@H0K=#gs;fEi-2Q?g}#jwzEvGL`)IFq`VEq`qt;kx+my}fGW z^3npR+TF2T^{GLh7Fb5Hs!D{t<=Yi_=XtvIe2y_MBcDX&Y;+9>v2^6*hL7uDu04!- z$p-aKcia-jN$wP+8{eC`P&sVWHw?E;d~@)kqC23_dh_d}C~T|T%KD)5A(BFk6Us!S z=vuCYYfh}fF71h zPmVor+I65!%T7i*MkQ#+I5txrkuJm*S$LSHDZ1TS1UK#a0(L+{ww%$*df;HAgt8#o&WBj6*3uy)K9thKdc}g8)Y(G+~1QnG^$DS&9yfYZ44R>(|&40t^MLbBnMJwegr^&DY+< z1R({tfbs!Nz!$P>=I_F!j~N{W36Ji|E=@N~lUq-{e;lkt=TG)%-?kGITKrlU7N9cj z#gWlfuw9s^@8-WQZPNJh&a=$!<4?TC3{S%^V};4W#NBg->hfS7+uaAEM{h36`&{w3 zT)4QXARMICi3AuJ@#K|WB@B6G1;&1%w4{3s6JMHGakq#h>d$$4eCm=9nBaVh6UKn>sufaS*w-iko`IObd%$ z4%=kR@zl}roJ@7rkEa@479;z{kFjmRB8>V z$As(+#VTU;Df@<;R_k)+2LoAj>Z0yQPJQ?pxjP=!6-BdEC9(E-7A%GACzdR4;$6D& zjpWl2`;4|iH_IfRAO?&)j%^?CG%J9)DmF~eHYDj+Yis@3@gOSC?wdut8?BVy-kbP-1yYNbHegNy!6TW~V6PHzgZffdUj>VO5MO2=Z!n=iwK^`fA#f`Cg1Gzt> zF_^T{EU(i&Mpp(%z$f)NfjQt4**y23Pm=Gpl2wg@4UyDCmHUzH#GXl^2}F*nfU-l* z>=qy&flP~B@6?w(9EJ;}gNKiRAJfjlj}AhGrgUyV>k!M<4YU(~%K_pJceP)BVjXNxQRhb@c=$i@&Gj*ScK~Y4Z>e5eneEBp$b-_flIH(C*)nvBu?FGdIw} zLzg)etA{q6AoS>J$c3^9KMHIKt@0EQcxLOx{7JU3i!dCGYTlL)A!6lKXkNiEb&~Tn zZ%Ooul$RuS(#3$YaeRG5PU0esxcqmwwyUK_{=BP6JN6*O(C7nxgW@gudXw)#(RsRe z`)HcO`aKg>y+ZQcXVCj>+bd6ZWJ4NlOZB8N!)*B}YeOw&Y0XS(+c~ z$f(w5y{AK^jy}-XGDjTdH(Gk4(;;6kx?STc=tUUvN}6t99jnJeAV{IgRonTkHb;Z@ z*Fn2cbfN%RKB*qMtDcyr-E1;X5MD`>O1YB;XBb+=RgdqF&34O7jRm+1bm-h^*$EI< z#Xsv?sZV;Th+-SO6hGU3Y0}hb{b*FH6H0=K|JwJS_lYV$qJ?X&8=XRRQxK@JI{jAd z)Dl=(HV!#P!1Z;Hmmsvz^V_}~tHyz3!QN22syuXl{4{@CS`@h69()WK!Z@c^dfJEu zig%fjJ2^vQ#3?$c9oxvNJT)TLN6yePM31E{SgD@$nX-HaJYy^mEM|q> zr-9+Su&}*{@$WE`+1D9rvF$vks>;qq~6K#yP{L<fvGTSzFCSQ@F>+4{K=8XZu63I*?O_3CZT=G$*|Hyz|5}Ew!;{ zizOwhuNcG__6Y3mapfvV^!CTPaV9h7CZT5`H)}i_K7) zj;tD=c{eq5-)-x0tMFsDY0C;}0`K_q&tNFY`kcq25E|0jT_X)py|a z#Cr`I_kR_VfMU@5fy!92b>T`Tbl5e=SuSmDb)F_@qFbaBg*@kJnz9l>d&FejD3&h1 zZdva(Gr~-6?R&GS(Bgb?IsMxfaVfBNHd&G4m$S+m%-7NTR$R505QEjpCvEI3u`MBG z@@OhP;!|}-Axin->AAW+rIEY)8^&*G)EMu=qo-+Wj==2^GP-Zee;=uyaUmjqQL~4w zDdPKEl-Iqxn$&*%wRB`bd6T)`u9{9bIh987B=}nJ0iSXF|pF{ zba1+54R7%v5B`?kFN9yfdyD+$LiUf|ovkh;$Kri?gkX}TP1K;ndh-@|>v1(EbhTgK zPmcil=-Yp9B6&?cy%2p1EILmq2|r5vRdRy-<++{-9>TE23{sgM&GgF*BOZ)A9#Hs* z11b|vrxT2gHGGS^9k@DS#Vrgp?xrl;x&TOg%1Tivyam*Ou(IO4({xj z;j40R53?hbi5r1iTiWdA8{{DA|IZ`jRZZ33NcDxV^H~m1&uJ|PTj}V4d{l&F^ z^3CZjFcN5?Zqo$nl3Y*}3!PF56Epl2jL|-um;Vs<_}dW3zm?ZYBDi)3mqBmw$5e`` zx&F}x^NlNHLzvj*m;sPuC@^VcGv7kedr%_SZCg1zbsj9R&&dCWF*f~jlAV&?6Xm75*r zX0nt^57Cbh8v8i*ycN`-snr3lz3&Id@Ciy=3Ql_{8{rO25mi=Pd7>%|i;8f4qC|Ot zUVlIX((v)&+6}@d7cz!14pPn?#h~w*6;8e^xvxxDRGBTsQe4W2`&pygS z5oHp807l(41%EvHCZLac8)b;6#1WBdp8}B*b$P+3LaO4IBPb>Z$5sd)Y4u# z+401L(r;7J;{^KP+Un3JigceT1EOu#==B}_q zVF&Pst`WDurul@>LDemQA+&7fwg?Z35QAUoALgQdeXr32Ijm^3z6HbtGeC(_dJ8;| zyavTJ31nnAAF^l#$3wfq{jDF!-}Y0JeXV$uw8JT3i~DMTJT-YtLb-^omzwkm;!YBM zS#1o5{irWhiZC*s(*HXBRn}-bCuTr;KDM0A-vTLs1!xujwhMpl#(()O;>z`HcRd+8 z-#tA1c@R(#_wp0!yakAp-^sWo-KaLaM%6`#-FtZp1g5OoUJ{+*TFi+h*_!C7IlolKvr zmd8speW{vAxX6X)v6Sc_;v9N< zB>$BGobWV+K)o+~3#6%l%%}7>dBy)JZEV-$Kcl{zwwr(R^&qG?+3Lf7x>m-ULZ8%$ z)}+uU*#Nx-GUMOhUI>bh`s0EFD%Rg=u&15}KhSkS&1wc(3K1eNe_bxaJh%txtttQ? zWVc)*l(4n?-2FV^g_zxV8T2{TJKQ9mR3utL)eeQ5Y;s{?ruZzdE2~T`l{VsoGZ1cC zmrRbbon(`Ul4iDwCBb0jHuYrEISq z^lPh~Ep3gR?y&IubMVnI|=ke#f{$=k%Ox$Lzx?8{NX*v|) zP>i71LNonWTZvm{$?qZ;$~}nvqD;}xn%eoCu;|;W)h$5a#=5HXa_({X$!CKx6=LJn z30#FT{5Ni#EBjKhon%zaQ_ohMqpcsmqn0$`K@n|i#xe5K;o?Rb&@(CbH&=d+GKFj1CnV<|mO{*sc3;zSkD;hqQ4T`_m}!@* zqucuIonlhgve}5ETyUV0r2(}IhDbpBFp62O5$UZd_+=xdkEfGpb zb8MxHi2-Q;vRC;=CGF4Bu}io)AdD{av#W^Y_3Q`K;K?Vg0djR}B}#rq58s5VUJ9H1 zAnv(_>wqFMOT0OM^b2DZ`>`pU0FHV|Jf2^|m|6d}hZj|4XXXR$dIATu`atTcp`@tC zb`^RpZr}2t`ROc7Qc}t(T;bCK{jn?a00t;3n-tR1v7n^aGNX-mt-`9gwBH7>XuXg) z766AwyPO_ueh!1K;1KJQ?~zpCr_-6F)G-i4AqV7+I;js1NE2NS3^|5=r z+s=l;a~DYQ-u96fjrw9X9N-V+|dEnrUMMx z>7p&(81_K7ui}eAR6qguf!|E2<&1iwD-9^B~A11Y+WGBSr~8sTxv@ z+Ug||Ry-A8FV1+_No}}S>Z__I^e-H7+1@6kzZOB_!WV#sa17w!f^HvlvXmT{>CjwQ zgl2IGiIPg2FwbIx073YPo~by*zwC3xWH!y-iIE~(x1BV1sl1g-LlV36<98Yx5PFek zO+6e-yc&^oheJ8}Y1qPrdGjw{F?dGTcGvN_leTgftHHWTgOH1NKX|;MJ}W^V|Fm6W zy!tKW{(BzA3W0i6sSnw#jb*FB_WnMZjb`0scy-fW*2R6Ok0;0tcBQfH!o!*%VUGFJ6MzFZ52H$LS1^ z6(RJNN;Xd09N6-!nB^rd+yWA#a!ntPX=mTT4K`jrN9ZGE8PPyr)}UX4kjynaWVAp+ zij9r`010$`v_UG4T9BQNoX#Rv=Vr3zZNVmfM{wfMrGTtrY5pnv;T&z1sKS--Yk2z9 zyj$?@*~&zMLfv84gs&_j(Vi=r7S4jwDL| z&gSzG<^OlihC17j%hr)*vK@j%1o)7V$oB9tbVEFC(CE-7Jc64LJ~Dyw1E;=JMAzx!fu6i+UEF$H zePg&5bj6YvI4un(u38N7vS**!>sXXw)XF+(HW5WzV;1(loGzdFdJ9;{og2ALB?pP+ zBi*35l_v93t_Z=zuSJsrgv}HfGu_(Sp4yKuhVC5*vXgdNTyi7AwB6mW1Kq1OC*n+K zN+Ro>sS1v3Og*BiYb)w%tLmdopEu(w3SO@ATux)H9AIk00=m!jZ3(cfu@eP4%Vzx6 zWvF<*=9TdUbM%vkdo1jRF;ECRpOo`5@Lqx7YfIbYR4$ZpA@40cBMBWW>f30a-S!*}|J;zZK%B%9GUTPsXU*P`CX5sK*--sw_Oy#P# zrPDL?_yEg`Ypk+~rt8zJn72DC{A|vc`HBI~(E|%>uP^m=eldN`?8vIq`2#y|J>XkQ zW6Rn!2frTAa5RZbcovz_cBuApGx4=l`O!kWvS|EeRXwzF7IDJG`3&{6WTpNKa%Lz! zppF`fe!LfKICvdsJ1w*Vt+R%oKqy~gJ4hP^v7Sgpr*99n317>J+!W-2ww46wK)I83 z3#=3-!1CYGbRbx4CA5a*(H>pLTiQ=a=_~l}}2(uzl%tZF$xc@tQbgAtiT9J2KDR zjHz#>D%>jo`k`zIam1CI9bw!wbfc7C>-+YDZ(AOmIfb&8qI1botx_Mt_vYpvwrw)V zN=`9y%yTfmA^P&>OL#fcbi~AR-1}3Ca6@0Fh9XOC300-Z55A}?7SZ!MU#=)?gCyYF zGDQ#yt2kJ}a0jW8(0uSMAlaj`=tk0^ViBp_P0ITM>aj5UfMhm`t?{`){Ye+#G&|8e zGEj>d*E=Nmp8p;3x}+*mx0Wx_>3ZX;_(Un$PFpI?ggm)gr8VbXZ>xhN4fEM!9r$J8 zB5rZX+1Fiuf!y9c`zJ})<<4ZHUI9nZ^W#XPQE1U7MTFNX_hBCV zFQ2Pwdgqy488}w#G=#369bnIkEDNESAL%s}|7cd{qF5_hr>A-5?c>w@EgeTGH$k!W zp`uPYUF>O*E#^+1*65d-km~94k`evcSa`0<)uP`vP6mFrxTkB$^~=NkT4R&3_4sWp zUb5s>%{nl|)T}_h`)LFV{Wc;L9S9#C ze<-3vnh!eEmxg*BpjdhY#aei>b=p{0U_^|v8%*>sy~Ph-ee5p8LW)L;gP*|_ zdfIzU&HRqiwf1u)HT~CGFGPRN)NmXmvJdH4jiYL%rPQCtOPEbDjcNjOUpGmq(X1Yq zsC2!0QWq>Xdca;tDk^ng^JeXYLg|7`^#*iiSoqCCJ%HU4J)t1!E6kR&@k@+V_JJ+u zyDIFL-czY9zfYhSAMCaN7=-!%d;Pazb$LgcEjz z9wj~KAC-j4*l&R!=lWkpP)WsIguW(0uCJKa&EcKnx4_0X2%GRDXM9kc8(Q1~C%Y|) zSyvB0uV-B>HOk7TWEDLIJ^IFB$7hXk+SUOxEmmePm@m-U3-A;h;k z@NWjIfqdf)I)_Yj(xQ)Tba~vHRyPIsq$_JDiRC1=vMNIFQTt(!C@gPn=`M!zo8`GF zKb%k8H}0#c9{$q7|4<-M1iSz%Gu9|{lVj$HH5ZeAOsVnx-5IGc>5hNWq6{pNZO-E0 zCV55TWuF!G!_W=$?YtWNF8P>Jd}rf`?_6>Xd~-P~Ligyx8i}kt^A(7<&k2U_v^N?1 zi_}_^o|ms46_esDLnE)P%uH>Gb-V@fXKiV-C~sy`8&nPqo2-`8+V!YA)T1r6{eo2{ zAEBI}VMdX^AZuQ4BHKTnRj9TKn+@4pRyvVputq%M*rJIk=Si+xah2=&m5Kd? z3h(MARvnRoQlrMy!)BWDlup+>oSFN!OBL(0*3MJC? z3=k%NY7W8G9k5BIm8SD_yo!+jx?3M`1gG4EJe@cagN3Od4)%@O?w$=kT#lDstE!aR z$IIwFxwG_Jy^MAxa5@0{ecYKbH2;p-~!ne)pjf)IYnPcTPZz3vLF z7M2B_lq2rT^Gjl&BQumu_~B`>^1+MA;wnZ?Bdoznf2lc-OK%*R%f(hQe$b7c!8lm) zOrs27DwbZSJtO<%NesK-fV`M?Cdb|$wbT|EnAPocGvR-}pY4h|<}0|EQ%ZNJ(4$A9 z8_B0|e{an8(w6Q5m)sOio>8jm?^a@ZWx=GRg4Uwmf|0*tg4vAW{6MDA;v6Rt*~tJi9)Z^xf4?j}5(GHTk}F~IZ4 zbavdDo${rEB_2H-Z=GR4OQfAF!3)!I@E|{^$%IZ!4{-|O9g&Cb=T78C#PEFV<2YM& zHUM&P6Ir z)rF6(`(itI{}4Q_Gz}j?kd#qXj~ADkXeh(@ltmLef^mtsoYuzuY&A^tD4c;~0Bcn9 zdB6Ck{$x`<25=0$d(C+y6s9Vhv-O>^BEZqktMZy{`mj`fT*wsG7-wyyAJum)ZG|@b zqlRPuX#t*r>QgFA0OgL~b)eCl+oyIOOcx9L{N6m|H<_$P+a5lZo$d$MY&Ah%jSzE7 z@TA_<1c_&$Q@%-FK2EHR@KK9}DR1A?IC*6?uHSi?d7O$jF)!dMf%82n!pl2PGy>f<%clHK1NEU;^2e^`Uxh4(6vjea2+o^|YH`U0SyF1?=!9$1(QV2T(Sw<{X|*my1Z#)jZ_9MLbJ{&v6HArwD7)Y;=~)sA z8;V$|9%ahzN-b!&;eXcZ)$(EW5PwlNE!uJ4Q6V9D{_7>d6*l<~Sp6-~(hc3^hHR|t zz(H64IG*}jqO`Aepce0%zJYVZmVA92(^f96Z~x{;qz)-VK?$Ub++lWmu~!9gpqV}$ z5j8Hg>LqYDKyri7Nbs8Z&#EYcqCN5GCzi1IPNI9Axv0Y zz9r}#DD82OFJ8Z=EiJX&c0iR`eBR_#vQ(d5ljRsJZuyqsp2J+Gpe!`QZ&LqJ zWmcksciReqh*|vsf|D0I^^jc$?6U_LGt+o$H|`c@%jcZzYd@RA)^3-%Lq;F1Y8$J; z2Q8rze)=U9XI$r%w>CX|u?5ux$koydKtenTwMhZjTShcR~x zL-tMeYz$~dDa2i7>L?|IFVzEw{Z9wNcEa*aC!T3<)yzqnxEV&8?tiJ}PhB&tWcR+S zFv7SVARVxKBuAIjOBh80*uxNn3CZy#db=pM%&l{cHRgr}8nrntn6JmK?=?aUItK)?wR4}2?X`lVGV(tOYB zkl3%8^V-O|NN!Tj0QN_E{q6#o{G|{sEI{e#5jjVF8**GBxiI(w5&SBa{19WOMZZ{a z)JcaNXUigQOYsM1@0b4Ujd+?=pIl%58v@fTX5SxZ&SehoW_KlT=*Z<@3S;&9gpgj_ z_7Ar}dJB9crur5rdnU9@MZ6IUM#>PZ&-J;4j)z@#jiv>*E@sq9vg}Pb#@GbH;a*6b z&#z?GE)TnXc^2=(csEq11V?ihZbD}j!*wi=^4C`$^B^mjb}Ods*HrQ82Jt~i+*k?k z8-;S!zYr(HK%xK`ia%*+s}-;37(sZ;Qrl9}DL*4P&wL|=rQc0^71!^@-#Sv7@g9;V z{z>nqlDv_IjRomOu>>cVp|FTirR~zRAiwI0<9pm}zBJwEy65blcu`s@%T5OY<#Csm zu428STVPT$Z&uPxQbEWw4s}jKec`1~m_e@QpqZIXfi-)%%n_LeE6X!r zmsNo*E{r_z8NWc5C8~Vtb2~@@K9vYu9p}{v%L{Mc2(uKww-k+x zL><9;Oy9P!4 zUW%YPuGx2rZac?=Xx+Ud#O2b!Z=ZqMv3GPe2bskrkYH`B`jD3K^{SUYTpSlF+6Zzd z_9DO0U`*E?!c*LrM>FQyUv(Ku`P)+Z>RMCQuf2YB848S1la|3W6hPg1lnk$ji0BGN zWOig~H$J@Js-c{<_nZx2!v)V^X9g|85XH>rYccn+G6z*^98;@C=G}XVUKq5tTG5YG6G%?kPu%dwTm1Iw} zl|-D|eJRdFYB&p@jy%G~O=9R4P=i?&ZY>ZYS6SF*aSI1f8@mY#$AQ)?ekS03@S?>Zp{HDJA<9@TJrMb=M*MeakaB?|EWnWSS zMW{pYtJfi?O8XtLd!dJmL2yz9JTKvK_HTZi-@lCGoZqvdKI&%Jef^O85KvP(1r$-) zRv4~??z$7$e;Ji^X6+&^vTFR&Gb)*5rU`Qqu+oj+>6(`F=685tZAA4x2!HPwln9>V zUW|xtd0kwo49z5a#q-5Z+0@@vQL!j4=rT(BPZa#mfH=E>3q3cJYYRViB}pW!M^DN! z!;wXNg)n>=C~fvDtM6|EgQ()QO1)s@L%ql$yDT^&fPPbCM;I$?wZ-I}H(89*%fm7OYdsQDFadUZxHiDBNe6WO((N0?6`=giZKxChBh#+SP<&m>-g>%s)>)IMlcHjB z@M?gs@GRX7-`2w3sZ&RUCL3b!s17M}7W#2m3p!I6zU}fqu*#q5qK(MENtU+{nOvdp z=M9K#(QW}RHdK3oejSCI3d<8K(|g&wQz?Vgauw}=(^^Mzg5L#=+9TZBzYu$}Qe-xPx)$aA9t*ebBlx2^3u0{f-nJDUJ)sQ`6_$K)M zN+GNTw>S%(hTZ|#;rP&ZEmEj|ST9Hkx&WEL9uX8^(~<=310A@DRhpwmCr{M5g|wx8 z2=t2H7*0knl0S`mjea==nVD#S=-YWdbX@#P+o!*`9R+1()(ZK}oxPSryjvi`aQM;G zG_DAXNet(c4gs`cC??GEqO%6K=z;t5cGN@$Tw%I&#HmX6aODR5kfvDDU(JhuZ%+OX zGm{2!Dqn>M+`R>SX382Rmy#E8zJ|5AFlAs>_4{L(Wn8L0n~HUjy}SzE)lz{INOlTc zBG23cOZ1?xo1akM;1 zBXVQf#*$9=2QK}~{Xa+2sf_xb6@P|Zs(tURp;etz8x(?>GZTR39wQ(8n*0cK-?ZNx z1Z}Jg%G`J9B|TJueiT1nATH%OtYk1P2j98#6s1 z(l{h#|HSgdO$67@55cZ+Y+0 z9FS=*y32xfXqm&+-uX# zZ__=!eyUDdV`D6oKe7L=W!VQd4EHXA9O8oqg})=VD1x@9(_>WV^@B>Qi(H3?9Ar6A z{CNv9j4N&}=Llt;o}KT)E8YwGyTwdto@?<&?S2zUJK$~X-xwTx zqi~Qb$bLRu^J&WHswo%Z<3~8o?29=b3pvYJhTZKtAF4PSjuY%ddM*sfEz3|Nx#*2ZueHJ=JLtsL83FKr65!whR;3zP+?hU8b zwgY2s1|h$#?U}>sH2;GGVKUdFjaIa1P$X$(x8tobUYql7WT%b5@zkJJWZJP*Wa~aR=#A)hj!Fr9cs<=a!*1s$xguRN$+(hI#FPrg z8fT595!$8TpRm#KeCLi^9je+Z=BJd!QZCiyNnKq$@ zSf3^*x=I)J*o;_<1qah&rbypqf8LmSB)a!{N4>FO z3HuZ1AI6p|{8$w@-Y)Qdxd$HjDofbE%uCvuW~yv}@EMg+EsogYY4N9*il}L89;4Aa zdW+u}hiTDH;7eJ%E{iAa%vVb)h;Mt(vZ$vTTFPc2!)PrBev)7JS~lM5U$mxUKcJop zhidP`d%*jN{8XR~fJ|-#p1@M?Ll*D&a=(OXvkF)>T#?pXABMqUc;1n-a5r&Ktz!Vo ztODk}XC()}Mo~KFv;DD5aC7+Nzt(V3dlUiwXlCg>B=lCAKcRs)0b3gCrdH9W&uW@rLV zBd8&81}~%mkW|;@vQ((1rUM+Hvr9t`h8 zfn>@}?CBo_>OU`HN+CdVya90FD4(@Ea9iZRU6d;Y(*2i+oPT{ScqUsWJtq588O_wl z4dhyMi02mA-f=DBk^1#u3Wz{N^OZ+=Je@DQe)^gc;~YS|-rn_I!vd)1fVFyZ!LW@Y zR16#W5Bf0k3D?rsCM_{WZ}{6LlZgC4M5mSDD7^j;+XtS zz?SadlZKG_mmaEFJpaRx|C6-;q{07ZW>bgt8v+qNqc4)U?0yE(Zfk$VZ3zdt{#yH} zG7cE1DrpCi>q^;Zh9amjM{ejG1?Y%1+sZRu*-%mw@VP3#ns~`%4Boz+62B4}d9X;_ zYCu&p&T60_YLb$nax7e}74>+_8=8EXh1jQ67%8^dV;NgQl!%n~C=Kw%`p51YL?dpr z&)iRU-8PBN_sz?DF8is!zQZ)zf7py3|l+3t(#|4 z)FcRoncfg4bX+&>f^^8$!y%OX94No0=}yP#AR znbeN&Z$!q$&^up0!O_Y_*OtuJ0QmzyK9kDi1a_?2kCo&rQ z94Y!QGJPHaHe8+Bq0@{l$0p}Mi;LQ?kYdW)^JkBo)vq9JdhCl}Lpe~LM;9j+T$wBE z2H#)9K6=m;O3V~L)u4#ro!|^}{9d|I38cHdi-2~!La z{iAV|!xV35F!JDeVwnZCkFoD%}m5SV-IkJY|4Bzf%uo^zw9s0f&UvMKD zDK5?f#7v)Q=r#!r$!0_ae>8si&}GfFgt~qCn9E}M>?m!h3B5b1YUyh{zILt3P~T2F z(<L4VsmZfY`Ok)Xi{dXeIoUbi%H(FirNcgG#BFcgfC1m-+gCWLrAI&i%S7F1 z<;U^jUj@&z7kjR!!+BqcX)|+YGKwm%_|R^4%thXL@w!rDM(`}kqZ)Eie$W8q)8C+w z*muBYvajFLwi+(141Dbc+>NADC=BC()9~qXe2Hzhb=pG!{nQFeu_Y>T?8ZrZWB>#H z;eNW@+@z2+a!hr0iW3X#sGmpG0#cbbcP{$*0D!l5&7Hl{-F;0P)>+zD%<=M?$(JKU z$Rz6_pRPx(y~AR0TPB4;Q*1QVmkDMf2hRldj|V()iluc9LxOkUcE5b6C@#zTojH1w z&iE{kTR{A`>g7+|jzO#qj-JkyEwu=JuwA^4w-4>1> z>hkeZp8;bz#W%2Dg?&4<@NiFZu;2C%QKQ^2(buuRN~!roPK5_-R_-k+w!ko3_ah(8 z-RWLUAuU5l5D;ep6Z%txHPONgC|U>z~GouK%(s1Z;?5IzhnnyR=~AvN{7iQ)zt( zZF7pT1#X49Lf`Ed6eyPK10}m2ua_;4)hoQ<3Fm${VRb6}F|yB@Tfn>Bo^(zuZd|2& zeNDdX=RV8>LFi)jC?!yl&|9ZmM9CZaV+(%)0;N1}dlX^wX^*9a&-4 z=4z;pavr4o7|ZXJOYhzigDSBT>JF*0Hsz)q?2TAJuUR&>!S#}DIr|A^ z5rMy(%B+;R6%;^f-Zk{zF;8M?e!UeDKq}oew4B1bJU|KdK`IrI77-l@Z%cN(z`2FkvFgJ9QWYAM?T!_SH_wuaQZ=-vxGq&>^d zg`j}&o;_^W14Sz;VC-DQG-_aJH^(2(&C-3)@jVtrsHL@N$wI9HV`Ix);=Uc!s~G=P zZn(&%cehO*Z`)NI0*ZKL?8gz6E=36gj^Ud-@H&Q-V_8%>0YC`38w z+Od7=M}NDAbH&|Oah57ziiKQNtWIR0UJVpZ32S`?CPENZi8gh~C4*#W4;A*d(QFLn z?oyr!E8v^NAYt_tp2WlV5<9x}p=_=#tGMCq;Hb<))}fw$e}7(V`#GL-(T%HZ$$f6o zB*uu+KKkUlb73<_paO%`bg@a|f(%Zf)wiT=%9QlNmJdiK+5H((LL`RR_Gg-(UQrXz2g(^M4E12h5^J zfAYS7UG?vH{Xe*UTxi!Y{nR(x^tt#O=_-NBE3sqA@Nw|3Pc6@wn!>1$!fz#N$Kzl6 zb?ej+^YzwXR&?Bx4Lwr;s&vqJRd(N0BjMrf*^|#4bGNpt(1J>n-bD8p>)|I2Bhyz@BAwgTB-_&o2yy33_Rr=m(d?&49H?7tp)eyEt}<@q!u#yQ zti*azb#|pb=in&Vh2e25S7%I4A2{_N&z1&=P#2iCI#~&L@BT07CNom|NQ;V(rM* z|6w*8u_V#?s@hYV`*;;N$>+E8{HrcZCFvsU_ABf-)R@{*EKxgAl@}V(-~=*(`pkf3ZFfoKD?l0H!f%}%tM}f04(BD*@|c+&zJQ4b;qan4Wf15_5`E`CjrNq z-pbaN#{T5Dmv_YbR);M|LBvA-{Jmx{%a}A~c7*ToYa_;-P=}7#9YyG{may7pi)zkP zqqXs<&qJsr|&>* z)%weT_AJ~EijW)j)>M{iWWwiSURhGFDgA_}{sRt?jd&+iT}|kTv2ENWmDOWr4EsX5 zci-BbUx6oUMoPf6`VWkDrih;`%M@8ans?}Dc}QF9LQ9q}g4DsvOK^+1oRWO&O&v%r zdeul6kM*LK3+$d&&eKj+!f$0vOb|DViV%^iih%5BL%(d? z#OujoYPnFE@u|6&7UcBn-%zLJRNC_kXj1>JNe*(8&E1ELbi?Fdv^xBp8)s4)L0fVvhf2JClcPrxe*Zh=$XK-JrIai?x=^UAuY&4^JgdRaiKsRp~c&U6ERQ7Rv0lrWuXJ{XlSz zGXfel#vpHPIb;zr5n*B~=FjWc!B=Y0)z?dVZ%5ef!ok(d<~3M6q`#^L+R$UYdUISW zo~B~2ueP11x=y3g0Hh&hUn;Y3GYs~Xmu_V8zvSGIrztWnKxG zuvInmB80PIOqsj^G$RiCJ|g0JOk15kdU8~2)eaql@C%KW8%(~;;`Gw?5KeQlynlc1 z%j2up=yhj#r z39}%6v&KTYnfA`DyVy|@GmCDX$C<6zIC;?1CpJ&lz=CLOejuz_C9+ZA`TLOL;iucx z$jiDtr`p@RkLFYKrwbT{LvVv7^Xr$nFXNL`7Jj0;J1+2q(Yv5%vh6rLG|uup)v9Q? z)nBub64SnGn_I9+Rwv;4++aEJ6aXe`^POj?o9 z4o^iW$;QuVewlRsE@q@1N|SOVH~*C~=((q9W$TB#R2r_@g5e}SLHI)haf_A4Aq0_> zlZGgl65)2&N7OZ7@JKXfwYx;=U;4=&SWm4Jk$!(O+fH~tA}-@x-gBQ2&d!o7V_rfV z>A@Wkt##WDbw&R^z2(e-8eQ6iKR(W?o3!2EcWU@z`i=07mDthRYL1-`&j#iF-=GOz z*eR{*Zj|`P8jeAL6D<7!&D1q1X()wVXSw*Wy()AJ$dvg_#|Iw$2ASlAP#|<97HrPX z^8=_&=<~xZP87l1(AMb@aNz1E6GJ|t_dAM@dP{-_(v}Txwlp!XO+pN}OARe{bC)ci zK*(D^f5P9qun}Bks507)_j}|lAFiw)-^cwdi}PpVceG0f3ni?1_F6x4Fk2)PZ-fTmQW``NuWVkA*#gn%7t*x9XU!L3U!78?obYrQ~_ud97 zN8~muS+0pyH8LJce(h6fEb$CkXr~E^P&2U+$L6qz(d#6OcUM+(fPCn5k1N;NCc`N{ z8*G_pgOfG}e{^}8$=D@J3E@@Jj{C?_Z*gLA(C0PNYs(s0;6GNEig(ksG`EO(ozs(` z(@O=uETm}eZmRMqahJ?JD9kyNjcQh>$DbDm?`oKSwa zZUhe6)mO`!S`S*8Q2PZdZZKjCFXS#|h4|wOG#M{5Peb10s9BO({t(j~V zd?=t5-0!1B1E1eU8dyvd&)IyzIZXB#ZKoKri_ZIn>rOWzrP4m*7 z{wW0n)Ck@x9fMJw4Z8$pQN|xihw!^o<^d6FXTs^=#8yOyeF2ebbW&MlP#Lo%sIrA7R*{4-~P5SWYj9RAv{UfiNPF%&;rtVDJMH3@K z^u>0I6*cIW`<6&9M&nPhVVZfQu{S^x!W$E*%bd7xO-&Sj!sgU)L~2mglnCm;|TsP-h8R zfTzGW-B;s|@(kBNz|Rffwpj+2zdtXl2VeaaOXb#8%=OlOxJ=DOQc)r7}(pq|KM<=0s17zO8G6n2kNAOE@u z*|}9mjKj6wOeIhoPwXuZl{KIzW>ZEMq<(fKXkE-Hfwmj4=&P8HRk^_`s&;`gKG|}| zi`L(u_~^71$sHjl-myOwi&;Fr%-ouiE~PWlc4l@T&%qaO&?6o+iSN*e5f@Ti8W0H8%PyMXXz`$iHgurOR=} z9|oaajiFC9($a^xDJcXFtuQ`)|IThz@GyEeY4Gx!Pj&O-x=^=g`dl4ZBGKQ|)(zZU zf9cLN%ID6QClopx7ruyZyM6YB<^jum*+|LQqZ0k4jUB`bi;uP5H?-L6<&f4cZv{IR z$^ysb;-OpvlX*kVIfp6NNf=88+oA4VdiX)eV9K0rLn}W^B zvUu<}-WvVQSO0&)f&UvJ!GHaKOdWCg|H^ytA}1RF-~5f&0IeOcTY987Q4L_!XG_e* z$x6u5_GYF2?u%Z%V;sN}G+qWG>=iyni3E9tEi)H?Dh!qrvu*%N0+e_12?3g1NW)zu z5M34)uz!m!%5)wj4s4m{44nn(B{|)-bP5-7yj+FjC zM?w9MSxCoJQ(yjHTBmcprxv ze+aI<0%t6MG1s6AE#}3XY_ub{lJ~;oimhKzUyPv)dEKm^1C(|YUgC{ML`|D{7N<91 ztc#^!Hy4xB57(z9LLs1=$T!nGhfggyc7&w*^yc4k73JoZQ3jvp@v`HId%DzAS15e& z$-1{OTdL(DbZS2iuz&U#;3G?Feho_Q>(I}J>rz?aoyfepFx;JL+HG5|#0aXAonn8I zwM{IF^~8Yanq$p}r*%K>RzElYnPjfz7G9sRqxB1_U+XZYFsKi+gPNNZt!S!(3Rl)K zX|X)OM4Xh3#g!sot;GhLIl)1MrMfV_wRI6))k1KXY|Beg?@) zZg2owVe$A8VNLedIT?M(+;;WueaYA%?cqYs^~k!SVzU*DfJy=e)oGSh0mL(fJ=lXm zcj_>hx$8H&$|LK-H+a<6bp}2KDJ^86Q`i^kXQx0lorRTePFFD(ENjkx{I2Fy`Fgtd zIyK9+$kLT8FpFEs(QX4m8L0xxt>U^y?W#7#AHJ)N*;vt7q$@8oHCEq7vsIjc^CWK_ z^2~o>-3(jT#|5MBh!$4r-eGk2m07N^5*yM!_6QATQ+mHzc2ROK1T-=2C7SQ%aI;rm zT=ymN)vt9rs)9uvgFiud;0OD+D7?-{qs`P5tt^th=Day$FBc#}t231QlU*XKt|3z)Yfd3|$I-IpX}_r}#C$ZKP39x5 zFAl%>)SmH#?YO2i5r3E|Qzq|3ca##D2k}S+J#D+RokWo%OcD(6bV_TZtSDqg_pH@~P#={RX%o8kDdg^9+ z((d}S+ohMq!Ou8eEQnGXPg0ws?E;^UlhK0ieL+?oZ>B|I2Bq0Nk7tVUjU|qeH5-Hk zB3k<8Tc{ZeVbFbQkIky&iHWMh{+_rvhPV_-XVA1Raa*xMhDO4>sxLk3d}Z_d(Gd2w zCJ3!DRR)yyQ=7HP;(n~QrzJFRZy>F5JLw?71UJjW>8AhHZ8Y;6efmg2O2PYT$Xy|g zfL#5Tfnt-q9iimpJvEHs(va>3C(6R)8@iR7Js<5GnQ!Y>hYbRq9#pZ223_6Uai?8o z-8<<;nR#}0u94QwOG23?-gy~3reTHX0L!CHI4#X^rv|@uuHH^DPSxP&fr3)0Djg!# z84q5^T>S^ zT>MNo9I`L6+PpIGM!Vm2W|2b)E*FVV+`|VhL2Z9KHYJdx&W|) z#yT-|vdc=UKM!87P8C}e1SvSHl4qY&9IAarOWo|?|=foE3+e9#m;&g%89q=!l^#SS`CbtM)_{#r}A z+emp*Y$_}smG-jxE`?d2?DMj-EAa;yAvy!APRWJV>^iaUBE04x*!=`$Cso1E(IY;S z(N66?t8vpct-EUSp9j%ukWOuo3 zZXt@t_N6a68!k^3#tA$#f<0QtOpV*aUL(dVUdM2ojB8N|S_E;vKhkKCTlw*smVJYW z{SMP~@Wa$iNd-lB*3rtG|Qb4__nicE_XO!yQ#FWa%EFE-LAyXkz-FES2Oh>ohTG7JDjg(l) zNsy&KjPs@zo1{Q1dvc8Wypwv}j2r5mYbnG+=924VwNdF{eIRk5pS@OyHf#_WYdFbz zz;i=R!k&6pEMKuu`4J2cyjafZ@z=%RXi$h?fPg{hb|rD8RadNK3!vs*|RDl&+!l6cLC z9k=FLA@dAuoS^(QqSI5sejj}>S?&+E1lCIFL-qI}Et92p z`ObhLYeq@FYtYXgP?i6|d`oB7fyeO=myU}tp#qz|e3EXEV)4;UD+$R}^ zixw8tBC+G^Y4jnsS=_}FkuP~B7T(YBg*jpPNLzXfia_$;B!%d@d32g6#gOt$!V=2F z&c2_JNUq3ui%8}dDG%i=2RY-|^Xf}%bvE%2TJ~s>2DMx$>G=@Gtvt?bXuQ$c$%nDz zZeTqQlg4<>JwMmazay1Kf%t88 zIrN7qPV=Hfx?yAYjAl-nzric@ey9#f>*gI=em_?Zh6RbYJ&dt?H+CC;8#%Y_QIL~U zz9DS;!e8!gHn|R*V`f37aMxwfHwHP-m(%UYis>-6KSiIIwrRnw!V&#ZKXIljTqvwH zryZE~{>^8!7&P#B5`yj9RW=9N~H;4Sk6=qrKnJlVLo_7jH_%V>R z*w{m9Xcz)h=PiJ!m_4fb0>7nS!SdFX_mY3wo^ey2u~Q_9w*}o*dgwMUhine3nbS-D zsP}mP`|VLp#`&q}?yAtpDDR?Dds33&)^v=H9s}|PA}E9M(K!#=xpWI6oV_EymnsMC zgjP7CHekR}!dtzY_DVy<0~XF>%50K93v~(M_>%V`#0xepg@~*p{OKlt9#B>bBv+gZ zb>2S2S*$+@kIXkHye*t?f|Fi4>U@U$fNH4b@6ltzX#L+}LQC8V?KF@4Zt8cUSFcQq zUjfCPDjVHzgO7hYiuliqutL4-$4PJA3Y?t~-$J?7kU>F}=5Om$D@^W1YJUPpZTPay zY}?Jm+l?s*-(7834=qQ2*kk7JL~)Ka5@$AN6v{_rk`UaU@L#CG4E!3WJJTxJQp_W5 z5yBeH$@j6ob@hC`{xn(GR(1Gfr}^askUQ6HjM;J7(z?wPC2+du%X-<;>5Ae;63mrk z&#)eMJ_55a&dOX~l!VHSYAPN@*8tUl)~E6c7Aj6s0ecsvym%PVs%^-M%mJlV7{h(!^xg`iin%X5(GgY}LO{yz3 zu|M2@Ka5X4?6`$--P`?8O$_VO-b)-wG@7e$KIf5~&pi@{K>H2)KDQt9O2f0PuYmLO-y;y%$rHTOLaCwc-;4i? z0%6H%WF?kc{H|T8SVHIJ!ck?022iRbm^KQJCZ*Tj7;DsuBU1qIq%_87; z4YU9ZWws4~_w)^RSO7XOFCpK*fSsJM-<`?K9{|4AhT+YQuW%A`;EnU&?^Zs)X}P*e zKwYQfZiFD3mt6ti4`4PgtNrUq|4;J&q20gBkL7K@tN*+Hg|4qBOzSM3*BY&BI+X23 z%7GUCFjxF{-s}JDk%AJl2rA#9g>V86s!`o5cfTN)d|#m{4f6ak1ACOE)EaZ zoJ?Pl&=pi9{h^=fcyydX@t$MXft%LMJ~$p4Re6`DvD5c>_=~#N%+y;f75gYWc#|h} zB+ti5FEG zI%DKG?a3`474;NdS+d%Ri*Mh`Gk$a(G5pKdBFdBlg++Hs0wio3HLSI%?b{&-RqTY4 zMOLV>ks=#R@3Flr>Iloh+=%SbYF$rOnxRLk2btU;X8#)%9~swkG1{7y2`e=%qKInHme&>gQnd8VfU5+dJj3@ZX&UHENb@X^I>*qrN~SMEv4{E7%av5s|iblcvG z=&%537eApp=3pSkb{m!iT)}Wsj8IhDcIZ*~aVol>9IKqLrm9`XOLZVK)fhPVRf(zM zqhY8rPZkp|#V_n>^`jMO`(oL(cxYpcXDak-S(FUYlvp@eUxvZFwja-Z)z=F8_^B}d+iqVo?f1(}F?&=*<8&?&ob58$aplc#5Zt-Q z?%?cUT#y$48;S-h_b?w5kG9-IU zrTf);whss&>+iUVp;@_cjqfZE)f0JaG(MU+@`g_WP@se&OZg=;(FleWe>25#0M}Ci zz<+3J;W$9}XgC)(-8OBELo9tKSir?s&q6V7<%EsI z!QSf$lfq9u5Gv*s>MK%S>g!9(eH0Oe_73=L6dY#<}HSRmM38;_To2N&qT&`<7toTGVi-*9!S$t?9X8s7Q6BR z`aNp^09>q+LHMvL70xHcVh1 zmCBsl^r3IyGsLef%*O6|8Bp3JyVygm-08s(&0Tu$Wxvx(U9rB1@DI1XwoUDL`4sU~ zx{xKYXVi&4$jF*^qJ?QVq>hVOB}FS)CWVY%jOC4?D}lMi;bP8!BOn{DSHd;W8bH;= zJfB1!x>|qLSbHN8bd`iW3_>wXRJDX%*y-yhRMrHpzyI=Z0>p7uw&M+*Ba_qWTN=vA ztU7T2x;hY&R4dyk>J$A+ov8d5-UW`=M~|c%V%=C29kA!0?XshMp{rRFcb3Q7f{grY zgz7~=3rUY3e`uWVZNvaaQVs?NEj%wf)0h6{%}jR+8_)|8#Y?)jcI>UB1GLw$km5_= z0g#w~D)S*JoO*b?LZc zAz617xv=3iL*Ve57jnJ5>jX}j zbgH#qc#dz!oeKdg!KHqjx_oXym$jFhgG%RVTH@(1P4)sVw|@0H*%|pv^SpySLHWX_ z&v_SGKZkF+=gNN=R(eq%nWhc~^FFp>wZXVpd0uDO{hk1Aw0#xpPJ+G4yqR!njNVy=P`9{V zZihftWE&UB=#yS=^C9)u3tpF3V!2DcLUVoP(;u3VMEP0W1fhJ1rIj(9y#008LQQOv!`1 zDDxuR!4{z*TclG0{XG&);R9N~ULD5jt+#|VkGm6qk0PL>?&bGS=*#EwW5Z%oL5J@y z+sr0yibWXAUTE_^`Pk$v(rKQ%xmo7;nfizcG&91RjeHoD^p$Vyr!6yolnE_Y7w-MU zJ@Pz^D$_-`^7Sg_LQ!<_`YEwCl>Wr%Ks1dQm$AySd!Y2|?J>Cdb+#tiK~847RjE`C zx!XuSB5qX!ggZ0DOpWlo0E&uFH3FT{;dNz<9(rjahB36 zs*ZZ&6?*Rfn+=7Q1}mJO;ec=*JI^#VSE-_&L19-2h7D#cWuxnqUgOw}(%T58CJrIP zOGq(bMt*L|p+1V$1uV|TFu9F9P+6OwQaWimZo=PgWZ#y#rJDjm|80h2b?p=(T%)yA zISSH4d37%8r06VmTy6wt<3PQMf-O)QL4OBePCh3squk`LHF>2#PA&hG3`V@H0RS}5 zP;rCGuPNF8DH9;&|GO5BY5?;%K)A@;a(k3;3b6M6(VKl+Z;}9Q?7x3N5>zOY*hO8P zl%*Sl=lGfup!EN{rvE1O^=8h062P5gxWc^PAY=a@6nZehq0&cMf6pB(uK3?iNXcwB zRptMvw$k6`g~?OFV`}FE5gEU6z~Tssw|C?*_M;s<0<Th_4Q|l8=mfJDS|>xgt4cvwf)O)Mj@{)WNAt7oBfc{ zxmw-prmxiGSoo4)CvQP#Xo?jD9d6VIO1sagWl%;-4q1C zs}tc+CV-2iBruhHB7aOV>N2g{R673J4h`o#V~^VpReR8u!9koo&xcyT0< zC;G2=anDPbBSAAk2+0CZv~bWncZzFGImjtE&K)N_FxeJy=`1R7jCxpG8}p<(-M$h% zHmz7eEEzW~k7L5QKe8;@x%N{Q>xLqErmrH}*`Sy8TXvr0w|@a*a*)kUd~xl>KQ&mvi{(IHLWpd^6=F1LmonLu-7ZMwezbGftbg98tu!TL12UlXt z)(X66$tc?81~mpRHs(LFs*ns{-A+AQl(}%a`(9-@)unQgGZ5*vL>{-1czmDy`@V87 zgD-Pn(*#c};!e;RtKmvxUpu4jJ&~-hz^1KEt}DVVSvCo(uX5lJMf$nuSNn5H%@XnM zVh4Hl`i;*eO}qv_3TmXo_Suf{kwQy*-~*rK2G<(i(Oa>m&w7^C8?WhORtKaQ;wd7) zLI@}JE4&%NApG$5o^&(w!$Zz&rUpe^NT>HpL#3p!Ot)_lNV7U1uzp-(*3GZniTIWo z-Rk~Lomd30Ym z6wG0!e#wBfd6B`Xa;-F%Hb4arv%_chQX_!D#%(LvkGAc?x8y(28>x9sZLcgmB& zSEXFpxVKZ27M@bI@cdou?h%ywdb4nS$Yw`SuN_KFE==tRFGtH3dr{IeOJ{L;p(p_n zhR{o+!(H@PDLs>|td$5CJWNvPcAblQMLS_skrU*!J}`3?%PaE0nXo1Vf5jj4}VS4>S$aJ7BuUiI#FnusueElG5w zv+|;IC7Dz8G|P{#2-Ie%ZHeO2CM zn~zwkv5#JEC|3a=zzPk`#8pjBe0eZn*HuG87kEDg z=pG(H*afN9ode0CXsaA*Bv;$xK`r5LX%c4NG$4S@&lna#ZP z2&%hi$HA>avtbN?j?ngba=i%}9PUFzptEt_jT=m`ReEdN@R7%Lj6yJpp63h8{&HZB zKe7$VK=Owej~y_?JX&J>-b>~u-N7OtR$I)GXju3oxv5hnSD3?58rlGRbZIPAITqU~ zRFd^zDc`2%F>58}h;AVT+lsrbms8&Jqv~Yq^m&Lg{~QpqP`4^#qoHGJD~vD#~dP{oKlJk5!R@E>0y`g`#E()vi>7d85S>axrYYGgoo8|m{y zyj`}>iWShp<|W9M7JKMqUWmkY(>bN%lJjUP=b3BR{?e*~5^yeAToixEe{NM6JK%u# z)>r&mlO5T*Ayg=@UAl zUfonLAMzg)wEhfRF+aIO-tNX+x|)yP3XT`s7SBQ;M6x+=KN8tI5=);}7w_G1Fh^$- zeK{<1G*IsnYgMY-ecw+Y%9RPm1u1dpZy(>Ke#E073aOf4-P_Ntu^^^WL;CjDdb^2r zOxubBd(a35J#_~bR4bkmrZ7=?2a%?$(dCcRZc?5ORGrTex*k?X!akibd(KOZ9k6|Y zzFHG>!t6tS6Mo2&_1x)U{m4NU<{n165o0A<&rjsTzDFuJP^C#0XZm;LbD<2e8`O&? zh);Wt8ea6q9&EhUt{T-);bI+U=PE1WK!VrNg~peqTs~FfLC$*2rBt87`Ft6-g|dZ) z5^(N{9J>ix_vM4bY&h)uQf1^eZ(+8)oj@FT7{7mgcPd7#lfm-SORa0P)T*f%NH1NQ zDx_!2{&M7AYVNMy`m}#$nqI?XF+d{RwXv^Ee?vba#pI94>F>)0aCCRTL)`~bPMZ3JIG0WKJ=@d~3;xb=_8H0N3zgyCI(8>knXC>BX z94d~x@f6DT1#@#d)gDemZ5yYuAKukryzl>b{%Z>VyO%+bh?#gS0EXIrItC2`BTU@h zeKhN968H_OHuB}EvL)EAms-)5KTj^~)?blybTeZK6> zV-jrsx2xz!g_=u3qeZqqDwVxG=^LzS`S`+xT9+c)eP!&pLxO%rzPfa^c`x{t{-^l& z+a;^SI}4ze#Vh;LJ&U)(k-j!Y8YBK|%twaFnoS1`|*iZu-}`|3$G$O&IRL>bX?DFF?v+z5zv_Z`w7ojtInLKTVtnc zSRg|>2@qpQ)ArZ8bX{?+^gBi){M;W}==fMrGRzDvx0z)O6nQi2$j&6o4lcNuiI5PP zK901q6D=&i^qp^}zKl8;zLh@^-n>)*sn`Y!5hewEgJVC9rbx&)9kdD)5R4t6dfdgF zFQffLh{NPVlz0#ARQZAR^U$B;+APrXkENWC%8vIRhZz-KQhvKd&)|O6v3=wKTOdGF z?YO8(@R&+Nq%f`T(>Kec9_)Zy9@M|5Y!2%Pz^Hkd%-){zr|VcpJ>wqxS5sCA@&s;X z7b8f!_oIz(`QUTgPS%&lKF=qL=*Pz-M@?|cnKmc=qL_=!)KvyvV?L%!_45^2v^=>X z)<0_MYH}wvXFZVWY*Z=(ODS;U25fS9V&{?U%1nK}vaBj*$B9sDeES zQClFcc-j7y3NeT8b9bq#iJkG_RMTDkmhRr z2KCBK!S+aj>{f=7x)^D3qtCOrVp-hlfZ1AFl*i*lN1!@v{%Qn6G8@V#bdXw8ueahx z636gBu5<_JauV@ta%Y|AIsOWJNX&u}O?8YMae89b+MQg$FhXA+MBqxGyo^l8J^x2% zi@r!%W3sdwy|7PRJFe%#u;IJuyE9oFkz4(=rsEXDUaz+^t7Oa4hJk5U=$(9T_+17 zI_3EH>3EKYqDhdhqK`E)qifM&ld}D$5kt@$VaoS&I~p3xv-2W7+BBPXYZMW6B2){L z%;YyI4wTZY^3ZuYoLAnyk4U^1vwgIREl#1z*~Lw}k8uhJPih>3@=33eA)9-y2A8Ji zV~lGu)wY!+G7E7+)E#!vSVF1sm;?yGUI5x@Q%upZneWVjrS1-%akIiEmtfQ1m#@*_ zf=Jg}&lzv(tB_MD(D@+kY?B{|0}pxq)1R+DZu#<^^e?v^Xo!{cm)|}}fM%;O20shU zvdz&^aOF_h5J;eVwc`_)CxW$-X~%=L;(g!v))IDqd0s2UNq^xkZJ+FIX@{h>nF}pu z?!>evj}SxPtv;fmfqYSs#Al8SaaiI?lYZFAoV`cnQnw-TI7#D+QFOM7Buzfu`(H;) z=1%k5n-L^M2UtBn)!g55L0UHncc~vgdt3#6s?U@a>wGL9wl2^4>zWG3sJ3)4tv=2cCDkknC(kZh6`@)R zD$8DXHVx`?)cII3cPZ8?lOvOFH9>!p=~fd*LY2b3tGcs9IeB>23ozC=+?N+kPq~Ma z70I4T0MFRfQ~KNpsc7HMUDg*oaZb#n;qPdpW-XT~!4;a?D1>h(DNN;CShG%)iAB@- z8V>gNMhCnT5Ydcd!TwrI6t1qo)_ZHTPbc)D#Z6cJDM$U2Ql>2MOZ!%V(-J-BBD_oa zAc1isfO#}9@>0J04jtIrTEZn-Ck_JkpDtS-L?Y7go<}>B$x&kn`}nNXQ{u3ll3Prn zcKWQJesGo1Ciq4Y0itvl6^B0u;&ZjI5kB^tOAEZvQZao#iu3*|H9K{qgCsl)B9DN; zv|P)Cs2w3vj$wS;n4iOf-ABL?C)XMX;n_E3Gz$yzdw&on_-mu__z>_84vZ6rMiO7XOoye?mpmlfY#;?R=DP_m~{9yC5_Dcq@`p2<*G zj$hK*d|;dA8aZ;KVRjx-2DCbv?7joieh7WBDF)1+6Z#4qJ|E5qXLrPC75F=dd+DAo zziwmvpwb$={)l7sI^-m6pVb%@P#AfG0Ah-=WTAj+W+vJ44 zj-Nw4vQ6Hn8x*|%(DZOi$!eVUijBB!R1&U0Fqb>$Dp@tTXw)spJTJ;TWaB(2F$Cs1 z6pwk-+qI3JH#{+^bomy%LrHyi%X3#iJdwLdx%_$27-{-_j4Sg?9g7_XMw1o{U&KS? z+&~tZ(M)p4eL_e7^LwS>Z8Q8YmDwcU)jxr&IFe;_Eq!+>nF2D zZQd&=%36C>bG=$55wB$wG2|dJCWjJHgm&m*I}h{v?*-qZdaSMBA;~XVZo{@(;w6Vg_)fL z-RWMpVtk7_udl>;_vo(BTFoIqN3jCgU$Pa|>3OpQ5xk1*zZEzuvZi@sh`HN0kn!!s+~c*|yC9E~ z-=NF4oWDUFKn(Q|k@c^Mry9kW*t8zq)$z29{IxI0V^+mdK47AqBog6{q3`V#$IOF^gNXTT)wdPuD&i8%Z_kA7%=3u4?;&+AqBV(5d;My_2eeo^%^W=(?KzWuH z`rC%p)PMxMf-svfZ}VcCQi>ivMrZQO#%BSRtjNX#saHF^ulI|e`{#PBYyye&fb&37 z=fI)w&oQ3|@{UV+&1?waSy?;q_3{b-;;lDr>r>T8ZY)&n;GA#kcxc6;W-$luEAm;D zydl`w->4l&zf9;;9uQiQ2Suv@9OV@NuKNadaaQ~jIEv5RaQ&prGx=G-zcq2 zdpbZ1dv}4p62+jCYVRRl5L0$(_7W}xIqssGSG--JbgjF$S*RasEN-+WO<#Ak8kDz9 zcQcca!77(xEW&oqD#|(9m}w*RvgDb`{H)#_vi1G8lN(mXqX4~UE`m};IMZcl6+Fbs zB8?4|wd!aUVX>7mqXvcc3oL6l)wR`4=FVL$ptgiqzCC~vGd3z4HS`%V+)3uU^~H81 zF0h^VcT}1$ByP3FNl7L5CiggtWZ5)9?h^bx0>eHbtQCUYAc2m38%^q*)CCP2(5-7} zXbfDSPgzian;$Q|@``dz!=6n={G)V(fS5LK*T^GoNi4722+}d7oU?88CV_OJe=ltE zgIEbSH(YL?*PeH+Hsf`0v~aKR3}^5u_`X~XlW-k1q_)qNDkf>@R>-j(ncalytWL1G z_WWr77uL@#(=h%#+S+f6pf>Kvc=;r`cpYmGF)QxQt$+Sg`pP`*6N(1<=nnRv(8P(sw2y-}Lot$1 z{(iMsndk_@TW7%$jrTg=~Y8VH{J?`>V}X2hk;cswZobroA?5ErTu{ztU+B@ko( zuL6m{=l_=1N*3$=)Z#ID9gyBK1Z+cef$*IljdXd-t@LU2nQE$b`OgS`qo{(NR#Zs* z`HmIMLagNY$=dIfF_@#&_1yqo*cU;Y^^u*vD{vnh`Y;xQI40DVF3}32CB$vH;_?mB zF7;z{fR-BUOud+@xsJpRMLOp7T5>@g@d>iX0hNlJoDa{cz=W@1--$K)t`C*QJ?<^6 z4173=b)g(Tn%>Wl)g5u8sf0Z>~15RH@t$=H>v^9LcGV?U!mw3+nd-d4FN91^WT4 zE;%2bpAL|>D~!s0v&5oW6j_fw6r{TO-Eq6(n=tvK`$JARj-^A{F4eVSkGQ=j&C9~? z-2Uq(rpWrfCpgmn55bx3hdEXCWf?%^%<9Q#5-J0EAgA6_aUp|E^Ax{dszS>xGn zu+t>NwohcotIedETin1IKTevl{ON1OY2Ibd=H5zE}`ua7X@ z*|~>x9?^|hnYnwK7R0yC?33_2#Uf|8xi7`x-$UZYwWhQ z5FC&kYF1p6GMcT!ysF#+62S1)&vMc!z(TzYc6up4aIrk!|1DfRrsfa@DZ_g@{((y@ zD|&^Mp@)%FO;%AB%UN3Z5C8Tjot>fm62`QAEZdg#1Vn+S-=g3SUt_`2 zJU4q!ye5N{WOM?M1^G{J%(Y%V*l}(2QS|u^eTm*xxYBNW$7#3V5YOb+jU4%jH|7OUmHumx4lmZ_Hd9aykyHqWqsiC*pbil znZd7a5*g5QvT1Dnu%+1|enwt*xys%vnI29Q1D#tYsgtG4@s4u?Q)yqvRE)T0&;-+* z^H*<~*GN7Sd6=AwPRq_AXm`-*7HcZas{tdmCmn08k}y)ra}>x56R(HCVD z8WX^dkJcGu>!F*Pk`jM5sK+Elu5m5|Wj4Jo%6SKg{9EkbKbXxr~; z?%ez?kW@dXKj1)-U1J}&`q+!nbqv|m&5@TF^OU`BrrS^Gh$&)KLPbsms^>4fZxLlq zShGoVpEEPx0{!Z!DfAN>e4CkPB6W+1jlVxl+UOeB&0to~{0YN2?q0&Hq#})*Xr3f& z|AR(C#qD}Bv#|U5*23d4a)Tzp(Ovat)Q>IIse6=3og+0g{LX)*8rDdz{z@W*anu)d z?^kr@sqhHc^LR$SD`MEF|H?M*r@cx_+UmQM{G&SL>}~$Ll*Hkq*N!xuucaegDKj#? zbGB0h;&{ge=1M1%UGa~nGw0JXE;p(MOWtRQd~3UoN>1jSnIGt^&VTQb$?X%DaKMG2 zy2Z7M`+2lt^uVSj*4AS|C)dgSS+m0@{M%LUcTAT!OcND3UB0<&lQyk+>@LlcQUBr0BeITD>|;mLX!@;(4TPxcDt}< z7jhKm@=jj}GqXU+Ha@3xl(LdD#rzSMl1uM9;G_Y<5+Z7wRayICF;< z%{l{{uluAzf{*4S-z%MUnh&kE5a`?1Fk4S7eYvuK;gfo?)M$;7i`1RJc1&0DFR7OYPC`R2O}liZ3T`qVIl)6y*^W z?wsC579?(zB^J%i0H33O)>z6oboJLsy9bN&Cu>RY4;c!a#-98j5=-hnKI> zfUoe982Ev0g61BPe3)l!+j6hbm#M^5xHO7^U1x#JX4Y;ap$&kbIgzlbhk%hg&NbbNNOR|ZL6BO49+^%`ezWo9{<1Pc#gEIzI07h;`T}wHOv;`Q$EBP|%^CP9&>@rl+iIb(Pp60|2Gi`ia-4 zYT@{PfYi_;GUb&n7OBdHLZ+0&@571_tVh+!c?-Hb7s#y!Uw`p=w)-|arJb2hn#iWe zmP_#XW(kVnjMqmyGq6&*4sM<)gW}61USc6^2s0NrnAY;~YTFB-REb^K+r?HeG)nCv13rpuOtOKAPxdcV6-W=4KL0cVozVU=@%>K1J!|(4h zNK&i|ihJvTPYk(S#RU7yV{T(m`OJi9AQRV1Sf>bm1%3N=sLJj5AcWci?Z zlKb2_jak2~7T|Q`X#`V+o-fV)JlBrf*>&x!qe#cIZu*ZK z9|UKYFCx^dn?HIKmXQFFg`a8x%wCm`%(IMw9YfcEKXjLrOzfXF9DaUY(2NW+DEnrk zr3Wq#@-{E?>V!0fPnr;U=^(8esW>%Sbnd@6^uVW~1rodD)sLcE@}`>(^7G~lW?6A< zO>DI}vqU-J=BQoc?kruKB|DK+JELAx_KoyriL1Mj-M{TmS1I=)bUI&N;EwTxfVSsB zZM7(xe3`t7fyel)tG)`8&}mjj9Yu9jQnO#oo5ty!A#U4eQpUubZBz-fww}a<{m!M0 zZ)YK5t-Ia%t{D#d0S zd(oo!+eT{1l3ES16Y0_NT~t2)rPqenDw)$OO=GLIHhyD|bi@YlZ!+j)h6X&m%{KBC^>R`3EOF=5xt7v7DyR-mkmkGI` z-d??&qd(mUsB=b&$M!LO!K8`cG+EeJn(l|;EJcH3Kf~~W8h=s_)OoqPo z(<^r4<4aD!9$uPj97R_mjVpe@`?@N~h`vqX7m89YqVXp7gqSJqp6^mS>vi&Gz488r zl|Iw?8dY}+hjilWk5-i^4{S4VAbFD1s1G*_B-HSeM}dr3tmm>cLrR8fSWof>bSuj1 z#~nwJZTI;&W0%dNTvV_ia0IEBrZ$SF!}iDw;5;#KeL72FK3-lHEXkkaB_~{qs_Ln4 z>e5uG^s9z#=Xx+r0HVkAcKUlPgO5@JQkco6kx@nXHzo@peJrGSXow$K;wWp3$z*bn z_cK75@?*=i$%=5#&hj!Vh9S6CIe{%VL^0biv(U* z6d(YIgDnc<6|WEyKThP!GiP;O?-HColTJ(r5Sq#4+y0oFb5K{Eo%yrV_5P=M1FNAW z!d{)z)0mzgKzWNo%V8?0f(NuY%73!~AbQKEqJIK9xO^Dt?e1~9k z>|qwVu%SGYivi{tD&~`I>e~|l$U926h0WChi@G`52G~n?l`-qxw>QkI^5-GcSHu1q zEyqB1FiShep9OF~ZT`pT0L1nmjnSO?CKr65!|6X_1C`HO27`7I|H4ZA_V1D8&t*f= z*Rnv8@g(TKH2yC~ew!VPabwm(piBQ(&ogG9i2o$(Iv=)f)&1|GM*hb{$NcA{#9XRY zwj3D37Rxb0FdI`?I{pOrUs&8C|DMs9y$I5)(+JE}DeOO+wz=p3h2^sPXK(oDyh<0F zTSF!%tJW;O)~Sv9xRF(Nn^4pbEfncR^PzChspi-3`3d!v+aLg z9LzAVJByS4pL`{g2)UtF91C|NGxB9kVgE5fB|e_vZu3fOG7lSFUd-!3=$jMOyOs;t zX$A~6+I7MkB1D2I2)Ii(|D;R;=tj87F<6-NpDqtLAJ#+FjcEeV+F@K7lrlzfBO7xH zyQV2VO#tjM1Lo`V2*8%2T(JUm7>BCxMm&6#P%uNyT7LR{wxD9=Z9l%%K~?Yyj8XT} zW!)i?-`zQ~f)$IxH+A@EF{~7=QdrfQWwY?STGwLd)9Gey*%K|G2)drPtRsLY&hjYg zMD8^X&M{~nk%~6K|mUaTiK0{Rkz3a9@d1+F4^H*=DbOBpE^Tdf2ne2e6Ua zoA{L{B_YHixt36Or!|EI{?&eP`ZsYPK^->;?i$tj3cmz&zH(NuMSn)woJPYc^$mF;h=BdvFw_!ZFQ{L^kiZf zg|ydPcLkL!DoZCj6FCug7JiZOK;CeF(8MdElZpMog#Bn_fup0%Q{|_IM`n9)6$Eba%7sp^03-^Vr5Mbg0v8 z{ytkAT-24Bvhkt3i^Bq^UeKOE;#H6}O?Md-hN1imE228k?@we_5H9s{bJdpt_S+N; zJ`eU+baw9dn;-HKpy^f;uyqWj^Be5$O!i2oqSi1l{&fVVZSQ7T{&Eu@(g2ExYFP0o z^7nuN#Ygpfh0COkN}n%f4-GLg(+~2 zA`xHh$sP2s)fT1U1hac+LI+cCa|aZcE*y~~F!v_a>yGTjY7N}er>QBp=GV7cH{W)D zvsCd?YIctlYVS?PhN+}Wj~m6HU(I|W$14L)92K2EJd6gS8=%9v?_gF|k2W!E=5c>v z84+VSY*C+229T8-q=-;Q;NXb%?D!W;k5~wN1NNZ95ClWjWgVNiHaxv6?C!?=ovRGj zr)GH1KLWm4+oB|_BT!l#me=Iv`fI|)L3dl5C2qIHz8t7)VlH2U{g}XAU;i>(FYika zEYt2D&w5X{jn$<2mLo_>JLv1E`PExGKgGs8Z%1XgJa;<-slnGk(1$fB8`GnOT~9z% zt{6c-0^k^E*3`eSrhl`{?v41Die7~ut~xbC=j|VX9yU|<`s^W1*Uc%K7 zGForWq-|!@@RS>Qs83ia^^4^5mEma744ov~Mgz7;m%)?VhnK1GQ-By1oJ}VhOhrM?S}A8S zy{=$d>$wK`I`T3`Z-RdlWt=SClxtI?A4$C8Q3utQ%eK({LAq+f|C?U-@fIVhXP;P2AsTPps-FFv3jeF#3mnDdSbAjE9>zas6Fi?*wvEA4St%~qG zIJr=yuPsA5h;lN1_H51vN8qup`ak*=83!}}rOsHPWxw=rZi)b(a@J4lUB3JqYnecT96jx^CEWIok*>30$4K0HTzk%O3oqFPM6wHtSw_YWOZjD)XrD3NT^) zVdCK%Z$$QR?ttH_;fmw3Lv8fs&(qr__j(;jh$5R5_i`5!Y`K3($^UA`J-R*o#B*3h zf49E2&S-Bm;rQeiPL+clGl?HRU*`LATW1;0q)v;l&z7P~lZ%0l_6cnwN#`mIW(!iK z-|i#*1))ktW+SU{`UmW$X~ZeL=#u1Jt$oj$vvLIM^bs-lulR4^ebB=Njbo!FAdco|Ej^xpIa|4H&%aju)1?5F^v`)X$0zHz|UNW^;X<-Hd zoGR0%QS)t|gJ z>ZrMwAn$ZXU_L9Fsp2H5#|xkPI}>bpZ;pVB%-sy;kyLzYkYH%&~@PyfP-*9HuP>r;Ic>0U#zw5BZ~&U8m3Ch<@j>nUmA>8xy+sm$Cl>p_tzv9}kW<#3XWUB``-bvP$lL+N139nWwbd&2 z=0tDzdr6|>tp1a66EFM)y^GJanP<$;V-GZQ3T}XKf<09ThhG1u;~{*{e7%@AFZr8 zyI+*gvmQm~3TMOM^R2}Icj)ZhXlq$!YgH^We7oAQh)~J&s_KqD2j!$EoddLRe=2Z| z*JnkSxH_9Pvj!}~Pok@Zb{~a9MX5!S61se{Kk={0vjnS3HVzyhXRBI%i>>>zS#N|l z6(eQw)Ti5_)*&1}_gjp}?V2cADK zUFA`E{Ju*S)jr`-CtD}d&v(qEx~rTagx+@h*6y2a=JrA)zeSiYe6`eucq_Ms8)GQS z({i(0HTR%fq_O=&5X`JNJKRyZLbzrt~&Hlo2(`lK3UbSFt zast?dBk+)V1Arwg;UBmL@XX%ClHS;7uBzFC4@SyC4f5yu7^h!i{gXbbKMNN+J9qu7=Gut6&CO$j?V8#`VsezFy+tu9=sT%w4tn z5w{~o9H|d)$h+oag*zJ4NgRHu1K*H^7ciO;>T@bbGvS`#MQ^Sg<%chQ_w=kG#( zo>2BENWN)R_@=1nfZ@pLH@GXLX3YK$eMAT{!`#6*W$m1DJukk3XG>B7#j1Za86p(% zq?EH#FV)hZL_3*i-Z?WL0D0P$r&_k?vjOSFYS2+>{t@xEB{TAxtd{|1gFuWnL=-)M zX0Vlyp+UqvoL`@LBtc1_eOHDhLDXns@DV7Gmx3!M**$<%L`f;Jp_ zkv`bQ?#A%trq{1)k3!-vRElO7W^xU@W4Ru@^q;wVEGA6JQQX>l`joqYp3bvU6C8t^t822#$D!)X2zrWg^2ux>221x@sJcYWr&0c6zl$gVUT7e zW+X%JOv*^p!!%y%+n~?E5ObnzsmZiTf$sEnrmaP_Ep5iq6CT~5*==L~Dd-~X*Vg%a zu~~l+?l*5LTgJ0=7k|r!FBRzkDSm1y%eUg*8G7rD@$wQW3vZL8^HN7Y;|Q77Q)Ase zHx62Hcqm_4KcX>8p)S><_j0yxwV9ZdUeBG>`e7eznRc|v5q4OvBq^NFjq@#oB;XPO z8Fy2m<7eDXa()$v)J^Njb-X{sh*HK2&8dkgD@D>^`jTvRTKMKS5q|1tJM--`Z?acR zK9hMRw;o>x_zSgD#O2Ux7|YGUg1r%FR(%M3==Pj@vXYTht`0@jK-}?U*kBI#6Jrb4 zYDPhc7gT`q=;uKX;rdhP@EY-Fl*lR>TTlMEobb8j+n7s#3OCjc$e{qtCj zQ=IZ_RgPK_NcJ12SOZvp`por4vcafO2@FTqsFge-g~(vqp?Ao{=O4X@W?24@Ucy0t zpRqAwh4-OcW#%iY;hfTo$5yj7iAYk(>#;LlLb=dxaqYbKS=C9jbh7mC6(l`7nT<>4 zq|(6bz_SlkIs@`UnmYlV4O`%=hXA}M@?@wKSkn&<{Dnc z7zeIU*uW3&w2{o=o^Qk;v=5m2IH{MQ{rosyAFGrNyd90QZK@SH@JPgNxxh?zIsuZC z@5cE6i3%^%<5%4rGPHxx;-iCzy!kEh%Bg21%0#237W+L|4B9qs=>p9(ibXVE7Cujh zUb&`EUyuCbdUPyRrt_;p*R_<((LjcVvMlP zHIg3maKOQCb~)tGjA8T9v$6`|i2+Ql8=}hl)i!#O4Rzs*p==aLd~7)!s`5Mo<;Dumw21aswjFf6HSzM<;kZLKBpY(d)W|PmQ5@-hEqgt^HZ?%k`sQEfl^?{pkr?6 zMRngQ)LN1`3-L8KZY7Z|Ec{Q2!GwYs{t4U&+?k50vOYI5(Q9g|SzzwV(CDvq6FuAb z$|#TK1Cs-_VATKs90;IuZRL&1s{`hp9s>GywidCSoL_OPzIP~giLum`HF1}Xpz(#0 zShZ2Yqg$yEb+-14iW?Sp^cLA~J>7Y`7q$+jPV5~A@5{UDIGQxy9L*;O3u!ZPI`hsd z02P+as=oMA<%R>B(GHd0PQ*@~`d20qyPO)%{ zR}9&t-5oIfoXpG7AJ`ZJKB^SFjClP5m!+!agh2MLIl*^OIy8o`Xsh>1i|O9yZ6=!V zzT0@QQF%7Jp}T9YM%1(Lmd%O)_mhOQLhfq!d~<3H*~i;cbP@0f7{dHPT*w>u8uU4M zFs8-;He`X`!83!k@w6;}`(iF-HE%{R+BN69PFH)G>CBGR0M9`0)i542nx*(peLR=? zvL$m@W}?F_Ajsv*xhen8vD~l$F!kOq;G2s9el#oV4GJ*rg@67}-Msko9k4en0$a5p zsEPUZ!~pcKF-HE?7|Z(JTYK`d7TVU#GG&fl+Wn_t_GL! zXVz0=mk-osDN{`KeMp!v%6`jbyz60N7?wiH6s6Lh*4RW#vAgbgWocI&`O_)gseCLC zWFAF6crTxC`-@1Ly1{zMaEMO+u!b#jJitu^PPAvyJZ4&(b`~qaakBI4y^3~IOVZWY z?|X4w4d&qj!7^L8_H|De6c=lTRA5Vnp#u^erFxV3wsd_W>*ke_Pk=DA?UcymB*sub zeV`+u6#6MlhU^ZY?L8&RR3*2wUY082PFNuvXu|{oCvusK5zb=tq&}!i(@UjZTz>X6;M?b zeeTc8)cW>$6U3(ztxw@sI_mHT}oprT99YW=fkf?{Q8heivMHLEhLlZ-gXj|Hrx-O}P+ zd?#a5qh8>0LpL#Rlz4|yx~{!pDg2>ny(?I2TuITI!8AB)j)CPjr1{2G%!%Xs@y{pdhbMM6&m6>k>Dx=T zc5g-oI&kv(cVqN5J{=8Z@b*b*PFy37>Au+Az}c=rBWV}i{8wx~h?^sTY^xIyU$T=K zas7p^u+>3nW2S<3xi90p-^9{X-^A>FIcJTCdTYs?mA$rlDQW`Lobuy1^ zpdjyp&@%d@ZgNjI(|RTAj7c&iO?pOAuy{VkVnivqszJ;n4b$T`@Z0N)P@L!3KVkde z7ri$ka{HK!#OzWu2n7zUoNSqN^WNvx4x|Oht9(d^J)}9K+zvl8(M|3-D(_J5O}%)2 zFla$SoxT0B)4hHp+jS-V4yN6x#nxdIsW>V%>)8{obS!n1x5GAiAT2j$9cz<;jRJi> z9f9T8J~Y-(7PyK_>{^bD1~+R@D(!gr7@FTy ziNZ@*Iixbu-O5#~p2!VjNtM{5)Z!R5Nb22^<@6=$svN^GnAkXRz)LPeRipAA?;p_o z=-HYfjEw7Hgr;0(Rd28Mj`sG?@>bOb_x4&Gca8e@z;|aPWmfsIdrb?sh}WAo(>QPJ zUs_TW86(@O=PnKy`NzQ(XEeR7OlYZKeq+uZgT1Mk`8jXHuhSVMa=! z9o{6Fd3NGC4Yt*qMt2_xgtM%Z(yITpYp1zUoo}c*{X%TV9KiwgZV5_vLEnqpAl0V_sI)!uS*3} z8^}J)iq!+p(;Cj#;$GO&ek(0%sxE5d`2f#La*B!1@`1NRi{}_kzHf>#d(^ilO?XeI zNlrSceJqlhn4Z1-sIf=;5+`w5eC$lQiMRQY&8YkxZ^FAdFDc%op$zXPyDI-^Sj+Ca zQJZoV>gSd=lE6Qn=`L#k&e-)SYv`g4ZYgN_R>v%5st z`-Tr1zP`00J&6l+eq}Vk5WRJ2y&f$-@@{w^&F@*zodacA!R48HNYTUi%vsz1z#hNN zJI4#MZ*1_PgJ{!Je=UB;W+agwJ6fSzU&i%G&9ji(nf-7cd}wLEx$DuwB%y)(jZRM! z_Nv%MohZWn(t)))L|$Q4BdjWci}amqoOZ^B-s1-imiRK^5j8SbnhN(k6rt|)hEMN` zm#;A_ZC1G@dmufs*)eduI>`q@zv>A+?ow@uIs!^t(s!J94fItalQU?V!=Lg_Dq2V8 z^onOccFkzfHxod6n_CtcdO1*S>^qS6bn^E6@c2a(@Gc8IQ%Wq~I!T3;&iAw|1q)rf z$g)*W(fR)Bv=F^ZuHw=Bcv9F`_6QS0SrsH!ZIkQKgsn=GmXOB3sd@3jGC3O1t~&s{9*rJSh_ne zb#Krer`rZ1e_;_yYC5|Uy&8QK&p`XBHBMkRX5FYJ(1|yILf=GwMN0J^0^og^j1A&$ z!vgs-SZq>qWTMPv=_b+=`h~0Vp5r}i=_0gt$b;g-_>YStt_fw$IkpeQjfIYTHzZ@OGIz1~C?;UwC za!2=IN5y3o^pStJ*bT$xq;E89Y*2b$;T;E>w`8EpBmY(I z1z^twDt-SSUMczia6$h22ton{_PWn)V-oUqr|%x`a|Nk(hL}ygiQN}S?WDZ#{0^fU zE$%UQ1BAgCGAVkDU-#`PbiKr)%2K_LT*rUNCBs}r<|(J^?;?Z>;L(BQ0FPQ2fHk6+ zkHWSVPc~XEMoL@C1sJDRF>;wmE#K$=O~c%qhh*~spf%?Io$Ur#y&uO}gv~IjYJXV@ z(s2|vxT*Cki6~~2D3)YKzE|5?`joXL`R zBIS0=zh@!$pVK#mxfTXZe~sP+d{UN{%A#}Y6m{cofV-Lz1;n7B06;|tT7EdvvN-@d z%#}aqV68{PdO-h2w9{M;+sF{j(HPvj^FciI6mj|H)amL35PO^W#!IR?wtm9PtImeG z&;W@SStQma3nhjnS*kAVc=EM{h?0@AYmxS7Zc#uc@-59<36%7oegyQcDf|S8yMqtW zC7l&DjRJYUjv6kafO+ya7e2w=2rbrKRIwFKTdU3!FFG`S&3!9z%rYi$FU6b@)nZH@s;#{KTk3mW&cD+lBmEny{yFU*a8xSc|%!_3Z z6mKSs|5(}sGXRh=XNmzy8Z!vZBmRy*+3rvA;+&W7SKT*@n;vRgdzj`@SJKR0KAG2S zBzNnu@*>xVw=wex4o;z6!keE{ZcrT*d!@+9>@Qjx6%L=H0F$od^G|e5k+%tNS76I5 z0Q47})yyqU**%lAJ47Yna%VLWpN2Wn4I_RT<_yGY2&&U9;(optk4f~M zvRsBSE$#-eR*fCl+s8i*BkD+3!JSQ^LT^dGTxwq}rn&8FGq_o@ zGpUO^@DB3-G9lwQvJQqQ)*fjek47PndWrnNosehTeB1d29yIon_Dg_ z3xXV}Hf3+GT&P#f;O&?8Emt$moR;}bqSCAo)XuniBZGeORstjS*C_4pgHf563VSDG zo&cT>TUH*4aazexh3Ac?)yI@MmDdE=9e zhNd2oq7%V%e__o!-7*{J5;=pd>1fz^lX!&`l%MY1+mbaubd^9yQIAV;#wW^h^P391$VdNfy z&SJ<7y+W9A0E(0NzCka{n8@4X#7FBs*m`ECxsM7_H1(evTIa*x| z9fg;pbbPPQ93*$b7+h{MAG4Zi5uII6-CcBV4rvZdY)W&OUQgOPO@GD9D{1Snyvt9Z zYdkl{!&O7=>53OG|FWYTe==!GCHmkRD%$uk$NNWK*;R8I7VF&_nBC|^cW`JloMvE! zed?1AMt5xWa}kWk-0HwJ+_GdV(=mB3nMvqIQPFQ8wza{L1dX8`uu<%~-05oT*Br|m z-J9&=9uQpE&XVW(eo!aMnFbLsD(pC{h=M9$1_i4M&xH~3R#;*xX^!2rWr80F&VfRn zEuSwyCZy2JGKy#trF2~JGA@ZM@^shuvGKqXjCdPjj6HT>IcXiPXA#>=4yOAgwjDI! z0<2bl%%wbOHct-$u(@5FirbV1zuwn(HOr8W6=m<&o9}U)HU}WXLi-}KD#y|b$6R8_ zgVu-u*6=!a;!B zrv7V2$5?1|;0AfT!0ZN3D3`qRl}<=8;j4G#psy=ZrPE!`3xIZ$Tlox!1yLcpsN}8x z)707G3}O7(#$i^$aHS_SmH({eeMD8yPyC0&x-9exB4)%K@+Uq%^%`BGZ}JDlH6aua zf0EOjw@ffJQAN6Uqt=6?ut`7)hTA|uD=`fYm=oCJm$cmm0j zy=4)ZoT_1YkW|Z=8goiV>0F$taI9@u^%?2a zjx?UrrTm05mlls-N0|@z$^;Kb#m`5CW!$Flj!rTQ=RNjh!15Q%BKdX$RRcD(peq7U zbrsMdD7H*`w(I&0@)MP7#O(btdV7##m5q)ZX3J5|Kbkuyi*WH@1FGLv6~TsD(ZS9T zjMSJ=N2>BHud!&BsJF_;X|XQXjFjRWRAO2&H(yHWM+%jv^Y7$dMaD`ys*01GVo&{r z1>`rK9KjyTpHBjzToC>-WlX`2NPYD;Cz$DzB;ZV-=^-#X{r*aQm*rUpQ?q`%#IOSOn+v-tSc(;1x z_~|90^5*M-gO$<90KKKI8eYr!!aoiGb43CBS7(OGUKek@*)T&tC)`EN94ZW_XJ}dO zy0??Rc!%nOIw?-jmY7WBD3iX<~jh9Nbw zl+J2~NI=da$!hnLOs^;!7t0Ma3zWm7nQzwqHJ5;SEbDw8AT(Ace9yjYzlu@NH)IxT zoYyb^>oxZsIp^t>dOEC@zvunmSDpqVG1|GmUJ5`>{WGeQC&Eo}?hxZ#u?xz=TZw zHAd13c$PAU)$ry4qPhRhN=C*mjkwc^O>@sjX>l7WZj&we}=fGniZQ>md3dkI)yowO{bk*=##c^&dw@=J#mh z;AD%TOTv~!H;g7fFoyMZ7oV37QP_cy)zbJ4H;nM4OZMA=JYz%X&GHDe zq~>UUJn2Gk+9q``LWqPdoY?pwYgc>XOpRppL>sg|A5c5Z-WJh!n9N9(v7wWwd)=d# zN96L7k$c-yj7Xy8ipUsPLV??0xcJNNe}1Yu7sA|i4W>}n!lC`Z8a=^Vx_=in07wUh z0Mda)7JGOgvQ(E?NKDrUsfQha(GTb*)d@`tZPX+!VM{cA{6doVq#NdQ(k@Gx$n`9r zN%wKh`x0?!*fQ(S(>doWZN~{~IcAjlOxl@aMw+?_fSA6k5zPCqw%F$1wwN9{pfw91 zsc;xRtOo@w2~%j$^#erQ3#k{sOpdiB0T0Zf<RMXA0DiuQ-n_opnHO?K$-rr?eVXeiQhj|JlU9Px)` z9&4gyfZ$9hAXK4$5v3}ZG-@3eAz{vTu?7i31F~ZAnJc8%z%kqz`-l0J)U#eP8}Lxy zD+G4e`pr1+e$LI?Iz6*F#lDMuV|L@2qfD9l2}#logI$OY0iPxPV^;jcT|INqN5K4I zbgP$-7>sGEnwD%l4kYo(IO~8ub!QxfpO)}^U`~;HZj`q``qgFudKr&CiTc*HP*B@s zHnZ=TB*sVQN5WV?HI!RAm=n(R0pLshzcINee_AeY+Tbq0pZuuYt?M2HYE|J{rcWCl zi^L_~C7=6UZqPNVFi$C`;z-QVE~n1Xz@P3M3ID6MMf17+YawPZ3tpZPfSjGX>2IdWH6JN$k*Se`Tk>x z2z4s_X>IM0LqkVC0j(Z=&IDOsdC{q$cmB(nZ!`1B@p3tE4fYt0^AQrO8mo~&~2 zuwaqyEyW!Sat2Je=$ND2t!PERw`b|r3gJ`T9`$?1Plxv$v%--UHI3GDk*qXxcUE$% zyzLJ+8zZ`!DNn2w)sK&t!mx?a(x>&wAyrA2$>xB(v6OeQtxfePD3PwBFHj&BNPe^z zGPrRt-q?WMwG)(Kb1ikgO_6@J^NOh{jIx+h03|Z-ARNWAAhuekTM5;A_(o9?3*7h| zS=(w9)A7x=w91HXaz`ZG%gx|TyvR=EL%=M`y3-WVs)HecVQ=pjiARjFWq5g~2iRX@ zM<=dU?HLnH`3XBLN!;T*9rrC-i&c4CL)y4m=4x2mvZQ>yV+&r9cg`(KOZ76Mx2+;_ zu8JVKSUZ92gv5DT`xb^(PQQ6Z_2^NI73nAfGMFAXlIFG&pA<_qrPZK?WFM-d1*L0y z+S2@A?7ekV9NW4F*aQt42oM|+2rj`1){q1b9^683I=E{?2<{%--GV!W;1Jw`Lu0`m z8ff}V<=lJjJ@3t3^Jcv@YyOxuf7I&LUAuPe>h9Y0?eF_ZZQKvfct9V5INO#Ezb>J) zSDSF5RA5_w@!`q>zGaHE=RHfSa!yfQ&jl7 zledl*{kXE!5k$8~{1N9Z6I zx$C+6b;SN~9W}+VK3s&lBb^>n>>_9TAu&wGM>Eo#H64HDGSs-+~CykjsTUu z6tnJY-LS*5_N8vC7f!6qweXK+k5w3^=ZPt$?~@!AJUu;?qajG2ya?*7~D4u!1d(4> z3ii^xIJqiVUtAVg+2v15YocNPSP@%jMeUEXh>8{vC(WJu3n2z^F9c}$o2Zbx;ENAhinO=D z?C%U^1+8&jK7qTGtmr*2PZl;W*0tdw>vJ{8YPUP6R9gS(y^`2mXc?XBE_`Xn@OV#9 zb=b)VjJNp6Sl4_y>0%zAoE>*YT!FXJ39SZUz zKwF?>2dpoFv>$$;My{xc3y7u{;7G(SK*bmIw zRR<4VzplsB=ul)lbC&Gh}j^@PULzo*rm z^&v;Zd6d^U#&?6oR&<3BgJ_AG5~h<8#}(@EJLP^u`k5m?D|QP5o+;5A=IXL$BgG## zUG`4mm_D;z^~Y-~whWvrP7 z+M_K0j8MVU@iKuFFNScfDTD-+`!kTEBz!8`!y+-Mcj9qBmThWktUEyrR;(zq7A2a` z6IS|Kxb+dE#E&r*I4?(n>@)FaotJ^?L+?JcWPU;L3UNT>l@J*+Pd54xEs9mhr4sIDQ=PxEH?&l9aCha$~ zs_piQLdjD-O`*kyt}{-qvESujtSGmYTWD`a`~j-t=@!q;A^-?T)O?B#UYiD`zURu$ zc6DWcfb3-=;$x$P#Oos&(_D%WEI7qdTLuQ!Dh9)tM$E%Llm`gZ_jlWX@^G3Rv0#8p z@-#mlzoCMb1FmMdCd1jPr!5n^GMSypz9s?>qv}b}#q6}54O2aY%sXV=FOTjgchgQL zo1W1pg)F>1*Avbgv${k=8AlaAFt3g{<|#&EiM!j|>YC0Vy;d)>p4m0z*|SoT0Im-N zRO6V+27*D*jXt~E-FtK={weprh50l8Q<%@fjLM`j+nbR27KcuhX|7 z51`j0s?!f`>PhSh)RhYWeaRk!Tc2#{@Tp)lA{gAVmc!2g#~6{Z zquv`$MPd}-E__J6bN%5@{8-faUA3>q*q&};Wo+RXv{?RWL*uKnmj~dItCIBuWi-d^ z_chG#$=>@(dr(J$0CBYMG9LFoJ6ZoR3Zq2RnU^ji?k?dr+}HQH+vJSVIA@2ia%#M& zT99=p6VU(O8n6hR1#

p7q^ddk06zv+?ZyIcmUB=g$$Brxq1iC*5W@3$y~0hb_&5 z;(m07#Hg6e4`3}G{?E%%{p(W7GG_So#3+>^%ksu}Ej2lg54+5I2jv(E_^$xe8vcDPK4R?VCkSH53SFEN`Q7@G{zTza&{;1sMof&N0n|0nS(w z)T{sP+tea2aUYhNbPiwTCi81USW52$uMrt@IpFT`=2|FZlqhhOidp9Q{ zu@+qc@&x6k5Hb=o#l3s1{11nmOm8P3Abwp2Z6`oR=$>r-0g8qg-ChHzNJ)|-FckoJ zi`iQ}215Bf(zX$A!Gc9Ainj}yEgWVoU&G8I^myNs^sD%kg;OKAQYye9i*T##-PAV0 zGiz6eWj@=m%=ZH-k|S=haFOl_*&3<*#k`UMGkrpRXuzc%KHQKpANdnfRmanyIUlry zisYZ_-xztIIZx6v+F!HS3?6DDH>fS3>Wma+Pr7mvtH_mO6LQ~C4gR)QG#6H|Hb%6Y zDie6j&Q)aEoFr{3@p&gg^E#wWE64iQZr*q%b5bMGl!($?sB1TD)3)xAO+9n_Sb6$g z8#iAB=`*x)%p%p)RHN4PcO8`XeUtZlHr_^GIv&B3*CUyF`nGS6WItfOz%Qg)i=rZHzCz)7seWYtk6N7YvRvojQ&zKJF^EVSFX8EI_nfpaq^CRgLXp<@&)1B@ms4ldFl z6XXhM;VGZXN2XC@dz}`8ixK;WEC`(OZPGBsZU7f(OOtnAhC=?@Wo*q#0=0k=Xt4X6 zB{Pm%BA#GNwg(n|8+}YL8iSKso9F)<+LA);=5*MrF>pznVP}=Wh1tP(nLnd!(nRp>n|9%`umF~usH9cZ#+LEh_X2NQdWkB4CT z1;PBWd1P7f0l07ho_ox5l69lU(9L4^0Awct@>4w^+5B{Jr_nv9Ei&UPXmBUi@a3r> zQa(5Yy#E`!#im3xXLZ1$y;U~fLHcWfCT}f=vBGoq3@23L!T#`(hSZS+D2i1qoD;!;Rhe zr02G8z}IL*Ae~%qQh%r9d1KQ`ehC;_l-!4psTY|H(nr>x@9n6{17sf1pGD%|h2lTA zIIQQ*DIWm7Q)~-sM5-Vmwc(VrSG(%id|nUaddumv>JdcFISr5eP3l31OCL{zN+bA$ zexbx#_i#4%6Um~Db*JMB4Y7|8#8v@Y$RpgD^7HOL%zM05gWD@h;t$Ivyh(v8aE+IJVT0BvLKf+uqt=Wpvi14C21XTuBvd5o1 z1%73+--cYDlEUOMIGlZfYLRB=C6Fg&-QLeXnOpi3QUFna$6me}Ubj$}BG#Iwda6zH zPxla#PMwy~%!R<3n>QY@>BVCAQXoe@AJ)|?4fw`Ejc)?f%m`TblxM{hVtDFFQe~RD zp5$k(Y9|P8V^~Y}>LZ6bfmE^%7)a`B0Q~XW!5eJQsGgp4@`!>vsq%5TJmqSoEVfq_wi3KnvznX&)WMn2~qx=OY) z=smV>^S{m?{jZiNSE z+K=I_@*2ZC?iZ$GZ=;dP1$sBzjK0D}LAAE?BD3y9=~{*2^4L^2}M zeUg+XTWlD={nR;dN+E9)5CJ4IZkcmqKn3~4b^pcTS&c&X^}m27Q~Jy^!wu1?H>PXXe3;OEPRZ1;7fiy{5*g( z_UC4to9BC!pC}qgN^QesIK~2p()Pm6+or}i{zh5(CJbr31C?pt7ob6H zBT6-2U(+%3*b`T8rCf? zn{&63HGC7Wn@Y7u(v#Yo#SDU=GwbUB<-tl5WB|~X`9X3o_=ahY_VOCYzT{1|GTt3t zf=8QH!^)qmZ%uJy=k86%0d9|CY(8xY*++Kp%v~{MM9va*lUuvd`bhKODYA1%M`U|7JACHGAYW8J00iltup10CT z#>~iao51$a-D3rwT&hx&Z6>O#%2W=hbW_UH0G%nbBx&r}ey_*8kHnM6lxi~jbG~s6MC~9LeW4r(U646UXE5$qVdSdRp$lOo#dZP#t zN3D1N3wrTkF4;X9DS>?Q2k0w1_{Ur^;_or{*)hOF8ldc^y+RMZog)>28}Z6R33rhg zZCR=(2g*Lyv32jIKWE=0fKVzEq{AGGvu^_*)F60^7xskl%5<8HsaPmYYSBTn4UnDr zX@?H6=G0-u#PT&Q9+~Qsyg)HUkL!R3e}F8FYKtAHKi7bK-kAc>*V%102zja-7R7_I z%*_ju?G9WZ@^4p0cEtme41YaC{-l>aCFGrM%aqH*HW`lX&|=}0F&o=P6&b-JTF1F#Z6HJ6HQqR5bBrr^^8#$p&aGZwLcd4zz5*V=kmI}C&UFLD+2kUtaUK1= zl?T)16?W95ECrqRRjp_ya{;NVr!xM|hm?lxbrT4}(!B=F_jYYjr&l|cAMnL^H7-j5 z9jNX^8oTXZ(DOqej|tU6FrV{r-CP0Kr_M4Y$^1Ort6S?z*tdcv*@>9w=c@AaA|R1_ za<~}0$D3+7UN>x@r%*R1idSM)y{BHTs=$ATyVG>pXL&mV-8LSI68SOSxwCMGL{`C7 zw=IqSItMGxK4$Q{j!&~JreP~E*#I;SzeY`OnF|sVg0leK8m`_nUFUUb= z7I^6M;=gki<_h(GnZMA+>+W{go8^`w8eo5QtB#P`XmU~Hqz21Oz^3RUUhuFbeIQT~ zVXhEUcs*4KPHK7b$wf^49v>&=t>CD4 zC$}7+Y-koz!9UC*g2^h{SJ2R$I=aV}rbEG!V}IImsY#9JN%5-%?Up9P$!wkSF7nmY ztrxhOAj!8wv$pOXdW%jE}eJE5*vbv#lU$tgm)&P#wcjbue5~Nt3#Y|~@4rdnkom~n?_ou+5XT)+36!dQ+}KOdx!%+2+%%Z!x=S)_z(S_u>La?{-c#q1#A<=$eq>hJ z&wgo`X=9;m2_CK9I)&`z`_}7M5s2~yzh_p%*XMVRXdsip5Z6VO6;;3-Nw)AOv=;dy0`v?CCw|!u~+$u>Z%XQy=%fzF|rJ9tD3_ z!_3F++VsM8s=@lNUa*d&zlv0QRS1rCgJ-AgfaT5}j>i^5RE(AHhfhP4pkwm=U5&oz zwOo5qxw5Rg0O*y=a<}1IvTbvH(lXtyM+={&P=5gWs^07KIl&tI z&$N_d0s{Kw8|BN0BZ$_W$k(eSaIzH`&R^BG%HkwG9d+cMtmFR@N9zAfC9GHi_3MbG zUbt+IW|a2m#PuRd8Jk9{LYe=TV=;G@E~r3?I05tzOpzSmkIWR*@lPC4T4j8Rxy4LQQv9pCbzrIWw~*Yh z99YZ^Nbew9!2mH7`@O}kXSrvYVaSFhvfuTpqG`uLrHFoUyX<%l!=09uBnYSP9OGqr<6TJ-|EcrSiJj zN7N{M$!z>+ev+AKQq3Cu<)N=#L`fc0Ys{DYqxzDtyU^!ZcY4Z`PV_hs-jB5pi67Us zMFzxS`0AU8&xFEkB3S&5qOzmeGH!$CnJk}5!z?$T{RXHsD)RibaTK>PVwBP;1?MaA~e4)gmlnsk2&YP4IM z$OY*}P0jOi6ResyWONsxi(jnFb&9OyaoWzqLYuG14LGJr#Is@5F4XGUGon)Bq3g|u z2fYcF*Nx}B+XohdvJ(VoYeaItxV7pMPD#oPUY8GB73b1HAjJt1lY%d0BwmPkch41o zEcJIieKs@AwjwLKHz*4NwKw*pI6u}6m`KpoMahveyi@Vdh$68UiSKo6oOB;np4^(@ z(xo4NE_Ol+t%VwQ+HoN`?W%O+*2L|5-j>+PWWnylSE zU4H4M=di6m-*5iZEE=9FNEL@E^l^t6WnL91XkQ*mQ&tgluWz7bEu0Cn{b*Jxe74V2 ziHYYw?VzVC)ldL2SJ$3aS4nSv_O4M|!m!&KDLRf3_?&~ff7Va<=Y;}ks9b1`1lW73 z^Xmb4CmysIR~Xb${20rmVg&X)qdePO6IMlnddH;EKL|(0vb?@nyDJ5Nq_Wf5>m1$sr&e zX-kAZZ;$GKAS+bKrJruKfFCjIsaRQNjQ-hyW2@&)946gq!~-n;-blsC@yV#QdQI&*xJFDqmAp<3?BC--74Zh=XJ?9t? zx@#Ano%ZFo{gv|3>?ZZr{cImenBU@opJ=ijZrOmV3n+^kHtyC528HS3=prxPa`qE$IVe_0MCUyw0bU zWHw43OITe42uOML1fS7EpeB|P6j-s^7AxBnwEg_uN`ZW$*#I4_y8iSItNOcAu*~Y< z4buEPEZt-M+^DK((-?B~q#+eQlw)fNK=6%wIP`nQ)z}lTk|o00QF~ldi>?|&6-Ud= z%S}Io*-oN14wF&hJWvuE^IWSC<Yw%ZA;LGZw|R62~4@}z5T1|MGb~i!_d6?%(w-{D!jz{f|<7JF$dc8 z72lVbwlBDMb#!g3*9>?y8rth8y(P{ThH8ohW7ZO1lHV_@GRfty+y``fUcfdq8fZ`A zV@3+3X{5|7)XU)3?YAo=2(`>53 zP1LFU8}jb%Ta5MRj;AN0E7T1WY4UTvV>S-YzY8uJFX?mVMbE3>ew_hfa93wHM%J4M*l4_du&|9eGz-h23!*hRB&vlVew6d>lw4F`4 zrg_?z(A{;i?@1=iz;o9m6hncQEj#;RcHN1-FVi^fcg@>Wea<4xFLN~yS`}PT+s*b@ z9?yE~ohtNPEug2gCgBXyNZ~)RPU`cxuAt(Aiz5Eu9_E^&x)N|%<{O7;+d4J`GW&fFe`kjLMZyOO% zhycxwo6QiNcGl#C$^3MDE<{#Y`Te}_p$SEo@rQ{o3|%}_hl7K+b1d1CC5oQiip^2W z4OGdB^CUArtyWkeLO&>aON-_==_u{(n_tpKDiD5i57%!R_k9Mp)0sWIslj2BK^Zh9 zMe!6p1`RMnbsM%YBgKCy0ko1BIefdOM}2)Z0N$@iDOm1aeP5 z$f!!bW|vOC>7&=w;fKs^fjAN?EmuLdOQ+%QU=I3Lwu3){{Z6C1XlV_$Tzgpv zI937m$1&1u>^hCC0{}S-o9>*SgP!*mKd2yq+zB5e-Ro)p`hY_lIoblq;BYA1XSe|B za=L!3lQY0kRlreD3j^ryZt5rDkbB*K&>0@z3GV~P+qwI)JjISH(LCo3xTs)(5{Vb5 zd>l>ve?zI}zd49&L`o2r=m-1(64OT3>wcla4}`JV5$qwKh8u90S&3J$C(YSWk}Vxb z49H@ly(i3U7CqJCOACN;Q7l7l)wsVlOhrbv_Y|wznp)uZN_Mff5?fHk`LI=+YO0l& z4tajc4uGrq`+-297a%HZ(AgorG8WW0==9@*;~sXbj-WGghGvf%$I_-vsGA*GKfj6M z*XH;&yyXPaxQhPyV-lO{WHe>2;i#RPx%`jnbTPTd)U=iZ2+v9XsB|A@)J&sCR+(($ z{LB|@1uZERdd~9YKZ=ve^=dYv6`w#R*#aZBRo74WQdSNrK5_^ax(Cc;-tz=rY0+9@a4<5 zC>{Z+&s+@fSCAenwvq=Ok%m@Jo0`xsX+2pRJoc8XkmM|lU^rQ>)t1$UmbWsLHC^5> z1Z3Sp49x3`tz8LwoHIxjRW}(PCF48_x#DPY6i-;i-R1dp`%KDp|M|h_^%F-f>6B4D zn(javzYOR38uHqz)!!FuXFoYd0vhisFpTfyYFwW|N zyQldy*AYhs5!Sl>hoSVk6cu9T{Y)?1={c;`d2tLB%B|)GcJ6EF#F&x%!K-I+8pNb` zJZn?1Br{1;A3icL4aByQ+KAX!HM9P0z1tku2p`A`^gdY=i zw65RVyNg+5!d9m5GY?JJsN!OLwE?<6uBXXLOKwg=83_1u@!&D5ls@pwcE)~z4)QQq zfD_qaj^PEyt?o_f#>DdR@GrjAD%fv^tslJ~u`jO%h<`CW!JVNqbyc zd(G+F=A1pf#MXB@^Sv%<<>{&FKJGs5Fwh47{+*AT;uQZFzTABoO?YudPxT_p^0SYu z>y8-OY@7J-US9pvq?Gbsg2F~YTf#|2K7@^73qt8+!?>jJbZ8o5FDqvVO~@iOFmwID zi6|u6iBg)j`OIkdK9;D7O<#q5o7d8wGfLIUW%HO6D+s9g)Q0V|aF0o*0z7gcgbxFJ z;QnU4ZTk9AwwNnWTlfo`12F9Wh0R&xSF}Et{(3UJ03KLir!iIHiNp5{J4Oma2cOP# zt^jCvX%3IzFz6=9di33cu6sx{ITM9d<#xiQMVX~aWlCZ1Gd-;AW{of9HnHUI31|XR ze?}dVo6b|Eh=1AFroo!Fy;R1Nwp%|7Lm_gA90GyPb!QhmKCOw!Vi|s+h77i|#>QvH z8MLI`4gPZK09Om%n&b|daQAOJAhdT#b}|Y60O^!Nf3iaFG1_rpcuQBQCiQiUY7+;> zV?zY$y&lKF1T+hwy}|~{mXhVaycK5f^+>8*C?moBS{Mtnvuhp6AF!J1b-vN4ouOco z{DAlDbkR@?;iR=otV@ILVb0WLHM4wGM0)Q2F0}aWMY5CPGldIm`3rH~EDxUF4ZVXk z+tFIhQ5Xe?a-$z^6IA%`OLsCfSSwQqMF_fo?V?X=mR2eDHLg1ogJNIY3+jc95)xk}=X_#~ zp*zByZNr@;VOV`;_j>xf5_eR2YWLfzr>&u|hS=w{E{JW>dsfP0e5;sGCSj6Ye}IxI zb}vg{GY6VJr}KNy{RfO{A4kvTcFg7_DlLkvy(EV?zU-fEvnD<@oLW(9{Bcks3^qMo zr8QmEj*~O7n!dd2YaS+1e?m6qx!dMM90ws4nCLqeUIcy6VE-1U^g^sGgF-qNUpmX3 zpdLWK1^QHooUvVrvUtBWgXIpjieHIaf2yEnQzd6oZo6g#o_ya+XJSY$X}{aBDFDs& z@@20`tJnv|=-VVy(j3Sc?%Ddi*^Jj7BE-;Aky$WE_?g~_7p1FZ%L#F`_3|tNLJ;K5 zWn=MM&PIoU2QgeSkK9$c!kzCLv)<~N%+Pl1O2&wvz8Z91=0f_9upB4nIAMK&PU@p0x`%ettf?03EE~e3`?O%AE=^ICIh2K4FUiR( zwP3iO2KPV2nI`gEx%b_k5Q%EZXZH<#bBO8}+wX|7Avo~NC#ZybQN-DVhBc;A(dI*JDyM|r?!-l^G5hId1lU6g5Lr2)4JMO%{s=e4`(A8~SG(5kCz z+q6cHT@>l8>WvPvcjDJ2*6F~)tUkvZ3pQY$UW(4eMfFM-bfuqt!YPs+ zr#e(|CrOk*cl8CV*kfI}ZV#V3B+k1#AD!%>@5MLSeFW&~S|_IZ;tZav{-UZF$?Me+ z=ZHnK4}m_w3}@J41Xlv=mC_TpS7@h>EvAP1arnGOCzZggv&g|#4fZQI>V375&}8$h zEA%8C@Kt&Vz@k3Gx{)4(hMt@@3Xd2x=_@JuI-D`{2u8zEeu4kpXhRvfnYc4_$_-4U zWVi8391kMud+6M5B1us@fj(A&-3gs1X}f=bmg3rO%o^MtQk@QrOsIx3o%HGk_38O} z7wd0SN*e8ivHJl9qIJQkKS0gTY5#ddQ;GBN7ZWQQD%Obj*6i|&rbcKhpT)0f$851D z$j3e+cX4XKykJ)Zb(B9}9;dyr&PpjgQ!2X_x63IS3O1SS{IkDSrY*e|`~uR_>ZNa3 zuePLp%6b&9DA7PZBc40m7sl)RjK-gij^`Sb@C<~IXMaY#D`Ds)7dwC^;&0on|NVxo zE2;1=NX(x)EKdva`Tpt>CA`ei#*I63x;VDutPylKt96B+1H|gd$Xk-RiMRN#?=V$> z5FVKA05#gLE(AB5o!8@)9bur&f4$55Ta*1?+5i6`|Nh2Wi{PG88D{OQBucMXMt$qY zC&vLf0JY!9N7OOEFy-F?h`nb+fLocRI7RA$!aI$LH8rLt?NN^dNE;mZ+cE?Lh%-;x zd$Rg1Byd;6*ablk9@^bQg8zvg-hJP3T2bF-|GIdWjmnx(CXE1uOR%M@D^Lq_zkF_E zeXN{01u=V?O4qXyye1E-B9T-8k)ALXEQrZaT77S@s&@TwZLxU znyZn{8JKTslbk1WR$13&4PR$o_QS#Vwm_BVeaRo73yOv4zIIifpE;#VI(qKgCQ!g< zwX`9{l*9$g?X$SrSw~Rw@sm=52ky>N6w+DNoeQxMtkK*;sFN)jatK8TjO!5mP`RK^ zP}e12>3rnl4hzL6?xzEEvw|Vc97d`q9f3ts#Db|AO&x75L9>>d%z?3u#!6!DBo{^G z<8U_F1~djHWU=1HOQs^D1gfXtF;&;E2K%FBK2Ool0!{o#=Z5O+K3wT38>uZ_=4 z$aNkL4-ov21^bbV!PSuxbK1wkNH9y4>WQOO@)aX#{R3I8>*h7EAtc~>qHZl}S02SFmMwM?EW5Z|LDMfnlpoe^O9W60d;}zegIX2sL zaGOOrdC$4Yy6&Z19U20+#loyeVGpTndrWYT!iNgymF&CG(4ICY?bQL7qonESgG_*Z8 zY#fD*sS*djusx*1ve1*;O)k~bWi0%{juQT1QS+4JaFe3+;SXtZR+S@4ZJKtrp(F6d zp55)Q)gNI(AndP2CWYTPCAvlZbGi|J#5cSP&>KTWf)C?cB9H6Gb!d^LW zj;m%OBnD?pwK~v96>D9`jO?uLpzXD|A`lsFPTpCKI3p+!f$c>70jl>#5eu2>F?1df zyh-W9_x#Yz6%0LNiN3vwzg6>o13a7FL+8w@DEBpd>kp0#Mvu)1Oh#-z0^DZ&rxO;Z zpO```@RoyPpIZ72E=MO^Qtwy7({kX_VC*jF+M(z?fBR5D|Cb`CU^0Co<=6U+-PBxn zMtz~ywt4j!E1FzPN|;LZv))=$wB1O``i6jab!|as8$9gV>;)K-qe|$WBg0t(8*+{} znX+s%e6*Nyuy82aea-i68!BC;WZv&sSZ;AIsiGVVwG0ET3YQ?`aC+$gH7^twGjUUV z3H_HZ=?HgqA6f0LV*khmjAv2>vV%lk8ZI8=ouix)^iMW-lI&{T3i>0stx6XZEbJ)` zBh)G>(dRHp1hUrChA%t&I)y1kgICBr3as>gwB2Nc({{9v zfE;HIvT#gK;^1PKp@EI5wr2gQw zT5apWYiechIogsjI|qA)`iQ>IvF3(HPtSLKn9RcflI86b-m8S?MZqkZu#@$3{Sxs937 zJGVlPCu5?Xz;vb-Rlf>LkJa91W%&8Giq3)8EzS@|dCla#7qqwBkX(3%8~Ra^F-JKb z8q}h%PqB#Z%t5~)RMd5aZpxO)KK8X6Zd5<~op2oVsgaxvT=hbRp@Y#A^Qu1p@e;=2 ztY@(QNiUDTzW5fO@7`*BWjM= z)RdU|nIFS2T8iaVy%-|TCD|;cHbdqD$#%9csKg_O3qmkH|Qz5s}@VcZ_8BnXE?|t5(ZGH|TJ@W$+eq;Pu{<$acJRjqz}%?8FRnCbBXG#;?)Lj z5k1Y!X*NS<(Ro$1I57ddUL1&&tE4Kd)~%+Jd6tp|W}?1_F<0jPiG%nH5AnZv{lBeP z!NQE?)^Cc z?Oe~`e&rhm;l{gh08rXn#dRu!2=L|yA}9suzP|SAy7veRLgp*ng~Me0V{eQ^A=a=B z@@gU-$zRGAexlJApJ%DMm|?i0!|*`b;O3_+l`l!PVA#d919fxKk@~e7*5HUcshdEe z_G_3K7kMdv1kw`CCnIFw*wAWi3=W@x9*_&3RYvy;Z*_(|AUK;1t-3D zcV1i)&*sR1KpFdV+-wJZ@_)L zU`t|}US8jzIWEVx^uslK*=0YUl1|(<=2_oov$VapOkZXxj59du$!e3BwuHp9X&}F7 z>*^Qf0AT3clH)>t%TH}PK0Fzf=_BVah~CVdQHZ5eysT--=XUp<(}@1QLLG$@Y?(;<^GFR$lh9&bms(kXm)IFphr%#Y_oVSX=DwkU zobjH>&|CFy=lhHng^ecE<0;N}KUfA{Nuw(kyC==5HCoy_4+lw8V^MoiOxI=hYc+I) zZM>RX^Adp@6WBd8SnD8AUnLGLk@A2oj*xbD>pprxE-(6(_6yyZ5PxvZcPA%-vSCBnrCV9%P^rN4e5N>z8`ta1%_39EwE_l_ z=ywbB7FV*Ds{?Q7xe{18cog({tY@GYPp>7td9mm{Kcpugj%aR)4E4f4#<(3G&Zd>@jqmEFUun^hp6tuv*gWTu!@MjB;`}Vo>=?1t9C^~& z1Ayf^(O%oYyrzRy&NnU87)BqGfth0u^+wNr6@`!#G=?!MDB$S1M>sS^3HhnWZ?37`_EDy#B^yc9 zE9mY-V07K+Vg7_QUi<+EAFY%yI5lYi1NW-)=m)n@$y*!m}O^*}xp33M>cL zmFUmy9rY(#>qhq~5{*LI<#EdNEZyTQ>LZxR`}LhGnRHJD%3!p$k%k9K906Dfti^BB zGchZCfJMNS%n4_9W$}=PJH6QccelUB|FL@7$O&vgKT;zmvt!tGGTb)-x9i%)`AJzZ z$CDoV>YApnM)0r3&bsO>6VL8{yuKd$CV8k0b8s$@%74c)C_4`g{VI@hWpofUdT@L` zM=iJ8&>Vg*$xq%h(Z6+D>11G*qYRhgCs^u5c7WGt5>uMTc_Z|}Kp zHG)oA>$-Y#$i^u9owDS6GexP9h51wEWk?7H=4EG8-Y-WVaj?DfA09V8WD5LGb=YH6{ zayOctfpzpSBVujKVf%*dGb64MwpKf|9qL;Z3`LR>m;o`|t(PJwYASRj;gB$fa~Xad zHItkQVy?{kMuTTZ?VfG9>)BxX?cAeK><^F|l?nZ9>o)vxK^_T|W;bleUQz>%_U_0} z)H>_}(Cwzl>h7ROHkhn$6|){)@^^d>BI}~F_$0X}v~TEzo;Wj<)KH&khKbhy_yuiD zHWqVPu-vqaf%q{Xi?@nkZBtPY&D19pt-9|~>pvq#p(b&WW{!@)k+7gu8JOb?( zW(wvEtVbNok)ics+nQnKhy|aQXTkM+fwFPY*xd;jUfQRzD>XkzU3WrO8mk^CFm)!9 z$_6Y%0~^=JZoPp}5f$KEFYn)2j6B?6!f*d6^(t)t5)kfyZr zU&d~(kQ>dpO?Lm~ z?SHbm{}6rtRJ4&S@jmS?YBJ2aWgzTVS7MMPCS90|t^J?LzyBu0{6A3W{&mQ64q}vb zBt5XYP6Pf(Rmn(~6kXrHy>)hXU7&3DT;@#nW^2(>K1NgfiEs$Jx#6@Z2%?Rgi zC6g~P?wKbuZ8i!2RznHI3Rm!CsoS>FyC4y}n5mNYBIm3=_x)r;AU2zm)>K_PtJMKw zu`IkgvOxax+ciJ;K_Sr%YOC6xyTbabrqi3PNxKr~9iyt6MA8leBESkUSh2{QDpKsN z{zU3e83m;NwMMVGBWj6?XNbsng>Y0za z)=Z1sQb9(^3pK&bH>~r#jpG4JS9B5GMF}-kd|K`jiNGy+&H|8&j)hSn({1{NK`=YX zg$^xVeZz%rhEjWlxCfH%M|zNjdDZ)e<&cwIsPos{!wu*wAEGT9IjF2m#GnJg?m!py z>lMcPrWgkjOUE9AE4CNlCM9sbQSIk_quNjx<3zzBTC$%zgE>~DDRaA9zO~3vUGXeZ zYw!VU?L@9bt`U&n7-j_)UynncG)hi`LpAafG$Z)VMRQ`xdO`kz(LU?i=Q>%**; ztCao7hI{KW|Hpu%eCp4m?OfJ-!LPx{Q0uvx34wbF_c@(*ye7JSq~%ZTYUMNRDZl4l z_1!qOHefu#M<=ce3tViq=6dz-$Ue1$=&wX*qn$*z1{OY8Mmjz8U~~PQI`>_QlT=LB zJM}UvChJ_$&EW>X;Kw5kjn-oXR&XG{304q*NdcEev&Ym#2DinD5THNSw_7G~Z(wJV z!1Gu^RPjgBa1Y<3zEz6J@ylpA*n2B+9*2UAa#Yd|FJnx)kk_7GCT2}r&FQ9c@oQ5H zw2l6eXMusY+De9;@pDfcLp#d6RIalGb5)poKiggx>{vbR-6p?V@i{9Jz|rlvme3V5 zAeis|1FA7MdH$v=zP^y9sV(f8foefRP0D~-tjk68;G%YxrvSQS8J=wZC?HKLI_&*p z&=_!l-bXEnE!L5N#UX~8C^r|;a4Oe4l$UKI)i8!`NzE!n{>F-gL$3{V6(V_<2YW%Mm z36_i2didltT0e6d(DuC0ql+OsUi&cajg~nbFBzFDyCx=~e5aPzoGissC$C>LDnc!d zo}S5$<_cHVHfJ54xCLJzVQu+3`)Wpes>S^U3JwL*0-thPw9KDA-t@EiaxTz12#H1P zXCYNs;|n0}Ko1)r1xEM=x9J9G;VbhM^C(m`UNH$c(Wywn^&JX)XPt^$UuvDW@)q%0 ze6*otg&V_#)?yOe2qaGsjX$99+(U%L4Nu$2Ipj1hOXN};4I+k=NyMb9UOI;}Tm$ps6t@IK=I$m$}g>eFV{ zBC+*~7S&{!x|*Xyt`Sn6@Ag2+4Lf7XCa$8=%HYT!59xqy5*0sT1jna-~0b=3}# zYe%~v3c`zap%nY>!}ewmvyE}35L#9BvO;R*OSqr7(v#bIDZL^jqz^s_!1F!LbQp|d z3h4v)G$*Ww@MI>2Tjsg8(r?rj#1nGa9aTXZkg9S3HlS}dx?3wvitQptKhi2?^srp8 zw^ls@JmSt1QNTTXS^+M7jo^RlD!Y#DL>f-q7iwF#`OqTsiNd!`F&1kS9lBkmL%DOlJBe__buNUY|ssvbXS;RG`{AeS{6^ z{n{a!JMm-8mwP@r7~-i%YmxAN9~=r^Q#oB%@>}Qf9v2vl+;dT5A*HssU z+7-pJ^bv#AK_;P{s2#mD(5pKbNUC-}W_7bnU;`nwnzujZHul&De_1c`Oc|Lx7GO#N z8uZUM6=)nbUfN}!#bjxy8b?wx)6dqF4!AALXem0Q z9A(}yy~Ns534XHD(-q~egBi(_uc48z&)gcXoIenlE`&x){O=J0v#PJO8A)T|l~ z&7J}2ljzK#1!C%otWu^bRWmbBs%K~YRJdM;(%sH&rzyISF(D)5Bic2Crw}TnnuQfk z-PgLhahV@PEz%3ERd)zB8q z&=8ed`+`FV@7<$4gUseL^@~m#&}l~77nqoE*5MECjrrTU)wo=9{7v;_s zd|w6V!AzX;x6dvv~*yr zw&%#5756?fbQA7{P!FT`Uf+4%6jLV5$>KRW%{1EK^<>hWUN>_?3#`@ikJ?#0;!X%n zcXqH&T;AY8PNCr~pP)UnO<7-D%W0J(zgslaB@WTK&CxEKe9+zgk>@K7Xe})bhB|kjGOJS67_A8A5a;%#T=q<7qVDM^|feCz7&%hDEDc2e6oWF;6 zq?uccg%o=D^2Xj}Tm=!t#&XLtZ462@;$hUvLVqn<<564{B3)B7wr7-l zKh>-|cxkEX^R`fgRNcU1^%q{*c(2=99YXxc#>!h5*B)IpoN#IBMXsTJZC-U_d)$98 zN(>HaWq_v`oEanqj|Qp(#?`m=@-vFa{PvyaASlD>NjH=fZlV;cGU-NaqZq=Vv`*k< zGDbM&qZPc;3#K;E?Z>+Q`r?F)2dAkNa7!mbTim6n%P2vrpJfHXARKxs#$NtI-O>we zRIB$O#wDA`Q=^Wb>Idt_d%DxnU0Oo?qz&KKKT$=529(L;9*epUdmX{C9@Z6a z(94>dSnAt;kui4#^=X7dU93*^7gr91Qd${XF#$b{B1_^1jL$dNqf-%}sJ&M)#pqU45-ZgRhY6nDwIg%X}AbmI|w zHoqmI=tiXJA6x#2lBc>}ifMZtBo9wozsGEUUi;H|UCgqFG5mB5D|=L0idNRZGqT&C zY#d0a?F#zWag0qdxGo1(Dy31Ep^0$3fkvapO2t-fxPs-7PF?1oy%F|;>?G$a1C-?` zlk?z%fEP|Dh8BSPQc7>uB@N{6JZtSklShoWQr`ZocXCFls)LIUeezZuvbyS6`$slj zj;}JsJO{v~( zlf`YIY#KbcF^a$g-`}d9RzSK8IcHjQ+;Do@yzRGwh2*QevYV;%J;xl9Vu-44;o|+zN zSxhNhys7a=7q2@@HRjp}W?v#W3&&5mTBJ+b^R0F5(v6RhMLV@$UY$0s3J-QZy~3>I zI^?!LksP$b9u-o=CR>^;M)*uRj*A>Po9G_(SP$Erqv8!C+KMbwW0E78uWA%1GfL^` z$Ffug6h~nc?x98d14o~%&vU5wH#vg#8shkmloPbK>hgW8ebbQxOD8{MBIcW_lLtGw zsFxZ;)_ATf-8#{>K7(j*aGc8#&~vVfKxb*)wNg{8TT=?Yy2nYZhwz1KtCNFykES$E}b#i%sCxmcgXl9WFn{ZZ5x zn>=V)E>Z-+c%E)?Hw-MBLja07w)MZZkf13mvI98S|E^)i2Feqt4f#KGn*4p6IJgUP z&TnmWb^Zr5k~8iw`(}pgIM3iLmpI-}El}(Jaj~z$9}uHZJ|Mi!18Bxk3_-IJt?epy zf?2JWC}zDeu4>l}B-x={-;O_T&tZp9x1KCXW?u^0sOhB{VK3-ezd3Nd2{DV%V(zd- zXL8?}sruO52pgTNU=Ee=t>;XQUdk90BQcq(>KC}pNvyn0c-vFZiZY6*$a^Vfj)k>A zTvKLXLtw4yQm~LeoiXVZr%avNALrFhNBhl{4x!C3G}2YYl$n>BK-nDWX7<^OLF=xa zD!{5Fwe5w*%Fy0(hZBu1{)PQSS?Yzkv=5OShtXAy?*lfVSYxTCF7Q;&!tR`f7ErU| zwRI$o*fAq*xr>CVIARLw;ljkg&duyOo5P=gwWd((Z*mUpm5A)V zl4XF7>z*rA6*Boe0-=LGdOu;eEMfZ#0MdA!O`?==%TbqLfH5(M1j@X0|3M{+d|m!Q zwZBls*Hd-Lg`0n%Pu3KDj_xe~!PG*6^Is~L`GC_Z;9h=Uv|vaRqRQ62S<*RMF^vw+ zcNN?cg~Yn~iS}?>ic63wj&Z+oj#@QgU9JVxn3$-?^6m3 zwZe^iY1jLgOYvDlv4doXs^n0~QwyZ8b=&pRv|Fu;stqn}Egcg(LRG4-Uy4E;x+Hf*~$4F0CESh#Azr=CP0P@P;k6b{j5SDyROv`HApbG zH711plq%{P%K3HMg7L2RcD5Kv6rvmnA(VYUnxHIElv~V1!?_F8sh=1|ZN+xQgzL$m zhC(h-_>tYUNfA9eYO9q83*{ue(k)Ff%d?%r>dN#T4EwB1sP|^I(XMd$UPV+#%f-j< zTOPMgeZSCC?Spe|n%*|r_;H7NG05CU+kTG@^s<$(o~a0{lF_H8pvIV!#dL3p4~>z#)&uclzlMy3WRofB)V z1_=-Dq9LYBN}XcGVx_anA21R-C;^nh;jDWP)oqUKQeC}=(?{fC?+NLd($R)rNZbJ? zOmSQ{_s$MG`WWus%g{nOde_bW8IWa_ zLJ`~G3>PC(@W#y>z->bn*=+|`ct6=aJ#(<&cK`csBKYJ)|E3!d@+}<}KAh|p`n@8l zA6PXCvw9PL?D!x#A!0EgpW2FDLG6tK=Xy@_x3HarOUNA9z~(Kz zzK4=IW$=2GJUiqd6~dAB<}}Tkg26h4qBX5huU||m%Qn7KjIICIdr8=3-v-;@I+wAX z4CkI3WoXkEe5!7gDOLpz2R!zJf!xWgdb&Z=qj|eOAYQdGiwS@uSUyrQqtGR)C>N!4 zoy(M|242E4_wXl!eyW-lM_+6Ea&3&7@6>M5v|+a|J8Btv`~Dlj2+<{DD(FlPf`34g zB1}p$AKj&)U$>WGgekjkRo8S~YGTLrGaq@{$!i{ue@d0vh?wysLi2JPRuRZ8V7~0= ztC+N>-0Ur2x0n@FPJ47%!Bdbh^PDI=jiX^NP?KGXHG3Fjxd;!{Zn1H1nzCmW8g3;x z$>OStieNsYsS)}?eA$%Lxg?Ws@~v$s;0iS3q>iZwPNLKsLusPrv@*;Ps{2X1Q3ks2 z;uox35L4I4wS`?p0;;KzcJk}&6?(1{oU46)Di(GxdjJNhKUHJxBvPf&V84?5FuOrJ zlPj%0d;f*^*hBaE>rx8`0h0O)Iik(lqS%1VE0)xznY<>oNs{YNrt&zgCvg{J}YLfUe8$ygj7ls!{81PobvVWD9Sb?w)LHt{Bs+o%C38vD)E*pAAITvjw zfJai8jl14L-_Vgil=96^f4VsV7=L&M>D5gdH`T+09|j5z9!7hPveee%$ougjHsp-B z6^|>{30_A*wi0sG zW0b@bmm|*dV@my=yK-3WfY%6s^f{{(dUp*IYztg%TH4gtuUl?>)HW2clv8*B^9?;* zH)-peu#+Cg=5u-X0PJC)jv8yNn>sPGjyM+6V>8Y4(zA7vZ~h*ejb09t zm9x~})rDnjYSrtSZ3+`o$r1i)2S_`vCRrUBZfi&81LhGY%FV$ujJ(>xp?#wDV-|_? z0sNN5s9u*%S>d^@^9rgw)yj2wtcU1}+Wu zqqqm6enm~K6Hu;I5e6MPGed8{gH>k(2D0xqDOj+&PB3T}IM-L$-ZKA9WEy2cGu15M zfWTUWtO8Pty7jfpp@UU6-$=~#Kr)r1V#9{8>PaqpmXyN~)fa$@NH9$&al1A_@n}-b zuA`U53>!y;@a-Q^yNI9h$nu1Zb}ep|z6{f&qlEPMsGB{bcb?crldgC{t+Wl(+zG^Y zWb;3D?vuPzZznbDVAy6Xxx8VrxTDMpBRfvw-ncfqc)_iB6BehLi52=?vwXu3YI#RI zn44k(04qEVy^`uwn1n9^(k{XrTqv)yPTef$tBP#(zNO$j$b4}|Ng0c`ca881_yf{r z$;Q3?`RfooqVhKUj6`TqDQ5uOg)l0Z*YFryF8zXk^#bTHKfF9n)>RkK*)jPD#RqFfYs0t6>HP=&Z zEC{}?ZTTB0$`=EHVgf)7GOw}OWB>gc8Ytg^4)CEQ3bUZ37FN!wtGj_3%ksJKVA>q{EW{@G(TLAkpha(Y&jwh zDqLB#^8O;6>`-l~=bYI)g};d3P7_kGa1d$Z<7r$K_S+CrUggfrn;u1z9W(~0Dcez0 zxjPI)+9%ImT7;%2lxVb(|`=?PxBwKc_F>m<;tGb3j6!JJQy z$~2>q>?Lc0s=Dg=dUaqsW=%2Ed`;uH3_+B^bj8Bm@E;Hrr0=8zGV8F*zKmg)$rTt; zY8T=H3z5DbJhc*}eP-2EkSln!9QnP#ZbWPE7wg{p+Iw>xenUW!rxKeWm%iRgX=Ibb z-~Q);UbogxYf78OcbVJ{A5v0(J=f)#V@8|o&){m;@yvBR)K8t$8)U%WUyLC;K$A!) z1%wPOS1uod;UqvBrZRCA=DGo)oO^t9Vsf6!$gW=6@}d(jJD;4HX^Z<0DCLK9!IIDq zOqgn+e3lE_14Z;iJrvK7@U@UL;m+LNsq71I$DOnG=_1zJo5(JbIL!Qs#eQ zPX0e-MgEnvIzJ)t1Zz+%b#DbX8|W>*OuX@}CY-{*D&v96yFn3{`T+Nn_^1}v{hW%K zb8#b?fWV`19ef&fV04My2;9JbTazpRLS(kV=>3`DlAP+)r=`RzksEOZ6n=&cD$oOb z(@p!|FXvn+%H4l)+_~>`>=}z>6rH_)a11$#0I!kHwC$1t_oJ_Ny_y0rM(EVW;u-C~ z=76yX%z+5f!Cwv;bHdEimgJKdjp3D45H`{kDlZUmPnjp$cl*a+(vAbg09b$^gbs!M{4` zas|}iVP*L`137~NAn6Dwmq+W~Hmksc*M}K;#JIo)O(FC2bt3hqbeH6NMk+|TuLf|* z{rPpa&G7B;*VQ|WL&O_uaQm5?9s z8bJJB$9#TH5j!m^YfGe^&b>IJA?4%+GU|#u#%Kr%h+z)Rh(gG0i7%PCGMI>uS4)rT zGwvgR@KIuqJd z`V-LWQpaqSD^Tj;i7$nnfOa#fUO|k+ahkuzK3WCen){H?Cc5rO`d+gVL0)E;ag>_8 z4R44!{ zPM1qCRla^h#Gd8sK27D6y#v-XlTRNI?IIW^NH;vYY0I{N=eCbSr8C2?{)No%fawg~g#Bd}Xo+j< z%M3d>j7HgWOXW-NR{BTpj}hzskU1J}zr?3imERQ%axu%SQ=t(&zD}i9O$uRU0;PKR zWQxb1b5?Us+t`Oqo~OP__GdwLOr^d1Vj1dFi^)(pYWPBFl&EQ_NdQ6stQkkcYPDA^ zjQDyk+!s}zt5NST%a@yrrPqRIF$RQ+n$TGGO!O1DBX$b&#iXZvHJG;(ok~0tRa>ju zm}v&Y$sNaE-iC}vnatGiL}Z1m_AGpb`ySbUr?nLkqz&F4+nlP!Hz^hD`LXSfm|7ry zd{;O^E55NOMPmv?My-XnfZ{Lvq__Zr>;5KEpmvHeVeM1>tq0$;Mu#`JHiKy=!c%_} z_Si2%b>6L!MRWVQu!1z=pB)3y{3SKX`m`;bff3)0QkFP`T65q7cbz08P4`)$YZUq( z$y%S;9whNq4=CfuO22PD`m2By9z@k2V?iB^#@p*AgZXVyvAC} zt*P^eWYI3apNx+|Ha`MsLPaNH#u-woj{qKN`}ZRqWkF-4#}gAgOZm`mJ{kE({0c48 zOEUv6+OdX)95J*3$(^3PqvKrOfeg(VXlRSnHsWj4{T^xC#@AS9BxDIKFi zMop4m)p?d^U+W?my$6c z1@Ulq)%EYIKXB*OG*6kmTX&xqZ@A-D)1x|95$>E^f?ISxTktF#s=u=@ikGu z&av9k$ZRD-)nQw6beoQTR-=r4bMbQv)87)MXu3k*!V*#VH>u=wr#i~3w`3W=BrRzg z69?~YNR2}L^xB)`Rwo4Y<~ApmQupVb8KRPnJ=mx=4h-!Y8*gJ&4ZSD7Oq3kzm}2iz z1>U~Hg2EGggj>#D?^PSH7P8ckwv(kTJyPkr+b8j zyA<+MRn_&gwv9|*X?MilGE36_Z4*Jk&I`jtt+K9;0GbWVPy63xh(Dl%aY(t38eHv+ zIL(b|#r-c0Q!P%NFhch==(eUCUtE%F+9dvUWphfpnKyE_msu9 zp;K$lWyqQ~TpQ&J+}*zbz?}m8zZ}-sco@z0f&c$D{J*byVdv>&N99lgccy;vL(Y*y zyeYzA+BsM=^k9?rfQ0bY?1txp3;skn@>i;QU%pbPBi2}gG&0&%bNXEgvD6bx5PEi@ zcH^V-Za|&DY(p?InOCK!+?F#R_%7vNU^+b$aPAURI`Z=dmh`(i3uS>gQG(*S>W zm^ie=X4ua0BkaAoA$eNWC9y1ufb#@l0R*Cx=%qQ0s&GYU+g{fF1>l>cy>dBc!g73BgffQtsqI7s1@KO_y#FGlkaed4ZAxuEW7L?L7r&>M28yuhTjUz3;E1+8gwt z?OLSXIu4KKxH+u)r$SO;bO1+Zz-s35=Z4|O_NrZ%O+k*IZF&e?XJ`-cHV8 z5aE8+GQ)7D;WK!#B<1GzrAVJXWj6KTfY#vjI-|UcQawEXJVXsORJPCqVE<1ARFeWS z+Q$=eqvJbbZ+`!(Hq6kcQXgvAsAs$-w* zNjOH!LSO%{BmHBS8_leIkiiAvT}NH5ohVlDm5N%O)hTU{7HYTb9!s7g9SSIvkdSP+ zbq)7m-6%BX8qBo8SQPCh`zq@x?bfJ6i*E#5jB^^d&QZ+-OP6x@%H1icQR?m6Oj;vO zTRBljhx{{*b7`)5LGf>LYQAm>dx=Fe)d{$AQK5-W$>cpov?||6)_q4M*1#=~SZSR)zTQx7)sTWrWdWTx`@~;bHn7Bv z>w(-y1h@mU^c?#BGTJmXqxQhSBj9s@az=Yr)(0yM%g1Gmid$$LEw@mUqUJ%e+_YUB z*a1)Gq6i~bZm;T*z}wVJAHW0K))=Pf;H457@!amL^A~-PJphC6E^i}+^mX&xyQpq`NV<~1rOOp~f5fspVIaQ* zQx!f0Dhhs^akLI~K4TbEQhY?h-<3 zoywAWO_F7jJfqaIK|P)45&-X!Uv=tsT`>jZ}BbL>Fc;k>UJKeu$x);sS&4dpXRgNC?47u-bgJkW%4 z{;#3mWaP|VtJ=@^w)!;F*AoJ%rQxB_w0K?{f}DlJ9K1@oEia#X6Z55?UL))#@W=|8 zyQ8&%=|@pLYosF7hY^7+SXtWy)Rd(N=k`gPd}@9hjM@&p=plcSAc4y< z36IoG5KKj`)!y0LeSm68b0Qn=0Q&r9}`o->XiB6?B3Cjsb%+2K|g{?E7M zRZdSfNskiNG*t(6kwA;A*ch9o)6%3@?(-{jSB+l+tJpF?(VlW|Wq?&TDMuP;k!{Jw z{St<2jpR#YMO~)#`@R^ftBvtcY9Ito6*p0ih=H+nTKHc08uIyZ&Q5KGe?_4Xy`J9(Gx)6d7>9F z6+83|(YM0yU(kZLu@izDy^%DXEmb#P;vhoxSUUs>2SJ_qPrF1IF6|$d&%CdNf5ssvdraW9ex_L=R-OVg5Tl3wIP+u6f^KqZD_EI zmvbX*hPcUoR^2iP@?2lu>8XeMP^WvF^*06`3AwXV{a_};RYXf8!@^n)c`i}-7_Jg&#LzavOi^{eX#zapmjbHXow3fpGsEMht6UZ-iVcl#E{oR-3vjFvi zj_AvovXT_7sINTy=Q{rS!jiC5v#4K2)G(&WJ3}pXX=BB`^wlSuZEH53{{n9MAsy97 zARJ+w0T!4~kAW^={troal6YM0y?7Xhxz$T7POsHlcZ>iskzUWr<%=bMWfXvw&79TW zKNbFqjt9G>zWwf0ZhhTk7pLLmMi=p-7gV)3Y!~}rso!yC22mF&(Z{TX(e~clcEfTJ zG~&0v|8B5YIoUD7KN1=2MFRfEOk&}>%K+j2N65js(P^0&7v}jvSNv{5;hX~ngg*JB zLh^D*%?CSUJd=nC5%H%PNg_9MZnszh%^4m@E(c1;Sf|@9&)*C4-%};-Q`5eBN{d9q zq8_yMz06-c0M_mQ{^`u z{d#7bjb>fR-jppYjIS#W&wAv8{zI!fg}36(%Y(?z=fCHG>sh|xfFQH~%X512&ujA? zfEGC*V{>b5NE`@CSf`0L_(bqP?5^4Ci0i2K4~Sk}a7l2k6v{h<7o zy?dem$vHrX`{&nFT!!NDoS!&i5uHj5e#tu&(bqW^1>v@d$f@;m$0-#BzJ_1#T$CHH zV}q}{&v=3_?+qBwTW24+$G-f%^k~#6ededr$`il zZH_H$-GDxBZMKg8ci8h^S<#HwJKzi8N`5cm0JihnM*zG#3;e>zqNU$F07k=XiKMbU zb}V_!I;Jhs_6*5!_Lx*Ba*&Z8S?sYg?D#RzDBxe}621IN ztz`mj|2=US(n-HJgeN3vHI~5U`h}ObiHZ}XP&z*FS(G#A?#K5JM@Om4r&^ITiEE`+ zRF8R1)a;@5AI!GD_iQsE9ym$_gRHD5j=xtdw9LyLdMHua`F(#HI{r0az&~5FDY@7r zPX{(r>_J@i#L-ae7web@>u(qR(TG(Q$}S4lu(Gdm0x4C$4Zo5RO0&-kn-pttNCQfk zItwg6&p0(3r=BU3e6G^dd9}fjpqOczU~>1HBm3SGUA?nsnPv)_TLYWY)K^B8y!??s z$a>dmTyc`UU2dJpG~ud~8>!Jka>8)@&e$D@f&z*Q4^p`@+wxQk_wlh}+I`Id^?fX3y z3Jil3EfyTVh(-2soLkY~3pH)Ohity|`0ZWp7F3jt>+e7Xx5xfozBO$^&`uxo9$#^R z%L#j>dBbIecZnf4od6_$|);t%bMqAm?8}f!tJzaF|+FWmIIy1&qK&aj;y8V>Z2sH>*fz{u=&2YCfA?zDS;O;W+3Q!a=0Zb5ggD^os zaei!1DSwPkG-RO-u7lySwnFn(1@u;^sGhYOF?$ibUUcZ2317(+LmO67_Ze(shZEm^ z0uMgSi_Jbzl!*tm_d6`7RL(>i`dPQ)LdX-VI`t0=17r6UD0gYc0mo(Cq7k&dMeq1u z~pMA7y+A3X$mvS3SD1#RteVYE@j0gBZ*qKMH3yczZ7IsnK)K%qJYB9_! zzDlz{{%-nhWBU>47kM8>(}wtyJzsFS>^ctStVX>;xP?X&>)m)IvyN)RM>&wyzZB9I z{Va1E5Mx+Ac!;n6a#i6v7j~(jmPpDEc&Wy73{Url(E!I^6@mYKdlV6R#f5%rSvtL7yxR z#%h7vf}|$-)`DhE`5?p7iW-xADSN~HFs>IAr%*J7B)QW1gC{5Jd7uw6x z!1j#0*zEG+ZoO1Jf7AMLe1QKFq8Y0^QJw17R;Z(Q*E>^bJ(6ad;+ zLR^XgyVY(g*RNU|Mo;(S3$vsksyp@vIr+-XeMP-F;v*4+THTHdi`uY&G^W;%|J51moa@WH)V_Ag z(q_{H1@U{E%vTnUVfo)<9u)NpP9mj3^i=WXEL^O6_qnrHlM&vEAX(+2tD; z0n2Rete~efms~Ky#rEWR%NOP$iWigK_*o;lP+RzoL%wXj<#7H;LRF^Jnvn>loM-aB zF-gH4^JvnxU#8u+k(1{eG>s*9rF)b%egsB=RsGlBg8RoWD%-^B5axkdB5I1E9Fkuf zv!!)g$xp9lBYb7;a(^okd5|)Fu?oljH7bHNQC;fLjsjAMFRI<{x?`|AHJEV+^__<) z{%pEiHg3Y*n%u~DC&6+Q)HdZ^P?N}-g}PH5x+#QX;LM|QNxQwtKFgyYD{FsEuzD=+*Qu{!G%jEu+eOhLY9EiEdTe`ZNyY8R z=OsC9N-F~|m9LqCi4A(9`F#5to#0%L3W-xn{Bs z37xfh`03<%+eG$8R>}!px67@zY=vj9)alZ6c^#~{-9~WoFr2y(k?u;f6Y(2^C6Yty zl~bGoeIV-VFSuxO6ExhAT$1SQ`bS|7alOSwdH)HeGnhMRAVSK)lT)>N3aMjfS0Xh_ zlF#DBp!0-uj!=X$lrf2TV&V7h4Fz#sMJsllo^r8i1dE^XDnb8E2-;1VYUmTDv#l>? z%uWo$=q+d#Gb1eq*YA|B7w z>QO6n;I{+deW!qE?XgUBrwHq`H^qfpV1A1wJt*T4^qe#>b8{mbYFl-hDpzKuokG!* zTSU$2F;|XEQ|lp1B1@A{5?r@t@RKEdI^H!&eOTI1wA7E@hzgW``{ieJoz}?M z5_@3&dMHL^v1_diA+b7gRQOH7)q8J|HhTb&B2%cqfKB>$PK7PaXjf?U& zyIG+$4^HcfPj_DZoDvWN+KrBal%9ttyX@O+oZ$~9c@>T}qYP1nn)>M)Vzh8oaRAhn zr2!DOKqZs_q{C}X6+w2{hJ2!WR?>D_)n_FK-vO0?l+Qq@s#gU7Ic~w#%NKt@ z{g5H3Cs0y+yb}!GH36#9r|jUK*#8U(WD>xTg4+LlqbqHQAvTbCIrpOO$8GCdP`iIX z-+XokX`W|tLdk6i7y7EZxh_XyLg~LY(gp455SOo)TG}E%l`iP^RLSBT_EYf4z1swF zvb33YF8uCT(D7HGT-@`ghV(0qfe#Qo_fMeUKyGM@tbl^{I30mLc$6idcJP8`Zp5!7 zw6pH<8LgB#9hx6G)Ae>?%PDPmg`iI&O{|F4_dbvL$mrgTt^lkJLp!f?-|8JkOT_ig8$gbDf17nVYHg`5WVc-wWAv>Ah6(&NVW}si zD-|P+eahh#p>D?z>F9YzB*PB8at^%}$7M3DP)RU93EZeua8EHi=J&=AU8#PmOt8NK zJEU@Qcu4Q9Bt%GXX93rGJ1gHx*CCW{1}RJ3J>HVEQC%G(O>+7TkFoXfLSg`@pYEJj z7Xc1+!$I#vvH02ZRH{mT)uPlv>F7URXRf;fIn9!flDC(7vs6L%X&y{oo?uxM%0UX0 z`4&I4(-Ejr)?LM;-Th|%8kis=vRzvq_O&tNrJ;Dgun(v6jnaZ1C-j#R)pB|Mo`*jr z1uBSYX1v##%l>fttI`%fyQ!(|1I^%1L4AzH!{(koD0w@6R2#7Rk99kEmTdH}=eCnZ z3UUS{DmS{`eTR4p#kP(EiRflvI^igB(Aq^T!QPj@oMa;eSw$1KDjsL;4J_mGYGU0d zr3Kj3nF+hV*Mz|CIv%at_VlB$XiwFHYEGpe%h^_B9G^{klq9fzs%-FJd4}Bd>TV5J z#JfEwv?lDQ3j2;*AR~=67GZ>DrCpcFG;=vvYQ^x=4)=%zi_CbGbU?C@@uK2&Qt=?q zR#eiIwvqJ0@{8@$=&2V< zMW8K1R+<)1?Sf~1oZj@f3%wJceQR6Sk>$Cr%^GXnBKM(5*o~;1&2DlfHVvb($7()! zIjN}Aukh{l%?lCFP1(Q)=6j+|Sf4F)<2^yPp*|3j1b|3-%7|IEpo+2x;3-Z=pr``~lzCLpu|x@fXf zwyY z=97i5cDVe}1HVl1dj%)EpSquxy_1iZ&wUb>4U+s^yzh-0Uv7)~J#oZS=eJTT1FgTv z#+~D_t*{zgV;%E{WHDW+%50Y^ z@l+^&w_{{wPjAlgyF9{KvWn_~j!Bg|5`U>ero1>`zU_%_vP?8_w{`-QNL4t z;kQGB&{k}G`1@#Zr!GzW%e2?yhqhZ1rk^piz+uFNQdH1@wvAZ;p0C_mxzOG3Rl6$s z2>U!GQWqlfCC1b-GJ43n>P8aA1#(<|&{Q4lt5~n02ZSXZ((Y18Q&h%a!zl&HERQqm z4kH|KzFT(}97AP!Oo>98cgAh(cAbH<Kb6v6?v&I^B$?u$m}m>1}nbIKNVcm z{eog|gfXwDX}U*OMR)ecKJ=l4JL;7rg6@x#8!>v zO|tnqbAyUHLMS{P^Qnb9mD}#GnN14Jc)JqGe7pR4IX@PU#XLI2xr5|`VJxW$N-c^X z6Ne+&q6W8|+mIClOZ3cBk{?!|*75+MGKRV-fr13eZ!B?)cp2YBuu7`qq;GONCkl$! zX^CvyUkPQ2D%d?7ys@WX@;fdBT26yjFq?3cI}t)v3`(U|S{_i^MVqkq1NVjt7Y!qTbxQ!kR9tk#fFRZ`=) z2^yXc;K)puA8%YR*qXUSZ2(;qLT5DD)B%IvK9&=J~{Kl=HQZ)0W%mfvVsJV47Rd5n^2b($^pIN^sT zOT@ktRpUd(JoGx5`QNyE%dj}MbzQUx2@rw@w@#2iaCZv?4-g>GI0^19jW&S*!7V^= z65QPzNN{&|CqRJ48|!&%&b{{DbDewkI(P5$@BZkgdOTHKRb%w18lSx1`_}&W(T$!* zlBjf6oGdz5*e(CQ(BYkUX|XpC0gN)W+I<+NI&MFD8P)s6fF{VAFtJn$6Y#tX7Nk?GW{&k~(C7}<~f7S`~gzv9_+f&SME#hj6OA_&Df zLn<)dAtEzrxp%bV@kcrvwkc*2Lq9~RoS!x98GUg=6otAZ?eUTcQp`WPigEj3%@wX_ z7W+->6$J%@&n){Ivsq*FwEeo_X@7wTUCf4<7L3aJCb8f%W7az?0N#6@lgiMcz`eM- z&~)w*)gU)iFs;fuTp-6cxxH`yQrN*$P=xIBk(gw@b=I6K=Un1P7`MNPqByTyXbv<~ zdU~VXk5pc#^CgBBHDPp9aV9n3T3+Ud+>~`6c6#wtr@5O5evH1C*W0(_^HIpR)hA7w zIkIZAE**@DMS&5j1$=S}yD5n)Mjs;tU!7wDLg~}4n!4;4 zRB76cNkF;cn-*Fp@2M5)x4vrmA)p|a6wCuH;U;f4B5hXvZXet!m&Ko)snHbN6k@y4 z)04p5>~QpR-Zhvv6y2ma1y!h@fF6HW?R!x9ED!^0r*RzS`3Fc+6Hsw%%2Riji;M7~ z_Ae+wh99U=YUfaY$NK93d-3pDjITCTH^XbMxN6J%^~l+Jq=tOTQRI-BBq#f@OBQJW zS+fTS-0UB;Qq0rDqisRfIeJZ%jB5QeOp9v(V5Ab&){pO^1_4ZU4Pe`1l>dpCDrgM; z9uD~bdAR^#+)FDo7S;;ndGh^2>Nj95icy3ue{%pL0RK^+)K%6FfED|C|2;V>j}`K7 zoO8Rs?zc?~O5vo2cQ+aLVk<7`*{>H|)&C)oEL8TjOM zRj(!AN+iF!S|Hh+u`e>%dza)>zYx)FpBi+9$(4bwhi{xS)x14Q zvX`N}Mz`GU^-Y;v)r{TgY2&VQV0A;spN9ema>#Ft(WQYS>*wMag=9Ta zba!AFb0_By5aJg_E==H)*v#ITB`kJ&=H7?t34OBA_4o)cPG@Fvz8vNZy@TNee@FTc)1CSE zvyU!HdbEt2J5Vz1mtu-}X5&XvkiVi^#l2eGS_#tXa}_P$gFQR3)|C&wSpbOF$1(D51mmLn#gY_RLUprF`<*MZr#Wz zbxn@>OvH$a(KN`<;tq{0WnaJlz9=g!P&%qOX*P*s_9FFeDNAa{7{AO_<)nM)@DS#U z1L#1oPKd!y0y}?tSg#*rOV_Nv!tUMS*$_2f>;-qNEKAg#b%zxAIUnKFU0>*w>;Lbih zRlvzs))eKLh1bTppZUbCx^1=4`r&53#q~OEp&BY^a?jvJUcTY4n@{y3k+_e#m~f)* zejbVMmw|kGd(0-_j%z+(3aE>FGwGY>jf+<~QP-W(#WLQ2f&!ejd~cx}72ojK)M>oe zoiH5QoLlI_b1soHHvRlZHeTBLFQ%TPA2-lNh2*Pz9*pOBc<$Vveee~YrZtG)jouA5oq6`0x^&k|H z{RgPK2zck;d$W7hB&4Tj{vNmb6Kp8;=s92Qr?;3r{=7i!^Waa@4{)w-xMmo=d%KK3 zWikLkxt<#!Do|xFJ#u4_@rJD>ht1_(puDsyejdR0QhWzwCZ!KoQKBgRTZyOKKL_zK z4^6B0Tc}le+Is2J-3lnEFD&j30B}n%1jsUy0fka0s{kB@#5k(`mthMK7KQaRx3vcW zuofVi@FV#;BJom~HiP+LP~6Y*mVY`704)0dnX2^wrWFkUFqHV)uR_^cs1ta(2f3N1 zQqfpka)b6+%l_3RlV=gIvr9=N(H|hLZNF&6uT_IYYDKyKhbzL20g{~2xj#T_%6FYf zhS6$6u;YeZ#ij;JCW)rx zv($Kpy85>Z9|Txqu`7UVI>#~)l5XGBSoCE$sT&@00!Ro)NiRY0(&CaMRc{Ti5M0(< zpyc<@4klho1pk%uZ;$~TFW?rW`RBCdgWb3RI-b1+q2v*P*iY8nQNz=pFZ=l`j3YN$ zw}5QYsZfqh4Y}};UN!CdH05W>ndDpug0uhjr{%D_U1O#nwXZ#AZZ&* zuR`a~3!I~shsbUyqqRjd<5D-p>kfkVXaH{{FvqL%m(+@o zdlT;v1LTPwxsyvG#k-9^Dej_3{iHVFT0YjW%YHiyx?2k4riQrm6N83Ny!Xk4I43*u zy=%5}cK&!OJ~(4W`+I~*bfE*E>UodU&PxQ0AF$OL3ame$IbyKZ)kzL^;_h`U^AYm# z(>CVKG^P}$k?hVBlaz=l)rVQ>69YjTwmB>P28l$uQK|T&o)uXALWcuIJoB~*#lWU` z)k<^3aWG{hvtG{)Rn9!c8#7dX+1}fNP(J-v8>G=wKiP5y>u-SKdl#SFoD^}>$od_Q0ynizIheJySA}@sIt}Pn_D3F*llQQchY>9z zJ31Irg%cfOAJdP_+?b(jXK7aHZ&LG;2I6ub(kFh2;r}eQS;=sc`XgNTSqfwDfI_HC zbvl8c4TjIv=k~2f&KKa3#<#4I$p*8WIb6yxFOi0KE4}=jmrP-jyPfJlh}d3NDdQ%Y zV(vl>%W2jaLAl+=4(mP207zM~u4k!ebIPoF`l&qylcH5=JbBV%^eX%cS8aG$_XT+k zL?T}%hW#jx6qaT3aJUoyTYhf(HfQf03ZPr+TWY^JkVFO8Y}}8Zlc>4K{$;U$Pl|o~ zCrDb|5Z0U9el#_W`&Z^}FF)WE_7{HfHVjD8)!zY8S$g93Bc{_*rJI~jxQ4ZWUGIFs zuT*AzrLMpH+F`@GEU|{cYEd^dTfFeWFiF*Y-MaA&nlWt65lGI(99Ce%#;|VzCUV%# z6i)AVAOc4vdKkA=Trb5BNe6dfg#Krulgx zWtXS%P3C8G_HaCZS#X&wB2BAuVslzzx!5nDPt$6Z^0@bQAExx)8FHeSZ>((T9U{CT zO8rXjom!@2`*@z!@m-?Q7~PA z^WYV28jIs@I`?L{McR4{-o9SzhH}};o;LS)Dld-ntGI0wiTBb@T()x(*vPC`6aG}M z>`QIE-QgV@CY7T+^xu;H#_9WPVeM%N)AQU7IK7yHd{eZ!BEswq-!^1 zLf48`NV()|!jKzk#JyveVkIoo{pgQ$;*$9L3L51Lt7H6;v(+Z*f7LLq#!D^0jRJSn`V&2 zg^Lz;`Zse%c5iQIySD7b|I1k!8+)J#Ki=X~)MOwj5xyLr6F&83MV)7= zJ>GcW8Y|6nFha@Me)y&4Y#v+f{ zZb7xx-la3w^@k}F>fvL6KV#z^M0P_B4VlmZn6yt@Ijl^W9=Km`N+O=eN>W3_frvJ? z9_ZCfTMJTDC~IBdvpnMUcoy;r;XUh?-i^Rni-s<=1gj!MN3IdM0a)J~V$x zk&T~);z3T#i+R1scvRV_Or9k8;iZ9szXiB>hBkQvms^b9xp)Z)UG1mY|M81sS?mjQ z7x&`66!k1xk@0Bpelq0Bl6P5YqR($`Yu0hCj7i-dZ|1DiQ^nHL-HU;2woHgnuj89i z7(pyoS3<)5687NSBueXwWSC>Cxx6(W|H*>QOf$}mimTfRgNtEJsH{N}1;tt{E8c3? zs!e0`%A$goMOgwr&KNr_~Q+PwxTXcAMkux^|T>4KuCs|+{*`nTp3~WPR%XSAX zxG=U_<^rJiQaUI6U{?%^0l9%vIV-X!%P2SY>c1mE6c$Y1KQ3h{4WI^_XL?i0`C=CZ zJoZi`(7@-@p=_{uOvl+W+K%MYibeneYQGzHCz|s{!(N(G^jkR1WS`_3GkMHFiDcBd zPl=+^eH()Ynpf@KCOGX`dEls8&E%Sno&AS~C~r0^V(hXK!)vDq=*RdC+VcVx zA0{kTtH%c(AEK0~<`QlNw33H^9gKNTjpi>5o6R(E<(>$2hEgnR?Tj6AtZBg`Yr{Ps zlZ00b7ShLQ$xiPC)Abe&%zFC}ltAT23C|O#P46p4+Wd3l4PqD1P|Y-o?v{@>IYSTg z==UkPtl4^bUVB-!-gi4Co@bIw*0ACi(!m{jQKW|Wnq=D65v<>pVy<`YmF`8uM|ghq zxRB(nZ|V9f7chj==xw7tG$TwM2J&IRIz0{u%+C(MMCvi?Y@KB7b5+>k>fLm)GIRm* z{DUxC8}Qk+;QfW6 zp;&&ORNxPCvLoMYEK>r>QCaiRs3oG zV@n1p4GEl$k=_At^bP0HZu07vX0_WF5ddtYml1P2;$2Bo0z@3B#zPUJ^luR^b zuxAL5EAljXP)Na$IbF12J+awEhD*3q@~Q7gs;oU&gz56CYxu={h)IZyE7NV!=vlYl zt1fdO=K6Hw;~yZNoe}^>sR0YNkVx^P&AZQHOh52xx13)PAaXcgoaH~J6^+@b%P%Ok zB^8OS8h_8upwz%3@H(fQd#3shoV#LWBp+6nNS4WSf)nhPW?M7hKs~ZqxB+Ng+^WJS zIVmUK)+H^hJ2$_4TY_^-+3vh9NuawYqtQHG@vZt9SbXh$HtnaAA6NW)C`?4!&&@wT zM7EiHnXFd`q;-Mc;)HUbpo_w9$vitGSx;(v*d60$hGy5Sghyu5;r8nRf!9g`Brvs} z05SPDh@+Y^>C-(C!|mVB^|Q86ijK@i2JD!3N4uVWyUja6R6)$CoePtcYu+JeUJ zI1BeyaoqrhSJSQ}J%K8>@0VM(IU`@Icd^k%L|jLefM^M|0W?I7$Y2gxf2llpKx9AI zas+Z;yP@6*;5n}KQ+^Xp!A~QxKOy?@YbsRtVGzYYyzt#icD^!c)QZ<{I|qm74OIE@ z%qdCS`&~HrJ*`0-uOYNAkcMlI*-WgDEI&K|id;>}4Pcvf#$6sYRtwr$h>8x1#;FPl z^XdE;Wcpcc+#P+AfiCqk9O1Ot98Td_;9}BV_Ts&nYz!`8nUk{B-Mj~!Xcy0 z602%p45!7|*CJXzIOg@dIKjw0CE@LlyjGGD-fS3yghtDPUc7V$)MhnI0AHIm2QeGN z4@~2QQQKSt*-Ps=(Vt?hEDqo_<{F~}dFx1)DtvVVZOCOITHk>xuB8&iX()SiU3 z8sw#>+AN(9&9K)Cvq5fut(=h>V<0pW5Cy||g&Wcw!Ou~)KI3cs)Xs^LMku3+CRG){ zo`6Ru3VpGW9;vPCClXZ{x1x|mODa6ZFYYFy!6=y04c*2Dm9jMlhq=PHC}pu|r(#SE z6_BM$L4A71rlM4MIQk+d_JBBMnXK0)F8-UkXnQsFkg@(NlUNiYZWfD2ZH@H-Yldy_ zh*@Q0)@#IyQ!-&x17zhO>%uw9817?IKiL^;O?tU28-X$J@hLGfI24vr?fM2g48WYk z?r{^g0{mJHzl_~AKEn%8~LfQ%LLD(F>w}!gGSUK@Ri&HuI z7R9BXl3bMX_IQU8P=b=I=$byRH%2jr^-$2bV4c&!c{eP7%q2api+S`~E16Ru9q$#5 zV$AA&*5E{IBD>|pbzQu2g!;^5yq#C5PFl6G-9-}rml{xQg)|qgKDq!2!e=EU?_W_9 z$kT;ij>bsh(^saUh+1iBDo1V|b6#~c?J?DRgJEUR#Al?fF_&($!3E)*=hmvEH-v1k z;{x?-@C4kU_D;A=ZGDwU$L6wtNKdue50Zo5tw@Y^^@!wA;u2(r%W$z0S`cL>NAr_{ zMEpO>S^vGP^}oCQmu0a3SuOkDJ?)>zlWfCkNlRzIcu6CI3k$&$ujj{!KT=ZE2U!V1+y6rGb~BLhfWKc+{+DaB+E`!w`2 z&23dvFFs%&L-Wva#CcdJeDMq9J@FFq`gTZcxo&$z4l&VJQ@fFMR8}jr@G1_9RI>=D zBO%9aBby9Me%4>}<5qghY8(iQAkGM1+x$J8p$;$kuU)%@73??Ix6)Yj^$pQj1oFf- zgamF{=pcWsGvnU}1&pIHoQ`G`0!i{8&Mn@z5AvUDH+b_cV_zcDy$D2O3aS0;_R@F! zlJ8V6`YX&H&d&*lOe?N$f&Jh3_>BW`!?OJ$#Bxd{VkXPsuCMZCZ03<15Efj0Jv}(s zSX#DV9fO`tqjQ4|GQU67=}dQwi>8lsH&wTu;e5(JJiqGBxgxnl8<u~8<;Iq+ZX)TglCJuxECD(3 zQ^B**b^Yb0oFws34`00%jw$sNqm? z^&2C3bJ$_XiLNyneXjoaKDG4MD!!Ozg%0~sN^U=6OFBcmLfm8g@5k@;5qX2O9sC?^ zT*&5AjF62}fvDz>w33NH7O|se7NGsAhHb8HDw-k|yB8u|Tg$@)o_*5*3eH=$M;2vUxF;C}q7yMuwzUZF7|1{qG_>ltsxt zjEMi zu4a;BCsTXjbESadUEy}j`xZ`E#|Ib?IAw<&2ch`d5noq<;OP_NTc9{Nin9HqnA$ga z>eT!&cWfo6@@$32=L1iJe%n|}P$S#enfH0D$Rg~DcAkE0a2z9Zp#8;^S1fj?i@q+>3q*WBr6GvN~g zn36E$J%9T;S38h+B5l9=`4?lr-&-xth~6H7qz&6Byw`Fp7?z*2(hAVdR;tQh~iOzT0{WA&}G-ATqFR7%&B-J~{yE8K@pG?=kOeSYt@`H9N+?MT0sY zeK!D)))}-Soj2|!RcsGh9~_CgQ>6rGo73jKVv{7)fz5mV0Xo}s2Q=uY?wGd~uv^vm z_rTb78T6f$j-M~mZs$y<9;F2KkTUsHQ82=&Atd-A7b)kr5x;5&lN##Hb&UtnJ31GS`Wvl)J&1dLai(%yf7*zkCbEDQF? zZt6N-73e8DGei?gb3V)rVhaD2hlFe@FhmQxy+rRr=`m*#DSJDeqpi-*`wAkA!=83) zx4pDiqI$P%ULc@7OHg@Z3Jg?@Wp2~1``qj@x1|aemyIaZ%~)R zk?-XMGwPPU_r+@Y41=~WE&lA09f#xliE`SNDSQzr%>K-bQy4brVlgHn)x4qesk42) zRo22y)KC2=0p{r8^t&U`%nTK%W>dVJ3y7^d8UvGm<|m@0Ct2V?jFLEtiuwJj)h8$K zr^%Zq<*x50D)t~BHiq=~Njkoo?yE z6duLoD?SKd88-xqA@JZ@wtUVid4voR^mOb)Y&vvD4(OSIReZx7SGrU5Rg=$bBT{&@ zxup8gnc}6$(OW^9-}A#)tanb|hixYaEd)6qL{Co{+;N=b<<*P|h8_vfIoij|{l?(U zDDFaiLF?OyglHAq37mKonUX9=M=-<=@dW3G0VSaUH4h{Sbwxr$-J>|)rViYyG)8Zb zF48?*4Z1K0LQ;Z;y2(r8_9(wp=Q__Bl6hd~^nZv~#k5&%MVfE2i_9oTls#CJCm71q z?|rU*RQTt$2Gk7=V>&s>ZM2=1b*hrXzk%3vJz_v$zGzYlRhp%xNz=)Y&nj6S_BdQBG9mEC2IXUFf3Eueomopg_$?Rc zJg=Midn`r64AJAZ`GVMF)+vuzZ_3n;drng^yF{UQ-f0#6(%XCS+*m{1ERH=9+7WSF zE@`pn9jcSpv1*){XQ$F`B?Vl$-Ln|22IUmZo z^ql+?9W-p6(Vau~f7 zDc@L3o=)R_rQE=ewU{pu&XafWOp1?lNs=}X<6YDSY*P`~$e1q5fJweX&)?cJC&#X= zjx3pBV2GnEiDYyJzab^AjKT~DXYH+*|ERMgG=g~i4chepUh&fAQt7e7d5fXQ&5m$;^`=g)!lG!5sN(sxRCyl`o>2CKr0|!24mMhH zMPY&pA-I)cy!c)@QaeMlCCs6MeZxVU>FlddOv}v~@?ArNv-RcE$$wB5IK_H%7fjNead*>RL;un=r>XYM$Y%k%x135 z;^!J=D4prI+3oBckL-@8e7?tZn=xXV`fX2NAFYrZ&UqnirLD$#KOs-Dxmm#BmLQm) z7&S^L<5d8)(6?=wZA#?VOo^cG!_mdevZ=|}H?X-O{gnEp+{3VMeajbI!?JaDzcgh; z-f$w(Zb(8o9)D@XBU%Wobh_*# zDoo{)(nhb`s@Yj>H0=5CY~G;7e`8It9#afG`lBjq24bf|BB6w;inxKhRJFR8`{8qP z2HLrc620=65~T1l19V8Riacd<2V%4qD8wI^w`yd4^U2kEMBDWgEiwc%lE6DiPtLw1 zpOq#n)SkWEf&GZ@PGw|zoTFx;T=Q$64(Q#tGBv0CMO*jw1|`?y-mA#3u(ce|0M*N}O0c4how z-W+_a{onTcWHTr_)NFfoJZk1>TDE7;a;X|5)g$>STHI!=G3iRZ`h;(C-~(xyc>jvi zi%5IWZ9)*F!k2YJ|3LRy+S|%^$rz^8K9mM-OHwO&~&jwF0B9`=NpJnt4q~X!%%@4Rg z|1d;-9gyTWpo}E6(RP)$LU#yW{%j)e{88n!S6eCkH?OqMvW9Ie>N&iw&CNw~$C2+5 zWA$Q)L}CCZhm+(4@F2Afd%td@I-$=^b8u_SPgLr6CZ;lT^4<<8$J8BnIA>k0UMUWQ zxbRSy;J>wIQu!6KmMo*J+6v^+KJn^-t<&!9z&(B{D(gNow-`;AEhTwDzfHZuP*2r0bsrscRx|1iHMV|Cjr#5>t|$}fASMWaMDSH`+}Tn;DfbE-?$~> zr@uZR{V$(yJikxz@*liZyz=`N@a(rZmyI!K#lXneXfHLgLL$!HlFqP~)j?}>%fXw= z?)^+D&;dRo#%cJ%hg5<^ZDtZdv-dGALC9H7+fp0Po3i{2)?D?v304_mTgs&6Xz6IL z!sMDSG@pyGPDOJ}rJ;O=E?r&@_NCjHW~OX&$I&}=JGR2V%}+358w46iA)gHylcBLy z3xN&=5Oz>`MU&svS)fip zF1ACOkyD*;`4~wOaRQr2C;^6tliq8l3Z|6xySYTD)^?M+A$8cl4q|FO=dZiIS3D4!;jgTh@!z zg_SDX0s|wzwmqh(M;$S&!VKra7d9y{CpU|+kYCA_=-ac8Pnyq6qslzBdzt)(8%=N!=Vl zk*+ZR@pMw`oB?f#3}|s1{di72f+M+b4w~er_w#7$qkZnj@A_UI7`_jBXDNPEyhiMH z;8R0Agk>|!a=iqV9t~%7@Qn@r9)Mud*5OB>NTHh=6NET7qI&bBN$jF(5q*YTzFoMD zY<|PeekRFhw0S8T{Nqr3NbQ)fscn%Bfq@#%OMi(I=$UCY2QZg7{7n-m}c|r$EnPhA0v1Q zJMb3e`o@|uJMA5&usMo%B5R3EEdC*_+Pw-V!S}VEWzHY0`N9QSq}r^=*S0vRAyH9< zn_A0rzw%orGb+OkK`RF$2@Xjso`DnWONxS?;NKNzIdaKr&69Q3$Bq@5dxuY!!0f6M z24+Re{WlxU9{|BC#`L%RJIOrKSg+U{O++)5t}4W5P1+h}9O$NU6dZ^H4v2y^L>I~f||DtR%4b3db1@F3sC zWPqUO&Mn)Bl#(uZJ2qNA;vFL#QLFRTgnD+D4>M2k%~{6!PRfHIyZ6~mcUBojhSY(* zjQM<-w3E9t4qJ|OHE>eyq_sAu2|r9n@6qsu1zUAjiFT}vsg|D%8rAEX%=rCQ#|gb=BNQQ z6sD)R%BOVkrq3_SSJ&Q^kahb!TkU<=C($C0givg7UXxcy9^@GzILe#xqtE^1Wa@<+ zl7}S1S6`ys&vz*<-F}%h#F3S}L_aMBgVvx=6x4ebopQYi6!^!A@IHPC#D5lj5%W#D z*>|@2y|z}gMJn4lcb}*8Z#)PhA7h#r`z1(2V_b^j>ISwzVOj6UvL|s6jp`{h-j84k zt>bSpX4!b6`z9_EDbsgZw!eL6ae0)a4YnjB^ZvAIsncoyf(P$X;)f=>az}XoIxeHx zdT=^WUDqb-yLxgmjba|iDb{<9znyvmQGpwNA225v#ln7Ch5n7?6c*+F@WipZr1z}; zr>lQb(F^~52P~@7omiTR&e*}VG&`clNd^P}qh_7^wgQ~L@Dgm1(0==(>Ep%$Cl2yf zqsoV*cKm#9D+E{k9SWsIt}#4CD$Fng>teT1QR}>+EwFeod01za$7{V~vXA3J0tlrB zMQ2X`WaC>}Y)cl@B8rOMy|l*st#{_Jigo8?yBrMN{k?8A4wZb@Z2lwj7TZs{C+B*n zHM(W!|H>o>%=v%CN?y1xk}Kj8wFZy6dJ7Y2HHdCgoM9L>e=EuI-UwJvvtgs(0BBU! zy^ZAhOYqq**zqoaCu%y81-XF{Ut+G$C9lo^QB?UmMtYPV{{0<*C4xx)&v(8XDJyvS zyyEZ`=0l3v7@(qO6saVCcLTn?1}HHAn#MRFlNpLa!7fVDb=6PmrW-icgVJM+^CSX9 z@c*kLGa%X{6L@%d_}+Gt-HwDwUPR2ZB`uH8ff9!aScit>pSr87qo}&S_s3vKkkFuu zu_2K$s#(mA9NeWjA6UdDgH+k_f`3sslf%n!mM^uLa-#`3QlokbIEsZ7Qo@XApRHk4Zpffs%9}XeD$P# zS(ibJ{rusXHm?*7=HLDwz`J>@0N|Jbv@A^WW_on||8}=SR#~SX)0em1OmB0yz&*7G zA(Q=-iA~i0C$J1px&Z96_NW`G17jRVBeZ6H4E=1$dE-{V$xSc{d%LVJ?`6$jyHEKt zwrB0?;rj{n?I=M#MAULmaM}LsRjS`n#6xvOQ+qqA!xwZ))e2aP>1V07hMgbQTV1bL{ zwKAi<8GlLyAjB|TSL!iyX27&SOOTWFc9q37UUlhqY&mg`nrCi*!N8-rV(zGHgD1$| zX`H8|am(J$#Xs?4Bn;-YkwMpe%)T;2PI#2#*b0w^+yG=_2mKu9Q8I68Bwm~deDm6% zI#9S;)a`SnRJ>nn4Y&jcyGURn%ZdR$lCyoiFEL)$g+jM>x_2p?&pOW4Sr)W;nYqt z|3F0;f2$VZE5{N(GEzR-Gl-r#Yc}HEFg znKR+bAtq_fd~1;_=}poUO*oZRM1FTrdomkcyNYh*=;eFBI2fs~R{}b1I5*ZbW`Kqo zx1R{KI2Z3%r#LX#WkO|t=Kz(D(}=7)FJs_E1ZXlBcmJc&3N)HeoL9TAX^2rz=On1= z#i+pdo(VS)4ZSALPTSs2+=bZmaE179UvQ?^1+%JViI`4e4DpBeU2h$e%hEPZ)| zB7ld_OERuv+@%2ZBg(0zU32USM0hhH3u^`c3YOu>3lZJ482wZZAloHJn%6n~Xd_~p zM_*LfA!k2+F`CnZ zt944A^6j->AnJZ^m)ObF$bFd}yIP>!jOXx z#EnJU7I7MhLyo~&?~LL8`S{U`68P}ZTgef)SKD5N!AYlOhhP>0ylW)qO}W=8+LaOG zIi@Nm`scsZ3}a~?)orGNb&G!hfOiLX#p^bkU+Tb`iYsz!a zc=+IE$?iHpEK$)1K!+>n@mXhLipH52*fu!%MeX%w6*GrZ;zfn*7hN{-f^Z~7uAo%+ zq?|W9?R}7t{kVl*ylA#0lE}TwZFu_oCgU`r%H-lQDi`{s!WC66?47e zE?ONn`&cs1``UZs{MT;|u@9sL1xt&P$xphSs_GS)a-3%;`De*SWl|@>s_%-uJYS?~ z$T+0klRDn)toF^09-^w+S0qPTkG9*#&HtK#QPAgqfOJ-m!Mn;B$IesQLVpSo^>z9H zrS!NKap^&0CwfM}5pjTmT{GoKMV;8@0XS%dPmL7HL0<5MMqW+*QAa{Q`ceDX$Lk=& zvgs219DWXNF_m}(^y}@v; zJY@Up2#xVwBDqc?IknNJp4v1qXZaYVyt(~N_%ea`S`s0-!`h9tXF7^FWe+=%lhn6d zVuUC;mM_gA1t#r#dZtFq2aE|gS$>hPz)~t8+i`<4WXCe5h-zKSZH{Uzs#Q|2+*hW2 zU&bP0y+3jJVU|hkg0J(!+Bn7kG&k69#9`JAhO%zw+TS zOOg_z8pujRkG9P?0e?QaQz?pQnGPq8<|ZZ`P^VL6@R#Shs zE?v+654$b?g$Wz4qCI11VaV~qvMGcy>1|0Ixnnc=B~v_RfkdLcp`j-|2IejkT)Nr-9vzOZ1m^h{Q&jPXN zs{r5{J~797^K`(`>l9RCovk~~a`W)xfrcIYJg3A-s3l6w0(f0!jlIQKCRSJYS3X=5 zjSotO=$`Bv`=BIlwtb76a~u|%k755eeiH&C1NOYgD-y`>CF_8hJ9Pvhk#vXNWXl%)1gK?QX>goxApRsMO3KO&&nuVEjUG+07lZ6a&)i@ zm#dBk*(5Z2@D-x_WYyK$Yk(LpkmkF#t@$JoA%rZf}DAu>WTp>Y*=38e1SunY(sl#%{<|^$M zLh~S2mYB7EQB|OlM5_vz*$Fx)s%0CvXy@N-jBh38R(n|mlL@cqJ-EoNpLp-S&&CV- zNf~*yLLN?amUb_`&~v<^&}O)bU|d*5u&gHEzs@=mJS~4JhngGnr&DNqW=oSv7wSSq z;vT7nbqr5PlJ+^Pg?Mt_gh?(rZcEX6B5pfqsiyoX_Q+B*g9}F4>bvurlIA_LQkpm; z&uLs2>U^JY-rzOaS~@e%#92d6tS3d2hfKJ1Wx(*_YY-~Gs*M)P)G1QXnL&H-cHEw+ zF?A`0(e3){(TCYztdP#4`xo$D_zHL-5y#oe;+A{)lkhdT6gP6`3 zOr)ne()IiDDio&L+?cfLmY{4AJ>pr}&)_=I0PtYZK0)~XL|kS$+OqalE-ZEuygti& zACO4x{wyoc6^3_5wqB;Zz7pjL`#wMF%-*)g7|*2}eMybds@r6zv4dmKkJ(K_lrmZS z%Dx$4_cF%?fUm}H#vZjw{_v)$E22z{q^#S5FB=*4Fvfd|tE#>Fl@q{%`j}l1dU(Wc z?_d!>oWJV$u)uTv%f~MoUaYYSnEB9>8Nr!_#7M#Vr))E`SPbE^Vmz5&lA5FPeqV7d zjKud_GbM^t+|~G^2OR^NKEr=|@Se`W`s7wo&75cDJB`ZkIK8kjn00?F6~rAI%3r?8 zIwyhyUdV9CU!xcBdbv!s8e^avP)&lks!K(fF?T0OL8p zUJwZP>4o9vPaYMtO+07EGTmJ)?EkzQkLixmnuYTA5FC7b5n@p@{o##5T-!wFly{87 zbX~Dc(t=@n!$Raby^-$Mtt#=>{tDiV$@uE4=IacxV&%S*b`0dL0YZE|Ss}|E{)wW@ zd`DOkuXoASSPE*qnH5|&HzTfOnzQVLZIIrhRue5L1{rFu+wu;naQDP9dgH2OXo~v9 zUzQ66>(A6qPdy7?Ss7k6b6qi%f6%uQ0gqY@_8v6-a!WUHGlN1C4;~Wa7L*T>+J_Np z&UT4pCYL}h-`Ubg3zwG1V*Kzg_U2-7dUZka)Rr>0r0RmI-uNg5a1ixCx60ZlctG6J ze1@M@AIM4NPXsgl63Oa-7xaK@Y17Q9liCOaRt?U{G+*i@FX5HlKtAg4c_)1b{KrdA z2>UE6mEeJvS=f4FP9mkCW{5WVv)gcv`Ug9876y2EYVTeaOWcj(LiAWVg>U)Yc7u);{2?ZCzmxfDMXV09Q@YcK@y3u_d zj)r3+YMWYKKcSvv!TYGQron$WSp;cH`Ev1Sl)v|a>8>Yp+C%Uto3iKIMq+&|mTL^) zJy&&z(->e$&iXzczz*jDDV4D2i{=Q+@t@MSc0&at-U zyW)MZ*fM91En|9A!~(rBX^MEVEHE=K+ueHd<$gEhw_F+0UUH;1Lr~Yz%tdB3nXg{l zx6W&|OZoHGR2iMzqs_=;bfgQkRNqiz9H-sRP}-o)^z`__p|Q+qdX{$>)5Ho&m$9}b z9s}LvNgSMZt9}K>@~-lTXvc0pLzdC@arQ_Oimo!%0xL`;$#kLhYrVIt5idit+M?-8 zbGQ0+wG=9YA`9`)_Hci#DSfEPvDU;P$GO$fvk;kC)u4#8z3mx{ zgd+XwDktpZ}Y+W@gQ>7Eo8}-Xr^*v-duG zKhMn;t@Ko_2|`8do{uDm{5QHDvjq@vy-(*HVKjpJ&xN+D?`}!3?KDC}ya< zpPQDDg&bU^>TRm;SxcLD5$a4)KVD_?HHA^e3IByYkGxdSsPe=OeW~IRezmf#a7VLd zcQ5Lc)fbP(cb~YZ)?u1sJTnnwUaa}$h7t-5{vV2&B+%pV+wKTxQ6_1QPA%nSkQdY5xw1q5%J9wJ=XS(woI~`I7VWZ1aKWyiE`w)Wl;u@zT<$J|=Rb5_v zlzx<6D#o&LIeh6}%C1=yBkD7Q)C(YEclPSrj_JH$kDn_IMe+BY{4pXr?S|Lr z&F?Psko^`^uRV>-pL!#tF*l7wyTr++KH8>ajMXIb&6CYxoZ*;1THg* znR<2;z81IF@;)WHA_PTjqmywNxjtTDqKFLo9n*U*z3UUW^xmFbLL2H|zvxx@EAxz0 zFt`vklyrLJf@Y`w8l2lWt)+wVfkVi;TH12IQm(z z$B^vs&`~VDl+o#w@nDvh1Q1=y>ezOMh;JVvpOaGDr8u~3%+4u$L5zv{_)3en@&Jis zCsF?F<-r7JYz*1UevMAUM8LV%1A6dD1+&Uaet9pjsDpxvR%*oIFenav(R@dm_V8wV zv})H}X?(XGp?TW0VttYMk^h!?sYzaJ>?F=(HMVcROGDiyoQ1h<{0K;H+sg8Q+8XX|)(kox7RAca zl_(7CDSOZjVU8eKE-n{$Y50Q0w8r-iUR10;QQzx|yTI>k#O$DAn|N(rcw1>u&-EN! zALt)LiHiqOxbgb$x!{N;ESet~XYwW6e^~ zoF5r4HL`0VQ(BTgTY}ofVt*BA&=MhRQ~#{H&}q`Asx6S#fddbiSH+E#`Ks-C_T2+Y za$g3cW=pwNqm*R%k(%qqn4+Z0rCUr(We+<$d#JxxM;g^|TJOi)4tbx8&bawdq!rXG>Js@=DGj_~M0Qdi-vZmIP|ORhcPZ|J7dd+~ z(8h&s&4nGn^$MQMI6r{Cx7e;Ww$R}a9(7Tr4weB#oF;YzTH7L5y1r+ zG#^k0m%eKE@NpxvY&YjU_uvT0eH$#LMU@^LsCOT7AJ=PxGdW_%)XopMsp3)X-T$3 z?3V58&B%?MGOvZL?(P{eM$sQWj@IAkBs$gGl~B?fw5^kXc^KKjR` zm3;5zGpAwX_t$17mevIBC9SWl=lyCcN#P zM?HVn40+VBfcA!@=wJqFb8*}etxG+pm?v)UB)+_hZh(@pk7hBrm;!1!IAVa}=x^2V z^XawctE4r(Zi}ZDYY?LfsDol}t8WM4oQIC*Ae!2Iid#Vbv^#U{MmUl=*=*>k1nxd5AaO;;ULxNrtq# z9@J`Q!`z@O`y$%|K?1qcpWCpngHrACey_rpx!X_m1g)7fd-NZn=>gx`TA zNcP8eUxcXaYt~}95knoR3O%J;2bl7lqla<*{12+rf!DIlbrbgctZtWjB4EjcxqSjgxO+3*kON#_h`FE0YuEk59V#FmpE&^J_S#*Gx_~fZ2}VYVxhOIo z&Nfof<8Z71pnBPoZPDy?jm0X0+*3MX_E|Qbf@zzgidFhk>{=psqFiK9XD6iJu|&MD zinSY+ylpCalmi;eV(jVx21wqI11j8*6iWA&fn?Pr3c!yICvj%9^wEubT%KG{+9ch z_`zP}#Pggd8Y@JsvHG)E{RbZ(*dn*))YeD%4f(-NLcP`Hx~8|DuF@u(6)pYjIUN99 z1#;C}tI37D;rbxiGR^{Xn`4@Qz-#MdkmJtdPf$W;iGv*dva4_0>8B2!<~~h03T@04 zf?YaOogQN?wU)+F?5KF{v24#{g(adn&kNyqh3N0h;v~7NJ01Y~UV$UyZR`Vh> z=QCa%e}&$87f(qLPk&V{0}A}KPPx@|QsEV)chDSHhDsTK_USy4XtrohDGTg2pNU~L zvp{i@d1q}wy6SKu5P*OV(3AE$;%|yHe}bks4LAY&(~Y{ ztmju4;b5wJ=TQrtb-uVd1R)uB)dBoircbi70}8jeTv@d=I5t=E+T~} zyZv~T-_h@GKDJ+Vo8njabU;$=l6~^=5PD7?0zjU?_~5v>N|b;Aun-#VM$(`>a_KD` zmf<&uY(?VBFunfZcga!o|QXd%xs@ZrYmG5F}5z(yt?|~qZLm8(vqrNgnO zFAi2y?q)(gZ=z$q?ct@z#AXE#U0h^i+*qvaV3R?%KjW63WL}9q*&%64@2W$lrAscI zQE-%*lu)2H)~a0kJCjj>sYh#O@hsWeBEcgis0O`=Z9ITg&s~zrAET9GqBAbjww^E! zv8h#z=E7l%x71JjAV4>iKB|rk~U|!hGanEbLC>_dt1HyysZvA*|ec;)a z&gNOKGov`BALsfCga@553f}&Dp4*#RyLTq40Cu}&9=h>KII=S$*6(2mZd;h<-Nvcj zY(b@NMBD>a@2ptGwYQ+ZHeNhB61Ti9e3c*is@bEf-fzE;Coun_vK>kEZu84*pZ&w? z{farU(g#g1y7O(X)E{itQ-u=67tiY|`aLZg(nBO!)kWbFsL}FAk@9y@r@0}FQq4VK zGt;sZPN9KjVu1me%7tZ=2MbYo`vJ-HXhgGu&Z8tt_1?`48xI-h?7c1o zsA(dh`$flgqZ!p}@Zn)nHhF^+MQtTy-Z-u#u2jgj>Nbst%R$Srf#hi}>+ND|f47nDMdlUK+?&QQzNb$z5Gd01cc zZn7-GM}CBUlqUSB55io4iL+EFKk;6%r8u=VlPzN=`B7w7y5p#HCfM|JzbyqLGgjKw z*_#(D`JLBG%tF+%<3gU|501o;30^%@mLmLACk_ANv2^d&JGBV7X`zv=Hiqv##641v z1f%7VI(j1|ycAiQOU*sE(FJlth|AqQ{Q z6)0s>ZJuxqnn2=GgbXSmwhq=K-2Fll6T8{<*R({{GjYrhWzoNg@$VXtGyP2er+Bad z$*LOPar4ejKC%9wS!Ec=NvOE6U_mQXciLepO)!}#{zNLlR{yXvqol2ME8FwN|V+ZDk8uIR(mv=C{Vg z2GTb)&iYkm2s=U8?X1VdTe<{^_o`UGfr8~W@+MPX#!f0!qzLTe^qdv@2igb)_hLNv zV-`GH!pG6APRr}28?z*-uQUEZJ*%#(CmLU{#RqwsX3aVoN7G=x@!T~)nY6TUGL3P% z&)6_TRau`BfIfx@E=00bSv9<@2wP3Ad}ziv8S5G)mkZG8_7K?VxzByRGHaR6zTXLU zf7@!J-C}TF7?irieW*BJQcn;;IqXb_OLG+dTuOX2laIaW z^J5br*8$y?MNw)e|01!sffPEExUdj~yk)=8R{U|RubDz=zT@&Ok=X`EsXL5dk76bK zjeGl~a`s03(k9;$E{(T&OU(n?SYk(k0ernevuE@r8S`wKQ?ug?6Kt&9b6{0p>xn%F zQK?97x);9Xs8mbU3msRHF($({_<0MuI`MA@CXOG3b}sRwJ=z?pYXCeu)4B-ndWwo! z+oS#Jr20=%Z%!<%>8R%8W1L~Sh&EU2Jljg$9`|Rr`2%sTjJRoG&p8ImxHp&VT$$y5 z{D76$K@YjwxdvF=`C09sUpqVmb=j?>SqmSk8|WB1jFmd<)A-$c%!=CC?c#i7f+s$x zx8i$+<25IWuSny^QuoQG;eK(tb~$wD@NDt9f{{?&I4 z#b;TLVv25R5(Mo#?H)m@*)+p=`h;GK|Q`MP-Z zyAOVzpEsmO<}Ugsw5XA$V8_3V50)|=z^7PBoXD$*PJdc+OhJDehuC`b)hR&0JUUoX znCXNtKYLobaMR~~kpAvHYJ`0kMf`Q!(OULoc8j6alD*bAEWg(E$&2R#Cn6owS386_)9hhTC3uoFR@h{ih;fdN=rF1`D7Y<7+-P-Nd6d3DB z=H8}ncBNUwHfwsDz4=(59$MxVaCv%{+dDfz42>feqaF2a4|Q*e@rFMmLh9?F# zvwP4>S%Ty{pFWvS9u|55aVgJPG~KI$4W_@^XR(K7%1+phJ!|jg?PB8Rbh~a&KkfPI z>FntAG{~&N;$}wL2SLT~3BvbqUVpzTS#*#-!Ks*JBWEZ|udAji1$iKDiWb}OsDg)- zABcC^tUnd{Se}$#X>|sNdSk?W7M!iSw#@Pl8o!KO5)pYOl&_zGPX10ZgnlE`T$5y` zrmj=A*e5EuQNqtWUq6D(;+lX;)_%+LNXh4LqR4n^t6uwkLqe-;E( z`7wYs;0K1Wh1wPZSjiFapfuLr*>~zR(S&lJ&bJLuie$xk2TNNg3WbF&84B}D=0syC zLt1n!$2t35DXdpHGU{T5#>n>aohc(@1cBUNI}0abf6oUUvff#c^DD(FVm)q{`zw#! zuB1AfYi8F0A+nxHqgC_Kow8Re@PyulULcMribY9!UGLiJ%-XRk!&TzNgl5N>C!Z?9 zpdPjrl<7Q^Iomy!+w@N zT6FbKj0T=mr|Ae}^3%-vw24GoJ2?r?P-pB~Bu(vLGnYJ~rV`&)bZu_+2VY{fkNpi% z;-O)EjO+V{`3H;T{(cdzDILf{`vO_?8;-Axs4fMIwOe31E6C|T*Z_R2-$-OWah&ZZZJf^GMd zHTw7Og9G7FM6=suXT`-cGDn!H^0BS=2vFKh&rNV}EF$BnqI{Z#FAA=jv#6)t8u**X zxu11Cm}zaHd9=WD$uT3r`K=Y6yAtxA0ihAoY_gZCCq4BMbwhO~6zzjROx7 zu21GLX{f=68=roB<)c;pS!eUAy*h?PJ!xECAlymWZn04|YXeah(Fis#>}JVs@RX$w zM`yk5V94xQ7GCC|fIg~X9KADt;QI>mbk0CK{6-<2Zfr4Of+39Lk)7jp`#Rm>NM5|a zv)PFXiqCbdeo9A!iihy{)9(oSgw)&_xm@kGxbG#C9MWG!)m>KJp4T$KEhI}XIM2V; z-)03Zzi4QDZ@lxE)P(QBr(&r$M^ri{hk=t}#fyF}xYF$$7r_P@I^)9P)-*gYSbVMN zb4e7`=PURIc#<|YE$EGgOEB^MQ+c;x*q$Y4gMrgBgRqpq{sQ5~r**;{uYA1`d%Z!$ z+9z~i7E9E4^V``-_|^hm^S#+E?R%wOo0Mj*YxLp4>q)2I(*tkQ^P2^=b1%3Sm4k&z zt9@;7cQ3ZR-B1AtSB~l%Wwf2qj*to^7-@hXY%Cxs`{AZqm_rKiPhxpT=hd)w0wC9QD;<8t0KR zoX#TpKuLK3)QQD$Ss(t;XS|76s&a@s$!(4UaKp(HXqmNJBnW4?YHwuXSvjI?N-fE{ zU7k`hDqOF9P->37yCTvf$&a~#Zb(HqJlUph^Bi%v>T)SJejY=uj8bES#9sVqAdeyS^fK?n==2 z;216Q`Dt9bT#zfqX*Z57HH_Prmg#WsLkjwcZrn(;DDc|g#v>tsal51SenwDBowj@MROWyzTSG+)nDv&WXPjXx7q7h^kM?{d%OD{Bk`252p%z-kP(c)pERx ze|t?RLV$uf1%s|5sISi$uL;X;u7Pm4Hyz57An`M16Zm~_|2mJeBh48i3%FE832=$VFTTt`v3IfUt^_*fy|_0*rtY6d>A`Kf5Dt` z0jLPcMd!f2Ug_)0aTz4V3i5?Nizf3ewZgc%Rervn5qoYsGs7_<=2^)(0}+uLzX)C2 zsxh*OeaaoX?Bb^J=;Lo7G*oKXa{-wCVq)9ok)xZukPCEuF6GhX6YAdDCW#-=_xrPH z=y0#l&EsMzFp&WgzI|Xzq;(S_QFH$JGQzM^PzCb?_^ZwdD|m4DVJL>d7LLn&v0J4(3lMG2so~L05?I^vTpfl+R6Y4Rt-kyl6%ObK7h4gPQhq z9Cn`7FZEwAKg>8LgMUaAA!(`B{FyG4k-}vy3sF}Sb7o$E!#mqJ@;Z8A&TDFa=_WD^ zdRHZfg=>p3*SNVw)!=FVkcXE%w!5nT6EV>4QJ61}cD3UPKX^M92#%roq}RxM%BLzE zw{#!1Q+*d?#n{v38rUy?Fs*UX$=N1k5*>cFly%|nx^&sH{Sn$d)`FMB@If=xpLGSP zxy4*h=D`Vlusz5qNgoL+xsILW9qFFd(3vWryx3M2s52RCH#rcoWt+Lhdj%cjMM`~f z(Xq5VL>d`2UE{JrCB7!DPQ?K~+eUQ<DICV%_*2i}dno=MTNC@k4YXK<=47Jh^03ig{`RxMZm9`QqqFvk|CN=D^g$ymK zOPd9xx<<-HGeQR0i=cB*mUUao>-<FR zc!)8H;KETIy~RtrGBoe0ocRfdZdf%1JC5()(|7;crJPdt8;Iz5sb3mdpRuYBU}od- z0DrH3v|JH-$Rf8_%+5r(;TB$ruhPlJ2*;iuk^Go=Yu9&(4ebzu0vPUOwHi$;bWvCU zUe*f9!hZf~nbd&{Q2WRs42`(Rb)I#>jGI9G>&;upurS%ep^VONpjv2}?}*3esOsL+ zHtF@t)Yam_Hw++s;joEFc=SfMh>l zo+g`{{t6fF%O@2faA!CmEi=7Vcw5B z?R^i+fQSzqo=N*C83tj#6VP->`2RHb}5C2@z zX3lEzTc4v4M#9#?z-Nk8LXW+{x_)aNXxHQqh|Fu532HI{kL%r2o~-O`L`LvF`aqo9 z0r(K5xAw$Rm~2~^`rt!*I=f}94n{_PIm50eEqM_1y-&@C$oA}O<^%n2&E!YxwbjV+ zCgV$c4^&3co^$EtxP4>(b5Z9#@2AO&GtkhpC}*Nj*UwvWoRbMdTzcPqS3JOFb(>lz z_|w0E)W$Ld6KX79`QP;1sfxP1UwaGLB#591r?V>vdrl|?D)LM*;8R?C@_ay0o*MJ; z^fPV0+y3mwM}qfL9laLGrPt?6W;Q)MYL7Av7v>$4kZ_kUG5WvP zfT{EY4FSNui9=`_Eh!iVIyQdrnrdV{9Y7gxlc^?F&pKuezA7Xa=%#Lc^U2qK-qPs_A&(eHWtaN4P&YYky z*ZXs``g5=`EUKb@$MCGM6 zpul~Dlr1B{&?B;+yiARUQsvNB6X$&4X3jyHDs|NUWwcxI?8Va3RiUxU-<`LOiVqIE zZfNXKRunF8nR}hJPv#s|htDHKSF^QO6F~ufPLO&ypBhC$FWaE{jJ!7SA^q23dkpVu zaR4g{k^m$COd9P2Sx(WDH_Uvh<7IGL!u>rmwLmO<(3?ATwx-ti3VCgxg%;Dm>N>u^ zJbB1|Ot>%pRYm+qBy(%A-9iUq6;>}nxcy4}{d`skwHos)Nm9)kru(sx>t8A-V=vlX zHS^SxcC&>!U#OFJrW~S?&o{@EU1;$ovvw>b?F}+FFRdIYm)e>-9p|gNBpzZSO~BtwFc#?rUf#s?*Krt3_+ zNz9ZC?VcFl+O0DLT29CoPmYMy;SByy0i{E|?3B4*&6M?ImzlA35QJ~4=|jbw7teRs z<%@M=!%f$gUE=~LwQ6@6LvROT_I`=&Yq^5f*{n#>&*~YSWXpx>zTxM0ffW8{D_8KB zd&#Pa%=NT~dKDMhC$+S`dsIIn;egs0uvIgA`W6ssKP{^wrLx67LzT2iqV=6~hPpif zeth6;UAa#GgFp(CwtwGEajEKBes3`M$EvCGho^~4_do}yXELbWcE?c{3UDA-mpuo0 zTXvxds4@@iQsP@;yxj(gTr?O#x6TGJZOX~K-SyAi!Iv0(KQ)u)1J|gFmpflv--8Eg zDRthD`imHL4sVCA71<)ra&z0w%Ij^G8R+k#Ss#|!kGeC_MOF1tvyl-a;UXb$r;GEJQjh3{RUb=PRA4lJOB86h11{Kzd-;~Quq4_lCDPjWmT5FW> z3cCr+Sf~aIRwLOaR$ks16}{hN2$WAU5tTMes{FL06IO_KwBu(8(!n2EBQzgVpsA$JfQC6+i@v zJ{NvG=BeoT@H0E5TP0g{HP0>EK>%AkSN8_&jaOzTqhjt3{O6$~fFjhi^>G+%e3Q9T58k0N0of=4^o`GG3hgEcIx} z`uw{8Ii=)NTid%*D!mdofn#Lf6Xm?tUw2>DCP{%Fm<8kQzTLrxOuoY;{ zDgNbF3*b<=hN=Jvx5dCrjRo2+D3$)(G5F7$GXJ0dO1}&B3?lgE6u<=58i*)@BQMrL zGJyidO9Ut|$=}(+{wskAK~+G)?+his`xJi$mq^IV*!)A$`n%HgA3w)&Tlo`(nfJ!9 zZBnZG>HN^V=iXp)&Dx&G3H6}w2idCYjuTWyXS&lZ6DGH4)nCVSSp_$w^(z@Z6d>U_ zIhy0k;UzxG#O#OZw$D63SnrhMP9x)q5j^r`r$jxkf-mv}!0|Q`_PF)C0d(Qe3Jx{1 zB+@`>F4qFXJ|}2B-uO+?4w1)M+x-`zdzj!fWy!~n2&(?cVEzwAb9z<+l;qM4UZW?Y zRD&v^hRTc=YrM#VvPTUUrpq#p^pTVDqkE>>Gy?A@`nRWcg`;wP&zMN#fhrK-#QJK~ zJ0)y*+Fb57lV2>Ji%Xh~L**svq zg&$7df=&RGW?aG(HpUKiOXW-LS&G5BV_-=%ri2dRD+7d!!_t30Fn+NVuDS#4FFm^s zOgAgyAV)of_Ac2($7Zufw$l=o6Qk-*=FdCQTL+TJ)}a)NCaGYzk!xKw}^q1d81O z6#Mr|K)^Tnzqgt8gx&egeb?r`J>!+vr-1r3+GTu#Q30b@LAjw!XmR<_i zWHGcT$@md5!B(XicSC$h%@6(d`7r+$=VhwXRZyg@uWUzQohZss7h9jrVNrOlH+%V_w=|K*lNv{YmuCv+hP z;8oR%j9J7MVf$eq9N{W>RI&`BHqaKAWHM(S5H2;2;q27@h>eKGR1YSs1xhp@TVPZn!1>g;uzFm$2!gySvEP+9wUp z=vDx6Q}@_rgN}2md!hp1Njz5`Q^82EDaqKyZlJ)GTX2C6dU*r3Ft%@jL(YODP3@To z;~hIWgJBsg&lC&dcS5KXIeXooo)=}P-0kg$$*k zva{M+CBuk^jP>Z}Ywo$$YuG74^j01d8rdhPbsQl1sBgGY3MHk_LZItK(1jOKRe)Pu zL>+lW;2#V4kqG?y9M4lPv1YGdf{(|+`&l}oPh%+Us|BmEtuaO3gG`1c30i;JQ|)6n z#yPfRNu&D?Pp@@D6jvpzxw}m1tXCu=#q&3fo(;o`Yv7~%d##<@OnsYJjJi=v-@^461r{1cZL?z2 z47vcP=Nvtm_~QL+5VAhql=V)*yvX6sCl&CTGzx21QtSZySGd_Rr^$(3_czk@ydT>3 zdswVHnLeHMF(*KQr*IiSLwFn?Z3x;=WO3IsOfP{Ol%JW?z57H1B2S=ud&-kX-F|H2 z!6{X5*_^#uzbB9&^^(rbfZ}k08>JydVUi(pJ7xDg%(3eFFi+MpzZ1QqzoB<D8UMdqx_^HDziQqW*qjZmf$S!_8Vx2ojQ$=tZ6}=FojwVJ2qLYvR#*FoL*8F zDU(_7+M6Kt4UvNQ1-+y;6ef${^H}^#8$W>2O7fw^!>)(#B}qUYc_a28;yzf4E6A+#czQ*g;*H*pVhG0g2~{A%pI?XPmb$%} z4YIwf)yc{(6(8G6TKeG4u=8-<Y)EDn)6ckwC{ zl1aBRqCh}2AGOH=YPxBBg7Z@$0n{z5m=hqaI44pbTPsp{N9w(d!D(w30ZM3=bmq(k zt@tn;B9v^zfVb%sMOWIoALB1T7b{z;{0-sw-h9aH%cLV4_pP>KxVWz)Z>2K^K((%U z44P^~BP97+CLJjM1^!Xq-rOF?-$dB?S+g!*S3O}dCVPIvWkGaICY@F zXeg@kA0EW&*E~S*`aSS=4AQK;*t*U5=zbisE@KTy;{F-@{_mjK|C@mLe|P)e&uM91 zrrWDw%j{8+%wcmV&5{g^j$y@wn2(NU7%FuyFHtm$-R*@KogN`BzWeZ19Ag^ z#zAs={{t}hic{D?^$@0|?AqOnJ&qALGZ(Nm5fuSOHcKCIqht}t;>c6T5fYf7ATs_3 zF!aBpeabXzhf*-y(eZqK`uG&4_Z@u18Fh6IBusDopPl|tp5@Lb+j}3&Q&Crz;XGT# z%mrE5;xqB7$TQ15PBg1@@35V)ivJBn?GttTntD~w?e|X6l4>$%U9I58Zd#(-rThxO z_GvXeWke0SrX0MvRs@V+GSMzqVDujWd*v7nMNDtM-A1k>{Z@h9Ra|OwKyk?M2B>Ka z#|cpW-+CeT&*C~en+|F9DO1yupc{Y+5x54lw% z)06l+O+d5jZ9jSMYDiA;0YT-_L#S2eA?)X9Fhszn6KOHlS>PaaiVhv#nGy zcoUw3Y#Ka<$^F|R{Hawie*W8@LEuOjz8vWLNXzoRD)5}Zn_{I(?y`&PG3YkHQ1oo{ zpSuhHp%{1m7w7*wpr4;#EwDR>nVVTe?N_3!M+Q%x6rV;cIbLE)1ADN+$N(GEbjVD; zS-&$A!)>KBVh_B&WPH6d#;tzG5k3n9kF>X(Pk+8P9K5-a2mF^QVdbX_4*-u7n$^91 zc84h-9;{+7)=Yrm6DX(QAt)1f;n$aPc0IwzhwQg!kjT^yy@6zW#OWY*9{_aUCjv(p zaAV&B@sF+hH6Ea1pYt%hc+q(Dh(J4ayVAZpU7VSVp4P0L9AcDwh&|}<1sXo<%ecHq zL|*gsWDpOUdO8w^a?7VZBTq(CHB8P)xxey*IbJ{^{av{47$QG3H&9Pd^h2I(k=?!f zDV7gQRK-3=H_V>%^Mf7%D5?vPpW`wVx?d?h!}dpgC%N*x5|->uYz5cipT_&q*|VVb z>zbu$lULX7adkhYa8)&i)He-=vT-}&=^|v#ROu46`6?=C5(nBfRb=Uy1U5Lf#VC#c zYiS2BtPKLPa|*a5LCR+hf3zjHU+FsX&F}d65|SXre|K6|?9uJ7 zo2Y*^oQhTW5ZZ5`U&nyp{LxQi+{u~ukU!xv!4H8c(JJb%H``?1lbq`oApZS)y&<+r z?AhFeYu(ag2jl@y?*w44{{~uJN21=^pk|dcxgh14HSasq1*5doGpl_ORz;RB+%Aie z1Rbq>N)2^IUjC9VJ2J+9$f{-6pR)QzSOSP@vzJ#G-Q}JfV}n0>97<#vj{6}lcGe95 z0v}5Ci$HY#Fvz^&+{WGs2Z}^KQAA1HG9hASDcC?pwb0V`DFxQ6ob(-%tlZgr4c_ zo6|U2{%&#?8`OfoUMN+YeAsMDZrk1WC{R^x2(9J6cG(2CPbD}ke?&N%h?&0b;oeH@ zwR6~L|KG$U15*310i$7miVZ1lXwadX<4G-2YLJ=IvA{`h^wEswbOx&Om!!P zRl!vKH}dS_dXcF21@~#rBKabk#bpGgZ>BGAl1oJ zG!NQZZj{`A^B7>XD6q4|zts;Fr`}E3a)YclSIn_rwF~LIot&@3+7#yc4MY_OomAcw zBlDaDTT~>xwkSFfQFM8@FxUUYvo?-lID|Uh?P~qz?b;1E&4mDk{m%h3@>e7NV@ziJ z>Nr(RTt_u~YKg`%ErfhoMZ4wmPNxA(1K(wagG^lIU*ioJAAg9qU0T{7G?n~b4m7%| zZ?{S~!D-fp+j*?M0OnDDY3ZBxNqhLWcPQ0Gu|7m1jHsS}&fLJj_;V~R?F*a2bPNHd z_(DxH0cnl{GXCbtZ#cyu?7XeDCoEm0voWa`nX}llByU(U+~rD9It-AFgIeY&04{iU z@UO!EnkdGF@e18oP zk!?IaULZheIO~i0eHHlI%;nllJm$#LAOQCbT%De)<0ZNlW4_Ce*HviM={$s^?oLfK zz1hq%TE&zTliO^NoVfQw_6dO5@OXJsjFK4f^qB8*#IcjlL7+qE&uagiP@sQr$3NDw zpQnwh4WPd-iN9ta2$`a8T!+?`^hd0It8-C@J#p=saIM^bJDZB9=z$Xde2eXyNnl6t zk6E(vl*D0=dvkfzK@v8@zGrEHQ#4nBZ$5NQmcQ6!13>_M1=KP8RzYhx>%H-Klu$v? z?B7PpUvo;EWT5~^9*q(k%d7RMt~FcLb}8RJ;b|}^0{~c7=oWr=niy(=EW85F z^!05fFc?S5(SudcU7^2vO+Ot_gS72|D6c05ry%*iM#QhV%dDeRYMwdcMFMe{23)?t zf+2J$78Z3b^R;*~(OE}l)^N6Z%6`e#!ckI1_7)vvaBcagM)9|SUiWVD^g}8(c>_Lf zpP*rD<^4(LPIJ~_8HbCnH+GTn%edCMRghwQtloo?5iy;Gm(RO9bWAc-#VE`E96iHl z4Sxs-&wJaYyX%Ma6QS;?h`BbBbjlUNx{y-~(XId?b$FAH2xZ9+8LGXbD^uL2DhmvU zo%S0Ox*a|WO>3AF`d;f?H1Rg&3{cpb%XcqYE+GFuXtm(Qi3v9E^|Gxz0@&e zIcARttivN17W?(Ji3T1i#4hng zIrUxA1&Hr{(ge_wiFtk4QkP`BMm=&C^q-@ZsF`@btzW%IN_m%I#9wg#mr&BL7=K|r;d_RYkvtE%4XfxXO0dl zp*|Vl(~4=~?YccSbazSV56b%NmE;vC35Tqtpx2DCm_L@KDWs=UI52dP!dJ1mgKSvx z;%4GC*i6YCd!wB+g3uKn&RiEtauT$vDB;TW4Yo)C^pEza9H5rCO^X}(aPJ0J-luFc_Fx|M2-}YRJ&2$PnhY7P}uXh@;v?SLI)Wqnq z0pWkL55K5xU<*;hToG2u1sh0as;7z=OCnFVv_rYazQ;{pHh3C%L!$WzFF#tm9V{pf zLe2w0NpG0yC%Lyt;pDio_l;-t{YNEfaEqU@AL2F=QXJrOqfBrXhjRvzVxoCcGJmX3 zRXt=6h2uW$QcaZ~J^2#q%35G7>TT%xUd!Y~QRzMYo~LO*RJ7$9%o)8bnES)-?z7N6 zIJR^E2`%Q@^%Tq050vdVRb~3Y_rlsmcAQg&Mz%iXk=6+#w9GSdp^0{%*W{&&y%N{x!R#Q= z<*&yh4dQX`oX|_>aG44?JF*11RsDS6LY38-xn&Nz6tND;yW<@NO*K)zj zS7Sv=f^88AnYP`@wMC6BWB%~kz@6yWVc59M70S5_wv47=;JFlzd^?pF$th>DM#pV~ z)O`t#UKXEeOV`iSo)8~oVfBl$5X@^uBlhkInI+T6eA+aK4Ab{!$N`3UM+WzlAt~LN zgz8ZXk~JCQ;ph_KI|$1NO1+qlhxdZAlM++p#h@$+k$T-6`a^C#6z`!RBis_LhG6b< z^BMB5o8@}}gk^h8bdZ3sF#&}d2q8E`#F=J1gG#3 z0pQHMY|l3i+RG|l^ew7u>IEx-PmwQM9#fA|U73931{T&BF2xA4TbG!)CR`m58fku^ zeDL|Wmr{F@PIN}O?nWqP?dX0ao~74~Qka%&&~Z3^M85Lfz+Ew~=d_@pYUX?IkThy^ z*Vh+t5di*x<}ZLxpT7Wr2UrCB;OrMbN*0l314$k7Oit_T$qT-LmhMRDUH=S-2$ggT4KD5!vwBLT%U-6QGV zBdXbnh(%^<0<1g-^as)FRV5Or;~%c{&83O^6ux5DntAd}di12dWuO!b5N;y4#>|Z^ znBTHX3l{LA4Wcq+~Zl#3~)!kfXZjL6uYT5nR zrq#2HZi#d@@`mLVEXrVx<$5|=PZ@U$5?T>h19g_8cx3q8B+JU$EwS1A}Rej3>C)bY%_T@DWNB01kIDqCF>usznPd+W1u9a zp(Y)!I>4rldZR0b7p!mXN)|cxZRcMEa&R7bFo-s;x;Uc;6Pfpyev7VC$u~9@9Bs1~ z&VKHb&2s6k`8It7_?^6n3jyW}IoiI*ZM46ab{S`k!r?HKoN%c?mQzX-QiY4sJw||> z)g@>$SmA(xbx_vRRNfSK;82^r_(m$0R&sfdRveezk1lmx31YJ9PRwUad_WD5CSQ25 zM1VIO!&H~|x-l#hW)b5$b#buEe1?V%Fuz^1nHoPK1xkCS9vYvGfv$p9`TVERmQjen;DNIKI;{Dg&P}sg6WPiISQEYu? z)lT0iB+Kuqij!#F$becx2mYy8iS!Fbifj~>zid6EEtVMH-{rGwC}`5P$!|H%C$zf2 zj)pNZu(`ak<1iY|d%F>Hf|;MW*5|j4+FPIT%Ds$_A0NGJFA6G>ZqE}Duswq#g(Y9U zb8y{#`z&fb3^z3=L9X<~gkI_hkf)jgge+SBTsW^F7J8|ANC+znR_-#KNM12d8=G#M ztO8ci-V>8%$2brQAhe~Wkz$nY{W(!qIQQgJmZjczSf-u~qJ%h!aoJ;PWGE;4sD7x3 z@^!|tKrJOLTR{8jCgQG~@ziP3KM-}Pe~$sDL=q>YX|RSOf@5G$D*xU4`I?<>Cp(rKz?}EA47?N>SV&Bo zpU>m~G=E|1le#0}JzOHEWE7@tux;r$FHZUpO>LZ>(%Kr`9)?W5gwsHX1=lK?Dgw&! z_jQ_~?6DKn@0z$vj6L5#E#q9#RCbjvwcv+>38UvY*Q#flK;voY%{cJeR4`!^&8P8n zG2z&9WWYVS6P$J*b0W7c0DHeWgBN^%9Mx|Qxi&D8;ug@xrGj-NrP0c_!#Vx%QX?t< zc=f=oL;Gunou-w(sv(_>$hkz4MUXqWtwTCpX*IpZxyrb#5xWx!@o6_Xtm4`*UlrMb)NTncR07VnM|-SN=dgQ)bYwVz(><3zi< z{8Hv1N$xO7?FF14sW>ww6-MI}K$f?C>22V}6?zgwdnU$rk1HNTNDNHSf5?0Ajc!$dPOMJLU3a#4qV53zjSj#JZ?+d zjdMqvBFl88zfO|}@loPvMIRQbhgX8Th505|z}hHMV^VkmHQn$Rbo&(;ZAo{cpz7`# zY>RSQ0O^u`r+E=2Gy1~)PIC&AYX01!&)d&vp&hvtimVH)$fDhbK%XHyem@=K)y(3_ z9@E%?0MbUBVRQ3l4Tr$J~rn42TwVGOnisY_-ZYstg7b?ATMU*NT=BCT zU4_VOvfy@x{QQSSip`qred|l%n)Uq}eg*XWoU7ps&mH8wgDV@(<9VwphcW5`ds365 zZ>=2(Gae42gw~ppr|Q~W$D}`21CD3{Tr2t1TKPFyvOX3i`W)<(m$c58}Rrzb`;0H#1B|_K? z7u{huS;G>uS`3_0!z=JqiCl7A=&jahx=%-M^kQpcD6K1Y$g#P$@i#|`f*9=yOrFcV zr?E+iW~XFA+Gsu~F|kq&O28MeBNCnTAIchcr9ZWu22$|J1bR>Ods=Lnh_3n7d;t_o zJ$pluBd1h3=k@e}B5k(RSI4=StRfXFET%hNr6h-RPdMmUg89;-y~vBu9g)FC^)?gw zEMau^F`q#ffP*A}$sd6*AbPTK`dk?=xlmyUYs?>U(XP~wRGcPFOL~QV^i05t(lML1W$h2Mk1j*i} z*gIasyvr*gs4&$<@VMl1`U)G#)Q8Y~E|qPnaWBQ)ANJ=!Os8v98uJb1QfzeZf%1u3}#6PHb|-S_2zo%fc~dhWZx-oYo`9jEozvm=7^{=tIu4PSa~O#RoL2aP>rB z*>ZFe)34j~>}lla92AosVaQ62Cch_p94nvE6JDqHdx1f#=hIq~@WE4;*Um&aNW4Bvn%aIsnZPz*{xn(xtrA_l6ajDx-O*}wxCQl+^tQr? z>{8rz-|K`VsX+FUQv*JdH||J0wHw%vSz~&o9gsX=fZZjFXO(;%X(F)Wc%o$ytD#+$ zu1+k(CE^_OoUM1RHgT0dk0%w!vIu_0;!G+&5{}vR(`m+KWK0!BzzxOVMD-gg{$wDc zt_e+j`t?eKXyZm7#{|CXO5FN;HoWC>3zPO{gCUydD&jgjmR=0+@{kbc(K}?EBf8?wr<# zS{*U=6%WCiKbq~A6xkGsGpMM!_9W~0#>=YmWLW~#NeI@hx^TK%Ku<)b;Uv%0{zPSEkO3S)b==r z@o}WUk}EJNLe!{nHOADN6v*@=d69nG*vbvq8UtAM-@*ob8=P}+a%qL6IV&}Qu2u$= zDNzkwPx5Fr%#+e+ym$K*cb5aj%2fIFe{}o4D)L0h^@yP#y<&b01o6}TVtVaid(I&_ z*+K*ObAd`&&nfW_)&e5p(LlH=?)-S<+LS1b?L~YK&i#$*uav zXs%0&`M`qG*(DGO3bIJ}0>Dc&>SE>P-I$$(-G_A&om7-qtmq4UWqoN_4Y$UAnl}ad z7fJN@a3J9=0b7xVTT-g6gxwc=W#eAZ^_X=x@eHXX7snvXo=LU3#E!|2RH3?|)qy(w zTqdQgl#P^TB!!1ry(~axt919^FrzJM>3|7e#UbF|6zA|YlQc*x*Vwj3WzN+{LlyG5%1D9$KF+gcqt(va^(WL#`YA zU`#K$-Y>ZEi{@W230)$Hl~pC>Zr*+n#&u1NZH88jEeP0Ae0cX?nn*n_%r5-ll22#0 zArE$JM%HrMC*&9?|E_3e6>9v4$^1d0K(PfHm4DjofhVi8qv~X@!&0}y>>q1WXj1I? zv>(hL=y9?0>K&H>A~e+h4El1|`#*!j{0W-ouqpp&Bg^{*_UH%j=YM$r6;&7iEv@)J s8SuT&`SaGue*szjjPmN&FX5LB72EFF9ZhX#fBK literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat new file mode 100644 index 0000000000..743300b3b8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405V4 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1136 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 48 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PC14 SDCARD1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat new file mode 100644 index 0000000000..3c23f66955 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat @@ -0,0 +1,165 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405V4 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1136 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 48 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 5 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# SPI3 +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# Chip select pins +PC14 SDCARD1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PC15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 (DJI / VTX) +PA10 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV + +# USART2 (RCIN) +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 (CAM) +PC10 USART3_TX USART3 NODMA +PC11 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (Bluetooth) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 (ESC Telemetry) +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry +define DEFAULT_SERIAL5_BAUD 19200 + +# USART6 (GPS) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS +define DEFAULT_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Servos +PB14 CAMERA1 OUTPUT GPIO(70) LOW +define RELAY2_PIN_DEFAULT 70 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 25.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB6 TIM4_CH1 TIM4 PWM(1) GPIO(50) # M1 +PB7 TIM4_CH2 TIM4 PWM(2) GPIO(51) BIDIR # M2 +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) # M3 +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) # M5 +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6 +PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) # M7 +PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) # M8 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 + +PC13 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_SPL06_ENABLED 1 +BARO SPL06 I2C:0:0x76 + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +# SDCard +SPIDEV sdcard SPI3 DEVID1 SDCARD1_CS MODE0 400*KHZ 25*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_270 +DMA_NOSHARE TIM3_UP TIM8_UP TIM2_UP SPI1* +DMA_PRIORITY TIM3_UP TIM8_UP TIM2_UP SPI1* + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 + +# minimal drivers to reduce flash usage +include ../include/minimize_fpv_osd.inc + +define DEFAULT_NTF_LED_TYPES 257