From 7c3c3a0a4136937cfbe7bd493dab2a9d8bf21d21 Mon Sep 17 00:00:00 2001 From: auturgy Date: Thu, 7 Jan 2021 18:19:40 +1100 Subject: [PATCH] HAL_Chibios: support modalai_fc-v1 flight controller Based on M0018 version. Thanks to ModalAI for assistance --- .../hwdef/modalai_fc-v1/README.md | 68 +++++ .../modalai_fc-v1/fc-overlay-top-144-dpi.jpg | Bin 0 -> 146377 bytes .../hwdef/modalai_fc-v1/hwdef-bl.dat | 76 +++++ .../hwdef/modalai_fc-v1/hwdef.dat | 280 ++++++++++++++++++ 4 files changed, 424 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/fc-overlay-top-144-dpi.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md new file mode 100644 index 0000000000..85676e39a5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md @@ -0,0 +1,68 @@ +# ModalAI Flight Core v1 Controller + +The ModalAI FlightCore is a flight controller produced by [ModalAI](http://www.modalai.com/). + +## Features + + - STM32F765 microcontroller + - ICM42688 and ICM20602 IMUs + - BMP388 barometer + - microSD card slot + - 7 UARTs plus USB + - 8 PWM outputs + +## Pinout + +![ModalAI_v1 Board](fc-overlay-top-144-dpi.jpg "ModalAI_v1") + +For detailed pinout descriptions see [FlightCore Pinout](https://docs.modalai.com/flight-core-datasheets-connectors/) + +## 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 -> UART7 (Telem1) + - SERIAL2 -> UART5 (Telem2) + - SERIAL3 -> USART1 (GPS) + - SERIAL4 -> UART4 (GPS2) + - SERIAL5 -> USART2 + - SERIAL6 -> USART6 (spektrum RCIN) + - SERIAL7 -> USART3 + - SERIAL8 -> USB2 + +## RC Input + +RC input is configured on both the PPM input pin and the "spektrum" +USART6 UART. The PPM pin supports all one-way RC protocols. For +protocols requiring half-duplex serial to transmit telemetry (such as +FPort) you should use the spektrum port, mapped to SERIAL6. Both PPM +and spektrum ports are enabled for RCIN by default. + +## PWM Output + +The ModalAI_v1 supports up to 8 PWM outputs on the PWM output connector + +The PWM is in 2 groups: + + - PWM 1, 2, 3, 4 in group1 + - PWM 5, 6, 7, 8 in group2 + +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. + +## Power Monitoring + +In addition to the normal range of ArduPilot power monitoring options, +the modalAI build supports two I2C power monitors, the INA231 and the +LTC2946. The FlightCore board comes with the INA231 and you should set +BATTERY_MONITOR to 21. For the LTC2946 based power brick you should +set BATTERY_MONITOR to 22. + +## Compass + +The ModalAI_v1 does not have a built-in compass, but you can attach an +external compass + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/fc-overlay-top-144-dpi.jpg b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/fc-overlay-top-144-dpi.jpg new file mode 100644 index 0000000000000000000000000000000000000000..264a4d508a77ac72c8fc4814c69fc9f69e171fdf GIT binary patch literal 146377 zcmeFZcU+U(nl>DobdX*If`EV^AXRFDx@juXi2{NGih%T9Ly;;FihzO;qzFif(mP6# zCcT8-LazxmKnQR4Idk^xeag(4dB6GI`QwD&BFXbSNuIUV-LCt(*SZ+Lm>60 zkhqg&lMwL%h#81T7>F*~06@Zhk`evs0rVkY+l;hxw(6IdU^Z!hQ1C9kBE$l zPE2~6oRa$PeOh)-Zr-Q-g2K;be}`o%!#7cnU*2`Txn{URdvA~X^PQnIU( zml$vBkw0@`;*$!dV7`;^@#}X=erbI)i>2!z6{~>E!ZpmVUHend{<)5Y{I`1cTgU#r zUy}eD5+cInkuU(jfb|B+T)R2O3K;gDERc0`(w!~o{?UCg!6nmNNzpREG{F)m*h2OqSXrkx(K`xfa%B6fzPPG3&zlqGZY-h z1wCR}W7Z{yUjSN)F93zd9bl~d1z=0~0uc820${Kk2SvMF0LCF%da69o3jkF)K7Wqu z0x*xd0DQ^$<8PV=s{wp2063BUQ@Fp|1t1iLZ-HTr;D;bA;pfSL=V88N|GJZZjmf{{ zUtHX46$GmXU2fc*==ADj*F_YUuXN|>bo0`NPx z#|-_0!xJ44&Y}nZmDkhzD~E?r%??t&0Q~DteisD%YfJ#+|B{n`>CXQmd(wsHu$cO` zw;l+>xXxxLQ8tW_4mxhvQpH3cC<>FTZh|KjhJMV5AG}Rmw$c+VVxhq<1y2ddK!OHU zffhK%3qa!CkI<;m8fJk`7AO9o)pQ~Muow|Qxjf`kFt4g2jD zoXY$QseT@H4i7QjHz%I8z>nZc8uMB_$xD;SZI(sTAMQi1Zd9znW?o#fC0}%I#%==w z6x94J{4hElx0c>FXa_bQet!)<1+Wkx4rTwF>YWR~>wMFh&GU~E7XTJjptGI@+l0RX zrZ@N!kjbL@-0Rsbd^oLVn#8Z)F89l5@r_FMh}q|tIOrFp{_Wd+R>J~iyfxbTQnuYE zpQD_wHnv;>Z#8+s+d=|F2fmY9bA_ssG3)(<27%+$u|;{_bWC>95*|@(l9NTwK?k<< z&$dU-JhJGJ2BWWJ>^USnL^~bCtj>mhE*Sc`%}qAAwOs%z%u}s*ofdi(4#~Nw(?cxZ zfIbH9)0a-75lr6orkKDiC)xDXj9`%2-N;3r=tlB=m9An%z-}chW>#U0nxwe$t@e&gY7qbR-}DI0LR+I*uLDYhxwT6?aon;pbcelNDx+QUh=jdS!1#wPNhg*L9S z&@>n)IU^5Dakl4)1{`wJqvm1`s*RdbrVN9ejTd}_=2@bY7IeA3t%kyXPw>$Y#npDti?EzljnL5bdAt%)X{jS5q zc)r3HKr<@!$dOqVjAH^yj9XTW5A`z!SEfF##RT<;usY=#A*xkl)+PFT?XltoAgaQG zdi=cHWaL@->+_k_6}Pp|3RVX!t57D8%mmhGWk^Pnd*w^>jYJ;HD$oUB*2yunInRH% z*xn?wxj+S9;wL*Ze3)q5N1nwEIO5VJufe7s!CJe>!`*|vIg2A;7A~CdmANpVI0VM@ z$7vV%C5Cod7#cDV3E+VXQsT5q<)Q)QZUyGEwSGlCQR9bF-H-5}vLMz9>LLNR+X*M9 zhH+MlPp-cm-#mRw*V=z`xBXeL?5Hnzb+{7eH}GY{QQVklJo8K8U-LTa{C6cH(jnC(Ds&jNd@G zozg8qdS;cdjRYE9Er;K5*B^>BW*?}|TUu@~|~aU?CXM8Sui;YWkO z^$9~yV1FS&QH8Uke`}%x4U`x^3$%5DNf*Bzr>eYM(k)@|db)>2zK-MJYK1QObRY}H z6NVDI=E2Rg`V*F$@TD!`*70LM;J}e!wdg`Wm3O%j+Ov`;Ketc+c3VRAbtx}n?vA|; z(JhHf-W}SQ>WIZrnWM?TEwp6MT_F$fz%et?z~J9Vf|WO-EhUo?J-Sor?Z#dAoJn3v zfnbu7V5_QJ&~{kVpf~Wr8B6GmwB;cts?1-ghkrghnfKx!fOH*ud9fY4&dl@+95YG! zTuZ2ymfX-P^4+NpSX6P`G#<&@cPzE=%WNIg$RYvI-+nyuH*#o9u+_>IpS>lXyfGNQ z#v4L9AbBGAaHI9~sF)DX?|><>MGrBsi22b2q@V)mF~3tIQ(VC;>X2P!)3phN)j>@t zGcCSrZ_7X9JA4g^^p!Za=GlbzfJTpq%j&}QIW#+Yml#y3|Jst6i(%l4^)I!A!Ye4d zHymr~YVY>eB^(=G0Q}?5BWh9A*mRUN`qt|gO)-TdLLluA4t>`Ay9{eN@J=s8?2e;g zLv6~+3M9qnLqnoM*9#$mq|G!yOyW;1fut^>#%q6TyU4B3`-^lr^I{H;S0&^!B#C#1 zz37@}d191+t$6{#IU7fcM+pv}ZOfxd#0~r%!3o@v3Z$NVO>_uzEE{Tdz~d0Tjhn;V z7_nerRlch*A4ofJhMElmeawy~xY7UHRxYc<@Uo7VU|ByQte&rli?dLk61&>Juf?{{ zQ$s|BA{Q*dt8b+`!Ls_oB(>Q!6nHs*m3S1Mkv9LlNUH>yAx_SywNAmYvipc-~AoY+X*K*&|5 z;u5*3@w4EA?0W}PziHU-weA0_*Kv!BSMJ+7Itn~mh@$S?a%NHO5}IPcAll$u)83oy zjI)eg`QIKG>%tcvoG*eKW_0G2AQkw5Kruy&@DiMg{Z-Qp%^kSyl4^cFj`9mAx~1uP z7IC!j-?n;S_^d(=S|XaSfefzmArkQn*!KSH8`Q@a*5*~J7!5evnO(e6|FYC!>G9QM zk{=tc1Yzf&V!7r$w{@~O{Mp+M)r!<-tsQ>2c8li$jW6_@DgRox=)@nz1(9|EcnM{_ zvK@$QmD@dgL&jtV2t4>H4-A3h{Ej=AH`&r%*S=+9C z@f{vZ`d1%A(H~j(v_H~Ao`;cMd*fE&DJ~cKt$<{sn;=cUO4OfQF_hIFjD}(F8;_QeOqw)A zWrkt)VC`RoNtQ1Fv4NtXYna3K2Ay;<3Ay+f^dsQxt;Oj8X2=JFj7cp{4a>f^6iZhv zmGz20TR2EX2H&x1lc^}h>+-S`sz(we2*LM->(wUeAH`y~ER`a^Hr~DTLzO?F=SFf|0H zQJ`8rwJ!Z`+|k&TiGReAUnWofyZOTw2eF@=A}cw07VFZH9@JV6OZ>c=HJwK)8yPag zkh@g6_r5$Axa>-?t)+GoG>ElbL|`8%Q$H)zoGKmke}g#P_`rmXxrL*u+c-fUIUqSz zAdd!~TmZae?t3w2{>&A%+Teihrk#rXZs7hhfdAyP2=&yIgJQRRPZug=l0`zGOpZl$ zN87(0BaPBNj>?5=4G1Lmt1olvC8sQT^?Mksj~s6X5pB%MVP_WRsFhPZftXt(5Z(@w zU}l^1{3V-ln>m&RkN~zBCBY~Yd73^xS$*FRI78#h3Y5e>6n&i?#PU9)M~Rg%I|_n{ ze>RjPZnrV1kqy$k4!}osmAY=rqB}9?y30Dt<~p0b@&fP~ z-qI9EusjFDvZk~zT9mfscCOSvzGVE!>?UZoW3mL<7D$izQ9U1ff7@5PkKa;x(^et+ z*;*@d+EsK@f*5kHAD*2j&$yxi8~?5}{~j0ovz7|`tJ$DO z;3=V9R|lH633Sap0fZ_7{MYvJzdu*MDaSvW+X4y4#O{{G9i3WIZTYzAygq1(7LSd2g`Z_YHw+QxxHBp^lPZC|VHGV@-Y_Hq{?i*wn*qVsA@Cvg30SX>w@ba>iA_?9mE=e(-t2UX2Y@CN zaH2_@#>o$#=f1M(FKWJ?GJIH(JyB<+8el`R7*BK$i6; zUhGG|XT`nGb0;U?nA%7>CTod9LSq<$*C7oL#FQ=23;uVH^k|nv8+cIkm8mKn`e3TC z=t4F&eOCQ_HYMY_={-*2?E2U{gejmyEzmVglD9PqJ{b?+(fRsQ#rWZ+z}N~r%aMvd zCFzi3gM7H#hgG0WFV9BJr90Y zaXrf!c)5>#IdEnj-l0%}czwi~RaZO0m%%p-9sOBayZ?wL#@9+E-~u4lG19~ZzwA>i zM!WhRuGHfs3Pl|I9-rH%xrVgqq;Z}3jE5to>uS?6mSdC^jiQE<6gwYIUeQ0v^Llzt zzmE__Jj5bCZ9F_WO*bn(eW}DB3*ph?FFfp1#Ivl(B7^Y6V;6w2_8}}`fJ<9dOPa|o zxTSy8aqnzVIDPaa7$ombT=}D9*&M0aZ#~DaqcxB+M900q2jo7mjvkZ^x^D5Z%Tay7 z)6@Cg3&4cva8U>J<_ zKv{4x^i<4lu4VUx`x#+GrJy2(7&g2{ug)eA|Hfp&Vi$n}7s7E3C)^Pc2VkOcbJOVy zz^isIw`9rOeeqGpIbo6yr=#>S;63JH@aCHfz?#wOsTVFx47^zeUAxmrf}+QT$@HHt zUI0#6o^O4S)OFOJJxl7bEqUM+KB;U{9X(ijSy?XOeRpP9FcH)M-cpIP!q7uP+itO% z7=5d%u5{zzleOHEw{)fF=*-9QkeullsNmjS00v^6eY=F7j8G~Ft~|H^%&8+1WnJ`F zA$s>Q+;2ba_*Ovd3CbG5=H$T`P&a-{MDnct$v4=8(9lC!l*a}kmEtq#k?d682t8mj z*E4!;mMmgmD%i}>sy?8n#xniVtND^dEUevud6iOHi-i8k;1^)2=#~gJf1z9ocMrW_ z-s}_^c%>FmS@7Qq{BmDV<-H36bO}|8dGB^Kb5%uU2oSfd<1T*J4ac6k;B3wlaQv8qj+DQX%VI$+AQL zi~Qa2dcI?I?(YO)IAlps0|b1ZpJN^O9&YtKZH$^~UQT0l9q0t@!PopkXq}Lq78J^^ zv$Pn0Tes^^L~xOg!OBHK1I@d-T{{Y{DpoqSGHKs$;tgTUyqW--RiUjevd8=QWOUl z@-7D0ni2>cbpV%_JYaRZeSY-Rn#Qe%X}sjQ$e;xS! ze9D%$rhaHT&g~#+MAS3x4X1Sfu+3eXuxRnsiST%y`2-5Fe{8H*N%OhssdAzgd83!P zVr6|LTG=y=<|a4yWsbC4(^Eu!8kW*s3POhn{*j8aSW&&q?q#a`)XBVYO{j5XkvFZQ z7>H{_YD1)Dpcui}jN6~+Q;F)|+*B7A7ngloT3TG^A7VF_+z-r-79E!RQ#5%7`|fCs z7K+HIt9t)R2gQhNO+L1X5Hsm$In~aIkzv(s)2Pb=4h6}q{T4Jw15ltFld`)l{g;1f zG#Y@79=bj&CYx`|u*xTS!HREl7%M1%!dS z6IJ=#JiSo6T}kdi@@OoAWsNNj8twEn?uT0R?>f+QgZkKXKZMd*IL;a4-pTRwwUo^+3_nbzoB;CA~= z*&A;Hj`;Iu0`fiQM7tGwmDG_Q+{F9aCLZ6TI$H}lAUv-j1Sd!B_jvE?5jDN^*|>k8 zX>$pryhPpAeaOz_=!=P-q z%@+wJ3l@^8&uAz~gp!gD5W=N7t%1s;4Y!<*9{mDgeSgjJ9WXw#UULa5vfMUYDE`=h zkY-JgnMsoavD!i++IoG*_O3PD{3711dczsOb558#%)z<~Dnk#&Tj22^bVkn*pEWl2 z5o7hZuG+iAp`?VG#^+6{$Egi$s7A;$VPfWuG*{w7Em>yU5swVJ=t+~7X#eS-U-O}z z`os8oA^dC60np70K&Ju0-INk??;jx_T19Uwy9wS>{~qpZ%{A5^rECze_oQrb}7^?MD1Rgf#%UDD8nhab7~qphnFLf#Zm3F;V=UIz2pgF8Unjl;@% zo|{hmQ#1F5e_4ASTC;>0VN?et_q5)Ke~@%%D^dM>!pM9fH$~}2|6*UQ6LE)&ldWsF zKd6I~0y2+pwW(-Y~R2x0YwRMAT2vn1SR zhkX`?EvC|mi8Ss=b7+QcIfO;z{h@+D(xGhs=t4ms*KlFOy9L(LIbDLz7nE0F)m|W* zS==c)&<}^;+5EQ-5M}l&78CvIw*n=bM>C|kV@uoR*99U7+RF{WZLWX*Z>1>g>wd)S zeAl~uqivqZf&q(aOTTI$betK z$Uk)6;R+xULL*}Tg8nDbr6I~%rGg)jm!_qpcPZ<$4mt}zjPNas#iy6mOTH|zV0?*E zMebCzf9T_#I%}zSOQszb8Y`HX)Pef2lvFqf41F;);t&|*DAaiWigLy*Bzj%hVnGg_ zH(DX)E#83bS<)zXq>~&OW68+)@zIARFIW4PZ+0W!+yVgOx=8Cs)yQ3^=3`O#M2=HEFWm;qhW0(E;y)>|0598}Uay`i6@$NeXqs z*>%)ZXY})gl+{!_kp4zqruMO?_2fgXrMD!uU?UN?%{1&@WAl;Y7>yzxk)!0FDz{1C zV5Vb3VXi>JEM(E={6b_^7so+>^FUxZ!*1U`J6?p@3;-jxI9vkKP=Nj_O&YEo|0n^%K-qu zc365>b97fm<(|?RhnzN#2LILI4T>F+SZ0Hd4?mdkRXoj3EK`xjvu4B&@o#{*!fgkf z&ql)os>L-n9|a0yLkqm)#wRq0A5Sn+tH;*Dx!<^SREff}v)L7Irb@-N7%pbC5D-8j z;a?UljLMeW9OIajM|RDzG$$4_K~39%=8!#B@gF=>!ahed=y)x1WhKAGE3ezq-b7|~u6EyXg|haa?}@f3b1c|5b9iU>t5?#Hmekp*c1B-4euw8) z(IROKDEYL0H2LtoL;i$1e^phKWfb{yyNJ+Uae%6>}hr%T?9V@B6|J1uNiq*7Mx>N{0-QY?uAE<@*d zfkm7LCaS~*MgYJ~!1n#WKPtZmX@BQ6kJ6dOlL~XP;cW;EtgAn}pohhE;)+&8PBo6+ z8iTG3UcstOg&s~2;Gyik$De3wmI<8r1t4Jzc#0C*D>X;m9}yGFsjdA|7e4!dG)42V zQJK_D&F`qR4G3Iz8m0Bl9)K@J z+rL^|&(_VhXogD*(>DQ*QE3Y}A=G1KQ5uXOoTW3lb;oA1HRdT7=g#4yiVHyGEPcSk zslM=?L5o+fR;lK#3%Tjk6*h<0A6q(c+!2=xvA5WKrlX!*p==i|jL;ny9SEd+Qi*7f z<)yE`nI?G3{th-mwZE|)$RK*F-GV-BbM-5ZSW<@Q$ms7(U@IUB5seTNmpPl*+F5*A%A1grBF9xk5<-u%@JB}CoUxXt6*`M0jB_4a zTKIHgx)-YQ&Prdn15}TeNLKz30{$f&OzRs$={AP+4GE?!`moC9==Dg-0|I4f1NhP4 zg*WSxLeZ7=0o7&sr_6K;VHC@qTW#(K{{XqR4R-$xWD3 zPo8fOt-r;ZMDxvDAU2gA?Zs_6+99%;0@JMJpbJ3CXBC&@X0XZ0MiT+)np0ym=6&i? z9Nb!NigZr+#VUBy_*Fa!z5v+l9c0mG7UcIZ$3H;#Ug;2#glG_`v<(UsTB$!~6EnNJ zSM{4hy1U6USG*{hHKiWIR7F-o7tRgZCUboq6Kt-H_7H;aIA*91OpRxysQ_z({@nU4 zC3|P7!>gpTCJ_a^p?dgef5100f80ft6~u~Diuh(i#I%(Psc(JqvmxvtRwwIR2lQ_D zFGKkI=aW>FPRr^5;sr)7_L6&1#EcsiJ@&|L4md5eC&Vpjp=}@-E*dEi;yv^zSHCna ztBB+~DG$MUl4LiQFFJiYD-qW^gj2O3S;-~DqL*_+NAf)_9CPNXqY^?x$Ntz;;nFuP zJd|TNhr%~1g5zb^c|2M%%>1M2r*t}b06p|^L?w{f-t+WfDpAS`0hJJ`?fmp3+O)9t z=KnqhqCk&uYG-nH^t&jqOKbXmJ=!9FN@j!xww?=pGtrsYO6_ZSOJ6aoxUdWg9n^S+ z>z5t-qtp6NMELjOPM#DvFm`Ek;U`3-RxWk0Qztvw8vm+tuQ#9(RYKdKG4Eibr8aZp zsCQYS_|3i$UOBtzDsO1$_dhXE^e=0_@+e~Mtyp5Zj@}tdhs*O=ijNVJ@F?`>Kw>l~ zCu?JG!xxcEmHQwvxRoojSaY6+<~hhMHPyb_3<&CHhxsC1#kG3qbi9 zrIevcpRq4pIl3C6t#6PQ`J&uQjKh}rE$IR8sUJj(wirm)K<>poI;3*mY57s969SO% zr^`JLDEcXe(?giFT#bMp%6(jHH`ku21$hszc1anR`V8Z4!JS+zIc|i@|PUr z`^i3bT}w$rI(MiDS>xV2jiU1^!425L=i<|EGzCAL`G5pCwOgtU)IANk% zezo9~|MLRS3l;$!cmH1K{|m1{zoy`O3Fcc*^Alm;|q`}{^kAIJm z{11<&~b7XbSWifS@1v0@A5UV2$Xg2nM~A|&xj)cgsY(c~@T zs_Sf#GBpxbYcHxmhC#l`3Iv}l}>_z-BEc^xhUlGls z;h2sV1RZw9+%Gb)qcCA_b}ESd)QOubz~_K32&9nR$kc8@*6?H@-{)$%V#&KD9qYVt z`lF;>`d0qghQmRWrxr`{$U<^B1?T`U`KLM0=TnX=5-I2s47#G`D-;$;?Ooqi znyCH4y-2z%^YES|a4UZn97o>hfd^sPoE8XzPtfum~CpWstMnj6ixRrek7=h>5RDgHYSArlQ6N#Kaf!QIZl5`^lB_h z%EB}t^8&zbI^};O^LzcxQ#>go#2Y>jej{_sM`nEZQ3Y3c^~rORSt&R8@qNfBp%muZ zu_wfsjn>J>LAIjjI44ai29&k03z|RWrCwJHx!Yvh(aYb#)3NoH} zp&^_142yAlY#z>3Wf7zy^m?k7U<oOLta9xi@oR+R`@2{Cf#|uI_d5;c1Uk5@zDjQ&el(mD;0-!llhGyb#9zbm zqqvEd5@&zfRlVs<=~;Q@*Ku5aK)z}2qtY-|E_3U07fsP|qMAtS25rEx;qF0(l2N2u z!TM2k0&Jls%o>&0cKm)&@8qlsqc9Yl~=M&}xLmJEyRymlcLx_#S89(qm{`g>XQx&K) zsLC63yHkbskF<@kI%2_r+=BefRHLlHQnKl#Va=(W6qv;1K$kpy7Dt6$ozDo{cl+<&e6@RO@^#+AeWs% zFQ)^LJcQI)gfF($bnp;N?wuI`+H_|d(+^3!$}hkCMCapts4CEH&`g66Ch@4D5Y)MQ zWu=Aozd8W_nGf{pKLX-3?6%kbBW8~z4BKIQ)E~yVL6n$~n=|z)y5rzdlM-psC2~@( zPzx9DzTs^=IkLnhNgS?-K=#O=yI9calFv>C3^WakId*6*XldXmNY3qg-N1A^_!;zS zYx%0s*5!|&Jj3hfYVIR{Q%m@FYFvp3#XG>}rBp&lVBvfLkT$=KCdc1)XImUlZd9AN z;;CdAM&89P6sER~>-SFsY&G%WtVjJVpAR4GNpFTOd4+NAUbFBa6*#IfVo}YPz7-xcG~=U)h++5`5f0NPr@H_g4#4Wb6I`dL zyZ}mjd#C62ES1F!-<=r4;)F*;3b=!~g-O1FuKH6%JVbA?%`)AO+7aV#AEBF?o%axL z-lpG)%gN`5lk$e#X6GXSN(3J^6|LXjwk!8F>)qC&XO9-cqG-|vw5|jBahIS|;)9UG z05*dGS@JKV#h)tb9)9hv={zL=$b*Xh_`6h*evlS`CTV~QaBsJX9VgR>St%BHZyl-@ z+&tu{`h&odzsM{O@S_VLS_|ayryV&w;T!SSOkAI|q4~m4<g)mm zcqgQFRtQeXYx~;Qim<{Y=q#GFe-NR8(y+9s?iCOoM`NkJnR^8c=6=w&x*GSW+>l-=QzUzEOJ_o?Tej>N9AGB zZgp+ci>OAUAYQzB(2c*Nl)ou1Bn4-SC9Ef>bPPQ&%D-FxXm}u*N+DA`Po;B-P~?cv zCqVUUXrUNK9R1>(0OL8gR($CSz-6UPhktY0FWACn-8bV?dES(rG1HB)YRM=*j~)6w z&`i-vbDRY|cmX&@A6e1q^2ws>Y)P+;iAQJ9G*M+wMWo{!JQ6y78jr5Zm%AYWl#A<# z`~+@2a5|^ncuBJE`!{1#yzOLKHXws+YD}_|pbAa#+{*GDAWQGrQ~@!FZBMffGF2!K zk&>QTAAhz$Ct;!Z&^jADSqENr37N`S9kV-$U!gRgkm3u!dGD9zkyH2uz{oINqf*oB zEpKQDyq~PXqSkyxowW;`BfkKc*FF6Tp!|Mt^eH=yDg9x` zAQ1i5`?v1PG!x$We}Fo!6EHgB*FH6QxA~kvNM=(>xMK7=C0_PtTVd#;WJ2UCV^wDA zM5aFqp?g8ArbDl$uZuh9Z&dh2OmNla#i6A(*T=s8ocU3i zvx1naZ3vyH@zfmZa2sYUdpbAi&#J4O` zIIirIuzyM(iFlHqy~>X%sWkPg_jaVqc$wJO^kRM@!Dn|ptxqS_O|5WDtH}0C)r1GN zp_BUi+jtM&=5ooCkR1{p>H44SxP7x{qYa8BDSOJxN)HY8KPul{u(vdN5w83pp#lZI z*D;l&^P+EXSIkOv*Nv)h?S2rgsz=H7z@vO?P&GAPHrTdgJuO?aO24>15KWSwr#p&x zUZ$2PKiVbF8*M(VK=;*S=4u?9(O03#1@Mnd*;uhSHvMv;Ne_bf?0;OO9=rgEJ0IZZ zv%ySe;a;Yuj_rN^$uV2^k%}3&cG*Up?Ew!CTDvLx_?N1j$>JgT|CL{*b)1o z!mLNoZnI7(YL-q#?N7f%-_cWV+r%lQ=E59%)LElJN?4-hqx0=L|C>dVinxMitJD;E zVCxgMcIf4%{P}*~cH)&4xo#RBX)}qIjN29c9OobJ*lZ0+^bdb9j?Q*jxz?U^B^ifnEP9&8@?C#=y5uWeRnP+4qYzi3Vam@+Tp z5=NA(qAr>=h!ZQqsl}<-{D566O%fL#^jT{MF!a1FYK_78}v1w$bvuHE?HYlCTy-sV25JweT#WBMaZN& zKydb5hfdVsR;`DHR?KPnulL{da76hOzdcM8+%WVqzzcY3yJfY0dfa1W!+qdIAy64N zd2^eOA)|FNubyU&?C?DYn=UXn1XgWAf8t9JRjL(h48v>MS+)^o=NtxM^235v%-fso zE6oueJn}0nsKcChbOm#d5vB#?W4ATy!jjIX>fH|Fp|MX*v7fHg82x~GGao&F*!*Dh zH8Mxv?UN2C(T4>eaE8Roke}nXj;s{wgRI7G<7H^?bRN`KUjUjzarQLW*Ees-bWL#^ z60}3KEu}6q>y>u#7?P@f)Qsk`;ymoZz^BabRvr>10)0INSIEg<1uf=jStTiPn{s=8 z7~{!K$Xgf5V%2>V9CKLYt1c-Hp1@aX1?Q_V8(jXgi*;*~z*I%eXWZIOYwUzP^-uRc zNwHchI@ci?3%cd#__Vw#ab@M@LdZ2SfyA3ex{8T9w=KZ_>ezh&ykpY*@k`XQ^+;sv zt#eoM{Id@D0}q4>=D6+Lsl!W9VS3WmZX)`J;7Pz6_@dK*Cvhc+8^=A`@M6$n&T05S z-)&V2zvr^fuF^cI>}!(;aKZDS`>IjeHe0?=8d4$RUOl4lWFqDAuj{z}T0{Ye$De-? z$G~Z>Q*{A&+|ld4x!2|w+2MpR*!}>qSlFdq2eA$%JsjK`nw;^GU;c0b@PQeFRw`fq z1#Xatnxn^J7yTr@Zko8W#m8*#v#s3SC{{4op+K->gtq46hIAH6EPDDy?fs?5za;qJ zM$YZ$2*uK|l}@h%6$Zyo>d4w#=wLQc-*Ie0`z$}r*3v4|-_{N7K7BTF-*H1@MRb?2 z`e;6KOF~dSddLg(h66lQEwdXjD>3?5EkFEFj&^W%CP(LN{R`OS%rP2p0#iNDXwdNQ zJ{{dIeNXRxceUq)gfR0wvRh3ISc3%%@^`D1WoJgGZbv;0N}(G$*?1Dr;nd*o!rp(h zmh?Y9{y$Ejk-zizMPAXuI*AqQR6V)pUWF>{d(y1dfum~DL3o|#A>P=5fWxgWTm}zY zkuFBSQ%c-s%bzneB`R#Kr>T*GDco{IqHXmb*o?mQDJ48kUI!9Fhb74ZLcMa`ujR1e zf<<{+eM;FcPORL0mPae9yxdIs>R*Jb$08M4NkXI#nN6m&{XAGo8eV99a*hnG6#^KS ze&v$(p2aIgDHj0s60DQXK3gk*gAm&2D%gC6gkjW{hbF?~(ltw|pShv{Fh7RoL|jvpsEtdyRt#?aYrv;q$_lVWG~xu9Pf#Mj0UmgxVT_lve5RA{-Y7BSbg^ zi)}K3)ybPuMxM5Jhd8Kec5zT?UQ6E$0!!a*+glj56%X!z=_dW|&9_XUG@z`zPs^!- zkyB^9J>y>YrcSNBUyl#(d*9sX+oc3yU-XI;8s%9WT6kJTe^w8@t~rGtW4x3JSevlwHU_TVF|T@@MFk}fyh_i3_1c0Ag%*zsKQ8lm zuXqDKaJD}U$%C{8a$+v!%=a@*ZKMR})KDxO7&g7qYHUhqP$`BR)Mv1YQ@9ZcU_Hfmn6>Z-2Bto)LI;N*5`U-E@$0KEGJWPZA z+{=CrUZrMN77rjVc|39$x&8G;yl4x38#HLtz$Oy*WSEPagBO8b%i z@`HIm^fK+(*;AkD6gpO-twu`xk-f>$%R{9*n@$WPBaY6Y%QZT?`G?$vr}ZZQ9A}HqjIg3d62g=xAN(w02u{Nt*DkZEN_4+?87l^4=I>3~ zd43`k=R>FyOIHVs-7yV}75X{+AFsYe8^TPM6V;H zs%}->ofwpeuVuqAwRCyr>J{{GFKt1py8fMjWxk3)K67dZvYQXhb(=B|2L$t9?GS$< z#e6H}N6{@Tcym08F)NTiW=I}4#fKF}js^E&4pZEnO=$1BSO#7JBY*kmyduO)<$vChoJ3+9ZM zE}yA;YUKQ$e|EL=w8HTPe}?BS=jGSEC!p>cKPh&fOixC!4o?VZ2)56v3te%E2UYrXcFG&^ zD+fm}ANoZ+G5^6EsC6Tc3s&O3kW&&PdhhhZ>!Z~UAcuPi=h8`?XTqy$rVgCg7jdE^ z@ozx8V_ys~oZzeoK&rCy#o}Z4Z-Xfts_y;!FXDL^o!ypDAOy{H4V}^racZv z>OLNn;>jjV`;Jo_yot=jbiSD%jGDtB(zE`O1Eu0Ni9VUEVgjX)(^nmH_w2pen)gID zfrqGD_#pcXtQui~Ymq7ehR_mfXe%YTa}#pEHn{RNI8v2;>Et~mg+zOsO!!MI_CnPX zwcfki5)FsrXfUSFv zlCy!IoGa0~7I}2a#sc4770F1_P|cg7<4jezW7~x3GEEL0SvtpMS5cl15)1KGy};nY zgJyX9m{?81(PLFyyU%vmL6RA%)o#1*rAQ5&fTCAHWjt`GPPlvPNA9cGMtwuYAXxkY z5h&S7gPjTb4O;Tt?rDbWL$^I~mAbL2xSN7N!p0sZTc+>Q-1XFSL!$FOZ%hV8V#ouHaT#o`a^_+5!FXSK-N>D$&~;4GQhvi zM*c_d|Hm_xAgl9Sj^+jBVF*_J-Rl7V3Gg>a9HbgQloFH4H?Rv0H`Ry?&?D^QRUVD` zmEg(^P7vp}WplkmmO5gSpvr*E^#>BFI)3C3LN7wu!bhY2s6ftO_bKY_E84+V@3dIi zQgG0)*(z!9hxRu&0x1saYp#t*tc0P$2CdXR_Rxr z?psSgTT_8s1V>;FH&3p|P`8=5n;7!24R%-DbYPO=`W&{Fb*!*-4yv?h&%A-TR4$O> z>k+&CDGj8{$Vx9va2TlIEif07Ru1mx#F6Ny6dCVf6ZJOG+Hm;w=U&6l+YYHGCs9H| zJ}d><(Yvx#N8pLZbUah97WDOcoDQ-VhST<5_JeLAU-mDGxgKLJD>PxFbKtY9|74N$ z2@*Be+Fxb{WVdz3FTS8IP!HWvnAbW`p>LvhGh6-c6bVH~ZO%<7#!R^f-2V2$s*Ul0 zev2M}C$9|9_OWp)c&uaNMb+z|$i5u=A zy)TcxIh4?H>X)WHPAMV5I0oL;^c8dCOkSOsPdQqC_nD@gZZs5Ozs(U}jCDi^dNX@F zwH?)+H>5BnOFzvaA*_#NL$dTLe(39*yjfP;ZU+*|JT^Fc6!3-+a{~NEV6ifC# zYzJlZ3(AvBRv_?PUy&c>+`@*IPV&fiHMYq8kuTraX0LaVim=LQ)2`6Rocm)|HE-LdeT{!6GRH=V z#(2p#D%8~HP`0M4yD7d1Pg%4ze&#|&FGU1P&*zQHLd7YLNSo%hp673sQ6^~J47#Tk z7p4@vxqfdFp7i;?SQ-bfA>X`^8P6?=q0f)jQyHIVxjQbUkr~`Dh`9DPZqCe8nR7d) zF?*%9-%*>!eumm`EHCl!=_8bAJOC9uVAmTEFtM!r9MxsAVEsf8gyS zwDjkFlpbxx^SF``)T^yPy!2qL(gzt)JIO9c)Sc9EzOR#Y`oSseeRwmm#A6a(oFTGk zJ&+Tk6rBS4)R5Fl$JEaGScP`P4$4Y$iX5)h}%Ti?Uy!;D(N#@rXS3C$kk{ zSdI@+EgfXg1ys!Y;468($I9n9wmH&h+dO++^;wz% z!>^Upg(k=G@9qUbG25yDKJeD^+1X5U4YilXv)uE3*OFXE)__4-QleD`=Hrsxw{3^P zt*0Ey!{451i0B;$bFrPsnbRWTIN*J)1nPHpDZ0rKo1%(Xx@&hV9|FFP`ez|qP%f?- z`{o|PtO|Co>xN2<&|2R#uyv_aB~(SMbym9)yZxFps$q*PZWThltcZcT!Yn1>wk*>0 zSG=STnDDFqe_q8OnDm;seTNuYT)hGb+#Ywy%HN=4z8k-4;WD z7QT9FLNT#UABHTW84W6kf4zHma;kuI1%jzw?%VK`+Ueidp~3hD)h>q<^*RDIO}c^| zCuuFuo!wxr;^Ku(L{2 zW5MGT9MpU7<0Ir`sj`jp7J5u7Qonq3Iq2@HDe-+&3_Q>}$mXUh(dq)D@JANfueSJM zk9+)fkNuLA_L*zf>rqcAP_h~i&^qR^4Cdv>b6*_=!~8%iQ;pz`56G0{dOagOdJ$h0 z1irmtqRdC%M_MSduih5NH&&{8cLuUH@`?*q-h6-i)1zm5 zPjJmfr!B#tE7mykOGXsJeVxRmGEg)VJXkQHM}IrbyXzz7INvpQZsYwi?yk-N76LdO z_Yy627AH+0VoUx5A_{)v>M^c|xDDr|+!b(5q0K>M!ezL6B`_$77LyoCcbLxZ0utx} zY-CQz><&aj9`-^*c=UW{`}FqvI>hgehZ580sZ-+*2glb1kAb}G$G<#Hw3M$Zav2LR zo=D~bj3V)6Xemild|hI^FiwQSyrGdw z1Y@Tecu~fdPNQ%&-LSPZ#0AC+a_-{ZGd{{Q-4CKXRi z(B2Y%4RJ7-59FqkquoucCZ?lXUJRm>Z^*&x@QXZu@JKh2M^8iYT+ zqZR{&2!ch$_2(WEBSh1=sJtwvg122t(`%$7xB`< zY#}D~mykHG8hfpGK&N>R%F}>Pcl4JizLkT&D;IfRv%uCSWf)uDFV`bnzo^8lbV5`Wi4@J z>`Yof4y6qEm_Gx^$J5zhhE3D9fRiL$oL9M8hRol$Qi2VdA*o1AzeiNhig+6%|MIDWPDHirHeB(Pl)VM)0ZbNl`W-dNRd>%Bd_17B&sh#qi zc7xGf@tNTowZ`yvR-|i3615b{j;m2=mOWU#$jvNS?M%nzQiZW8u8Bjv7>$Q5-UlAc zG`tc#h==lC?Iqnoa)MCqGA>XSu<7Hq1(*j*Y976FfUr^1C((R8(&TdY;k7u{(Zw8q zRV**$Ne%$Fyo0~d0AHdC`!I2Cbvx5t`CW* zIASh5>=E*FcK={ck1mbBI~;iAp9od0bO~{;n(NzI5csI@Fv46;(5X8m zRwd&Jw~)iLkBwnQbiYX#8C08?YkS5q|A}>Dx+nntYuqUCOkTJ z#Z8X*H}@%F(2(Ag{1Q@7Iv}YeKuFtX;emL=zwI7Eim(W`iT{`H8IasIf4EbZ$Cg1Y z{U3^5!K^vB)|cguI8$_97;|&V0%Sx;LA$3o*{e%1!|&3nKK2npzV{)e2&Vwrj^ZnK zC)96N-TAl!KYPl5^xxY39)s0+A$6#WE*l|Ri+3?o|~Ggn*n zH1oR}Tj2jc5zl6H6h9#yg@pBd!n)j75h$2nHW8wIq?jzgy{~<1o{~>_BQ{IPwz)}r1@Op$*%T(9(^Lrh zgCNIF=VfP4t0Uf@&qpu+K&b4t`DpVEbWn6yNK-g)@&LL(6WP74T+sV@1kE7rE)G}V zB6l70e_Bdtej{k2O;KFXev-V{PlqSLx?mPQiaCbLkp^}59m3bRfi=>Z&+ZYFM&Ib1pAgr25QKHW80v^N%#`Hgl zo8@*&Z|4PJ=vyX{Jqc}Qy6T^49m|z}4b&<;g_+wHH$)4g?O@wPV)BW76_+%rzG1`m zDQ(!yO3yP|W=GX8(|b;KI29IHvc7O;*|C2t>RYF4h1@D}?uYrd9Cf4ZwUNgwm)0B= z+6he3Od?!eXd=Nz{SSDXkz0uoNDoKJ@9OxjdgHbkRQQG?rdE|`Zxj7-{Hto>I>}{j zXQu5_1#$!~7Ad?BMGLRO{UBwBwCVyU`h z>o74q=2Rlw#BDsMzyZ6zl4Vl*zM<+wL%jw9-caG65M{Sel7v$uITmSlAP+i=BD^x* zQWcRWo($&L3TZa+_fQ#5I{aMsYv>?!=4Tgm&@*lz^5NoUE~u58U@_d-gaBMcHgJzS zKw$U51FqF(jfmGV20nmeE_^aU5&2Y8z;q|d@a@5}sXGwRKW?eVTvBnMR8xIGT9NY2 zq+f0UQ-^}@&|p=9B!|EnCxbj(kYL{7(Ytpu6Qi#2xPz=-XYpHXZPxRq-!EbBRq>o* zt%X2whT*mbyfJJFCH}FofP=aEd~(W))U-4%aFF7Tde&B@`?V6s_XFbTJp<-Q`J_V+ z(;U<&vH1!KLxC)736qT7_ooh&7XyIzDYy$6IjI)4<1a}b4hPCQAnDBMF;}6-{RT!H z-ifsQv{Nc7V>4=)mA^Jw5wH{wqOuz}7pccoyd=}yRb5ZCM!PoUSP|eC|$m2PRlGbx9F!J|zjNx{O1Jd4pB1TGz>{ca16eEITV$gW^x?HTDj=&HnETlY;&1 z>z_%b=qkeK2l=M9I}ViCg1-nBVSM8Ba>RmAphAFEBO1S3KLLNVp4C|ONrVcLwQ6?R zBnJS*VF~tb*|_e+=GN_!n)C~)Jj}`~4Yzgyw+Z{C3~dIJ?01~Je+`uv_`CcHJ`kf{ zNY2|PGYFoV3*U2BKn!+n2OhF1|KyrCJmm9t8pJ>&8>7)gYojmPM%Jb5uKdMQ`8zS*qKFMbMqEHRJnGi;hbFg?QHmd3a#r2$i`~4-gnL z-SIB9L?dUta`rS{CfG9An#bYR@QrXxmmFyv`k&Wr;WEZu(6zLy4=E6h?KEKx63qKr zni==8-NI_=zeue1MJ4-_w=%Tc#(KRtDEH1o_X*|o2aZG(x72`zSOs>F4ufM9Ya<{dNHVw6^)3Woy8$MM<-1cboZoe<|IJ!jW&6wO}xkoLu zZ=Ix1x!1Xv$LW`h47g;6U+-Lg*RHU(3yuixv%ZHj;nBR^=-5b~s3R%%PLxrcBHbl6Ug9L5>p^)2~$vtdV z3w`BX^zL5lZppzr@LDbP7GG1&eB&S-t+lr?#~R$0sPG|SHsiL2H?R1R)Fs;UdviC#>dK!H1^tOc82#?`P+=D&^FM)< zYqNVz(oT+<*k`GKKK|GyLwCc27#u$a7^bB9zRl*N>~YxYR&-*hF;4!Al2K23He;6* zA?Uw29{)e_e*d={G7!xKgJ;Cv^7+U6b_~$n2c*$Saz?hbYW}bCf2Bt^FnP_8*A!^mdgpGg z*S_?6{8@sj^{NFg4lFG`LTZSU^_QzP%M?;Gk>UOK zZfi>o_{~=-K<*t@{ml!&eN;r_H$ec@Ti&^2p*U|_bHRfwkYs9Vd_7GJGUa zn~6S5?0t}i$_*#OnI)e5q4Ixe#rw~LP8u?Jbkj^e*vOA;*DNfFoH*F#%2G`E^qXSDDC%@{Lm#4iHRXPv zioP80LF%Ego%3~$xjad|-hCc;506XyLA54ozU*0=X&kHQz8XiWZIHd2Z*5GS6J*v1 zo1CXA7Ly*PMx-H^iPIn3(s)-n)7DN1Z`9HjuCc{4{X@c?>3e6(m16I^)Zjisk$K(? z>``WJ=0bmqZmc({2c)WX@LWbU{g4`U2u@p_dSkbV>X5Whdi&cYa!Wmea+o9tjC3D5 zfGjxbeGj@Jd{lm;FgA?Ov3^>t@nOJ;JgU6Ap|fZ9d_jpkvdYn&bJd@;G~nY@n4M4Y zu_Al(N*e{8#nfszBIR}sEPIsjl{6Yl3X91FYo+Ip@(TK+rIYxs-go;DT(FAj+4;w4 ziruUHl+qaw6Ho1|1D?|<*>0l2IYk~LrSBA_sd|VDn~C`1<$fy^6RHTmr%((Nw0pwW zzD6JGZyRrEG$cZfmZL!dSp`?9dX15CUM>XCI$3v}Ua`BtXZ5eW*QkH5<|lW=GkvXN zm-rvo+OqsC-}$sWFjk6B6KtH(gpRiHDljN@@Ohb$I^;GsE1uXOVSb3HraXhR@3yX_ zaV-lTKxzpD`i|teHkiZp;fFxFLz%<`<`;w5LOM#}QWnSnNl3@?Ge6s8f;>C*lV-R| z54P*u;0NU=Jz=LHr^;hI(Nzo{Mw$qBv9>a=tOxK79#O-AW$RulpWNpeNwsECI#_~hirUnIfY(b+dWp|kOGJZI_{|g=G&f~I zLbjF?u8J4P9(N2s%KUz4o8+weU695WgX2GCpBJApqkU=m{1G>ZWuhF`N}rTD7fN+E z4?l!cFN%LK0zAHPI>lIGq~mQrZWywNi(eU-C&b$43YVY=J5$~8Ja(;;t0LILx-!2@ z`MFH}ux`%-16IjVE;b}oi?mn%>bqldvQFXRDrObpx`F`|3&iF>eB(2!rb{JtGV8<6 z+-2OZ09oP_)6!#pEo2(q?y2`TT!|MXHonU?Aje>Q5%E^89bAb!%aTL|AGMh&m!Us;Z? znBGji(N9xg$avO=@JI8dp+0Cz(201j!nyco_SQKE zEn4=Z9-ms<+oQixWsIf1&#W;dN_an*ri%GkBa+m{itjWYZ~*jAj`DB_smv?FIfg6u z2d6&>tYay2=q-!076djVp284Zb=w5DkK8Hmdg{3$!am{W&!tp9ri|5eoyN^UD z^^{UR`L2kMdOn*D?P{^+D$8a}?c$0DE`j`R?m_LU;+q7--01^ZdEG zV|$RlB+1u}j=!baKO$UIZeuCjdFVk@_&yP}!$ybNL%)>}`1VqtfZWR7?1L}J=pjI! z&UV{?yD)O6T(ea+c}$J>&q139U4vLpW?=yq@3D3m*#uSuz;Nj5BBJhYQgvQ^5zK3( zL6zy?;9Pbpx!Ukb>nGxmy*M){6iS1%e+Q)cAm3mI^}tJS-VtphXrbEXu4x#BG4{Pu zs;FwW&Ci|wV4-OjetIx1Di6qx0TwsM>pN{F6K6Z)^P-p5NwAD}(Q)JeS2qzbC5ooH z)uaU9U%hOcm^7{)B#(4|(2y_wccrP6|B*i}TZ#x&h8^AeG0q0k&^AXf@s$Z8Jm7hY zUj&;ZA@~CldT4xI`ZYp^ps=8_#PTw_z)852bSnD$O_%UcQL}7s@SIHXpZ*F7UjxfG z20dNRrAHBWbyRI_h3DH!2{~oCeq#s*r4S;bkda5JqiC9VqM-jnO>f zu)XgY#R8uFC9odX=$@~5ufJ|=I3^^5-^jm@rTZgPlt==$wqt^oY1M0@iU<+jTMxNt zh@M`^y?1#Br%)}$8VZ}J^8o@^aYS3CMxm-3m(*evJ=*Zt)2l9KNk({?C9W^LMMVl0 zbmd}rsa);AE&7_MN(zzN=R6@1_c@w*@~ZnOBD&4SF)Sn^RFUr9w4wmx;`jQt3{X3g zAZ`8+lFI)~EB{wNf&XNRpu*+Je@)_nSKIvS_Mrby7G{z{>dV)h?I21g4&4@mGb;)l z6dY@#kn<`eS_yogB$5U9 zmT(XbP68;)>el{&5QZp0p7gX@uzCyXUjFV4|Df>&lycjCyfG$(c#K`tQ<=26N=?dfY^l4iutKhtE`Ghb;~lmaN>Dr_S1BBhxvd6)zxbi2whMhG$o`;w z&HRPrdp^2S&}azu`jP+=rHy(p_O{@AtMQIfnnGBsWL}{6lRZU-`(7(G?Yx5K?I@Pgp#>QMIxb*izQV8Ae`GNW zmupp=7J94f5<3#(Q+WaapVqV=KEOQFS$=XA1+(Z4WM8eHp!3?L79Po)4DNFrnKapI zw3yKKm4NyuEDv-2ZCkQiA&s4DA_6*@JvyUc`y>Cw^^$T{z0V~bE`RNNJ(CY8Vt!T|ZQ{!V?k)ODK?~d;n?kpg-6VvD3Vn*_6)BJsHC=a_Q4Z5pc29iEdFp#&nsm8s@?QCJH@CL+6T2n7;)I{ZGP+it zAFRG!r*reqJRv7tvjA5A+`FIvJu`yI zNbfLn#$WyYQ~pI`4PYl8SmAn**w%1GDd`*He2nCLFkZEfH8!CfLJwVp{FP}c(C)s5 zq9Ri$`+9^_|JNUy$IQtf11Arxy;^?VIo5jRaQR)WlrdRJs;I#Fo8gii&nF8fwt1#x zJ4=&a5hX};H=w-!SJ5t*{qNEf#9&JIrxJ!BEaRnck&pjC zc;}qtRvFZKR_L{wEoPIsw-YR8YMEeL9 zp5FVGBrK94M@T+!B$sM}6;wYtwpQwz9+GVxE$F`z}xS(N|&o5_d z;^@HpqkypZb~p3!a--FAW9~*Sc$q-z*^z-GdTJ;6OxoK?vVi*Or$wi>SM2sGGxZE| z6l1ujigrNhX~n_IN>Vr$BKK6Bz5)Gd2JJ4my`LD{C$ePi_1sKNJ(I~C*t$Q`PmQ9y zvo@M+7~Ly=1F_$=1hzf)qnKaC($^_sAw(rE>1KO+C!hlM}hhawOz4iP{A}c zKHMRirTJ!9n2h#M;>+~9nV_%_OROj4 z;YhDQOY(!~{pQ`vNd8c^HYSh#Q}iw-%2H9L>-fE1Y@Xbt^zQY>L;b7w@}qR?&4KdR zC76V{mOX*7sB2nj{+n92K?KbX(jWMGUD|C}Xz79$cJk-Xwu6NJp57*^)U1UYng<(w z5rg+kG}lTmM30QTjx4XkA{Fdxh?!dkX%4KeUSs+0P*IFf#u$gqu5FLck89OAxY_=xmt&r!48Pi`!qn4j^@I zj@Hn%V^YV+;R9$|q0u`nK{LfX#f8nez$0|CPQ}l=O^lSgUUhnxam__vI^wZxrS3f_ z+R+~5f6-eo@=_Lf)WQltPPH8Ar&krfb0zW*L|YCBrr9R(b_~}$-xilz)n%xP1???| zo#dW(VSFNewA>~0rYf$*av89z^iAbSh&!X@k}p=(cT|30XzgMl9o*KDI@V@ka+}%d zwh$)$a?$L-mAem!|pFM@ccQ7LtItQUor9?T*)f;f^|-dJ@&chvVYb>cG}g^JOYfXnHm=v5~? zLud5ul}@M^O}gJ!%iufSxD?LPKEa7UJ13kC1$Vz(yP&n@8Ku0B))yxCAvhtW`D^_T zgi!bsXIcAr%a9-OOql<>gScyDhXX*?zfSPPmbk*}B*)pOeS;rDUIapIpSJ&JEpJi? zf$6>j0PT=Fvo-Pi#kqyZueEKhm)Y5FH45$`wBj@c`rX|BUF-wZ^@#~D1ftflomJa8 z(bG5smA+Z29S%0UM#k^K^Lm}PqV}UhhHM~U#l*+vc9p}mQ8-)+l^UR7NN~N;*Gt(N z^ZbPe_wm1+aQ~wT`2Wh}`#-g064IimKye^vklL5| z^HsP)1NjBtQG)Pt53FIrn`q0~m%G$O=PJx0hpa5^KSBj;gRx<6-lB*IqR~CwD8gwN z?@14vr_o^{GG8C9<0_#7uL4e~Mz4=ZymkNYj88BUD1V7k2?!K{Og6H~t`ar1(Ve$G zs68?EZU*Stz@aj%fLdSSq5ka2hDFb#&O2GE2|O5X5LS@S<;7^0smSHA>2M3np=)+l z-woL#;9gBVxU`CQJkSzmE@D(k;h+#1;smYyRQf7bN;UX;d3G{CPbK0jKAf8k2TWsE zo2#my7QPiQ&=Tk3huu??B0TxWk6muWHp6q@wz|-s9F80pp<8i3vX1&wxI<6?X!swp zv6;}&(HIfD7^1(%8^ppN>%Ayc$`}ONkcvfLCK*nnGY54b1f2K>SSde+;NeTd_9QL6 z2<2vnylkk%rcGK93Xu=zpTF7grn*%N`kPzI@UEp{_x05==Z%1Yu1^&BZO1x2(U&n= z-7_L8Hrt;p!@sEUgi{i}(wtnF23+9`==t-=KER~{&zJ*h%fZv2?jsR`5_{5$itJgD zEJ!_{a$nHR%dBaqhiJzN5C1#*WJz#pv^3I*7OIUKc=@lJ9ugAR-j)d7+tJ;1f9ZEl zY|h2qDGuq_AofMM9gpgrojsVZbY%YYI}TuRc4V|pdO2Aa!wSbadof75yQQth-Yf?! zDIc?IeI)X*c35m|B;t42%Xg#nW1MTet66}s7WdQ_q;5W4*^r5jc57alD?95R3kIIZ zspHmtxvyohPUGtLh$j99ZJUbh$a`qv-jKGUFE`!RAFSc{m;pCFXDSdz(MGLDz7nLD zbwdjL2v#{KKN%q4RsH&^w#IwvJqtBa*afhve&CFuZj3l)S~i9V7Lchmg9}-*!;l*= zStH$1)Jn&z`X2B`-RSG5PL-5?oBBsUo6pa7_+^Rx`UffhRG67TZCmhFgsZg44|>4@ z71G}V0&L3l6-2HblR2|2*1LR$3O~0)*b|&>o#7ZS; z^ZMg=b^N`4*7*gArDS7aE0EU6cj-ct%UmOR~Y8Q-<_dnU0AZ-TuSLJ%wD0p0?mmc=Vx;xmMyl ztGgjZ{;lV!?fXQePU{8k77J_@QE}pdK^H@Jps_)v)`b3!OyGSb%5cG2gI74;_?Mkb zNB?jXuU-P^v~=3s%D4d=Xm)(yz=MhWt?{kMQikoL$y7rKMR~Jj!(Luv^6t_X?@pS0 zq*B?_#Lr`{cII&hIkZVW!u2{x?IP&6E^&nzucP3m#oA3;tREQJ6qxy2SId+|p?4sT zK}EG#$14hR8iXtjL+$N$l`U%r zd5&RZly9@4x!iWb(T znR6NNtyI0*Ui%6N(p}YwE;aw*#UQ!x%wv3#YDl|YLU5$3)>xuk{6oS7RJG1G$Sglr za801M5z9Q*6~m6uoQv$};F{3m+^V;D5Z^Krhn}z$`=+fQ3n&>m>5x|jhu?%+lhZ_@oo zfNF%6#(mYyS+2;-1Z4~b0LXu~KLrWU=eO2q(G)-l5@lLdApLWo&6N>uP*3=^Z;mnNby)8WC!21Ep3yxf(6@Y{=sfQ1WZ$p*df>x_Trt2~=pNbDulG_ip)^(=42h4Y$Ie zKU^M#1)&5gh9BeuJIz5c`|f@rgJ7@1x5=`QsLs_g-N_r}%9=z^g3RhaU!aq_e7`jC zt@Y;x`=;MiW(dY=d~5}r&Fgor2r!pN@BKc?Ew!@p;_3VOGfPuvmxTCHuiW4;&ZP{L z9>o3k8s%$=Yw;brifcz?{E}0*sjzQ;waixR+bG<9Jf4%tR=gjb@24)sw6si*aC}@G z>-$o=?BWb^;xZ2ET3CWPa1IS8(^Tx-Ax@;vPd)Z+0thxSQ5d0ROJlHH40wBCRB zsrAH_Z_Bov26Ok#50`AKhNM=A?91eRf<-)Zzcso8FkAd`mBZ*75K%!a-aGwJw&+2h znzc@OoJ?|Diiwc-2CY!p%t~n|AF?%LnxJ%PkL%27<*zq0vtuCPL+c`Rm$hE?R!n!v zcL$H!lckNz{iKFt9}}rKZ!&{@sl6+XM^&d9M?x~s!bq+*^f>6&sD*yXIMD#{$h#Np+Yh7dgcH6mzGoVoWUm^lDT zY?iL@TGwih#$vDOa=x{=Y&)y3Y<)M5J~wEnb$)^_Y@5Rw4f&jM!%(;BiZNE%Fbdc; zCqtH~5c)PGiz&`NyJ5Wccsafwd-=zq<*hn1aUF==CH1_nqM?2|t6?N~6E1H>MtTX^ z1LH+k95`RVc`u9s1><245{EKh9!Cl{hbtuRUDw7FYUa8si&0Ntdb~9&cK7o&b`NYq ze9DOj^!!WY3l8@Y<^A4Ofn}-2_>~Tyr{4mpJNdy*EYc10!;AUD`BdvHid4SmJ0&Lz z0gJyk;9t2uX%_N}I|#}@`(5PLy&aNCJ&TMLTgoJYH&ct-oWc)6#cTrAmON6?PR;S&BdbE3#KS73KNs9%1;zVl<(z*ce)l&6z5b0nLsDfq0&RT!jX(eI~@bE<$BI#zv~HO#+5+ zkNJ^hoB?=8wAHBM(vx1V*uvmQOwOmQk>Jeqx+*N^MDu>;pmMsl)sBnJt5hbDia?U%TjsWJ+>U)nXSgY!)2ZHogmwJg?{n5-_@2mt29a%*-NLAeVy05&uPK=pV?U(K;u9O=Ao$ku*qmFyFPkp;Q3P>egC{3GG?mf44Y z0mUYmb11~y6wtt3ZHCI=aDlVnb_9SE_0KMVG@alahSnV9)L${oa4GC_iiG* zFehp?w6wY`OFNqDn(u=i&h`cI$`N6qW2GlB6{YR?VBtyq4QzZQtAipn%c4CmmKrr% ztPgBA@;@G$o&ORqw>$OwVRhz2w|q|13IS&MlCejIb3baX*ty0kPLj4+_3M%l*YP9_ z%^mR{1yrb-4(N`{%B}u>N_yozCRMF*0RCZ{Yy#Y;+-Y5yIv!njtNxlgET99ZHR_-J zz#zqBt~xU2>)l4f_lY8oll&V;{iso?9j!G`vhpJxn(+BD{>(dR)X(au`Gtu#pDT5);&T%} z5<_K9_E^H9Q{kABSEekn>`arp+Cz=`(m>i)Kyv%2{Q=F~UVCOmBEzP5QoXp)EgObW zOE{a@phj1`!{6vt$!Ls2Gy)|}%1Cc-M%B#`1o8#D%1N;@V6D*|9IJf?*zj=be)TJnAs%J zvx4zrL;githNd)EUxZ%5EB{P*4AXczJ##(c8Cwm#-ylxg+B33b+#~;MZ~;(U=lsHF zICCegRW;%Q9J&{d$s=_2egJI@2O}r5@jvOwTjfdTNYm(!uN=VCswVxMCYv9FZc_*; zE#=5&_Ka2o^on89dJA{LzR$c)EEq=B+P^Ung1;RGAjP);f6_jDCX?^JT&S*oiF2;~ zBfFH!l|xsGz3>kNOjys;pkc(Cq?3zqJq@AdFSW`F7HBZ-i8m$rrMADRoXR zS=^{*Q1^>N|E&}4i9x54lFoSQZ$<~ygKd2xk7IDU~VQM zjD8n{Bil5?)7MaiJtlIbrt7?Oq<$zy(Qx^aiexd~?ANrDB^EK)_^hza(+WVMOdW#f zPV^V5XGvul3QMZ(I@Y?UWA3CH`u*_aH=cmYFOvOKir3RTb+x=(SQ{_$o8~@C#9P=Oh$$%YgACVUd;+ z%Nhkym$oJ=TW&dwrKz-#Q*4=*VpMnO6DfS_rA)@=+8H>1!+FYZ>s}<{dEAm ze{}74H5#pXYN;E^#a(S-RJq5B*!+F$V#=#Y4Uu-Y5ldNTY({}Ed$+MamEqXsL+o}( zlr-OrfAw+YGc(7Bqow#Od)+DPFjWK8%cprQ2W=&Q>{nRjfbQd3rwQ~-VeQY(jxGJQ zcJhYdjV5EWTyxfY@`j!z#&Aw(_laVciIU3AS!&<{vF)ns>yNe#B42rX!bS&wH|sWK zj65kZtFzP-lji-hWIqM~H+lfJ@cdcno9k7J+EDE%VzGfT{t^OrC+2@3sI@g^ZU0Fn z)rh9Y#VHw;HhDLh;jFXW^|@omGSvOE|6)xh{e{j33ktcpFoLL);}%0p{yFrBo}Y(Tl?m_U;sk(>9r7_*{2TODtZ>>nN@yIo(vTAZr@`CS#2$^!5spZlP& zpl~<}BmKj}<7_>h_7Q1te34!5U+1$jsUJL>(RAT&{RoQb7XN{;Wh6l#?{a#!G9UWh z``Jd+;d}cGudu-LN`k_SQ=fY~x_G%PUG|eWhDZg9IVFQdsK?P=ixtSm56=EUEJDyf>~)x$lOGhw5b2s+1xG2tX;*|_`(s}(@2ZE?SnGc# zrqhNB7uwbvAKRpjojE&6gF$hY{DM>`>}JJc+of?KU>bntqTXqTXbV0RW%KuG>B0jq zz>8oKxHsV=8CmsHg0ThrQ&(@>f=qL(YHfp5H9jI(9r5TyDTCcpkB}3V+;{9@CW$@} z^|i?qpVd=qdR^eQw#2TZ^4p&FFq(;-#rXt7#&_d$%LUH{ucq^5#3LYlh#L7_ZS ze!!B>Ry)W{cgf~*NK4vk544*k9s1cL|7rh+p(9T`qz7aEoGs14MAo}C)xGnq{kchp zCV6L2DA&$?`$@G+7}?5oY(3AT|A4l^T9%ZeRzrol+m2){g4}5uL5H_BjpVC$W}(z( zdSN7bCqtBXl8Vun&bf~-FU|D>=L2+%$bfR)2)V9>;*h34<6NJ9Gna*#;Kc8@cMAFB zaQ}Wy1ZF#4%h>wrc*XIYwX~X9*0;D{E2^#?R3ojYlM3jcmp8pxC>yjxzp5TNCEtu+ z?3njb;a4ODj^ucuG>4w1{vvq)Hj3G_iScb0wFc2uG zB-@qqp7;nbR?^RTqd!=vPvSeR5;!TLH`UXx6<8C^9 zb^w|P%{g=;>r1-fA0W-OpRkZ=`3SRMh5W|6>Tpg+X~l$p5@7Nl-M~;#U2|lZl%Wxs zyUj!G!~5g0C9jqC7^g4Z`#p0-YJD_gtCWN09PG$P*Ixd5*E(74!8`qhISf(@H$#jr zSiGX>=bpEdw9Rj|dhG}PE&c~Wqc705zugud-~bcn-cREL7jWN|q&CoAO9#Z?ZQzVq zhwajlg~Qn#yQYN6P$#KVHPWuJKG0S^N9&Gh>(=HQHF!iE=MFSg@eT?X%`+^qbZpdsYVdQ|4|!ZOd% z)^16w%dw>|U8Kq28VN_Iyor@o=Vx~$%hw1&kgaN_xE=cVy3_3jI98SU*eE5?bZ#g9 zd{8S%!Y@LGiDGQC`f)QAhJGV-cae}*mW%y;{MjSR_-bV1wXKc@RNJGnwc~yy?g_t3 zXFPD7Ff6-be!C@)(zTUy5+h`zaqv#V)Wf81Ky>3094OveSGbWiGJPaLW%ZxYnE#XK z{(tW#)>`!JWOGq!pZ9u47@!o%MDMg3A|({DyfkWt`-~c}DUK(a(OKS*$6@0xhtCM# zOl&>r4*l`WY?s7$INlw-@?M@ksus7c-AI2Xv9+Wi4$)Y(R7d^(j0Y=usdgcX@@j{} zez(VbL?%Lm212?})illp?~h?NCbPUQZ+){bg<@5;hTv$$kk-9a%kcc_m`3*u<6 z^us#^M5jy1aX=_F5!(EuX}ApK%c#Yv41zz~zf2Rz@f^93_+cZw*s-(IwIp^H6`wnV zUxg&>%&`sjPWvztUg8|w7Nd!nY#-j%1YJCh$NY6V%eWq0cnVk|b1Jq^qwk^amG-F; zdd}KOim0cGGMH%=&H?2aLUPKxQ}C?Xp!zXsHOwGAaYm#u+JY|Vn;@6KLC6hU4&jd)z_u2@uom6a{`388AR%U`j3uH;n zHR2Z)eF-8pRq%G#`H^GKBxRn5r*-?Pt{|orGX4G9v&51K>C*Ckwc<)XvuPJ%jDFq) zyFUcpDIg-}@x%1v5dM3-&4UukNL}6blC{Gn46FtH_0H6cJp+#gU1e@En`v!P?Kz-| zlID>rluGHSu6*}QFp^0_;t8$ znc4DZ3*9Fd@j$(1*E~ocID4-wp2~u_P4%|b2o$!t*cb2h>o^D0#I-KW^p_?#2%ae% zN_>yW@@%tMDC|sSbcpqx-=jH&IjI0R6my=HqVkm(cH9>OV|k+)+iBW=O4b-0@}NJ!0Wzy4We4 zaz?V6663qLF8m$__$TLC_XuUOBU3>`DyIK%aDD^qm*{a!Nx2wVHD_dM`1>!O>9E62 zrwY#2KM?K%V@Z!Ud35baroZE$e7_%Yn8JzlN|;o7KY~8yK2_JQ?SB9TVW@n0m{}rq zd==(2*|1Mn`k9)q^nfq^RY=dFWZyp1a$z`S_YGr);(aLmA9hMiJZ zr2YQ(r~i6K*6bU1qE~~_!pemwT`zmjIQ1A^#@IlqteG8(ULRu7ph-XP>YpO5SoD(} zvf{g1cPiRlX-X{T)`AEjg_)5J3a%rv@V@hL?SUd)<8miFj9+t{)*=h_s+aXE4<6}S zP}_%xOEpn&)A$FB91=Oj`OE2OcJR|$ET${dP#PTABznB}sl1v~^`PQeK}|Re->`DmhO%&^WE`RjrkGvDD!p^<>f~6jXIm$c+E3ymEST8ay?@xV8(y&Gx_uz}hK?n84 zJEv{}MdkBhk3NS5IDOIv2aSr3vc9~r$Thujaj|t_g_p}O*Lg8k&fMPKD!SQu=`cIg zUn6d2U3QLqpJ(`CXJO}1ori6=X^Vc+&=46e_xrUs}-P}k2OZdL(hcrVm*+h z{-&jhKh#>xV-rPvKbfoKHO!nQ$w~^8B{d(XlWWa>hOce!G+j^cl9AYV8_&>}-rUp> zbL#KZNj5HBuhlwxb~ej!-LJ&@RO%ZtpTS$kF}t8%_e*!E(<|S+_>|d3OFLSpiIDUa zKdHG&z=okNQYCR^2}AUv_tmXoi&iBOl3v`JqCim)PV_bv=drG*R2z?aCUL#2(5SJa zNtX3ASxlUgjgTAfK6VKIIJdr#0mIzqYk{ZSb4h&d-B{pWkISoSg&s^YXrwWAFRb4l z&$5hRq>DbPRKyXhpC2dMl482cMseOOUS{6fXc~YuQhb^_lHW7(8c~}`kFVEJP!5>e zDYL^%es8>2O-Z;xlv8>i-hI10Zso-U`NmPhch=Ue9o5lYy5ye1=Il0;Ka=w(uE&Ei z{f?0eq!zDIRq$?Yv}v!Y-f5>p!d{CJEr~zF|EJFWPaQwK3oRZ6-$&d%*^cqJFuFx~ z?AQs*!`%ziu~p();BtMs}=RJNhpfMDJle^^GzGA z4}Z8M5neHk;|L8jD+&faXk_rI2{K&j{~<7C)(EWl`Ye3pSGusk7YwQ}0nu-o+)`dB zZVr&&E%HAx17R|jBqVMn*0EF(dtM#t2!`oX-@vYqmrU?3tEHG_?)ohHN{&YID&ojmlS*q^<1{#euTRVS#a3g~$k@L%Yp92C z;ZUg5KEqf0=zdhLnLO357%}^|7+l?ptqh{=I`#;;eyY?rp!w|Nauzs~S%m)a2-i zV&GVV;)jWD2N9W3X{v5@Kt?sy&o_y{pLlojr_#i^rJPQBfnaZ({WCRvr1n1T&0eXM zZbh*3P+tA?tbyJu6IX$yeX_hZ$` zF{+O?T+r_0qP4XFLhf4pOfhr-#s!xyRSUQ)oP#&8UxsK*E=cMPlt?llSXiLE2$gN@ z!-*^2c1T;3X69~zv7apEcKvvP^<;kxaqPr8?a#JbsuC`N14w-M5f9DVLt<_{Ukjk# z_loAwqVvY4a#KlXHuY00dHZVbUUT76_C|-xfrUaT=7e?H8EU6$#zn8XpB38j=EYwj zw}aV1tA&T|EdKKaD)9$=8lQ8BP8vT=m3xu$tFBeU)bv}$ShanzSIx7w0J&&^pj=iC zArjA!Oea>!D!P>o;VYfS@;C|r66)2}#N$G=*SSgVjEq()=Y)lI#JqHCB~OEdc3WnsJ6X% z<}~hT+%3RaKuaQk1zUl}Mz*J!JDRI{N)I90VSBbNNfr%WJfx{Qyp&hC|6FT&vZ}s^ zu<~Y7PS;g!4%1_!gNuWl{y~b?VnZZ^M0;NpC+fOdUpzgqTAxJa_5e6?R~l_zt&bs@ zu1Dj(VuHvgESWr3laf` zuQ?pTzn(97W#VXgAR%IhrYi$u|2pcg@ckm9aggqOUanrs^>H)Xju7v<1Xz6Y1<>qp zLDxs}mNXLHkI`kZtzkDo=|iMi6s9PL!}E9=JPW6wAqKct)O#s#p`lt&rtn_lE<(?d zd|dVu_FZF_)_#AXtmPbHoSm`C4PuZ>4LDFY9xg`=aV(X!a-VQ(_F)*9H=}V<-H@D;^?mg z?_}Pc-JJNQJF2czQGDQ?Thcsn+}gSlCGmNQ2SaQ?ssC!cA&EO)|H2FE1*K@jUF68}57G$db;a<2 zTH|b-cAz&jSZ&s89>DA@6&tPT^zz|?-qW3Ueh1Lw@(YW?GwUoV*`411t&r$CE3J$vKAs)FK?HSwFF-SeH--_Q69gDC`erQy4 zGSjBr>C0*YYdx`~Q)@Q=fXxjn%b;OdtM9kFY}Q-Zi5 zAW^*?l%Jw>fgkPGf9x}RL1(qt%0PVNE;GOh>IDPo9O~TSF8d!0dbVLLB`=9YAjT5s zBkpA(Aa7ck^cL{ZT*qd29!8Xpa*stBcn=M~)4hkBRkArRvBAupEH7E7{y~}%c(=oG zEnIdSjeeiB($_&;J#Q2K^1`{7Eqb&=$(5D!%;7b!tf>izZ*DfQ%JUuSa*u!M;_&6E zl&i3u=r%OD4=iyngSEb_SR`$jT~^oHir6ge^B?+a%1$pNdm|d)s%y^MVZC2XLv%yi z+#fHj!O#mNt>T5?C*_yPi;YN_w{UiL3Xde$8oyogxVMqh5z^DpyUf3gzpnK~buM^| zs8gDqWk1jsOq(-{ZNi;41SzOiS)Oh)PA=Bn{RHxn(_6QU5~e@X2H*Ag$d zHy*Vx0H%C+vo#nB<%gxpMrN!RYrPkeqh09e zVU=qb&L-nC4HH>MkV=8a!7Z1+RQ^GF1%I3aII5TbbhqlkEYykX6@moPWoC)PWXs12 z<-L>cP%(nAqdM293v({)BGe=sA5pXMe4x83gW^Y4!xDzaPGj#J>*9C~_Egt`Y!ov_ zcj*u&*C!DByRrhh8!pqd5aIKE85aXaH54YDd+@F+klQL>Qd?V@yBjQYa z^=*x98tzzzBo@8GA!P@bhuA?ovPO=sGH8Nc%CE|G1rLgkS!35SwYN_!%&`Y_C)QZ@O zsY~brPuUx(B{8Qn-G*hMJ6)6HsWH0-p?EUibZF%}J_iO9iM)?-cQ(|em(tW5@#f$6 zn~NICaFVLRP~@G81~|Y4q3fNK^VZd@#hBFBk5;a!+n=B@QhFz^({aI;CKcg|10b3( zo-ge`FWssTM*7LnDP66f7{`OhsUhm|-O)v|x3n>1!euM!#VeqhTpv6jgJ z^5b%MJ(b2c31b3Swu%iug(IWpqnO}FjU0hxOJylzSHocW7A6K!MXxn8Zhj@f|I|{L zxc0B*8)x~<*{M#R){XENC2l##_<7g(e3g=3IAW^e?yRp5>IcYxq(Yd`%JfIVn7)+z5+|0RW~c5&X} zZKt*Be5T&Q9^?Y8m}T7wtv&mRgf#?zoWItD7uWOJ(U-Aj zRG%thhdV{)coOR9&OrucX>BaMf(S8ogTGx4isa)im1s6A?k>JiS)JL|{K3yUVaK5Z&v#oACd5$dBx;ut;1+@C0GWA;h>^{^Kz%M12& zTQ<^HTCa=-h0I!oHCyA(E+ zY^VAVTN!A8&#@QH%!fkNhCG!|Bj>eRKUz&{zeEcpH`a^ub+5?)i+QUbQg-ta9EGo* zSz2f67Jtm=C9Qw)w?*no8Nr)xO>Az^9=v+{mY=_z%BMd)WW2_kXF*l!)g%m^#xv*l z)?PhJ4VGPoB4^v1TZ(o&J^2zzNJJbhqm}=xMl@cZhZFsbK_9(it5ci$v*|U^&a*%J4Q7EY)m6m6>ImqfQqg@|~f&xoh%o!#93%D!+njspTFmkVl6YJP(KY zStIcyN~kBqh3JjXxC77oBSCIp*JO%i8NE*tyj)*W5f=grL5{{g#Qw@5w}aQ;29!_5 zuQX_zT8)e9A%@juf~^+4iLZozW!nGv%f2oI&8*KO5JXTP{e%8pv45w=ki`GN!!*`7 z64}g+{|&mTk|mO_?tSgHbWmD1wZJUTWSULN)1z7xwxVMb+_6&w02BFg|6FwFV-pgj z0>G+Hj#xnW;PxSnkPUU~*c!lUdC%&^UGHBft`fzv2#CxmKIKkNba`c$h16b5b@Rq!1 zGTlaKqhPL!lN%2K2X5{@CKME5IoHF1dL-|Wa!aN1W4_e*F4WdFx#>FP&$FtE_NXe5 zN&^FdOFl4mB&3+BoESuvJ$48~%KPdXAvZ$Ut)E*CK@rZZVtYh}Q z&WB%=F*5rie|LP|A$#@tutiHLN-w*RHHE+R{QyRFg7XH^I}JgsDn7Qy?=AQIx-FQj z(`t;p$*@!sd9nLrxBmm~IpYFzp^d1eR$BdjQ_ig35Zd$=UL)*lAn#0{_2;=4Js#l) zAs59r(6%&O<{S%C-wE(h6&6WUQ|8gqHIjc%^X*^d1kj#KqkV}z>V@P5_!_dBje2hs&z z{Xvk!Ox`KIKLH)Q6DTffM@-|Cxxbr7rJ;nl#n``poAJNKO93BGmAmlQV>x3SH&uwM zb=_4`&R+)>Sk{O!5K5%y-3{d2mBERtd6Pfnm~jwhIm0!jBK4^lL)qH`?V|D1oV4_27^D3Z0Lvu?^dbG^E(V zlAcAq(OBgw8S?Tg?~2%Xj3c6UycW1~)^*(D{vN=4(`=Q9-53LKIncnq8J<4VTv}m$ zq;l-*{PYRS9n)MPXG}1CrGPfO5_fb}D+oWhQoi|zZTX)~n%e}#L&#U;xjM4Kg3l8G z1sZ%k6y(JDh&xXe3Q+AoQV_A@Kss_a6~-uEKC*H;GQ@k*L14XqNJVQ04{t`Nu0Q zl9Ch_lXNIbej->50mTL(h>CeP@hr7YNe!eMkx*d;)u7&8aufDe?{P2q0_1+9%XbCe*8=3n zwtU4Z;s5D|`ev)qVFWGbQ>-qZG@TVTzM34<(MbBALmMn0#Smj;M*gxfjk|g0biEMY zR%@i^*)9c}v1nUD6nfQNc|==!eEf2|*58G~vv2Y)b(b9zmm~&JU__^i4*$Scrv5WE zpYHArrFwaJnFgtLq*Jhh#syn1+%$mno-3nJd}UFicaG=sO1EHqCE^F4H5^6niOq%8 zX~}?)9$VXnkwNAxd|MD(9_s;SiyhuuW`DdmcdU>TZUS+VC72P{EMGBvd#+O*-+nVMrL z6Yn|8{y};}b5ZKUcd>)Wt@S9G#y#|7!boobI|IsIL(42-yD2HPBPJ|_Ly){z6bw<@ zdq*BcajvTm+^c*7H?OjrIvYD$!>5PHmq(4AP_DdEkGv($S5#*pv|gZjsL~(I*GH}; z^v-nE6~=m#^iy`wN4Boib?tA}GFq=ojxcUsdf;+L+1Te^3-29;>d zSK2}PYgyR(OUHte`zbaq=_`#44th!P#j^QFvfy1w`;j?QG9q)}eBpv^UZ%{pKOL#| zHYttn(pyo(i;p>#mIU0*;j1y;^#@8N<#kuYVizI{{oHb;iXMFmMTo4p1?{RtwZerXwlOMb__yHnyBVI$+r_dI^j6ok$bTaBh;rTq? zB8S_s1QwbEq%W@U8GJpo3E`5ky}Snt*e+pH)EuXt*`KBZ4pbz08#^aAhutp1L3^cP z!8esW^rm=&e|O-4nzXZ@uOCuii(3m;*xM;WGkT*ls~lXNtQPos?dSV2^uS36&5or~ zNtWRpnDwcSclU<}OzMnCiAKjbT<-NkumTvw< z8zy~Ys`qD;)z}|Qbg$FBG&h!Po>YwO*doesp4)zMP|)xSnjrW#bAd*XBV9e!uGeYC z@$r9YsZ&am8o3wsu|lct%vsUNcqHjRuCPyJAI+a^?=74D81Sm%pI9hlK20=Yb(>TI zr#*5eF1`D86@@C{vK^_5@c6IhdT>QGAt5+s21 z2m#H#l-&(u3T@PTA)ACouAg7=?!X{x=PUw-SygGAg%qn7$nJxt5OoSqOIFya3zPGm zm-ggh;a}tUy?AUz*#bkNqvX@c!F5F+>wXSjK{^s)R3^tG^5om749~^|Ei9rd#ac*9 z3G)Em-XMRUTIP!81xc8V^#=yK8>`5)>PtUG9YpU?y!shHzV$FK)p69=F5Y2>z38T5 zW%DFZ?Y@Xm4wtoVDE}9q+2>N3C(>yL6^V#6^LBTqo@L*lIu;wc@4rVH{XMhV>DFgJAx*~Ko+)_#GPOtArb=E z0{u+x5cJX_Gpyt0n{*1lQ^M>wj@qF#-WfPH2r-ToR*XUnf{YODO8;tDLY6eM>Uclx z4JZP6t&FRz^ ziG@P!e7qG(rM?2vbTZK6Tw@J6E%XgrJr|{}zt-{>LA6+?zO1Z=QkNA+a70wXg`}61 zHbh{E1-1Kze+T}3NPqB`EcQoHIia+n*(c~rN~I?JT=@7<3GM02`CR~8z+qC_>5>D( z&LYV0;syVNgQXM+v6DgCM3xt$;q|t>*Muv~zA#O0vK5W4oUu*%4zy-gpx)Br=wnR9smTA6zRWWqWiCX_kZ1B_aBE?YI8gpqQI)S z0kzuT(|M)#cY~y0aCFmNhxf(Z--4RN(>6wXQv;p4hm}3UJIWh4pU7VOqsna3lAM&| z^TeGm{AS;W`NHu~hOPX{p=6@h0oQf^K9Y9v!S-}|ulqnw(FRl(rX@=gF55q^Hk5{9M94*RZfyKcY{%=md>>#I&&=snI|axvvf1Vu^h}qg_AoYZD>=dwg0a?^ zw!)DQn3fBR7V z32SIas`P@WUlI%Q4i*H*E?0n3!1P*Il_RS~o=Uu>Lr+k3I76(7o}9MH&<(^?MdI7n z-$_OBh?34^-RA=tf9-cKw`!Ak7nO!pA<~mS6+UBrBRt`^cFIx(D=4SlF7(VF8W;4D z*HAW+VcpySvP$%It>ka(RB)!B?*}gMboUchQ_78h3S2*?oMxiyUB!9sujeGoB$3{| zmHL8Euh+DPN_By{tK4B9^k3|EO-{4#s1s+8$iE6VE4M*2nWe{!$F9c=^qDu&R*fc@ z1uL5>zs~?HDmTB@;Bk}5qDvTnODwp-c_x|e<515vhQ)Lkie><`|%og zE~LUeiHgj(#<@*+1gByxhPpG-S#?i!a@f^EfkL_QA~@?g(b@a>CiGXFxv2@ z26e!aF#V({mFqn!Rqmtu#f$vigSMj+UCfL(j+0Y~RGdtw$uhYVmHORx&xLG#ptMcy z2&k}z?rZCJOAnMuubHzpC1aw?cMV%1XG`w;v!1E_+L~b3_aN8U-$`h+1JU*h0&{y9 z-2)uN((!K0>NnQ_TfP>)LYZ|j6aC7-SuJ_AU$(kBu|Ar{GqI_SHhJ~sT}y(_{N>?* zHWvOl#B8j8CD)kZO9hHo_(JncUhszT>Eq3HrOs3vd#-z4&m?b@o|W>)$1)J5Kl@`*^(hO>z%9YiEiqyM@_jie zGt$my^pBZ_C=)_DuCMdrBKsJ4LA|eZUI+h{6b80)Ak+32>Q+()TkchFv%g^sa`qB9 z=}or4Tc%BjIUHC=7cyB$(p^=slnokuy%X)LYlW6%mZYk)xKn*(rL9)m`a$skVg0BV z`ZTHynxY;5nu1CCbcEx0C7asKQ$I6}d1q=MlIFEP-|QOkj`q`D3l0Gya+I_#k0XT~ zknQ2;JrcFuqWW8x4t+GUQk-W^O)lhn<}!Tn%NMGOEZ@aI4K~<*5bTUTC}~|;Qvgqz z4r0Byc<8%wy9{oX;97ep)zqvPdg(9&pPyYPZ}iBYiPw+Zs`a4%wiGnH&o6MM^C(G1 z&hPXM>cS7XhDq`cH!4R~EFMN3S($4^%gplF!LTrL8#B4ybvIFTy_i+o3YFYo%u40R z;~W*X;-E-}|AX|X2Ey+HSx*OPpt}hR6fno?1_UnV`$Cw(3dmDgcK3VAz>vQq23Is=|cI%`D>*9}QUsrnb98U3s zIbpigl1PbSv;I7ESTiTYt}-faX9$GR7XFK>yv(PnQ>hFkS zNAMAFkq9fI>M@KmNeuwqO75*?9d-`SSI5Y0*GPv^5cdKz%O3<(J|jdektYvl>hc@! zL9Y5;zu>&&cGuQ}E(Ok4rrg#LlZtm#DYs>?8AE*YfkmBD$rMBVyd#$oiOU zKP6aKvepH+)y~yraXH+5OXnaxgx!?#Y9%!^4l#^XCC$cP63)yV>)tANZT}u=ZI@P+ zISuPBHf;A_IP5diIXoXJdk%*i*-&p6gr17_*WrUcyiCvPJ}S(})JrLM1sh8VVL#Hy z9RebGHcq%^RN>LO`?jCa5|Tajld|a>G7>KXOVlP)8+mFD-H2yI z3UIa}$zV?$K%duBZXgmar*H|FdVfML@GY)lf!bx4fk z#V!{PJyzBkeiA&dzx(Aa>SE-})>bnD1`Pip3x|3Cp!A<0T2ObIz$wQQ?yc@2z^;qq z&`>#5lDq6AxPLJuo?s95CKTC(+T2z(PbG0a_EYCMY|e+@Gh__^vc=`py_Fj1S|*#Wdz5JEull=BNthl7mKA`{m5uo* z;TN#1eHn-U(Mme5!Ij-oYgnMV-@R#Z;2J+~p>i<%sw8eaA z?o$iwPyI8OV|AQ7t3vZ({H1wB8Ld{4)_>+`tl)u9rS;f+BKb%Ceu_{{L#b-o8m;grSf#8;p8 zY>(xK3bl)PKb-SO~u#|^0u2X9$1gdTGOA^NMV)XNc&X1<=l+nx=6lR3v zX>qb*+J!Fc`UdTYLcI8bwEtA_;rb{Y8%XBlcJ?Z$(ZzP6zr1Eyd=hF^^;K(xFPMLG zqHtD`_Nj@PDn%w6AvW11QJp_f!r zU2F`rvrAoB3vpE+x%DvH$|CBrBOdWbvI^0g4-EvMzTuf4E?V382*J_cCq|5Idzla* zn;WMa=;RwW|Ce{}A^qd=eI$!@H9l4=LGNY$K{E1ehC7^oLP?*y8FT7`|81JJwFO`; z0j)s+4w>QM{3wfWZhT*PBel;8A%sEVFH1m5uEl;|Z|HOF6nZ1$p+VnfXK)Agxe(If z?Yhf_o~#!?4vVM%^VGkk_0u|z%9H`Ym=}(3~676gpJ(vnl z4M(~cRh0%fbkn`6X*xewcpKEl2@Tvk+!1=jS0x_KX^*1h~0tPo-T0I}8u-D+ai zjE}D`f!~KI`vmxje4P||d%w_&T_{W~|4B)w@*gC}ybbg{1n2K${p~$+js=WrzMXTf zVj+u>f>!P2O!LWIB=O{(GRlW={tq%ak;aio8sA6}P;jIJrfZe|r4Ho(O~erQv%g?9 z<=M18QM-HX1(D(@%kOu;v|%t)UqvjA*gv@hHSz`i{f?pf+HY`LM|v&>U& zBj~+RSCPiItqT7^3SukwoswDTJVU5A&;;b;I<3ej<@(t+igUB^VI0?&?Nh8d%?_>_ zd0Jz-A2Ck-V#kZ>f=b;sUdmI}E~Gy6R#gg4c9fg8t{6Jv1MsfQI%Jr-R&dvLCCSt0 z3zw*9D3zp(&70>7;_S_2MZff$&Da>HuFZvJgbeb-y|b^u0DEdit+S!6DQxfUueyjY zr?i>BqD0gTzGOei&9#|c41D`WlIj{?qYflwLH>j<<2KliIWF>tMi&W=_HXXm|K_N( zrk+jt8#yW7#MB>GxYvvemGUQx9BWr|nnA5B1Sg15F_s4=;QcIT`wlslRCtV*uup^; z%tuTt0V7XXl_uRc^J=`;wEdm)Ik8i1cIWDb%){K)b-(Jaj9f8@IwH={k^n1GO09WM z2)d|g)(m+NRy@R8RZ?=&Rxg_(dE@40Tn};hq4Z}rdNmsU%<^ltp76Z~J$Q6A>9BD* z4eU9wr@$Sz(K}G!c$aMB`lwM&dU&SOjr)CCRfXX4e2sT@Tj=gglgEa5U%MS>Wilk{ z5&ez2Fp}h3%lw(@@)BN|?2>dz<wVdi4usVy0TvNM^4ANuw09V zWwyBGmCxGG4;Z^+x}CGzQ|k<=ADtN2MFLl5=gsQNu@vU3DCM8*4o_HU9v#luItIKu zEZI3_*AyJ}*50@D<+k-7^);@@UcH<6WZ7Py7DMrxyc4yrtPbN_iGbrr?_GT*#VpdKSg$FIBdy(qZvu9hGzM|UxBi*LkJ>(D1$m-$8PlCMS0XyxgN|8&EysmB><>n=5R*P3ExeK=zPKYk z|3a+xfZ-~>!AAsA3ISEXur|bxt)V| zeSiiS9TMd}Aphg$X~aG%z}Nt5sN7a_ds#DFT>!hVasL8qL+>9XYuzk5mG2%$ZFZvT z1HPWn4^6``r(i1KK03t<8FD^mX$dWTseD_>&lX>(x3)w{fcKH8?Ta#YTG{Bx1NE-& z?KuypJ4_m8O#@t-8l5OZS31-p$Zsc5-G_uEY;9~YfP)DHz8%6=L+Rw^c_dC=I#V_` zztIE4>s!jAO4sXm8_6~1lYQnJLBW(ERHUBaH}Yea3yNY_!^Qbf`e{pYaAvJVg_uL+ zU{B+8wZ)X&Kq~2PW1jxHIGbYR2SxR$xm7%@jMjvJ=7FYiVRiX}Bh6*a42$KcdRK1L zd~nF!Dq{8(t@aPn!rR=H8j84v!p2{Doipplu-}xL6yE}*?Y3`;mRPj)LEWbUfxXh$ z=xT@BLC8G@x6=_H*VQ>H}2-u z2U~65NTqFdj0_gJ>UqdVs|>EIUA8A>*)@ud^@b<9(na9N&e5RRbft!Il9-4It;1Q@ ze)uu$y0d=8(g&;h(gh2+sJTrM;9BQShAn;937^ZI44x30d{XehS^>1x^ppW(Vn#_( z-5;6msBfl6wjok8-_yihqhYCa!N4#xdpVPHM?v${tJXAGp2r8s+CUms;%W#jv?)JI zDr$e6X^-37-gv$~65tij^o5)}Gu|OzAA|9YMC9O+BdLavm)cGyFl2*;7iqavJ0rKw zS;d&)nC--IgnS^Tcya$>zWDc&eu^Ah{_8p>Z@6>G## zw3mymZK7Y`W07Y`F-=TWbt7SPwIlm6ij7sQANzBjl> ze?dJ_ghs~t4V-Vs0v?L4KF;a_(^8Ppq>g7$E+NGRA19r2ZY_TLa=J|r#L@*We5|T( z1M0T$(^=bOdR#QHFsifJ#?IDuEz3}E3>_fr4} zlDfT&Y48?TJM+(RYVP@PY`{g!XZN4^YB?=!!RU?QKVxMaHz^5qT0n`TV^~y5S_?)Y z3T9lASV`e*tG2=(rEx$-+p&~i&v`x*>>Xfc43pGxUqN&vMBv{c+7sllpJH-FE<0ko zmMIILD=vn-Uhzr>;C#4}Nu+Cw=)c4n88mvBe&x8B z$hfbQ0s$_1Q)ZWIxqyjngCDg4ijlilsdIy?DG;1W7ap`E-g{*LNIhPAulVg(pn0aw zvfzd1(OERk(~`OzFrY+_*HAyh3f!Gb=w+1fKK| z(KnjukrsRpj2*lw`AnxA`&o9iwHW|dk-HqZE%4?2s-1#{IpG=3U&&7YrmC#~ZDXzI z-E~7=ZL?lCXGA)+>unh?FFUV}K3xP0c2XB3rGv^~oCH(2hQ$ubo|GQ`nSN4O@j)tM z7{euP)aC0i-ju%%O_gJ_Q8(!+vXtrP!udTu-76C45j&JxK$2eI#z|kbyVkfp9U<`n zSf(6N7SepZ+vIN&{#=p8dHTHEH;W`vKQZ$9Hz`-&hn&N9nK7PI|5H!5;CkNkYw|W9 z#u<~2K-Ey^=rNpU&Zn}8HORGBFfU(AqQBb^P&N|*9X0Qc+LW zvvX6acyGCBsipj_w7Q(O)Zb6wx&lw5t{#UR#0KbPqBY}M4l<=~rt(QVphos`o;xKc zds@O4W@@BxpedP^?c=~O?-&QI_>s6ia1r;AHC#-7})Ua@# zD)B3SiF1F|HqdigeZLQklfnomtv2>UJFVaAB=B~9VVaFhjITK)o_MUM^cd$7>J}wH zufD6O=tmdN@wS-t-2zd$sl~?2w)WK}W$*q75oMw-kR1}fT(7@Qf>a&~5+}I`D=7yo zk79@EH(6iuLX#M)$i}=Gv?^Sv)U*QEt@R#FrNuSufEQkN1B%jgB3##Z?5~~+4H0 z-fgqL2#Dc(+wkpg&iT)MGgf(&>|Fk3=r*>vQVmOAD7aU9`Swis(uTNZQ&t9Q7k0g_ zKA-OyK#;?W2`b1K+*)UrC9?3F08;Fnk|&R0^b66D*@^GXfblv zm7s~IGHUd)7@{-*Loo?RZ9glfbm!eTaoo`E+B5bt-tZ_5KVuS_xU1rZF9bo7Lw$Je zdlY9~*goiUcY8XWYVXtYtYHqII9MaeY+_$!c07oox}Syl?(9Dy(g8pEU$g)x8qf{| z(;`0WJnK1-;z4f`z52gzp!(Vm(G2dE{i>>7*wBFk$Vb!L(>Wa}uXcqTP8a&v_^&n3 zekS7uPtr^zyR@1}3FGU^4{yD)Jb`|hY#0917e$~Iv)R4PA3NXhoX%jJYluPsSV zYAq3BTFUt9&3?PY)&@2X>xh&0p_3Qq8hr$Jw4S=br}_MbdXA-Yr;r$5jN5YNIr(oO z3|*BW3oe3Z1S4dC+Ij8)f@-V;qAmC}ac zEKt?zONR?lxokZqlWkagM21|v3G99$$uej|O^lo8ejE}-P+j{z_49G;+GGZ9?pE2L z5f=4pxxuHUM-4j^td5eomOzDjqh&E0+<0jga827vj!6Vl*XI4@PZqyT*Xs$0lO{aj zwq}noLDU0tbK!Mnk*Y4aV8rCTKY>jyRv+o1KW(XNi**Xa!g2x08CCiG5VjQ4a58I( zY1agLy$k#`+@}DuUcGPBlFW~c^p;1P-T2MGw{QNmUbo(}>W z75|++oWM*Xqq*0{#SpFrUfpNOa9HU=UXs}IT7TP=;}eck>guZH*#A3*GN3XpHfjyk>~(k^0f=4W@a{VDj-uP2rT-r}6x7 zhwmLVX-aKL^DY#VH)=8B2a=YO!~I-zIEgz@vi;-mh)P41mHA8rfE)c#Z20mMGzt_{ z!{Leef2%sqbng>8l>GafHG)j`wF`ubPc^gql%*AvDnKXdjwpLN*1&6zQ4(%HY_{02 zKh_y1`TTjHQfEaL8p*4J^H;vO|CCyayq+CgV0eOOp2HyxX zj;&E1gog!bjIuaYg`Pq!Z-@cX!FNykt@~S?&&U(D?mf7lmwt2-M{{Isogp5we zRc3W?xxd2jRx>UK9ndQLl(6AY8CVWwz!hETLSHp+2csaM0R_I>t7BZ0N;tc9G5E8h zsoBOGuP4z*=d~7G3FWcSK1nC@D2%UCum93gOx>C^zN%X(33|MuEOiJSJku0mI3$MC zMB5rg8PPlOrS}>K3yVKl5o*t7&x(vowmD3Y_S8urhgi>jGE~*8ul_SeKg|=@Y;GJk zFrR=#ffn>o+t2i-Cf$z@WxejJS>IjA*$J!U&IpB=3~C;D#c2khrZjWvLQ%;)mB{c$ zn_FZmyxN#LuR{Jg%i@(Cnsmfa(9bWL-j3~wOAj(e3C`nqO+^LQj6loZTFW-`iS|aV zG;KyryeGlb*>gr+kE93H}lC>Hp#Ftz+U0 z-*-=1D3oF?Ew06-NO6ZkaT(mDxD4*@g`$HLD1*BW6d4A0cXxLNcc(kw?4C`2drnR^ zn{)P$$(wnT$vb)S=E;3O_jP@)1IkyC?0nSJkuBx$EuAD9{E2oIcicRZ=l(*tu3v8w zUoiY5X{bF}$CFLG?Q5|SBs)N*(MbN1HORSeb~ro&(eoY0DgqboHh1^?D}f*1NF=%S zo-n_Sp}g~FR2u=Qq0KQZKe%t^j*m2h^R1nD;}ZB}X|9M4M;M@3Jv4h&PL$JJo)96i zo4=6q6JIEw@!Fktkk-z*dCy6fpx%5R2_430yx*vwQ;$vGbDB^uzXMeygGpS^AdHgq zhx>?`zRitv*TvE=Wy2v#9ZX-eZ=*8TPmGLf@>qQ(&UT+q5OD3P>ExZ$-}jl0X4>}6=%KwnQBANYgQg;nFLO=dB{jFKEv1zIeDUj417zO%a_Ur99D;KCgH)Rl*mJ0Gc(&_mEfcp)pq1f(GB$s{X!ARn@%yo@}{9V?9N5dX+!zP=3T}YuY+BiGfUzSvN80+|%|e zOXWbFTfDB&N1iZSCjZ_ddHJb2sGsnr_$u{BQ&SK(M%+)%_nBs^Rdjqv>byA;Y@Zuv zxE^EV7TFiw5`T4ZVy%B&C*KZWQv7J(_e$5)&eV~H58df~T+Wf0FeA63ELCcGcHjIh zNO;2_*AZuRX?|LF?uJvA;6^8n@OeEkt3Zooyh6X`+;YK`>A}3E3yp1;hi_mEnbahs z@= zc9mdh+D49h)n_xBsdvFkWND_Bm?=j0H{IaGCNmsZ0rw`Gw#LpXB>C1{^VPya$aO%N z*`pm-+>Kwww7XNN#^D@A_^?x?pk;`XN7QLbyqLmYw81n6Fkh0osdEH1ZM1N|64vbv@ud?be1>{|S~kZm2G3uq2t`E+H-cU2K0H^)NNq&?f=A=4p$vPa)SSC!w4 z%iAyiaSBgQ{_H0AmeFZDRAxnXxl1%jst~Nb`Wsm&{TzXuVDx*dHxP%|Wu!W8M!W$L zZd>^_MwZ$O`SBi~=`rToAYQXMZZ|FB))6QT1MLXYujAFCejm4N;gNhH!z!BXRi*Bk zp2_GEB3f~_IZttP-4B>OBV>uFiTA=xf(HVpEAWCnE>dU+9v*z2nQWvktC`qV`2Qi1 z9bW1kK8$8q^59xydSDh6qtS9+AKrVa2#&%zekxsBnNFXFH64c3JzU_uH05I? zQd#yLtm}m?Y8YXM(re{Vp}=Lhl?bEw1t~oz^SN=a;&`s?d>HA?ax8L|bd)a^8D$?r z@KZF|Zu)vf!-Z_{#~{{K*YO<<`rfBT83F4?Nr-GGNiUpmQ7ZtJjULskT?JR_*qi># z+_A?&UYwo);%hQa?J2i16}N)5B}1`*SagY?Bd7645Y=bIA5mk2qBh$7lIzAno;x%IZncrqMS}{hV`-+fjhD$kQ*4PV zDfN@6Xqnud_A%!%A1nfy;a}K?`QL-oPW7__pCl}SzGrK%_Vh&*hY<3^U|=BF(!*L; z%8M{zw2v0l!oi$K(BFMT&;N1&A;oJ@xX(E8`%uo^UWaAdAaUC-6r_U>R&G+943xkQ zYXG5pKL7Y>%Pqz6s@wUR?~3~X|Ga%7!fu`m(9b;CyjYuVUNZMC0)h!4=v?%Vabuab zZqyQG^!Keg)^tKdbDQIjGsYmscRygU2OdaP3r`T4SEIiOY;$T3@~ z`V8I8s+dpn8J5Q&#adCGrd;@D&680$LdwzmRuz>aptt#@7jCutC00E?m|20d0ULYv zFn%^M5gN5Ec`9<^6oqV-7tIljiU{ISoRbe zuOR_geU<@k#Bh|}gdFV(DqCBZ@yD&nzjjwmC6hN68sP7N^pw#Vtl&$`-aE@7ns!wWdApU8oF(qYCB$nZ}kZvxTL2{}=GZYDkx zybFc+G&~BbC?G8ITzLx#ll;RsfR-Q(*wR*qYLejp7Wyi~k04 z)cB!NH3Kr89Q~+bpl=)!AZP4FW04>=lsIbLB$rUm{*5wreex#z%g?;3%{aFnL9|3M zETP9~h42;y>4LXG>1aO)R^tX^2uULyRtbe|rWh<}T#t`cxGe3Z4X?^M>Q_k20o*x- za1R0VMWcDyYFD933-a)34I*Br5vhXs5XRk_-}b7OvL$PPO+It57UoI)5&~3dr0~Rf z{>7i+j5WipjaONU#eVu)M;XcGdZUf_USM%2_qV<{KiVEZ_wb2j3j=Z3eV7Q;B_%mB zKx(Z`sw;0N&%SXQ#kpJWrXCzjY!vzXKL?YjBOWHv>CYI1RZ)Tm9dfi|otI<~3H%s_ zNaaX0P>0PXpWROxd?VE!y^VX*H$9U8Fl0Ml>v@fw=jlEi!MeD^R;ZLs^|1;e7_n~X zdlb2@+G2|VV~3+8FMg^zB+eoHhQ5MgIkW62UA=d9X!yARsIW@eJO}Mb_=lvDevd#~ zE{!31Bk_^{K0*a6`2N`K(x4MI^7^pcxDoYnunlT@Xh<;KEX*~&Du(nc@R(>B)tmGI zK{&Q@y@%3GH_OFBoE>{eP$>~;^Yb3v%q_(znoh%j5fLXA-3HFU~()!Kyr-(=Wkm@7ySggX z6z*|Kbw9pW3eGFgSp>MehPyPouc~o0p#0=J06|RBfVtWqzEqXH4-FP0+9Ep8ajqRw zDyO^8~D+RJZrHYlJDF zR#HecSY?a9|CX#wN>3CA?i3Df6|gOKJX^+Ge{|8PxH`n}R5*roc~Me&$<)&yjJ&oD ze|)DtAyrNrlqamBw~Ne|KgA^rg{J;!fJF`NghGN57Lw9hr!i0Ws*4Q}Of2tEd59y> z6#B;WWMwfUu3{i0KS5X5FZt6&YRC}9Y9ic^F+~O$|DxU8)&VWu{Zn0xYt1V&!r{Ze zOck3hOL(N?ikKs$@I!{3q~5opa$J9}Tly#5KPzj$c9!zwhUVQlW2r79;to*c>x-r6 z-K8h10_pijWXYg=zfWH)nWF8Qi;F#gWsxm?>@3@iwAa+9HhM~n|1`vqpcVRnN1HM| zeR*kXbwk;37Ncqz8bePZt`Ear|qko$kq)ElQLb2#0-ivU|%#6<1!eGT+}X5x37 zE^D%KcVDHK1ZvwIQ`~B95ZbBLhonc(iZnrbN;(|27yL3Ncw}n=pE4Dd+a|6BnLSS` z?dW28+qI1QxL?6iS&{?jzI|91!A3tFc_%FGyqlKKQ@KlM7A8vTylKr2m@K}Rzp0N4 z{$~5}P~O4P!)2GmiZ%t5F4fR}TflQUTrffUbZdhO7DG6WvXW(70gJ2t@h1r(ti)3VEHDgju~Ej!j6>tuEFdC}+lswAgUOFcDTH zDH?XXch(66`z-^I$zp&ssYw8TW{U5VMw*R4tKHz&#oDP#oTKc*2VnE6mZnEeL)uye zj}-rOZ_VaRlHe(XwitMy7CWQ;o`C;gH72RgPsTxrxl{+8=0a6F&eB(jg!*8%>eCQP zt`&(jT9MpZ<4Vp5<_!U?*Q_rCYrfYnu!Obz_<9J@3w=e3_iCs^+eK@5osgoAW#lsH zPc&5EStOrn;7%fII3D_Z@w%Jb8BlbfFw2z+eHK-PjZXo>r6PY+2LDZcyH~;g%$#uN zB>Vy*FYvm-0}q~XIWIOLG=w{#VqCr;4&-M%k2Ocfqxy_@{~>-$XGv|qc;w`#4^B#L#JI`;mY z2ge4tU2DQnDTDl7%!;i(-Civ&>D+?rid4UwvV2Q&6`9WHr`_y^bCzCEc8^~eU2;ND!yNF6IcRm^5RDSa6J31mErws zEukPiYpjvc8rqdQyK-1?6%mK{gGqx=l$wL{aHMdI$f#HA0tpu=ust0-_Gd1x_YMR) z)^m8+4ajiv#b#dJX_~Ol*UIdiv_?Z}MTf{EBI)a+e5`J4T>4Iax~o;>mb(n5+3y7& zWS{kApBjd2uwm?{v})|EroEXS-E&bAYWL&g$6M=PC9QK0lX2ZP<1=H(j;t|Rw1q4F zc3)CQ(99^=nP^2UUAak^Nkt;;-V}8U>tcACM$&?IWX2iD5Gf>C*unT)q6pBR?!^!? zY}39}^dRL#nOB=f)H-v5#@&;M!5`)~HV|9VAZ*%S>I z`E;&yJALJe)fF%_Og)$)QjkLQ_spxs z**KY6o6_C?kdWA;dK#&X7E1cEsO-ijtuEUB&^5JT`?{RDH&ip1rE;YuZ<%jya2`_* zZXHHm6>7LK4HC(8pqPEor}*`PeaG4Dv+c*Otq*&G{S{FeYuvJalCnashcyJBpkyvu z?f&f5l$q!FdqW+fIyaU=f%@dKez1DlAwq4PDA)|*?03Iml9hgvc~FCh@OZX$rZAds z1zYtjuZ2-24X8kH3HcX=fh{tx#jS;)+U`)$)x4h}Sp{+?p~8kL;q zbD%^;Tx$XKpi>zt*`Q5|qB3PfG6$joG0Wsf_|)YF5WNZcQ?yV>zUb!a%+|-jqv7G5 zd}p2X|45FD=P3i)0W1b_8-pn%{lhgWQ zGdfZCYTZ>NY0Zt*=C8nu=ErorW7nYB-mo zar2UT90ytH#cQ~)*WUJ!O&Kg?YnY})yNl%J0B}aCXh?JR#rFLU^TwfvcHTW^`sheq zC2%Y|?R-bTPCW@pF*U>-nB-o|Cp9_S%hS-r{ON1V7)|&q>4svHRs=D|oVGIbili*f zL`)#M+7FBgI!WH?E5>Uov>JbsI~N}5X=mABp>n}wHwy}IZ1YN+A^3ZGA9>xs6-$`F z5Ul5(Ua z1~pC2Fnta()OA(x&I`CcMj&awv-Ev>Cb`$bF9Sopv8rAM z?3w0}3ZvZ0W4z+J_eSr(B0)G&9;1x#_bgzpKU)ZWfz4mVgp2eZ&UEu#xlTN)*!Yr%Wea^<%=t_C`uoah(%LL+)1(k-j&xv zU`^9n24v(`fhnajdq%+Kvt2&Z`#7Nm_YDoPUjJHdyKjQkh4J~zhrAZ6Gst!%`KIkE z*A*%1XLk8@I364Ks~Zq0R=aKEdh#7VNmn&15AT4m6T2sVBulaH39wa!5FNVL2>5kP zMxmkCW7;61L*2{4*?&`___cPpfaEW#EIlEa%T+#gx{G0%-J7sH7wb)7D#D0J#asNr zJnzIg@_e`QsH?M;))trY5ihcK4^|cxZ_%mA(9S-=BJ13aWIsKCHDywOdw8&Pae3K> z4LADiKn4W%a#Y{Zm-FOVk-Ip0+ov0v;xhVUYMtf{nuzuZQYqp{awjwOlh%V|m!c`N zmyh<-L|fZznRG6_`ZfC(;|S=hJ#o6|*S#E0jcFxIi_hgG>?(xjn;rK!MJ>SPiumWm z5abU3$af0SGVv{aHvQsNVipu!KO=*Ee5RcAUMDUG*|m-d@PUP*IT`t==Vw+VR1oyG zW^smWG+GHa?h@;bLquDPzk1zPo9aPWpwIk>tgUFu*TA#-J=k#x({o_uATovIQ-L$k z0R5U-KH|qkK{66yC(iKDGN`D)5|Y$r^u^zzQtVd1Z6Ay@zTCbX{FX8{J94?P7Iyxo z9GscX_%M7q=P2Oa?$y(_0(yojqU2m9WE=AQfr z`3^bI>-glutrUQ;58-iYOk6r_G@ef8B+q+KZl$rQ{&HJ|XU$U~pPsFiIXI+cR68gyobChD>l%|+Ld4ZYJWYaPzAr_I z3VJ-RH^25zB5h1@_7j;lTtqX$z^g=f)&m8Dmo=h!Vf2vj&RN?7;O;a0Df%!|! zDjZPEg`hDQ&P$Xpb#Yg>93^5UejG%^AD4CR=~O4bEUEKo@eJI`w#T^>mDqPd$5=p} z-Y->dTo((QstC%zu{0T6nA^VgSxo0(d}+jsfn;Tz9Z=wd6V8=Y7Oe`46_LJ^rZcQapTz zAPB(^Gi!ge7O(aC$)ZPzkfa~2+6QwqvuMALp+3SUk~5p;8UAA3j#_nZ4-E^-;OG1P z_*D&$(g`FsC@Lw&(dP$>nU6~6m7!QYBOw5m9Gds-Uy+NsD%#HzzEK|Q2k9k$^$Zrp zGFV>J8+%S`!eMyK6ZR~=7KHGs;@^NRz*T@|tbSP<*N*E-n{n#8sb>D?(AoWSdHgxF z$NBBY8Qvdqdx6?Eyt?|kKCy6S+_)0xcMX~Ra zJ?+a)!Cb4Y`jOJ(>$5qqnx?bk*)oT`A-q=crt*4a*+Y;V$+&^+$>#}f>mysP$4TBD zS__)3=sh&@>tR6YS`_}I!Vbj5nIJZsVn^2qcy=Aq#SP7`p?|6aa83u{wA%1aKYekQ ziubwVIDdj0SE&+w3-5kC2|tyCChMt_6foa@!*jn?ZwMpfxK#^Vm7%2#{ZR3W`f+P+ zwMDw4RWm-PH~FUHbA!RETC1$8fQz9|#gL_GB~RLy0270b!nD(j{Bzjk?<_Hyktr_z zC!k-zbNYeZb`XvGX}byFn^fM}ZFi$cD(&%1%8BXDARi5mDpL(m0&xD0HQxF7?e8}p zkKL|&vEh?VMiII_*Rff4K+FP@CUF|!F*&@BOs!9<0H*R+(fJ$V7qT}MVOVUcHBkyy z5LT9Jlt#1>m*LR(T82_@i)Jne&v#fDUMo!yC#yb=>0*gKkhoy5xS<*BM1raz3@R>5 zIyTX$@F0GkttkZZrhuRG6Xm&6;yO39sNKc*DC9P5D=ep2O&e;Qt1DNDHu`cPO?pzZ z*UWmr7F8=vizVuzWaVtj61dIYFJHzYYj&KY=O1v+DiZ2gk&sp!>RiSY1Y~9Y5I;|` zxh8h)wqQ#P1J!hnujHD=yHB!SUbOn>hu+bOrh3z<*z1TQAP<-)`tP!pD)+qab8&Dv z|0qAHdI@XdW>bR+PvW8h-r!&7cAVa{5Axjv6t-u(e~t>|`zK$`Lp(B(l0IsYp4HuL zWy!5y-%a9R92gsU#ViWlz=3))GkX)2lnpTwbnQd|&CKs+Wo9#rs`|^^%A^R%@&n{* zSQCjPE@rutp+&1pea>`m4Ls3`%ZwHqJtW-z!$SWkwM$o(7nH0{@zWW`E{}R#x_XDV zU!*oEzH@>m%rSjeSv#;y!y5Y%0?t(Z4Hn9rG56`#h#4Ce4Mo7Lv;}GSZp+G0Sf!|u zqo-yk)XDx39oZ!OEnv=kvpKNrxu%AcAT*9Rk2q~5sp28{k#%n+ngoE{Q7BD2oN%KH zO*nlXLV7aOsC+x$Q$%ytjg5|#V2uc}WYFycMG&WLfoPrXHd{oyKrINX-faNHYo_ff z_Mv!8MBS2mzm*h;=I$So<-?q-yR_i)a&9D3=zk+U{MW0Y-Z}jiYu5S}Yf3?>5%7m` zifAKD^f-PRq4X8S6%6zyuY??c-$WV0=gxGND$j>Eoc+*BZb;`qo{2XxQ+B#CLV^VY z-d#a1uDT)cxcGAzs>^Q<>wU?Z$GuOva zt`I4~|8;Ty-+%xAj}A0{c=0a&A$@p4I}3xh>Jjcv zvH}DldS4SyVtR#tL!8js1MphO6J7{smQ?>LegDuZCA^UcdfZMll9&)9$H{*g*Yb87 zn-?M=sQ*7eNrWvyh-s2k6-=X2{?=A{@W`&^#qE1jExWsxS(WT0?t z2|VipJLT-fr1|4f8&NCiKcwRL>k%H&4U`pDk#Jmw2PZuN-o6!1O=N|0)D*YE6`4*> z+Imj9qgz8lmwD7|tbku0a}Qb}+fCJ9f@L*7GElgZx5=I9=wEbiS8ZoDTvt}bX4tX* zv1K)pU3Xoel4;OFtB~~M?Zye60}J*3LlO&K=ktf}c|3$7Y0e5-L&CguH74!b_QB2E2 zg~{bB%`q6)39U<@F*v4|k8~D_(4xbwP7%^)^q9LXJeo{`SzHOyWJw)Qn!kN}suMDu zXrz%>6i9bFt|h3cCC26Ee3;9>5d?Y7f+G1sLlW!Aly@Y|Q{bYh_;`fci$$)lZTSG* ztSlh!r$ok`MBMtN8eD{4>ddgjJ)d@^rTphNq41@?!^lgvx1JY%OcY0t;}*3Y3(Gk- zH#fylKRMu|&nz@x1wcaAF&;AiILG`mwc0~^G63hQ_{u2!0q?hbOr2BH`OLC|=|3dD zuaKd~ZvjR63$;_?HQf_LKl~EtHloYisfCEU?gC1CAikpGmASSjH8B*Ku_2~7j|Ymb zNwYsZE3(!fDc(MLjc?U7wl)Hr(07yd7MkZ+!pIy2-`$j69-At)rfh|WyS+tBt_E3n zToZOoOo_j)1nLo@>=k%pA$gtlws5n(5U!1?6P44%!av4F6Cxw_j2f+oyWYvw%Ps+_ zdbVL$Z12iCb8s=*(3t<%5g()86;)xu4gb84JhZKz$0kH@`PTvGGd5=wIB?zmjdTfKJ(H;wxfP<_BE+AL@)QXrOD+vdC?gf8=d z^t{^tRMeaIx;*IC*#%r!PIL0Pmw&TDx6{--HJmz0Ra8yh4z*)fwuAbW%<-vSBlb_H z$~CXANYsXAhz<5FLUFwKUPXV3e@|uLLTvmjHp9!u`}}*U9SvdqB>{u<)NBivr~MM( zmtsWWAFzEEYF2g^3Z^FC1)c}F?6n9K%H8+po%p+)8YUYovr zdj6;%`#=-GF2cwE@^K%S$xUi7lFkYuo#d8pK~pBcA0A*z7m^O_s^?xLBT+af{d*TK z19Cm&fbK-V{bb17M(dvR*3%S~wjSk{eARe4$|X)gMi8%x#L^Wj;=V-|8ndqrTAC>K z`nTlJ1@sbXG!n9*gV_he79JRC0VdBE4`{xn^$Mt|uG+5obNO8o6w8?blU?B+7Eu%K zAbAVHVBT-m+0<$YQHY_9i-}=a)B(MTei4Tiw19?uh2# zZBy8Y-g~IF%OW)jpFB0+mg0B11?=?57hwrlSwN@heB9}MIfLSG93^d^#Llt8e>E#1 z;>{GQn2@%E!V>QyABjgMDn8d*X99s5Ez^qA``nI-W_Wa{g{i<`4A{N*&Z zER$!{)HT?>P?MRw^d*B@rpAIACzteyPXV4DBG=*OUQGIHg_*j{7}2}bVI($Xt3A}s z%*<3&&u0zG(r2LaoPie9+~mTsXg3TjC3(Glulc#j8V=O%%qD@ zLjC0BqiHuWR~FdL$xlKaRFTuEop#GE<}vyk${T6B%9s8y6}@Y8jM)}2&`8Y=^n4& z`B|cce}T?6eQ&XvRo)lb7p}^j$@-!jzKFfzuAEBoRoTY;mzMh{t0v}jss*?|?i`i; zzUJb=Cf!#`%&$}2S{l=+Ma5p7gcCF3g1sX5*OhuxPp^vZ8uv#6%1HV&2E#zcXhnSd zeR!RR4;E?pWa5h$YKY3=C%(*bbsY}PiAV+`Q^`IrYR0Icv^=*4CDGUm|A`+QxFRsS zI!m<98|AZRA{EtyvX7#8UlQ zpFxv_GS-~6MvJ;{7pOrO%aeRQ$A-tvki9PCRR~DYtVQ!ZbZB=9a_cy-%vP{y(`YAC&UVas23oMljcG_>Ktqlf+(F&NC zO`B98$fjZUT8F2GI_m~DSorYE;V@bA zWOk~rtS3q7u!oiAlmuzKcD+>0Xt|Hqh14#au}NG4!vd*4CJgD&MiS$XbsMEhi}ACca91&Mi?z>x-Mm8+VwGic+akdK>KSE++Rr2OOgwRSsbQdd`HfH zh)dAS(U&9o@6cx64@pC~O>*FwaUoI5k}(s_oqVwLn{39QK(D>CirvE=a;(^y(ZQK|5mIo#LIIxPrWaQ zT9nz1Ys=Ne^ z-(hj2?^kvDDIYc)pMkmnGPxJx@hfDv(yuFf3Ybm{Y`5tT-Z%*D0clciq7axbs$Q%h zHFid2fP36i3t#v0Id_1S$k=IH>Fukk4yqPC@w+#9dff?!4>7xWZlF}E0J;xHNcW&Q z>H|H_C!90Rq6hAuGr#LMfj$c!A%~Y=DGC_n_VYn}@)&*+;wdVPS{#0VyD5Ji#dvP7 zyK-59xr64uY{t+B%F}h8%Sj;F0PvsK&)Gtbw_7LN^jhSlv@Yqxi84R0+{99l^>^I# zaSyMOgja`cNuOh;I9G>#_@4ijBAjxTw3>B)t+iz;KUhy#)hizwyq%Ncw0bw?$N_f(av|GJ1dtLn1=DVON ziTE*@2sB3fl2|P%Mwp5J#Es8xVIIwv95|JCW>D8H;yUa!Fyfg2*NwA{iCpMM%#Z#d z*#T+(AywA*6{XLN9Vr?}%v|GyBfMpT8%;8K?~t@cU8JJ&1~x`izkNBRG+)0uH8cl8 z48L?8bFO?6mWfLc)uo%EOAyyMVfSfrk)NLz&N=Ps)@1*SyV^mrm1B%}K&M6lf@~63 z(1v$exm3W%@1oXG9Ot;H@4ZzZYSuFh^0G5kY{1%qzwbxi1FEr9a2;BR7z~>VUCeCj zDtv^)Y#s@_xTdM0kTT;&xxDSZN|F|(3Z z)Z3(plRm2*R?&6Q*=Cnc`-HnO9cmKypm_M(O5?MR&24Yn7w8nw%G@Un(Z{jB`|m_| z6}+1cF9erGurS#P^3Y z!KJ>T7FK4wyz&+EM3~PuaHb1~aZh~EOm8X5q_2eHPqTC%sQy2TI{)_xHUDQIk7_6d z=Ds)dxaIgI$y#`&IqHjAv&68JTKuIO9F2@wvjm=kt9wvA^5NASA&q7Ir&rFA7dRxI zm)*oXNqh4v`OaRY4eVu({<-y5A}n{4*5a*yi$jtbf%s0xNu??dCi)4>S8L?H0tT8_ zKw?*hsV&>_;{oI6o$J1$odbQ%hHPs!J)QX;%p7X{(UTzU0l08WX{`}%v%zy|q38$N znWDiBta6!Q!IFCpocaooRtqt-+dJ%9sy@PKi0M8%Zpz7TOJk+v+*k6T zg}e#E0&GCUw`AK8}f_KS{YpssGud>3$tSdywUwyJ6z043FPXYsU@>gx+e z4M^QAf6xm$VlF(3iA{5{^DsI8_FTXbk1~hMkgoBINQg~1Hr4V?!DtChx4y`?zCs*h z1BC%n>=N&XjLYT5V+*AB{Jp455vpk1GoGu=e7*nmc#f}i&>jh3Q*fPesqvgcnW_Iz?d*W%x-s_w!*8{yp;08|@iYpq+PeclVN zsN;MOj>9Vm zmb4D|22gRSgV434srrg%B(oVt8RSI-2bA1GxC8;io|U{G zBizW6`wZT_dw1&c2RdgE&J@9DvAERBdy)C(YmH>sHY^*;DTyr#mH z|2+YNUo|71OT)O^9ouJRedBr}p^$x`XpbRkh-N+U&qC^Yio^Ggv=m$V!9DmH#w=4q zX-V#uy=xIJ=H1j7Bic6|qHQmHJkYVvTfOt7s=p0GgERLA4@FT)zd)f&oSrnd4>uKMWX_6D|Z4MS@ zl~3!b4P*45*AI`bc+FOFRZ(gutP`b3Pz%Dg5%?V^{U*Iz|2?%|DB}b1wcc1zX)BpW z>`t2c_Z85F={^>(#6<1{m%L9@jD_b$=(?RP0+P>^5l89=l;{@4XJz5SFsUm~G4D0+ zU+nQ~%g`-xSF9BhcXE0CYnCUBmWD@(=+|NVfrhy0&vms^*4=3+|H&@KE`ZS`7HQyE zk$&%8Ir#3FafoAr|`R*hBi&IIQ45W5(_C$yeVsfuQuf- z=Pb=Y(x^tFoLBEYtZ^&#%d2r}O!k)7EH8H4_$iS)dS! zBs{a|IemxnowO^nL`FNh)IGHraU%-A46ch|i3*Lq)>^jw?- zHnaQanpC(Vqeq3lPu^sMiY6zy37Lw~r(w8Y5h7O09%Db$`wPza_ z*$-40e!H*lzDN=E2FP92KN02FfF%>7mh414#E(7-Ikod6g5>w3lgl@2{YX?`v#zP+ zlizg=Xr+3kmS2*Vb$YCwwhrSz735z8{y^g=`)S)lu}}*-`osOGW7mOk6Nc>AXFT>z zN5xZ>u=yK#9!^9~>KwW4nrr3XCnkHrPeST9DTZX3dkWBGg4#b(LDXawh{>BWkbc7! z-D7L%n{%!@N|RRxbK7*SAdAhaytNwx71UxtCglraj!9wIrn_VBD@qZ{t%jXdF74#t z_5oFlr)rDx!}aT2m+|60wMFRnakGia=A;@-YG01PHg?h<54){8|7lv52JrpL&1hlR z&OV^xO09&=gJuHzISx5H+#hd^13A;zZ!77Vr)gW_<97fnU)3pp1PZ8&d$8oK_>~HZ?!V(eDmehBtT}O!7$d z1;I=ynBuh`l{Havy4Mmc^9(-x);w(&wiA27Ln1r6z}e-pR=KA_)D)8o_*uOuv3ZrH zilkGT#0qy06M>$9uNLu(HV&h-4e_n>j2(6=R)*0?0N(dCT`(*^H`m0`_P6BUiTc^% zAHY|Kx6{&rT)Pcg-6;2{fZwlRu~zA8Vk$zhR+ek*9|l?oPd@_)5m4HkCyZiG`?)Sh zz1G?04=*pAL@w8)u9dH+uOCx?3_CZg%Crxct}*|m@FBlGpuk={xj5PNp-n2}5!7dn zPoW8TfETeu$PC>5sk;^U+ccr(5B})VU-ok)oxJ%$?d5%+)ha{6$qN!+j64~6*zW~G+l#L%o;oZE7dx!P;tKSZ$pKMy)@v)+MH8)ziSpA= zoIcjpH`erEs?UTN^^YHCTTNSPQWWd)VRaWh><*~_C&Q`=+NnD>#VnO%<*F~aoXbcd zR(RXI9t6Bq(2sm5>BhS=Z8Ec6e(A!VSskaS!{yGx~yY4$3!zNy@_t!2Q4G}HSUj>R0rciGUPs5sxGMu-*dNtpG1UEdeR;xT} z41}@6jXZFhNBDfPWwJSMt0HqTEODd$N8jT1%p_rxWB>i$*{4?>%Ng9q6-z2?v<1)! zpVCr>s<6_cAm#;{pd8*WBFm#L6`W*q~Mwy8|FMA zUJF@MgAtN@3BkFLtFhTqa`MVwp%(Ss(7Qa7IT& z?~c=`G{nt=I5VXZ;6!`e0|yYtzjCg3J1RmBQM7Ys_)<{!YvoJihWH7|Yf}`<3hS?V zVME)vdWT@;QO+<27x4adB@PM0ps9BMv?^K#zkBcyfH60-drvVLB2S@$Qn zb}m@K4%1~SQ4@DM&G8YDChH!64drhZ_HZdDV`Q^)|D}`ROigple)<8zQ!i?)m)iuU2&(;b&QZ!F&XeFcqKOHOQnF|(Nd($YBEGeB~$|r`%o~jU`U#{vFz)Q5GH0J>RnSD|b z9*uXge#g?x8a^zxfC(506m-$+`sik6E+DX+){bv&w~5iel{FTzj#+JLP3_^d*izK> zJUhqOb<}keAczT)kL9l3Eo>|%A#f4rPc>lGlDEE!ly)qm&XK-<2T&lNCYqf; zcTtz1P>5r3l>aA-0;LYdsbkRPW=Ab4#9A#)m5B&6qdu>M`4VmNHS2AV3F=0@s-Pmb z!C8-U+&cRafT`65y%IfIs;EuY?G2*d7C-cOD-v_jwh@<=nvLW6|0V7X@f+mz|E#A- z+Z_S|LK80j4+#c(W=Lpx-TePdqC@&mKHdMS4>PaP*7t@7wwF+5xf)-@Fpp9&EB7DL zzIdPz^X6xZap!=&>dU*il+a|I8A=*KQcO~<;-~L@H|V#i%){CBk6gn`9_BI->mzgF zkrsTCf^+f=bCGmS8FP}e23GXbLqkw`c2g^sQ;Xa`q|)egJMutpCw;fV`0~Dj1)F3K zh@ec~2T%(k9HAnz(T9_>&z#y-(AMe{#rRgwp)hToagXU@10-ymWo;Y|=DeXvNl%Lk z3ijPtp}o#|Wo8d{7t`~{^xb!A z?5;QGt5r^7pZ|<}2I%@TZql27`E-QxdVbw5ij0Ik!{QBH%=oQ=0o z0Q%CQE+m<6U{xtmC)?E~7;|Ew&vG1msAtuH98%JDJwF}{&6l4O^^6hE)qp>Y@4 znuNfKj~aKDr8aPRVt7jFCE!4{@6)ar2E-EOQn%6Z@mP)g29vN?ErEDhzhP&`J&j9} zyo)lP6^;^8?H9G_4SyIG@ZN4hg+zH5xEU&F6NjLhsNzF$PW^-rv;G-4OGJ~_37mxY zY5es2g5dGVBZ%9QV48L%4e@V4nvBuA=$1>kHEl)qYPbVrAMEj~g5{K(|GT0mk8U$d zCyvwg5pej#b-HTWo&~I)-tk#7-v7|F#dcr!_g438oo;zTd)+Z?$i(vp_QcgdnMWh8 zwaV%WP^n>$2#ex)s0}{S~52=uajmp6p7O z{$#qXQ~PF**U>fMvq(+=))dEeEG%6TGe!$!CdgMDPVQo0n+!=iY)yd|F*h^l0i zPsy1I%OfnyAP=ux0&4DT-P0PieSo(n<+yzsd-Zh-e4*#HJ4LJ4zjI+I;<0zdy}ycg z?v@onX)aFP`0cXW=Mki$Pn@Bs-I2Tq-+a!^ki&xunl3hy$n&Z4C89W8T2|da^wRit z-JF{%0XBIhaCcpnM0sa8XJ-k#Z!zl40KGi(7m{QQa!1{U5f@Ds7cOtN##)}k6l*EW z%pry5wM`OFq14Xeom^oND2;$y(V|Hhk5{S^3Ck@AaYPms^s{uSU?r3@&Hd+!#Gj?o zEV+)_#w_{9OJkvbNVqq~h7D}tvv5o%^A@BEUahk!@uSy4V+v|NVn#3!e85gY_upR8 zBFZb$RV8d!GE_5(+BL9<3JGKyTM?bWBjDI+D6!L&0)9D6S&(a3c8PL~0;GG&#o|vU z{^rMOH+iui7T1xy7QYeE-EW)5xkbBmtCM%3krRJ>%h84b*<@wIbeVc3#6IDc9<&j{ z&cFp<%k_=255)&-v=40d$e{BIlFrr-&9mJ7KYWCH>38V}FW(C7P53FgO(j5wX}}g^ zLH-naHpC+dKmrviMT&GPsW+f(;f9K_&7$C|AslQ;k3t&vTb{A_bm#D3v=TC#!nU1* z%b~nQ31lPR(3SL(K+pz2@^$lLZzj(SbU>uXDFCZeH|vYg54!+WoB)VA&3))>I89Nk zvt9{(30F}NNHx$`fO^7;B~7e+D66T9vCT33(-NG_X}RUlLzf!X?iK!E0?9oGFzhl z^=q^ibYQV?tw5@&qEKIv4d&DVr;D|B-fn2tWj{oFs#~QqU+>`7sj@#&W>7wM1;{4V z6u6&2d#Cp&Khadr62&wxWPVPfzTQQBR@qrTjMqI0|fZO5y zao-KkZ|T;x^YX)I=_3xNLlL4{3w!0hpQ<9cc@FQ&6F))c*7;3$$~ak1m26@Pn|QK5 zHChzeupMtXqd1fP{^96olNn5t*iFo@sr|%lpGt_;#3xc~0Ec+x373HRgOe7cvpAly zgn)|(M|P?WrEq56^hr+aDm6j)YR~)*t)rO3d5$nT0!2}}*fT1$`+uC))dvS*X#U;g|xCM8I;#PvYL$DCEH@}%V=g#@h+`DGZ zIxqIxS;>neJ3D)SpU-0k08uQr+d75!?c^a_U%|s=~An@#keG-n}$-#qJk{%Rp!={duAIEx;)Do(eBcr zRwKpZ7L0xMLm}NIMUE`TT1r2=%-Jm4-(G}Ce&@ZPfs)blS?>~rX4Kx6SESixO5$(M zgrGwZ`ZRLUG4{4Q1RG}Ll^iNB3^~ca`>($L3pl=;oD3C9f(XCglBwWX7%HrQFo%?N z4TcBQQH=(5_>yyF8+WD$ZN}ekjrAq$47POa|rR?7i z*Ki2{e7!#%=!A?#l`QQ~>h(EOafBq{uXSE@<)uX>QEyln(1a%v$K;#B<(Y`9o!Qz> zQb-_9uM?(3Y@=fZ_6MChr?}Vk{ zu&ieqiw4mHR z##AE0X|eWtabzGoHVPRj_{WK+g>ANcxz6pH4Y#V7vlvPH{HMz*iVqvlN_n^=uN0|n z;=ko9@pN`1a@T6Xeg3(`DEmX~mCWNyoO7?rZ5d&FNmScThPCrLOJiLk75Mv)rUt@j zpEKxsoZnAh>zP)L4ID!vq}70S9ohkOu&4Uc)mh8$@{-+iVcZKH_iW19m2jtQ&h0D8JfSaDmj15yQhpiu8R>pHe)UBBO;+j+dtJ=A(*iBudckbUNnuV zWZ>SQi3E@dqAWIX1XiRJigO3m`9t)6ilvW3f`hl<{5}3dTX*_-0-Ej&4Gx_RSN5aP zAFOpuD)338INSR1be?;8qWQNaNT*GO8EuX?rVV3~xG!Yty?hKf>OBi%j@iFUb5nkm zd|(k)KkJX4+hM*uY??W%ULymg6=xc~&0`j%YER4G-&LEgAZBp+Xj$~7l^v~taPweE?t9}!&tH00F0sVy5jW)mh-JB_l1U)et$r9xc4{MhyVxC{GG zuW!qpXR)>^R!R-RhRt!Tj~!r=z$RwIshI|?{S}SH=uX@w6sz)y>XQsuib!kgUpZC^?6kT|tu^?P@ageCD;GxFbpf>BXL6Ul11xvp)Dm(~slQ7_TBtmr1yqINem? zwz^>#!8^P#zJ3{{!q(tFyeMO=ZU>^fnWuVt%qS@2bNetdI4TT1c7`A$O830BuL@2Q z`O~GWJRCGak zG)k?bMt1t>kxUf{-EBN;Y&W&Y0!#cOoDt8TVn}_|QNr@fa$9|xS=47pkaW0Pbw3#b z@J;;pR>c2kyZryNWd8FScIQ8WTVH>;!lN91$X|dx@K)`u7nbK=Ko`diy%6a`tN;GT zq`m*!dOl|{rZbcwvK2`FI6spoca~HiwVT$lMprbm<~@O}B;|8a={E&tJqCu=$!;o7 z8&(_puRRwBUQbpKs3ONVmnAZU4s~<(k|**#ZeQ^G)uADXiO=ZnCC+|?v2B!_`nPza zV(#d)*!&nhRwjF7HhiVRQ3HXRo1k->32c}Pco-&gjJ3&vjs>rtNo-07vZ1bdslc2{ zRrvhCUjVK({&%ZtrMxA6%7TY2RK$>v6X*qY8^CLnn7Dqn?YKq{HckYWHF!n&M%sI$Rj_}SV(a}~<|Psw`ORtV zRrFley_Ob&%afVjz4$M{-%U$X)Z;kPJIW|MB%egd4wZ53lB6u5Urv5$q`vYt(6YD$ zH-3c$SHPw$YE>-h`|l|(RwpF|o52*v6cFn8dKXYU$$f&WOwgcXxlzZfyLY-mUH!49 zKVP`7)8}%{OZ~DOM|F-mBwtX2oP8GuqBv!O%E58nDRD-4v$&`07ep3sF&$W=>Th&8 z@b)Hon3}3ud)*1;A@7~s#~aRnrBjc#M>tX!JXHR16(I6-LJLWfJCRY-S1z3U{&BRp zM$X;`eTa5l5^{kmH2$(2(xA`S)2vrqPER=IGx$s}I&l%CqO&HVl;2m1OkTlzH@e;& z51MN1wtGZ)xtwaP@n07niier?eNWuVT71Lx2bDQ?QWr(b+TQcZt|1ETB-3XrZXJ6n z0*0d+vNbMxh8HBie^|>`spN z(g`D~Ez@?GbM6F~d3moNP1-CbpFb$K^iSreD`)sSTO#x=nzX;I)dbAnfPwxc1_!mQ z4GkPTOt6e*CPay=C~9z`kt}F`Vw#oY_hA!2U^Oo4x$%9JnjhRWeUe~d$}9v-YV(cp z<`2F%wA^6A|{i zUXi#jRBp!|^)(-kyj(L>*yU7ZRk>B_9fiyB1Ja@OPoj$IM;GBw04DZl?8o&HDZu1qg5 zUWvs-R8cHn^k9~{Al(5|)rlq2yN}agkj)e~u7RcFs=TGt^SIz~YD!PiFYnYu?8~KK zCD#mx-P-JC)5lo8*tc<3(byPG*A=@xk8dJxmnCViaS1d)>zbrr87ksf&%ojAC$82R zW+4eGkYmNov}Ym@SkAXDFZ2w1h-VUH(6(XpxShVwh>vM_;F=BLId@7`pDVxJm|~y} zw1MIFL3J%2>=o>E5fEiVuJyz)2nK!P!_vHl6^q4}&5FY79?gk5xnUfc2L9AL6v4YT zjIBywXAMCv+piyf<7HxyL=9U>Vw6AT0li~4=bG5ed*8TOR(?&(1zXZWB}4QOYLnKH zEzJqH4(9}^kR%y_ajRyZWx1r#Siq??&*jx+MUgntwZeMt$os;sd14d6hkm8D=5=x7rV%QF3d<Q$Tlp4GIQ%rWQ-QFHbRjUru6G|-;b)SbB0vwYOof-U-7L?Xyo;`-?xTG?H261{tZXiMf+NcYx7 zfLc`!*P{B@k)FAR$k z8N9^a)@z6{b)9#aiaw}#vW-o?1-5h&8DVjZQ%>4y8@sCBmXvJNyo(vAXBE;Y=wyk9 z$Y1488N1#E{Fgt<}J=S<_wkhs$r%1t3f{)d1L{_Dbml+Y-W#v5#sCt0v~ z=*~Ur73ZRzR34Z$G>yH=3q$pgx)M2)eMfH^TY9D3_1ohLnp|Cy;PisS`B2do?}T(T z_$#*uU7Op=o9e3A7iDJyFB{pER^FM zl&O$XVNZKy+aQPb{hY|jdX}SZ(Ib~tQ(A}$%xGp`0P~31&EDZnqICQg)YRbR_LJQy z?xzaH32Xpfv}kD+X$skfc`(LW|H+#!w<}N9j5cbfNg76mDc8orK0XbWx#;*gP|kui zMzvR?Pr%L7L~w?G**nRgEp9QScMHzj=pvcyGP$$d$&-C>uXBicOF{KT{ z#1Ex{(z11KHJ(TX@~iPs*U(Ele1!`gZR3`qsb95D=9^+%NapqJ;9(b{ z($FEBwtcYxTY6}$($-IA3wTEMCbhC;+bb^YO=6m@+W2+k+M_E;*m@RkeTHlDFu(p% z>2|<9p4Y=p98pQuw@gR9KUJ}K@(ikIM9jQ1rHm5?bdf8=!?VV*0<`Mgxgl!E=M4f4 zGbXaX_uecg3&bS)87?i=`5m><`;p@XsGygGp4emzD7 zAE9B#$?OWALC-bLMGt3wc)AFfu$wuTp4tAGwrI9XVuf$(;xMlzV`L4qz0zqzWYG(` zTJ1I&3Z({|i{KZ;ZBRLS2E}Xwt4osK zs2Z6y=g13DO4aaHDZx)%^P*Vp4hK9aAzI*^r2>8lCI2~b4`azhJP5J$T+k?f(IIzS zHFD=LP)tK`s6x<(c*DCX-=faDt0{uU_{R4y0M=(I0Uzl7-Le}?X-17QJfZT$d=gcE ztbS-)*)_fbW;Txoq+7^0?mqb5>?bUKhO$#-OZHcSe|Jl@ zVC&hEGa(E%yLzQRtCs|naF%iv3cr`IzjkL9t(sjxeo$j|R}?-1-4c6jdQ7i>&F)G- zwUm8vKL7ZO;Nc2dK5!?#M>>H?TLu*kNSm%4iInWlR8O3hVpG!pIU%-cD{U_!#L||0zqaAX){8GtH zbS3%F`hg@4sbxr754m}&zx-|W;^x=s0|qa^m&3JK`*X!%%ZRt*A!`mOt&F83JR7fi z9J1ldLRTEStryoN$GZ;gs11uKw4HD6Pr>&T#!Udu%3PE$sx0K91$l3H0%whCac)yU z!{3CXI$~+i>Ie0WPRQIs=hSbLFs{ldJ7E0X-?wxvVf8&;shd)u*!#z%w?#*X>rXlD zIC!lSm);MS-e8U&>Y~PpB50OD4`I8UkIWTj_S0@4dBDY82Tae2wUymB-FkfQ)$JVh zz%lX0NYVL`OF8=+F9LQsO4PT;xUBT7gOdi^I3oOU_uuv8QGWb-KgiI)cFb1(%B;Rs zwes3TJn!-+LEOFd#yBOiQZZ14P-iUNhx;U^FCvn2%jDE#TI6e^)g9diBGwfWO7UB^ zr6BONOX~6VcNDsz#syIzSN^*^^|B*`kHR32q=@(`ru=uYiP^;l__gxUCf$r*ZtGO# z-t8zNq?qkEctvlR(}|nhJ5V^X=asysrGV5z;(J)l+eSE|#J;pW4M7fDldINvebclS zXLnO6i!6f9cMB;+adMZ91Z3yX(L!dlRPNax)Q7sJZSGf3&7hCkkM;f5>5n-ZET{Dc zFGIg@hUYyGnjkp0&Qh<`%73dypSRmY@*~|oXWxr^Xaf@Lv=7bqtsp*!?vgWg&G^xw zw~j6L+}5w;LJ2?X`Q}5XV#q0d$50K(ejyud3Oy-bH&s&E*CXhRemI_hDs>Ja8;Gij zBn6zei9l~$@q3;RMF!FNCHd3tmpJllf2NUntXg8^lb0s6o|8#!h+N|F4V8TZb*(El zPR z(+pq<@$S_zq}DIiPDG*98n@$ZK}{!$clVMWKbO3jz@BpXcP{$>+{F417XPm|vPyV* z+7@Y#dU}dD=zb{JN|uKG!gjJ~ZG}#k6}Gmf(Lw`o6XbWF{}M_xWbjc#=6P;rNgcD% z$i8PXyym>*A-uOg-4ph87N-XH0^`6b=L&^Lsr0!CGo6Q&mqU+hAP4V<(*lpoS~*9a z(f4um6$-*FFMq3ik~^^c@oz~-|80-0u+Bl_5!40tvy1oABC#2<<`~6=XkJ~DiCtY0 z^qfXg@W-(Qs{w1Qidzb5;%j^t2+lYTgd>qVMKx{B)AmMfHQ5T@sh>rh`u~{GHNHo? z?jzn=eJ;i%xf#QM#D5fT4IN5Tbzn5S*~`0$9r!b!|Nr84#dNZh*A@k;gQ(a|Um~>a z71l|Hsnja0W4-$XFQDY9fx-rhY@zdOJy}q+Yh_7=ZB8pRVP%6if%yr!ZkvaB+&!^l zZi~uOOPhQUeH+T#?b`NmH&Fq_VayW={M;P<$g5YfXDz?M5c%QhT6zh+alP`6l0Z^8 zH6Ae5pTZH7CN=+2qo4LL-SA?R_S0v;Gx{~OmFD<$6~-QZFc@tt|AicN<3Tt9eI#Iq z^ts0-ykfOSCzJG+YvOCtG5z?7dGw~E$T#b#0NeqLfSE*CMZZrj-+ew+kj{t1d>;-WQ>`EOJ)!&kb0C&Woa4)ieflU>C|4sU z;oxI#xJH#Sb_yz9L`}aB6(sQbCA!jVD$wP&_|dqL6`g0)yJukpZ_i^#wnEkKcuPPo z>{@rFQF?0a3>?j1%Qv)H?^N!HX&o~r6ikCWoNCe3v{iP;Q?^%v@8p&L8F95Ko>(-J zOHgebLY1n_Pvz7yql&I~rpU=oWaRqYHm6tGgi&%$NEmCzF{d=IWeVY<#5d^BpFqJu zQMp3{+l`Dv>QA>YYY#=|aCH6k0J*ooeo=0ryV(zxCyLX1&Zb-V%)y#rs(^9jz+4uk zXkF`)a(24L2DexXRLmHvLN_ev-pq1iM5DHynWTj5p8guRZa}o;Qna`r$W`~9Bl-hE9UUU}cDwc^0Fga05r=aAJlC&+RTN5!Ha7v>{{2uvpJ zy~$)nc}l$h%=0)}zAZb&48qS6=Y3f*-NO2m9JdIQV$MPRW4|)%mA7a5*q6>s|98jl z**@SkN|DnE(A00X)0{EcCVK^EDbuBOB>Km=z0eym;jT%n0}eOp=~1Umr6)8Cd7qN3 zuq{E8Gr|*@TiN9y2y2pYDgKl*{i9?-wk}pDiTH87JFR^FcsaZI7u_QFCUG;7`|oYv z90A7&f+5kYHg_SeZSEg3V1@C&2gA#9+C^5(+X(_8ioZ zNVxlk-n!gTYhRSaRv>1K_vf9)<_ro#%)rMZzBVOn3?qQ-vXpq)PZ3?^)ZXIyR`Z;r zTf^A+Z39J9tp{=yY_8@lp81|~!kO8+hx#31BGM_UAtr=jkiGGxI_3y?WP`D0T zIqT?2y<0AY@_#SZa3@EUuRcKe2|6TrY|&3U5lV^JS9T6Av5`<+7z`J4(Y|&Rg)qXpPx5>Ydpb5dJ zTn*5%aXI?RHXg~wiEgP4GY5-p-_? zOdINXP7Tqmf8a=U`VbpfS5y7&no!zy0(dfSV(mmb31wov#}fw zJg=xNakuj8r`FGK(@X8|6lfd-1U8zP?hWmd4@nc0C%>r_csyw-v3h|FynXFXOE|VJ zZU-1ueOyFc)prqwcL()|PmCysfw#9&vF=ir!&d$#rMx-OF@ajmWS;DlZRy3cyb~)#84mniD1Kjtj1kBf*}_17tjlxj}O-SIi~DcCY(QAQSUON*r)#? z+GcBWrD>I2a=AmukU`}Xv@3t)Q+z4gs%wi^_3gF57{2uz+fQ?w%f(z=K##wGRgH?CBxrKKqP7<^i_ZIQ2pMZ44Ud}c=)IOI?D@Gg&B;bZWP){f1p$*f&@r*?jt zn5OLX+on;Md9S4LFq24@4E;dIHjQi#L- z-y%3pzNz_4G&_jsiH3QTz=gXlEz{r-rOK{8P1mBYqHk_fH0-Jaw$=E>>7nJhTbT1# z4jmSsupf4UVo6(5lcWYer!XnU-6wT#=}XPQs|>Mvjdg`h^PQ6F@p;=RqO6V-_qIUH?<{Hqw{`4;9W zkMfg?ha>aI(hWm&DSzS~!|`0pd11{rjg76aVbU2BYL;O85FjzHCfhGVA?CaOI}LUa z6-hn_o&D(eak|W-;X_R@73oW!Z~iY@=T&%kYNYGKg72{kux;J@Z>6T)biv%Ve*x{f zw;Et)ABqNd(>Y$j&xPGkhvpzuLPh1(uVlmL_s=CME5j|tR&sG1(r#alrf0RX!1EMM zc7`^nKURLC;Z?t+vj@f~eE(d;80Gg$CkFaRF?Wh0cOVhHUr;9&$HO}Uq)s+*E$ECD zXB-Zq~VVd7T!443}1mr1V|q8_{uOwX#U=7@t~B_e;kkL9qLV` zK;`ZT!M&JEdk);w0V(S%ucob; zVrJxu%UDo2{S-Ky>W77d-2|ssloob-CAxc^tmZ;?4RWWJ$9Uc@_d-qwmDID*u~AWn z9wOn^ORA;GiHKcnnK&UVcOA0K^L!p|e+e{P2E8)U87U-A3PqU!gorjoSf zbrPBKV@8xPq^HjiYz*Ct)FK(CihdvJEOMI_1OLT)_+*4a=~dsGu$Y-rW~vunkx2i3 z1L~CSZ1$NtONqYLfnk$-wQSYLcQTuXj^HRCf4DH}-r>ho9bP||oxz?Y!|}wqU*~K7l3s@(Jqr6vAxLr z$gCT3yLRpy@RNWTd3A<$dPM?{&0uF^OQqaZf2>g(RLMn^S6e^8&Yt^B4T(%C@zf;@ z_GSIqsuoF5Dd+y*`cpY9V0|Y6WjY7VF8wSm<^+@kGeA{o3F@xOx>oXyQbTeNopJ5@ z?liE?q&WjK_KG_4@(PpY3jW}A+6g43rtBNf(UX_T{>Aw%o5c05=#1RZxnb&?Snj{^ z^Z)FN?aIHj)hEDq-X@bjnU|&_R96$HK|8}(zf7keb+#*i8yvQk*bF>rKwejJq?3dU zH*T~KH$g+sVG7>i$)8R2E26odRz5`r!LKeYDNbf}6tF=oCJa0ebC03Pu%LNqPpbGe z{KuSAp>Y&3I{^(>Z8VGmmvrI?OMmBuhxtYMANdBliWm83dz=24#B` zy6W}_Io*DpEdJ@s?zXDR7hh2p;T|DqPQFzsZvZ{V=o_kImQ$T}wpwU?N8rJXEkz(@ z1f4*4lgQ>`dZT38pS1BLePSPpyey#FyEv-kYs!L9*?9}v?9}7v885yl_i}^swlcG! zyWd_+SG>;BQ@p@edVNpye+JvKd%fBHS!oJ?46@AAW~=|jWWVVo$hh*W{q?7~cS~bQ z1Qs{hU3nJC%?!z?OoYqdak2VsmW-2ZczZ3Wbs5;tS6zTQe==FQOi^9g$KX%h#MpbH z)&rRt?&bw#iyx(a9e8{S_n;O%3~7(mO@m3(SD)_dsb#DJPnDq)E_eDevZ)Mp2~Vd)aEV2ogwIxLd^qww;#5GU zDbg*3cJzYb0T3TV#gsk1!740utIljG->H-Ec5Y(l$b>$Q;LJXfol>ifWFG74*?9x_ z9p|g+SP{haeQ82{opr>|hG?U$FTXhDZa3S!R?6Y#T0eOD*fOP*KWP^%LawXR6D5%D zMmb9nybvM_$Dp1X{cr2uAe{`50^9v#R#T&ngCztOz@ktLPox$rfP^fUkK|WklxlxqWDYo+vr@ zrj&tpGv)LC0%#=EvfS6MI-cct#2&?-4;K?WoUc75eX=~F&#D)>eU=YRV+e^9qAJCR z2G=3^2a<2MTfO{#b=k{2<1oLyn}6ry3ZI*Q6cwYE;{)w(s`>eg&Xk;4i`UuC0rBc& zKfCY<{D>RHG815?kk%3!C-vYKUZ6R7ns_Yb&{LEai@K(GwboFJNx0K1fJaP5})+se9 zVKN=5O+#EdO+)usZtY|ftp>wT@Cx-T=I35#Ih&D&KU?_kKuEcEfdh~mo~_2^VnLbY z#d#kP6^u=F#c^X@QRu&agSv$;%tiF6I7DZ<2`hlGklD;=aY_yy$MR8eqowng;YC3* zb)nnnN>uU{KX);4!J}d8?tLw18H*z!^opkg_dse44$NZ4FH~qWs1gVj9p*BkLV0Twq{WQl(yXj;9prh%tmQNU}yLN_8V+m8!uA}%(@k` zWU3LBTnWrJCm5YO{D#dv(O{GHRpQrb#M4ig2vT2l(d6dH|F+{7S$ur)U}Z=GLmCkG zZBMV$(`^%8C+-0l;g!X$uh)(lyS#)fZ%t{r0OJll*NGk1seb{lC)_F+*EeKJeH704 z%48i)Y;DbKmi@p_WFEvTwJMM;`D5-)k~(u`BBFUqR?V3klnSoPbep1Z07eO8y>?x5 z?f1v zeXd@g3b7}mA5QI3uN zg2%CTx+vkG%kcDM1yN~FpCQ%?g)anGjP)EY?8APhX#?pfg;6qZ+qy5m^vsnCqy8BI zLjPC%MfmdX?9PCYTgc#?A;RG2>IFgb{cEdg%RDRA0X|ak_%2S=xX5qMKxXC5MONMcHA9`?3(FE zY<5@LCKwO;y)ACkI4JdN^I_ zpXkM=9YzX%*Uokm5rjvMKln$~k4l7D>-w_-@Ag6EE+`72oyh9C5H{Wes~^%_Za?4p z2?`YTG@7_FGsi4>950 zy?+g}2*p|&eQ#_MhkU{NVPK;u)F|F$+GSDqliz9lSJE4e6_!Zdj^_ss;?d`I^zVv? zO!im?Tw*YE;#3(aLWxWL))Vi0&+kPv0{Kb~xYWtz+CIy%Sa__|dOIVw8$Gv@ zrq-b;#>)h4c5)le9Kr1C*~fPI&AryI0Jt)Dvtx&;7mI?6yZrL4=N_L-qlw$;7MpmVL}>9qNVK)VYk6vf^KDF346)~x$UI$frAZFmj@Hx_ z*_ss~P9PO@iV27gH+A9X=!eSO={$(-(@cJrJtsu%;;EB#N% z6F{Hi;LKDVG{#7>UV(7vO@^-}exJh=@7qsZ4upK1jMPty?HO5HsnB3K)w#jV7U$&C zBDmQs3{p3;MF(C$mir!}hNC+D zSz?f4T^VOfAyn1C6G?)L)q0=$GmbSx-r7y!OkG{VwdC0GW*XZ-UhL*W`zwnA+2;}$N>!!3elXTe%yox!ru0Z<*);9 z48za&Vo28lB(}o&acASqS2aXNza9@N9=BuJ(0=S2JCd>sYJd&@O`%yqW7y#=#`*R8 z6-c?$4ZT^1=_g7D`=8nfzWrlzy!}`Eh^kOnpT6nIu=o%=L+>iIU8-DT>6V>2F!qJFk>J}PvB{6nuo9H&T-y^Z#TTG^5${012s-zf!tlL zu4`IP_^;br`(JDpp}q^sAJGSfBsN7{36_`0msK9q*=G$$`Kta59NPa}Ur5OMGtQ;C9ua|j|YM&>cp0^`qKbErAF@o(!>AK%QM9aGNklX z9%wGVG{YFI& zYK`uu%rkv-YvjL!2k@0p8^;7|olA&V(|=+HOOs=QfBVC~-#g8CNmek4aut?=D!OD4 zqyuaUWv~s5!(vv@oxo50`98=qSL}9^+z;$*`9rEx?@}L7X%=%${z!E(=I4qV-I$M; z^R)i7Rw?)I;-VYPr8f8lM915>`)(Kz!M<$K1u=IOON`k z0t!ZD-O{#?&rZmsSzBKfb_;tZl7kRxnyZMQGal+>FNO#bFEq?(|4Xj>(uMVg$#O@8 zA-=_gN#V$Q;NWv8tQG!23oG!C$)k4f6DCBJE>5yc7(rAA(dob~b-do?omi^wO_0nz zy+4&Ju;oeP&&&SQYJ%|*;sbX-?wJ+)cd)(9!jIPD`?^q4p=fC5xI2q%PbMEIiK9#= z7g%c^_7`A`IzKwLE1J{(0*bCs^G?X&lL6J{o07N%nJ81id5<=Z2vazRS35GweDr1+t>(Sq@TuY!*?#f3Z1PW{A_16<542DN&-j38ebJsY~pGxcdtbW46Dgh1h!|J1`AK5-FeyFF< z>duepGe_IFdxh3l>)vXM4>$s-iL?AXfmJ{Sv{eG(GfKG&F@DD;MR#XXr$#T|31kyu zMwB{EZG4&=@J9XJ2l`6RVSNQU%*S|z*au3k*|^AoVync5Fx}>l36jBSbee!$8jub= zmst(QxDtlxSN~%JHqltuAeL}u?UArE8JktUBEdv%`0i7{z>Ev;MssM(Mo3y-+Z?ZP zSLB9n3BK%Y`q4ek=9R~rsd~3%!tMbsLFOahwnOKB8p1fOps^r(7~o+kE7J?;@70fr z=grrRxsr)o)?3m`++C7m_q_Ro8Vzs5M>c2z)*)e>5@l8rc63egbPcKoN=29sLij3- z7?EeXEjTe^8?tsAPY>jiOa^~(kgEr+PBpA*eDx(Q^O2jW6w?>tt%r()VLMk{jY}Z? zT(zdbz8@B*$3T{j-^ZL2A9??wZC`yRwDj06e|Gcv+~hCd5NyATW5&5(;5=m%f2fdg81bap3!*Ee&*GUQiN_DAi-11V>Qe%QeAOG7EW@m{(I`xxaT$7OUM zxQ!aWsMrm>6n~fv+Z~tG|B+wt>Un%E)4fV<^Nbk9VKP)}T5o9x@C=tpf9b>kK$X4- z-})r6?#n=)XR#eSOzh$qm`{uO!i!=$x1N?|6GUvKc4+W^-c>+(&yK^Ci_h;Iqh4hT z%e%5KE?jy*sSUmx7Nu`B^-*f;J9_spT@MLe9@QHD!g!&dt8B01ugc{CVzrM$QJHR~ z>826Xr)l(@qxH&ksb+G&Og|B0I>YJ}lPjX!*=twy$ll22(F55*%|+B$uH4OUACq;r zKO4(9X9vA$k{#4_>Ffum@6pd*da|kNYb%M2JdKNZj&?er<7&KQBgJn?Qv!^-7i~0G z4|ZGv!b^bt22@d}2UW$Q!w`5ScJd=V?Z+Bs>M=YCS3f(%O)qpZAOyYjT59P)U8WsK zjr?*sn*&m{EZL01tL5Xh;Pk7%fb(qvN}Z3D6Ifg@PsooWMZe#S`-r`Rr)bUQh!t51 zJTPNNi7<8Ec>SXCV&1&0MC&UVxE=2=IJZrbyWmFEB1|5&_M~1noDGE1v1Dm}b{QNe z#_`zgP7oj{LC>32^5D2-@RA#-=eQ-uNCOe7EO>?qp<)Xi*RDhkupg1{r#DZZ65RMZ zpH|I>{8~uv*L$@T`%dM}ESN!Y&Geh4H|>sSEAqMqf|rE^R4~4-}TjsCCxOV;-PyFgOCc#tp-S zqm;rkwvY7f5aLOkDb)a!qu2jACdRQkB$p!AF#M4ibg-MGD=MF8z}Vj7fTc&E6Q5Tj zHDv5tj4=A`t&NOX=X6Ar=sqr_o8PmlJPX5T&&LVG_Z;XMO4&f!)|K zHWj9s#3L!Dxp*J+`5c~$P4iPxykdU+`Wu_;nX_2yv6)>ktAQ2q%CZV0 zdP{`gOQe`J_>On!MAE-JkRg%mKwz-K(&>s{DVyPT{~g~VROWiu_#Nn2urN*bQ;^3N zmp~;rah)U7*oOS-v2|lQa(JeltjFBKtQtDEJf$=+21VoZf;*>=HWGhzc_b&FESD3x zG2xx+^}u}IIccQeP4-5G^H(v(Z~by)GNNSIS!6mpe){S;tXc8 z1Q>C~=(}gs2YmF*<<>1DWUOCN9_zE{A8MI%X1{r4sJKT+lWPkvF#{cu8boG;pedeg zXM>2f=o|MhvHuO(?Z!QJlzR~bgwnO{*7@J@x*9#w31v{b5~=C;|8L!Tvcu%^RhWc< z1YSB!7(+g`aG>NF#*lZe&_3yC!eB%yz1V@+>8uBWcU_DgX|i#O^FGEmUx}^8e`L1! z!g!#BE(v&wW@w=%j^eBg9j#Vy;A4$_SEA3mHzenz10+%Feo4q&lQ$%w9nk1BlCSVg zG`Beg7;hpDd^2gNBLk=Gv~Zdu{p8KNh!U@|I4dKy*L>NM%J2D2f4AYTjs6AXB#HxH zTdYve`A9l$SyGtI9`0ffMOPVK$4MaPt34zUZY^1P&1d>+(5OJ0^3ObwuYN)B@fq;M zL>F5a2)H%r zyI{r?s7ADT6C>b3u!6rA%6aHdT)|4SIV86e%fZQh1Z0y@yp7gUiE3rz52@#EV875E z49LqYoLI^0pu1;zE1#ueP7Z~z_ZAnK-q8eDnymxFDO|f3J{N>sN-~-nQ9s-BGa&aL zrvfLez!Z#pMKjl){fy6Z5Hh8rI2C*OSr1iy=SLV)=Rme_$Mf>3;WQ}8X@$Kp@~{t9 zR`tS!9~VviyJHt9g1C_8@^Co8JraCL^*%8oN{R^VS*#{SgmwtT6?*~mxa+Asm=~%; zWNR+!-l%m`3TW7DK@e@i;GC{I0S|4i-Gk=Vu!j^BEc|9IgYc`j_77E{!)NFC8t>Z) zgN!P9WdS^WfB+vneEu$f(1S}e-CuwNdfgh53;wu@Pbx zKUBU$#<3m-%<%^NSlXXWUwHo`HeEL)6r;-GY`Y31t#TebFlMYqT!J7S2`U&8ufgQR z2%Bn|_bNoim6U;HW!z6iV?4}z{lgd)IZ7-iYyWVKFl}}F5;Sz&FqyNh*;BPgaPPx{ zYWGhZ%9Iu9uW!L6Rxqie@b?q3nzNyMUnL;}OW<*SlH*szMv(`tgquUHAUD>^g@S3r zZvzhE zw`Zrv3GF+2$s~Fg-knF#aR{Ueh}=1nGfGxO#v&+~cC+Um3RjiXk;dO=@n?9UIc|Q@I*xOXOX5z&N6H0Bylv`~vx>70$y1h-Cr!WQf%yi9hM)pLF3r!9xkt2z0PcAI*1Q;4nZj~}UX>KtsjzYW= zuyCS>*#Z8v{76`4`{lgu9Z2#wpOTZKS~eLMEVnaE(OVr{4~}d}&Onh~l$6jVvx*)( zr%RsXv3tie*`e}H{X(w@RaND($dz9$~6*elL1lg@PODU6ZDzEtHRc8<}B1y*(i}8Emmo{E_jtRU7l->4E-p|yvqtq zI=`&GCtg~W>)0(dj>&6*VIDQ311>Y$RD=_Zppu6R#FLt})9QaijI z)#zl;r{!-7`rV}iFTuU`P(hFyVe>Dp07%{snYO+&!T zJSl-!klyUB?r@e7e#^NgZ%Uz^+3RG3QQLiN5qBG3o`70Z?~dP3Z5tT)E=c*0tBnI~ zYlFq&i`z$fCa@6EiI>gQeNZ3th{y_lU$Xccl{xv%)LvK#skMx(Hz`0S#d}_JTcl;z zuBC=~77XjMiS&yqX&~2W@?JNC&gX}KVyvvF!u;^(54hu9Klh1brIx+FUg;Zb>-YVI z1CJYflnbzuW9kkTCfE*sVT&VgMxJf}+hYxymT(3YG88hvrEDpD@!r{3ZxKdxtwKYf zIH=+=@-UNrhLeknr<4O+TgfH%;jI9Mq{S~M^yWqj8e!}9o|M9$-9m2@02al3d%?V89IAO z3M|%QyfmELXEQY|LM140yQ!!Ij-o`-5D9L}f-qRP2>{*a5w#qVk}%<9K#Mwp^S$B} zt;)xdX`Dsb&%5uH-I?B&!cVDQ)M_=QQji>w_6zFpP$_Vz68xldu=!*78J8mC`;STl zvrnp6I=Q4LA`QuMyt1Lq;wk)QbelOP9fInB0veopL-gcN#9?s0xa?m;GFXKNys%X| zf`4|J;YbYb@rBU(k5eHN99sRTqKx_s=k@-NH!99dRF9|lbR3$gpt4{`nTZl&Ya7L4 z?;b^rCD>4ojYc&-N@a55D_F7^QI6Y2UnCEl$fw3(QVEzy zGO4V6RBAlQr z$}8#J)7cOVD8unv9%dA5N%DkvNy0HhuUYTjsq|-} zsRF;gh3~e#Z+v=_g_2EZtIC#B0@p94040Prmo2w*5b^T{FJc#wP%IS zj1_F{6^SJR*F;MW9p!s)scykH#&}BCcW*~Lc5n|Qf0I$VyS@&!BJ$8mML_T8EU!N( z$YpFm+>~jbStzjJ?l`i_2KwpA*77FozEGqcFa^X|`(h4AdhI{67Fw$R><-$Cc~_l} zj-RoeFuR1_uii{;qSiZ|>w@;dY#`>xB|UBY_NL^g-MfCB6s?2H=ZAF_A_Tp~O^hOg zj0FZAd-?799Dm2<{P{1FaX)m;JKSFpCRVm!GV6boh*u97=k@3ML7N6G-v6>at8VA& zGuJS#$&UauAN&tg(f=WaBLCkN#{KWU?msrfp;P@Ow;{*~N??Haz=5i{$M`z^9PBI8 zl?_zUmxIET5^|LulmhDS?sP4cA7HETghh;pk70)&;C$-;mHUG1xaIeA=FrPw#@?nM zk`ai#-}_lWk_W+Cy=t&uR!2vR@{bEQB>R!iRt!P2 zz_GJ749EIOT#U;-s^7uYhR zo&EI-bRfORW({73y5$;^nK`GF;4xm9T;rK*8a?dd;9ITf^7fpmt3by0HjMFTS9UnK zZi2V}KD3m+P9kC8&rrnSW(5E(5W`qL-=Cj(o2%FFbdpVFhLZWmAX88x3?j4*JQ=L6 z`feu*e`*ck5=-HX5m%Q$VEr{jHMJ1xBXw`*(#57aU0^mdJQg4G9r>~5vXCwKLL=Jj z;-$N`-7HZ)?vk(1uf20Uzk~O7QXVRwrPwM(U`DUFTXyr$+%!~oIf)uGr>ExLy3bvZ zyffWGA+RAHQIpjv1UPr>d|6>03K$o-54B*0(V#p16ovgNAw6SGm*Q5QM^m8+S zg^NpAK+fEfXuPwkxN2AK(l~xq19K|6cy-Xlza_6 zxFL14Ry5S^GN-1<^U+GR|lYdnp#2=Yq#saVf&80y!OJk|l^f zCe(+ws+i`Di9WT;oI>dhZbA7mzO5$?-tic+$mE!SK!`_ZqQF{b5$Y25ZQ!D!P~_s1 zM!jW5MFZLQJau66hXv%BBi$RSkyBfISEr8ZNJ{;*JvGhjx<%W*gGTGzt|?S81k1|+ zfBHv$#t+@zIa#1LClSYHUDJ?lV}TwD@lkV*cZ9q6t*XC49%t7n=Ioe?BD_%%ytNFzCTy^ka`Rksq*v$^bA2)N@>b*n1ww8!e;B4n zjiT8}{Knl~|9r7Fs?Vt!&U2aO;&=p$dhcDQ@SwqKV$8az^nN1uIyDR3P-*xiwj z#^G{cCYJ9(mYKh5aEwGq;(2=@-SX=Uinqy~>TL=g{_%G(O6?X*J_e*@@L^ zfH{&5oT>7&Sp4uC)5M>^m!E@RGf!;Ba$R2A@Jy@3*;lfp_&(FrJr(LYPM+hw1$h`| za@a);I0V zU+?khcuoa;!LuIZgMLORroJncnmcqU!GGb@YLs+{dCVj3Oq_lZ=O@B#dIf2gjSvxO zv1MEc1sYwvw63pH*h+{GPf{`)o$F-|)YB4kSK4FVhc5KCs;sZZ=@cp*q*`tH0H6Z< zv!E5N<@oP^;acM*F`vk-hD#V_)g|+n7ORq<@dNFJxMHG(#Nn>5#)Qv1&$vA zv6~@L?>HFMh0)?6;T}gIh07Xib+mx6Z*2OE7reJLL@A)Nq79pf&gPTnlcnE15QqWH z&)%3kQDmnoL`7=ZJ*x$Y!0~ws;J>YQ!Q;2y!36~rTQx4E5;=nQq0+!=jbbG0u_`bs zx81ZH@9I)BNhn`0#z31wbZen|C!nc5Jm86h+t=&s0r^P#G?Hp_R0|&lLQF2vBR{rP z!ak2R;8gl6Z%mOhWnajiU+O5a1Te$}3QPDB>m-kP6yQ!%tvB`?ldR_5&V=dp4)5mg zZZ+!V_^|+m$~`QO$Ikk-&QNScdz5}^JiGeUefA{gk!CvXXNChMI->zza)FiQRlT)A zYlQDte736a)HyPzwD(5ahwK5)ObN&FNN&WPhJwkFxyM+Ruk_%K@Ysw*e6j-$7&vB! zVE4jdwo;Y939~N$X8C?Usl@0qhk+VPj#V5hB{>FHquRQ@MuAn* zu9viXzm}iNk)|o)^b9hmZ6vt)ZbIJrh}6Bm7KW*0WKV&zt;(T(R@Z+sDD+xhqLKPd z7h6!fp}u9-p0d6^WWPDNvCx85y1M#&t0|(Y!O>ALl|hmy;rS}21HkwDj#blRq~{n5 zRg&pdfNdN|yj_DkXuG8W8amI|dp|fJyaTd=(PordE?4muxSCL{u^OU;f;EiXFDCok zKqL{5I|?qEL2QBD5d9VkCje@%MzsBQrgejD2=xZ2;{))+4mp8NO$hlZD`40ynrsv0 z{nz0V`a4AQ!EtThbk}k#Of9V*bCB8c&yI07jV=^^73)IA-A2IAxK!~tHpG+ZT7H_c zbuEw3>9dc&KRLOVZ#qt}>7Q)dlZgw3_|K%MfzDW2hy8Qb2@heP^F7^!8VaX7xuMopr{bmBM(z&Va#`SUvP!kJ`->8G1B51 za9{(+{GGp)oPT}xAnShrAlZ8w*58Vs;ph5NV!Q9xwjZ^yjO&i7Ik~{W^`{~Hd}rpI z13A);v2wfrURB8hspg0Y{IGGR(ab))CpR)RHstwa z_GH|}{(+kr%WshuV?W9Ny8Pi_dp@EQ3)-hW=O2Tr=R}C*SpSJu*N$rH7Zr3I_(5Ov zN#q+7|JQsme_$S193?RzmhtN4GkkC1v{;6>-eQ{qkrb6t1G>}%gDj~!e8{XJwgirU z<*xCn7twfAD`=IRekA($$SrMyD{%QNz6|&IjuOe-b_=^!Fr8!W=#?^6>Cd|NxYO=;z0grl%(nseX6@vX&=33J#z4!r zVi#+rTI%9MJ6-byiMouOhm~`z$Rkk>Kn1X~469R1ou$NJdt*iM_wvb#6YS2lO1#rI z&n=Z}YR_DZl~GL@IiQcvHEtL){LcEU>y*A4r;edi)mQOqf8iR)+?7@CLnRxnbcu*+ z&%Ef7MzCTG_MZ9j5y5%j?4tNQB%57Wxlbe;X}^xVGQ?B*h;D@`;gfR` zHs68Vo#S+OME*Li52WRviP?ue5%zT*2pj1xRn%ZW31=5iVZyI7o}T|h-Pr%G-t0eC zXI5HWmDkabF~84|fU;w;D{(j?@lGh9%pw;f+{beZ5R2&1crKOd{HxuCNH^(I+BzYneD3E-LfjEY)teIt4 zfu1{s@Nb)u|MngiCb{ZXK;R79I)HvSHMMsYCzJWLM=>G!a_#wuSi^iTaxq~*aC}s5 zr5K;5Eok5XGp41IJQ%M$4bH?o1NF;G^HdQPS>OoZ6yN?4|DQu6RrK)0OkB~TSVnp& zVnzQc+R3-gd)24MS_k4WfdVZVn8W^$vA2Gy)9qdsGP~&D+g^s&WK*<4!$6od2nSt3UCp z)(|o}Al-wE?yFR@QNMT2v#gIs0gBP5ZC{z7D~Y)SuY<6nhP2IG^f=hUD$qC9@vlD&#0 z;S2%}fJC(a=U%ey_NKm9JP$f?7lv{_ch+Ke4AFBvq>ydAhBy(IO=fd}cX!ou9~$#4 zNHD3HhbUh2!66bqlN7#QmLcy5U8%I--;;N~bg% zjg4>Qs7$vqS5>!{D#-{46x6AY4eimC5}D0&Xx z2;Q{oB!2b6VWz{+NV)?l_mfPg^A{fGf|3REoIm}FS(T#_TVx2{6DA+2w9sa=T97xT zvB@LM{yq3dvW#QyzN^>Er}5Tc@zHg>s88KYlq9-cA!ztK$X~(gNDXUhc;FFaBiV#A z((uEt9)+=S-AI{?r=3JChSwxZ4esYyx|3 zkvc1cs)q^>uLKH+8*@A36KXyp_pOuuf~G_hU{znVL8?FQz6AosJ!x`+I55k{ErBRM zMMhZ;cN#H#=Az;IA48LBBP}DfsqC!XAfVxbtu1iz(31i9!SI~)Lo%qC zIm|V^;lX&OI*1*9FFck;prhZFx46c(c!^_tbPGS1RP*tD0d7cDVS@f@lA8E1;~(J3 z82H6k&Rxs2N%O#r_(pSHoZXjf0(qie*wi2WOmhJMQGJB#XFvG4YjGs^|MvBFKt@#aY~cd5UAS3&SeTV43Tj(q`ug z7Mu>7FSk1vcz}k=YMU7oss&YI2A8X?+)Eb%Wj&0+ z@fzq9+{(@a0)SZTAT{7#0eiHLpgPcQth6mXiMfnl19$s8Tw5c|7KEx*&^k+Cgo&<( zQ9%Ta#g%q6WN*&xYF%=)A(OjIU>oH4G1}`T@W6?=(cT(J@0QLZ3elateBv9<;4R(g zxZq4K9mohR+LjDc>>#tYR}`U3R5iZ$&J+7x48?I`l7uTAy4$b54->cjp-B<3ha>V% zVrYn5=0G8!`ja}jeR!-Pvi7-hlv>p3URlw$5W0mIHyDWbK$Cu1pT|Q$$V2L2T`*mf z-*6FxI7?-2c-Hvi+W;KSt-$aBw365!aV04l^k~ev%Jp5n`=UB41@(PFWbQ6_{!*5n zU?nE4vWR_2hLLLAhjz$Et;oM{$nI;sdd^HA7)yRE3vr|plfOBdANZj>j|ps z0|Rt5waW%~Bzgf?OLvZRf_j%NYc)Z5-d$YYy6GsZU2A~pq;lHcWRSrYd=9};NbO$u zh4j(5x2k)b|gx`xkxL@ZUi&*ETMRuU4^CG|j8Emh6$ZK;; zOa%*HVYRc4r+-L&YV-OLJ{##SoIlBZL7qw;(~!u_VAgB*)TTf_-%lWfkfz=vNX8=%_2n)lE)`$`i4XK5U>yU#;CD*} z@akrd^p&DcgJ~{KSr_}?PdYTc+lv}dmcTIVC`}ey{9HfTPE)S?L3{9fykfWc0bo*J zG_$plL5Nrl_f|9g{s4h zRwsy76duHRn>QP2m_I3a?-TZlZH?+4j*$sq+UNf$LQtbH8+_|a(AwDC*_cE*VjN0` zcCqM1&}Tx2bSEEn8QY7y2NT~ecO}3 zN}a>gfCC-|&Q!WZ(%)m;ngj{gZ=d?+^3fM&m3MebDLs zvgEd4a)mn-@SD>i-4rU3GJ@pzp*y+jJZbm^pp0JLX?s7ny#h2Ja9dWZ#nwJN-d0!N zoVXv_sh)y++|`iX!HDFot|?fP+#E$sv&B_NuaM6~(SMa8bAJ7EbjZ!IOJo*A+Sg{s zL>)@o#D>iMuyJg$D!1s|(XpP)%5_##kc=QjwJjzfZLg%X9?3`7m?;a|9FOYCKoWX$ zq##S^GJ9pOs97Aef>oS>OdbMazDv^sI*8GRPg+$N& z0b8{R1b^~0b#Peh*%zB-T+HNkO?KyxZ>Tz)CzSVV3zciS; zX-YXr8E1JZ+pZ`rp0XoIeW8e;iC092zj?MU3M;MF=uJgB_#SGu!-G33;XJi~)5IyB z6?21A6~7SS$%8Au^>YHisZ7j&OK(jjCpai9P3)X8m~EmKy-ts5s&}a8*aEcT>q`)& zHa;6-k%lNs)AW^Lt$sK8I6x);)t^CyKK=Z1@HY$Jta}KFBnp%C zd-?SW1rx9<#ioLzU0tMe%JQ7QKZxdpxcj)4VS>he~ zhNV6`2vjW0so^mAmm|T!!@Y;ADzTjRlE_BNDOoA%D13+YInMAiOxW`@SN^}?D~eBI zO*VW-g+O-Qpokp&EO&44l6_#UO+r}5V;yNi(tA82)CO5Oni-@E-a#;lcrx)9K`6i?+tE+_;jao$7`6Kt%6=ODn7rSmqM-&Lp{wy`6Y$IT*XqIiOneF2>4lG71QlX zrT`2!raXy)wer2~w|)U^Jn(So;ozG*h{v#T}-VQY`I5F85(=Hc$We!4hK zaVDT0g~?)7IE6&dRZy;tljH@bZ+GNdbt2uCdrJifyok=PtJE3gS9Nu=t6|N>S;;eC zaz9kc#G;VE=yAs8oQZuD+}vba$s02!@Ig&m#w)MKri@D}jpOo32<6|or zC&h~_WDx1`4})2f^b^%CmRs50T{sX;0TXl!Yd9e@&JwmHi#N=r`#Mq2bj|6vU%d#!bvf4aJte`8zH4AtPup7+7!Gx%A+Pky8FCPCw=`OI2W z3MzT4iMgKgnFY5NByiICt0Thb1EfXzZQP+(#58toR=!g!S!ThZHhV_$a&T)cALWcm zHw7q0Pf6hhU(7qzp zW8L33YYLYHMZNj9!G`6He)9)aKr5<&fi-OhGaSAmdr^OIJ=eByr;M~#KWNJURhl+; zh(eSXi#ow|%%OBM@jRoZdYq;xdu(3FOv&z5ZY;jEZ!4T4Dt4k#S#B{jeL$f|U(}TJ zG!D{~c-Cy_n@%dOOc7)K&ATXtiU@#coS3-iQvM}sJOm+e>P<#t+k3_p#Tbe3zVP2? z0@n2x_TgQ1%mJnw*7SYl$YY&5^Ua_ecI=LZ3U+h!_E@hG2W58U+CvZn6!)y7j5E`! z2C>k<&*8W6@%sAQ(E0}T=Xp*v*@L_KJGy4FSp)0XQZXzXi@j8&ZDn8R(Sy3~?YXhX z)OmFJ*U;!DdIa+zd7RVlMNYD99-G84$gd1gyA`WVg31c_WC{uave8j6W zxVS_R_jZFTAAmcBFPeW9+(JW*jnTZ;Le@TCPJKnZP6)*<_{I)&Lujc@4E99&Zr&u& z368DQ7A-h&URl&@ZXx8b*Uh74>`MGq&c_IqDi24lSTJLT?(r*?sxt2Zm7`KIBO?f zd1*u6atvbW`UUa+M|9NGZ-cTqkLu57&mx6Ku}s5wOO)~ct2h~l=Pn}oi_t=|&6-oi zJ1)QQ+(|DbWv&nsBsyX=+|Ab#`gRXa^cI3#vK0oFv*ry}{7e@E!sAkyCxt)nO>aBR z54d73T{deO{^|H1`JC?KvYm@GuP?hjCFpf=oX#`csg0rRDG zSMd;BhH989beBn!=0m?^jPG)>mh*1umX6$xQ{E>kei6~Uz|dhau15y4*GHIN$^a+BcqskAxbu@6=eW<+PKBo zQi{b|Z^(3$K(78kKeIb2gP#1e*WVdrF^in@Q4f?Sm^F=oxgHciWIMq&sU3TY#-|dK z_6-^C(#tGb*zcJdzYw?x11tz_ed?kT)V7)6GVTz+W%Yp1DUxANM`NU{NFJJC^Y>Ps zWhZ^<@{Wmrl_-FH>zF%7VwG4c^F>Vu)ga{$U*`oDPv${+xjWVC@$*6>{~Qu{=f(m` zUy;0ZR*6Yb<8lrf#;NQTeqHN;=TUgt57;J79GIha<-lLmb$z?bjD$6 z7e{^Zo59ab3{6P8qfl#++cPxBoEZLh45G^8`+kd|Q*jqwTEzMYM_U$4&Doa5)=0S) zlc@y74R*V}&mar(YnMS~Z$qGu=e%bPev%XTTq$w87}a3*gMj2|az7MIs1 zTS_DUzM6>YTu`H$T#8rCSGA##;>gD=g+#-b7g43u7E;*WQ65-f}uZ-LS#GB$+Yj*IyeI+v2f z_TnSxRWC+NOKuumdZbdNqg6Pl{|zf4wlcm>XFiMoSZQ16EH; zX3lp#S=WPB36;vJFYaV>hx+h;;WYlUKBYz=EuQJCe!wPn+PUw4DJsit+*DyjCBc6m zjP(E3aPxd0kd9!Q(#Cy*%p?;;MVA>q}IH+#xXMT>L(`<>a)Iz?NasWGXq;EUqVOs2l z*wEJxQ$yC|=!+FKl+uY4j@RbHxU>HMq6hh3Gj9KzkvlgkiU{Tf#<~GPbvIy^+~5abe_X~jr18^O=SHs{ zS75u5=azNarM3>e<9?sQvA_v^&+8=vYh%#g9;fE;`;mH6j} zuoHuC{9f+i4X(|NMjQ>JAl{&tcQuSqx_=Hw>#hSCWubQtt{3An7NCgj*wiq&!0NF^ zAJ!Y>0t`|8up+BpRVfbrl{MW%t!?mHV27D0tB$n!cq%vcsoyxH750C*S%UrW{&Yj*2vMuZK&&n za`H25+FZr(il2<)J*0S5}sXodI90+Rx}t>u1D^r%J?G1|b=2$)qoi(IfZ3M|Tn2p0#gdlEDrM>#gp@lX)7g}7g!#?Ud2v!% zH3Gn&5QU4^#%1TCtOLv#%r@W$8@jO0(UJ#63e>xB_;YgYeddNEO6Qh$IB8Tr;SCd1nyrXMfGB%+xeXLtM_TYz7{PMD=4lX%r~zv@>)mMqeU2LKBT8P6g=jL z=&?iW%#3NKB1Xk$Z={%LW=@M+W7hbGwK*o{Zt{C9*&nnGzCub2k~O1PZfc}z!L|S~ z?@3l~VoOIHx6*#S*}rhuzWh6n8YtVM=7MDiOblFBHN$ubmp(=UbteM<~miG99#z1K;4M$boI038W=1^_1OX;{0BZ9RUHfeSV zo;0o+K)H=s+4K!z~l?WSKZn?cFbIsBVJDmmd zJFWEcUc_h)Bzi6F{=mB~tKw&bT@k1(+?U`(S+d^WEm2LWd|qdp{pA>c8~Y08ae;i% zkzBy<^?P^dH6SM0_}jPoHkTd~^Ankpi?qBdu}Q^g4(|@zqSlV=lK6K~ zY>)5tzCAj+*zQR6Fa*l4TMPX@7B3p2BJV(OhG;jb*QbxwCNFlI3sel7=T^$%Ws}4M zNKCF2!Wpqd5vqUw{)PIHO=DAGjaI=3mMW^=mh6AoX&g7XawHtSJFQr~2al^q6>uir z5S4Gnt*AiTDy^kV0}uMDXIE%`f}zAegKUut3Y7aSE3; zq;nFmF3wJ(72f}qH(i(sOJHt@_!Nr}^TMad_w$hz@hP2ZIX7Z`sYFMmK}zS1^zMR+ zV*{1#4o47rJoWmgh%2v3rAweC+!4EGJgb^^qYtsACF9yn@Sln=anD0*1Cl~jjNOXu zup--5&&Pmq%JeI^Kr-fGwd7H4=Kc@sVoBw_w97*z<#|Boj-Tkc=EcfN*b~pvK6bb9 zaE<S>x3-0-uOoIwJEJk0B;9ox8YL!`90vDhr&=t~2%4x&caE>KP8C97eRw;xzU(_7f zyn&RkOl<-q9B;SDI$plfod~hFG&jfXC|TyD=q2n%)9Hc-yUf2JI*hGh2Pm%6Q{kF8 zPZuPGa95^F{cdS|*)-EnCRF6Z=vLo})QEl_{?<%_=2}Ucz(dd=#%dnOOB6T)<0scp zww=TIm3PAY$}nH316yp4zz6p(jENtelP@qj%2GuI1~h$k5dzaUod5q+-|%nc*#GT) z4aZWjnelpyA5&$FN|VLwW?;P=La7 zgX43UUy)Car>AqNJ}eD`Z_=49H9-qqEA57Q3c+dQYUFaHf7k8Hm{)>V#ySh;+nOiJ zmg7gAZK0lAn-$F|7~9yR^ut^^dNWBYhJn(9vZ1F!Fu$?qmd-1etjPhkumZW#q4jb$ z`#JXEsI%3!w`HhPhw49`*@KFo4qnbDI=&yFwhJMyUla64z9C$I(r(CZlD2?Kj&6T4 zVa?2y&ghZOEz~+5^uRq`=`IZjrw*5ZPyj~5fkR0 zAx9Tz?^$>IB>ghBxEYb*%2+^B0E}T8x!sX#*U2)Pc}tLLirF8s-qXG+ zm%sR9jkO!04^7heu&S3^jr8Q_w5twKe-SnyOsIJrYWruHchZopCi=5@fDe1Q87x1x z0gO2&)(oZ^qrmWazuoTWYFs$zU+f(;6wL>e6VjWfjZVNBWq}Iv!{zfnjK|(Fiwyr^LKWtG3jgh|>kgn75hncsTAcJ^OPy6Pf` z83lB9yV~@+<7WqQ`hb(9-V3H&MSr5=znyQL)tGMW&V8Ss;fbqQ7TYRR1x z!z#)DYdi}p9hodkV+zj?!7u{*HV6M?oQ-sBewvy=XMsRyqQ&py>m&@Gz&H_94Xl>$ zGVc^Fnrw(1_$QrOYP@PF$*$5tT^}&34LO^>!P-k4HA|zQk(~XJU2;DUqaQX|Fg6OU z3mOto)DHKXkbgMAT-93|H8bw27wW1r4p;MQM}{&tPbwXM4h4L+F;3o2T9a5=(m~=> zT8wF_h_WwZlD3%0{07BcuXrg>MZfgRYcs7~i18@VUJ?NoL)uhbV?-&<xg>;ch`^{ zj@=-(dFbeZ9e^JMCe!-s+Y*K|T5WZ^cL?ZwZk2tpGRY=SeBvabD`+%dggoQ3%%R&w ztx3|Q5{-4jip$BLkk@v)DpWPSva+AAn0q4)K4bYceI8F3`o&8D&g7 z(oZcEDHRH;+@3N2D97hS{PAQcSTj-m5jA!XH(Y)>@^TLsw1#4dso@lQ+j*+>%Hmb{aeM#!i=S0lNQbVe0t z2$eXdA3F|4GDMj`cD^P(37qZ(9Cp&p-FzVK&6kb5XEe!JD^XzLS@ZKZ-+%7j5lmh- zl&xCnOnTMnIY)gN7TJW^3HNb(!l_9BIwtIra55!y~l_-Rr#T&4#UYP@G>FknSs< ze(xQb8|@qlCmxavT}!X|q)z5-x662gYiB9jFJCq7)D@T)Nw!;MH%K=0kLvYA zaMXKf7e`EnZ64q6Fr90^M9OsWHSXI4Wt{a4Ca`v?By_d!*o7IJa|}j+y&p~?w9Zr& z;zTvvgDMZIfbz*Lpe;=+I1ca)TF3HRWx3wPq*)dTw4%&8nO#McfC67c+nFk7X)CZc zGybJgcw-ih0mtBL(KWjd9ZlpBZ{I=_%sdo7@}Tp&^XtI!aXvdIrg$c3W#F))?NeTk z#S8C3X1(D7$u)e7V2<_;#{1_FQ1lMF)Qs_w!^R2tFA_qmZe%BM*ifDuoIN@HZDo^! z!8?_|aD`{dx1??3!yFol(7nfkFvT*^*H5tgPU}|k`kJs{AM1>v)Tfo5l?R(waQ}V9 zru$D9fF;v)Wb%Af9G*q6ukNuxDmB-p^C5%o#~H5YPY!ksd&yxmlRgXPw%s*C_s$Nf zM4U=3S~7K@a$!OQH;zMx=UlVqVlbyfFlG?J4@40lQ6)|Heo?5Y_;PnVL~(6|RxbA= zfHFoOTD0m`4cQ@=!Q6YDsH-;-lT`y;=5#7}ZSuRUb6;G?y4#n5CsGt1XB%T(^e01J zynq0IKjQlog^r2|p|$SUZ{SceWequ$Sy|B)*uqTHy8RybTK@D3(_Ea+U8;g;7fgA8 z`gejeEUyx2osGAQGI+8#oerqtA?pqD%^bHuE0q%c#)1`~(WV)B_iMo*UvA5R< zvNa7SRCto)(>Rm|Rt&p#E%WKMxXTgC)YtyJAagQHJXw<5wSYg;2JGl;MEde~QIBr( z6_UjZim3NC_MO* zIx%w}r%>cYK;bVkB=9a5@&BSSh2Q+gMJU*HPXj|4hJE`B*A)BmIicfi`+pCigo9P^ z|DW6dldqqjzk@IEQa<@pKhBL{+rBvrDoK0oz9yaAmdsUmtIa(Uq^Rf2=*+SAesfq) zVcWTRgS@JU+^Zd$=U#q{y|J+>&_8>oucf+=xoU~8fx>tig%}m) zRsMM|$Q7PO0^K=r5_b<3Cz^Puv>%%|4IN*A)mssv5!3TAy1`&08UKnxWBul$CY18( zS*t+&<>?Ur$^mdz4hKCC-$3nO9!hSA#J%1!pTR`!o&QpgD?qUyh$2vqhu)!hmfOf95& zMD|Yqrdz5O{Pi9A18m?~R>Eg7_<6%PqMYCbpiImh0_B|g@Goo5R-pQDWh zjpyjv>cDUL!j(h_4}RU%u*2BjciL6$USBXrZ4CC!VVS2vodSs3^BT%+b5u=I^(chO z3dpmGDu=uz>UYZJ@pKhC*Og~{B=c1^!Eq51405P?2|cEbEzWz_8gwPKx7A&0Q)1yQ zNX`op+vg4D8a6?Lx%mt9?DnWM_W?V6ei)`*wUx#?<0_Ve8PYGSTG!mew|BS@M{$ym zg)9TLeG#~rNN)qC-YjY)`+R7K;A6&Kt-yDi%h>P+?o0h~J9vHMIKf>*v?xfCKi%ec zh6;&X=tWO+tm5;w3nR?@d3EZ0%Vo?bf$rq3p;4rtEh|~u`I(A~6FR0y0$I)75sG#c z!e`f`?HJ8Njb^(hG>hwx}n`-GqQFC1k`BusMf(eDskfjR#C{UY;3 zTX^0DeEBR=M4vIOMlw{865b(-w(0dE?`s1^yI4JzbvN6yWzN^h0X#+dUcMp_J#lt2 z%vUAM^tFy>864ZXqW+|W&o3WZgkLUa&STY>y%s`vp!@Bs*59L3SjBI3=DKji^EAnM z!X?1kSXWO3@gtQUcYOSeFqf) z?>>9DH|KJ9QD=ElG)TJri_wGT#~AXH0HSk$r%j-jYsL4{RyQsa2!iu^nd^SV(q*_p zn&P@nMU<&Gkx{E%FpW-Aoz|wMwqY(OE{oH8`+VSi@CrrX=Px4^?=hAXbH;AU>!mV_ zPmRh_j(Ws0SFcqG*~bfoCW7HS5i~@Qe%YM`4x^#`{!|d47!<3dR9CR{i_eLAP{5k7 z$yu{sbI_O=jgrM~j!<%`%NPN+6^>YF>apTHLQ~dV<@>??N$%`m>hpG8Y@ z{fte+p*hdn+Z{BX2?zi9YmWDOWcs<-kF%i?rtc@D?l?BA3=p23i+W6D0dgW5rS;9D z#*5s_zJbj__P6dCsD%lD(uswp1lCx>JEZIoC%6_T82@NtKDm&2_~Hr}?y^m#; z-S_(lwG;lRQ51O<9%`J)U|{s{8K1IA?I_o__@cTD_HoA5M9{q^P+0$-r91SduO1?=Lh6sb{TlItgO9*-ru4 zOsPB3W-9~gf|Q+IE$z)sNqASfS$SJ=Zg7DT$hhDgkALj;{h7=-7JuP5bG$~&wEq)z zZynTD{ALe_LQA0(iaVh|p?Gm8P>L6KcPF^J6n8IB+>5(IaVxIH-7P>MSo-Gs+uirw z-PzsQ+1Z)jynkfw%+1^+^U2)LJ9`M=N7gOhuNP{55_WH|=c3G=9C6LL5 zw*4le1AJ+G-ZR%!yQPJ38GM)Vr|Sw%1iI^;eUUbxM?ntiKdG=P;n#0{-PPnuW){E# z;>dx$t3tV%u$g)KG`5rTjc^&S3e@n#N4I>Yc_r6w;q~ytX9KobEs%;A^PT4S7;AKC z@L2r?(#h29mDFCF^GI>&%K-CbES1<4?xjQ#_PVm;rTkx#qdypLC&VpT6FDuT&Y0@i zkOh-eXK0K?CA z%gXRZIdX7i*R;vY{z~8l&x;};9mu^@P~Ei6tS*G@xap415W}&YerTJ%E$C0wH-dP< zk0YZ3=X}s{E27TfA&m1L|<>OlHUo<{Ka8(WhRf%SvtC!$NU*m8eRbV;pd<#v2u@h{C9 zj1IvLDBq@+;RCY%$xN$3Xj6jL6X)fw5&*w~DtYH|f~Wa-ugq2^UG&WMWek$Dg_~-bv0B#0M__s7xku z@Js&lIGzI?i5S$7psnJ{NQtC1VINjAv zwMs|KZl(u~$xOaz-TQauS96K)ngQ9xKY#3@y5LBc1KH~8*wkNYlD(67&6#pW!Ez~A z+@`<30`7zh!-cg#>wf{j1AS5dk~OO|dmGO;;_OiMb0N`lp_8c+B{@r@j}7V<1|l%~ z+vui9BCzW?N*|f^JK2&ZRlp~Z+fd+NzzeRvr}r>-i=8t`Rgz4Evyjz`fXh$nIJNhl zl(CVkCNphd|67N7aIm|H>GY8khwE4Cx${kF!Gx4Vl^myjfU8#`k^BH0g>Q zJ@gn84?+h#nn&Jmh&&hCZLa{sIWl~1(${k-T=vx_Gszm0qMua5b^R4eO*hWx^=JWK zFN(qDldT*Kj{>#J*hYe~!d0STd2%dzhC6lg9t5QtP4bBP3(hs$;k*TdGUC>$_3EzR zriMIYmEH&qZ39qc{|im-f2HC5U)SsYr-jvjRdoHE_Z&g^Plzea*Es>KRryI~d&7^+ zRaoy=$!Z>0cAzf;gzaFB+to0cCx2f@yv)-|tUurykB{H>!seTSdHCnuD1tzOxXT+o z{gr~r3OHOfLG%@wF&8D2Xw3iD$$`QPnAMZs4l|FW;<{?xc~;nEe@E-><~yO`>ZbgN z_YqVPFC-%I)g%DO0WSd#gx#+?=y}4KxH^T`ZdS@=OV4F=fNRpVeTI3P7DV@su*JN8 z_Gt9v>E8%B`N_1r9tI%%(Kt|t1zoQwctp4nE>=%2zGD|gkC#Lh)L2p51L67+vD75l zXwy&{1ZaD^k}1Gv5arg{#>qSer2Cb}#6j<3FCUL=iOfc46v+L#=&stdtzq^_vY_IU zH)BDmm6*Q_O7Tr&Qe~yVZuofg*XDj3@Fi>paap!%QPFIX{kr(`#%AnPpYR% ztiJMCOM==`{3BENQ>SBTgFH0VwH{07|! zuC$aSuG4JD6#wuL4&Qbdp0&kEeH) zY}uRQ#6Po0Y7UiW!L#^zEKx4Y(bvZu=Bth=aJEB6ciBeOCbcj33Ts4%^m-u)S(gQh zdW?hFl$X$+KeyX$A-SMI$0kweq2u9OZ+wq~2tj&hho*<(GzYM2CgF7@9eHM3jv93^ zT-=oc8%4X>AXu;_Uy1>L3`8c6Ow#&GjS0Ev#he_vp-uj^vwUK9rvUj@hef#|7m!{B|M6 zcWsq71a2n_(my^5_sukfXL93XS{3mB`w2x@*T4 zS>ew$Cw9!7(-4i}IJI1iy9@Kd!hKvTG>^DbuUW&s9gh=_j`#-mVb7b8iwJo=^V$oFmWgbB77R5w^XO%o94cTe?@~DE=WwZRiu2 zX(^n(nbVtTMdaO*D!$q&lN7T)H-OwFN#;Ep$^Ns(_U_l2ny)K<1CzC*)|(=3hYmo= zB(Cr#=^Rj|Pyz{M?i-uH_aDvgBTh72+EW_atc=yL>WNasf=?D=mV~h71=6Vk21DGg zM1|^)6d_4LZw+FPX%~d22tFvUq`3KHc4a4@Y46#y{2m&?0V8!3E)&7Y%yUF(t1M!E z?MbVg$%oJ-o})BJO}3`0#eRfjoy!A;S_^rVl4jaBf|gCaN(LBtlI?Uzt?Ysl2G8I5 ziT6A)e5lPA>f2iED+i(+J$kCFm?3_}NbA2NOyh>1Wb(zm_QSY0yXgxC49Upz{^OsnFU zbKxhW>Z9>bUm@tOT&0yH9I*&1W0q{FU;Kqr5Fr?(G9P4(hmZOZnVXE7$alk5Gtp#n8P`wHqMds5f@s{ zz3j7`XI8&LbJ%*Nx%C~h1zN2L0q=!Whjz#otgK+;>Pk9Vb7QUTM&CS@|9;}|xIClA5YlcEedr_m}1Qas#XndckV0!vqm=~yfEhmYrQ8KFa(t6_^Z zR@X8r@mpDYu+Z<)cu|_d7J~%o-Rzh49{2C#hDdT7MdBL*r$29E1bF#z ztv%6qG$r=FrG@P1pk+%R{9@P*c(E78JC3QYfgi`%QQumZwbR<1N`N7X*|ML%(w-D~ zI~h*+P8UX~(sZ?x_Q(&R4ssGUkEs)(E2}0T3zTO$qzDqXy~7F5M;Z1z1SBdLvaL6+ z%SwUIZHwz)ol7p;(a_*M2^h{Zv+OlIs|z4zz%@;W;qNu*{mtaWz z*y?`PULAhwX;G=w%+VuCRf#(oVRt#qD-`3Bf!JOw7v1W0mi&$}(9C<=%N<0Zf(w%2 zu3D~O`DL45WFis7BAy>Re-;-ocMd#`fNhOJx-7TtH}SYnNjQ#xLCeS18(3hbtfA$b zCT{24Q>1&WsVcr(u0z)=p5P9(QV+@g1$VCxh0PRRukD$F{f8C>!Q|g9g5h+auO23Y z%Y;$jyQ8#7J3POK8G}R*1&3kJoni^ePHAygLYVfW0R%Oq`pm3Zsv&d7nK$J-2P+v1 z(g>orRh8d5iFii!!Qa+fHG1DjyX^~@3KYjbFhHN=Q9A*KJ{Aj$vM_&V<5=N8KkNSd z${IH2$;s8dMnn~OeN|dHO1-2iQ;kuRCfh{6Mg;BHcr{16!hA%3_8K;=#0by2sS{25 z+?mYfTmszH-4&TTyi3Blrw1Xr^LlGBR244#F16wqc@t>1kqPI)3ff|r3JQEKw;y^`lYSB{SGwZ1n8vR=Ct}eWOd*|U$ygpL_Qez zzXhkbOK+Wlb^S32kAe|Si=_wfd;Gm+gnyj@Ao?uDR=flqXJ1i_b};*P&+e(OU7&kpI$LLas7T_`+A&~3SOa#o&_SwM5mQj+Cwz$C@ocS0S{el9seZm~q4awd zAV7}1V;|%?UPha{Yz;uyhh`4A_l6jn9lbYyMk= zF+QNy{psEIK>xkQi0d?p7T_nKB4fr3bljq^`Rjvufv3?Y(5Fy|uL*y`{PS|L+CNsO zxnM054)D7zL2bPC)Zfpi`=l#8p-F5!xphj4!0tBB3~b$Jbgfjf*_<+ygeO{`hVhV& z&X35zG|~8YIKPJgNUMuO8~8rHtg$}w`-Db?e^O&7gnx7V4qK~*VPI+B0%QE&*@B;5 zr}DED*gLaSeKpsy5)1ie*iCsiY>+3Ma*h9Q%BlaiteQu7LN;y$`Y2!)5F9ilVXytd z!ja5*e(eg}lygc}MBN~8cY6p)CQMDNXu2M(6Q{Z{qo$1OEvd$N&KA_QZ?Ngc(38@( z0dB0AUKyEOW5M14pZu3QoBl_3ivPRziT@i`FJ0QO=k4mV9OB{_l=Q|K6%)ftb6div z(D{d8194b$|2vpYZ(D4m@ax8Jb@Xr^K`JF=m=%2BO|A_UW!qT$T%HIwEx zU4?hA{2KlK&1wqPZ`=2wEK;XwO&h%_4Q#V<-PHAtLrg&CAPOQv?n%pPEO*;i0n<^$?0FfMEoSlrDRN%Agdd56>;IL8A#A~2egjh z-iu;OFbEy*HQqH*@Bpx()tTp&*=YKF)TRm2>gq(4vHcnfn+8OBmV`$}^j5ZXh8Vun zajq5CVn10}mN^zWl(s#dc#6_jFH%|}-_OUvG=6y4Y`gCA_Z2rip3&Lmnv4k59y87~ z`ce(`ds)VUt15WJ8K5f1pwen=gwVer^#Jk1_mFM$113yyt3#z=n^bZy z@5tef+W1kjPmI~3l{PxVTTSQz7i8cv#yoe$1j@L5Vv{>@C;q{xLTk5ZE}M^4xTWiS zs7tYuTRI$4{SC8ZKP>1PJ@-p03_QY=A75ouHoI>e&EBII<#D&1u)dL+x%aYb-+n7R z>_F8#N3Mz`dZwApID1o#p-Yp~F%OLheQ$IBb({zeL5(ZHpMyp9M{EhP3w)t>{5hOy z5{`-b_*IB8)RWX_Ip(*laLrU21L+0Qs`n%MaS5@kGcjk=#~%92RSVU26UU#c7KU^J z&Z~i&Y@saWP-b6l+zn-8?rX~*&-I8A+S3E0Lr|>%fhgmuIWKV zQ4!g028uSB@8~oj&lM>98?LZE4W6zXk*GbyQmtlsz)I8Kn9El41x%FYf3Ef;?A$vkfUK9;@^_ z1lQM-{mAC&&d2P44$TE%y@5@a4gB;`>5z(r)-=V=B}{0V4L`j}fa0U}%@92B3_aDy z`{md9XymTL-21P!b@hlZnkueWgX7pGNxvT)%NbmH6VcrV(=WkLyb_dn&SUIcD44{( z$^AZ0a1UX=sCJTIx0!H3&|kQ+icZ3I^T!V{b#hz&xWhvn_n*ka%JljY^v#Nwbl*y> zOB%3H{bBJB@!n4cwqZHXQhpr-zh z^$dP*;k!iV4R@LGOP4tO&PYB{oN-1h-7`2snH^}7)5m`$2<{bGDIlv^lR5d0>Aj_2 zZVwEv667m=yKL8Kx8VH3iw)K2;YtL-BNV{g9pI?2BHt|`3%KCLpN5rq4|Td{9XQ|4 zpOeJdzT!MElP#o;4-BKW6IgVG#C`RZm7NlFw+s2u7QuWGi2+WRQ0sp8dNS8Qd%n|_ z`pvdllID}hJo7I2cl3`PGFx4>3*@m~NxRWwg)~~plHZK7Ll|A3F4aSJzN?a^i5iuG z$tp&sYgYu}FKtMBdA~&QJtkuMx}!%tQR`%`f26g4dvaxG%XAC75!A>C4B#QdgdS=C z9EHDwP#5r|nl}@no@8v@ta!U$!>7SCB}m3e{W~)3V}FCua_uOamt8T+q$vqLO;-GIE>Bhk+AR(B8H4km%ZJHYHp`I7)Hto= zevXm1T8=DZN;nDqT)Qy+U}H^NWVS2%_Nr|JFKlcT3$e?qnYhqI-%r;!NQW>i9eY1a z@1vQ<^10s&n{VgU_(Cq!xp->dko?hVtmRwRSKbRax+zZbs?}r0rVS&N-e%@Q2_SS( zJ&5-eDp$X;a_3LEUW?ZIxzG1CM3+~{3Cp0;l%}a^;ZukDc{6=l;_k@EUx1mU(M-K* zsx+NWS-b$pE2JUR@kSmmN{=12NIm1M)N$kD+*ZqotL8WbzD7Uuyc)}2kv zNOC5u{%jt{0B3(%D{qeKdEi?3zDPaLBym}#zBJfJ_t*-pFd=iB;$Lm>e!V0WC*bXe z$B1k@;E4u*NfChgQnxvf#vomkGSakZw5l}m6$(xXxj2<1Xc_sS^@E%+Te7QCmrI?lf0!AWm z-P5uPs(4gFgf$%bHpJ=>zSqj1|1|`vb)9?-^X?DV(40PFS&H_IBf>#C-N67M>!>QC zM%nxY)Mtmex5;6tw9f7dh8I(~_=`@5ZOeJObze#jE>j%D_Hcb9gllVdA*vl8GM?SH zzOHianmblxTdFwHr!N6MZ#dakeqTMfw zE0nX*-OvAjjfHlTf@AFrfu$wg)t_W+k?cJRT?{E+8@*WfD97EY_sNPck3vgVTfC&bJ+3Tc&XyW6-4!0vW=?}e zB*H})roAqY`^<8PypceX)8{zUw%~tywq?+4vzYy%CGOJ_Ym%MR31i&%xct9>L*tI} zey{n($PN|X@~;)M`V(4;PO2`dK+!;$#*zWn)2FU?m-1PKDKECDuUVun7@anBDNt+h zkY@jbJ_pji0j@Byh_i z1Kw}XGfOboq2Nq%Ler6-CTQEtMCrpeM{>FSpqvdyLAxxY5%4 z?O$Iccz!TyucSFwGEYdXBjIgU)Yz0`ntEHy^yv$)+96|1CoHE}%Oj8pAEPPvEMw1$ z(c3F^Cg@sj4aDtGDwizN#lkpJzm~lf`4cgZnnqFza;YV48FbVw3DP~(Mvdsu z-e6q%^PD=~{+w^pfPG$&lUFot3zUYj5BTZiU~gCmjdzfPAW!gD#a~NLT?o5L&l~;U z9`mag753Myt~5BV>a-$h#-d3~c-}oRjv+K%EcHn&9zzUoHGK)TB+=y=el*SWO1T(a zD6{JvKiM`MEzb36H}ueJs1Vu1stH7lhPKa;8obav*cqMv^4R$jLNVM zxx=h3*S#?2n|)$nz^R-#-S{vOb>2<6{KW3^@j$!|k#NJNyii&0g{tF|h@Y$7qPcpnT624$p;P9Quu7>;eBV-X4@hO) zd7V67cU_EkPfrt0Ts8DNMx#o&vH#}?Im^e1b_i-e_-i;zW2Jy>#6wf2tyWwOi!@M4 zy3oUX?5igW-iV_+{adcJvGfng(EIOmiyCYNj2sSFO5^&$O7&&{>7*Mj+=}&>>AlriRF%C+J(&sqc$`btg2n}_C)SJ3p>JE{4uOIe?$cs zMOuy?>m+RIJ*fu2M&#Uun2R%v`TR1Bt28X>y6elRh0GKaj-pjOzHFq}TN?4crAmvN4^ z8R_|r=IoNPRYjV#3bhg&?2W^eY&QTWIi@sq0utYaEGD2;4kcPb z&3AH0bk0oaSh?JXey5eSuN7g!M*iPbSSoj#K8}5gm&v?Rpgf4Tkxs&Ko3T5yjro0v zWJ5csC3=!Af_GmDuD&48muw6%W+DvbLr(PlxywU9Nbii3@m~rVuG*^_Qy5=AXt3dz%kATv zDn_+4Ic9sSrY*c0HH>1{Wtke-A$#Git{eJeNc6Vy-SBHdzCqLr#L$?`Nkcaprv_T7 z!TY9qkHAk8J=uyIE&=@LS49%XY_NIQ#l^di><5;=XcEO$trB;&mQ@U}chJ*3hDyc_ zlwowdT{q9`Ajt8(`tKxfyP+SWg^xcXAIf`#SX(FQ5eQICT2slLfAnL1VeY?IJXc)2 zLG_hi37kcrZw*Z`oX2pND$N+C)$n=R z>C*Lw6fT3|qWsm*t_II2i1u80<^#9NHDfxn`%noJ%JoM7=|lD89}&DhAq%KYVa6tDmU-0L|H!x9i8I zda?<_${@GyyGf8b*Wt~7HiCe30K)Mj5!((2s?1^=&rf@j6KrA*Jy(mtfJ)ckv*@N~ z95F!!JV>pEBoTw8qNIs|twz?96wC%SvT{RdHU%M=GRR*=dSZqz<~?DNznjFn4C^QD ze1T-*l4DtqiuR}AAg9u6RoMzoHEZ0~oS>&^Mg#Q3%0o;`-JioJYy{GodeA|gBN zKB>m$Mjm#cZKqB(nnmt!r4E`z;9Vh|+K?na8%@;%jfhN5J4xuWm2 zE(;Ia?FiSRD~e$nn~25KT;wO=#_A6h2_LUF6Dikt@^s;@cuk6p_3YduNk1rJg@hZ~ zO4H?;iGQgEU_yxm<0@@n{xV4hkXKnnlJRyHnj_@N*$SKN{^)b#nQ*2^Jq_MM7tCQJV#>_ENL-QREBA{0*5xturFWhWJNgIa4@d3v3^zA8xPpd^&6a`V3u$f8sx#PfWC#!#!4`!5W8hITqmYBi; zOe?pkm5OYO1lyV4BEa^058^7DL%ZxE;2Wzux4U=NxSXHYJ)~m@M5G>K=ckXwCYqKy zhpRY578%7z)eIjl@_&&o_aO2$_&N@|yL)#n^z zT2UhpY?RN%z^G}lq19AguBCIvCDFS(ks|L^vc>7rlC&PUyDh4VPE&C_YnE3VYvWzq z)Rd)e?`w0c=P)_Md|;MUC;5c&bAAif99fsL79fIFBhLaS&N`ghK6KtqNO&@iY-XWl8QJ zx`;2VZyCJ{>|MzU^0R%1ye@%+I%AjhJ74)b6R}O0@^A6=k-zLlPy=BwiY2Z?#l$RO zbtA4Z#)9g$SsG#*mx^?f?eVexJ$bePFN5&+A-l3;5?ahGJGi|k(qxrMWO%u`{urgx={D~EDXI_2e_ zzk&)60yuP3I1+wqS(C)1G&s{--6IlQM;Q3gGv&P_I^?YF#YPyNd?sWa54{$>H*JJi zz&IB3?~S7ci_CmpDkAQup)Z9V`MmMFc zyR7N26Pvb9ow-2FHz$mL8MWsMUc*$I;jAxgR0_vf<|Z?mU%y6e5@IZHMM#kVn**Y~Qfph~rl+Kw8k zb;DyaJM>phZ@m^W@zgUSb(i|^`1GQ4jWj8S$R!xVAr!5SCRGOFB~q!wr)mpqKQLTS zZpf`Z*Jskt?uq;2$l<(wqogN6|Mnrju_RyEllS~Jv_vyTK&fegwkwv6U8f}8D7hn{Nm}ni6s`Ba_x{bb^)v@9C zk9Z$<$D{O|;f7oom00+!L5=7VlK&s0RP@;Cwl+3(mH1zq!TKp?5M}xbBtGUtryC~f#MkZ@!v;oi?H3EJkqkxh?1@R*m4St82*#`& z5#5G|J zERK6wS3DTIC#6RX7_jPF!+0$7uVlvm{Q)@G3j}9}RSie;A9+93eYS%@Z8X&)h_TCm zH)i*5TBrY*#QWcSRb(0TKM({J9xo51q$3N^W~s$ZJ14==0SoyZ+jl!90hMUj$Ig1# zbD}nM*M=_<(^P$89*lk)jA}!7T@x*T0aJ&_^M}>Eb+DsN#yXUY9}9&yxXU9?bJ%*Z z3ERGJ^c7vQj7KjMvf?Ky`i@(NpTq%(Dv_w;9}?c~zQ;a{OndvkfNADSPtw5Eji7@Z zU5(#=0hmuL>#UH$tRnU#TZ8dd>IT^{KY#b*-nN`rI0JkgGHX>M-8L(&0_fQs^^Aub zvOc})#J%;ntX>inaNiaPhY07ctD?ky`RGY~j2IW~5(jvH{+S=5h%fRBV2FfJL;q*+ z>L2Hk4mPmiBrCACKh>vd2)v|Enm>Vh+1&jPyd-SdJ$ue%|Dm}pWGkDFo{G0eojk_3 zRu`+^KJ<2-wSgzqI{pNkb@(9g6R>w<>h?jI_*zwC1Z;ioF7481oqAZXTu-6(;lr-+ zRd$7qq|)rUE$fGd_K>`mkVt9LXng8MMax)zXAK|~#X~CCxZfyzL~yb3iS@Ga`wXF0 zYs81P^zbN$$<*APIA?t>vum9I59%Nx#-%P|kG8=L1^D0`ofM4(GfJ#O1(s6wV8^LD zh_%gCv2jwobGEXPkfaiDtS!%J`WmC4YVc=bMkyqSISI`0?1mrN4 z)miA2rAJz7$Km(E6q13Ef&SP}>oo1?O{O#);@9wVFRanl8nQe0rM87nEUF*o0zHT) z7@IB;UTDTk2$pQJXQo1nIpWNbbvWlY+_ity{r7~Vie6YmsvO;xf0)Z_yv#MHy++~$ zKZxkn=Wek%@5tNCsqLoX#l9TYK7XtnrF7{w$jiGVqT{dc4jh4(?4nPM-3@Q37-`WH zek^|X5sSC-%1+rDlV+m`HY4xa6*8yfj20T92FY}9DUh|v-g^HE;#ev6l@jVoVHWB` z)L~^v0c^6_0>-7wHvF!;hJCI?2yQeFw9z9>E{C%%i;p^n^r67_r= zlHAPk4nU-|wo+3m8H_D@|uvu$yrOcGqiNWO*7%GqqGmBN9Y736PYQC$2@e z(pVK*neMGc0n17?-i%CLlDu!r_#_&1$IZYvYpYYFRG%S+HwHBFjP$CX+z%$pmm zv^PF?XEl3uO7P#lGurdc4tzQA zd>4lEA>sAvn=pmWQw8mzq_1;l?^{#duJTieGwm51r)~IWY|4Gv1xnA)u^od#u6TL3 z+vTi@8V#_PE0{kCe2KXxBa8K@qCKr}Dag27>(2Q(x+1zph;nzNSHUfd5h;4i$S8wQ zU{r$lK6!o;ts{>_HW8ZCUeTacL%~F~9@Net7&;%6w3hYt;|g^+V*B)VhP@iSbh4TwNG&udPk`x^u0~RWe=kxw{=pS7qSY z-KYOJn5LM#lvUKck$q(T3ji(q{AxK>lJJ*-iU}|rL_)d)hZ7abIg-A2bYO09Bh(^? zRGldc?1d(v7z=&jM+U4laVcnCXI{cD=fnV7r`L1 z&vnmGFED_EO}3SkO$}1GG?atVy9;RSE1wm779ORR*_Q;`(W&POGQ_`R)4#z8NQXD- zKXB5AjPRXX7bg^VIQ^O#B{ot=2lVWxF}CPwu5g?YQ>sc=;iM3nr;z zsUSP-T>i3$p?12cbDPhsjIrCBJDsi<&ZQEvtsH0T^_H*5W8hM|d|Y+b!}~Bo^ZUR& zmUTe9YA?>v~$-UtRhWYX(*|586&@_$zw{B9J+E!!E{p1y?@#)IK z9tn^_a?YJpwbtUz#p&aHF5ndPqp#{sCFIlM_elG^5$4=PP+mn;xhG*iw=|y7pM=G? zzYe{g8H*d<)COZ*59rm^;;w$H4K&aI_pViu-o1Cceg*uxpnAjbwWqnEHA+5AwaxOW z-JN@yfqN}@E^x8htH1Fov?aQb(42mg!lR z*}GH`P#XAY<%AhE!>3|lT~Gz)2y85|bLWhSrh!@U zc3umeE&c|(PoE_zcX)TWhL0T%qwMG)FB^}KaReixh8SOSpz%lYQ=sesrxmR?LO*fSEvtymvc9DB1F;Tv@1Pu9$Yr63fdo4>NPEq1(&} z7a;cCAa?JYqUJ~Wa8_noq>SS=dDUG*vb$ojyj6S4+j<4kcWSRG-+5C&D}P#L6!qQT zt(z7ZqQ~MIm!7lfF{VCzZ(rK&v-=R{oS}#&sNUF>00zJ2PoA+)M;2+?rNDB#c~Cc> zi5BhYp{8o6>DNK`$ z{gK0u=+*P3b-^7X^9W>pwzMKA%P$1s%jlrJ16! zu_a{LcmY`2X1=JG99vPn(;nU0!8Z64S;(;>psTsKlC`Jjw*W8qK6_NUARkhj;u;lC zx{LEw_mqI)$y@;IRyK6;f6!L_N9*~BfSH3>e{ zv``A;nJ{>PzCtFQUiyS7L~2o{dRI?ezAIzm7B%#kfRP44lr1i+_4$awT&;E(aUB6tTpk*CDkd*PK!MMlSoSk9-{vR3 zQ#s?Bd7_qsW}_*fE+p=d%8V6h%PD@86b(xArDMeHdXJGeR&CX;z zUbG)gM)g)Bm~e}`wp>bKh3j#kF5>&s;77P8>7n$pU-J4bj+gE}lvx6-qSih~$Cq(z zkq)nrhBxYIB0M)U9Mx{{G9~!Y>$$Z{9Tc&RGNCTIA=wUtffOaZ5{XIZO)1H&RS^M8E0Abho#yB z%dtc2dTX!Z{n`C{z%qJRK^}5xTqau0z)q(Ic+WYK2cU+r1{b&UxGro$~WN3}LY_;?pAX zqlbK0jN~d~J(pH}j33CRmhU@R&Cwpnk35t9U~24@)+3NZr#^2&1Gp@3J{@|pL1;Tc z>$*GHHV1K`+5@R^+ob8N`&W61bEV+Ir@R>9VSptE$ESkL_OVB2$*{#;Nc26Z>qfU{ zeK?)o#M^x&NgUlqIPX(He`68Bz?p{gh6nRfz-$I_2v6A3rgc+Jl=7~z0GdTift@pg zVP09KY!e9VIkds^2ooDdR;xc~O~Si4Tf+`qDcAbp`g~XrZ=wAmYHZV4^KRw~!n$<> zKecT=X+^c+i4LD%|L7W{a<3fAD(%T~*U;I3lv8ctiN3_6?vJdlCbor#E-YAz{}#E)Uh^Dr1)a+5xUx?ZP&Xd5fxp!G;AXC{mhea0DB^a% z(#|DChJ&6CB{;IvwK$WsEcc_>;D9vw^GPbiu7D*0Y~v6MiQ_@pp@ht|&gl=vBzmmd z_`@VW@PvL26(i94)ZsYO{v?sbay~>tSW|3 z)J7tTjVwB%&QWC>Fp9|>8W_gO?=n_J@B=pwBeVudO{-&|k?aLsK%n!C9g(4QI%CO(-2VJbaK=fW` zGxD?a9^}zhI^f;nV>NIt1UKw-ox zJb2wqR%b@$o;*Ci2HD`FJI;Q{6wn*2z^->5-aUSL zD|EN9KRceQT(_{EIpm|DyN^?-**;7#YMMH+Dv!3MLfNq9*+R0`)0x=5=j`Watf>G1 zA_~dnMe2W_bNlxORsZ)mI0$Pj5I09E;)yw57u=N&nza!7{ZaBYmN|9VDONW{(oQ#i z-)8sg^%It-5-Zz!hceKo27lP<3zd}z#oU<4miMOd%3myjnp+L^!iQUTBF?_z5;Q^jD@-XpfCTc7be{{R^JMU zcW0!V&e1@3TBc7} z6tThb43Ix@RrqgWbU(?lKE3by2)t%K0m6_GY&EWd{O^EkmA!NPZ+Jcmxy z5$0Ii-OoiP!Ov!)(Z47*U-R)jj5^+M-Egr1DS@v%%A-B(H4)jt#Qv}h&=v+n;rWgB z5FCJbw)QVB-YC}qDdS$jO5h=#2x=5yhWIdR@yn7Z!oaQZe>q`u^7CWOxlbH|@obLr zDF8lEXLQZ1#66(2PCj3&yFB9#YTHQfA-=^di8Qb_t@-IyS9N~cN8Nj>$6h$&94k$0 zTA%hW3+lLindfLmo2>)?jrBi$3VcGU*!*v2iIyU9u9LtUiXn;dE_4~>CTo&?>2 ztxiKh3(Dsp1vqWVoC_Awu`;8=*0^axwqGAB-(Nt$;)1G@Ve6G%T+vS($L`N<%vu1f3s^SbyI@ae_BF6o{5K{&ws-$pY$g%RiQ2262LL zJLiF*G42VF_7@OQU1M1^Dv$%jdI>84T`}7LVMzb@yQJ1%LpY*&Lb=>1ZgKn}T(|h* zuFm*bg^MaJQbsX_32|n~H1N-{iu=O2^QT3#|4)109o5vntsA5&LR3nmMgc`dMCnQi zs5BKLphRj^M0ytqp@bqJARw>-MVbQAL4;64FF}!xAe|794hc1q5Z_|oefHh^?6c3f z@7;6X8F!5R2V+n&)*8$;*Zh6+o8O!hd)j`sEPmMfy;#`oGoR3FVA1Tn9ZaCIPM!^U z!e&P}-QD5j6CIBH$b!JY02VON%$2jqAAx_Se8nrfss!%iy0$EsRPvDF`&8{9sqA@* z5UDUB;}~=<{-XfU9ritHY6upgCyp;m;UufnW(snl+zca)c*;bLwAt@HoU}-ZD*+ys zRTyT@cmPIXLDEmw*1wHK@IO(70d6VN0^9i257kLlVQ^aeo=X5Qpn32sxBkqPZ>oR* zU|1)Nuf}rTEsAI*nB9}WzT@=^h0&r;P3IjF=%=m ztIRJ~gl?P#-hiJ?dYK~8a*RwUxaV_r&+Y7%_)pEKf9`rQNlFNJC={&#Hj4IM=VI05 z)t|X57@&$Y9;b9yl-kDSBM6m1fwDI1iZO=}1HkAF~$c02_T^t`b%`o)6O1A8vM=YxDxMgQq?nLpe5 z3f;26;+I!&&lc~YP|WW?_p@bzf&~@`DNK7V9k}Px(4Q~&A0Eu`%LC}*{^etPkq7X6 zkT)NVI|?>#B&9bSpk-r;=!m zddAgb__LTQrH!qn>@+REai6+YgnILjWk6obDpQaGWP)$rO&-%?J|b8NP%tpc4M34CDUweM~qRo zUO#c9#;zXk8XO(`fYKkcC{ILL1$-O6SHMlu77`O&W6PzVrFasG_?j`;$D7of=gXaG zu~Ibly6$N�xW;BE_H7xuAQc0i9G86zri=1x||EdUFvxA2<6|@1E+jw>Y~-479X; zNFyYyKtQL)p!nULlSjshtK!7y1r79W!5DTk-$Op(u&GI#f>^Pl<^2V=$!?~9rU2rJ z&PO5C1{>%DJ^4jPpF73#oKubH_hrG(rGaH@DBww@4>t@I44?i0b+Ko`c7zu?U?o|B z<+ICG-O#ahBAy;zWCm9HFoMYAGnPhjQ=${x=8o3XOSkS)qAAp#-Vp zTEG~DJY9cORC$`enG_#nQH1PbroSz_fal$Gz3q6BQ82M#>R3|3+UmM^vfZ@X1|kc1 zQ7TCjyBvpqfF@jifFiUf*h_=or>tPi{Gto|&plBL8a!R7>egXsKtxpXRkOV&?%$J+@3^e*|GEhGaYupA2S6HD!_9ICVN z`hagEHJ?&)!b#FzAOd^TgvsD#sV7H0=|_X`J_$jXM1HGqRh6%l@P6m;@byg<+ja3$!Gg&HlT*>E};eafmA(Bvs4%~fpiOvzdkp|8`Rp`~ID&I}B%knAG zsv2#Nk{^f1--V}3ZSt`WRPq0VYI)@<1T}JnWSG2F^I*|V-a8LPw|S%*R@XlXHU^Qv z;lsLJ{;H>kQLk?x&nZEL z?WjL-Ia@3`33`oO1D_HPu03lrh?WW!LxN=u@`o)62B!q?}8={il^by5d} zl#oDWShi{&=gT!+IjW|f(P%7|VR;?un3Q78*pGz`D>OanG`QI($KDHz*lNz2kAcsd zE=`oy3|UO09&ihlkMq*CB^rQ0h6>qAs6MFt19b2*v9`Uju7l&TvDLBwp*mrI_IzSc zG_3WtrQT)(>qgNlYhds%4n_p#d!;d?FUpr6fqs8r^002Z>3-d{IlD=oN16vS@)%#J zH?Y(wHPi_zUni7DPUy#BBNUx2DxAjC0QJVry1<7%rx+IxNTiUWB1&QW^AmPGE9KI} zj`G-V|#T8hcR)=1}d? zF`aCbf_{Qt-+JXT(X<%4eA!i?Pok^0HWY}zZjDH2Y2J5Ud<$n-V0>H8$w9DSj* zs}!UgpneG4 zxk}TaOmlv#c{2Qsy&bh8X%&eQ6Nu4Hl77F*|8MyZY?B3;=|`x@ z`FwAwJhL}V>Xx!;)LgDziJR|f*1_<7s31t5O~NtX3vwXui@zp?a4Rd-H=Z1s`MwX= z&tJXaALG--V}aGA`;a?qwpQW;B`~ik z(^#D#DY|X={+NOQ{4D%9F#H`Kl_OGGD`edA2BoD(7W%}|nSU$go$QioK{VyS+DKkb zk>j_j3fJ`;GhG`35eUgImw6^=DNQ@(Idyz6d9kF;>|Qw>+3Z z{lK_uN4P|dYOuB-iHAg26~3|u6OMGV%=}ln%DmT$fcc<4RIQ=;!0mYc>u0oKA&0$J zQ}dEjTF*IDU+^>x<8 zV4Yd=7FWr2#)pS0LFR^Vx}3=w3RDTf5V#{_QM zgi9@ru}=2z1DBjI8eNWASvk;?i^k*WQ$qR<*Y8xvd|NSy_fTQI$EwD9Pmw#Zv)HF- zVf)g%OeMI7Gj(iagRz^TUMNWKHyGeQ5_a~TbLH6-uiGK|y@k_d)z4X7l3i8P>H6|{6F;t$Xd z+2dZL)ij)ODL&5Q1a?&G%p5v$GV-bLB*|`3Di{OY-Y4s5#_h5J$$o+Gd#L+;XmnAz zUSD@=RPI(pKGK@MrYz@OXSdl%?S}iVIuK;ET-2bb9@9a8Zwo78)Is$;V*(Jx5N<54 z4}RiA%#T7ZOJx4xDR5qInc$$w5EX~8N}z;?_njn3vEUpa7BZS^xJ^nut7CT*t0hIg zIhpk?uyQiO6%gb(awY9pdhQ^4fPU8~looL%DyM1)6+b!$%rlc->*n2FNsUz7EHW*x z2v`|AC;2YY`XLYqzy2Hu?c&KEO~`|k4!%u^!$O3kka&uYR{w?*a62uRN#wH$_H)A9 zjUH>ZiFcJ!*an|yQJs@!7n1hkZmvX|vM705NDpyx7hTa`5S}U}rc;390al%IAgg|xrQ2w%mssQTp;xZysa=Im1ZL*rkaNE6p z#is+6c}YhsuDxw(30)$X=%B2^dOcC!!^!!%LmnV#!c!#(^2rZ5`7HxZGFG;(?-Y3Q za2quBY+bP3uC5>o-v+WC$6I@9II%-}#qg_{8PNeEk<&>GNVJi0W?WEB2F8^wUT)_U z;|>B3uqCCugY*;g7aTsz$M}4(h}?&7>-tg#;Ktu3Ab-vlazdv%Lkm&i^$M5F{f~6G z$rgW)=GzB(F0ak}jIYf+>zy4O5ZnhxJ;j0FS+6le4r|p;=Cnx{pB>$9P~2fKll-Hi z579QkhqIkYO zxmtZnbq6Sgzk^A?6e+hH|4Auk~m6Yzre|opokE!{b7C zh#o{WA+tX@Aq7LiYxyV^t=3)Hcb^q$PpysYKedw*0f0poTqK6cTbpu6X&hxp*EP7t z>ej#?-?kU2QadgJf$H%sRteH}3!?S{DIc9lkKb{}C-%tNa}JI~CA)R@CHbf?n%((r zF7>bb{@*pdmVt;Yg+7hUAyi`y8@C$I>MDs3Up#+d@dt>(9-4lk=#|}SbvVj#IkT)H z!ZP6Dg|_F?eA*4HBRu4+<|sx}3Z&)8(4nsT7o~@8U?P=wdoj2g@T6BaEA&?&_gfqB zeDzi!$#q5I^mtwzj6ZZ(a;b?T+BL>X?dbLu$AY{NOWz5inG{E2GeR$}vOls-f%EDC zG(f4n7N5(t8?sgMLODpjEh~?B5Ws!7HS9c~k!2j=Iq`=xbB_k`bSxpaYxLmMG3oLV zd8Tkn2@O%TXZ0^!qSvi>^f1;)j*RT`MEP?2=Posb8(ML!_&u;mz+-C6+3Dj9rujsiFj<(R$iAXzc!tn%=%Pr z;DIbK0#9rJ!IZ)n8Wxqt`U$rE1>~b^?v+kMc5ikGV;WCe*`NklY~Gs0aDB4iF98OR zPA(}Dd&_D?P_gvG@O`$4Z)-<_!atR7t|MpkRiDnzaiFA{BKE<--bm6zgB1t_{Wu{e z@axBe(_rfKIiGbk;U*$1+!zsnQx}f#c((vS98oLDDZ3-e^d5hf)7Rjx_*M{!c2yvm z-85L*rREKMVXB07M?`~qlVUUNewFviSv<(Q1W~YnE(_vJRwSvMYfjy?dSJeT?*&H*qEN zzLUFB+q&tR^4k7-MuAA~Z2aJW-zDUJO5YW7VahgIvggIs%N<;WLn7j7_jfh5SW_fK zTPApL7bZu@S>x?4ZWuq~;m-3bej8&kpssgr%cihK0nD;gC?HXgj|TV>fl3Z;rgtqd zx(lx9B#X!qzg%OL%@Ba@i|`ezBnSAUQgy~1RCkHz{P{lC9}{#|+ZqWR@KX_OgmU9# zh}T<-`@W^H&oI}vdkEw2T_Q3CM&0;^RW>4;fg23>dlZ-*rS)FDpjn;qQ)IPPc~1Ry z(a8$j2l6c5hf9wX<~guqE3p8X=ev53-Px7lBJ`BX`kag*{hW!A)Ra{a%^+_G+ZDVV zcRY1JPV1P*#rr@^G*~SS1I=wXMW%qiY#z-NeUG{|IMS>3R!gm*v>!i1K;fzM;7?-tu!|6~W_*GcL3n z-1{&W)F6AL8mVj8;I?(C16aqPrFqR%5xR6r?*}LyJcGPASnAs=6HktebxMts-JSF* zjf8FKnM?gDW#T={gVe_wf^uFlFga^#pusK4s-GH4ql$+{Mpn5T*BXja8Tsx)7ezwi1 z$8r;{XC63Z(jIYzz??bOA8a&pA;A^&anwiR?3Mi7rdNgLj;T4)-@YNft^w(Mjp)5S zXjzmFdsL&B*@Nvk5yiWXcLoa6Wtnh#I5gRN*1U(Ra1+sb30v!n=-ZB7`EU$aof84_ zk@_WwvIhJ1CZ=noTcfX~oD+{B)C0{cm!o!%V$OW;tV!RBPAY%?__a4JCu@~)ECZlB zKZKFdztUF4_i}gQa^ExGXk!x%ke2B7Jv+Z;$dTa_**QLedhHQ=NcZc|^GUbhn~L=8i6KH3ZKiI#w4=*L0=yKtgchZ>{M^k%uU+ZUkHf3rZ$| zfN7^b-&ARClrPKDi}k*e6_*~O)k=~Z4nrj$Ji@;*7+l;LgiJyCfOMO`{f3=vd02lA zvtaU9v-Iaawi8VS`_}czLfDY2AXcYk z1X?b!Q{2o`;Zol;&yz1Mw4tpg$_aPB40+$|zh6fV%s+V4xbeLVcy*r+E!=`sC|~`4 z?WY_~{qfdlhZcF@Ot8O&=t(Ux&+eTY{uYA|_as)RVMg=;vREUkv(~N1diQmf1X0L% z0wys}ZQC|Fgjs6!Q%(41i9sQ}bzHTNc2KqtW9JSVnYo}f&HP;(FD`~2G%`Oyz2Y-* z05b?2rb|CDEMr3eQGqcLXRu0Dm*&}BGDGDeq-cvkS(T2|M5*d&5#SrK~qT)*T;4tnRA zI)C5elq+zOaFCV9l)zEPd&OZFEj-V+HK-jMv`DA4H>DiI+3AWJmEtOHOCKe8zew`~ zNLk;<49$x$!BR7UX2_0=^)R-1OTScKmhJg|Rz9e_%Z*~n4-kQGC1!kQ%|A({0z%pk$4NNa1bCPg5;2_cKSBxQkIL5m(zk7ABTS0hPJ=SzeWvj z@jcW-v&tw-&NuOVCjB7prdUuNuHY*@q(W|OJCc5Qk3|5-Yz)N6R}{&us^IG_;p&hATXjSBS^s|*2oz_#|nKzi@S z%Y!ir(%L9(gX#-QuvB&AeUwzguv36Cj5i^x@Ef(Svx!4C`Rfmm`q$gF+@#>B$&M3` zmxV{#uLPdWcN6Q_{pL8kA>>yu{A=+0`zQ6C+L$8PL%U9HZ!H_{c#3$@+}jp<&bi>* zsV?E>!8f)OY|6~;?@UFlNk$LkVK%{&I>L86?EI zVpSLgWUh_Zr5F}>BJ+6DocIX`4d=S;*F+^_WGYsaPj#|hSu{qZfT+k8U0CbHu$L;{ z@g5Z#o%~$~qO|QoFHsyB_EYYgQVp`2avBC->DdI!ES1Zj`QYh*eXsm&a#yYJ18j&| zKSy{a2VtZb&jx-6*?AaHymr&cS8kBAwz3koj(Qgr@1`nIT#~63RC-9}lYWK{({s@z zVuOOg{P3f8cDB#&#wS)4Zp7$J@5FfB=4EWcaN(q~fXz#$kSDz?*2KzN9b8s+oR^^S zRbF}4QVu7vm7#mN%SVCd!TRTc{;ZD{6uJC4x6YI!e1YbF6STXF1OiZdlQl^v&)MY~K^2$fsq1%U4c zL_`+*>f>F1N!rD^3#FWaEH$F_sR!+qA?|KD*L_s;^2hd_tgSezC@yaOQB?V1j84nL z#X2@&_>rzD=mAvNY}59jSn2!`$H>cQ5?d==Oz=72I09sWrYcO+st^T%ASLbwudK|r z$8?G-nX;(YcQFL=h-Sgjl~e5}$XUybc7y^~PnIYd&iUnvXnj#Dc z6Hhh!ntOnyF+01RbvgCwfgQTVty)(CZaRAkft068X`ZA{_|^pZ;hz-x=8ZeDn-$84 z;-G03KBmc8rbC+6jL{Sfn_< zzAynURa#bmwek&XAX<*VGelK_psf`Mz}$A_hor)BE*CHGDBVa_ZuFZ#njcS1*6KLzWA_H zuiNAgpjmSB*6?CwD?VQ(r04;g>tBA(19=9m$5}7cJzbS+>1TR0W+}qJxjX_<9ILQ^ zU7NP6reKH?x(AdZWNtGV-J~}AdoVpX@4=aIh!qY;&o)=(CeJ%QOI}_{dh(Lpw#=4A zCm94K9XF5K1C&j}PP;Mr!wsZ~>-}7J!f!E06-ZmBT2r-@7t zOa0|9Lsx}e@9ttU-8663ig4-KXj11ZPp|7J*}KUtpu1?%X0W~OpmUnI57o=pn-g{M zjZ_t3iGo4$(ik|t>F5KvB7V{2LHg-y$??5c605ZsHMkK*X?w%k5Fh9rWL|P@j=Z9- z;yd3D#{slx*P1tn9LmzQEE(K1M8@lglwVnS^Qvw`EDenQ1;G5TGA17p$t@n{o;?$4 zETIT#4@XT;uQh{_aNBSC?&QOX;nx(#JWkSjZ;tTO!6cP}fh70UL)VV?-FDP&cNk}V zq7srOm^!QQ%vX%T_Ho_8`m@X2_FO?gr`~&5$l~C<8E@7UjA3E;2EXM%rufkP5v*v~ zLuxvsqIq2CmQzsOIu*9N4(O-2?zTF*%@*ue{WL6MP>qXK?vBwBn@-s<91QKd5@pEP z)QgKZza>^-zxuIj9JFI7iGH6TYk-Z2tpbR+?EB{JRE1`f)}4&61lg%qJ8dDr%*`VH zqBodF$#U^s$S+2|Mq*)O;Huz9K(#8yPi5hsX%unSw}Pp)fZC^M5P04aBX+@*SkfF# zy}ZxD%yhoMQnXFb!8cZkCuzi*YcZSE&Q3mf;5&L63r`hjn5Bi4&my z!Y{0QpZ>B!6Uw*dFOOJtm+>XxJRrA9c2nCOnwf2Gdbo@}URB#ai3uL(?8ohYV?K`Z z?X`Qg^ft!ms9*^XQ*6hROX2~_a)kB)T+fD=ms0%m=3Y(CYccx;Q*Xh5kxfp4=BGbk z!v+SY;tQB@*N!Nr2W#Bc>js^y=cyz_g_xh{#%b8(AZb^=$l2ZXSpAS}Dpq+p{bF1Q zQ(*T-8mHCoz-3F$!V|RoYnSW=$bRO6DoBi$A_%-Vr!*M9fMk)=p&8}c?I0r0ZM<^d zZ#3pm@bb|9&ffM@ZCzLyI=5wOmJ1gu70+K=;w0dBsCEYWT8T(XJ5UEmCJg#%CR3GZ z)>HjOFjtexvnxc>cxr*y9fRJ|JPxiKfj9dkEy_y#pWwMI{6}|nlw&+)cQuEvcSx@c z@Xr9ZEbss@erT8rZbd2air~ zPP&;D`Kt=q2s4$&E@c*C`S3d$8%?vZwXE9+W#anDiU{$^kY}<2R%N}uqT@qqtKVdw zY*{kcGsG~BIkV1~K|*|?s4T6)0;$zn5!*}2`Dbs$yVf^YGHW-Syt0@Qk_kdf{tkNm zc}vir>9V0eca?Ac05wQ`7rO-6#bM^J#?A4}{s1x6O~05!Zjpf&i6e-#e;_RREz$S? z_`NzPfUQkM9iR->ivTG%DJnF1MHK6Bj$A2YbpK8iRVN~g)S!x;-Wgn4oU%Llq}M4Q zdn#ni@FX92(zTAV>7xXwkIcMC)p%Z}P@GJ*JZ$!v*9w3&ho?HIFal(t9F4Ks zlaAIB00?~U1I3IOzQ&}=*AIcMkHf@)6~-dfx{xh*vfQGm?cjj1z1HfPSlK|*Q6vpr zn+!+^78~oBaiWBT>!Fe+w{hlI2P-TM=$|aCX|7rY=u;pNs9p#tCjBV{{d-9IXFpG= zN>WgiC_-(H6aPv@84}ybYSy!+wk=WND@U&Jp{t29J>;kKO(g_QG}Ovhmqv<|LBvLl zUMQ}8-JPK9Z=*4+stNuXNzUvOO^R*8H>GlHRC_`kT0ZR--b1g%z5rL4rIU&h0hPT9 z&5~$$T}MRnzP&~ZK{QGd4s4zF7X&w_eA&7SI>_MnYsHN58Ks;+oPq`KWa8|qriOe6 z*@Qf_J~ECL5-5YMo7>+(&kw(_Bf`VX!59|G@Jg>@*jLk7mq%*Ec8hJyq_`*vSpVVj zw`#*4b^F^do-M6LI2g+5tz^ffX5(3A7j?cKSGMH!rV5C?$1L5$8d8 zQWj-vYgifo$zXTM6%c#6zh~`d9Im!K#W-n_XS7r}gRKfBR0Mqj24hISS3DLLR+~jB zC&eivx$KP3h@nTXuV;;!WC}5;Bt22t5pMRbc5_fk{#-VA9w*b>A{MD}=2KJlu?<-U zp1+UZ*X`_7mPZZCij@bs6t#)!@sGqo3>w(d?Su;^CYRUY5=@bb{UtKOehmGC{mA{Q zN3x!ZnAsU$jWvn$y-IDj&B|u2PMIxNAAP|YP6+XvB8dkL4C@x0P(R+kt4ZllLN46aRedi3@_JMEN z)*!@n$Q-yZ^oh|EY(T(1ZBM@ps4lI#1g>gdd3S^Laiu71yEhE9mMih){%)$W!)b=j zS8OWd(@B_#Gj?zLV2|z+qB??F(O_(F7-pBOL57tW` zzZY3CA4i%(r&QY$cVJC*%-#^fS`0SO7Qx>2+IRdOpmYSWe-AVdcvk%O?Wx;(e!1sC z0IY-7Ljhy#yL|GwPstt2=7bN0Y@2Mbr@mR0fHD3U3;(j-f5&>i0%SQLLIYFoq;9HG0Nlw6-3@}0@?Z--07K3R zqaHYw#z^O}+J)BwEh`Pc+jU=ycBX45)!Pk_Vn)#$0XG76WC48`2CI=65>O5K3e=ho zl+d##1cB3-2=o~P@f}7m#Pm~v3`r2P#f|yv=6{*}FNgc0Dx^Kz5oCK literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat new file mode 100644 index 0000000000..11a9e49e97 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat @@ -0,0 +1,76 @@ +# hw definition file for processing by chibios_hwdef.py +# for F765 bootloader + +# MCU class and specific type +MCU STM32F7xx STM32F767xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 41775 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 32 + +PB1 LED_BOOTLOADER OUTPUT HIGH +PB0 LED_ACTIVITY OUTPUT HIGH +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART2 USART3 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 32768 + +# UARTs + +# USART2 is telem3, MSS_SPARE_4W +PA3 USART2_RX USART2 NODMA +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART3, UART_2W_DEBUG +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 + +# UART5 Telem 2, MSS_UART_4W +PD2 UART5_RX UART5 +PB9 UART5_TX UART5 +PC8 UART5_RTS UART5 +PC9 UART5_CTS UART5 + +# UART7 Telem 1, TELEM_UART_4W +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE9 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# Add CS pins to ensure they are high in bootloader +PF3 ICM20602_CS CS SPEED_VERYLOW +PF4 BMI088_G_CS CS +PG10 BMI088_A_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW +PF11 SPARE_CS CS +PH5 AUXMEM_CS CS +PI4 EXTERNAL1_CS1 CS +PI10 EXTERNAL1_CS2 CS +PI11 EXTERNAL1_CS3 CS +PI6 EXTERNAL2_CS1 CS +PI7 EXTERNAL2_CS2 CS +PI8 EXTERNAL2_CS3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat new file mode 100644 index 0000000000..6f72d1eaeb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat @@ -0,0 +1,280 @@ +# hw definition file for processing by chibios_hwdef.py +# for Modal AI FC v1 + +# MCU class and specific type. It is a F765, which is the same as F767 +# but without the TFT interface +MCU STM32F7xx STM32F767xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 41775 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +FLASH_RESERVE_START_KB 32 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART4 USART2 USART6 USART3 OTG2 + +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - ICM20602 +PA5 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PB5 SPI1_MOSI SPI1 + +# SPI2 - ICM42688 +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI5 - FRAM +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF11 SPI5_MOSI SPI5 + +# SPI6 - BMI088 6DoF, disabled due to lack of DMA channels +#PB3 SPI6_SCK SPI6 +#PA6 SPI6_MISO SPI6 +#PG14 SPI6_MOSI SPI6 + +# sensor CS +PI9 ICM20602_CS CS +PH5 ICM42688_CS CS +PA15 BMI088_G_CS CS +PI10 BMI088_A_CS CS +PG7 FRAM_CS CS SPEED_VERYLOW + +# fsync pins +PA0 IMU_2_FSYNC INPUT FLOATING +PA1 IMU_3_FSYNC INPUT FLOATING + +# interrupt pins +PF2 IMU_1_DRDY INPUT PULLDOWN +PH12 IMU_2_DRDY INPUT PULLDOWN +PG5 BARO_INT INPUT PULLDOWN +PF3 SPARE_INT INPUT PULLDOWN +PI6 IMU_3_ACCEL_INT INPUT PULLDOWN +PI7 IMU_3_GYRO_INT INPUT PULLDOWN + +# LSE crystal, unused +PC14 LSE1 INPUT FLOATING +PC15 LSE2 INPUT FLOATING + +# HWID pins, unused +PA4 HWID_DAC1 INPUT FLOATING +PF4 HW_VER_SENS INPUT FLOATING +PF5 HW_REV_SENS INPUT FLOATING +PG0 HW_VR_DRIVE INPUT FLOATING + +# security module, A71CH +PH3 SEC_RESET INPUT PULLDOWN + + +# I2C buses + +# I2C1, EXT_GPS_I2C +PB8 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2, DISPLAY_I2C +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3, EXP_I2C +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4, BMP388 BARO AND A71CH SEC MODULE (0x49) +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C4 I2C3 I2C2 I2C1 + +define HAL_I2C_INTERNAL_MASK 1 + +# GPIOs +PE3 EXC_GPIO_25 INPUT FLOATING GPIO(110) +# PE4 EXC_GPIO_26 INPUT FLOATING GPIO(111) + +# allow to have have a dedicated safety switch pin +# on PE4 +PE4 SAFETY_IN INPUT PULLDOWN +define HAL_HAVE_SAFETY_SWITCH 1 +define BOARD_SAFETY_ENABLE_DEFAULT 0 + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +#PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH +#PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH + +#PG5 VDD_5V_RC_EN OUTPUT HIGH +#PG6 VDD_5V_WIFI_EN OUTPUT HIGH +PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# UARTs + +# USART1 is EXT_GPS +PB15 USART1_RX USART1 NODMA +PB14 USART1_TX USART1 + +# USART2 is telem3, MSS_SPARE_4W +PA3 USART2_RX USART2 NODMA +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART3, UART_2W_DEBUG +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 + +# UART4 GPS2, EXP_UART_2W +PH14 UART4_RX UART4 NODMA +PH13 UART4_TX UART4 + +# UART5 Telem 2, MSS_UART_4W +PD2 UART5_RX UART5 +PB9 UART5_TX UART5 +PC8 UART5_RTS UART5 +PC9 UART5_CTS UART5 + +# USART6, spektrum +PC7 USART6_RX USART6 NODMA GPIO(74) +PC6 USART6_TX USART6 + +# RC input. Support all serial protocols on both PPM and spektrum +# ports. PPM protocol also supported on the PPM port +PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW + +# setup for spektrum satellite bind +define HAL_GPIO_SPEKTRUM_RC 74 +PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) +define HAL_GPIO_SPEKTRUM_PWR 73 +define HAL_SPEKTRUM_PWR_ENABLED 1 + +# setup for RCIN on USUART6, will auto-baud for 100000 and 115200 and +# auto-switch inversion as needed +define HAL_SERIAL6_PROTOCOL 23 +define HAL_SERIAL6_BAUD 115200 + +# UART7 Telem 1, TELEM_UART_4W +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE9 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# PWM AUX channels +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) +PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PA8 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) +PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57) + +# PWM output for buzzer +#PE5 TIM9_CH1 TIM9 GPIO(77) ALARM + +define HAL_USE_ADC FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# INA231 battery monitor +define HAL_BATTMON_INA231_BUS 1 +define HAL_BATTMON_INA231_ADDR 0x44 +define HAL_BATT_MONITOR_DEFAULT 21 + +# on some units a LTC2946 is used +define HAL_BATTMON_LTC2946_BUS 1 +define HAL_BATTMON_LTC2946_ADDR 0x6a + +PC0 VDD_5V_SENS ADC1 SCALE(2) # ADC pin 10 +PC1 SCALED_V3V3 ADC1 SCALE(2) + +define ANALOG_VCC_5V_PIN 10 + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PI11 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +#PHI11 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# SPI devices +SPIDEV icm42688 SPI2 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20602 SPI1 DEVID2 ICM20602_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# SPI6 disabled due to lack of DMA channels +#SPIDEV bmi088_g SPI6 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ +#SPIDEV bmi088_a SPI6 DEVID4 BMI088_A_CS MODE3 10*MHZ 10*MHZ + +# two IMUs enabled +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180 +IMU Invensense SPI:icm20602 ROTATION_PITCH_180_YAW_90 +#IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90 + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# one baro on I2C4 +BARO BMP388 I2C:0:0x76 + +# microSD support on SDMMC2 +PG9 SDMMC2_D0 SDMMC2 +PG10 SDMMC2_D1 SDMMC2 +PG11 SDMMC2_D2 SDMMC2 +PG12 SDMMC2_D3 SDMMC2 +PD6 SDMMC2_CK SDMMC2 +PD7 SDMMC2_CMD SDMMC2 + +define FATFS_HAL_DEVICE SDCD2 +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# red LED +PB0 LED_RED OUTPUT OPENDRAIN GPIO(90) +PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(91) +PA7 LED_BLUE OUTPUT OPENDRAIN GPIO(92) + +# 2nd bank of LEDs +PI0 LED_RED_2 OUTPUT OPENDRAIN LOW GPIO(93) +PA2 LED_BLUE_2 OUTPUT OPENDRAIN LOW GPIO(94) +PH11 LED_GREEN_2 OUTPUT OPENDRAIN LOW GPIO(95) + +# setup for BoardLED2 +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 92 +define HAL_GPIO_C_LED_PIN 91 +define HAL_GPIO_LED_ON 0 + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +DMA_PRIORITY SDMMC* ADC* SPI* TIM* UART* +