From 7c864d13e3132aba4098fab6a3101c5aec09afad Mon Sep 17 00:00:00 2001 From: David Crocker Date: Sat, 7 May 2016 21:55:19 +0100 Subject: [PATCH] Version 1.12 Enhancements ========= Added support for RTD temperature sensors When cancelling a print, if cancel.g exists then run it instead of turning heaters off Improved file upload speed over the web interface Chamber heater is now exempted from timeout Pressure advance now reduces maximum extruder jerk setting by a smaller amount when the extruder steps/mm is high The Duet no longer reports itself as an Arduino Due and has its own Windows driver Added experimental "maximum average printing acceleration" feature Try to improve speed of getting file information in Print Monitor Bug fixes ====== Simulation mode was not working properly External driver support code sometimes failed to enable the associated drives Fixed potential overflow if a user attempted to use non-existent driver 9 on a Duet 0.6 M408 status requests were not handled when in simulation mode Removed hard coded PATH in project --- .cproject | 10 +-- .settings/language.settings.xml | 6 +- .settings/org.eclipse.cdt.core.prefs | 9 --- Driver/duet.inf | 86 +++++++++++++++++++++++++ Driver/duetinf.cat | Bin 0 -> 6402 bytes Release/RepRapFirmware-1.12-dc42.bin | Bin 0 -> 268732 bytes Scripts/signdriver.bat | 6 ++ src/Configuration.h | 5 +- src/DDA.cpp | 92 +++++++++++++++++++-------- src/DDA.h | 2 +- src/Duet/Pins_duet.h | 3 +- src/Duet/Webserver.cpp | 37 +++++++++++ src/ExternalDrivers.cpp | 2 +- src/GCodes.cpp | 51 +++++++++------ src/Heat.cpp | 2 +- src/Move.cpp | 51 ++++++++------- src/Move.h | 23 ++++--- src/Platform.cpp | 36 ++++++++--- src/Platform.h | 3 + src/PrintMonitor.cpp | 12 +++- src/PrintMonitor.h | 3 +- 21 files changed, 327 insertions(+), 112 deletions(-) create mode 100644 Driver/duet.inf create mode 100644 Driver/duetinf.cat create mode 100644 Release/RepRapFirmware-1.12-dc42.bin create mode 100644 Scripts/signdriver.bat diff --git a/.cproject b/.cproject index 868045e..9148db8 100644 --- a/.cproject +++ b/.cproject @@ -106,7 +106,7 @@ - + @@ -216,7 +216,6 @@ - @@ -231,7 +230,7 @@ - + @@ -337,7 +336,6 @@ - @@ -353,7 +351,7 @@ - + @@ -368,9 +366,11 @@ + + diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml index a324ff3..02bb3c1 100644 --- a/.settings/language.settings.xml +++ b/.settings/language.settings.xml @@ -5,7 +5,7 @@ - + @@ -16,7 +16,7 @@ - + @@ -27,7 +27,7 @@ - + diff --git a/.settings/org.eclipse.cdt.core.prefs b/.settings/org.eclipse.cdt.core.prefs index 56c0bff..e296b81 100644 --- a/.settings/org.eclipse.cdt.core.prefs +++ b/.settings/org.eclipse.cdt.core.prefs @@ -5,9 +5,6 @@ environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.9764 environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/LINK_FLAGS_2/delimiter=; environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/LINK_FLAGS_2/operation=append environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/LINK_FLAGS_2/value=-Wl,--end-group -lm -gcc -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/PATH/delimiter=; -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/PATH/operation=replace -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/PATH/value=C\:/Arduino-1.5.8/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/bin/;C\:/Program Files (x86)/Java/jre7/bin/client;C\:/Program Files (x86)/Java/jre7/bin;C\:/Program Files (x86)/Java/jre7/lib/i386;C\:\\Windows\\system32;C\:\\Windows;C\:\\Windows\\System32\\Wbem;C\:\\Windows\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\Common Files\\Sage SData\\;C\:\\Program Files (x86)\\Common Files\\Sage SBD\\;C\:\\Program Files (x86)\\GNU\\GnuPG\\pub;C\:\\Program Files (x86)\\MiKTeX 2.9\\miktex\\bin\\;C\:\\Program Files\\Microsoft SQL Server\\110\\Tools\\Binn\\;C\:\\WINDOWS\\system32;C\:\\WINDOWS;C\:\\WINDOWS\\System32\\Wbem;C\:\\WINDOWS\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\ATI Technologies\\ATI.ACE\\Core-Static;C\:\\Program Files (x86)\\AMD\\ATI.ACE\\Core-Static;C\:\\Strawberry\\c\\bin;C\:\\Strawberry\\perl\\site\\bin;C\:\\Strawberry\\perl\\bin;C\:\\Program Files\\nodejs\\;C\:\\Program Files (x86)\\Skype\\Phone\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15\\drv\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15;C\:\\SPARK\\gpl-2014\\bin;C\:\\GNAT\\2014\\bin;C\:\\Bin;C\:\\Python27;C\:\\Users\\David\\AppData\\Roaming\\npm;C\:\\eclipse-juno environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/append=true environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451/appendContributed=true environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_1/delimiter=; @@ -16,9 +13,6 @@ environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.9764 environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/delimiter=; environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/operation=append environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/value=-Wl,--end-group -lm -gcc -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/delimiter=; -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/operation=replace -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/value=C\:/Arduino-1.5.8/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/bin/;C\:/Program Files (x86)/Java/jre7/bin/client;C\:/Program Files (x86)/Java/jre7/bin;C\:/Program Files (x86)/Java/jre7/lib/i386;C\:\\Windows\\system32;C\:\\Windows;C\:\\Windows\\System32\\Wbem;C\:\\Windows\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\Common Files\\Sage SData\\;C\:\\Program Files (x86)\\Common Files\\Sage SBD\\;C\:\\Program Files (x86)\\GNU\\GnuPG\\pub;C\:\\Program Files (x86)\\MiKTeX 2.9\\miktex\\bin\\;C\:\\Program Files\\Microsoft SQL Server\\110\\Tools\\Binn\\;C\:\\WINDOWS\\system32;C\:\\WINDOWS;C\:\\WINDOWS\\System32\\Wbem;C\:\\WINDOWS\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\ATI Technologies\\ATI.ACE\\Core-Static;C\:\\Program Files (x86)\\AMD\\ATI.ACE\\Core-Static;C\:\\Strawberry\\c\\bin;C\:\\Strawberry\\perl\\site\\bin;C\:\\Strawberry\\perl\\bin;C\:\\Program Files\\nodejs\\;C\:\\Program Files (x86)\\Skype\\Phone\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15\\drv\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15;C\:\\SPARK\\gpl-2014\\bin;C\:\\GNAT\\2014\\bin;C\:\\Bin;C\:\\Python27;C\:\\Users\\David\\AppData\\Roaming\\npm;C\:\\eclipse-juno environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/append=true environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/appendContributed=true environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_1/delimiter=; @@ -27,8 +21,5 @@ environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_2/delimiter=; environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_2/operation=append environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_2/value=-Wl,--end-group -lm -gcc -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/PATH/delimiter=; -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/PATH/operation=replace -environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/PATH/value=C\:/Arduino-1.5.8/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/bin/;C\:/Program Files (x86)/Java/jre7/bin/client;C\:/Program Files (x86)/Java/jre7/bin;C\:/Program Files (x86)/Java/jre7/lib/i386;C\:\\Windows\\system32;C\:\\Windows;C\:\\Windows\\System32\\Wbem;C\:\\Windows\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\Common Files\\Sage SData\\;C\:\\Program Files (x86)\\Common Files\\Sage SBD\\;C\:\\Program Files (x86)\\GNU\\GnuPG\\pub;C\:\\Program Files (x86)\\MiKTeX 2.9\\miktex\\bin\\;C\:\\Program Files\\Microsoft SQL Server\\110\\Tools\\Binn\\;C\:\\WINDOWS\\system32;C\:\\WINDOWS;C\:\\WINDOWS\\System32\\Wbem;C\:\\WINDOWS\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\ATI Technologies\\ATI.ACE\\Core-Static;C\:\\Program Files (x86)\\AMD\\ATI.ACE\\Core-Static;C\:\\Strawberry\\c\\bin;C\:\\Strawberry\\perl\\site\\bin;C\:\\Strawberry\\perl\\bin;C\:\\Program Files\\nodejs\\;C\:\\Program Files (x86)\\Skype\\Phone\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15\\drv\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15;C\:\\SPARK\\gpl-2014\\bin;C\:\\GNAT\\2014\\bin;C\:\\Bin;C\:\\Python27;C\:\\Users\\David\\AppData\\Roaming\\npm;C\:\\eclipse-juno environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/append=true environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/appendContributed=true diff --git a/Driver/duet.inf b/Driver/duet.inf new file mode 100644 index 0000000..2c32363 --- /dev/null +++ b/Driver/duet.inf @@ -0,0 +1,86 @@ +; Windows 2000, XP, Vista, 7 and 8 (x32 and x64) setup file for Duet 3D printer control electronics +; Copyright (c) 2000-2013 ATMEL, Inc. + +[Version] +Signature = "$Windows NT$" +Class = Ports +ClassGuid = {4D36E978-E325-11CE-BFC1-08002BE10318} + +Provider = %Provider% +CatalogFile = duetinf.cat +DriverVer = 05/01/2016,1.12.0.0 + +;---------------------------------------------------------- +; Targets +;---------------------------------------------------------- +[Manufacturer] +%Provider%=DeviceList, NTAMD64, NT + +[DeviceList] +%DUET%=DriverInstall, USB\VID_03EB&PID_2404 + +[DeviceList.NTAMD64] +%DUET%=DriverInstall.NTamd64, USB\VID_03EB&PID_2404 + +[DeviceList.NT] +%DUET%=DriverInstall.NT, USB\VID_03EB&PID_2404 + +;------------------------------------------------------------ +; Windows XP, Vista, Windows 7, Windows 8, Windows 10 - 32bit +;------------------------------------------------------------ +[DestinationDirs] +DefaultDestDir=12 +FakeModemCopyFileSection=12 + +[DriverInstall.NT] +include=mdmcpq.inf +CopyFiles=FakeModemCopyFileSection +AddReg=DriverInstall.NT.AddReg + +[DriverInstall.NT.AddReg] +HKR,,DevLoader,,*ntkern +HKR,,NTMPDriver,,usbser.sys +HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" + +[DriverInstall.NT.Services] +AddService = usbser, 0x00000002, DriverService.NT + +[DriverService.NT] +DisplayName = %Serial.SvcDesc% +ServiceType = 1 ; SERVICE_KERNEL_DRIVER +StartType = 3 ; SERVICE_DEMAND_START +ErrorControl = 1 ; SERVICE_ERROR_NORMAL +ServiceBinary = %12%\usbser.sys +LoadOrderGroup = Base + +;------------------------------------------------------------ +; Windows XP, Vista, Windows 7, Windows 8, Windows 10 - 64bit +;------------------------------------------------------------ +[DriverInstall.NTamd64] +include=mdmcpq.inf +CopyFiles=FakeModemCopyFileSection +AddReg=DriverInstall.NTamd64.AddReg + +[DriverInstall.NTamd64.AddReg] +HKR,,DevLoader,,*ntkern +HKR,,NTMPDriver,,usbser.sys +HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" + +[DriverInstall.NTamd64.Services] +AddService=usbser, 0x00000002, DriverService.NTamd64 + +[DriverService.NTamd64] +DisplayName=%Serial.SvcDesc% +ServiceType=1 +StartType=3 +ErrorControl=1 +ServiceBinary=%12%\usbser.sys + +;---------------------------------------------------------- +; String +;---------------------------------------------------------- +[Strings] +Provider = "Duet 3D printer electronics driver" +DUET = "Duet 3D printer control electronics" +Serial.SvcDesc = "USB Serial emulation driver" + diff --git a/Driver/duetinf.cat b/Driver/duetinf.cat new file mode 100644 index 0000000000000000000000000000000000000000..387ff227b1bc564d68df4ea5cf4edce5f494703a GIT binary patch literal 6402 zcmd5=c|4SB`+uHi#+Vsnm+XcTCEU;0MRpOgA1W!0iLs5wAZ^T)t)xUni$rCs6ct6$ zdQOYBQ>mjxag^$y(}D``JwoGs&%6Bb`+eTm^Lak5`?|0Dx|g}G@BO_VAW#}6QD&vP zruR#t;#jdjsTT;8-eM?hc zG!!MuTzq|Cx#_*zb|n|)YH3PlFs4f4X22BS4BW)T*m4n&5;4bwUeTlQtswe3Bld_n z;((YT07{OC3t|HQ1H@@mYl&En_Lw0Sh%?k#z=r`fID8$U28XZtsALNNJ3$FSZ~^KA zOn%IVq4*3iU4sl=vyo_og%M>?1SQIaAqfZz;UR`l9gD1hBZ2e8C=4ay=5PZtA{ylq zEENG-B8Nj%c(Z2Nk&nf#XLgcu9tlFDU%a{%_yjDU7(~M`+#mRAcpz)w>YNc{#1yXC z9`2EW7>w@86zTuW(Ms<#`*BnX!K92A;feUwp_Lgw0Gkn%z7>0mYkvUL&83@s! zAzp|d^v#10cWjfc48#f!GlcGELl;)?*bJe|AF`;PA)+@Hkxk&y6bn!i{J}85KPoyg zkzWM(do+l`smG?|X9pqPND$nd8T9cJJluG=pwPe6n8D4>hMOI?7E0fB785$5^j)_U zNraMcW#iJ)i9Q_eYTV0rSvUs%q~4R3>j3ODsE8{Ph`7P?#>bXCI{~h7IT8&0vym|9 z9l%*wP%{IG8`ChLH{nkqJPC;aAP|cI0%AZh0YfoNX30C3v>S!fXFqW}6DWxO%m*-I z#u5vafWf|QG@}RsM3Ou<&jD8j$|Tqz%gfEh|62r`763LG#-^60FgN*?lh-E;q=impX=HzU9MFM}4?dp<)6QMXv6m+uI&2TTMz+|6DUT z6j^pP_XL)x(xRTHY4C7mSU02ky25Gxk>|~w_}-a$XCB%9F_LvUwYgEheU^4aTTn(D z-6x|r{9IU<{Rd)uWX+#zM;=|#drx1~T7lSUl`G1{u(N30J4z**s7I<21#ZrRB=1vN zcXc1AF5IIY^6_=}Wsh!xPl7{3%8A62t3BFxry2F0Y*)ThM0^~}=3KJv?OAm8w9Q)^ zGqF$mOy3<3O|c`p+Eg{lA>iLMI~hSoWX$y7y*J?sQ^6#PvjKP zgy*h4ji>|^Qx#_BE*sh8`Q`24;mG>igI(_D+-}JMb)kV2QIV+N`sMNQ-#WDPSx%X0 z746e$(jAI^qp_$ijiMt&A^{Umg{TkB<%Mkw!jrtPr9-3vDv1m)12Hji0s+X9D9h4a z(ewcacrUb^Bw4)Pkfen~LqK#e~H8_f)1Pthdnd4(IR8c*G$BT=%GBS#1F%!5f zLnbGN6UH%&W$}z0z5Rfr(2pk38dw2~VzXkCbcWC#nlri4W46ptp(b2DzSrN_ajR2dgNu~WvbC@6-0DxB#+GOdF#FaSX`Yrm%8LA)8CG~~XMc`f`tiR0 zRK`>*J)=$gooAyOk}aXEjIhg5*j+P+O{~J8Op8E5nXLX(hPEU5wVPUw|E~|*l_lDd z&p~d?+Fmv5C2Des1zQZrytZ@m(mvC-lWy!ekw8y1EAo-eo7)?tbDzQ}UG>e16n388 zcwfP1=hgZfCqFzn^Xu(>H#nVnxl@d}PL~QZNz*@A6C}5!oXwT<4&&^k?D?km3sbB& zF1l|H&M|5BiYGo>nty!tD<8>&Y4ts`W=L(4SqcHS9Ws$$#sJrFZN^Qhy!pPv`9o@T zEhg2XM@EBy%TJq(X#aTo#wdUcqLD^4OeMx_tsKg2QF=l1Gu(7_tb< z3FKv1z^27G^8S}EhJS~phYPkblX6W`Hr;*N9gfSsy{R#TtJj`c9%!4_xVU4##&m|P zZd9XBZrSakBAwc${Bk8}bqzX@`Wm_>ol@H|R1&dIZT7wo}Lu? zi|3yWEYI@(G-vVZ)ofkXwwZRDpRcj9>FZ;xBUQRtfe6kGM2MX{%>S45(I`9R8O5 z>1hfpI~xzg@0h)tci{Go&E>snN}tJa@-jO^D?N0$DS-DvD~Ujjh;Hb-R?&5Pq0Za2@0_KQS46zlZmI7rNb}q&Yfag7 zC#6wOPyTDOzWuE6^zgGO|?JthKXTw8B*15GefOWyC9bJl+ z?q#@u3Q0AUjiD&u=l+*T^IwqqA2o3?XHs2A!-Zr>X@c`p2)Kku$qdvcN)QZ{z@HL$tIKAAjX3m2C z%NC06#GhweK?g6sy%qbiF0(ObS%~hb^D`?G=E!Bqm<8=s+G5gcu+PB2E~Yd>;(bkL z@RJ8N_e?5>ddl>?T%J;tQbR3PZCG)yJMrvsx167K65@SAT0&}bhtvrC{By`hr&BXF zv#$3kRB9hz^lL`Kp`1O3O3}UA5sTv54j0{^n%iwfyslNV<;06#Uo#AtdO$$71p@M% ziL)gTP+UOPhdSMf6BT~eAS*$Y0wkNGlwjhs2LBsLVys4^$e_ex{yQSS8}Pee^o_Z! z!G)1Hx!kWq-((PG{Peir{poMdR&SS>s@AXoQ&>L~@7ET!#60-9t5$4Tp?i8)SJbz#pFqrU+*i zmzRP?E069G8pWbJLIQ+qz~F}+RQW0X5iELupR=#OZ-AdaeF2M?#NkHaTBElrQ9^#4 zIVUA0879QTt4esI2-z^M4phJIN+H01fq~G43!59yGw@m-$zt+GDV8bDFvce+7H$d5 zfhBHX0*uXIar-}U-jG22>$0`G+va(zIr*A~MUAhYLyY$O6PHQEsG=bO&)ad`)#3)t z1%uei87F!jA8p8X{q{w*0(u7(BmC>o3_?1ZT$k8LzhEdenDRE5b3dPi-&l^yI6i$2puz2``-w^)DVgO(=-q4^%eaO}%*evSrqV&)15g zTX}**c)y-F|5Q<-YA&T?WZI*R%&O^;vBUJZh!*k(n=}zU0nTT!1Zu z-LvFaDyDt8~3n~fj%7EzjoCSi8>!W=$049~IU zha{D@oz)1oUpZJ1%)Apu^RbV?q%ncy>mTTSa=oRVDbSoMoZeWT5xm~SbBjV;b*oyUxWo_x_N zQ09mCd_K=yY#(%MUJB!Eo>sCWa2pAX*|+*9t-jLk`eR~JX7pY``et2Cy@jt=W#5l#*0)LP&x*sfCpx~=o!Yog+ul&)Nx>sm$L$Af;1MQXpVPdMe9A7_uZYDD8H-oIPHC2ds{y$rRJ6%|&O!aQQ!L&kRC!I=}b-zWSM& zz1LcMt+k)^Jm2*^&wADZ*%b7JmzC&F;nyGZi+{^}WpMJnaJ}+3p7~`x^IrAVi=X-7 zv=WU!qeSWO`3rpf|L%k`D}Cks&(ArkL<#W0_xPVb-T!O8Q;7=UdB3w@`7)U*qIwAv!i;C8LYV^|RZ{>>)$^xl zxT6MQ)Wm{<-oaz|E^*{e#}Kb2LP|EI$e0@?W{#B5^3QuFG|0r7UJxWSF>}62*%sVI z5yX*TV}w9VJz_}jB;)!V^G%5U$cdU&$G6oJM*z^ z8Ah6G4ya4_zBaO1N#k6$DiG0HcFmE*Tl-L4P*$yJ`ufWz9TUSQ@N6OIq5Tp#*A)F^Dl9Q;_>k0Kg%9^+^P85X@VOp}X*Z>sG)(;Z7N-J{NR9|J^9MfLJDN%SErQ0^ zH>&>B_x!U-{D9!?T@Un*W^P&R?cMMYehXZWzufl%QJpOIvGH1ZsFcH0)D0`3FKy1G z><@bGQcRD#dy>?3Hzju!5sORGGnMC7PKsuZ7^JRcVw$uKr}m!xQ_S;*AI`-$#Ltwr zN#OY=CjsAYIoC|NrB7XZOJ6*K8pyx95V8woSqguszlizNr9dhCfquDbyVS<8C7(iW z3SZGrFnT71ul5kk3i!R;FJ+d(?=z6Df#0(*S|m^;1>``zemn5fqcBzkdLQkB-y}6< z0qJNa7A5kxokY!x9+cArqzos{Js#agCS>zSn#~iED2_^)%n=EZ9AOQCvWq>jOc4A^ zJqe5wehJU1@8{|jaP{0tGU0+9o|9a47&GpyVhiKwB>vAQF4)nucBrvTauvR9 zlFRU|lU#y#!}X(U1#0S=ezk&$Vp93qcV_+|WI)<9$u<2$Z(h^S#u6QHuJ)SER1`^F zvxVEQ*`^Y$+vFsN=u_VdML+kbO4hyA-1FeG)U|>c@FpSh>%&i85|);&W99+x<};-N zYER;e`Ya76x=^UpL8u``ho8uOi|ZoL+-7f0$xI@YC)7#&F#&15caY-q5g;MjzHgnS zgq$wWsNM`|D{KnMBHC>UxbMIf4O@iCFV&yz9bD?6c` z&?eE0;}n{3j-b1oxX&5T2BL{nHDDK}&K#h`ICyLClZd7*I9)nu6yYP8V_MoyZbXucYovu>qT(xoKngay8om)2E5N+6`9 z_)@-I*9Iv;kdoj_iOrANDCr7@6xv@;{z^y*fs~2s<)B`Z2jLjf_=V z?_9`D9h3X*$hf8TCP41=F}bng7{;>ddb`7?YPZ((B^e$vu%)=)#LECCp^1)BhvnZL-FudvIIuQWcQ+VS94Q& zg%D@H!e)1dFUjtVxC1_qEvG-|k!vBve7Z-jNoI>pY?O8_M`$G+NrN`L7Sn;qle+E= z_&ASnt<;>zM0|Q7xe+Dmd8!c4Kze>!VQii=Z#+*(KkZRah)*cI9JyD}>3BQEhf*1x zNY!Ew=pq8(`9wnfPUbe~xq5912NZ!ZHCg8a-O~n;9gHl4aL%k1Lsw@{Rm~P@6{H(W)Frb>Zjf~%Dqgrg^ z8L^GOKpVqPTN=@j(~5S$zL1rqjDLe2YTW0dj+0*%;Be3rQyZ1K(DeUkzQ56 zl~auYUBmM*y_P}w2m4F=hTXdca6a!Sb&jpe26ZhORo9VGb-nx_>UzXi*Yl(58g~D2 zfIfMnPtCnQ)!i6HXUFJK^!5smV)}r06#v;Vn)V?Ba~m)vvD6CBUXJALUw7bfSjfcY zebTXz`KaS1V-;}OM?KVZHSpP#j4&^*WJ{Q$`d|i2FKCa7L*^F@IcJHP32kaCsg-k- zb`|jVbeM6ynzcHw1NdNkLPMsEQv)C9`Il`?zzLfjYY^2toPRkof+-i0O~BE#p;I;; z&6>{G^MLm|w*=Gr8nh(4M}Fv)vqkW}R^$`emoLw-=%sGNs~^>m9hS$&S|%**mn3 z6uI+X)_vBM);QzMGAxBmCt{dRV)~Sf>AZz`(TOb}1eO~Kb5}v{Q^(Zi`(r2$G>)8N zL28@BJmSPiwnXHyJ3#v==*>F@bT4~yRJvYFe?UxsUrhJP-A!Wpa-3d!AB@v>G0%(T zcZqq%V}9Kb-aVoiN@qkAXC?ne>t(t11VJ{*JJ4*_rA0=!Le+5E6>1i9rO0ayM( zQx9Aj>qG8Jn-{q++c00sy9mX{z?+0?#SFFaZ3FOSnO_##ZD=;e*tC0JkB}`zTNDa!h>N5F+BJo`2Ss-QbmEFH$AITOW5gb4Md+tF_8{zctB- zWKgG0-%058og^KZLGu>FAH>^5_`fdI6$ zoN8>MK;u$zR4Ix(Vz_MTZOg#;8==mT@}W}X%2ererW^z%GxCtu#qF@(OdK~vog=iD z+Kx`DHXOBo)uw1CG_7qk)LLyg-&SW(wg!W}J?yp)y*9}ZLoucHpBx0#P&I{|zsGRJ zw4iyLwI~n8k{%+NaE%X(&H2PPS75&k+SAwc5nE)wx$%HO(@ac(5g=<=&b+e-kwCQ-nX3#f{K7*2%tB0Wa}qP%;=J>n zLk&6-o@bge{h03-=NUa8Q#fX((RpVY@Dz&D{7uy zStd)wgU4WwasFbCd1uTV6IO`lB0WzOj?6K-PMBjTwZ2PNI4J;WKXx24A2A$gqnQNe zanNpt-9LlmU=0t|tZ5*$(M(y}A)xv0vtclcBm%`RiTUFS)#j_Fl`)8qC?pmTaq1im zle=~^aArD#wY#O@fhg!@M|ix_@G_P^AI822Joj7L-5lYDc2@>^S-KBh39+_xahCZ5 z@OUxIikP++qM9-#Fe{#H!gJz+F>_+8^+j<`M0if5^_}tzYzIbUsCi4q5??*~jh*3Rl#Xa>&$62wbSUPU#q0jUWx!Z@m(t+DOE%p@8pF{39#M*wu(pdKPs8&7^ z)7wX+uoC9NKCCJE+UXWGrC+!6#;A7EdcUi~H1W3dq*&wIVoU$*_yg15fqa_Du>0Qw zgr?y7n{|iGMTWHN4Rz?iZjfLvHHX~yi%(XIa}}P$@QC5QZxGY}I?~5?V6M7^`zX#; z1=ri^i09*(hZxlEg3%*xozJlFETR6+KIC38OeFOLO6 z>3zH|w?o4`+F?2VVF~zw<{Y&LH%UNRDKpacbL06?8E9!N(5);a)*=lo{;U8xU zMI>kkB-m%I1|&cpA~rVXbFc|5r?3sg394EdgL|8RrCK3j7cy7#Ue62xe!>Wfw2wM4 zisJcw$lU_E(^3bX-Pf5TtVIo1wT?}4ZkATc1<46M4Fz2Y)dX|HGp?23w?i}291>D+JppzFD4Je9vZMW``rp`aeQU3)Dam^9WZu+L%SSY>0>l zpM+J>KBS3gO%hb9V204;FWzZb%VCc_=^~WX0#UncReGl~7R_`y(ldYNYMJ2~%}%5y zXm6|k1Mi35?j1~DY9@CRd(9?sWdMcqbDnYHH^Y|okb5({*_9DX;CVywC`(`~aQ|c@ zwsi5lFywxC2xd8~mH1}1$DAh(#f~ax7pv?dlpjHhH?cWQ>e3^?IR(dnis10f&%wPY z=v{U!wEd8kSP;=UKB7w;$wPpit6(JaoX<93A53bocP5Xp-Y=6}7}7l7iq!D-IwEb@ zUdt?VF0-~0`p&zlK;!8ihDh%`9kIvymHoz@W6WLH#?g7p#@y{0bLSXy7q)54bK>3J zP5u@mj1)giWn{kMIPAp!__-cJ^8)Z)TCd^QP3$4_K9Fnj7`b5ElxhPHy!V_y)*i|O zudY(*A?ITX<- zXCHgz;8v*5BFcf?8Jh4ohh{U5HX_%W4&xGm$AvV&xEzF$xN&!R%v~H%`$k^wn7e~x z?k5XIJgOOf`42>ILt{6=G5ZPHeHmbUHc2Hm<7fq^R=Sw^T;tjM*5{A zt#|b?kdMG+ARiJ}mM9(9Y_|eRcxU-*W{_pDT2{zzz0h6qoKJdFis7pMbY?;CZO7Es zO9F3G^LmO{K)Eu4DA%qaA`W`7Nz%SF)96Ue+Lt+>ixh~o_DH?;$||g{qQovP2>c^h z-v>M%!1_MPyxTPtn$$W+h(W~OA$RrwQN7JD&G9+&4M)5`lQZhrL8o7? zUKo+9P>`$Z9ct@Jne0Mh1JtRDXlMn5xY~iGsg?P*19NX%AED_4?tL2G-pjjR*Zm&v z{snj!^DX9I%)3vUOF^63$j)WoVWmgpr(Y1Jny#98xxQ<1q4Ws#S)+hj$_26=#bLX= ze_aN1IcKhEqv=&a(ekvQYzJ=MAt3k>7LMt-9jjhz1qEilVfuy1?(0= zXvAOn&75G!IcxjMPCEth@uroDC5>RN{CFF#~}3{0ktcc z_qym%y!L^u;UYutx&BD1iwM~o`(BqkG|ckHR>f<(j4|*;Rg5A*j@#}c$)%hkk?NvC z5MN;n?xKTojp0J%=O4tp*QE%R3q*@v%$E>|FSaQTtBfikGKfeKpGPTTo)qPC@MK7Z zaf%T6Bjjn|x%O#do{Y#Hn+NTp_6cI194#B0CqAcuyi^ArN2JcbN6{R?Actoy*!$qC zz8N&Ndth~C*!>wuZMH)JR^QbA65&MGL!pRYCyr2bNsaYHmoyZQ%KXBU>t?lSN)nh1 znB!Hy%qd-fQPJT4Gp;^VEya)A8amjVx9(k$rXl+XP+OjNXD*{nfM`7KM_G9xFRMF~0F5pjN=5P>zV z2iuO|`T4Ad8FGI(OlaiHeQk!AEO`1ga|u{IPZnyJZ`on@y?t^9X_jz=hT$?|7H~9+ zVu##{0SZ!Ya?os)=>OK~P5W<9dB)E zBWNG!*e)kY4|YHdhR6j(6_$geq8-r#dNJ7kw?u(I;tL|Pa~YvDejsWTAB0y~&)RR? zwT-!p+BiCI<(RvwF?Vfa?xHr0c}~2m+2n80J99PLiSl^%yr8oElvfX)KFk~UiQKfs z@vu3RJ}<=N(?tp-B2r+rAxV4BtVkTElFtMuV$|CKXcfriXM#&yEHf)II8iE~T1c<$aX>BW z$_*rk>j-Sh;`M>s1yrwQiMVLMmtl7l@P0w>opnT7vmMQ@b?of`xd3mqU(&KgFTqX6 zZb(|?C`sEhM$-H~lOgv_KFtz)tG4-M4f{EU+{5D71s(ek{2WifJe2+8nY&709)ecE zx8iSgoY-n#-Hle8d$a36!hOD#MIBhey`CR-#Pc)c7628o=VxxmX!-t7Z1Zg0&$+WZ z$a%HExw|r*pw%6-9?3&95=B8?XGV8l{*=B2I!o8LwVqfVZl`k>G zj3M_lL1-w@1hmF!CUMnEi1vMkiCj476G+?VNEFD>D1ivw7&BG#Sleuk3Z4$(8m`$2 zq+BRNfF#0*YA!i&1Q4u+J&R@#u|YRdrk5K>} z8yGiTm{@k$oXo$`59J8^6rvr=9F$L^wS7?D&0*`8;Fj=|QprI2N2K*RFcwEL zXP9hW5s06uZ=^Nx+$>Ej*P1!~YcIGOv&6|ZN^bhCBu0WX04%)Ia@8OyJUZmw3u})W;CM~{5%X7@YMWMqUb*7f8uP_XXJz+Xc;Kn%r&_mGZH1MBxb#k> z&gdjFj+la-xU2*uB;!~FFM+zHz7fFvUBdZ$)C4pN3x-M&x(v2R#6L~6qGC$=bS$&@|!_!JfF;jACbMTXFd@k=}$nr9d>67wF=`*cy@omhGrqY$~K;l30=hX zY>ME+Lhs<@bXfa4px5cU|FSKR#%)3kui-LKhYHt0a1za}Trl)kloY%g!Q)7qQn3dw z44sx!7bu7v38KFRu0x>|mo6tRC?PT8bAnZMSxe)8L z`)$GWX=l%-Hrc!j658L=U*yUQ3i<=59(e4Y{)N0k?tPOc$6Wb>^Q{6}>dJd{?UkJA zxt6CIwx&GQ1H6WS*C>(K)H(Kou7cEpaEYOl$X#0yo#84$ux>@fT{gv=4%uo=wK@Kl zUYC;>z5?#ucudMGsITm}ZoF3Q%3H|O^3Rr$Rv_oV&F?kDXV zx;LaevF?fOf~4#-?(dlwgrs_kJ7TWRY=KA*l3wVn5@y@0gjsRYEJJ6YHWXHQYrxMr zrI1vcoS2vHeSLVin5hzOrK^Mm;O!^Xjn_~?LGS&?s)U7*#^~;bG)Z}gqe{3B?*E_) zmsAP&=%AlDRl>b=Ao%?tmT_;DpjS!uWlbTppMr%|Dp0Dl>vN%w+hBZ29oD3hkKI2d z8Z51ukZM3xLOM_p#Zh}-6BKl~yr4H0(v6UwK`)1N+}?6%@9uis-ckg;UsEM4qq8~@ zf|ZT9Dj}`DO1K>@?F^)evNZ4tNcMqT*ApJpMeURB33RE#r27ct9`Mlh)-8{=dwP0s zFMg`iU%v)3ufF@`!ff#hb#DdzhYZXy64jpy8WmMVrsf(y6(V(?f*hiRwBGY|(yEhP zfMt+64eX$Y3c(U3DTrpIT+1mKoj^%7)jb?xcilaExc5{YXa^}seX@%R{ZvrVp9(=b z#D8Zyu^6e9CBX6ZM9N;f()OAlgS;f5k3`3S|85yz%OY`p{YxF@0Pt3(!g$uYOy@Gw zL1Rg6!cvj!@N(=0tPcd`z|5QlUfeIh;u~~l4t@i_>`DLZyf^deh)&SnMm^{CEmn&f z_;PqM7G{2|;|;nsgI*1s+K)YWvA$XQe#jqmcMs4_pcT}A;QS*~-9gZkJE{a0M#e01 z!XrLT__LQ2)CG&xd_l%e!=C|JilNkYvD7wSsUlyg4NGvTazk40`*l@9cQPKCShx~m ztAxI=D&cyvC~v@F?pTq-l5&AZ34}En@4LPVR=ol=(^r8{W&=0OO2NE4$^J+18Vnr$ zy&hf?RyE+(|CpK9TLf+X=U(DcjjlinBHGlSU8R_hul_aWzN=M2j;cy9(WQbEzg1kW zaT)WeFb>|8K$u?l!`eUgCqTc#vEMZAsWg|{h&&ibQwtkKu%)dxyTfKXV9bR zogt4^36r5rRQMg8BzadS1@q`?s&%^(Muh~J~Gt=oJ}KYUyhIOH7fiL zD}asGvRvDa)7Vq_10- zo`dHqSP^2Y!7EV8Y_I=2ApT1wiU!I$sVRV#idxg@lAQ*@p|_&FgYE{8iYG!*HNjEz z&(1>|qhtso+WrO6!g62fL#&e>j(*25w|OFy-FUi3L161Dmpd;+)`Ps*-oJ)6ya($} zw==Do3Xq%6M7c3IUSi|f_o1{dIl;JyNnv#S#=%4EMFG*N#uQ`oq(i0#BlM2G0C53! zCrB4Xlt+P-VEuT|T?v-$T8Ce<$}-Pm$r3&H|7asCsOKJGi2c}ezt2eAZt%(0b^D-u zvj@j6kq4;#SbE>}>D*q)%7i)>Lcg$d;hx2_^-i$L=98Uw$AyE>T*sNrN6erX2a*eF zGWBO)2fdi|1g0YGd~U0faw!6%xG0_qo#0ToWK_AKr1=vUDZ_gA{Y($EJ>JvO6w3x~ zR5yH<_nC`AI}C}f8^~hkOY9k-6>jkn=jJBbOlZQ}GGj=vJxw_u0nG_|HD5p-TI(I1 z95Y@Qz}Bk#+@X!+m^^H~J|g_f8Q{{>x?~)QrQ^RG_#AA*8?hsZt%9+i2xGq!V451nGKy5sWxu9i)3pkMrdPINkB1bK7K?{`D=~5VtaV2oUh5-?9fcp27S;5_`i&_~BX6H&Hm^=_t$ma)cv3{aub&*YD>D?Eihs#}U~7 zJLtX@YP}Eo2pj=(zXHXxuRFmbV1?C-&bwp7fG2_+Nc#r|ZT4zF1n5Ekuo+@*702$U zyhG*#hUMHNz%|&uAs19<+W2PM5o=wZ(nCFh^|lkX2Rr|e$QYx!Nx(T1fpe5(wa7V? z68mIQ7|_dl2HjI3^1P&pW>4o;O?oC1b?>!hcP^R!7iTSdh23WeI{Qiv?w_4m^ecYB z)W`NEDO%Z?j-PVBcWRg%^N{;zu$5kR9AYs=Cppoq*ToXAa{ieNuc%}H!=Ss}=Xc;n zB(A~`iRmk@=S8#;&m}PrgBNXdgi8WEjU!wJ-S7L>)`|V`tQFc$2QF<8=$vLeisGD! zW!l@)5noF+BQ2F>{&q|I#8?^wtk&FUY1gQhYS~h!P8aA(kM+vI5|5glymmFv$1gKG zI!L;>1IKC#85ApF3QGbTqOIY8gRqWObg|?aL!V=Xbb&CEi?4{d$63t%jh|hCv%78MibyryJlZQ$tDc3xCrS!;?S2nwzRGW`%P(L$C z>DsXR8SN9R;cCqjgYKPupjXC{K~zZMhQm+%@Wh%8FKtw_u{=!>aWAa}{{ssxWemC_ zP6E9~tbf3hKFx@3QDJDox_x%5$2lZd+G3ee6l6jiLZH}eMPGK}n-Wx@e z6aRrG>wGjhJccG|B28*XXhK1}M=;~(5hd`5vKutyBk z*>JG970r_YZx6DEOfws4c87HX8Qn zK;{FO3sAzN+)IG+-?EX-hjR89WM>a;ylldpbqH|QateQ9%_!kEE+^-T^SEId#ETr< zcyv;^Jm5T@A&Sg94cgXRzJNTq7RRLwy4^zrcqwn?mc*pMZj+nE_>w(_l(PrfIzx&v zC+DE)U*{5yA3~(mK@-xx%S~r@PN_GObBhe)&emHS@{os$*xW$5?p4=;y_7OYFm3Sr z`4FKY7>YB*$T>Ra#3=c)oVqc0Val9v&S4I+U%+f+IrT03Jl>PAFvxoJn&c_ntpQ2F zjEo^$v#j&Ab2v2ZL$JE1S#B|**_qq|E7IP?S*-)^yy4UG+2@JZB}Wn%drnV|4v^%% zq57tL^O^?ipGdy2YQ#Sw8Szgvno?OE^Hm9oZL|%#!lyHVyG(}-}AD%R{R0`=}l?Bl% zJ~VW0;oFdAEUOeUT2|qnz}<4VySp~KGhlJ0u(V}yr!ucnSXQ>AGbjjb-h@gat+rCQ z9ZD+`t2oj_bt_$}nCFb2XYOtN+!YYe|@pGv`R{dmiy_1<)>Qs|CFiD|u4;Yx_D1ltGKdp#NS>)cAg zT^Iq@wL)WnamTjWfIA61A18sHv*Tc-eHKp^SUkgZzt=B+dxKEw_j}doQi|5j*$#^N zvSW8leuv*j;MeUd!TPBL>u2*?Yy%jKvCO6%FIWBxR>2B-bKp&8hhsjxWt81>AEc%L zJyPLWzui+Q+C8&IY#Jk!nE>xK5uWzjJ(U8sd!~<+Nr5s`$V#w#Dj^!bQkZ1Gc26bP zJ(Z%}6Y^Mkr{tkZuzM=O?zs!>9yQo1UaP0yv>+$UxfmfQ<`=B@csXW%F7EdOK${0p zrSM=2g8EiLL{reCmBOD8ww-VdrD#(w*g655g2Xn6E(9EFw&wvoY9MW8M;8@}Tck>`ljfB*%!4{!& z+MLsKx*#4R0a87lvm%a30LOwv9FsDkfMXeeV{w3E%^1f_R0W!K6PIe8)M$a0<%6f? zQ_cq+L9Zt;)Zu`=%JLzIE0-|VCPmGpM(Xf9XmdNX84NX!Ak;K{_kD#o(lAC@EUAD| zpA2A(3g)P3H*$lf{os_1x|fM)Wf9Tp?7*+kYT8+61)x>Me?+SaK&y%|XjK7dRWX8A z6@XS1B3f1W(5hkttttSmdPKD92DGXGv}zcIRuzC&6{FBf2WV9RXjL(SRuzC&6+X18 z@S#=3D72~ow5s?&K&!M7w3;*utr~JZ0<`+*7ihH(&`S2dM5~mX9zd&SZJ8ok?HEC; zZd*@o>RP#zm^Kxt%mSS-T2=Vas$vvcwU3}x1>i!3h*lLow5s?Gw5k|Es|rA?3K6X; zd}viM3au^K;J z%klE%4(MG$ujv@{FC25?XuP@?Qd58;sqm~HuPT0lR~b-d0=(Hoc-oIw;L#m}SIJOj z3RwYoRRMTa;lry6z^jT;cvS&-Rq-pl>Nch3r~t2qJN$U%<(U)_ul`h50eDp*;#GwY zuPVmi)jAQc+C{uNGX}3jpA6tfln+0==n)3!@s@}lvWk$#RBL$y#*QEQKb8ldXCUU} zyiG|<+Wp$g;%&k3Joe<@K!%h3XXG-lTl_ge^p8%&OAz9RNpY2I6e@fS`ZTO76+%?* z46MbxYl{Fa2KIt8zm)wR;Gl&t4%ib-#0JCNFJwO#WM746N&R{Sx4Z?UAFSP=J3#sY z{}qpd^xN(b{mu#vNI&FbzjIL1D_nqw=nHa1s1_OZnJ>1sxD<*Lp6+f0S`6qaRs-lN zH*W)71+Gwc#5T}X6lBU=I7&i`5^nlg|PBWk$|tH>uwTe z8U@)s9Nyqs4w{O^r>UF(O~otwrG;63*|&K$6|d}5uSbHuDmxssHyDuq5z(itITl!h z*GTGZ7dLV8fD7`GQ6fgJ%3(bs@~O71HCy$dm0?d|MrT0ASs76teSy##+Ctxu9S!{= z^bG!JS)w}hFd3^hg@MkExB}}oL66UIK)L4~4(L4`& zHRy)*C&;~2C)=+)0PhHEVpkPc^NvI0iF)IqCN%3dM_^5n0H;IjFBT-VP>1eC!^Soo zg#jy84sxWwqhs*~+#kVv?i&?pd2u8XPuhB3TA0rwkyVCrPl2I#9wNc+z{^Y$vOxBuwx^eb**RvceoI2Vn*^WT7X{^C_~&Vj3A@qRw& zr+&QutJs@IaBoDszj>5?`bS9pZ+O2L%KSIHzXi&S;QhK^gS{rrp@+9^i+ zi5<(4tmBsmQP7(YbQp#8u)8M+FbV6X6oqkYFUrSQulW8dMvO16V%-$`;Ya)6k6xSj zlni)hw=f5Gr|NDCm`S$ggU$%3AO9|(e!L~Pa%$rOYfXdI>T&-Bc5le}g@F41v?=2O z^=E?38n5q8E!KdRI8ns??|oLQ$K5>qpFNsoeF5~vr}8ZPA$XO4|XchHvnvaWo2IM7wuHY_hY}(L-b?p zUus+=Vn4Q1N3eh662SgbMc7VV0@z<&B-*JddgB@6J2@wE!AcdeUkTWct<=qc{j0bA z0{a7gjr}*Q)E^6%{-%{W;fV6}WG47<#NKh`gKid1JyA3%;?+*cOuWJxybr|=xV1wz z@XO%X5CYcopR?8J$K{WA+3c&$Uv2f;q(zk_!NN3W}mP$HIwou4|> zfcvm0i*0o{S8c@m%pzgchv}rIk88d;0Pp@ov(kD$ts~(3BZw!%z4)LmUEFCo;J#Bt z<#+1vPD@hUY5C{1hs^cNVb~F}7(Cb>aX&#p?`tD_Eh-Gh@oXTj*T`CrLHq^Q6TS0+ zcYh$>rG`Di9{0f^9P>7Ie_(}E9{;GbzH2y5&+jQD;vezt8*PoYi~B}D^G1{NPlMi2 zLf+Up+6FsE%NHSn zeTukG{Kif`+_K8o^4~|iPM-jp`n^swVD3?M5b@t%#p8ijHazZsh;vr^QM||FQL%lz z2Ig^}7Sqq;^m=E7R(@tN)AF<&A@0o8f=wb@}`#cwNL5=MUlP_q{II)9-Pw zg}zk&hS%j~c>X_ogS>r8>wO+d{YS4$+~!fUm=$KR^;duCVM*|LSUm2TB26gpRCqls zYevmr0<`km9+rp1Qg~Iqlihh^1Bne$L)jE80UuRSc%hevx@v|~IhjaQeWgI9wO zT+5r>kSa#tUborJhr39MoL>%ct?$A~A>bX5BXN~vE;EZy8phFZ_-e**c4uV9MZ0|O zWjnF=OpiQ{#NUQ#A(H1F>@Vq+KKDtFe46aJNlN*CMfncFs8{UI=4S=%5Hj_|ewBKM z!05^SJHT(SLs+Pnz?H6Lhp<>Lg{wvM4q=I2wx8O&L&(zqQ$X!jwu$X$KN6Oa758nTgU~0EK((p+4BRhm;EpgV+8VcgwN^H?V4tuLTTnXn%Kx=tu zhp-0PdPucHc$hu}UgNtt3U)T*vlIfmh`>OXGyvH_>&w$9>xXUTOTy`3WQ$m9=8nUm0@?^$=p25 zSL=_VxG*MyQ8DYCFt)H_WD$2idE5h{js54NJ?4}=op`oL=vlXTwn$)mkMC>|ix?+5 z4E??8!DovEAL!^HZ-%qcPLjWvFAI8qJTk^hCu%}oFP&c#+ALbVIo|=@1DNl`b5XLf zuWafsd}Y|$rA2F3Ib!X4-0M82ebz4MJ)^AMXTjQ?I>y@dxQ!mawd>9K&(^NTy%gvG zXMv2;d7dg%gS~rBv`cKivU$6}4*fr{c_G-)tM`D-TYGNA=KWH%c|ZG=&HDkidCR;u zFV=f}Hm|7ncx~PQZ1axjJ)>>jzj34Wo)^I8_3J&AqJJLiJvMCfih9qVu+1Cb9mg9s z?>5e__h6fM@$cw8kB#!qdu`scg(ZHQ*XN!0+Pumd;*BZb-&7tRSFU;v+oaxowYsR9Z-j9A1wo}hEdOBTEhu4zm3m3PpdMfIvarVV3Qb zuxP~IP6v7nxW5&(tpjz+{ULsPJHT&m?*x1ME=MS~x6711dwZ5{AB^IFjYxgLe(y<= zwsnlfps@b$M=@pbty*7fu|F>6H=%y%N?@{?HKu*0clf zos=sa!C*~?RGBp4&y?fCjj#W=7no@2E9_4kQriWDMVWq(Xu|wNI8+r9=w3SK> z<0e#x1qCbNG^J?-T_ohe=OI;*@bJ=;=YHm`E9SO z$Nibei<5x@zxKL@L+Wo^;j>5d69i>`+X|mCQsyV1+=vx^`PWvsca_L*g^yh&!glx< zpu@a-^_Qqs&^zOQXNLzIz;<{*(beCIg?k!yp-T2(JSnl|0Fq_%s-Ty;!UL8t`xt5Y zL(FC73PY8XWwLf6Ri!1m#t~%KI5LV;C4FNr+oFS2qHc~nuuKTqax?p$;Xc?G1g_03 zM5;b>TJ!6Sjk)p6Rfsy1)KtT6ukE&n?W&nH_nrL+n%3{`gA`IY>E3-5HPLZ^a-rwU!p zfu_^@Dx7X9QGnf}SP60S@ysRR&04xa%7Y(Jy+lyx7C>u76pE`}-|YO}?r#Mmb$Y*b za$BS?o-mZ2JHklIb~rBy)-p_wC9n$~(}92;9=9-(b|P7ofT>UkR4Ct~r|ZU;lLKW9c;lQ_<&zLed3+iEAetyxI}WTb^|#hpqGnB6nyDg8dnnw-703?LQ}8UjJj;y+Zh{k<27`@8bSUA$(V{5N`9AcRIjNUPvVV z2q&uHwuIv$cK{b$t9=5^Alt{?^oAjfJG2S*o51e+M#FW-J%Ykl*8}}VL9yl4b-2vG z9Ri%wc$3&qa977cd=^8|NwHGCO^|lYmdhAvmm~mbZil^E>sgZjQJ|N!Z=1)e*r{1B z<-84Z*`AU!LL90tiDdsK#I%1~dGrqB>&Y(a6W zpP-*ms9()JX3kmPo*%dV^7=#T59KGrS)?Zx24+c^=$&vzZc22Kln>~q8NFSMkI5RQ zt9KD8)y3C=wzaUwVIO?Hufy~eGGt5;qhOPni44J?1Fh(Bhnl5$o@`IdgK=fy6jlQE zR^|;!r>y)cyK}qZlAze5a7jtbvE^G-DU%urts3@4|A9LU+*=Y5(4`1iDM&&$vnkAJ zc%LSi-4WepTQ1C=s+d+~+Eb!iQdQWRzdwH-(`eQ)<1PCZdizPJ%Pp~Re%!G855su3 z4zxmHPOaHOXt~xO9Sb%S+6542qG^xbOeDrTCc!DheU7<|l>e;nRtA?|DX5VGMto;q zrg5EV&U9fA!FD*wK=L3PN0mF@B_mVW^Thg zsPh`k73bmYrTjyEk`W5N2GMJ;IyErnn0`JU%`SoSxMYkfRu5E^@*(h~o*%Hy1*#H! z0?We^N_d`X2XD|Nx6514V>spCkn)VK z#9PnfIOQ6o9MBa(ilogUl&Nr97o^#BTYYJN6Vtwfw2yQfeQ77ew020ls9Wz#`&>+G zgS4M?kNeWv#k8}KMkeP$8U=0iLfRj==Y_uLrP+DjxQw!QdUCB?a6=g zrRX5#K28UxO&J(*k5KloyZF8P7Pmr-zkg3sTi?fk3+jYUyr4qTda2x*PUYm>GvtpEX3^UrMChU)b&p ziVcF32g5AcoyGEr+^t5bt5~X-b1%pT?txcAUMqRe83N@xox$+!bcVwBcg_L&edoL= zJo2Ayfw2#`0;dB>lCgAr0$ztU2L-3%lDZ4dX<4M^;%>Y<`Qr9TpvQZ;MUlMB*Tyc` zXBEV}>x6x9Op}v@@3)*3d^b8J@Llhe!uL^UjX>#cv{315VW-%F3`*>GD&V`yDTnV0 zX8?ScJC*QV<_v`I-GD1tCa^r*z!pAxVd>NLs@ZrK)Wo(-_K5Yk5MpbS2g2G_CU-dI znZ>fWnS9nzWYg-+8L&TRb^Zz1y{6$#TzmiVV6G@DYWKyRaGFs{)b@)-G$Y|_hY{_a z5i5i_x*A#U1?}vlHtjQwu=|g6XrGd4b=-z5ni>6^gx@}V1+~J2nS5k(wW=>Kq?TQR6 zH^`guT7Uuezaa$~C*3E583JkUpBwKW&U8qt2%aa};Z)NwMtYbiA9lY1 z2tw4%{R+WJDVKzSmh4VjNRTT8BLYe8CHIkW+bn-IeI+2Y3ij-OVmc{EkYXEI^_iu+ z;SM20w~U3nb_M;uK(<3(`%8kX9s66}7ZmMy7WypzB_XK2B)`!d27S>n`xX+_DxmlG zLoSiF;T+z96yVS?($`4-<>9$b(2U@n$haD36YQ5EQeT7bnNA#IoYtFo49?Z$Hw=Ei z4I=qUgcxPL{f+ngvS#kvO7O+Q5a8=l7 zhQ0uA`FYBZw-4RHux|otZLcR%{|3LeSW6i>ST4=z<1PdzZc3r|SwrZgwv^INZd=1n zg7JNjQ)pMih?yD|GthGFQo!av3c7|jh4nfOgX>wZyQ^Kv^RRQTJ+z0@mddsFwQ8WI zhlbu1^58B12H)NYd=2nXJn&HzSe^Ge((LJ3P@`%Ro5yy6wt9C-_Vw#)cN%sz2c#p z_Q1}XvJ9Bp6Bi?X;*f?BThEs8liqt%u+VQp1PPIX`(>g32G>8q+=Tdyfy1zSb9!vE zUBZ6~a(tLev(JM%B>V@1C2-z4%yEPGoxN{d0nbSI9!O!u6jrwzqB9fVbD!3XPYD6Y63M?w+w zv{(thbU+4m={X}ysV@i;o7(bc%NiEN$FF^O?aOPguH}Far?M;9D)yWZ)bgdEuzV>5 zp)cVqpf6!J-U@S-d8+wK*vIyz5D7W7YHcaayllB@fp{BFaF)r|D40}|*NNmq@Y^Z` zsR*?}kW2<$s2n|?zznMqe{x6%z1=z}!8&!Jx4*yc=YYrG&%po3{ao-FAKVbD1?MINTVwjnDa~pW zw$Vh&A^7(80yTeK>(x0eL2{Z}ELkMUk}gr0qD^pqdh?@@){YQ?^Wc|+)A8?wzZ}7S z))2KMj3wG9v4uUBHgWD0cg@Dti$+)QX_vc?(qi&#?(8WaDzJ*A=!anzu zjF#|U!s+qKtVA}7Me0J+>B5YBDxX?!G?6Bai2{wb-8n3lg?+!!CT>3z{+2@wD`jqK zAf~UzvD@4<7A5sLET>j)CbcrKZ>~G8loAVS>=JEP+jL$nAf7@QF;@y7$^QZPAJ?OL zQ=T=6O@+R0gTC%(mC)zwjz|XY6~^z0%K*=1 zcS0R-zDFwbpMbhDpzk|qrJ6{21%6?NvW}Qewg_e+E6w| z&ZR9%TdeO^#-(M&^3#WgoVPCtXUh!_aJOZ}0Egvqx88MYcE6g0(L+f~x##-kzX0 zR4ITNt4viOX{n~x!WH?E`H|}^iPeF>KrRXt1@7b3f?L(E&$%@N9A7&7LB8<) zVX!qh_$WaBv7CMFqZOvvO^`PCcqq`}d_%~cn1A1FxKeuml)VsFByg7t@fkdrQ@b6< zg}pkkL{lfkz6@8x?hS*OTHib7p2Bp;b%9)EZ?8w?5Z$CJW%gp^*K83_$vMNEW-{4@ zrEq?C$WcL2e>)=sd-YLHYu!3!w-BHs<`A>Y-=sn`FN%ZHf3nC0gf`CD_ceKYzG7v} zE3OQg)RitJW=Wd0*4^MgIR&3+W4WDjg&Vxz@4;9}xCpYw4j#F<=#0Jg=ZsVPclA)N zm^(bM+a2N;)Stll1vU21d*n&5awb5eNDyL?#x9IrO#Tekdd;d3M5PV|{;FR7Lprweka?8T`AmNX92EpG7 z@uxuaoW*~Q;u@W*H&uZ9YZ}UhIkZFGcVQJvu+?miKFrWFg8m99F-a_OR^EGF24_b! z3ipX~i@LLJ9@JSq&k_s2yK`ek1GwNrURNCe6H%BP` z4rbZ1W$Ezo{ksWGV?TFp-V~;t3~Pz4aONZ8^ZGSScwWH$Zr7d#8%Dx!fwu>$0nP5x zJ>t|ssXd~0ng+4Q3)zpICyXb+Drvk{lKquq6-bhfSqav~6N57r$1g!@=z~se3N%HS z7Ku4BKD@6>yqdBE&S4&KiP!LVqxw3WQA<`bDz+S2nBKp%3EMl~en_|{;V(du*ss=) zdz1=2S}|%oR*2*A5!58%;~{V9sJx|Oo>I)4D9FUQ2kYEe_b!7E=A#n$_2OX-{LO=B zz#e)*m|OOOaH~%BBA#={#S-Nd|IRQ`gX4}Kay-gr#ufuIu3neI;?r`c_HXkP3q)D0 zCD0X~1-pb27IzXvjWI4qQ@YcL_@{?132%UfVzLzrGWf`CO<;YNL(ZllxPm>Gh$K>L z;Y0j!t#Sjv(?QF&sQ*Pmetao-d!YUco-xsOE8?>e6232bUL=J5> z&jou_@58mt>^IH~R#G>~%m|X(u7K?_56U3^4}<;^67an=f-GR&a}|9VkN(^y@Er#=>Y&wg>n4F`BXwLwboS;ifjA$=-(gttOhMn__ z#b#gIy>@O1r1C!u&M#585J9BW+veMFTo%azXVA(fRn7funVo>Rtnl;_J934k6Y%*o zquaE$aAuZjAEwZ@-F_OWfkw%#s(rC=N^u6*$$koWV$?iE9k9#5Kfl+W3~?J2|KSkD z&?il7Sk-)pc}?O!9DLh=YNnriQh{de;E>wHZbVa=5AG*ZcN!)d`yE>_m5)v`X9AVq zht(%lRU%ONZv*}|0(?})K2=O-@2q2jv(M%lyC)^_fkO@_rn!G!&c0)N{WP|WDFj}u z!L+vk?deAw05_KY01@h|vF>JinSDS%%MdK;-Cd51#X&H`ujQbO>NELYE?|9VCASDh z2fxv(A)*>vYGw!MiAyu-?ZCZx>!21@7Mw)_W8`@pcsDF-0jaT28Rf==oF-TcsR8;Y z49?1?7}i#|_9qyTKo=!L{M5k(B{CzCdf2wWhWQoNf3d7KR@+nX%sYl(U8cOkDOm?c z@oRJg)U7KwgtsmRFXL)6J&I#jvtMIPRu|l*QcN;00(!z<=>osA0q8m4@zYb8H6YFg zBvA9d|Bt;dk89#u`=7~#BrIwa+G0QrL=Xwp2-@P(8bcTnT&T3YZnuq4>wpVXty;a6 z1Zqp9S`}?ktVOWZTQ?H4)vAToF1M}iOEK-h9VOf}y~GgUtWRO|$5c}cQ^sILhMyw%0Uk^C9?Vh+TMg~cAMAl~uha}^=+>f8 zjAgsEgoWs|F^(Yh&-TCvF+)q&u|W+~n{+7gyrmmO-XOoMV{bMN(mvvxof_mIT=rP( zY`SWL=PSv%MriS~qLi*UYbnEDpr*u09q{?6CZ!y%Uht+x^$%$Z7<9IwcO26a#JpNJ zMmD)7PE_H}H%{b~c#EDh6*%3AufE0n(gnh6{! z)&8yFZ_RS1LP;k{wGTAVRg(n`Kj%3G6}mt{J%SX2)PcM&p|(L%!E6qfNh{#120DL? zCNiZF95B6(;^W%sO|(W~s&ehWWgfltgk&>Q(MyIhDUm7Ez@MD*ru{AE!u2O46~=4K zGt|IKPFe%0D&iN?e}z9lpZXA_JJ<!JZ(}UrPYAy&h^>i8b?BM?phcK{P ziyZ#1s31U3kC;qN!`R(zQs%6JX)dO=H|yaCL9!cB1Mo%XM@j`n$Zf=!@kz0pas~?Y zq{X$9Q=z>n)tsM$_*wz1yonxaOpSC%_Gl5^P%(pHr}Xt{;a_uly}iX*WspMCv)g&- zWKoT&$pwgmzyv!fje;FnAVv!7L2#q%t{=PK^*AKYRNdFdj~^!y%=EeN3&LM+k75I0 z`>xc3?hx;d#QHM>au`LRKApsZe4Oxj!H~O9Pq8!D;3lGLb==lic(HJup}a1VRdIG( zU+5!E%PlhS@Ry@hZq8k0Xm)P09>gwho#7V;d4o#0;#6^w*gyQ>OsJj3&EYncOs!qd zQcaJrbGSIRAGnX>?L|i1!K(nnm$y@cTb%vUqu5YRs@`JIa86@bT@qGihF7$zGE^mB zHcNu41*(#+*pwcLuPo$D`{=gi{zB22mC$Fx%qUU#Ba^;EVjm8=vYb*hXJCU|+J6m=?$b-m{xo_@u?9sw<06KVSs=igmQ zZYui~B*Bjfil^1A6Ve?g}4$aTx5qwbqYd}6CHroP~U$n~c-(l09E zpz|1T;qLhONv}^#bbjcPlDp(L)_$gl_qbQ|6a3v%gyVBYb>NflQNz+s00)n`GTjF`FeA|FP!cq^iQ8=HehpMNsoG znE_s?-YKqL@*+oIaoeNCEa)#qH5UhyQT*hA^rn*1kg=evJd)>vPMo6QIBckPb-QfSxeo-Ha&yT#L_j$p^08gGHkoTE zSyvLumKgqu8G(ww?W`)*uwjW+#aV)4@G$OauAFP+mY7;hHHf^a%1xYESxWJv5R0?G zT>IRO=V}++SfB%^;B%XW*<68TmTf-fk9hRBg#W?UHL9{!wF+aRaLz1hWB8%+myY7p?&oV?qmyc1F}VN>9r+fsO)tBu z3ul|o$V*O*hmMtmU*#i`m_m5f`T>6XCwI~lnL{D*Ui(^&Vx1J{M>1;l>JadY7X+9! z-=wm_MpW3>+XL1ImmO#cW76v0Zt2DZyhZTk*p0t4vbBL_)L@GL(0rB(eWb#ELHLU$ zXk)iBDkdye_EylQ&u@eZe_q(;ci!K*Yif>Tmq4wN>Pn;K1x@R+8Wna$-`6OAu$6%pAc>E;SMvn~hH znIR4mol^1!kzGAmJIi_iUY>@rBp$$RM*v12>?>v&$W~HmEl+%!SL5S@7cc+!t`IkBkW_Wq@3Yhp6<5(+$opjEqOV`PZXq^n9b0>VI1ai zJH@jCgr%A^bLoPw7AWwgz3x(uzDoK>UK4=H@5WlqKt*Kb|B>Y7$`DNxk zzxaq9rTUtPvqKgtDE$X!JCW~pU8xU{L(&}xfMx&{x5Q!0qY~yia^_5leA@9ydf%j~ zHinrVh?C3FBTo`ryz1hrIgi0>&_m<;CT?q!NG1m&ZtCdN6Oe?(8=dfNSiISg*jT-s z_`#^oqslJk(d(lRW#@(JQ+V@2x(p{VE&XW;-`5w%<^q2+aiwuumxil^&+=)O2O;7e z{M|)IFU(n(Q_R%pj^ZmGqBT`>s*4|s{MdQ1bhF``1}gqIN>vw=mcDdu5c=y>GQ}yJ zpOk&-A|7%t7JuNXF5T&>)4p1l4_h_TcdG1tS72Hoq=D}w24<-F{cT=XK$?8qq?@@5 z0+8R0JXL2cDJdbc!2a8UsdmWynvnPdfQu%2IkYF@1K6Bw#vzL)y^CH5t^|IRH$Nxg zlR!c0nFLRtwq!3Sd$mcHy*L$^#?hMWnNgHme{fccU;!y&2c<3e?=}T%UWC zFDG}YsqccP7HnPc-GaUgpIW$e;dcxBE_!Ow)ihgt&u@MHyXX5Zeroa7#osL^ zZwJ{n3WL?ECAimR=h7JCMp(j7nyk(z67k6pJSppZ!iY~2@#JLZ6RG$l2~Uaywa#Bt zfcR{v_$*47lS@Sx3(@MCxuL8@(5Ou~cQwOvn<>{U#EAc6#s34u|8e5~f#Uyo@xNA` zovXrbMXxOq5|je?xo{RRh$7F-cs7@EJF|0hH2M6CvMhCx@RP1c_!a4AQ<3ls70gBz zQ%$6XB7w*3Z$u1RO=))S)W}fdu;{4bVu4rt^Qcb~RZL1nm(I*}ga;YbzsU`c67$Ng zUnQOSsM2>=n{vMir;W;>*kX&oQ&FY!&%6nlfZ3ja~3|(FzM#91(H_gMvrvn`i)R{9`8jwk7tKgK$DKp6@Rope_xv{ zU6ZRc(d@3POEq23ePT@8m%uAF0QXN$$W{{kFRsxn4`3OQI+;%Dyo>$&JG!txuM_*H zS@!=+*nhM`#QrX<@1%n0<vsP*>l8ItQadKI@xLiP6Pfn79F>gl41%Bx}b&;(8?>i#)RNJW~E{(&aq;cMT& zB4l^c#AHj&zeE#B?f;>P|99)dze^LLMoA}bMwjkdJu{b3Mem@yYsg(H*_+4K>R2s* z48mN3`%g!zj3H42ijTohI@Tj`#VLosQHDKhCvQ#dt1kY+PF5;d=MNcT)Rf*Y(81)r zHHJ{*0J5f0H}9-+{|*hDYrB^QUTO2w!1VV284UyqT{N)szoY@|55^etio}(HL@Gwa zi$74oj@B+J2rcsSMUtYde~AieTK_`@{|XgIn#jEL-*ZaX`Qe=h;20#y$0cQ}T}{)cDXpFJV%nMeF}cix2-_TD;pQam;rh{zrJ<%Om>k*~!+@8g0CpbqM`ypxvjFG^&^^%h<1lNTQim=|qgkpr&5jZPl^n;NbV{M0Q4YiZ{(!)~$x?C!XNe zvCKw0%WS=02vYm-%W%sXc;bD?a!3eLLY__q!5+HAP+>P;uQD@R9ydO-bYwhrz1)1^ z2MNESxd z!;Fct*T=AFY&3T139U3rU>lnv!j$HKcE>5JN40;yfY`tV(_BZmu{fqmpQB055%%ol$FJ7a4`uB z8>3lyjI{q6SFxSyuYugMxOFGayeLSJN8g;W?-{QD(kZYcDruVEw|n!;GBR3eH1+z| zLU@yew|k@sy2fgGEYZwuqBQ}~S5}mJ-B0<##?iy5t$8z~qk>vwOo8dLy~18}NSaW1 zbN0S5fL9tIR^}mP(|xmHK^;~D|MQjGuM(&|>ynG|h}y|=jBhT+cg>Lr+~0t6@k%5j zhnU+bhggbhS=t6jD{R?iDE$OVzm~Qh(u|dpUqgNZ@?oqZCd#!cZ52w@WUsRwBQAauM>0$gfB%LjLIF70AaUKXPe~4O(&+SEPLhJV)dVt)xKd zkRX~h1KTNj>tY)fLvNhK&kat9mApB}`d79LJ{!oBpMvMc-f}Hp>K|n!ELs(nbJK~B z{s;HYnV@|kK%4E5A$Eua9zgo#!vXHOMo`n3@$Y-QY!brAE&OrWC83qQ@CoP`oD~Xph5+5X&_UKvCBFzu?>eF z*XZHLRq%d#h15io81^G2+R?W^L``1z4DX>UVtrdrE`2BaYId-#nbYKqgf0G9hcGW4slj5YLL!FZ|r4nR66ry5fL~;8$8Fe$Bvj6w<3mUHC_EkLbhlo$^77*ISHv zVK&k({82)N5X9xclHUW_PDm8w4`@xrMlB=~F`9q(j!d9$=l*A)rTkyu{Jiekjyz7} z{W_%qXH5T*hW)G3u;1@?R7UCVcKC_+$gl41WlVWqx95Lv2OpK4I|aO_n(T3uzm;pz z{EOlazL&Uz58&g(9Xt*Fe?M=Ly&U>3i3F1g#s#JYfyQGX!R^PN6ud4C=4MGJAK`=_ z$F4m(!R<=mFOlKim0tyj^b*iTFKWN^mgXP7vscgQ#MP{SX|L{e|M@?A_5X*m+}~p_ zqVV0rU6b9*y?Yaq|M&Ll@%+#KpZDrCFKZ{9w6sMnA#&URzDC@w)BH>SbeT6l$Rq92`K+@Jf& zHY<;Mu+=fYlpb`e;kHw|Jij zw_b1wM@c?FD`~))t@j@;A83J4gvaA_`AY_(WVYu^F{jY}f^xUok0DY>f0~MJcfT#n zSw6p*PMWju5Hu5g?xXDoT!<;%X78jK<$+4uTIeGi^E9w2HREoE&BTSnD*OoGmt)c_ zze`KXqp(B5s`t4;n$ee^0xJfpj;wDro$FgNbfBoX5e`ycDydIWAw!Mo;irpN*WOYV zjyy>{ILg6s#O8c;8x=JQ@oeMyS3LoIRU2nA)iTQ>#*ugp%mQOH#|7{|3J;7+5%1VG zj=OIh_J#bsHZuBUp0$UF7Pa0^EMZ^5UGmZHY2DGcWzpTyw;=S5*sUiYC1YOgBd65K zM@OkC{$Y52qT+5lOxYj0$oIO>s-W&&qsbmWjO}GzSyR=bVrp;QC=6%>{KQ)WPzbF*5JgzSYuX`lAB9_v2Kieo|>a@1N7U=9mH42ZbiG>z<^9wvbf=GA) z&;b7lo-61cKRUG>%E_3PkPs7edYPqTA{o9up#H)Bj#}G&OUEo-ZTN?i9(mrL71_rq z(Mg+NA72x+v@G?wbC-c;RV;;FJfc}M*PX%8BFwNU*mJIFeNR9`m9gDt)Gpo4je1fcA7=Pq_SB96|1?v_+}7!nBPn9595 zzzT$_ZJ`HCoHe)1`GF3^R`J2-(}*CV{Tx6v)Eq9l9RA^bAsL9TLX{(?53ah?La>^^ z?JBA8Pll0l^R z5nOOB6*G9eZqguPA)yEpLPlM)OW-Mk(cX_)vKwN?O1e|(C{`*2&y@;6qohJ0t|349 z+)^JsO!}a-Ws3BY=%?gyK{|>aX~cg@+u}r-Q8~~2>^vJVz@-C&l;tUf4N0C!% zoSNY-1o_}mrM8^8#LkO~s+wCq7H`gd_8AA>3=Sdf295H$zw!RfwG0|o*Bt1_t9XVK zIO;>dmW*cuaFC2iae(FrcqsnYR@e--Q~YxsQogyJ=4ZCHyL-3!+@pO*e^BUQb8?8P zOFq!yexXf{nJJ`$stubEHZFmqqH$`z&;skrk4-72bFgQ#-C9-{*tqT1vgc-+;!ILg z^3lh*QbXX$FgBW-u1YZxoiB+=jpxZnzfxu4O>!THBvs1Qxo;|9H|BGX^O1HM+W)uO zaf6dW62QPSn!*% zwEhlets=}?|3@%;v$LJITgg}+y{Datw@r6OL%z)>LlC}9-Wb!rJt8umfVaqa+T2m% zc!KU}XUz4Iq%Nr4ZD-44ivLkN^Tc*&{(0`Z-DF^9Z!TzseCH`qhok>efHgl9T?cNeS4JA1|6wHD6ATV0q<-ubz8 ztu1T96!D$A)JEPY!yC^GeButpk<#C`R@%}gOz3Rk?p#A9EOGcpKMwUT>!chRukfT~ zgag9lJEZ;LI~2Ic^D%#TzCwIH`VY@v6`v3K!}HDJ^MpS{l1& zXcNF(+`ShusgPwYOP9zaE15R&VeTjp8tg1Sg$t`t5|_kJ!3v6hd6n}T+I|7t<>yzBtrMFc1?mbxQX*kBWT?1Fj)9=8azpCLxb!ft(lF-4fQgkY3ds=ofQX&6 z%0LOy8F6)1_I=?qvrbS%9&481q(cF#2s&U?U7~3n+hly#umit#a}0jr=|j6==`v&5 zgjBVl7(aEI0wsDIw+WJZogf?EyZ0(YjPLfso(NR;J9cjb{zH%k zL32QhLe| *IX?AZeC`97%;C&>UdSnodWNZx>!y5l%lB zUiW8nPr&XoC8$%N7XV3IR<=FrE!Y@+8>yYO32wz6)R^ z;tGLF7rp>CJyJ4^6OA~(R78QpQv~!^#z@r{1Sw8_q}!^6+vaM)p{^EAAe}-wgLDq* zJEY46m`x@+Wz zHWeGrjuL`0Q?Mt1>!c9zbfb@0){pfpkSzAC>K$~o3xe;&7n3NjQA_+N9 zcvsjL5%@d+T8bP6ej0pra#b)D7>5X5tft|<@%N`cj?>Oc#1t&1CCy_bcEO>v3nxtU zkO0n#R;rLU3Yttw%iknHCmypD97Rb+(wxH70)E8$@DySR2BgVw9`!l2jr+h(*Xtr} zk#@;Gm`9sRw5i+wf=!VDA4(FY*&vZ;pry<#L9M4BK^vJNrWBk^>oA9r_sIKXE`TqG z)Q2W+W)&5$aEw&}D@i|CPLuc{I)6EB(6Y+yzCSjVAW8SodOgpI_&XgrHFg`9<5(MkiG zZK58$?9{UUw=O%gVAlm-)g5Z$@ouGPCBBlXGh&>CpNK;uHiiWUy2Dm@U~LFzfaj8a zj$Y{1QkxX_{@&+t7r zx$jag{6#ti&@g5DXeMc&$JpV8C60myz=a=R6E3NEJy|p9=AqdS#lYA2^*2OafVodS zB?(mf+*`dwGDPuP%WsCS}mkssg_+noAZ+JI|w40(;e^P}A#u?lG{OMWne}N+Ywd7RkaC6JzSt#7BxfHUC%q+~I zq>KiZ$sf9+SOv!NsP_==$f$;U_q!msz$kulT_$+9pV@L$P-Zf5YFPGD{QZ*1-f?Of z+ugX=@W44LrjJQ#lNu$lbj%D>Z_8AR3R=zQVb4XpO^iZ0#5Tcymn#haVZVrY)l{9t zntWiDLCSVxM>nQet*SS%tFhXtrf6%BG1}6f`&pG^-DBTnxP3BudHSI@4RY8gso98# zAH%JHffUjBqPSU>7>mvJmFV^7D@*C2^yR@KoV$r|Rt-9s{s6x* z8t|3D824>J+=qAy*Img+$*4c)Zm8#S=^*;2cTl`c=^hT50}*vO8e6Z$mL z>g1!jDqsY&$uP#$=cLifSi_7eqtPO-2y9}sQRsIB`aQUf9`>_+yDf_C z8t1}0;|%E>r^^wXOAjj_`?H;#S;Vo)N6E;Z?D*bA#x=R)JVwZ{Ivb^q;AmYvytlME z3&s|VRoaeO>7-*8LSM-T*4nH#20m==$0`!acC$*YDlWk&g&omtr^2eT_BKh3DoZkE z^8n1|qr};K4aUW=zXEP#92@S8W2bGKSXb|VQrDN(5NkO6FRG2bP2rX=QKPi8MkydQ zORVuH@r=H!KCIhg0^kQ#ZR>55Sc4HmN`B(Ov_X)*KArd=-pL@)jeVHiF9ezASU&?_ zdNv{@btdc%_t!z+Md$~QF3H9rMgtoMKW(fr$NHYV)-cvM$69CK0-qOD>|sN&Bhr>_ z)u8VC9C=nPuJA&WaN4PAdXPJ6qXzuy(u(q=9%;SM?#jd-XtxL2B{Hh3j-a#kjdNPu6Q4v$PrhF=`a|$=3a$hvh>fu- ztq)(}i7M%h>l>b#CE>W1dA5~2fa`0X?@R8-wbT=3y${z{JTt9fxE6c1SwnFx^n7pa zh3j%p)T*AiF7eDv2!q1yQ zao%48r9Cg^zdhH}7R)g=#*~<0C{}UdrjJct_dmSEiycPyN>^>HSX&Be8za`%;2>>! zoWHnY(qch#@Arzyh~zy!udDy~3qpBibP0Cvsj$pL#0SJ;OS~YM>%;2S+b7-B8~i;8 zJ=7h2&#~1CD)ZV@kCT3c*lfC-UQM*w-}b50ADz+WBG(cd8Rhcdj8f?A-&y!G@{j(O zi;Qoyd;Y#nE**G0LhFimKvPH?D7pGFV15%R`2e#5e3N#flUX)h-s7|moMVn{Oetw2 z#Wt;!L{ksvqPey3nnzYU309XMJ>-1L?a<`TETy9*iVb;Uzd(t6o;T zAZJ<10u7g4%9u9WA|Z{dGCb&r7#C!kY&!{0$uSPC?F^npI6~33#~F;B%_S4!H>38O zo*o&!#;Lg6nb%Bx0R3=S`ID2k9++*J1>FJH34m*`=_0Y0!dsVIp{(G#$U(-3966^a zJS`b>0#Z-A|Lko_=hzGO7p<1gvE+TWhGD@gJ)w-)3#)};tiqTYK|LrrTX5ve%7U>$ z5mY>LzTgO@Za{9P3f{6;ihi_U-(X&?zs)7m*qyF3@cT6ln^r2=H}m?=sTCfo-yK2t zujue2sYB~buxVDRsJM```sHACd6C9;FiG=c$tibEmrKaj)4aN%sQ4RCLZf;V%YJI6z;q?3=5c`(hU$62S( zeOCO9%&R_k)*JKEfa)7#qFi}FK$*Uyce{p=z3 z^X7bL55H2WR+d@VRi_Ai(rChbVu zIZ?7S3BG>mqzl6Ks^Xd?lcZp~=&6R{i_LFkkX2Q+bb}BDe=tiNniVezQSf@WL0}=H z>~B#(^LU_TgRoIa4WxLd`Sr97!Una%NGB=Go)sq4WO*+A69l-JQi@I+T$ z_Y&SwL*w;bpJoMqQP5E`Ej$UBqnAl=Dh>ZH!6R%^JPEPL@jnnd2`YG2{shDp$j;mE zG3r*S80?wt%_%)HPiR&!+CMu2wX+;#uHu}R3O4}mTT(5>x@Z0#3(9aCN z1ZE2L$t~*KDD0g!6TMaK%TBWM=`e3&C)jc_64aTa0eeRw<>OqS4nlEw9CKpGja1_=ioj}2xpXgKVHRA1Ka3>bN18aSP zS!#hAeBG&8F?%+n-R2~XOOw>B!^RfYJ|+vM^;Bkh#oeB0+f@4dtw!uTk7G5Z2q zrNsVR&+jsy5?(E!aqe~smgZNW4SNGto*1W&8jN^3@DUJ5AM70GYmT0-ZEF-#$tik> z)xPazbv_yQMl;|^1=>pt51*4jZ#QHRk zSqF*_Vkax6QmYL3D%5siqPp_sgLSwnw+rLp)lkAWcKE-lOp6^LU3fEWAN(fB3U5X3 z>l$fET?rcoAKv1(cS++5Z#M2F-{k9mmf=_7Z5$HAN%iFFmwQeucNs z?Ipbn_mW>pYjn~}xI1x`JpH_F8|%GVLQXe>zqp!Hs-CwEcInln(eS*e=_BDE=op9i zk#y9%R}~YqrqQk#_A)e{3UA)t8|-p%kf0S%E}}yvK&^xHSBJHsxJJtM1|Iiy$hDD3 z-LV^F_(!MA>)EqgH!0CkNbtoS3e;#8lO7;mG_)XyB|G`0AAEYdodNibcU9$6@!5{- z(rU3+tA7ZgqFK_XuOYMWxg8zz#WjNB_nGHmm7wCEaFBI^;tz`0UT!9ya|TLA*OGF5QSJo?DYXne5M0~D6=0p=4d-I4L*H|aCd~>%I<2N+q*`Uc z6_Wv;_Pp-3ShxJJ2xUnbvO1BmP6K8U%YW#a!~e$_dGaY*Lq#Q~M=cJA7pl+#uX~|) zI@Yv%-_if(okn@gDeP$%!z+fG=wci1tbT-cz3wdUNc3yJt8Ye7l!}X5e9;t%b#zf{ z9IF#c?r@QHx_SxuVtZQa?#aE=dIBwP>}>rsYN^xc(Ilm@qZcCTY@WO zttD$NS$n(iTR0HL=GBH;OGJ1v#tM6xA*!KtWjMPgug4r4*2`ODy?iP@{HC~G7KrPm zrgOdgYNhOaX`zB8eJx!g;in*ahR;14GC1L=l3lejlz7vG#3*vEQt`==w0?J$tLmkI%5)gU-fwb5WsGYv7fVq9uXAYdO*w5x1w7 z8y|jHug@nK`{F;r*hN@3eeNagOFA*-BlGjXlxg5=wg8L1G84{bgJH%U&PKCh{yn%c zUBr!|jxO9FbW++8cZg64`5sq1T@>_mXZ7h#rFA`dCRvvnajH{{;T$Ii!SDvcQSCdsld&TiGI1`^c-{@*#y zxlnG5&;8(G!tYjzbIlT=x{#b?Rxi2aBI}~KCIY6ZxF@_ES#5%}0q_S&IJc)W971NL zigO5YYu6ea!mB0+_ydZ6+dQ?C-pa)pozUAx!}L4!MroQ&alo8+TD5oP*E&ZSnWHBBy%q`w^YL zZxnwgoX!1CL`Fr8ueSBI`MH>yv3_ofeAQh`h%V?aK7xfmg4(KGd8NBbGg-1Sjsq@f zu{MtOoOh`~U2Ab-8F^>ST1QeX88M9!dph6l8gqg;W>_w16^>nnjq-rgciTD$u8QpLVJ*(=Oi?beupH@)9kPyUO&@14b57Kkl z60#$HHk*zGHr0G0m@7XK)~a6;dYchDLAh<^_bay}213q)?Sfu+X$j$TUJ`=pT`z;1 z1J7na8oCzz8dg=z`L7MY&b8DQojx@$4BvF7DxhgvUX^NG`QIeDh#v;= z{ggY9e5l=!o-(l)my(g4ZOTg&p?N`2Zlg38gphR-qX@+q61@Tt{LAdc1V;3Ld!dBi zk`nJg{vOx@T7I|!j)3t)^?+n1AemVWn2s;-!!cHbW7K~O$5?Unm$1Lo*~po97aTXc z9uVQ!vlEVQ7!)V}YdF$kO&_8rD((pM{`__M;YeUeU`gOe@bF$361Yk@CC(H=*my@c zD8w&a7|oNJY(>FO9F-AhnZSL1v;n|j|w2*hb?p7a_(B!204>gh5IgX_Udd~M!t+NlY z6ktD<($@9d>ptmgcBP5)tuSdXqLW1|g-^ty^Rj-YE(o8jC!T^sZP6=a@r8}#w6i+T ziB&1!ESUW#rehTNzM-YO9Cf(s}kpZkg=)1!kJ!B zGsQHcj}M<6!D;55#9iXKEAzG7rDvzt?ni5s_A7iD@?Nv&nEcbzt zpH$I<0#0Q{>Q!W{`WvjJ6xaIe>&(@wk3mBhD?9R;=SA9q_V%75Bqoi+RXvAj5&vo5 z5bolf$to(o?)GE*9#7vd=#@%t%#GucW2()n_4YD*xHPRU%h1!fUofcC>MHDp8>^{a z(8CP{$AEcHiL!KWoMeJhu{Sm7s&W!sNn8qaT)wa(-cDxrtkniYsZl0l_nNJ&o&`yU zni@FGNyR@2A7zkKC?Tg%Z(&nh>+l7ZS_qC$Z=aPLMT3(g`4_@xGPE29t1G$tD@=+S3pO7oI1Rwr?7 zVOy?J@of%7sS$g8?dnIsj=I|y_rBsHF+3WruNlnzyJm(h0xeDf4nK}W=7$-$K7&N? zIumJIVH!Lb?-wRgQM{DiwghtJZ!IUV4_;f zX=YRL-#Wf@Y4T43*OKcf%`^k0se1X+5_lL~&t2U-A&KQUgY|WT{zj#RwosMO!r7^YK)cty+B4AVr|2N#kDNmlXHl^kChYljz1dAy30*SmkgNMWL)DX0 zeYc10dlNCM6ZdVvmzfrM0%IOk7s>)IYDTNS&RYN*$WaK6Zbk&vn7x39F6wFt#xoYs z7=6pVXCZLnXh)ohUTQG~bv=z=sI<^T>1~;UcTWpi?hF?x!ZJ|k zf~49AKj##gl^&bW%nh=ZTU#+lcKw6vV0@<9b){ZneI;FOVnStSS|>cD<5cjluO3k^l%3?h~g70 zH}1Yu&{Opu-Wh(+JN+#WV@7Xv+kGF&FP`?dx!YGHKX>X3G<<0FdqPM}tNSe|u5s0QPeSA6&yX4_*GeZ5 zx{Yt@qAwHZYicK*dEMU$p9<1Se{Ja)5A-`$j95zc)oO{NPOceIps3R<)?$q!{oEnW zJ45cYkU+GyOlz$N1O-MMe`j=4jLn?P_)c~?X1Ii!L4Z}{o!>rd4wmUumEyR1V_YgL z75^cLWuWd2ACpx4ekbu4S__|_4f157ZNl7Lt)5ELS|y-~!rMD`d)@Qf32s*HCf}^W ztTR zEFJFozAkL7_TI(T3Om8nUGSsO^?j+>XJ?1FKE#RLco!SnKhMNw=kfkZjmoxO&YoDOwAtlOGIet7T ziB~zl4FA(o>EKJw3z0hvO=sR%dSa_8GE4*xcefVxE*(@rIi!mMOd<)vesDH zx56JY1hC%#LJz}=<(gM{NNWw%_Gs8Iya!K>+wp%tB5YzWhkLtDjI1@O!yQ%!-x)>Y z2y_9l7NO>zh!;x4vAZCot*6Sy!Ed#Jm1#Wgy!I)GdbeM!aX%tR?iY@T_eXSp$7)aT zrJ{ohu5UK$ERb`@!Di@fFYy$6*!eAdX@4NLvZ@33@J&onhXn~*Eh72KUATv*7Uazx zbHDt~U$*g?+Y*w;S z+SH195}b+S0rmr&EV`ZV3#!U#CF@hKJ746an>WIL%_E!~*K1D6n{l>QZp^rkO+8GX zLn{lqn(Jic%%%%M*ft~!75!KASRwxcURKCi0;pd7B~l3zb9xRUM$*ijg@^Mg?eh*Y zH*0)BI+=sy=Q$E4XiG>ONb=?4C-}b{ETAZ=e*$1b>0>7-Z5{4J?_87kJztZ&sS#}e zD1L)EyaXew#K`KIrW3FWAd={Hr55@d+sXP;}HBL{0!l7 z$exk#HOaUVIwJd^@wj%y7$Lk+*SuVT@9^$~sq(?5sM8}?NFd*iF4~cHI8VZzM9YU( z6CPfFqi<0;%Bkd$r~iTYV-dFG+`Y`0662+$=A=HGJP@p*Q7o z4}={hIcHi|l*BzgE^=v^KsPDiDO*(!Tu>4$H(u*Lh>0~uB3`B%-d*Z<36V|k^sf9$ zh=c!RoxW5EH=VVfftUR=LYSIPhEHYXF2t7Hg-DsZgo(PZgvTlPT2?ak zaOe!qx_;iG^mw$=C1d``90hu(joDLA%3o z4jiN#ee=yd@Zzriz;>t**i6&BkHPL5=d1q^%<%j~@s(y$wsLHWJt%4P&6oEmK@EuS zI-5Xri%fo+%#P%wdfIZrzfD_6X_8s33EWXf{*?)LzVF37D6c+TXuv5q;jhSydw9vW zSD1>kpqbbAqygKqve#YNjNI`(W5l_K9!W6c(><8|dDd5drHumbT%@!!Fbo}KGG3?B^eee2$vN}4?XzI;p~w)JMaYhpd+MF%VzDs+_3|5$MD6%nis;o z?)_fCL`O8~X>CYd3dOL(%gOog3!HM&HG^aacCivp0qFugoWNzo>>c=}!+pU!5?_2Y zcHFN(8{!{`9r?k_L~7A(55W@x`ygH6P1&A;%ZEG98VDwlvxdVfi6^mN_mcAlKTeU7 zuD#PQ?-ve=oXbJorpsSrm5e9}P7fT9h@oWx6>6@xQIQ@92%YFyb$N;iNv3_}Wk`V+ z)L||lu(}scpi9_*%L~B@-`G+)0Vj&jTUJogq<;>x@ z(x*9>sTKD1$>yDM^{U{_7Gti5@}4nz-g!Z{yk9LY@hI*25mURc(A5GA;iJ&1J~-c3_R$ zE+nT^T6Pr{z~_J(X9Pr=_tUedU6C2S*jnMBXkBqoec2U0NewEf2c&o4e}}uZV^^Us zHis|7JMW8MU3UX#Dfln}L;|*w^b^7PuLVo>T{2JAW zi_x>l|AopC-GI7&-IAgBWqui?rJ-2=yB~5iJ<2}JQG?r@waa8%hFB2`qen;`6)lZ6 zsY0PU|8X-VL0%K0IUwZePpFs;@V%d4bV|yr*q00wPmuNGpoQq|)LSIw!4>j|H=z0d z0NW_9v+G-=MIRXS*Wa_0%b8QV3a84bmKuxv`ukbr1ggw%uujFUvomVqzv3&OS;UNE zmK1B?rn3=p%UBD1hjUTJ5r~))!@GTYz-x*}UNOKJZmhGL?LiylYe%t*nl!9ri=^By z|BZ;~g%h=x3{2U2yPd5;BoIn5qZToI*AkrI~Z^M47nv39-%~ zcKGm?2i=HpW8kJ3#Dhcb&RaohN_)u(%ry?RFcrWh9nls72WlC^lD+5yh&rQCCPJG& z(ekiKvgI1VLuIrvI6}VV8t{+P0|&+EZ$YqG3DJ+T1y?Xw=fL*_5Lix!9JcFA5-gQ( zh;=cq2faR&twH>UNIEm*7u5=tCoFg*zI*;4sr8gHYK50vTFlgiH)rk}$If<P?i zw%A!}!1${Q^*dINTjtfWI?SG3BcKLBZ(;AR&n~;lsIi{`o&TeQ(D~mTen^Lj`z)dt z+aG#aQ;^7+Tn$zfDSY8{XQ}Hu%>>hN-VTo-FFH#ASF*;ez#2ooP)&zFR*N6MVGl%w z)B#7JrCL7@ccLbkH29P-qq5zd*-kWODZbQf#>v|VE2a6WSrRgB#I^mc)rCGa`F_<) z-oq+{h=hn1br9CE!fRNM?s>ObT#u@k9CsxHp3A(liQl`bI@hBr|9aH9;vMcSHcEAu>Vx??BSZ6)P# z-)!G$X+OtR^R()j>id zxHq-!6qMA=Wioa3GDKcnhe(|GMQ~5`>CpE`#G}#M{XTuYfSLb}te?9wifbY`DO-$v zNr$-xa&w%JnTre8Vm4UIZkB&KpK8%rV)MHnVw(E0I4c7WLC$89En5-0Z0Y*HG(jeh zbzX{fu=-^Umvkr-t*(XaGRcv`X-wptiNufMNVKgQ1IJiDZVr}=v97mQK;T-s8>o}q4QVH*d{o^0v%^e-*emm?2cPOJ)4x65T0QrqD%@yJ zt><^6jtm=#n`P_~;Ji2=9&jB!VQab25xqjoN#ZX(+uZ?3R4UaU03IH9TN{y~zYCh^ z(mkonBfopxx7)si1gUAYKj&(@h%Zm%UZF-!&aPzynrG$G7HLr7tw;AgMs&q9y>7~* zhat4b-Oz^JIyHp&)YU;=o|B0YINF+WM!I5V`+HyMtS*GC9aI3SQ&%q`ws+v>Uen}D zTMB}-heDgM_ac$$bPL6EA&)ZiJKQqQb1tRz z`!ywoS5AP6p|e~JDHf*;7&!WN;l5D5vPa>~<@>1kj~t|BoZl|-xB3M9vl1w;XuAu` zx|^Rsm(;Hd;&VUt;l=sYh2Oi#ew@gk$Q}jwJJtev>&~u)JSZ%RitfiAg+$}1kbpT& z*GA^FM;&T*E@~dzrZ#7?9-K9s%xSoeZ8IUBF3DGd_QF7W54CA=J{62jdZlIC!ix)I z7d^Y^okdp{jY0g=5s-uuD!b~rAPjAiX+9Ko*Q<+Q)hk8JaCl=TzxyY#Nm9FXP9+3vN8+_CwR*;LD1X#^s=_vbXQf*?CHkNa}#4K6_ZE*Dzka3as21r?fN zO-YEX{08bnB!EP+e>$8a9NmE#_NGfXAjb*c1GeJA>2gfXM@Rf$>wd4b4Y~rP6!_h)1ng>#`Kn73tJUJl|PZW*{+>^@u!p zu&xYI$q&|%{LUqz*j-S&7RqqNeu`#fhJW__0QT167aW86|FD17^nXkAH$|RLw2%J}ZC@TAMX~MQJzFLl znQRb3f-{*UOcIa@2@n=_2uYKLCAbUvoFu3n;L6CN5d%<!U9MEFuVK6!Ef32FR5N zF;Q^2F3%no1<`9%bP!NGEKbjs`F&4Mg6O;N{qcUkAABl3Rb5qGb?VfqQ>RXy!wi2^ z@L|{IaSz1VKFi$Wv~!6DA9hSk8rI1s(0_UN_Fy0V@9ja42WL}Fp%s9+)`!cUP#=Ev ze2ddYc;6~ISD&+R&ca;_FDzWdr^z?P^MqLaUVQIs51n*$>?@eKy*_W{kW|7`YByo( zYH46^&tM@MdnW4P*2QDdHv`8!Pb=v~Iu;!NQs=!?7vf8?PPikEQu{$lSbh2QD*qpwh2CIvS_cnUfP>eWn^Sy)ku5}o0Elqf1S zt5qABtUH}uIqFTM=Mnb8*HTh5Y@>B0;aTT29_UkRzkC7?SrKcmc<&~ zZUNfm7U+wU7r`(VYp|CwJ?bQRF(dxf{-u-xnb!jBbM#C$tkN^^VRu(~^Q4eOzbj`t zr`|MD*vExE-;dL5(Yz3k_AW1Ggbi)XjWYyltx9ffsj$6pl5k3H_gecvoRWuH>T+pb zw!;H`2VYS5E86`8?2B#{fRD}8f|u}J6?ny01+q%Aws5_33+Oi>(|HHCj8k=mdcIHy z)#k>E|ET=UOZcYNVa3V89o&mJ+at?5bPjAP``D`9^lnIIZGOykCl|KmMaai#Y-wcU zQG2{AsZJ-VVzeEDxtFf}zJZ(IQoa1#b)L>6h1^=wJ&a)$xhomJ+YU`$rNQm~#dkn@ z?GM=Un%?!}0crCe(l+bA{_!m?>}BfZlUMTgW`VX4j*iEALH^E3#+Aq2iPnd0(e&oh z@9popjoS&ogrQPNd;48$Un;aY$d`P`3~E9|(b&&aZc`*5CcpD+$q_9MDfi)V$YPoylagx=S^Pp^YT znlpTkV?*I3=NX>OpnGU^c2y{R1>93wKXMc*mV=v>Wb#Z!GABicrw~PaB(TxP9;0#k{5*yh22gz zLvj)PH#4C%8#HtAa@Z%V*MP$WOwCQzC##-LYlBq=$iHpDq(cRq*5G$HNV-EebJnL9 z@sj(Ypb6`@F3P-8a*qsdw;Suugyo#vx_H)N@S*G2 zCiseInvPRYqL}lfw_zP1RQm#{f4QF9kGoePkLK(2p)cw9QsgYbTz_78+hwdv4r@8N z0H=K_<$?vfTzM;DzhmumE*7hg+uaeMduNPE+mXbbvmbT63LV#={>fgYwv4>!H2g!**IgSaXfZpwZp0*cy>wEq!^g!3f0(wLb z9mOH&`P?U9f$iTxuYjKb=MhpL=HTzhdJz0fOl50;FPq=y72JG%|MuKZE_E z5I+7K2thRaI($^TFdd#t2%e^3%Qbio{cqrD<;MV?Ea3Sqw`4Zr{xfh-jpSD5MG#d5+jyTkgVZ5%?Sf}L)&mXY9zRbAL;#gi75BkV< zZ7z(FX@S?-WrZhdt7V_9J(*)M)1Sa;V3$B~qEEJVq7m;@DyoQ|h$@GLR@jD#5t7@~ zT^nKfAQ@VeM2i@`&pqPs$NX{Z)2=w(&KhNhj9j5ZSR(gNVr{YWw#*m(tF8(VJ zG;WtYda#oG2-j&K-@8tM(_=*foT7C4BCs zZ>zhb!`0m}{gm7FT{mW#gu~qfV=_(+me`d0VYBs>?g>%%!&X+=`KSn|(6yU)w_Nvon;r#SE22wscbqO)Z` zVdf(ioL^<(KU%>ywSr>9_w&o>SHEeZCQ6k#Pn@fsC*BZ|%)KLxwY`G(_0ov0dTA6w z0m2xBJZrs_Ur{fOY_69^cTSW&ML!d`8$J6pFv%6-dz7W5J4tqZ8nI3H(i^F8g$Sc#7^MkPUuZKq$RcYu(@!7XYx0!6OI)5eIb#Yq3x!5h4G zubqqN)-v{eK6jfZ4|0pHmJw68&Mrh7m>0~}ba8edqB~N4zr(Xm%7{4yF zQengU8G&_DZs$7mX&pQgA%{-AXVp2TVjXw(5{4TqYq;W+cF7Ds zF!@c)(8)rA*a^&JGnGPV7yY(4Gm1tG99ny43Vi4cz3Ob;r|phlbBh@L%6$sl&-A$) zePdu{S;blSbn$K9-P}W1l{fni-bSnP2H(v^Hv6^)dn(&)9eS#QTmJqlKe9KOcklQ=0^x?nVBvt1mv*4n1P=Ib}B+!H!C?WdR#2xO_*t zX!d0mWe<$Fpi&AhUrk>PUq~sP6N_fnrbyZfteBA#&#N=oVFn=zvb1sahGDgW4m|c3 zQbOm)7ows*!1M7MD#K)bRrCR#?|w}^MsLkuz{fl!4^h>{AK+KhSFNruz_+6>3~_$x zVz&R3r%8xN%EImmlB1P7)b0oKwA}D6nKX<-Xb2en>ECK-P-V5u2k=>;O>;d(T`oQO+>s=w=>j}Vcuf!P}{J-3iV^6cblZL z^Kvh4@}9%VspKBxHPtK7i;>>ym3;lY^9`1H=bJ3{eUf{q+^>QaXeBWC`2YiN;zlt{ zd6Cm_doC!WN9aEQ9hKZk-aU}jQC;!gwi?Br@|rz3-zhKJ&?vbhyoYK=aNF$zYofdR zp%%UOJ=jl)RyZUTv~*TJej{|YUzZ}fa=7;;4U@ZoU|=w;I+wt(X+d{tPwfiHebJ)< zg^=85J#0qpil?M>dsuh6l3m9YO6uQ5Ntj z(MOo{hPV31u&9;hX!~|^-ADS zyay+u=09RlxC{#!i>&9tyQPaZKhqs9V-jJJnp5n`chJ)y5ydqx@eK9N(i0WqDf#U8@HE-9lF z9F1zVr0D_kZjs}z{FMOboe%5&>6qv-USHxj#{=@)Qh5}E?mTY^#_$u*NzVR57uKw1 z>=AvlX(ZXaB#uTiL!2J$8_i7^%_px6-23MomTNg?$~m=8|(FO zFG-1?gsw1+1EKOSPQJVK+p>Rb^M!t_iTHo3j9 z+2%0=HaC0raF@;sfDOS1>*2)WX-sj>kH8xYA!azRHdr;?gRb z>tq{ju5hE=f&$;2utdb>t8jY*w+!=}_j%p<0jUyPGOxOc$Er2Nr?=e!%Svp%2J+?xYQ4!UuT zRk6XinC=Fvl*aivvr|h4FP?Der$P=^k_ON3aoe#6-;TY05^U=SaUUv|GtH*=uq%K! zmNwIDb_d0S?oVa8=?U=SLATpe019>m5b65{i@iut|DMZ)^mCq|zSBi~5b;D^4C5nS zaK&XUe33*?WrpN)nr@vMR`JIraf2LQ_ka3e8^3OM;Z>)(Mm;$RDeuXiQg8-n3A(>| zi|L@c2-XZdDbPyd#rZ!6{|WiME27&yI7swRrFXjr28kNF!KV^6bi-bWZnCXj)veP) z`W&travF39-;Pn`K@aPB)=+YZRY1P)D=H3~Dmu-xiI(lf4eF3I*5@uh$aL87eQE>j z2_48Jm*IdD|P%&1b}9w2LLRr1SPNRJZM zO08_#9B_R7xWVFDUuPS$>FzMi2_qlWhgzU$v9*tEGvfBd@9|t<&)_t6*I;q6&*bQ9 zE9GQ1-J^;>$-WpTYGPsp)>y?Cimal_dKvahNlUWY3Jt2>nw_pMRpD}8b&OihnhjZIlQCf_!=E)*te%auQtt^V8{=GN+c+D~m$! zEtkISf77%)_@cZSBQX}ae#JfVf~lkVNmq*Qf($QhG}3QGy3^TL?mL%xD$@BOSL_c> zy23m*j-xy&$kXA>uFWZDM)(j>HFhby|A#XSPp zPP8p^vBneEV0a3#Droo8xP0nj^$T3D0SB8Awj*ptu(hU$!+fwb$QKV9DD<10WL0&K z*W4~?#{rDR%z{Rwc{sh zCKjD%(~*`LTN;b|+w5w^8r2TXPG)UPN!YHi^_q2F_h^4q3GPh!BTBMxMPTAC3{vQbc%b^&!<}VTz%&+ ziXEUzCG@qyqC&1`xU(HvR!Tk28L-Fox(7f{Azc#0+~hYPYp(%Qvq4vXONDH`agIo5tuv?|yF!TQXQYiS>orCbk+& zRU3!{VY~COy525QFRyQC$*7bA}!3fOqaG*TS7Uf z1hfuDuWeU=Ggsm+hRZMD%ojI5ktXMDZD^sKET|c5-1tpx?1s+Ec1GE9pQM8IrQT-; zkw>L=U&IT#h)*y|rHb{9D z4N|_P0baR|Kn8pSoXy4+NmbxmV0)bU4etOBp|#&+BW^E;3DI&bQOMWU!{~9-zdWh2sZe=(S#mP=+`4uxr$}S4N4HC` z1ON{oOh-it(}LL4B)HU&toT=w6E{+MIaXI3a(^ z^B%^0ye&_DGC3E(aRuCBK-V1}qvTAsF=rUlw}J`21T4ChVPBo3eq^D(h9IN=++`{= zmB%#>YBZH@!tFz>uSVQW^7fU@MA>7)K)GyV*r#&Y!6^Gc@B?US#h1eBJ^$%Xj8SD6 zgwz>9+My2Y`Axsm6;-A(==lCfohGODL+Z;ejhq^X)FL@miPUx1!9cYGx^jTWWQ1=3 zi+d3#n9N4}ES^IVhvN#%y@1sx2ai2P%Emd)eXN{RA$z7WuBMI3_zKqy=4~uq0HmGWxCKm z`VLmYG|Za`4OTUG#L8Ngm4%BM7AY4sRNcTGsY=RJR!^)p=}$^p`yg=uWUJ7=vM0c< zNxE&27!zb~4zqSu?zaBy)TJls2Z@^CoH^`xWhGzjcB)|AebD3YNduS*kD5sSRsRg& zNj4{f?t^~7EePLy2(JZuu-5AN1aX_!YNfRZc089D9hzP^D;==xC`0-SpA6{^8Mdth z%VhmIUTa7c#|EnAjD^kdxEeMO_wJp#G(FOpHL)0buIE+$EeB(~l@Gm3>U~FZub?La z7CJ2EO=0W_MT@STv^I1WuY1kmcv$_8=e~5ULz{Oad`NA_ys@<|hlj!k;a5aq{Hqmk zFsE5FstlFOrHqPit=p{I@GG<80V_@#x}%g2RHiuw@iTaE^VwK8tt`9=Fqjbve7g&4 ztF8SU>LvIW&tZm*5SGJ+-DtsqTUXQgXQ3ylvqLM;*eT`Pv#dFbvMV7==sa)TYn{F5 z7rXrJDtuS}D%z2$ujbP#zq3|VzFL`KZLn7Lw&0K74~+x0K!X;%4Cxw;3&oX)zkn7| zJY^^51%j?Mx;zRRJwf*yL7RgGx9)XMfj31h@VFdL!sjV6ozS(@T)fTyo1Sdm6Pz63 z;Y@vOIQCS_u}6;Pn4#kZEzbb+NA#HFXLgSwE%Yn5hcTFVuX_mIK%VGf3|ZD+`O%JX zd=gUo!vpqHQiiz_e!f&jhYa%!Yg$zr!Ce2H^;PSu1ap0rwVT%f=2ex3KfzqO2J=kx zP-<^N-)ybXTmm<Z0&vRIl>R(8*q9_&m+B0WwmWmL92p` z-G79ScO>!k(CS!6{!p>^)aail%x4T%W0jFG-~7FGt92`3zS#-=vFgf7>j~`h*McHx zaI=CqA}ws<()vr(W(O<|VwLKUfSd0?3i2`5fqFbYz>}Q=+jMxsdcK1}d*{7no20DK z9a!rqteMH*o>Ek~>E1}2vZk=+o|WLt${|PS7=+n~wW1OfZBnEyiKBFauaaYGYzGcH z?yV_axw|m>m<5zlU!=7TtYP(2SBCTXgA%OwRSvAQVeA>mNRle=tz=9WoR}k&LbM+; zjA(8q=J0Lsw3=?tbJ%Ol@O?nz9w+8@5U0m-s_rBvPW%KX5x)t|HNU!)d;~mj4uTF0 zm5FzB*2IaAb?CS_@mAPJt#l}%;duSqcrpK=j*A!nb`bKA13G+_^z*8(eRUkZ3fizM znNx3M*T#v;AW2+wIDvvsk>0PvSE1=LzJ39?tK^L+8!vy|*cJ=_pc?V}4&pT40?sV23|jm~XwG)|BiKLN;_w zrt_*1OqSOfZ>>gtms4t&+N=57tpCIryAt$WQ8}TK$=Qc`n5@0<`ng9y@1Wzm0~WYr zaXaiCFZx#Ts_R|rf1uVv$Divw;mYQyZUG*A=LDa1<#0P7c{pO-2v`%14eba1BWRp$ zbm(Vm#9;)Vs^*%EDRJUGJzW_6mx49?N4?M(3uq)?gGMCiY?bvzUYqyF)sf^7>i|RY zatVurfPOmsK{uv6J)n*<*(IIol@Hq0g}6wM9b77LeWZz&|*_{&v!b3(uJs*B5q z@&n;HWL2RSx5;pp#cDf}!7)CE`Aih%Dfy`YzxS*+%E1hu2FqDv%7pdbU zk%HfeyXb|OS2~WY*#6499S3=vV>vI+ueQnXTod{YS`Aq(a1DFc5jBO57l27z*UN>e z*I@So+P|P}!JM4RMb(giHlPN5avL-BBf-l56JwPZlw5Q(d3f;mJWl|ERF28{P7twT zQoC_y5IDX$@OM|tWb{gFtnHLc_BrrlWp0Ab0b_AY!22{W{e~PO0GkMQqM&nKPw;t_ zhg^O8m_B+6zI=*`izFGfAq*o??kU2m#`D#Spu;MUQ_wvLw1aTRDvv{knfR_SE@Xq! zf?G=sHL!G151Vu&lemfd$@lVc=^4v$smXjcc{gtQ4F!J?C)Rq?ppl}zpkdO)3jd*+ zVS|uMhg|y1qSb}pVy%l48K06n2)g#AQvxPF6rk7%*EYwv*=rpm;qxX&xT&;Yb}qbL zXvAZnA|G~)N?K8<5(27G~dXm_NCI%-=jA zuBhAfk9|q}2<)V?O8v0UXey`ORFZAf8RDM&uoaO}7TRCwY~#+9IMRA|W-57ir3a+` zA&uh|X-WKGaC37#cl-RSzW5<;!u0oBV?5L#-`!0H`mUm)NWulArRek#{8VlNUwW-3HzaY?F zjK;NZ54IfRbP$2YX$nR+hxT3ChBnO-cF6w0hYE+=Vo$R-76}+(V~%aQq>9A1CM1gU z+K7wki}7te?sYv_mrVBvJ?>3CTbD37MNZ=qMa~Q%t%k||Mi>n*Y)sY}C-ExP!kxU4 zn<(k#O}83qh?BgBxOY&xWZVG=y1&P1^ZUXA-dMSnUtoRRx*uiUMm;mE#>%(gDf~XX z|A&x1ZCvepQCwwlp0PP_Ly5|8L)p!+sb%&ljK)RHuH{mHdkXB; z)WK^}8vn=q#{w7O(}?<#V;iz4)H??K;d_*@O!~4g5q~!e4fwlJID)_H1tse2aUb-p zcJ=382i+n5l3+@FTn1oFJd76n%uniYM#uZ_RExMf6#rvZ{WAqL@#1; z?m}%u1Ecqkp1J^*sX{Bu{h+0Z*XY5=d}Q0mu1)-lz)hcXGq@k3prCNr5rp`sY?*?d zcV$l1LPF+s-zY8M4LoTfcL_@P!3@LQA2pNPEb44DmI@w_l(B-~9&nfc?GFnk+T~-*xR&$M0!N z|4rJ$f0H)*S{l=;H8iv+Ay4KlaeFhvjl6tOh~%TWA&KB$*exDM6eIztN#_If!F7qSfD*&ZDfd4t8+_;wSz^{KPb6 z9Zr*T<_XE74R-bU(aX617)&-M;h#Y}?R=wlEBqU3uYNmc+WCg?twqd`eqA&woS?=T zXR>%_&#vyMsA5SQ#ooLi<$Eqyh`bQ4E-p%xy@UVcyaOjQM=nGt_h0qiKlC)}zw40{ zDzOT-s;antr{kfa5e2UjTX5S5I)W_~*5|F1D;fNY2rmFNquHBrTl1#n__ZKqIo^EF zed?rkR)h1Z8S-MG_88r*q&nMOapFgwIB~w`gtRamJS9$}i6^TWO*w+@2ZPT5M~Dw( z>M9&tWn8`$C-j6{UMWW&=Yn>rRgmo1S^o`oRVN6C_%k(|;k{)X`pgJY`wM8n>-@Kk z%rJ@c>eGQm`MYH-N+v8CvOa`GLzwJK!hR`k$kVXu6q*l5F58uZ4yi5_slqNSS1gls zqZP(+3yBM6jA7kN6dy?Wqn-j5eIWTqeIPNTq5Fd{KJy*eF<^dM9($@LQ9Ox}{s67p z?@}4U%fh;ol(mq8{o)^2*H=xci1J0RZ} zBIv=l!%E>KYwxqU_xWv&z9xvf=FQ+|cyNc!oHrKdh-t){pP0sp`p=IAlhwZmYM(n`< z;$haaO%vg7Mr9ZRs_~G&xrSDzGy7QB30LKe5$G#3XK$DUodwg4@D{fTUt~;2u@9Se zq4IvOPgKW_}6h0WfO9($J%4`!aIQR`^u)?aY(|PZN^xfMc6>|5PP{~%sn<6 z-Zj&b7fwWd$#tE4U!3T(3*&8sj3s3+&3CN<@{O`ijQANZ!G2RO?CD9crzd>hAaA9E z&C)s>`2EsF#eR%*XEND@4XsZ~q|OfCFU=iuEwy7K^2dbory+mbYDi)>Cb1*ly{uKN zmM+3y>&3L|N@t;Tc+(&9%nsWs&Caq-(sHyW)}X%d>%PwxbS8H~U*fttz?|%0OJRy& z!mk1Nr4`Qc(PeqisFyV!ED7R&9MYE0L$9f(FHe5gc#a4CU!yXp0pSXt(>0v`sCSGi z0J|0hlJ%*eeZJCRsnLSM4v-$G%$4`>v(nPUGK>nFv0Qq>oUzb^6@k`M8Z8}Ywypi5 zTwYm+yN0+25X}u1tf10r@hbM4)s^}>g-I(E4z4J~9!6O)!MM=)DCsX4m%_&#JU$M% zj&3ja=<9xRS!&eco56z)qPnMXSLzGYrxuHPRumo+Xl1n4JjkoDZ)2W^7LdWrg`p)s zc#pc|cW9Xk@gp8%-8bkX(SK_T{L3NOT6I&I3>7!Qy3BgSs<9SVsu!vswSykmLF4RF z&0WpX+pz@T`L5*tYbJ5AbU*V~?s8Y31^(btT zO#p4Ou<%@4r*D?{+(jsJ6Utn{*|C~ap>0bn*O#$N%Pq~)#lmLkm%>g-EJQiHwwC0oisxq^sl>_q_VJLzHf%YkCPQYrltVPL3?tdO@)$ zk?SesdMp+P(qwySBHBWGgaq*?4}*L3JFz2MS3~`I1g#o`*8K&~WISu|9Ej%wJp<+b zR`yVhvEs&_{-x9-*mgn=g23%~;@!X=_v83Q92e^y>_EyGNTjWyyQ-`qR{XMu$$UeW zVc(Aa{7-#_3{}?lNyG@?>i8g&)|Cp5Tw?K+6I1jb{OW`=9(O#7Ig}eegI=k5RK6Bvh3G` z%j$7YLO({LXD(>P=a=>ue~@gByfQtPhqM8BHv-SoI02*4BR#E^;M#6PKBv^=7*=-P zRbCs}Hgw8ot|=*>x@ti|=o?w+MK^3MwK#@M`53f66ZxTs?#L)RhFAt-u*~g9FQa!x z#CA!vpFRqCM;cDuKbjx<()<~6~6*1kw431I^Q;nrL{OAt=s_gRF6_-#h0MMy`mBZx@98_!0B zCImm?yYW1XZ~{SrR(f$C!T?$CMZ}4Z;O~M4)G+om`NM1A)fbA@8)|youLo2YR;b^T zv|%#$CYE{VO(-pj(nd1|aFhzwg=Gphk2n+=AR5t$^ znMeEWI7+1_i$00?CG~~nXmL~+@q7(@nB0cK064r!D%b=+4DI}CE>)OzezF37>e;Xh z^{i8FOMd~S)q5EA)o-g_yRcj{w&)*>vTM2&l~RwrY1CLpQhawXFRSS4G4j?kgGnw5 zL$B9JI&g(oVUcxfVd62sLavd$uc8_td!lzil}Rtf*DxN|h{ROeOZ(SPjI7ws!#F3q-upE8Ka zxYIg!Olr}4m$mBGK+C1}5u8Dc@wE-yIY@;(Kf7rEq$ndSj29iGeScZX8jnVavE{%LENkqNA(n@7%+?1;7%yfzMUOK zsEhV3Vk?uesYL^Cw%OcpEiJRNfXB9}LRO~l{gRs);bGig(*uR`Mv^kP2LevWaii%$XN%Ud_g8Hk^96| zosC=OYNwOrsFSH3p!-@b7dr-iw6Tq(^0DImhji_Zf8IPU&XxrMWDLajj`e#K6XPE7b{-% z_SH%?Qq5Ec`Sq6X^&2~R#hzkGbrU?;0QV!jL&|Y})ywD4fpwiO*!R9F?|6}841BN) z?1orT0{ZGnpb(GYIRMWEc=pG09-fJK&Oy5bN31wd zQed2DRojd=w5n~ulik?keiTo}(BqE6$%P0#83lfymA|LpevoPWpXvK@!1nsJO#2da z#0Z9~u`kKe9J(26|qEyf*|&Kxyrz z3Hx{PtYJe9!KlampKs~8oAFi`DA^zCq55CMj$$M6i?NGNG1y5Abx*^ zARr_lZbwK#Xhax_U`AMokd8n+wFS?~2)84QN4OWE31Jq(-3Svn^>52{v(gOWP@MR> zN}mG<5P=pxffjDO*1~?`Hea!eaKO`}D(NrY83>Iue6OI65G^H5QPPK*g_4Z867uyR zY_)H2(6bg=1~X7=gSt8d`~i1ljb?6mPdET zGc2rfE1I%6^-ij7K+jhGJx`b8oeHCbzW(?9aWKX_}NiX0=f#PI%3S?f)fM-79sdy3}HV{wZ z!xBB}4UDN=(24JY(=GrX*5fYr3@IO0Rsg+_Bv>yTij?ultp?pn#*=&wwm_p5TDO=v zkO{zc{Udv+AKQF$T_>ap%?auDO!QI{mweaY6Vl{SS@1Sh&!~4Q)>E$L!0)|nbgDP# z#L+!e+g5&4O%f>a(-Orf=hvRwTng@hYd6N^0K&T0BAHG+Hz53X^zk*k`vif;ka+%W z)0VZoiT$XGn-Mnd#0l`WY|f(7C#3NjqKr0Q(*BoAPe>L`qWC)2CQEQx>cI)QeckQx0%+x>s4=aV+pd=GN}C(2$FE~2i{Q6_7&^6{b@{lIT|$Mh34 zOlgIo@thep^~6@X+o;`8b5yEZ3EY&n_Hvd3C2$`PEk(Pvqj3@?Oazq=akp)SS>SH> z_i?xX0w=`EYK zRf-FPy^A3N;8B}p<U7&kBU22-^`P@KANY^2nUnQ{SA67awL`XHuZVJehr) zrDs1y6f=k!$>_6KAv`M#Ba@#A|KYcRr-j5(YL75tPj8NZC71;b(OJI&7xG8VNHG>+ zSD4u#EzyPY{^a}>n%V<-!tT(H>YoQ+!40?pxTi6;fqfNnLXqhhmmkg;5WXH63W>vi z|J|4NzkO2Op)c+^)%QJDUO4k6!bp6F0)4OV_y6sa>Zb3Ff(`RUdqZDrLmO5i^ws_U z@_STwU%h?LRKT(C_y5o5&oXSy;19#$31dJ#tQ#oQ*~}%|ve9G0agWa~74#=85r7k2 zKfZz+Z=L(XO_ocS?R`0CE(6|Z)=34KqsPQfRE#T3(aRVFc@n%G)tTQzsc>aJVENe_ zAz1DJd@1zx>-yh)Y5&{jzpLxd-}~Rz{oj>)ycb{6(8v4w`iSv+?7A^b{C|j_JFcs@ zuT681cGJH}&q7)f&X=RJZn+ZNGZu4wlRYBq$t&S+2$Bj?y8Kbhg?AOlq`FLH(UQCu z3u^_M_EFGo9sTP~7*7s5s+j~;QgOD{rLQ%)O`NOVW-co|q^(}9QO8YfGCe27; z3`<8Di&(QZqmLee=A)!)0HjqKl&;v&`!#?687WCcOolRxa?%M5b1AN#>0YWVNnuSY zNEWEXJCbG8lUJVHL*IQuF3F@Ri$Le}LF~hb%Fo+FasX;Wg#LOuNF}OJLNz)DJi=8w za`a~|9Kj)ZSql1Av~(1k7cTb?kU{_K)XLFRYSOh9zL)eq`m}T;WZSvaO0E8{INLlb z)!o@AcS9Tdx43#C(EmMxfIift6@WK$X@^~n9!*K{MvAfsTFo-m|5;9>F{Cyu9f|SF#8@&a8M=U%wNsjWXU!=U z&i?AmpP$uSt4-)Dc~?>qO5!TKu}F2{J+(HoZv@{1zkog?sA&AHZ}ydVNRa$@USH~c z4N159%Ds05NUGyHeew zsNun9q@_fODx~&Exy`f=E?M59MxCEkuLOE+H!EJFjb(~$2f(@PV2dIu%&&(173biWLrsD zyp?_F8z}{zzEV~%-4E+nwy$wY`@vOa*6Z*ipAQ};{6ZLW4|dnzQ<278 zSDASUMPo|Gav!41D%hHTPpT_b!a8Z~n9YT!kMlJuQIA`(cxz@%lLYo9=El#Q^zA3W zyYH8OJ&Ipfg+16EhIYCy7HW=tDe0gU_B!+gsIAoQ8XrjwPdFg)lh5>_%ZM}mxYKl| zU;n2wef5Q9DmoF?jZVTI>nLP@XwN{BJ!eApL1*(*J)xR;oSa0J#fg~#f)GyVj5!Ob zbwg!|j0v`3g6;y(ImnmhR)p#2LRW_Nh@^W!XAF_p6)hZt+rY3KrW4=r;#TY zgqC=Wcrn;=)$-)e$G3tHvuACnQSvVqvI0poNz#+b--q2>kNX1jsF9>vbWVbk6GJE3_7P5bLTxoJq+ZsUNsdM5AGqhsbwc71?Zp{r zx)QQ=)?lj2T6D3J=Z|2&a74=I8gP1YMDla6-#zJwq=J6HC&67fHTxwk^u})4igOh@ z2_%`VoloVK*XUpoFoI4WN(1gi(9a9$+y>ki@ZC_WIai*p+!~^~h`p>y`ITShZkQ!MoZHtY;P0Wy1 zM0-aU`n=GiGMYH*E2Re9{2|hTtuyPnuW-H>%DG+E*ZC0biFy+BeX-FYNeso@g>NnOVYo z!u-hOGmv?qHM{XGi#TeTiQ9k}d~PE)9I^F?y@VJe&R<3+esu4onpa&t@QAGIb9LGL zXmK|7xs13J@4be<$*s%k(G#t#Uuted`9it;#(HBNSYRt(Wu1_T~q7 zqBe0$P-d2oEXi5Kd9Y2f81Z}MI^M3w4t%<5nB~%BcoD(rxG}mbJUdp$9P|Z|WA#yFy=h5H-5dY75LQo48qsiE`|(h*cu? zlN_6k*!_qNmZ7ljQpml{%^3=AWKIcDV1UHTws$&w9yZZu+f!-|Ysm6UL)y~iu9(W{LJSJnd4lZi|%E#lWJCVzn7(hlQN-1z1Gs^1F8vcI=?M(P9GDt&_N2%)kpo zicc-K`O=RmZP>pfG#`Ro6VHWs)**ZaTvZ)}OcP-i!d!$p1Uo__!iNY=Z$T!2GA($X zKrnHyqsLQad&+--Om-_`lhFSvP;O}HU0wEA(A^psi(Aixv3byWzFoGCLKbid4o+Dn z*_^y(*cA!?!OKciJCwl5L~(9V30xir&56(|@gt;JG@9%Eb09adTq=)! zT#i5MuSWa}!((#nDgV8Qfe(9RVHpEzE%#>;-B-q$4SHkcS!0}d(UT25Z=%!Rpf4j~ zS%OBIFAKUK@`qYCM*c>eVHVQv^N&DVQF?w=>E;?e`f>uN(A3At-i#k%uLJjdL*JZP z_CCr%N6kO*N9z0Mfg!!ExkGMUfj?TVH`8!ynFGI+z%B;o#en%ELHEc&&kuS?_;D9H z;Q7JCm1A6P@#qhkxH9}23%t1H%8@-GyyoQkbp9Vu;zL7`91HjVOO8#DV+#Klh!G7Q zEyumS&wijb{e$c~K0@}q?A9dF<#`I0l{NB64GScR6TM2DRDHq{%y-n{)W3Ff&74|h z^-s08MEtgoU9IO7FDTb%Lm&OtUKo7j*^0JiqJ-h6`(D44(kZD)Z$-#n4 z4+O3IN$X*A&F!VCUOwP9xutjbveDz|sAo4c3arptAPS$-ThE<;s^@L=y9oWBc4hA) z#d7(PzKGtQ7s~NrKE)4zhSrcCHFprY2xIY;$8l;|EKuuarDbud?Kg=30*9h9tdbU3 zgYGV0HCow6lcK~3P$>l$q9#$eU(KL>Ufk2Bxg&W$#Xf~_B2$iw-uKSZmzOP~@}U_L zCH@qcmB!*U>IQLVaJlr*BOB0rno-Gena{nu&eHj1yx0vpJ$9VF^~diE=;bX}MgTkW zxUazv2Ho$1%M7}o^sd7fKQzS1We<8+on<->VjK=5tV6hh;71S;OrT9>geZg}1RkLd zVL5^g!3=#*CbyyGNoZ@06e6XaENxYMIE z!g^t881}{nyl2u*u-Vb4kPaEJ>Lf|Y6Ut)6Fx+8B4wlMMyMy2jSW3yI6vhb7Jy&J0 z@Da${-2<=fF03C4D^J`c$!FC_4+gQG89tNGU!x8~t_nOnfk3(d7e|mTz%PpbK^LI= zA`^b<1~CD;0Kbgr(*^kDR?-EyK@1P+0wB-zx&X1_F6aUj;9I}z0>q1zf6@g=5R;(` z@XH9&1-LkZPW@HlD(C{-Ae#SMT>uHX0JH~KUI87giY)9&{O+q>>a7Mk$nmF@IWbOE z_lmFr=(@y<7kl*k&AL!s4bfcP?S!EWwMZn?U6UhANTNcUngv?HxN)j>C#V#T8Y z+FOQTL2&ubOFj{(zX#Dz5xR~I(9akMorXFyJer-tPFNJYqys?X6ArFQ50aM=x%$04!X4O~B*f0JFX!>(NDkSd*aJ{IG&2lpZw{0g{} zp_c*66D{g%?PX8VT%wj90JkAQ!XU;u9Y)-3xdgqR$S%Yc&@4%b5f6akofAmQgvmK8 zMC5ck>0PuTM*KV8oOgcdVz>8$O;>PAumSZR+I9wTy1pInTx*B;b^+*ynAU(ha$9Pu z9QYk)qBR^kpoE39dq_7!96|O*{O(j};D=&N$1+~qy1GWmt;T(oWBWAOS%Nxy0CdGK zlIE>~9UGUtUpmhat~3=Uez{g!u8+X2aBX`M;BY@_NvA&fqJgTyrw+4PPIhA>ShwBrSGsi~;9I;(V{! zVS;ogq|2xiTW}K&IMd2N2O0S^gT+eZAZFhQ7yGv=%|yVAdVj zV4moRnyu_o!iwak+3}9#*{>E#r~g((w|`kH<)uB*#KmE-=%!Ud^PWj5ePaG#G20W? z-K>JHI}>*G;aWx4-T6husY3Nq7B-p_z=e;2eAN2 zDBLt!3x5QXlTL+UA2dj1zje|c$TVWp>;l{prS!eQOR(1v*1bV-#f9607WB<%KNrE^ zUe5f1Sedx_&E^}#UnIJpqg<@Y=_e=`D{~ZrAT>dcSzV5&PJo5>K{bs@oyq74=~tuQ zQfo}f4O}8_3fKByaHwu#(wU*KeHW9^q0gL|nJO;wvH1$zJJgh5HxBv6VcZZO6oAA*z9yUSq6%=a;+8$07^L*5T0@Rx6*K}JH zYNHwF@uWZ1g170g*C{?6jk<5}!FmddQ&1)q`n;e1q+na-rD84l^d}W7;#UlQY4CnI z-iPD27QY+uTj~2;YO>{UpZ*lVrg8d`s28xV`{pm!bT?4_+#*Ic)o_P8$ovfG6Yx*KANP;OV2S>D!T8+EsRR?&8)iOoVZvuf7WG2 zIdOj9y>yb99({NPD5HVX0~W)AZ^Ez57-%D;ibH~*OMGWNXN7MKRc9*pc?8c?G0Q_R zBG2ZjVq{M$&bz<9KL z%Pk^_Q>yqcDOI!um~==lP|Fjbb#q`}pT66M62p4G`*(czKIok#i`%h#dC)nATB;*# zc|AaF!Tkquk@P-rf$hRy%Yv2j7a#9tm9WlatiHTVF@HXjGhPtqF$UPb!#74bbIQZO zK{CxPoC7EA?C9{}@P!bbEo_k5%-Zg|wJcef02W<@^{~^Dg^7j)hOwYu9)f15?IYy= zRRHcfQGxz`e%-qR&}lg?ELc46@-pRu`Dz;d=L%pI6Yzxf5wyM;?Y5w;_U%~x4d{Cq z+O@`M;8wfv7H=An!*0V3ai;4QS`QigqdQSddIR?=^i|k=?a(==?l!PKRd;i497YE2f#<-GrBMt#<4xOmDl6zurVRN z5-8>DG6wnm6MB2wj`ijv=%=NMyocL*9M+0b#Wy{vu&u%v?3l%=;;TVuGe$6N%TON! zdtNUFpGF*MN~R4q8qX`0@vvJqL}VtV3RxmkS^)2gsp9Hj#r{$m&pz~Lip+#m(cbeh zPGi`iYJuu&a=itA9}0mE{`I;)LoRPc`Dd7axk9O1 zdQX^;uZte4;mJUJqKxQSG^MkLUHK z50Ue4bM3v%*k9a8|9+CkiQ<@_@HaAkwTeS;v`of9^k$s!K_4(V z%)r1@@t-|R+s(ktA0G-rK2IF|#X#czbe_Gbns0s>x4Nw?_xeMii~dT?n}k3vWE50e z3~HtCC{gS2o^R)A@Ovv}*=g{hLH9=iX4qG>K0Wp0Lll3zr}<$Qe0imc7kpHY=%>9j zmA`=YQhnd}9^{k7H+oJ;bDL?#e&(-jD}cu$i}`)PaHeJ!ukL2mPhMTLR|Ct0@vzS~ z4>N#h29K})=1PCvmn&iDPi2COnBE*y1)%ejyGi8`x&Rg0C}F^%@53H62HZD$~C6UjY) zv410dQlG>h5KUF*(s44B&MD0H(r)@;qXMtIz8t!f` zW__yoHA;Q}shE<}6qRtgwXsNh3Vp0ViTAuSQ1>Uu@ekyPYoeMT$Gd6b(h8(`s~0nw z^DZAzej^pFMu1I)qF3UZs^=e-HoyYsIW?&FsPG%r-FK^}2#M10@!Psf!iajSCG%XI z31YtKz`rYQtX^Eem7OB*#Re{VXC60KU~vzb@bYer=Hwkx{`lL96_CpZ-D|KDE|$^{ z7fVCO7fYt`YH8T`s>N%}+PjrsYB^2%`JvL&8bYk(vndMAsums&Lwe&0i_ zvRtZ{b>+B!)2>j9z&(gNuzs|n*TbV8b+O`=0M&7iW@B$1Yfh1^xaQINGMZPn6vi+X z1Yp8O8ts4jzmcviqY=O5O88##GnB<0lh)z%Dsm0Izv>|hBYMI&riwqq+cMU`jY*t# z4br^Y7g<>1NEQF?50(GvjS!vu9zGx<;WHO&yf<>=GMP4<_Oe_9Qa<(2D)5nqu<||B ztpo*;+X2oXe1mokl{#{*=6~ReESH3|Hg75NmdJT`p|k=RM6KB7>1#!^XPQ_)K>@s@ z^jEIcvBndkavRWs@C~WrI&WW{Poc!J2@UeC7FOGBnVgW=IG_he3lNBu&_4011OfCN&{}bO0d?DuZHYU~oDH5;YKq zARc8>5*1G-yavAovvNG zhE-Los#dL919H*su?VFEBllx?pN98BSofm!GK5R8p0Hc6-X(e7!O9%6iSYPAX!|b5 zT>N-&>>okPgQ$rMdyGbqwp@7GIYRZgO{a#x2y} zk1x(eG0cQm;xVHy5j#qP#C=X3=C=WI-T{C(0-@*HiB7IrWMFF%Qi)9n6}OZ28&S%m z(xH=#wb~Aj2hCqy+uI9EQ6kmcCcm?&1nU8{!~i_-||Go(=JciwkR=hLvaEv)$qiVaeuVjMu8H{5IFYmZa>tHeO>NktJ8F<5r1kw<_`sD3o&R;%n+~ z-=A~eE4Tz+4STVb`iL<1Z|I|-H_%5#_0j^T=3`}#A)1QLgX*|q>4;pZSAkZ%50nRH zgncV0EiJs*sR9B(Zw2A}GEE!MECv`FUXtsJ#6c|%T47)-Q8r00$@_7CZu6@8Upb4g z<)aiKaVk#vLH#qY1_pQJ{1^9wr*|9xMG)rC{Uq8)C+OGZvw&mf0ntbl&m?JvWJre& zmz!dPnya)zFR{<6x|r3fes4Cz1p+MSh;jd_3uqIYb=Ihc>Uprr1^pBSqRA*z=>H8g zoO5}p{rluygX4O z9l#DC=vhP-DeMn01aDd@Al1aN9rx2tfM z^@?4MziaIxI49du@}4nY71VjfLShO#Zbzv>8K9HM*8%K3`08O{=1)LlUa}9R>_aKA zh%+pVO>9*U_{w3%>3TG+^x5S5_j|k7bq;*4N@L=@Pn!dRiqkfYJ;Lg-M{e6Pa5X{k zvXAunUh(amH+v;^C`&~kd3X@ds0I!=8_#zS(JZoW+I0tL_n5MW@;u4&tUr&}z5iN1d9y~jy?^Sd_!yb3WsxIrDS za^$Uy3XD0E_e|?0>bH~2YWa+&@1LRxdc-m_MBq8m2&s?}fWBU*|`lN&1 z#Cg@rAQw}Plb$Nk1luf;Nvg!|_$|b5G=4w9Zx{SV4^|~c;&(BA!|?k#euMC98lpsYRt_cyb_U3~BL96it-n~|>bOSe!B=r%)de#f@ z45;8bya7s)SYtb*)juM=fsOLorIxyhSIdG+!AqGgYqCd8CtVo>8;;Qg-6d;=CP*ou z`wi?D-*l`{SpQ|AZl^SLtkW@#dj7>ysSV}JAB3Z9(#fdx3Gm7dx=t>yC(3F#@*c-% z-Cw7s1F^q~ z8)!zoP%>tv`qlg!so+nnTB&<=(G5+fRZA-6#w5DMFDO>OTE;|;wi33lQh-?@nw!Iy z234vmW`Syrsy!*|Yez}S|e_VxgfL^_7iMBsM)TdE>txWxmoLwrIQsBv~J2S{abz|LKJ0`;q z**9|kA=#3qA{ze9rokeZrpf?X&kn8twdo4Z+BnCQ+_iHI(u!tH#cQxhA5fvG*yI#9 z8zqzgNDXdF?n0;LRRORZwTrK=TnR5+!qykI%*(kk_O4aME0?rl7ZBKP*jin+GO#%% znAYW0O9IflDeOJ_E5LGC3t`*sL8ffTN5L+pclq3@@YZDvkA2T*%eB2}yI>n8MSP|o zx@_z~39<*an4R%C=It|J9bd4Hku`&!!&-jV_Mo`fZP>HC7_H6Y=k1$&y)O1O0o-x} zcme|O+wghB!k1d%~01(d-{Q7U4+-Ho>Q>Lul%%m7clPfkJaZ@k(gX-?h?R zAOc^u7AH#w3cRklxWP(Z(wkG;%ON=Ko>hM${P1Itg#wW8+c>1D9iSZRPh-0(%Am7DvQM%w~_W1T&3-Q2qjUZ!k;cnk9oriL_ss?tcq7sO)*#Muojw0*^b5)M}& z;3Ir=ZN?_?4kzGI(_cRtSzj3ahhI zAN7@qW4i(n8`uY);R^^q46GJ8DdtT#m9rgh;i$3NZD0{{H0$CeZrzW_XJ9jNucNLC zLn;-tOpVgWMIpew;L2FG8Q2$$FR|dwb#V6#(9<$7vzzV|u16tE8y}e2IihG14kfP^p-yvo7AX^HbPtQ`Ug$i?KLE8Q4hPPf6}r zw$&HSwgX?zkTpR|D>yqxCKHT_{+{@(-H6)}6Joyg$a90L>lYfq>HKA~fyMY!?1jeT z=#~ZVDXETn_RXDhY2O0s?*qUmg>#4YLB@JNBqPyA0zqduRkK3QZ z?UHw4H26IkINmHgP`H`vgRXbh zFQCzLpgkjeC$H#5;$s`&dq=$q`x0s)4BXd7Tw#hogqUEAYdwBxw0E|}vYzON-q66K z@zsm5;1^>~wS^)7t8J-BvlTc{fR;Y(O4$7}T9Q{sV+Jouf0}n6y_TXD!H?RDr%~wc zq%WxkHO0pHWA$jgQSYaRLo>o4+X*gxFS~3>DW3i5>{8ezDa{>|tIj=|tIi*jr=C3~ zzcg>m?9%+Bd44XvkZu)(^f91k#|YO-0`1azTR3p+D6lO|ve;J4H$Vny_<~}o$VNUW zGQf{Z2i)V(#zqjk2A15W@YW3MKE%;lItcCF>c#kbI`A}>-G_F6-HJWGRPh-YD6Om2 z!J~6IJWm+F6KY*3U~YCspA>^5WPm*5aGU@`+d5`si#)JB3BFFhOa5GAIig8Fm^$tf%N_g5)XeDvd5Qkn; z#$+f`QA~U*WZsW_C)@QUxbZQt9%wDKx);7vy-|3l(K6tj>JM+#zfN;jfg%unY+#?Z z5e-7~Du~14k?VmG9|2=5u&RUgA7v0kjK}Y6I}ZE#MLFCr%Zm!m9kW&7E{bkvY2L-x zeFPh?L}5Pdj)&d1weS<#iSN8355w*YOTmqkV5b{8OX2Da13M;D|9{>Z%Z5NJJ`B5x z8>=+U?EuW}r-0)R$wIR*Cb%NFx>#D8M>Ih+_$#;5%%}M;hm?m@FD_I!3t7kIl-h!H z1A9qUdZZdca)imZzegYJgB;k${c@OPCJqUx;6BO zfh|ROKYC7H2^FJRr#tfWMIPMcGz(+xfId{bnHLQhZo}EFJ(jtAgzdHY)aPU645?@i zjadrL?0e=+!kE)c8zI92fW+nmq34GoY?({rJx~tXWS5HOh9EW`r3P2MKNq8e`I-nH zssZJcrVqx8_Wc;}V%S{5g6_bQ&?6;MF2|9s_)f9GXtkw)URRR-oDp1}h`Jv2C6=FX>Z%4Jw$L{qLsy=F*x9~>@@nhIL02BiznM^ih}bHpdRGA2lfW%p`CK<~AD}CzQm!@( z=B-`lJo)ALQ76Craul8K)Q=u7BKU6UV9btfk{06tQXR-xpbo#i+d$VyUwOmUwMC? zmouA6{x7eHQ)CiqbP0yX@B+g-~%q6)9J5eKyht-gqmN@NH%A*2y& z0mC_j0z`(;w+QL5p2ac;LcwAYLSG^jD%K+O&$c*lT*G0WGFehVf-J8s5)wzkVI%mE zG!Dhmi`cg-;N^Zj>a69ZQjhHf9NAbAW7*r_1V>0wRe)wJ;3$Y?ui<_?z)X;APmg4O zcc)0(_*yC)NP)z&0Y0)C`3dV4es>$ovf8Wa>9+7C|NEHsY4zFCYe;!Qw$w*eDJQD8 zFosd24aC>%mr-)A`{gXa0(wqABwEq|Lt4C`>*XHtpM%eIrBRe#M5_DUv|7_j2V9X? z^E#*>2u_N9a*G4~7z@4qSoU~3sMnOxaqQkr2xk^0Qwon+MDy ztY6}bW%0ZO!T5MaEc;ZBf_wo{3)CyIZ6UY^ATAK*Bj}@q_HmGCq0;ku?6IC{{1K(o zX?Yv!C{xo-*^lrB9aPa%68b3h-HrNk46$smzrK4>ALA>!V4Q*ao<)7TZq;{zf1&*c z^AYtmdphddYyB3rq5Lbs=2U-MGtt&2&jo{4iW~a594hEGW#C>uTgs4oWyi8fsFCK7 zh#Eg?72-x`#j*!v;EE?rP{U7#rk8G0RMqFQCIxgddc3zhfcNU>;HfD)Bf~C4XQ)_~ z=%0suy)=rk%o9j#b$)N$&nqiOEBD~_qoW3-O?8`s zQb=Z@B_J(Td5=zc9=Hyg7X^J}x*;hP9JVlTvC23R* zbjfshLX+&W9>1NF;G1Eba2OI_BHjNg;m#&_dgvi0#+-#_V^X=SkAy8;gfup>P8|BG zwFfN6H^`x>E9x|E)%Ca`*|OPk#3r~^7KLhuk8FR4zH9v7=^Ldf8i(4Fz=t0q_EVtI zq((sMDl|2r4&3;mfG!o#nXI-7_~M}21@q_5?*o53twIYrCsFBNI7@9?VfPEtwk9eA z=_B_!)wjOyM}IaTZ6|nSqCC_tdXC%>^z>_YV=cmOjsKU<7bC_;NWE?9=1;?;v6_`j zH8ya5R1e4lQ-awFH_ld&X^3Sp?eza!ndTyvg4pcB%ctKdQB9MW0m?2x74)% z1t6YzMN4g7Blo&(N9>-QSlGi6B{TBv!1pF^QGO#l?tX_m>2&D^zFxyApYU#t*LVPT z5WJ+HJ$#+FFqEXX(9J~Wj3K$P?2M;=VJz;WP?xU}zR{NzUT~`cgCOP_ggC)`{K{SC zqPEmZ&HI|1(xjsCRb#(EuZEgG1|1Lsom#!D$z!4CRSJ6`#Jzn?YQ#Bjd5ye?c3~$@ z6_oNfcLx4mg&oeKLZTmDaEsM+V+%O2LcRqFF-AF;A1#{?sJ65hpZ-LV$y>$3Jdc#MZ^L=598 z-*zjQn9{z!PE!p}umyGbJix28 zd1@O;OVPX&;>W}474_IuMg0Qqqo|TCmUbyYg+-FY4POLX*R=C>(zf1O~Sk= z0@Tz71#0k@X$(Et2WT%MS-x2C1w{*;lEe|y1x>Xj|LYiGkl{yF)f2f}AUmM065Ya( z&arvdv|5xiRw;)@Rp{L)b#i7)N1gPh#TbV=r%7kQ*%Zvit4)iAII1_xusC-}e!f$= zBlP2GX2%=^u8xD8((3iK-5^grzG2U5*g>v|&lD2Bl?~;ghplGGtcs61JQ+CBVjEWY zE%xPaW!;e%E{m#@I8oB6N>izQ>09c(bkI~|^{lrqpgCC#|NO41M&Y1*&rO zE1H+ImET?o9oq@11f;slrz1*b9V;9#`i5C4^CgafTtM;8)hHt z(mTR8p-V6nd(22YHMHLxfesm-gLo`A6uRuQ!f~LF4_V0@aLTD8tHog#VLN)5BX{11 z3HO~9!Ap2&epuQeYt!SWWn+2HH$TsR!Mf~J&I0I0iWhAq!PcwAle?t#p8feXZBRm+ z?mDDTEwg9uv_5?5=fc^A8?4hC#H44fe``?1O~{)4IJA**pBw~CxxXPZOE4y;<;_+# ziOEfmi|`XfLbq|#KCwz7-P#4&^uUQuna5m7S1E*ZAt8>ms zpg4G7KC9+&D&0H$JW>g*Jpo#KqAr!gpCWa%;Pq2A;5s*W;^r63e-qkxT6f?OJJt}j z7{n@C{{io}y=PZB&9gh;F)et(8gc6M6=A1we%|~V%mb}k9XWlh?r`?luHP67jkC3q z-5Jwx`pR8@Nl|+(SjfE=BK9r}g07$zJ@lw^|209FkKKsk9%_w`X>z`^dL0u3-+5d} z{HZ|;-&W#AvLz;Nj)Z5_FjnXNhTrGeU#=n=8u<4_;gQ0U+I`mb(#lgUt3?aT75Xo7 zJT|Xx{)Yn|KMUW_EBi|8tu2oWY>RylaHNT>r?f z3bQP*UKIxm*Hl62IESQq2(x-cWlLkPiCUj)xW^bX2k?si9HsUkCbm+!s~V163ks^o zYJ24RCi|WR-^#`sx+^ZW-&n9|Y|*K~k8X$j&*{+XwzR8bhIURHI{S-jn&5tIfv!g2 z#}l)+TF0MiE?ffqfc*jBM;h=WBWsBtKU$&pFtR}cewfpi5`K(q0e*1nS?eI{4Xe#G zAJzjq>VX{*QkMZot_22$HR=axs1IgD^wRWQ<i_1s7)xGk{l5$6z$y}zzrdoePD9XIBGaZMdeeK^ZmoL1@- zj88h3ETEZ;R*Ku#Yus&Ow}aKRk}oGO&}+BC64XRmg40*_U} zG^_JQp(;*&bD3FvQ@`{^?vlp^91g{6709iEr6AeP-L6Ak|&=l-ezVta~Sr8Xyy{aW_ z(WL-e`neTsN%mt)oLhla$Nuo`Sv|8pB`xXE8n-BZ8fuwmy_!0>Bu1(8$TgkN>{OvQ z-ijJ~O|3oUq_#jGE0X9wqJ=G>e>I>ShvB&!;r{p?3QCbYpp?}1KueRL^&upYj$060 zNxG~9G15!n%^)r~u1vl=_ZaeMZk81#NLO8V`%ct#%_2JpoxuG!!?)Glxt+2)Wn%A( z6b6z-JF#5YsFM<5!#g4~oN3wxj6eBCxf^=aLLxMPQ8sCjXp+k0Vd62_BGUILiT;v2 zNdwl?Mm$Y;;L$c|Yuz6=^d(C^JbdGk7hx~L6kPk4 zFHx`r8_wQ4@QfH})OzsM6{Kh!;*z4$ipJ@o zCp9d!Gy0;lsE2Kuj*^~%ZoM97@BX~3VJ7%#liDa%YOg&gJCaJ?L?uU3$(vAeFiKVl zG0ccNb67iO25`RUY}!jsKBUyfV10(lR|C@N&~t%|DLuRnvW9^>NA$Pm=F3abTT8CF z9Ia9H=rK_=lC9Sc$VMWk{?JswMZP?SO`=`r3?PI3v_yU5X}P}%UM0?6m^Gvbmg17c zA=Kw&* zU{#lJ?3!yjq}w{PN>6Z>JvQ359{x3=a=O)v)jMGkUnx_IGCyt;u*X3Qi~lWxj7AO0 zMcYl(f23(d9vvZ*jGOXSoS&%e`a@(3ci1H2VEqU!vAdJ1>yJuTHen|ZnRQ^R`#N}+fYRU zD#FEllua;oW^K@H95$)8?zKB+ViKQ;r)ef8JP3=A_=P=vOQg^*vw?IQiw-@s=k~nq zeLFQzh4hnl)M3eWP`}^sk3x|fE5anKIFqpA;CJXG@{B~IP;}__EWhB#tVm$NfmZrP zT)$_bZL5ssgnut(;13OFowrNa?G#NYJ#w3q)`)VnQ~!Z>JY*NxxOPoO49kYjn>mN( zJmD4bA0S)a3s^l&TVR(TOF33R*7=Xkwad#=$_m7slDQ=FCYX_8u&UrF#al`X`1<=n z>7vqFF;OLTYfvSIHgu{}d>K_N6yVzd^S>6{f@|Sy@qUU4z9Ytl7|mb-)_X{MHXM6M zhfnZ>fcFPHC-6WfeTBBWp+2ms3+$mxtqVvuVV(I2_s)MhPB)9(<9LUS@n4bNvRAzV zQg{WWbt9k$_MEj-gBmtOM2)&>M8ANBXRW~vGge%T65+G=PY3O0>H^C_VA?osfoP;Q z(%cdj3Gu<_jA>e&NV~H#cMNQMQd)C?{*V#y(wg>%ti;gz)Pj1|i-_V961Ct-Zjc^4 zx20L5`xHDix|QBz9dtGkH~5#Mw3hC$$q~a=yAu~>f-g72ustehg?M))J0H=nAiUw; zgi8&oA?l`k`>Ua^6VU)!{}njV;_FREVu3g?2KperA>cCRBo+`&6JMZ||8-*`Bo{Ox zUC_UTGe|X9F!w7!N(-f3f#-3aMk8_BJV8QaEtKq)COlSU$(l~TL@l2m5FGBAmc9lk)i|8rz9%9>RO*m^t%bKEsC2E`9ZC*tDzv+hAQTi3)Fg+kQ zQM;hc$=j7c?Fwo58Lf_j1{u*b$G;X%G2|u2 zrCpdCxj6L)+8r#1E-Vz{%xSian8kIRV$nsISHMQoo}U*5)x{NrG{tq_y3lCTVvgmY z58ji_XlLSTjfWrvqThhIuogeJAr2H3I6zJ2y6GuXR)~Z9LBD0abs~JP7#hq4YwAV}2yeI_ejD$E z`2N2@tgKH;eOn9SFry!J8V6jMdvC)-dz4&4)8IYSLSsL|L)jr(Oi>{#n&$RP?B9^J z2fKcp&@`m3CQ7}Sd^HmcE=L?J40T%kiXY-mzI@PH5t+vBkh$=D2HKuR@OJN*3x>eH z(woi%sm3W9zjnq*Kf$}`51bC~{~2sn;2DZ1HvX=L!gzhdqWJIzBlKyPz_arc@HbO? z^UJ5T4Jp^}GapsFnQ>`K+UM3_?ui3L$hszju36fCq~5&3=pV@miJkw_FBAHO+%b|J zI7S-I$(Um_M!VrTo;1)8@I5p*OYBu`6Q$SS&)l%=C96_P478Tp98prtGD}i08!XeV zN%Sl2nL?j~mNIyYQ^TTHuN=+I^2apIC&ZYT&O>%u|DKIeQ^}5Fve9%*K7!{M9s?-t z{&8i-PSArj!H+~VY(yOM{3C~A8hK0?#2oNkShgaxpUTO*`NXx#<%2I z#xnU~JdfasLdmt33$x?vLg4=Z_pKjCKIQaMKZ;sW*##%j6#c?GJ#n z9?vDvI*p)4dKDRMq0m90lFH;?7ax-^i#4;$wOKzs2s4GL5Us{v(d|M)x*b2(g?htfPd(6`72{4C$%$73JC=}@qB#rmaduax`hJ7;#uGQwME)ZtDz+jT;GSFbh>e5@p$ z3Go{v5EBOf!@vnQafOQAgdeNjgc+;cgc-}-#zNu+5FNbaz(K&d7tcOCr}13ILppKB zBw!wFim74oxmr*+AJJ;l)M*X!UVY%a_~gV0AfqNkdU3?m%uo#sUE@69pIPDZ_juwiWk4sI5J;gOwS zkF!)=A%7`U$S3tDhU~CauMqmse19*8FchP&Cw%@Z1XG|lZv+gWmL>|lH_%QeeU_)q zADh1>|FeAU9GxVYG#j;$M~wkjCxzWt+%#`nX3m_krex`Xc|KPJVi#b)fSu{$Gjg(> zZu0Y?e=@Y3xJxN)ba5~=uAt$vgYHq`v)CO}J!WhQ%PS@iiIA~|CH;e2fU!Y=uk4Y6 zngXgx(^-hyG&W5hXiSq$!pH{gwIKCOIY^%^Jpzh3K-N?TKyoo6Jg|AZC?sA4MZZsv zaJT@;XLIpXd7vG#L6DWX;?-PRr^DT`m;{-%bV$N9c~9W?w48&OXm%EMEOW$0*%L{r zzxSa`b((Az6c{#*{nQco#-kbM<$YTmaP2xM9xA zLFftJ2ezENx96L2?{h{z4f}S+zjbA^e2N}!4AZufCKhZ2vB`*w$7v7##t=6Q-2Q*$ zMRFc4_^#k5D&b_z(EEUA2P30d26Xp(;diW0vso<({VeGDdZW;9bVCwq9t^*~+Rc;q zRLQ@Y?%mTf<5}BAtTT5Vh_ivya&3+3lpJ+j+?Xq=Du|aJ16hA@$HvQ{dLe#_VV4N_ohOgVTP;`GHCq0 z7FdCpHTF+Oz^k>F6fBBnpFvaYyGxs-$DJFbWzIa5Of*(t=63M+K4_bdw-Mcm0uF;N zZ@x45y$aZZABp+2fX^v;OgVNTI%Rj0x`1k~6KG$ejFk8T{*=vyxg+p=$=Ox<+>{KdX!zYkIpuKVEKWT6LDv8b? z>UupWMO}LnyuQ$m)N>!{z$h33E_j{LhsuDhD{hUaQYMNi`~dbFPaJe_FGjs2*G>|L zbg4Tfub|o(-aC=}SkMZPBCU7`FhcL?{#&bDiz5a5fzQ<$v6CDZ<{guF zC6U$G`XnRH3O?w1!4EqqUm@-rIX_Yy9Mms5k0=qBqxb!qo9{nX3u|sc>}NOq>evl< ztE0RMKKWdwX!il~Kh|du_~#)_pUU~UpUUfVi9evUc8y%S_+9Wdnj0hM<7*_oM*iVU zf$r2btd_8#f;IkkcV0B?Q;4NIFwxlXJ>(5S*dcg#sj8#c z>46bvz7HIFraCa>^k&SxG4+s^%+P}t7dMOM-cqNckKmayUit#~ra&c_pT+EW7HOZw zjLn8eDiP~I6?_3I-|;mSU-A5wnhjrgVqACN^ZHxgH)Ew1`u$e}PECqlCHlh#e4T|S z8xNf;h$0J@LSSc98=r_Z>Ea~q9>E+X{R?9f41c+`VygpsK+OWq9q)r8EYCICLSW7hd4QQ%+L*3twSZ<8zC&p9X^4q%WSg+LAGGAEgC#vlJ!zz`g-aRbGZ## zXTmmU(*&_NPjXI`d`TqU%dIj~1Eq4_x^lGdk2dWt@QVB^#!Ht2g)%&}_Q7^Npf7Nc z)W&qYy^OaRe8uy+$gl7H2xlYyS%mu`JO<%1gahGHw5(^FdOIl09TZN5o!qbn zRs2|oW)q0b4Jp9%ei-GQ&;ZiY?psVTeKXY6uz7MT&H@a7-8aUhEvL`}-kdu6UF@A= z3g$86y_P)`WAg@;C)>2!L*U<}qdbbA0?@63jP1 zVY^kM2)-`Cd$wJ>oyrVh3){|MJSu?~&*M4xr($C%e&XM2weN;Y`}oW*X_sUU%9 zfln1Zi}MP-P(nl$Tfx5wq6o`H;rKGZ8_>TQJspbhLr8T1wqx}wHE8Y`HcAtS_*idH z|Lcx$-lK#=HGp{^o@02v!~>j4)kr;nRiZfpGD)G3*Tp@Q5vM+^?mvj#>s;Vh(0CYa zWB8gL%D#hrJc?;Re#{NX^8`R5wpX{)+*V^C`G$gxYxwHo>4}FP$`0W?@8Rjo|3JJCbrojnVp*+0l9wAUy$bczC47-T;0*4Vah1Yc+;du^W-~z{4=<$YZ1ht8`6R^V)#UACh0|J3nHf}p$ z8shTWt-vCU7!Pl2dM31ofEuqu>r?SIj=$|_2;CV}0lCYXPCJJ}TC}IMZ+aBI*+B^g z2#_;osqI-@F3}1)c_{MT^n_HC>><(lmm8mTQvOamgEpm0G03lH(_#H{GGKkiV}rEI z6q^5ldS^ojtZ(*{bnvsa&(pt&dZx-V!xUIfp{1TEP#0d;i=I*`u$tQTIeO%C^v>t# z6R{7q^x1~bxnA&79-+` zfzGv63IO!0JxTs`H2(zTNAT>z6NQJt9w2E(WJ5Ee3rbD!Sa4fI@b~fv2Rh-diy)lc z9@xWpF2D@`btZL%*VPqura08)ID;WB-K0TWsHe7GQ~p)`aI`lrJskYUj@)C~VbMUK zH{#10GD9Kfr+f?9uGxXL6?bu6kfR;@cPIS*!>5L1KeYNCB6w&*1!%tQAv>`aqSg-@ zpl5|N-Tb9%x2sXYljxm#r?whWj}4vRZ4qNNq|Nb$zs>v5PO{-oHoW4oI)tzotPC>v zEo-oMuEE~9274#>**-21yPXcZe>qxBvUx&qu_X4&mPA-r_~rdMJ$`#XTGnR2P&aVE zpN{mjX!uwRZWdLlom0{tX)9^l4+(L#tO*Ul-P0EmLV*GFGFz9icM8>ltGfHO;JO>rUi(P|%uvsh`X8ed2HzY2#tf3Cnr zH@lF+vV}DVs=A}ULm-2f2uUSK;oI)TTLq;0PSly``JPt3RU=HD(#el=oU@TM5YUhmnL9tyxgWga9&=%MLSTq zUTi;qIe=(-2ny$va|A4K?%-CfB=Em7q_ObEz{Z8LR}Q9S{fT)^ zP)q@>JQK7Ng(tL;P9#IScw~h@5z8A54*xwN%x{>Go(obdxlh54?8CFdPAY-7n4clg|b-Ga1w3sy6$!x;$Od&BElW+PZ5k1 z2c6IhyBSy%#5O?IY;?Uu6V89zcz|dDyA|&*Fgw9UtSF ztwz3IRJV1H@7`dP#$nti;Y>~|^oBO2zvCNB-Oq3s2Fmms42$T$fo3t`JZ8vJ?(~;_ zEWqO+!I>$4CZEW?R1j|qX5accXLQMe?I;c>R!YEGgcItlkBywRHQ;35fLgt-nQfu> zt3Y{KV7F=#?!sXe%0_lfDfQTo={7I`ts=^&&;E`!=|F!?y{xni<1(%XZG0@%(63rAiNCR&8me&|n&S z%;F~8`p~Rhf-`ike+Dl=c%eT$S5{{8+pTc);-Ag4@O?OM$9Lej766yO0#_u@F&OhJ z6|?HYcB5@nCWYp=(ww8vTwZIkAErm@@0qa8dC!EmLH83JLF`H3U@&-~Fcyr0a~f!5Ay0@2rRZ z`~0VQPxGJFfjj5_L7GQ+fNx{MrPpfhpj1feeiJMqe*lX32}i&n)!FVuvz87AcbLxN zk*yJToB`=9mX+I#qom*I+Nx!iIn#Ms6}9T;b^knuyLrCh0Cv zxTD*FoC; z?Ch7Ix7%G)d{$Ew&W`P_fxf6Z`pxupEvJ4ME=BAJVbkS~Tl_}+hs|CcASd_IqlM&3^44?CNbahVv3aZ#wxa@2p- ztFPyEzDVm#UqBi#$YNXCI2;r~njG=&TIu7<5kkagcmDke^&8Rai5Q_TpeH57=V6s< zcm3iOdzWCfrM~_cXYmwx?1jyPa$!IU_IaY#;r9aZPvev^9^qXGFGV;V;kOYUi|{mr zYY*x zLb1M(&B4_)t{6KrG;W~}ry7gVGwWWSEX@QB6OS?4C-(#;SHx8}~+=&yo3X&{Y6;?OavO+0vhn_tlM?gM-_61cY z?8ErztsLc$9WCNN!bhD-Fh#N5o_L%;Q+Rm0$5ww|*2D7_!X`p;E%EksSn>KAOB4?J zi$t@i9Eu&X({eJ;^CH&wUm9ARRp13!L>=3TJGqp}g6ZcxQ+{s#mi(XdO>^KSf%}af ziT!+}s!v7~^dxcbvN2~)&3r0zphMd%q(;I1pJr4|p3pm}S;&NCwPD#(=sgeNKB}*v zZ_wPm6#5wF4V1pwf!gniVjr}M!#Yy@jyTI;$eqS*1sC=a+`9F}lS6#<7ZW7%B0EwQ zh?=+Znn_AC3i^kzPXPTy(yh9K9|?a)eRJqOt_MHUW2Gu?cQq52BK}Ws_S;=A;r{A0 z^rGw*oZw5M(&&xg>VdoGfVi39&hCZ$>(A&r;`9B8-`^*F272(1Tw&n14WScaU{@&w z*!O6A0yN^Sm~|^X!z4O$4##d4kTn*ZyP0jDIJ-!P`F#rQAX5uyCM1b>S z12`&zIRtiR10?;PE?MUaW1sw{&RhsNXW4EP=&l<#?YQfX#9enJ-4ZBw-E_l``@Bgy z)ba!F{Ey`paXG#Hu&QO`JQ+2oOhVWV=v7di$IuqCLA9mM0jc)q>VmK$5miV!5U*K- zPF1#!)XO$;m}aP!nL&qMcaS`hq6d}yLE!i>37Tx|pr?j&vmck~ms%CT)_zRo6Afw_ z9|&6Kk|AD#_57agt|vU(>dA)HE8sQ1S|6JgCsjck&LRe~OrIGydkK;l=Y@Yf5i*iA z;z*Z+@%O*cs55ZT$h%)?7V_z;u)7YH0$C!Yof2?MK)G?B7k?fYl8W)$3El*i^Pr#C zE#M!)Rd#;~JOR|=)}tJ`ci<)?3YKh%r(4E(x-Yfod7rTqD1qN@;LMVEPQ4cA}l0$KEcm5a$81Y$9=huN`U4cFF|Pw zrCJAxP-=Mu@0~a0ntJM)Zs2K%W`EBleFq68B?rl4-R=vzKZ$~0C#+%)!E^z0klx4R z{pps8y9Lt(C)Myb^h7uI6#hQ$)WJ_mJkA(PJOmAR8yuPsk!lR;hxv)Q8=Hnb41J?2aw>YU&7%otoA{hi!+K6Q?D8mM(ha#%ecjjx?oR$u z(O^`t$6|-|x_)(QC4HR;`*%I+_?;JK2vL^LyN4rRUmvZH4&$_aH4Ew&%u^U=5P-lUW>5i-1o+g;b)5%I7v z0!|0*`0pUqY)9gJRR!@P+g)$q{Q<}P`D(n+!22tBPlxx5ZR{RQzd^ZY%7uW@KAo6 zy8LY(dZbNNz6l|!eK=|#-7;&p$YV8TW8aW_f9Nq`%dg>=deg;?~Bih2hi1;Ju zh`widX!w-ya6f$4gGV6l&i_4by=*!;a`*!L#^(f#LsN{{I;7n5?TE(TlU0f!r7J5oV0mHVN2{P0ogD$h-uRzoFfuQB42k{6^FC2s5`v50J7weQr`<1uHMl35Wwg5 zxNruEF9v-p26ex1US`F_s|#XV+{9`0;QpUlJ*mVFiG;lt;r1043{@5JE-jCQ} zJodFU#Jlvk2J*LO)M1zkY$2J+F-7s2x3>6SC+x3a6B5@Dj4u(iKvD zS;#x*R^Bk=C2wqP?U4D27umQqW}6jfkzU=%mu0&v&SyouigmRo!%tT@3%`|A#)eABk+oTJnf^rCscC^m;a+ zK2l6HteQ!7@}wILYFo_~mv*#f-z8uVmw2|aktN0fD)u_^6YQ^Y*j4QMS|d*3xUYu< z+A(00nnkQRFAuFrm4InNDD!xX=n44nM!AkMD|$EtE&7MY2#ni%tJlgPQ%YyE%G2O+ z<8Dj%8Zs0(4)Mg*9hGvKO|t z*+p1(rqjUq9R$I*I2nv#KbJx;P1v5HV@F!^3invmtbf@B8~w(YiG9tuueAkF$4Ib% z$&!`@pnNskRXUNy>H7D6H6t#r`%Yny$bKrJQcl8tqWF>yHbKp{Nj#61EkcefkmC@F zv}kD{TkK2iLBCJ{&p|Ls`8_FLt!}>6TTnK@Y!$m|3G+9^0LgMWa%UK90hw7*P?x`goN(tsH{%b^7x2 zauer%!;(%2tO0=!1>c$Yn#$&{Jvx@8)^9lUkdsj{Gc-YP1Nu9j-}vfF zu#6@+uwFjhlFXsl!J!zuyJr?j%6$V%ejZnVJLu-=m4r_t?bK7#(S8rduUOoc%)r}C z{$}PQsA4VasASYujN0)01~24$Ex~uRSjFpF#_RIDM_=8)ECAl;d`aier^nFTm;wG) z2ev%ja^*ehqnSL%h4((c#O2v&9$vr(uyfqAP_cV!m03ZYPS=*I93U0DMB_X*9=PkU788y0P2`rBA`4Mbhl8c`j4G_-dT`PAT70gS10w)^66byf zVD(UDjn8%YfKul{UgtqxXItA86Um@^Ty=;Y!)(A(r4+}34($FMl2#rU-5HaIZ>1kL zBej)X#lE6I3VWUhpoIh*SwXNjeY?*0s1%OdPq+Mom(z`x^9I80u2#?i1aUQ`;%nQ} zEgN|%4NvtvYNKAt@--+xHsDX}FO8%N-T9y5HZ%Icl-Ob_N z2K*V_VgcO5_3^ke+s@176`}$D4oJ)FE_h@R0@zZl%)KBJqhkMBOB#6bgO#0i!!7*q zxgt>$t(_NT8Xvktx3VF2g6;=dsr%336B72%t(be3iq<~pKi_B-E5Iu2ab1;_n^5#_L#e}C-@wI zEM9<;^RxZQ(z}?CouK*LfmsJo8jaJ7C@qy;#IC-pM4?lRemdnV&>J+f=9MH%Zy@*n zTePUp^{PL25zoC~9jy_Tb>BeyzzRGjDrdJp_b;GwUPSKdJ90m@|2FO{+eMgq3A1l> z%femf<^CmK+*;XEdFk)MvgBV^wqc03vVc-$R~v}86qdMdKl)q62Hv7>e69?Ck9Fte zbX!{rId>uGynLegb{!G?+n_t@pmIc3yzVvz_2%WcU9A`yk;tQHnrrK!H>Rn%-G-y6 zgUWoxU*@aW%iQo=(iJj3LR`PBuIw$sj>+)|JqC<=0JizKXhqs11>pp2TTV}jjNCA~u})bVUaDJT6|QHk zh0lxLD)>26%DU{ChVVpKf^oZ&v5Q`V-xjwk34R-sD1}9cgFk7n*EQhKaX&q;V>!6v zqm^x-e>7BlG~T|og2nlJ@K4_33FtqXe{NSeA79uE^@XkgGulK*5{<=4v}0{}cOQ)&(QrDpl+p&D zmxYpV_`D3(yIqf={uH);Eu=?-Njmg8_qUbGW`pV^_;62xHr&5PUrr^w*+%19CVeX% zg#5#McshPxg@(f4xt2mYa%J*d{nkW4szbuNmA`jInN#sLg1@QpMp!(Qzg@(-IT>#Q z_}k^O2>7r`Wmh=Gqjl)3qUtF|#q#dh4MzL>r4#auZt1k0X2B$11n6Yz^}OOSSvpgc zZA@km?tO0eM{j?gR!)z#ZlgT+Kzc!SePwa#`*&lG-=@QTuJC;w`%AzMTHBUmH5lC@ z?4Z@k?fMR7SlP@{z80Zhx4|;s$Qu1iQ8H;lWT0d^|EIE_>>a&JngU}@`q$j9dY(7A zL}}G${yo&|I&)Z|9tf+Qw{~)`>+{1A9J{M*S{BVI4X^9)VP%Xe{HN2-kR~C#NI>2n zZ|x6W*G|aH)13Pi=QX+~AzdS-?;nSLB0<;=-ovjye~|HE=54BGFQ}R@_>Uo+g*-Xx zqS1PYw`d#A!S80$>5KLW4eSroTu5d1weLVmRA+hzy}p)HfL_-EKa?pPN`ZA*%ljNR zcCVwiU%5r&d0h|sQzrUTKDw6L^VhbFJ=`%O_iZ<#hv6R`BXZAn&gq$9TCaFZ2-L znIH#cf8j6Ni?YX}>{<`$C8*f&l14e%Li4Qij!BrOohzu`&ee#81fi8}Da)#>f}P(P zvRbdZrdDZ&lv*9Ru3MBjEuIm>uLU8g1wgJ5H*_DOBqt(#2YsRMVZRa&%?JHSg*GJ`buYdV#plKyGWA+R z@p*XxcyL79_2#tkr`Io{uc-cWJjKIUzo=JF^S5!gplCS+4COTU>XvIbEn?1KeHztr zk)IsHIL+;K{d_1{dI~$sAovsQTmr9QT<@ILX`BRWb?`GTCadBr56_T|mStHpxDUQ$ zX(@8Fxankg1@etLX6LD1KD;n%e&!U}XnYhWxiEI&j(&gl4rt!u&~)X{yw0J~`Jvf- zNWs;GXv?UUh40ZE*yYjjQCN<3m0F#HZ&nsvR_e#5Y5ZMPc3z%J{E%SU^=L;K&*RsW zbgX&G8P@Ge;qeK4MOQHmI2X#O%{r6<`&f-OHEjKLtkaMu21HbAZ{!l#6X<6Sm(=1y8ugQlP0XOMv)vb`tT`buzDgE?4IC%uu2*3r(0sD3r5AEAJ z_RSq__~Rf+FX3!=$7*vCGDat`4le-CoyKnp*5W4oDm0Pt6G3Q8>vc+5qk%^p^H#U~ z6DMr9YdCMgC-41}^ANz{uxH}@JPG`-CGAy^5w}2oFaoQ^b8Whtr&kdcKe>+RPr}k- zekRTbok25dC4bAp+cdl_XVOmpL5{`kk-k-_zaS}!2W*;WDXnUy*#E5Vt#;~egSWdkPPd}x+CTr#He^o17bQO z<_pAVU$C&BeJgF_6GrirN1nPaWjm)haouqQwJy-%L6 z)UaO+?x4etJ?-1Wgr^GB=MLZ(^ux4b2Wn7e(RS3F!nPOx_gVBB;!|0iokl=l_3Juj zQN6#6&Ucitj+b%n-^y5}#G@amSC;WNFCSBZ4Y@^MK_3i~>?dlrNIRO2kuZse| z&h47XbG%dB;OEy7SBmE7?G`QZLsMqI-J%qpYuUd+GnB`#T0<=o*(v}1fY+6MAR>cK z0Nr;4z&=C==T^fuB7L(1>pE6YUB=+f$^v>b~eFLsX84ga+*UHUWwc*oz4Z9ANij&ENRK45iy8taKdM|)jC2L{BzKMQDo zw+lM7@uU81c+YG@y}{~h>s4dYK9zd~l*&Ut1mD-c)1Ba_(N2CIhua0Kq!>A^oowrD zYgVa6NVG+lJkqwl`Atv*86J|Q9My7aSFkC7S=(vPh4wjUm0eg-L|wb<5Oz1R*6nfi z#F{v&j-Aph`odE+wDK=mXe2CtX3X=QaRF^ZPGUj!0`WzyD#yJs$Ty; zXZB%OhQ&fO8yHj&y`os+(iK^bESA`+X18&v4%#xAnb*8IxaC$MXrXA)dNoVIr9?3( zt!riX&ZKrB^M);AY4t&|b7q+3_kPY9l-u{~_Ye5#>oDhh_VxKZ+vj-_o2X>$eLd*{jdcwm27uGlJvhz#wu|0dcReLz|L^(`DkAb`wM6< z6%vhAzDrlqIM59){^I@R-<~tE0RwvX?ybEaV{r)3RptFSmw^_-cpUKODLgeAkJRvZ z-1Na~Wu}hMuupgI&P{;4iccv;n|A?sY-=}lX!uWePefT;yIev``_+|6^uJ2$CF1OB zjP1oz19?~h$+$mPr-jD}4r5}@J4^FSe5eymkcrvMas-82LegBU0H5Rwsd)_n^X0=& zsO$fUr76mK$VC}J=@76=s>dh&5Khbd>8R%ye?-S;7W4VFmd|191OB<$UQlJc`3cnM zlm1D4vwSM2@}>Az^B)Q4cO&QiD>*4o+}W%BYCyY?zSf8JQly+>CitjAs)(Re&=gTv z4bAm?!gRyyplXdpk?ehCB-Pp4)Ife+j^@%iL^cT8AkWDb8j$KgAsaMHEkS)6fAO6a z-=5=GMn>}WQCgymBiZ*TqkE4$g>rWythGnjBM5sNVgKq8HVa{IA?)KGVN((I8p00t z2%FUK3TAM5@Z}=h|Ay4$evAasB6$tTVz#heHhi~U)(>9~TUn6sw5^woas2uXD5E5t zZfJvDbV1%zYe-;QL*)D9dEiHp@S~@eb0cv-_%)c76n_H4y@`}nB?;^sCFM#b<$!R? zh=#=_En-EO%g3|DOEJdmWGDf0qhduOnJqkxnxn(%FYZ@sHlb#RQr>)}ydZ8PQxCq| zul67UJussOrf?4|-+dwL(342~n(!O--9tsNP}3I4&V+M*yq`1>BUyatTiJmVhc~;0 z&x!xfO+||wA!ofdZK_~#w;)8rmZOC>=vET1{~qM}DoDJD`+cjulYFbY4#LOJ8E7F= zZVh`BX(N=j-m0{<`HDOW_5?r&r&bmg7r~BLnuZ{CWYc=wUxCkU<>owDqNpxQU_S?G zG&Fp+Fb=gn8*cO5{ol%aD|ld8Cdj2$=mwdCcZ=gyhAt;H{w(7OIt zIDSt!{~O4ktmJ=5$=?)?f4xaveHyGj9;=TFuRbmI&vR(Uj&QmcnzDs8_&yCjggUYT zX$8tAsG>z*4$F~-pj3EhDQ@7c6=_99SNWue;lrXA8`2eBqYT74fnIEdJS_}S zZVUG`Nrl#RJ}D|-?)XSsqMiempfnoig-;rQ`#h6zAK+e`LVoFcZwV}MWuGZ7CdhAU zdR{2OO&2=lj^KvabLVV1CT0xrDKV8nNrRGo(szD7#aj8PT&e{<4M=wjMpXt?&^@YO ze~=ArUEEdcG1Bf22v!hug+B2IDxMdRKK_6>0|t9HZ@>rt0|_+;>*?&_EQE!}Y=BiM z({$muP$|HZE4<6}V!OSt1f$W7$S?RvX0X!}vxRU!pR@q8Fs{?Eqx-CR9(+?e6E`bZ z#HaEGEwv#at@(g>wOg?6b3mIkf?ipSr*j9^{5!y_un(NrBYi-rAAU8Ht{AB7ami+!b(lr8MVm`?ZaQBpmRRD?}y&#%EQ z{6VAkv=yme2&bk!Sl~YZIp>caTIHPSI7T3WE%DPHd|fH!CWW&cka*14D@Z>H^!tX& zT3}|QEiE{=6PW1l4f~+e!l%MZNYlsfDKNq2Z=QP+8*Dk>PAlSl*jm6nye6V73_U0d zpLDK^=m*Q5n2k{#vlS`lYr?I7@LZ0m;|uNA=qF}12KM#Ly%_ul;`BN!!|xSmgFN~9 zUF@GNv_r?uE*bx~*~Ob=|A%A`F-h1Y2ZwEv1FUWfQ!dN7lj; zUq!ZXD@N`?MK1^U0nw7oSE&axuwps3bEVp%YK4EH?vZSyi9{O2xO~#B{&LXcmn6NH z=zX6Ae=fk8zux|hGWvf8uPrDIhl~&WJEXoDrM5JYC-S3^6dKvxSFq@S6se3*f4?fJ z^-13-H1Mlo4pu<&H&VMgfV0N3Uqi&1xDj)*&ueP>$FDR6X6KH?sE#mPNEcf9fO5+Q(O9 z5&`KEr4K8+h?`a2)K~)P!?F!c;8oRP)*|qjyIYf~)U;$-cZ)76`eg&AY)-^%6$%;lT}C z3RJlWxo{)@BuYIEOa%V zF%83ca&^_t$FA~8W!~G9Ka*2IbNi$`*bAWF`@NsZX&khAL<4&+09!|}))J$nzTJB> zO1(cwVV}u1%vpzW?h4*agyViF&eG4IrG}gDO8986nlcd~|5PbDP(F9SV^%4k;IIIl zwn6Ew1GG8~?0bJus#fy(y@Xjo2M$sopL9L62x3_RJeJcgOi*|NJbS1d`kqVaYz79Y ztOBi)j=PfXAK(`7>>i{W5l%M=oW5a@QAR*UX;aSdfK=HuA38x3aSqb{e51$S?Y8ws zZScZJVo;J4Ea4LB2}uiQ4 z3Ob!h{_m4cAkQtGukO?cZzwC|=oJYf?mQlt#D-YZ6YF=`BgAaHPdE%O_kCoui$A|Q z;%hk(xT3{N>lD-g-t}JEhqOWm33HXY~lsr;+rh%)VoscceMeZ3g zNi)Cq*u}EqDtY8}A~0n2w0a1!xA$m6-vhHsNRubBX$tO1e*<2@2<*HSz#{2BFVP@N zl=jnY*#!7!)l|^k-~={bCVE7t&?9%EOsjGh1*A?u3$OH3=uXJo>Fo$sOAfnX<(~`3 z&*9Q}*1MeaD*RGy4`}nX0%0y;4FBAD``frJiSkld&w4k`5Ur_hI0=l+ly z5|r9ZKo2E1i~e>Bkj)OZeok73_v$m&&QufV8+0bfCaPi5E1 zOAE$zE_w%}Z2sF1WXI2|-2dm;56j+AIT6;9zB)J0Zoo|6()qq3jZdYsCy0seWVmx5K0r+~%;e!#Jx!&*u_dolz&E(ao#ldAPB;3LSE z1mA#N(nAVlgA}}x&Yl&3%qxMPb)SKQfhiC7$Fp-m;y0XG~n$M6er+C%Kk|IYE=#One(KX=ou*4d9fS=N5s|G$*jhIH_BKdnPardEZmcJc3rF zr#u_E%Yp|w%rR|Oq@V#QbAL>=jxFo@i$d#JSPnEa=D$jo7g|Aw#j_2;B$*#dWn>F? zqlCiXM+!gtH%~zN;(#hgSlp?BPLmI|DhS@*vmKh?2MI{Q5RqrQXTAEg|S$b777I)^Awdj|2H<7&P zQ(zT)GyRbNQ@OR!GAhSxlWukn`)Fkxcs95zuwG5G=?W#11bH9HIJ{D?AWmB8cF_X+u?By` znL}fATwaG&HX~38zC%3xuO+Y|xgxw4;}pJwU;2+iOHr&6mg4P( zKsRUZanx}@pCFciZjd$>Hl3F}7*#~`if>blN*_6>SV*eplp?07j z{DFb3!g!{3-5MUDa=)%k)!#M7#JG!nrb}NNe?OTm2t~OV>3M$EZthsDg%4X>K-#&# z8v^4#$p^Tn0(tN)Xmz=t8}hf#@!M>|n4&?1qksmyrE}CaO1%xc@kWfU7dmCU-C7k> zb6B3Jg{~u@awhW5!Wg^j2wKpZFT!e|Ie#$-%*zVz^MzP1HZI)+oPn#L^^y(yHn4x^ zr?t|KwGxM~yHLiuI$AGk?x!esW)gbHWtf`4r4^`$*~0ZmYxdLHxvF37m)wV@VDC8b z+=+8=@kOHRrsgcf_fhawa==?Whi4o3kTRZ3@L9+Yw2Xad0^a#B_${?~cj0#(9y){R ztnJ=gS9f`epY~SPp6bZ(;&I6ak=SMVS39(u}U7fap^MNm@+2S94JMmvRQ(h4B4KIKh7k zZ&bpIaIz2-yi4YVqp}-(l~UkCy!j|@Ed{05l{6#6Y4YTwkTX-+w}s1Cr^F8o$7dnF zPKp0>IR44~tys75tg?$Z(MS2U*dgl_&G}aO7{XU}UF9{e!tA7=B!Z*{r7vBu?|YOl zMSa%=iMIDjUt;Bt?K}hB0U7+;#`7S<% z^yYog{W_{(ez;H2sKUHlfoC5D)pwr7h62*7N<9bQtr)wykzidZ`nl6bx<_OSEpEA~ zBM}hUW>HRL3+6Z`9=_1J`C0`?y-P_=tAA6$h2vLe{0Vr?A`9HQ1Js(87;}}X_Dc^o z671BoZ9QPzbU@-Pl;-pWr6kB1?$0ExS1#jkolD<_?yGjHNHPJvZ0^vS!9h0@9+1h! zv%=7)_zg&p9iWlCr861&V7iXke3$eT#@KAK3)3FmkNuUTSpAlP8LWb*6LlU_P$%s= zr-B2jVTr(MXpR#a0bOfptRU~P7Wd_WWnJ*$J2R953d}~m2}xrhFC#wYSnMqhdy@87 zHO{=}>KXK1n4xr<*frTU-jT3WEUGiz5%0fT(Kr0JEC@w;hdZuiBr z0HneyuCxW?rt*i?Iu{?z2c1J0>LgI0OFDO5!A1Sjqe^?8^%a9lvJTQ&@d{1jmmEsm zUtw=Zqww|(&`+i_je~TJN~Ur4OSj_0aiPW<1>06@%scq~96IO7ca5%N9j|2x{yJ#i zFB9}`qEoE(Q-L+D3faoM(jJ*Gxr6nu;uJENTIFi4RUT`NhrE~8#;5qEJ4Y8iu#Mz` zy?PgX1K_#eMI2p&xdnGATi~-Jo*97!5cH|$h?9E}w$pPmdm9&DF5Lkr35~}o#YPs@ zg`0h7@7+a&%~+Vx>jtiPFKpWt36p$lE@JM9t^keuIINQBVOI@SLGW7-{xkgFRO;D9 ze_>H`Sv>nX5YJu?X%QM-rDyxV?_Mfc0i#BHiEG61AE6CT2oh%){iSnf2)$A%)sF9cZ?{RzLc5n&k! z`@Tom+5>>=+`u9odlV4OiM>N-U3HHXi;ycBVZ?LjF3Ab*i=O=!+_It-KT@PN0 zS1R|aoaR-~pS(KD)Dk)|w<-A{BWd!7!!l#3_bR*3wgh7wBh&TooHeFucu2RB&X}|%}Ab1fycpsW07Iw27kY-`;=~+$i z*?!=F5A;hOtV^se&`w5KrJb~l^?+Bp1K-MZuc>Kd>2jE6)UuEKgq_LKF;HZu!?ZW< z#x>A74oY$0PA{&cchW4Y@b_Zvv3RLNDQ&;v^;4TuKElVFNbT*|YDw}R-5}j>i zvlKepFMZfRw;~sJX6(ooR$$~TGN=ozy=8dU_n3uu!}V|cKyAmH!1$gnieQ(nP@R6M z2K)i9v{zOk%#(mHi^1zW`UBBc^B_NsV6Q21ZNId#L6O@6%HsYi8>vwEe(C8eJcvr1 z|3~vllCVmCL!++s-!Psk?Y*o=Y)v?}6{Al)x|?v$HDCP3rAgy1*0>Upa*B{5auvn- zm2yp7w!p8il;4Oe7BuT8q4m?QXbJeGu}bUjl0WKe8l-ChrnZ}4*~bd)Lw&}5B4Dw( z$o1DAeNI+#jm8YS0Dp-4YrqcYVs3L|pU3Dtua}vylHtV*nr+>%$atln{lY85$WDhb zKg50L$K7c3W%ZW~;&-a_zVemGgH}Ju%EA841ZhJg()13w4LySD2%`ULdhFzQ= zurFrg99oRM^8@w;?HxLwj^X_WgeO7{*MhU_2Rv4sRbvq@0;kNzJMD#CKCO^5C%P(* zX+k84ub#6OvRi+U^zJxC?+%t^SzYj-KURnFj79sYZ#slN7i^;qMv}sMCF_#@igPN51}OQI%#zMz==93qc~W?vU0X_QLXB8c1dCn3L+(?kEc*SxmLLYFtDw=oB;GhWyNOdxK3&3nkybvIQET;@{hqisb7cL@t5p- zMqx#l2<6SvAnn@>9Fg{KtI*9}VSAy~+L z=5}feyznKz*Up18HLYmS4b(!|T2rX?9qo4)cc*w07H~^3<_r7_>xsWN2;)6Xf$`Pt zREt--UTOKGJLjNfJX-pQ($WWa&TLD=c)g6dS|Sa?9E7B}pomk;hS4cgxNom3J6qdo z8KcP<_j}^5?hz@3{IRW~S{Mk+VZCLORhCBjIs2-E|AzI7MBp}4$m%=p>uO`NXBj(m z#`DlLOcTDJWuHB3_Up61pKX6YK#Oni+YWYn7$UDis(&Hs*BJDg?suF$tBz%tVta60 zXXH+k(q^dgfTE0NgK?Yph@uggf>EF{FLhNnw9Rom@Fip#(U{u@U~#W|Zmme!n5p(@ zV@ox1$Wm9=ImHI$e!y2ho^yDzvOXW*j9-%NkiBg3NllRI-7XU>(K!zdo@s-nWm!7Z zwI6;BCg5#<*OZ1klWFzsfs~Q#T(4=cltBJ3pG7UnSPiNr>t|r2x%;b2dZ9rL_emo@ zAo_ysGYHGz{o;CIcBMx!4em+g2AnzC%83l_AMJ^Z1Ic8WSSuBN48uKefMJM!C}Q zP8tYb$hJLJw1d+80v<>$N(gmPPZoHnA6vrd8j$}yT5`2V7Y;=zGuIgGo;l~CH$@u7 zSoZ_UXhyl;RDR9w{>rc3O(RNsxh3dqr#G7UEm!hC*p41xMBhhUOFBz;{iPk&U^9=y zzs#HBd3gK%5&4PI{|VH`)pl$<^dl^}Qpw;@Tq$dIyDXi=c(%bthAbV0$4r_B%zwiJ zWmHyExU9qSELd6H{7_o^n`HzA6Ne8+S=7eTD`h3Yn=bB}$}`JUzDLP_)h`}m@Mo5q z`R?zLQLxpSG0mMzexM#$|CnY6*|~Y{TpITrs7S5*24cb^8!4C8tK&Z; zJpSWAQRlE}%H7x~_~`uhTs*s%b8z#x)!Ybf7&i>!sDbXDq&D%DNhh0MQ2HXA(4_lA$tO{S8bAY3Fba6E{A$bm! zbr6;`2tu9&j4#7TmIU4HfX?u^b_{2WESWJc|G>N?&lx1RO1#qRu<5(E^n>=j@Cepw zi^>&c(`kzaKfrbuJ*eHz=lc z%_rmv?u5L-I(3rbv-W1oAkgonpyNwn=eQJF>dkM?bjAQ|AEne! zYinTU#4Gg_D)lT^>dD=O6(_=@QnH@K!*)EMd_wNTdlb0$M5Rg6uQ)SdODBbBG_sqd zT4AcTsy2bOinlqktyE{-{21;u4>I8%;u)L-WLGJ94mj1NgM^sn$tv$xdTZoe`D zKf=x>ja=w#pTfL3@vs|Xf=_9q5_Vm99c{;ajqChvr;6u{>--sSgy)Rw{1I=2uZ-(# z+ZlOle9@O@)jdQ|zuNa-s_dxZr}Mp*+1Itj1RAtD9pJm ztqxV3wKGjP%&deh39USv25O_1f`1Iz6={ES7LCIo&^0-zw-66e5#-OekuzuWY3mdX zeWD!pa=*7dUQ(!f)+~g7uJd zU&zj-8U)@!{;+h9yX4dym)t)GR*r1YQ}<iFP_Ks zHwu3OPl-1@-Fu6uyU8YQ@FrQg6g^Av_8kH`)jVLqa=ABnPpOVy;HgcQtSvU+j_9+p zu7W&u9znmI@JnnE$O~Q!;u__f;7LdWe?Z2;@$MZcGwB&_kmR0H7RLt2S)#F+sI^3B zrrHI51n5z(aqxK$dAw^uSr_nd>Dl}2r`Gl@mF<~Rp5f}V4<#<)(z-mK?lz=f-;(sq zX>oVM7Qk>zQ5+i@bT$x<633QynTl+T%b_szN6R&6g_hm$@&(`H)5Uho6U=Z!PuiA~ zy$^g2jLxjSoO@~mpUSrx1{+#t>`p^_LQ*qk_;*kCA#QNTH-^ENS}8x*^!aW>hOR|J z*1IzkmzZE>-8o?z`qky>^Gvs2P_pq&>9#hh>86N0{5f+?SyihJ_YAMTMmTty|CQdl zFIufJ2XIxH7d^WNR;c-unG5Wg74rTKI&?hO--S8k2b#|7wf{YbIdb120~S0)X&t|j zx193qebf?jce(xhKZUcAWd?p+V4F$(H0@K{t|_XX69<{231MFxJ9dj2+A@dwgVD=e zo2z$&56$KE@c2$X$hrQU($Yb={m0AdTA~^z1kKXaS9t>WeC)H|*47K2C)C!WUH<$~f)kVDoL;%yTnW$f>rB$Em&WiCv-- z_JHeIV=$cLz@g9=qt;9VtCa0aW-Y+3QSO*qPZOL_?0QdF1&<2ke}l7|-qy(cEo|nC zSo4{vp)-)RL??~rm}1y26m9> z+@DjfwsJIb6e{g}BDhMi)DjEX3Y8QEZL%^&`+@MDSf&re!G=qB>z7~`ty6A!acrGS z2MXiH%tT?NxT*cGC6DYrCE}j3?QLL>lgnXECX?E{BlitAwL0Ddzf%>D<8E3UJM4uI z4z?2Q%VB3+E1_XWDXJ)itFj%vtN6J+fP3%cJs^(Vsib?}MeT`WbCs{u@~@yt)F8t9 z-AWrm-|&sc-&cK)18%(N{Wml-oilK!6k#_hqu_OYA}7?|C5%F;aqKya8eo98Qyf;N z$N3S*7J0p594l8!84fKCf)P${14?_!SAagJb&Z$-JPn~yO8sf&*@{Fsj@kXDdeE)+ zWGx{pUU$P|+->b60dM{-Z@VrIJpIgieR!0N?cBg|?UxtqdnTdX44;A4hLK|ZGx~PD zoqjJZ$QFur1K+?s58j^j6xInhf>u?Ab+68;Do{bIlE2NcX2LFHGGo9i{ z@xs}3Wi|Bn#4?m={mEa=T2}@J<$*3G!fBn0L0S0^} zkA%(ff6H%x+KXcwvE~YZi_vO)fv^!bmjZiT$}TaZmrTrhDwYjbHM?Zb3wT6lFsLG_w|{3)|~yfoLZZP z8xL{NyP>n3-{n86=A&FwmG`^DBezI~-ZLOZe~jFkuI`b8y*kLZ)qRkKafz23%bYW8 z*iF;DIeS!{fHvL2)wN5db8+P9hjjp-+T)hlEy>lNtUS&fPozB(6Ex?L&Ky0vyNSa*KH%#wzBn}yWg70^`Ax1@uraUQlRe;+4F6?bDu$64sK)=DEzOKb=vH6)YG^> z>{sBSa_VZTU_~96qAo}j%Z$JS4js#pJit6(*nY3ai)i)Wkn3qPT6h0C7wbFMaz@tU-zBj*iE}Fc zTGK}equ97>gjedWk^UOtmD+2hzeaea<{Ig*5njn(BmFhPE4lwY{fk&(Gz!%JsT|?h z;~8(*W76gAHg3%|HEqb%9e*R~f%97Zc&6bCxg5sx7IVZO;&PaV%TeOin%5ZqJKxnf zOGLyq{yKIbO|%O-ctTa{IC9|Je_)pv zPa>W)JQMLu$FmsE5j=Hxh(28fj1OKA)2F)=77iU;>?Uo4q2Sw&Zs7)G;l7X|=eNWy z^$~+(-F(*UjA!L3@IcHPF1DtD5=cQ`U+_^H&i-2>2P*TygXWIV2=X%YbK>gyi1ZjG z*HU>(TxTnJolOH*c)FM3Is4CvT>3AbjC>B-HB(abm#=dYy_-4KJov+wO}I}sI^&RM z6K<0Y&1ir`;LCO)|2ml;Jao_(?pYb1xBQ$qG?~ifvp#OO2#4EE->QE0VuaU0eaueI z7Anw_m0t4JbB8D8UA-(uaRUvPqvodzpU9>2Y{GX^J8+!w9#co8ezx7P(O6XmyyZK| z6dYVscW|q0hAk#Dw|0+_kv$FOp|62O@U?=kpFCS3$-w%^ygUz?$C@;z^F~`6!fA)PTA2npR?;^aqO1%VuYMS$R>oC5mMFOy!(@OCxb2K_lZ}) z^yeRy3~LwH+zdnEjCX-e*plR1q-Xa4}aCk^vL^k#yP zUay6PNoIhiFQ_IO=^Y_c15y99cF8xJo{3%#--E+>NS5-wRN?z$s=Jg_@Ck=>PWX>r ziW!eZiM^0of(Jhy-i^oyx?SKln!ry1{*N3K#x*&RhugQh4zwwFp$3deVZhzNbJ^e~ znd|P8bzR_N?9&RX>#Ra@eV=fP=YTJ%rXKdk)ce+=EPk5_B{liFOR}gXAuc3ML|$G{ zQ|$a>iYC59>mZu{DBAVm`49PseD3^GPDiJGlji(~n(nWj>3Y5!!6z}{>6zAwZwmio zdDeZ}65xgo3uIvg`KZpTVJZJhSmKp1d0(&MUL{=rW_eq3v;595qo8+imrpn^OB(ra z^Cxva>a?(sOq6x}fJ;(#*J4MbgKHa%yHON#QBDS&xg-tl;{W^r_+wAQj>8R(xeocz zO}^*Hp83-Qxz>Gpw2dtH>56smL&n)>&F|(d*xG2GEw|DtfG!bb` z`-~+VtRVLhO#&<-TVq*VS2Rlk&2hp{d>SefXT_vl6J5dpu|jU)pRJ3*%HARvF6TZ8 z9b-?6JTc28YBF$}wV7j4<=TvU+&rXMdtI@t8k&5j_*k~3%jQ@p#dL##rL|d)5u-xXoN&Gw$*rkorxO|Ir1J^XNhGCd^>u#BJHBC*LzPWXmOA?_zsVe zV8{z5QCk%Ynntaq3>vOf%YETmWKKC{NZ>aq}NE5oE0`@|{{; z6_2lnAPJj--?`9b(O2X9O1kUNca*&c<;*HYIk9Z2Zy5Awh_by?xz!g7ySU{jYYOf- z#zL2$ht6Rv6A(uw=Hi#qUi7JBHXE(~!Hd$++J#DMPkXytJD7UaqqV75TG2~sZE3i* z)^KYR!mYJlN!R4Fp|z2F)RyX~yw_<2)!zHP-M#+}wu7nn)Z(9Hx|ZIrxmBZcWDT9xHN`#+%yIuw;~S!BdK`J5h=grA$F7+fd4!a4CO5 zDc!X=5MPS;G{jE}$4^AOn*Y~!wd`0nu}5o!aJtb*r{HgS*p1^?*BL=mRtQ6Gzhnry7xgb$3k~ePfLS@w zQL~Ap_t~J?i$Xo?Jts#q2HwfrO1*`s_h*lqhu}*!;1J=XH=-xKkavAZJM{Wi=;6Ce zH=AzKrjp%B^nt%!PPX2SyqJHKcNFC23a`MVr{)x3>p3!fg1TxNHAy-~?!K(417n`KwBb3(Jc zO8L7Sf2r+EX}dg$JHO2El{|Jb&MxB`oCxXQZjI%wY)0rSIc-KcW+S573SGW`%W1JL ztST$JGh}&1cYcj79eY0;-xEW_1S9mx(vV9Cr3(hUQwcc;U#9H%0(mM*rk$08eSp)9 zjet)<@RUkp*?D<9P8)&?!{t%oR3yu#RLLkU7IKovEtU?hWV~Q=&>rfCbkveq1{)55 zhgKG)q>GcIwqj*EY?$?h(AKaJT~K6YaXuYV)2eu+tD943g?&OR^hu*@5*_4emE<98 z9Gw@>VO_3;RSqsSsw34Lu|o%a7cIOZYW0>Kx~f6wak8MZLkAF65OlDDV5)%6(~$Y) zez32C^T6A;$Wb3rlZdqz%T{=M7p2u(@MXl;GmvSKrF-6;FMQb^ugp+9X6WrM&K9Md z3U`jU2RA)wjNb{}d6Q1KNA7PmVD#Y+QW=j;!GFt+Se;-*SWP(WgOF1@NQQh)_Dfn$Fv*QayruuF?|@oKR}u!^r1o08+HzDYW^vhnbvZdr6C;>LoZ z%E}(ZZL)W4t@5_oWq_67OjcUibc9`KZk5kDBPvD-4&e(qp&7p1gUA6be!@4v~I zkyg15?*+k8SQo7_!}~b!*<-POj3^~9G#RUe`u1nEoYqYyN>D>?3K=&ORyYNrLlH}< zl2N8X2^kO?j}mDWCL^vCaq-YWN8S!D$I3nr89KP!Pv!aic(m8b4u=diqi{EFA*5x7?ldq814SBPbk~SYGQPC494gNlp4XuptXs3i{z~vVmC%_iP?Iapc@E2CYOww zHwMzNtG-fdegRf|TteNWR<1(ZVXKCp)ULv-LafzocsAf6f9$mP z+_F4=1-#5g!>8{NJ{kH_R(4|`S>P*9;x3Ps^~Spf@5k^SAJ79Q8V;@cQGfxR5+9r^ zCKcZ=#*194vBPT7Ud~-K0F;l;Y&x&gww9fQ6*0`Wf2yoQdoTKNR|dZ_#;q}gJBpd3 zdne{wXDnJ|=&+PSSvdgz)G=}E4#K4VH*(kQGjqI%!xAA2KZ^_Y$J!kOKFJToe5i}R(31Ainqv}%1XT? zQ+aCm_$zs0*y_;fpFpJ|&uP?dWm!s|3re2W9(e}#$n#i;(iakBVE3Yj3?q0CM({%= zJ+&o<-50`I>oO30d6rN;vj#m z!+FSz(2#UHc55x*xGfy!#{S0s54?)7>-;lBgK!c%9Qy=$Y5zw0Ps)oi#wI1bR)MWr z@K>BUI_BF?uq`2fw{%|FRS=l6Ls;|LPz72PysA-*vTr-vRDW|8|DM)c)1? z=-CeBqMBdnQhQbdsU79msN_&7qwXHA-mk95PV`X*jjabRvL{4+Qd_?QWjT=dDPZs? z(Q_+XjPY6(t3uxe;l9m54K}2jjeg6AD&)c}!fjm8$|`l=G>N-xS&$9;zrDSD+I`SG z?3CUPj)g1?_aq^=)50!`4H~L^vX1uI;hziU z{&y$j!ju#8#JC7xK$*=S%b9Jlv;LTmYoeUZ@(9F_Xv-8P&+3#O4d(TYQZOjsT96}q zVN;KT6{LJ{i!O)5^Rp83wTyhTysU&!+usXr4Z|T`umZQ%b@bItmh&war6Hl^GE@xU zIYE~kJJ0TTUF;*i?of3L@)kc2sS=kl)ty)N!lXTy7cCjv#AoHrXco1Lbhs_b^^bSo z);0#X^z?YxTu-NW%%J_8+7*$ zb+xt6DvQWSZGBVBSVXkwK3B#fO~&hsIcP?H-mpP_V;F^g?9yb!LH|U6laV-r$J41hYy_E@m6-(&+7T@*=4^= zQvyfpx5~pa$JFx~JS3r}whfBqVK3zM{PvKP0}CCszo$x`<-er`=hF0J1wboOa^B~#Ha8jC?@3pmO zmqp#`mu7}YU#Xhsk}((l9L#_QFi8VVuq`~5KBk>&B`;Vshc|}TUL&vPR`ZZI=a_Pq ziPn96FxSy;3oLE-#Tqghuop2>BwyxIwD1=~I#0{QL+7kHS_g*~nQ_07U>otDh(DYs za{Z4(yMP-=l+|EC54|Jv;HM^&rcElo7^f0*5xYWOW(C}^!XAjW zjUouY-vdz4S6j2Um_SCl4_frht#(kKnv=NL0BzJ5Y?J* zF5>JKr%vPsPjk;&G|iZQ(k|v<-YntTpAZk`mb$ltisSl|?3qisDE&3S-=rNv6x(H3 z&jj~XvGkCb;c<99-#@xQGH?aR>Kx1hORgtk$Quu&UQ^V66yK%f=S4_A9T;x^8n<*Wc);4(&ewBT-~#Y_cn z)718@c+LU8+HJdLq|Zn!n_4zdI5#7G<~?$L48P;A;sKHwM;i~XgnbKjRYuZIRX>_~L<)p8wU`QtLzj1|@Pir6Ar zv)1N*gzt~={gT7&&~#Wezj}I$ygk;@UCOEUp`s{m7x|R-8Mc`-W&)Pljw$Oxh7P>i zhA8NPM%*~Yx#fo2W!?RJmf`$zojKzH$L}6KHB(qA=j0eV@-^SXZdf&Z+OK;2V|h6q*W;R$e3m)xu@~plw#HFSQ+U-H$V3O1f%SiGX60bGrb zVKe+OKs)LlbeKR-A+O%wKb!+PL@As-hP@olX+_T86&hI0nU9>Qp-(_V)VHhUws$3l z^WLn~z}cpl?fxUkWTzv{Ga%}g;7V{X@T7HH6#^aC8*oBcxbbTyWC(oU) zQmxSGQ~rHFPW?ST4mxs*KF#J$^zSF=)i8R-6D%P;kC=4p-pH1`#436A_@rU^jMwGJ z$u^AAc<}T~oD;h7H~P}Dq(;h@_ML_6nQsvCY5vcA!Gn~q6#3ZRnDni()nRYRPuw8S zo;-S30n-_&&gJs#$M2{wV3At94STe~&aBEC$@BX&6D03C<(vCchdZxFoZ3Q7F>BPa z&y;!=qMjtuh~%6T28Dk|hkrTyM~Rj4>|_noYP5qi9zM&OaoIyR>A0ry`R01uotr`L zfQ!TK#mzh7)tSMoGrJANhC(ec3oFvv2^ck9;{_PeTw+q-^kzbUy>#v>kS2+vzyS0UU0sEs@8(6p25xm12vGVlO`rN?~} zpuy^aa|8)2{Mt@@N?JPvmw^Xsm(_{&z*M!% z`tcb>E!u4CVXbP3voK2wc-dd<1szy=drNePD*yz;e~ z`5M?|Dr^|oa1{?BofE2`@RJl@M|e!TaSP0EUX-w`Zar@J_ba>++NfPk;_HJMPUdNN9qMiReizBARGP@V1~`1HLi$ ztcSn(wt_Rbs|4(FSq6G_uUI|72o4v$_rW_n<_!JZLv12k|HrUSo%`s9C@)x0Mvd>$ zdfhEt>RmXgW7rliKZ5EoAm(}B-rP$bU7@N4_AG2`oTn0 zg@qr@d9doRkG0IGHD>4_EvCC_R`|>6!pudr9=wsyh-e*MJO*4aQ}U={Ei-gQp$xSA zg%O2yIB{DHTu0|p($?fyXlW!YYQ4Kn3qKuw1^bS;%DkP>5U+}^s1!^ul?!QYbehAe zD{et^cK9R9gheKtOOL`@g44mLOu^iXK21uUqX>MgOVUi>=;v@DD>9}xN|M-33*%QKTcYTOd_N-utl(3_y+uo zY=svW!`AwBHN@32BGiO?dNFLNUn}fV_Cg!R%k)ZIMP&7)pI2$LHzrgj(i!K#;|RW_BLmTh$$ za3yYIDe%ZF^y*nZak5J=dzU=MYSSk3Ww`g=szESpV^uw~ETx>V(6WxcK<0 zJL<;>51_t5SgX5(dok*2_>7|Y>$#y%VhrqWAD7Qr?bT70F}P2`4dB4(oB#IC9o7oV zi^fV*Rm4lC&0K1n2)~|FS_oO``$<`i(w~0K~F)spLXd+PAFI=ocCC2VygKpOO>(4v{{>v zlIx5$y5Y7gQ>C#gVzZ@2_vfnIEuM&1;^9RXcD`KPP>%i6#o3>HJEF=|WvsN>7r$+( zGE`bOQVIP;4Oa4mf&q*xDQZo+@gvOp2$!~_ul}?=xWfEWgasQ!Omy50Nw9e{MoX#XpwLgGnm+SjbX?a95jAu77|<{5L-XPD znh5iYU&}hqyeWot`6m?UX@7E`Atdg&@#P4N@nHe-kQ>v`x{(TRA_hKj$@|Lv1^F0V z_N8ev@l@9rM0D69T0Q2M_oM9|_$2OI`=MY$**4CEvcJIH)MD8-&iJxkxD&QAyUUCU zml^W)ER#xXC}{Iw1Zw!<5tWwBsad+w#wrV}9@|{S?avoJ-FN=>(O8ua1=cAmR$Z6e z&?TM2cg4fAT@HK86RTYbjO;8WnO7Cai7(+vvGd3%8ooC}@qpC0ooO98QCST=NflNG2k z&L7P#2O}~5urgM-Rv_s1wLy3C?!qik1R?2`K(9^ws9x)rbn-h(i?<285q}EMZ?!9~ zIvFM1i2Ns!|CAz0o2rzl^+mJKgQH<#K*Q$=*H`Bk8Q4R?ZU}l%Xgq7(dfm&g$K~Qu zzvq&A&)=rW&&r=HPQf`Mb@knDnyed9ThQU5u^iVqZP!hOG~Q454M{uwS%oyNA*loQ zz;1VE?TE&H8;cpwti#zRaFK`Vet9je{Xd~uoU@400q zPkuwP%~OWt6WYx$5*KA?V$*0rTUpbf-K5!^iS=jc;_NR1r{uFzm`-EOSc!Mi_UiPg z9O_u`ax|MkXZn9`zZ>ms$2}m<%njz)tFD`1Uz*16BzVcu>^tB*7U4FeIT=KVYYO;4 zF>IE1Jmd@nEg$re6dbgHm-hZ^fG|3JxzGl#P7L@gwB88z8KJ{48NZW!q&-6EgSdqd z!)}4(wmty6v{;#?;2uY_w@Dwqfa)BMI%|T@wR0O1aUPEmh8AnsEg`l2n(84%&;etQ z2O0!_J=dQk9?@)_(pF8i9V;(4fUsKPM#r#7SZ*p;)@Te`OFKmC~gy&DK$F0>Aw_Kg+ zk~i2a`OSFaMB-RFCuG-aAs2vMLR%lvnh%a9!oXwB+?1@`<+9_z zE1*f$U&S#8Oyp7ql%zP5L~hVc?%wrDVjSKExqFK##k?b0OfKr@h!^>+c*k|3MSMAT zRZ~2uZ%(tS$%20J$w~NoFP_74h3zm}zYINt29w|fHI*Eu&XT#nRhrF z5jTNwbK;ifVjUBolpDg_yxks7|1-v!@K|cM3(sOawAZ3al0;X%ZIH>GB<6{3a4Obi zHeYs?HYYhJA=9@1sbkNvP8P2_00VA;D;J?N^fCKT=Ds{}SskqxXyp%z5{&N2eUpH3th4gAUQcN2 zG7s_Fc-VQ&8$kmyAbvm>StKoUq6XI)Tid%By9f`0-s&(gqtGFz;3p$bCwG+Hr zR<~8o%!v{B4HfVs13lZp`5u1jsD%U}hq=r5@TtAp%;_WD5$P%5AU|rEo}3BD`d(-% zPV^h~9{IN2MFwXIfLzdH3{mooB6Z2DUNgS^fhK zSx9M=L|p zlL*~FCxi+2kD-AP$&W#MK)1L;QWeS}Dk%WHM%>HBNK-k}LuvU$SF&;{3wO80rO+0u zP)7Y6@TV@%igU@h#pQ~*rPVb+*EUD2D~N|qoUN5l=C_5UyMv#cH|bo1)0$kV4ZTx@ z+WOPrlAXjTM`KU^6Tgs6$$ZTqaRALt4maqur>P?2;@iGGcNUE{gp2>63qXS_V)qegR{mk6=VO>0QNFoH0d{I9h&lY&g0O4uAzYnDew@5~UV^d;V7nq#`795;9dEAobIxLw5!_IgZL;3V#( z08ZjIFY>6I-fV?GN^nstI``W55Oh;Zj-3cSOQ#@eM1GK^mA6CRM>AQR)(`qVn#m4? zW^K;xY{BnnjiVR#8o{xv(D(OtaH$ZY!eFgvsm~Er8&JeyK`kr8wa|IvoLoQNVPYEe zY(Nj*g!2&2hm332jo2|-$B$t+uN5<(d(4kPJGt(<*j_!=73PM--NvPkaB>9w1^xNu z+Iz(s+)l-cvGx(6k&6>EL*z%io@>qjt%Z0b-Mndrek2Lqac5dsm@jP+qp?P^_9RT= zQX|_kMDU|EQ~RbnZWn1Tra7{d(ynXG5VaYvKX99Lc+_;+yd0v-C zO?|F~U^mSNqq8>La_ene|C^jzw3koi&aXhrC)bzMAD64?w9JXXdauT*&w)3H5x8kb z?uGx+esvzywKNOd8tVTPkyhtMrFOMF>}yCgU4Y%hIladn&1!Iu1G*Dh!oD`jQxzUH-H|8xL^Nx|-Oec`(d--O zsc`ma)*`pa?^F?1T?mYJ@#JV06NqMiy`sMm1seqh!ugQ*QJJ*AM&Trg2HcB={k+X+ z@5ENR>wZ^KO!!9XeV|2N z7Y{ng|602)Bg)N>`R`ocw=3V5A6$5Espn%x&n+cSwhJKlyK)PO$I%hYptbk#<&5Ip0>K`Wca?N*sIk>IyG zm;(Ql(d;qwR^K(LbJ09r$hE1hH?qz{;H(V%7W>Y>z2nPUXS&C!zb^3V>HcfmIJcZO zymwx+oE8U|aJl_)nj^y%dkv)fuqqQe=@~j9_H>1}PGf@KxDE2in^kLImIks|q1ZRI zp>79wy54(@#Je@J#fMD$I9nVOgL81AShbsT4Xy7&p7f@jlld_fz(F+N`sM!T%rddEih{?BS3}nTKfD z?X$pV6j34Sc<%{CvnrqSQ22hT{Yyv2{`tgD?5X?n*-T<(&i-3iH7eK>mG5=47?2voP(@6 z8D$L&G}nvb47{ZTs_VDSc@?oY1f2Ef=A6M>VxX`-ZEo`1Xy{E{9V6_08|{C2AD;r8 z$9`Ag3haXwvUNCY3Jm`kv#-CL^0@x8^$Flox!RxfoCz{OpGSZBLFYHp^RoV8P3AY! z8W|97xq1!=gBVWrO^64-CZJz$}hYvzZF%V^hPf_S>IPaXDFng(7n3E#M=Md!cd3rY(!?jHu zzB{+w!=N$TM%=%5~CY&Nm}nag3!j?i)1y6U|w8w4$%e#_sW5LZ@X>{ z%5VuVMAQatxwp*cjo@r-;G$UH;8&pMXjPTM>ZG=VD~^WWDdH1Hv%9bSuq$V944#l^44#m#BA;+qJ{p5} z=i7w2LU`4Rd)dUb4Qa9VSavM1{>&V(QAnFGA)&8M$!x-!$C!u~*9bp+91LlM3+_!= zFBOpM2*w<4pcolb3^Dae7BL!OcYyrexurX4j@*@Ii=2k-s^N-!R<4%Lr7DGhVrgBq zB*?zpI$EpQv0PFgxoxUYl}g3Xt)f$MraGlxl~I|F5IJN!bG;GgBf3Sr^ofZN#s0)Sc@ef& zx}W~*lkPgS!TwSyHA-dEa#mC&2%OQ&^mUUBV3ir%ua~V)zHZf5ch3 zWC#3x;XmlCUGfY35%BMI3QH2OGw9*p0mKytQ;ZOY(7Om#GCL6RL3?tG^KY({1=KPd z-pIne>arA5TW%n3hqKmBZTSWM_nZRcK6(g0!T+YSw3yoRJ^ZgbYm2EZ-@?D%DHKy% zn&5xQX(^$$`~&`#&e9TU%jfWu1XyhewdE5zRJK84n48Az$Gl8`u8Gy$XU98 z>L)wwwa(fFRR4SMf8?|*r25~4|9xlaLaP6D_}_BYE~NU`!(ZbR7E=8$!N0+2Sw!`( zgnzBGbP?750{p9-wTq~3!lHFJ%`W=pk(dWBW2DpVeQ^#}^t|F+2ksN?*{5JNHp>2Z zjy)Gv#T8onYgGfPwwC=MHLjlri+YW9&^J{W?1eelOM%(%cp$I+)DwAvB9ytOO6u|1 zb}6)QyRq^eTnf~KkkE_557!5QG9;F96u;nLyK;41BdP*8s%TGBa*=za9KS)-zBER~Sw7hy{?I|e>spc49v8MHuGy}P( z!_9*$fLmxhC6(fL8Pb%s!e$lxj%_^uDL*nNZPeMBX*nmQN=sVqG)d!Vo(WxuMgZVJ z`b5EMaVHig{M~Kr+H)*k9c;JLo<)+zVc-jg3IFy1cR9Cd=7pIY z12<0;vgRGowb=m;T9qa4F5bhT1Vg}ETd-YX@sRv+ZAfJkL8vE;kf&95S zU(fl#7S(Wiy0VQWS%x88QhQS$jBP`TUgmaox4rb}MNxm0X@E>vhyMxiiNI$eKMQ|L zm!E4W7t-?4tED*X-JtP*V_KO@ zaCp~akmvlXQpa@OuVbt?ucf|Wi*Q?B!`Z~7P- zT77A37+RTD0b`EnM8>!Q5|A~}Df(BSgs-;Ub4FSAK~h{(X3P>^(K@W`gJE3LQQKhL z|FN9dL|j#s^RqT)I@h6%gB*gDY=NqrpSLkn*$yqNJTeC2+A5qwqp>>W6RoG>e{u!K zBh~kheaa5kQbL)7<}N5blAbX(s}mAhaIT((p3$b6l^(9WI&FBrZzW4LW6HvL=Qenw zR^ctjgxliMnu&4WGs76+O~=$M4qTVuIr_b}d60R^X*o4knKY|qa#rx^WR%4!l^xG5 zoxL#cT4WTRq5ch&_T^KcXrGh z3o4bUSD8k=C}Yer!#;FcO5b<=kqU3|AE^jm;Cd5V6D%!$W*BT=2hW65<8!_+Ayv`= zXY&t=eMe{T1R5%w#7v&$dD=zq^;du6b**-`OPRGe_)QAt_k6-i_-_p3&NLhxh?BjH zK4xGN;xCd+?O>o6 zAilIXOnA~`S`sGw#rqEYi}75O^{s1eaTsj*zJtGuye9lDr1UZm3+vwmlF1!0rJTRM zj%16OICFh;>-BZSXY13#ySZB}8u2{jLSnPPYyH+wnq6Un$2TO~2weX#+%YooE+=aw ziP`J+L6d=_hBr}Ogl_Q7Gn$ZdKvP3F>SB)xeZVv5D@!D2p)}kfz^XT)e}xHOp^Wcw zqKe24gX|0w|83Jx_8(o0TxKxs7Vz{si4eqWc`RcG~`pA zcgLvfY1Xh11f%&)>ppb-Ftc>RPLHFWG^TXIhn}({Mg2B*jvp0>Ws>4A(rQlS`o*!Z z|HGKVgbcjRRot*pYQhzeCK>k=y@FHswl#9s7^A)k~^Dm~Z-vfUT$jndX3gm4F5Kq7Y$Hyg0l7<@JavdEf? z!I5?zsiHGJ$6uVjhiJ0q?o$d+dn|QoH+K_pqarD86d_&;ploUVC)zt89)M18m4ySs zF;0>VKP@sZsIY~6&s=vf%In9K`>$KWPh*EtVuZ4AMfMx6^n*Ava_6MDAxeH0HYUgfn9HomI=vclgrH!h=$s4&wDUy0M0AB)Wf_EWD zut%|(>%sM7lEN+$r_zCZT5u}2^wia9gh}AXH+6A4A=lqCc$SN+2j}&eHi2#Si_4A$zdL#qeMLB+A<1FR zB;5W}nPQWPM`?wGwTZNlE^eclYt8M!(dq%?%f1xl(yI zC%iA5me)oGQAR_O^}*6p*d!`FSn?#4e5;At#5L~&w=F378O%@j4unBLd+pyegKzYjZnIpkCMwlkk?;z1l47-l6L2CzRM#CajbWea6Gi z%*+CI^EViyGu)uJz%Kz-AW6-39*TX@rUEie2;PUJ9D|fMz9aepJmiQbX_q>9E_B>^ zwqB}NuD3f) zopeY|z1|)Fj&w+lCk)ome5?&a2VP|Cq0n;-m+8Au!HyjyUMhU{y=QfG72s{A*0X%< zn&91@T8KQ-2%h{OVf~TxZvG|Mw@a+mQbY=US9UC$WX?lxtKig-2R5_j!dP(e%W!8b z9UkJ4J{|>}konuB1FIZT{lnX&Lk~AfwZQ1yg&@?`f%2H3 z7Oc1jNVBCM%veL5(Tzv6*tKar`_)an?mk$xe}J@x5$j}MXiXEoQ)FkO%mohfX`-|~$$;D6=ciwHF>!ySoZLXXPQrD>4L{KR@Er~GhJ^3; zu{@9H{!}OYTcS2Zq7AFv%~TFn-E$JzUZ*m@c;v8e#!4$7`v_ogHpIgB%Ls6O{Gf zAK|Mq1`5&f3VtAedd>z(JB>~Kz!uZ6LekpUA?hSZ3o35@AJqH>SX$Q}3^l4@12#jJ z0oNX*(3jxJs4!p7jUfIWdI$f~A(I`Hk510ew=~hJlh2sq@$Q^E3VomxvLr+OV5~C0 z1;QS5Oy*2#-)X|lMyQYmNt$c&?oGXQ36#<`=T#a1@!4K`CSCe#<#>fWhs$9t`kXv3 zC>#>CUTT#?bk`e(b5=1B5F>g5$uLEUmDPxKS0nRj=3nkFqtjqp(*_`4_YyErfqAFYZ%-oTj|V^JYtE72Lk3O<)| zq2Yi9{A=67(EhzLXT=y3Gv^tlNQ2U;m>1jy2>Vwt&w&$sR~Y=XEQZ!NWpP*D;$U8F zV&>egymRl$J6HL1FjNZs{j$**fuPTW{Iujg$qK(1;lUZV251kDC;tKaCt{@*)4coFSWItn4;|``;w!J{5yJY$57XobX zyav>7nn#0yPYX0Lr2PiA#>m3rRzKuJ+vnO~5vBdoh?7$DkX6#9Q75HyeO}C3CAC5t ze*v&In)_4%k%VxCzU#9JzQ4Ok%I_QCQJs{Gwv$p!3Wa}!4o@$|NhwP4FQ9XI#4;(h z-&v_$&84-8v;6Vcr%4ARX0#eNG#A8AJ!;(03^QF2KlA(`g~CpI=x1<0F3BsMQkwIF zq}@=OtM1S*14h7V)bhniDb58eBhQ?a(jGY}CBLrxs(1>16|flQm|GCbEB`Tn@}M$x zhjBT|9fsA$QIrcFjG{1St)wkI4NjHv>yy$J#qhFk;D3r&p57!et?G`1<-?ym30q?` z^N_ApPWRPGX${_EUC-WS%6~+ct&-MH)3h0ToRoGe)E$ zC@%P@;CjJ5kbW_!+F?l}D=)r)(yKehEW3{n|N5zk#)7$opCt?HF4vcJTp0O*9 z?f*=ZekV=t|Ct7s?HzE9aIHi0hE5rltBW-jDE|R%s*01+yOAfQUB^#KwLh(r4&z(B zr93GeSZd%;N}C>32`Pb9(rgWVx!oR9o(X)w_Z!t6$4PRohvpw6kt$SuQZn?xR~@pH z*Zh->!?#rjd45_W_+2Qu`lowanTE0gjd9m>jj{P*jd2{-t1P&!;73)%m0_K+!-c}d zUDq>d_)Wv}!}w(o#(mCF#u~$a2OifpJo_2Hy^ud1&H@($N4Vy7k^dOKXA*0L-q!v9 zeeV(~FoFNPcUhjZJl9}f|Cf_ey87A4QTA7>-mdy<&MN7Cyv=y^8-Fp{Ka|Ej%*NqV z{}8@DM*T#@)TmAT6yt|d#?vRIZ4aN6fX4;dP!s1GsB ze=DRzJv(uChn~~E!;j`iVmD@W7M%AA_d$Qu{VJ$ZCLVyWxH(Y^2G6T9ZQmW%B1}>V z-C+h{Ix{FQ(jAOiklbHLc5s_au(Y~4klIg`4ElA0u34Gt2Vn1f4HvHR$J|P_T8Mx?k^1 zSE~fGpEa$PrfXEf8J`8b4jaZvwi`EDD}uMFjCl=sHIL03Jg-v9%8!#G^Mf~-YuZ>1*EX3ufzx2WY(MOZlPsOz-4~KY#8&~|v@bZe_pHJWwMtqC_cGio zaMf_@;Wof+gxfS)9>(uipigx!??LhhSCfI2=VW76$Md3LaJ=Wa=B-7RqiyCro#>___99gHzF_JVk^ zQzd-s_q)QO_4Bn?Tc6qP$kb1<+pmfDdbM?#?aXu?Vpas=5yQ-Da;d;Ox$GhxA=0gC zcb>vtOXtkH=ZFR8qLsD1cufKWnd%>|vO>)82wN5x8ELCCfF9Whj&w$r3DTI~*|$xa zfU+u~`)WBhK36>k{7}=3;@`!;yXlEj`dLjfn=_h%IiE(((RXsDA!mpG67B}B%Bd!H zr7A+IVRup`Bh`=oZ(I@lJ>d9#0V!fC_gA$~Tbr*O+{Qj`k#3KJaIGZm-zM;Pyp5TDiU5uuzE)#WAty~)Fed3Wis`WPX zt~pZ(a`Xrg@8@uN8?XRy`gdxtuT-5!YS!#PD=DT1)$Sj>`N{27ovWEw&b2nRo}&Dr@NHB)d`hx?&S+Jh_|sqN}ua+EIZKQ7^LoSJU!Eyg*deS$u_adqZ*j- z{lN~$3u>ogdweEi`n<#OWSH=Pr)$-?=U$XF0un%|p;Rq=2g>_o6O~Q*S+iQ`jVD%N zg+mE>DB_)~fp2HaJqTNMij7@m3?_SXNr*!k`D)=~$VTG))0MwNq8Lh{7M6ChW~8wM z-{kH#f6$c0w~52O30bW0=RjAv@>_#~9I=s6wiRTsDawwy8QR3-k^_>~j)+@L4Y%@M zX}GoIl|i}aso2d0-C=~x{p}UEv{iT4*B3I8z`s^TOs1M>b z9IU7Xy4VIr9{E4}gA$(@zerblFd{dM-zcS6NrOYpn~OY;WuEwcagloraNj8Y zCisBFH`pK%e*kARSV(n@#(hZ2MjO-Qhg~bKL;VCeu{gik8zkV@Af@%WTQ>( zR0$XTJME3pwZK|A+d}o2fcX}z=M(o=F2ddQiq8cgbqQN|7wr~kt#+5R(N+y^u}_5D zHF8joeBfT)m1Exjn&Wd|fOtg#*h9fyS?6Bam45R7ntmCb@w#X-T03bC(3-Z^mgEou z&nMoV+rx0z4dh>GI6#djoR~& z83P`k+}hDdJ)F)!#Ez!;t`x(3ZQ@_udZEe_C);ocmSXk|z#5a|i;-u2$mU~`(E_Ad z)DVL<^ztEWjLuaE;R+zdTIhKco@;&YzpR=`QOF-H88M<)cj-EiHb^Asn;FGK z;RMV3O=KYJaurm0cljS3Ho%gzPpp*KH$s3Ih!NS97Bs_AlE)9WW7*+udSNo&n@u1- zR$pf*5K2Ruh?1*?zVml|LLtX#fEACtBj9jlae|2R_qje=`6(y--au5`7Nl(MLz>={ zQhkKZINh|I0=#fVOBd$?r}pF0xgit^h$kB;4l=!6vC7N}skJNaFnGb*gS~);sdEBf z0bE+(6?#?J;V7 zYbW_Q_%6!6ARX16H>khk7gf^SV!d$4cL{&@`xui7I7OktWJwDg9B{R8W8NNk2XP+| z{tTpk-|?yN3;mu0OdK;fb8h9_6LTvIPZV-RnMIXFCyKavjZ&o*oPQf+8MV!sS3K zdO|O3=_EO3J?JI9P~qic@`S%mZAIy3a1u)g>OngP`=>wb9#%4?u$=NhfGm~jarXo3 zLdY47ob!?MlFXl>^9ilX_S}gJ`xkRVIp~%YJQ3ZT4sN?uSnV(^KpVW~<*kpACiV_T z@LhiNZktE%vddevFlHp1nkfxtislV$g`8;YzZVWzJaY+q?_2Y}f2`l*WIwQ@$qaNS ztFVf4qrBs|Z{7A-I@fPbu!*?v)D|nA-RmP1 z*3%JL@UQSr#ozn7`gXKj7xmGvke|ONS0}s}&K2ZbvU@fV@RD&D@K8vA`fT<(8t;WXLz41DM0@AVAzoOisaqKM=ZNe&$&64u?HrYQ%PU3YcyZ-us{-+;Ou`^F*F4f zRi(`N#`yHl*dP4bhq}J@X>dyE%};q46Upnp=x?rHHMw7FQOSOwhWt8W3t^oNp;1Sc ziYyp^=P>&BLy9$OsG28qD!ot&zV$S4H;CsitR`I}no)1dZ8+9MBj|C@li3=Sj&B-& zt!WeOa7kC1f|jB5LOhlOoL2Dae}@!2*+0_> zzu;_2=(vAI{M;%-YLZ8>gHGkHuhG4;uyv7M5RsmGX|#t+n-1OVTR0u) zh1RaVy9!BqaA46B$8n?mNE2yk=!HSx1L=Wr$MH|fV`rw1hqQza*p=OHQrYz;$*>4L z@QzhCop72Y{^fUFDyJY$J?1%9hIb%Ir4@b!{k^eil8YTS)R_mp=yxGqazUDG&_lpa^%4>6I^-wy;B&Inx^FO%8BpRI-NGwaus_Qz%hB9N~ttK5f3j1xvXRghe zl{msVHc{17)Jpy&_!YQ&-ER}mLQYKA2x*I84IgE0mK4SjiRYU(OG?LPtWd`AwYc*l zd@EMF%N2~bBz}HZ{H8ncTU}Hd>c?$y58*(kUieq%SUX$In4)-Qqh9#b%WR3S@5i$> zdf{`7z)B}uqZ3~CU&J|+Bn;0=RT`bJ%Fo2=uzvhY{_Z4Os0Z#iNsunu%WgqCLdF(6 zjy~XY^U&`MqqS0BbBTn56V7kp7qv_uw7~gpn?m<6AJ&iBu4$c=^njBcr)mp~RJR32 z&2f(X6ZPIL^m4S5Ycnd}n0N!HkgRM*cm-?fFHY+c9+ne@HY{d7E zg0_*mbymV~=+(kzeaeQ32V3grj7{i(Uash(@^&}vEE|#ZQPZpFd-i_n`#<_N*!p+D zmF#Z8&N55VCOPeYex(;(;7v9}@?X1{q)O+km>q4((87uAhTdm7qZFyCR$ZdOSvis9 z14CQT-r-UFShO*xY$C857VUizzc-rfF1Cg-rDsB>7jx^D#G2{dKSh6Az;~7oYB8z@ zXAcCwO)1sXF>T?TsVp`tRQR`NFz|oaG_o#A+6w!S`y6sx3ZkGf5zj~CjC>7qcn0$H zK%U;nbK4nuc`0a6*w4;ZRiMr=Q_cvRLXQIo1!lPQ0__&k! zwwGOVuTGx!lmKL?}l0cSKgtUX{454a-W zG@O+xHQ`tt-8e-hU|!^qb!YVdJ-LMbi+$Fo7h)lecFo&gmM$ROF<{L65c@!gL^B!^h0NV=6(+O9??i91$2GfbQPL)781{(=IixnSrIOYapHE!qu;k}lxC>pw{A(5XK3yBI7*RiW~45;VdC1x=0+tC}eu2U@+ zQOji@1ra^dv(^D^JDsjEj}ze^4`mg8=JE>SMOIMVrf7~Q{t z24IB3@=!}EKgXnPoinV5^GDnQS#S%4lsBiA8zgqgk5Pk$S#Rc+#}0!QKfV-Sj@Sq` z^%q!3OafQr0%&fG4V1K?d;m?lkv1RQbfPDm2d zqJrf0R9IV_dP4FVPe_ajQrK`DoE9z=&H&d7F3QBTO~)J2mmZGO`uO&&y;goCc8C(} zT#Rs}oa(Exymv*tSBgpm?`zi+s*Rzr2dvsMAoJrZlyk6M5F;d_-Ua4{CpGF z50-fze(?b0#H$rLp@)Y!Cph23ul1Pi1Hl1N0Oekb`|5YS9am^xoRP9IpDRF%2h%xl zN?NO+G5G?ljPFMqqCvF<+n^U30;(;#>q>oZmsz=zE4L(p=QSG%7v_iYXQreJ>l zRnJ)AWL^j6Y}9Xh=6!@0!s&qT%BEh58lF@xnN6J29krn>4D`gMD8^ha#f_lvN@JE8 z77CmZ*g#hO8)Ksr^eMe(WkAgjsITo{U=8t22c^4!SVr#48?ZZ$RQZHNd_$}Vu=h_G zc=A?=I-XzCUl12zRuH!CQGBB+%i=3WtZ&q_j->$+_G_={^`qq8$VG2dpg%k~GY0!m z!r3%tL<_XLsuhIC8?i@iW;Tw&I!O6fAivMcm<(-<9wPvKZDgZBwb0CeM*g7Lx zBke14UDD;?jC%qz?%%SebCqS{l|OoPAx3ni7w8!n8+m(+bM>Q?|JW!ottX^7R*SKb zeCY&iYs@iXoG12hUXsT-de1cecG_N8Q5$|KYEa?}w}rCo3ldvt*@b z+m%^(f7ssWpm!SVRawz{2+zW5;Z*{g$*r;uzC!)f^;GVsVy`NO`UrIC;2!90ued3Y zjkBOmAUyYAZ%^>;kb7FXO!1Y7r@f|oY^LC(xK<${FJ~Hpz8m7k*K}-`-)FG>hPcdc z%28r;6NfX!6D)D9jF2B3+p9W(vU}GYFrx2KVhY|b<-03Zz86OFcC61YwBNtS3aMcr zAIYK72!$iGSq@qDEV(?BPrp13Z)^u$5Q=e~4_5&99mabm#(Nq3H0HguXW>^1hrMco zezJxi4D^8Wkj03B>`4 z`_cJyrnA&8i7TY4`da8Q>yRxS62(&`tscBxk6xxDE$G3Y{Izp$x;WVTOt*wY%z-{C)_n`r%G`x2lh9?D3f3HAa(i)&BX6?o|I0n-wym4j6;8gYiS9a6yr2yTNXkd5NA{+&L3~#bo-ioXY;Lp zX^HZUl;v#d(!vq*bl{St*=vi|xCp!9h4w%1t#CzVQ#(HG%2|$_^Dn*&^6zC|yNh9rHX1JsBaMIMv!})p=7SE@Tz7wyMD;QBWF`6>ds~OD zG*s9xW4^zXLUN86XTbb?rC8vRO3Z<~9*sVWN>$!9jmegB74K zJCWDy#J!E*T2CB~-V0||Z18V5-=dBpG0_un~nH6gP73Wg1V z@0e`Kq9=TZabKd{Ox7!+_$k>Q+=WB{>5y!y>vl77v+semxqArlGemd~DG5=ILCOrI z9PW$QLRtmCH(Tu1?8uKi;t*dk(EdH*`?z-^JwuCqEYhv^zJA(}fX|O}LjM+ne2E*M zU>{TaGtpz?+cWlB?0UrA<7EfmhY>y-Z!o~~ZI>^~Q-L+ez6WO#tUGhQ#k~Z6o%mn0x z_&%}BT(;TPqbU*6Hjr9q?J2R3;(VF+fsF$)a*Yi*;Ko{LEYt!cg2TOz-3LpE*=4a6 z;9_fKeFDPNtA=d0%+D^amXcGTAy%`4XWHIN@v4B3v-AzRTE;}s7FC=I1}H9&dg7VD%eu?-$f}2zMSt3iE^u&=86T(q){5*`$R{T{g`p@+k2JWcA42 ztWO;5kNh9GE^5Scf8+|4b0u}<(!r7yjrLOXx8@UVPPd=4&iVZvh$2hJG1AAK_(Ttu4V#3Ghv4*JSsy}2l9br^agALgtl__cWfcJtJ{S0 zh}2}@RoQfh#R`gJ5q!}1CBAzy+DG3EXr^^$IcJa7SnSJstZl)s7H`+{TD*1eo&WX; zebX2H3rgN2%|eXR1%>$AFc0P6-U;Qz)azR*Z>C&cC!|1%OIYDm|H8ubV+%_9*YyKN zb3ptYvO5d#glL)`(A;7YGMyPEZ`d-R30`ffsQUqQ8QIu=wR4<-s0dLU1?X&)!>7Soa#NIzuK?p=>g>zGWNejONdvkC-G0GD0lw1;&*yX3xqaE9cc|+LG0p zwqdHE3<)c=`GfCw8#YadYVwMQj%`Z$7xi{QtBWWnk{BVp{X@Y!f|Bl@)wIeze5YqI z9w$-X8-aH~bw|-!)OGLW6*JuLl!OTFfjpsnf=)Q(Hq9g$L?UPW{8z5okck`#;GK5W%hafMG23>6Ps^@}*5Qz?hy5fa5sotzxn zj+C9^C9g^jT}4O~*9Nq52xSxpMA4mG5^f&0ipq_t?<0S$t@2z2e-ns(^nKnAXiecc zOuXPU+vCxWojAqNc({(4;}x4be_5dBLxie8@d99<3CV7zZefv;-?0F+IQ+YcelIFL z){HS>!CF*-dFm5C>@*hN5Zn9(c9+Nn3W~1*TX37b6L)E}s(kKkE%u97JAv9$suX_r zjmjCF%bJY#N-4vz?rJE*nbLC7a(%$bh32yf{K}lOlI0PfI1!rAiJ(vfHSn?eO5zBd zfJeeE3ukglmeGlr;Sa!inX#CO6~sS5gJ4W6-3?_0f-5n}l~Gz+Ka5`7nZ(Y1j_RCf zLlixkW2kf;A_y11F)50cm`%cjP_+1EB19uv(6^_>8W%xY+w+)Udu^iZj z5mueQsP6azU`sd^*vS;F=N7DmrZ1bi)23+S6e2J(Xue--qPthtNPlTMcq|AI~sDwB7iDM-5%bB+a6|$*Y_HDG8SN+yPyn{>&`i$1-kzSlHHA6+vZuEr0 zr@bL^UU0ak(%Rz_$71cLGsb$HFV^rJjK)>-Zc&Y~1Op5!UXvzbR)Ef5krBHjo2yap zbwl1|4CFI9#iPEbN~Y9p9m&L{&rFyZA{6@5f!7;~Jz+#KSF>LFeZ+d{H`99QMg+5d zE+`n_VAmAj_hD)OIx2I1g%-3O=qQ~`N9ls}-F{ePrG0N2X4*qYJszovzWc42tC@yy zUnv#)@NcFc>o!Wio4&%|8zc7Dg|+q4P3N_{QJNm8g`g8(=_+Ry%9)6K{iR*DFq{*T z^}oCJJ=aJCuJ)@$+*RT2NKY8Zt-L2as=b* zy&=MQHxnC|OYIEm`o^LiUk2E&6x)$v7*fO_#q(V$`XdGCo7BJA^rfZm1# z4ALxgb6W|mtQXD^Zrr^GdwAapxqtOW$b&O&klTh!gCjc8ir>j_=^ely#_x8x6L1VO z(|QiSyV}WLYWog;>b2Bj?oB1oq2uvd2uwid>ipe@L~jl-gh&MRO&x(HtdPrlE<IZle)KcbDn>^C&A!E^COjC?=N5dQ%k7bcP6v<(tlU{u!k3`b{X0 zVs;}Ycn2EKKY^GV!I-UBr#lySwehl_t67M+PyM&nu}RQkTfugnVdm}&mhvu2xxX`b zj)})f$}Rqb(xUHvMc+M&@OvoZ&-iWVD&z0}qYOLBh`Ce7RHWT;R~Zi=T#hp6_sy;{ z-ufS9OhXxNsk##+dy~K1-+b$%xPQ*S9HPJE6)^4~y80Ft_}08ymg=^Kvj^O{hCU z=4Jq4#>%A8o#wq)$Qsv_JzUK|q%int=5;t|=B2FQYNGH=?Z58|N?~(txf4>Z(0HbC z?!`JBdK3H^I0sxc+*UXz+^=wra9%ihZs6B&3-bjo9xe@T9Gn%d73V5D%7a~#nm16} z4d2cy7Jz6rCmG{G(Y;B#Cd$@)(*n*MY-6?@rPDaLkOiiu^C zUvj1v8?pZxV_!r`Ujbdh1et!fxYzr<>lRj_jYRuG$D3qtSL9Y8&0*i&&l#Zsoc-ss znK(E0c-)ZP)2%UVv6~>r^-L$5&c=5%YoKq>rVYplN#4D$4dVYoUqg^Ey__&%sq21$rBTJZ}v+-SLWha6YGu<~FT(D{jWR+UE(OYc~qfA1kFrINQ zaElXt6t~sZc806TNA3Y~_!{Jmm%F%{DcM+;jTjLYw`lRvm(M9Dt*0srA4vzOz-km?+Do#epvq~s` zJNR?k7I1Hd2)J9pN_W#i6ill04o-Ea+*)CrENx(t=gwDNuEvPcKlBDyZwLTk)fj`d zyAJ_*OtGeAFeUk%@fi@^hbf)T;%5Ex2>i4xWtXtcly|6Nmb>!uqb5F^Cz2 z7|7Wm#)z28u9!5$^hAt8j)_FfGhH#XYN@950WW zbFjM;oEz%4wXF3f+tV#R54;y>%UF(Frrzj+eU`)3z#V`)4fit~ z>}@i=;40t7x`uB}-<;My`qsk1mEh|^`h2@v?1wuv+%h?oH49Le*Ub!`J;ZERbsT>Z zvaXC)xaCvI^cOoa1(Z_}(md}`4rPS*9mzwkxs>wW^pFR+WS*Sau6#=gWZJXR&%n$% z4;y;4vtn=Orz7WFPsmW%KC5{U{;_xR5G|^F%Omc?w>^4Sjx40gLXO`++bZAmiub#D ztRl3l+~=8?JuycK8YJYS_&*n~T5D|+;2`Bplfr=4q{ z=RG;T24k$U>p6{#o*rdQI(~nrKKQSD=z%+t9vsPVP5wC8_V)Y8Ao0 zd+0y8({ad0%>=ipg4tsj1e);EBI&Io<( z(E7=s^|_k2QNO1%NMjYnFha-*qKs~1ZPp5xWE|9Z{&l2T;wBzwkj{B=1q)3B3KxUU z`5wq)x5c4I|D`v`8O`U{BFDpSqy}2?HP8ra5FX~PlIK*8TdvJ81+`r$r@BPU@||6E zEl0{RchxoJf2r#Sq~Ca_E~3tich$8RVX2d=q2FHaLe%npd625REq;TXPj}Ts)EIYH zO%eY~O^1;F&v$Bi7&)$Y{_$2c-jAaungb1;)O(A9HEq2u{>7W$wKtyWOdcHUw+rRK zcWzA{Ow=KIt@^e&-LRDmO0#9&3)OBJXo*U?G`t7wn$ngftN%H_SWOJ zkpuxrc5TH{9zSz7^l7!i8-aNFM0OkdR~p*#MyGmL$elBiR`7X(XDvD-4MqH#&RsS| z*BOb{JhxcTSuZ79j@Jdx5%Ray2loa+9EMf%J5M+L-y5lm<)mvpiUnsWl&Cb|Kt<(__o<%mGIF63ahot{`zWys}{Ybh6J~inb zK9kMH(TTHM0`<13dxv7oonms}Z#L`AO%BEIhn>pdjBwbIT1?hTi3SaK+9rlMi{;2L^1T%Hf5>bGdv>jC-!dJ2yxJX$ zo>j0(klZBNE>bFo)E8q45q4qyI|ZpSt?-n5(mvsu#w)QG56zaYFs4$p?5a3VN|bxQ zQxtImr`{@Y%^u3tywE;sk2yQ-N`2exa0)5*49aHigih{`$v$zpJ8sSHsO;63L36(; ziLrsc^4``d{u8}Q-$)eTMfr1mL3?;qAVMf6y1UqW{9d4axmkE@Pm@LmSq01m{)BtJ=D=uH1MlA z#>A)wGtW6StyOc3@my0RKWiXyVo9p{tLdfSL}A~^sIS!k@kAl>h&sh~aO)m*j>uNj zbc)SD*w6{A8<<7%Esdgvd973I@PP+{*!u!waULN)U(83M7~Kgg;CMR9mk4|E>!eUi z9lx%AWUHbE7B{LBAbCS0^;;h^BrbZaJ!S{x6UFjQ_U^GCfU>}zUYgKKIaN+3u6ZDD2mky<3OLSla^SNyDz&G zHLC1R@G})PW8^zc=w+e54#3eqX*r+-k0~l8sUA|}2H?L2d2x2jQLoq!IE03S;GaFo z@oOzQ!bSzpZS9C4ADFl339WS!Z(*TRJrgzv8&M|H#w)daKhSjfACtd#EQJE%aNHft zw!ntZL8fiCisKXToUH1a0|~IdPW-tmVhi}or3djH2D7o@riwxb_?zG`8&ri83sDc6u)u*4*nxpW+KT1Rco(n+VCi76u)Wfd4?Oc z%&vEH?Y*vP*qhFLU~w?Q8Mn4R`x+NQc`4PeXR~nAD7});Gr|csJ!Rs5XrdI~1<~MM znQ%=3Ie+ODa!iS~ju9NtIVRq#2D&TFK!U$5vYkfU5)jf_x|I<&fEydsA@6ZOdCCC& zPL+JKYKHBbP~b?C93!l5)1B&pNcqM_$16{T3cPGvg~RQa@)SD;@)w-jJ>~!1EgV*vi2kHa`cw4cMA&Iw#03#&{ zoZsk&g8eJO)(?ktjGfZ`F3p8S5q3;=e`whYF367=ag&aGnIXa%aN@7_L(b_E-b)t` z%$wW?C1V%nO^pOT3BFTEysnw&r95D>MvR&`ryVuJxl>!@*u3# z@s2#mp=!dXHxJ8=fj#aCbTeh>SHKKr%&`R@7D4vL0h{NLqT2@dKHR4KN~s3!4Y)M8 z?fI|O5vu1;kc}XWB%DXRg9l~vA+RYsRpJ(KBj2zsF1R{Zf@TX79_H+w1&LX0ELQgC zW^f}WOgvvy{aF6v#9zOS+bmhWv|^W$-Jk$&7rU9`>s`8B==a$}ay+6hK)82mIjlyw z17Wf=vTd5iNH|?YSDZj!^y>r!;u~Nosyotrn89DfW1bcEP`Y z!Irv_;6#8P(XwOTv(-R8Y^;_WnZcLX(}CF@5N{(5(M&g>V>AHaIH0>!TO#+T;ohBS zX?E;R+qOk=z7UOI#*OSa2hj)xOEf}Ez$Wi%Ut>>9=X)UcKV?LCqOVEczP0%^*rW={ z)#X5cDM8y1&1*G(#@E)~rYvB&VmBP(~J5Bxr+w0gN|KIN{XpeA6ZxjUY zFn(;hjeestnE#(;ki9bMR|o$hAG!YrX?itIvV%ifwSv=Ys3S_PS5q_6?6gI;Y{GqG z3+@{`#G8ICv|nIf0&;ZhNG?sCjrSk+vn-_`td^y#R+EhX0nm)b4EnC5FI{8N@E7Tx z#`0cW=mS&_l~}k$u-_I(14DhBfqbjn-y%hK5C7K8m{%jGbWD%4r*G9 z^}H!SInLIFPZ`HEL#Uj07hOe3KLN*x$|t`@E}wkK!SYA#m%pG3Gw$y4X|1Fdu7Et( zMCT9Ers{VgUqUh#%so9?2g8mhQ8G4f`jHFNO30s(O*9_5PAO>xOc_s*}yo0^Tcuht<0ZNx0}KKxQMfy%jcGy&gXE~CCc|()zTZX4wku& z?yR<37|2aP#}<^|Z71!e!hzKb9<5`puhx)7doC}mYJSWv+xCVYjw6uxK-q?wh%IN2 zFW@ZZx?WX(ig^#Qy&YAyjwS(P5i%^X)v#Y)A#IoEXLNS|9K*r&xC4sL-E7mHab_qp z&4QBS(irop8BVn9Jy@#fmD>x*%(^oz8M@3^LCN-moGUjrL*iuQj2_wHxhA2&#2oL>hh07K9?qkwp>wON%vfTu+2HF7A)AG_X2FsKJb`hm{G1Q}?ij zXh$<}EIU5TSO9qk1|Y<=db7DoO4-n;31#l~!;S;?KqcOd0Xnkb7{&kb>^64w;4{k0 zLi#2H-;Q)(Dct>R44#pGE5)b6&pe`m4Hg|jHm|)t1i$wK!%mA|!fzqlTUv~Te+N2T zz=;n0?&{W=r+iAj1+s^Xy??P%pu5ZTg8}iOz=)g?KxTZ;qv*LIguQoPo8yIt&kV~Q zmL&{k;xwjN1rEuazqOzrFrFVmiy0G}#tNGPiy_yN*KU1MM&y|r2c(sr9teS$SYZ|J z{25R^)@TWn!6$_rNzZz%}Zv?4$>#(K z5=uM+@~rrs@1dMUK>4b~z5%=qPt=qMl)=6R8hl$85EWTrgSYnsv7kq@uqJHt^+YV< z9PH~B-hkK&pp}tk645L`F%VwCcXi^szmI*8zE?HIKcnqo?f6g!1wD)>AS}q>1P715IR(wA@TZD{-B}BSY;Kh#^fH*YF!xf^FD|4 zl=YiAY^o}Aqiv-$y`T*;GPDDASszOjfgbZ9@)^4F-Mo|U!MpOMBHxdo0WYENtECaf zYRSSFU=I?%77A~M4b53G%1no3F-9#fokU1>G^YQEU)9hU#VqfBPH}(C4Lfc~y6202 zavywmb0=~C-vV76!vOEauLfp`Ls4J?k_l{II!qN(pUCI}tbPFbXMhoIIH;f87x^@D zz7<{ho|p46|Bk!FPDd$ii;ebjV<#Z}6N@3ri;j z;~tdbQW0l4=#(55;ukCHY9>LCmC@x`Zz{|oQyPINM7Tlgq%aGe+7z!66*T}dE+kbi zBLZP9*|v&h6qpTkMuBcQ&MFVeeMWK&DX_#*i5smru3AbpsQ6jX-kMWz0sj@CYtEyt zm|U(^QF2Dbonyx;oQjg^kO5=kUPT#OZM`nAX@rEEVo(U7a%w}aqGX!p#yLevlj>LG z5TUh3DX(2rn3V+~a#>Ax$~uFx2nTVc^q{eI-%7NZXn1Nb*}L3}vlwKlc(jmFKt~Yz zLclfVVB6Gsn^h)R@t1wcW@u6+=7WZY^UN{^AIkt(TY z({_#W{3hwCffYzO zORv7G^eW)`QT|HUS4h%u=Tx!ib7P&W^w>K~)N;M+_g77#Hgky|Hhtl`yo4FL6SBKc zF*E8W4E%E6^bw{^uI)i(q>KTjlrmu-kV+iERAQ`epY*D06G}#UjCp+v>CSAxNTJ%O zH6%Tz5T<=nW)fXy$aQbA*GwV|Ef(jx$Ix%*9;LNCAU+Cz7W{<$Jp|Zw+Z{t-Bablb z;9BFRKtAZ{3Ap*6Q}A8ETln@E^Nq))%GL^44Xuzyz@@-F2)7LGDeKn9zk9qws{I_&JzsZdrY09 z!44HwwgHGD5q2gOciHA?%ay{)!;rr#&=^bL2>U@>#{t{wc|Y$a+A&k4_EOalrcfWLVtu>IKz8POGG2;)6!U?T;QbACKSWuRTyj|$PQ zg>a5&HA8Krwx%D{PML5!#FAuxV@(LB6rKWxeNR+0iYB!cCHmF+d(%|=#b+;Qn6|Ty zi8qx7+;7p?gr6QHJ)L5II!>%fXvkat2*XX7eys;+Zrp6G$DTE8Cb(1sI{_x}r&z{kw zoPT4@gqx$~n6DAD+6ft>SCjauS&T^=tAJfsk_LZnZvyUZl+aP2(9?UB!l$zDiM?-1 z2K0Wok_8w2$MQzuyK)8O23pGBlzLh&hNRkiHCSSevC+%MOg5G&fT5s_k8Vk|kDhYj z*>5$GchyaL%H!K}_D;B|HYl*ht(L>Ky+DhJowY0=Zt*LGgg|~>sy#mM!n5bG#`Rxr zNMddtcLcx_PqD{NIs0r2dj4I9v5YZqTx!QWif}1}rGW`CLCWL8iyxW zn^NtH*b7T(gwV4Txuw7EnQ*h1>(SahR^vghUd235jR5`a7-VI~jc>oOC-Wwoe<)ia zM9F#1?4kV!@{$)Aq0w5~=E&nv_JwE3Ugw3S6K^Y^H>(g7a@wPNfE^XPxqJe~6>1*w z!DI#S{HV|N?g1XG?E7es*}i%CXSXU8EUca}H|LlCaJ8o}mwlX#VIOB~jNyEW{p_wEU=|#;89lQ5**WpC|7urAAQ+0(#u;7|-(|}r-CltbQx#Z{fB-*FBraoW&diW0#i%(W=PKI6ZBO78&{3dv&cWM$DEl6P z?{9uaJ^ugE_9oy_6PO{crlBP!cck#&rt($bmH8SbJO?Mty^{KoKsb&PMtcZW6t}#;UR+fClb~*3E-w1GIvWEhPi&;Sl(_$zK8p# z!m@dtWGsH$oZ!^@%;2R(Yf6DbrLU0fC-skIdB@vM@Wt3mUi3uL6G#!aun|3$ zExqq$xe_1GhE>%D4@+j73-W*;NZY)4yZruN?~P9p-sHvo{oJ%yYpA{7zsE8V%~8kN!Z|?mFlftfw|rAmB#u|9-phv#EiXRb&rMLiKk;69M#tH4 za=&@KkNOSupqKkpsUdc|HzWTBhc-2?F5YgX9wYt&i-+v?x8LK%?mhvSeGTy5fqoO{ z<;CZ4u7KT`+YmPL8ePBX-UOBt{5AU^NhSdYNX_s(X4Zou_A1a< zuEMnHy@_a(YDbo9j&_mrb*z*A)*D)Q$`_vh5$0v$a~h}B;CU_(@K7JH;nL!n`UT_v z#4(18`x8e{M}mq~GTgHO_ntoDh4yr9KeY&TYN8q7ZF)%fc=^BDZ!!+R1h&c>;X;B(zT-=zE-{v-ba*FgTs za(?;wYJQSeu?EVam;*y0N#6qvki7n=FccbQg*5Y`x$k&LR3kS{>%Ga9b0tFm7Un0O zd@QGm4e@}=bTCBLvWgX1t|58n9~)A@-MFnzZ%@>4jYa;vRI=*G!T7@-nhJbp;k)m> zJmSSfI0Q3Gzu2J5*A>LsBRxYs$FXkU#Y?>d<>f>OY+xRbj?%Lz8gJNwA6&q<6PF(6 zTcC5qnV+~?RY8a$#-l&VJD4G%GBz;@_moeM`JWfh^l58Dpbd$1?5a(ye5`hmBe9Z8 z5Aj;B=;X2QO}Akj4#t>-c-<+d-VyPv0)(`?HgLcDJgzUQdkvWKff3}hz_{^$*taRBch z`C-6;&J*itm2q%)@4vuv)b{wzdKR}i$YcMb?R)-Tv^~nP6>a~%Rxh_b`fA(Fz0O)4 z;9}`54ZJwI_a`5<9Fhw#^sk1Ht5`{pv2r~Q2)FP#-ovFvcr~Z_RG}dpyTJ+bmFOXe zm3>EIH4jV*xM-EOyCoL7?*uoa>l$cvsC}tdj$suk;(Ld3c+LJO}9tt8}Eb_miAB3EB=WphUqX z*-3v0QNQ8u!icgI-(?rBD<>}SKg*dF7$|4)|D_x~#g`7oKSfM(M{F50#JP3YwbHwj zYdK>=F!m|cOET^wXgB%mGB|6)_pilLVB(HaK|NEMZJ7y516bW zPayJzkgir@C$*~bzOZuQPXS0cI9a2|evsv3%8T`SzRGU>b-RgcruA!B>6Vc0CUsts z=y`~DMnbRjSA0XUH|d*H`5TO9+?0cfGmAu~d(#d}veCr{)n#0!_1A53DZ{-PrLStb zn{=(5Zfovv@6S%WL7Y==T9kKeDe{}L%pXCgN~dyhZqv<;+nRe3Yr6$C(93Yp>s`GI zjB51RMbD!beFW=(&f3^|Xia+ZR_&5!nRs)uU7f#%t(2 zRCd!E@}?z--}ISEx557p>2L?W{Tlc9c1=vR)-H&#h<~6xDy$Kz!)hs_s209<1#vO@ z3h^5=2`lB_HKdc|3~_iO-+D6t1@GxS>MS&sLfVD4SP*yh8Q^V>@`;B+9iccC26^Q7 z+{l-l!=1xQXg!#;G7kHXAqC1h8rjOn-|it^$H^nb>5GS8STk?cfGWV-&) zkTYD$dUJR|K0Fk~xWe*Gew9GID+WBi9CAa9DCi8DvgrQQ=b!@`Voy4QT<}&dZl--TZA)m#eWigh z6Y3)EfzjL5`o=^}W+MljKm&?6VC6R&>|5c#nMQ*Tdm~6U`1}i9apq-thG}HI&5Q4l zjYp~zb{tN?duRWh`1^7{XWD0uvlM$LbBpjiyMH167WS_N-w%`#zn7)0^3E%qASGnN zFRZx9Gslro#?o$ue`{@cao%jwX9k>O?>jroaj)xO&#(Q1S_8MFmtJ-)gq_rg?mu)u z#+MNBxk^)|tqQFQs|v5u88tm2omR&}@`Ea5=baA?sS>uRU!W5LoVd4tid^dWz*I+y zl;AW;3B@n?lI`OG+b#WX`9@)lJ|!>~Pd=Pd$_W0Z+0$^>-!qxW+=X*AyK8|pyK zhC&~54gVPJy4RInN^QH=GEV#eC-SauS-5etZ;(S*kOgdo<_SHT&R2Rg(fnJdLaA-) zDo#Aue=5yqIn=zsUcxFo9?z?Img6eX-hkuUzJLV(-jVht)v?$a%YyIR zovxu0m$+>Pd`Q`Tg$0dtbg;e0cTES%#7o@+I#AO6?<2m2f73~a74Oawm{THVCb%JW zr0DV(;utX_tOO9FC;Tvig!?M0qP zp7FaZJzh%XM>fo}l&&j1E-?#d*zF{}H#hA8|H*j|_#5X@PC94#BVy+SIObVbx}dba z%^YkKj}vaHX#L?+r7CFOSoEeDrg9G2krDi6^WvJtp{fEymPIn@4foQB#)&^4C4I7Z zNVNxchxO``kUiLw#>o1V(_WJ6{KQ#N!v9`a0$kS9p4%CWr?fwbozr_MY8{6&;-kx9 zwV~69BLrQy&^x4HUum?fyr!n7qbs&xWNDEG={(z=7HM>SvGEf`#r*`-0(EgQM8#D09p$|&zzRNC66ibvd1+l~i2e4` ze`~zo=;_`A^Eliq1%t_np!NmjyOH36KJ|m$K3? z5HsRj|2f|~rO-GyN!~4L*P))uI+Cr`yEVJm3*1(UJ_H}t0Uk5RvLz-bNzQt$f|GBh z$E(-c$s=8*eKYoMr+R0@%hO-rMfsU90iN~dyXHz^X6^>_m5rWs$bE~onA>1q(S0V* zvCFd3I|F|omH+se`qHXWV)z z9MPmW@g!`CJaZ{MBABj|(?3KylhX$U(<9{ccPYP>gZ~&0>^i8NK}d(cH$#Q*q;x0< z4W0Xm1-$iucK|}Y+_KHSNcs0UjAYc(r?J{7^VPzCsj5!N-&p(ypFB=M_#T6`Nu*gLg`R9l5-hB&c-$OOQ z1AixO8m~|`mGxic#af7oK-%7>x(_OKJd~+PEng-i1NLu|87xd`dg1V*mPH`=$ zJJD8e+GhEs;RVaj4S#^;m)4PLTjaus_3(>{)+;A?p@+5cJ!(-rBDCm>slI`|R;t$x zId)RDYUWsIiEr*ockN8vW$8NOK1%QIPbJO6PUneF5?7#hDkMh(&fg-^o_O{ndNV|R za~Gn=8D@u?uukZ4FD!v|mXc@XN0iQ)l&5<6No#8H?Uhfzb7CU)!KokIpQ=9;Cc~#K z@UV4p7hFlzYZokb#n;YVs&GL}@OL1;TF$MObDwpELZbkSwFOk$B0x3c`f}~TyoDYn z#GiFV)hZ<#7A$np9pssh2nLcJ4|JGs+;HF-jB|XI>-1#D-VSr>=WUUxcXfMuxGF@y zg)N#oS=dB(zeqH0&Gcp#O}BG9GYh`#@I3xi?u5GK_F48Si>^-F!S2>}nD0*Eli^`% zbRPDg>owx)E=@}~n+?Ayh>P8I5ozj{aPHF<9bXo=r6$>?5lg#<7YrSyY3&^}M^cTL zoA^*}{Oqm;c6k-0txH*~wxy=RRy`FE8dg%I6!z zY?gf!U#)iv)x(^GqomWoOiD^vru-$*Z%79$stT?s{_u=~>vZFs#Gj<$t(3UudxkT+0b2tdZky%%DAC()FBNsxd(O zXLKJ*a6@ylL6Ka;^1=$j3po=!n2Z|b7Mw9o&Kcz#R%;4sPe>+%Z?L3^LS#w9p{HL>c(rCdtmvj~&d#vF zcP!#UWtvkyaG?~>z|Lkc@=CJVF~*(fnv%a$lhbIcp6(cLgXf(@L=j3nTl2C-I*k%D zC+ANtNV0LJHxWTR99Uqfvl}ooys+3SsHc(~Mr zIhLj7G!Rsr48;*&dJuO88SZ@zBM`NK=3*Z9j^rb_0~4{G2H~SoS~(19j0`f_;wt(97k0yfa+#hs!vQ_pibwz&Yf!aM2 zq36*S`Pb?KA$Qw|E5|iyN7uLUdJU{Fd0EyTX$+nyNL zIgP4m2X-US(_6py{1KAKA944EC&4vDGq~vm_{)iMCb}+azG^8h{pMz|+DzhHJY+I!2eCtC?>3R%(BlYu%(P z@~>lp_a4`Di&=cOBD7n;doF9bCCb|%ZE^>&j~eL;(7tKK1@wt;R3S}auH$Xoc$UV* zw<{1|sx?l{wW>I8L#bntD;hbU@g$U<(j+x5D~Kumhk8NNT-QbQ{3fgr<6`W|?VcR0 z599deMXpAT& z-)4^`Kid%kog6c$j2UjNQ^Dj!2f?)&JD{fhs4&=>(R>lDXfAaA7 z`<_Qd*zk;XgwT55IL0lPgZkzmVmFNvj~>+;Q)ljQvXt~S+=R25A8J_ZMvs8#dvPJ~ zhb_AL;~l1gcvrGm&c!?9T{)r$zfrE__AfD8CviDqCKrY09FfQGxl#)>!sklR2ZI{( z!3CjtY_w_=k2R8K-ca`mM5@3wdwmHTQ;Sh2CdlUpeZ;pkUK8Ke;~E&ViGPX5C*YUH z7~*vrcUC$cEqt^Hn&-qv3*zE=+eelt_k*+G+e|Ew_cia_|DZz!4t%kT8CY8Vm0Hi0 zN|sjQT`}waLRd8!^vUBrMo+3co<@vdJivP#E*cpPNx(QuD{ptde@(wnR7JFJId;rF zz4!ZW#b`^O6>i(VZN@wwtZa@Acg-$5f{0+BwuRlg@996sS6M!+`>aI}UU9u!_d(5` znklv?s`DIxIQ(o)wS~v8boypnU5$AxPE@(Sm69sby-Q2qs8|Y)D6Y-T&k1q>e;o%* zbMQ*90__TqOm{?a;kL7`FTiC9@Bc-LEk5r`)Ct~J*Ov)x&Vx=p$-~H*bM(ep-&KyU z9OIZ`+idyj;*O{PY?@n*<`$nUK3+`tipq=5 zC)>6(nuTTvo^Vf~bNZ3Rz}xd)n$I?RF`wzjS29zWZM+BbO6DP)<%*N%5-olM0pGX8 z2Ltm6(Vh5#VXPxwA)XOwf96SLoF6(f4jQsFH}%GNyD``w8_;K>9dlIOO$jc2vNi?j zkE;xvkspnoQ@;zncYDdUl3mVi&X-_Ww;iJ+i^~c2tKqe2K@KH-4b@L|N{4BdQR*CD z2zw!e$<4&Cuw(sV_l*Uagrx_I4Qr)TVK$XUuwX}n#s+$_UWU@_Vi>)=NZUsEMzuqw%>SBw2>CiXKyT?5as@h<1V+|goA)KicXIo%_NO+=^9oisS_c!$8Q_2ru*i-SfTmZGZXAbHvqW&aut8y#i+-(5Io77b8_dM*JBr`DL@NK<8*G z9SPrY4JC7>6a(#OS@8>>Al=+FwL{fnQwc36Ri-s)m0(&4$rSa|xIi!qfH#uSSsbi@ z&6vrFUtp&pq>G1cK9fd~sSQJf8yi#e7Y*lIEIik8oR3;_tj(j!_~>iRm_|@`eIvYI zz)MkzLSdXx9LdxX?qQ9?3Wm?Z_r=5V!0(TnM}y->Li<;5mrQOm(og@Ve-yKB;nyuvY<*afZf2pV(yhh)4CHvfgk>~)&-n;$YL844 z+*3aw-ly?VZZBFX$ZKrN8S8M8#z)S)z|!KQ))Z;RHlYSc9}G6l+dPIMqW*|kQ7iLc zv+^10xfQlr>zG!EX-dprxFBDxZc3PykWcOL7+#vapg1ls9ya%E)bQd33(W1zy`VT| zO^nE?_0TM%Cs*k5*U9!?gM?q3!sHTuY{D*?{0^%KA!cRz!fi9;xTX~{AAvs99)f+K z9diGrwhXjmM*bOYx&>Q4ux*&vo;pC5!Tm38)k@{X7oyu;0z5*oZ201^ggH0IlAPb*)M}y z#x+aZa(LrP*t2#kr(7tf%8PG<@n7XuJ#{XT;?w$k+-STBjtJk#bJq2AA}LGZWO!@5 z@{Wfa`I@=JalRDRuFB?=)--0R_?vwYbjzz@p~&oKLh+>0@`IWp z|FPtZ_AiTdviu5)tooqi@glChezrkOVnzP-+In%lM++;dKX^z}tm{_&8ez@#hlZqE zbAEk1I>F3ag^WB&WB8zEsMl7IlP8#uB_@VaE$X<^=0hD80=prv^b+(r$TO% zrWx|;Y@&y;Eo0U+Nvh`eT!UH!{#cutYe@*;Oj2GoH{pjGRmO+lJK1jKsdU#=tb3Jv z)kvq$4G%ZbF3!+^wJJ(dU3M7}p^#3c&1KxwgWc=ePP8ToiCn2nD+Yek;Ub=t`w_+k z_n}3@!8MP*Xa=t5?J`Fe=<|nhX*M=;R>=!aUR_wiH@c4mI@f&|o*!PQE7-~6ZArES z8~Vrma2H9@zj#MNR^F-VZKN|?G&fQIr1C{v#2O@fs#AS{CGq!W9$Dn1`7Xp{C9PjeMN|RySm^gJ!Cx)Pu)0E3 zCd3W3IxQ{^zcE%TzC!se6->A$}iHn@cT@nD1za9pz?q>s+C{Ni4Slo~3}L#43)o zhFjOk@C@w9g+SLaaIeL^85&gaQ1r}=2e@}N(2z!c9eI+j7k<*vDJ=ZG*A8u1(FZ;4 z?T30g+Yv3cTyvJo3QuoqAb4~KXpFb{1%q;D#@>bdaDk zCvyF&!pPFEU4?#2VWI!YLe^r9#+v2$aY;4jxTJe1qx!jL3!k<5Lu|*TILlY%o2B6x z54q?a=3QpmOWG_YJ2xYW-5&F9^HVEMS%;bn{VLlu>-xKGD{}qnT%&ojWHb-P4n*$V zJIoUfs_u=os+Me)Qp{Y&`rqm5Vy#=P>z8kqMh2g4e%_LTOGsb4Joc=3L^X9YcEZlH zfN_VJ>lWI$2a^3fA7d5nAzoJ9i@Yk;lE3?|t`NB)}hoHxFsZJ4w zgL5{77EmqUMA)VpMNKH61;_6x4 z2*-|6-n_{Y?Tu4I%9;yb19_4&w%TApL@;<#OUtPH6BS?l*4$|?q0$>XtlJ1xEEz}4g(~6rk-ev5R?=68?o!k>XLERs=C#Dm#%KzeJAdV32GGG zGpbuXcUkTp;tfBOUtQhG9tdd=9^f7bH=F$EkM~#r1%1`yt!{PRCE>5(F6`~h5FQ{} z{^G;_geK?i!n&O0-12BKEHbu^TavS+N~3O!(d5-p{W&EZ%BV-oVdaiWa37Af4@dlh zH1E)}R5~x0p4@OnqZU=d3Y52EdB*bak5(+BT6J|9OIIxA3>hUE7`+Ha%I~==6uahR z8@4CVs!_hc7zv9>H~jo2AiX9)&l$@u_{2j+qQ`m{v`ZIV7fKi0k0%`>AsRv1`nzzN z;-d3H$%19#k@#iGo(e4bg*fY%A+YIb(uE{7ncLSF7pka?ygJB0&V-UA`+^b<(zvQQ zrhP=Drs0f6-)LIF(mESr+7lx?y|SNQXkedJ72=C0i_Pt8i!b_~RdJ1^#YIV$m=!d_ z3Sy>UfL8`?TFeTm;d|gye|RvY+jsj%zzlykxT`OMtzaW7bwfO%&087?c%j@_&_u19D!Culzk|0o{&C&=eg zr5VHkTi{&af+aM!&^gqrP1DuY8<~;bp99SX%7bnL<*8BLH)mP$w>~b5n|ik9yw7tr zXW$4ILOe!a;C!LM*zTND)UGeV8Ksg0`@)i#73bxB`%IY*ceq%}$ad%aJDiADzl^i* zDlynIF{|3-@8d9+xDT;by&9$Err)c|Od1rgO9*2UH;qZELM91GOyV;RSVZji%Qmgt zZYkC|82iVO)HchkgP6S^j9P|!v&Hqk#?oFt$AVcYwhk+)IYwNu?X1Y+gjChO*MPj4 z-w7$u1$r!2e@M>el2?SV#^r*kFEc?69+-}f+D^2p~5M6vyeKNc> zPqBXv4Jg*^#aSLm!(5>AyN^F<({fZAI7Pp?HLHC)2D;n3N!+4*=HE+>` zHHNK-a^T4p0~^_2!8dR9GuSjn6ht@%S0+|Q6om8$9Wk!t`{?v9Y0CLin&udsdo`{Q z9Q2Lk{lQ08kc>I&sqBGz+=opCDA&5!HMnx8N@aiYKu8bQ0Xvz-SW!@$yi8=hi8vp@ zM0IaMLA-pY>5VUVr-t9kZ4s)5I-p^HJJ}wcr>Y9siil8%4;Y!p#LGR=uq;b(4Ymz) zst=&Q!H-dB-Z(o>PV{IC#@W@#^L@`JZO`*+jA`0Ah~vJ6tNO-AuragF%y^E=WDL6D z*%rcwbU3;&dRENLn4+-eah0i+Q(a^Uzum%}-OR-_#&A)M@bd*N2(=|)MY!B%KkziT zAKD~9{|5F`rK21!_!kbgpX#Er2`5yi`|ybW1s91yT#NuNR` z!Qdbc^g$e~0S+S2zI%G~zrn$xt8HI)UE4Xdov%87t?dR5Vc4kch(Dpjtl1r7E4`6gHe#zpOd|y@lDi@y&5>TfQsiuKYaP?i5nZy8d@4Zv;w9 z#>%ESuEz3XG1uzhX2>PBomRK9Te(~2NfR?sCT|sa!G?SB$X8Mv#xDJ#bqChF?#39g zMa8#EyhW_Hd=bKlWhLmbOWmc;hhc?X(6H2H5)F77Suo0hv&ng*^NpfLXA(7o3`VWVfYTwPMUCciN!t2% z)_)>t>pzin&8a01ILS}>WJIqHbm{{}m-W|nE1kA6I*ri7sDi&9{O((lwd$c&)n$n) z$i_>rl!aUI3k$DpnO9aFT&3Lag7*c2V*si{GK>V(L7!L!9os(anV~NkaCz~Jb#2i) z_%dRfH`}?Y1Cr76sf&$y!b=+dTct^Qb<5{rpKDe$Rl&v})}GcpWh2F`8_``UZOToh zb*z>mWMz9-Z?xp*c~z|*z92W}?8%l;^#?T*Z15VUPsPqOxQGi8N5bQbD)S~=f@)4< zKcX2-GEnKKHPf4rZkVm|Hm%v1o69#$Zti!DwBIV-l(`~_)){u(P1*Qr%`5O2!cuIx z>XuK!{@w5fU}d`@1;YWnPw*Y)K*wsFcv z@;1K1^4R)ab!F?BX@mkA<1B30OT*BE9Lx@~M z^TtC`>ZS+$Ov`QByYX||wjQyI^~68jDCuF(gy^FUd@v{XQj!0&@FM?Hp}taWOL&;@ zN3QyxwZco>q#06ZCbx4NVhH47j?Hanxqp#V#oV?m*DD)mB-PdYnOZxVR_e^)Tc71r zYF+^EEqqmoxTvdnBWwXs`x(e90?v^|Rp*rKz?$;hk{ntQk_~JQ#tP5+183lc7dzZl zXP|B3@i#V8z~9VFZiltKT(GuVtwz5fP;c9z;T!p#J2jC_{0@F+w5WnCsW$M2Z#7Fx zF$ZHW?Q`hyXeQux4p;My!p`05Sxv&8A)-n>v%xT0*!kneZ5m-`Ufm3l*PK-=cY4ht zwdpxZGi!ERK9^$Mu?ACMv#}`y`C*LzP`V#aWYLth*s(~M?zBABu(|I;X5}7-F%vIkeU`(vX zdQ`wVme#Mdj*YiQi*LdHXVT%9TL_P@(8pSgVgTdkA@jw7Qb9=GO~W^aWb=58Sc)kO!r6W2`Rj zEJ?1W_H8j%KbMoEoddaE4Zl%*2(z>%k09DXmbp>IqW! zp*aj3JBk@#Svhi)v%2R>tJ8^?gosb5;t+?BTjnYl9?hpiHxpxBDqE0RU8lHHHSyLk zt3__R43pZ3a}Ms3M2#St=SD&QU>&f$sG}41*Kp0reI~eumG4PQV8vbJm>qSoJ zyVHMzMMRhG+GmgtJLEvihg zy<$=F2$xT|z6H%T1-(a>lICReZ|{A zXwQ{~4}H_HZ_d(R_Tq%Ws^PAii;x%8+I|)-Le7=Y7(Yz3aJHeP=`y#PMRmoLGQ!;w zAK`i|TB=6Np7zjAJCx7Zkzc)^zoESS_c$v)8Yi!6x;OfkmW8K(4m{A?C-x5q#c8j1 z)&7yImRAz@FPHb2AKag6Z-u4vOLRs9B|NzQ9v_DY-#qq?i}x?ZH|6bVa@n`~RK ztnQ9-jIqag;^5h^yn7+=N;zijCtR1~3_0bA=~2pZ?9cJZ``tnQS%zrd#DCb%Ftp=$ zX;~P)`Tc$l_1>_5Q4qq^{RIAen-hqP#t3f2eOsWlR`1bx?Ztud4mr%d;hu$m%wWVeA21lW|@A_kVxIBmd2g zZ7w?9d-44o^hkC0_m!_aot3`>a9w!+*^0B5PStQ}bG(J83145nKX#UC zspf3WTNb0lM@pyfV|-RTC^OaF-}yt=1)tG@ao3gq_-2%I;C^BSUAAz0KAB9Ha%&Xd`IyDz1~bw&LP((uSLIs)o-0 zz4`{$q?lvmc?NT>_OSZu+qkmc&UBpHg&ggsGfJ_b^#SCMEr=}^AJZDfVhaZ6le`8WOogx!#(vMsI@qud;;{qx-9+ukIQv{rl_v)Aep&rmiEIAG z6aJv%!9mXF9yGaWm%g|2FTHWqm<_Vd*O=TS@36WL0XLOT?Jay;Su+$AZa9EhrCO0C z5o=SLQ8c}hrP?t*{330zT=7DZSqHC({G>W&RCZgxm2}n2gugF8i<)3V>cm+p&#yI; zq#>C%*}s*fO)NdrI}u(v63gDg$|3!uhZF9!+?n$Xa+0*e(q=YHk_KmvoprEd?;~`E zie*e~nC3~(%P0tG*$~1uCENLy4bc^t4UTmUKz0DoeAw`|@9(W#2w)j`)>n(#p~c8T z9hv=|t0iHFvzF49rfbizv=_XbiQubiyX*NSAN;{5Z0YZGArDKf_EN5c9eL#~r{D4Q zcitf_fQ`6Enh2OCc|P)8`-|83w}mkSerf+V4!<>c7wDV^ zpF5Scx`K$AL&_ow0j*kB0C-0k+#{tSj83GI@0mcSxz2sG7k>Gbr^&F(q%x>nDxd0- zZ7YLzFF4to5}v2aPjZJ=s>;IieyGWmV%gI*o*Hw4@qanvN-*hB)|)72FD?;hIzY+a zSVX4eGgHdUl!9<~Mp;bR4>f`qP|vMRb{LBeg0F6dTt1?EV{cu}kzD?iR4c%n3HIFw z$##2#xY5Hs8xX^Hs9VH-U!e2NzybLjwyI^lidFF~>!Zn9W$(j0sQ3?wzP+~dPAhj2 zI^o{Vbv-}$B7?iN=h1fu;I;t=1F+|Ggt3!ogZprdBPK64AAMuyV4R1{a3^_G?%O>& z_XJO@8$M6^qa0+<5?!Ej>+tS&Ppl`L0)#^>>OiDbm^PGV}#GKGN*!h{8bykZz?Iz1~gxoqAB!QMZkS=7$vu zHnv$0TO?J>x@f{eKm5t^2lPj&%z^R;+C|t41^u;$=}r|q?W{#CI;m)sWAw}_NxgSe z;h$SWh10Dp>|1HqrW9y8w|PuOi&_MnFk<1L>_(+;GE=(SR0+FOLy7%V%|t1h?F5fp zu3l$RpN8!$bju`H&MFnyN?$tTTL7yi>3JGUh+YG9lJSHzq7}8|CA3Ml{R!IP#1=3^Y`)&DD~omfP?LpK zC;ESRsP{z2UN_mf3|N}cdPO&DVwqZm_2AgnhOk+gW#-xeiw|z}&6pE)?jL=V?BC1w ztpojLfR9(Nl?iKx8uH8)8y2BBqLD39~Xe9P0(Bc+)7_4DGZXTcL_O7s~Yhr9}A*w_x) z{z6(efE(g5!V8TP1Sh0(s+(XdGB}3Vcdn|mho)=mZe`y}p1rs>@y!zx_u9r{J_&R> z1H}gc)3XX~q4zXm3^fcZi_QCY&17k?8>1!v8OBfz==i#2Qr!f*-j;*i7nL}-YqV{# zeGKxj^uJ?`iSL3VA(ie$JVK%%crFMR!AG<>N$V)gRJ&BMbI* zcw)C&!p^9I>rmRc;SECY=^*@Ia;F4Cr%w&R;5En=T!S9%r54h8ZEDSbwm%Q;zxLJio(AyT_4t`2 zk?*pBHfD;<%t7Deo`Dk;!ok-5BJPw5PazJ=@EsQJ4Cyfrv<9q-Bmx=*%3+E1+1&D} zL(=t!IXiEUxWLk*&+7`4a#WU3vV~%1>;fm)jD8icmzI7Q$G^vYg={r|16!Y43~F$(_xtM%C+te4?C@`vkS zog~8wA2qND953Ie?K^#$X!L$x1yg2isNI=ZEr<`w&=KTvjPrGb6Xh-@595zsKuH5-aGTf`ZPl3C2<%Kb zEmYbWA9?&hO}IY=|6v8aMzp#CZT)3(cfV!qljhl(H#F(H&(G9DvTLMf-TrMwQD|**_X_6|QSvwf4HJ zdD9*Xt1`+hzgZGNtMHGm(F%T!#O5!MK@@<1gZ+b2WDi?8<5*UW&@ zFb?zL58ZqQ!FCz2WyrAo1lUH)u>I&GxYh$crJqPeo+6Cm_Kz*pvj<&Nx0(xe9iF7y z{Y+;@^d&aN-1c|{l}$6tqeUNE%x!NXwf@SZ6;vBDJOm%B@B?Rj5Pf_NJiOERa3U~Y z?mti4J-|G9DsgwskyALaHbAjM;FqGSIGFN&Fy+p!nZcAdf+_R69Kn=b!IZ+TykN=; z!4zwkT~1kRe>OB);OrS%LA`50Ah*;tvkK;0QAc&kdI&bx>(sFoqg^ z&xsS|JRE$%5nfG>Jr?_gq?a4uEuEg}drmaUd3dq6i_-SD!6R*FU&MFQ`RvLXZe{Z? z`PoyScO6b$`)c-lTjikn$G*s3^FWIb{rAS~`SQO{ve#}ITm8w02eTJ)&n2!5BOWVN-H`mNa^>;nC9RQh@KQG z-Y4HL4ZgX%pKxAsl_JdOM5&7r2kkEKd8njt7*U-Ud1-*V9R0-GoY)n}4#H&)rig)Q z!Ia6t6klLUFlB5oXg+#N^`ey_wOBT8^$vz(I?FUY?NmvZ9i zKEe>I`~QP4HMhrRje33av;qE9enZUz{E2xE_Od@5$H+C~p4@fvOiz?7@;5vhaTfF5 z@q2PdojukTqtRH0HL$T}ad3sQ-}jp1B@4UqH_xl`?{}VOgYEqtJbLT}W#5&f&S@)l z!!rWSkvKcmr+le!H81W&4zu_f;vU8!$=MY*xRsS8b1^kBh z@rdo}0X8@EKPuNrbmYVzuH(S8z6a$u6f;4=d{aM-Iv4Rg$G#Z3l7fpY-2z zU0EOZFAKINq)(ye;r^w;l>S~N<=uW~Fr_V+vakQnV9LLODLbx%sTpwz6n>-cDRRYZ zFDE{Y-bRp2#rQ8<*U%Y^t3Bz}0NpENUVSg1NBfWTQqN2iHJDcpFK75!H@90->oek<_|GHrREsl0(vXOMgi936zIX=bic9M-Nz+ztR^k_f)DEzHa)pK2E$DeRW_oA$t~1TrI<>jL~xfN^fw>Y0Qv}S?u0krFNR_ zlske=x%1eqkVkf{WR=r?xcQ0S%3=L$)0fQ{+(~065?8QG#KccL#0~JNR$&It6Z$+d7b#r5s!!<|#3KqP zyXCP%;o1*-G|kW8Y{&DKgBPi8PTb$4p%ugP3Z35UxyCoH?!l5JjZkO{=i3*%U`W6Pi zx-0lqMBi<}lv{%-sy^at>YYFq zUZp4hB=;-Apjmv;qd=JfNO<7)oXnF7-VE2_A|Z$+k_4Gy8aVcsJ_T=7rc(Zq-b@)n zs#i%l807F9k-w|^S}%R0m+~kOZ1GTD1qxsHB%earcRb;8Sy+Lib_hw$Z#ciTV9URY(^nv#DiyGrK!AG2Tjw9Fg2<3#rU zvOf&_*0}*s#3&PnY1M3lYnS+o$&(xI`nudzXj{U+)3*WjjB>(l6(E0G?jMk?1bK)q(=Yk}N z9!RBqeL3tN_yB?A{18TuCwd~m9~}A3LwpL#L-;2=e|=e(%ZYzRJ{R)ciztG$mKg-D z`U+YBiaM!4NAv9oq`@)HErmp+^i~BS0`XQTiOOKu9&9nySNuHde z^fh;mIh59i&Dr&sf0X(!ND~Ji!zt;u1j2+qouGW@;$pdlO6$rI%TSR`2zt;Ft9>n6 zu9dZSocNKXwCGQgvhJhY%9l&Jl{atW3mV}`-={?huSitmuX2s!#!`)C7Ztf%`3@(g zuGUETpTYNpYd-k>+F*@ONQzv2t;R9I8XpYS$aB*{>lM@+Dfm~ZsevbS6!45D48cJg2R8#;nWGChyw8%FL}_t@kCdJ{cqJi*9ONc!?3f70#W zN-HXg{JPsu=28!)S&O2AvM~=_j2v9%ed9{tW}5N4G}d-cjI*&J67#)|Yq1LD`Z;Ww zeF$u~S=5TSU6vyMsYi?a7M{P5n7Ax%qYb_wkgLc)oBO4~V>gV#cR8WWCU0XTcMGMe zk@-nZx9-oR&=7)Hq-u{JpWudAA*yH zqHn9^(%E75Z+r<>mDie-1N&i4h_l(@n_`8KgtKu%Yx!KEgT=(v*)dKEEt=V~7JOYp zBtbuiZTA5SR>5lY&i*LUemZP$_M8xw-tCQP_e2eASj^7wTr0EH{YE zQqvkJBHLBLe#5Cn2U+U$^EDj|KD?TXGftO7${HdZ2hJJ1SS)62v{}EH-C~cYlL!wT zj@xbFFDy=cKW?avn^xo}EYIQF8e*z7z`+Pxxn9%y_-&e&`eKUd#et*xdXw?@N{@6D zR`+})S{Kh_e}nICI*z}3+o$lnjP)EM)Ipx^!#75~?Fi&rnrDC|P-WF!8x9bEY_adO z-**nN~QaP zDF=cnPRSKac`KN58~P@bB{61PiZQoHA~|hfJq({u(j0kySsa8bTkcIXD`EDNS1>d$ zLoq7fGsE0`Ca&sN_MH{FjtZ{Zm6nWYq9?Z8vT5*_@q4-MTYf+L7}hJd zW*5qG+iSGW!6jyo&pM6Y%eZ{FPGu7xJvOs(_=X_-ql}up+d9!Hv4PvXv$J>u6)$*frlO$KZ>4B!Qs7q+{9VA#1TI? zpq^Y|S6HhyY;W#`2HkG`yQ-EAYJO|vi^2=So?Y+!%CcyoiCZ_dq;-eUA@+4K{ zRQqZLw!SkmH0K+rjIbTBpX#O6a`{|>5%lk8;!luDjNqA%WtuB>sboz7bdz0ck;`%2 zo6g>_U1~dgbwZB3;t_W1-z*&ttH;cft#QoS&93k`k$19nXh>p$6~1Bg@7nNgi;dlI z%SFNk7sfKoZCxJyJ3`BPj-^C3zw`FnX?bBJFSxOOb>}cSfw!^Lh>ILXnS&laRoftJ*T3liL?*-Ww!u73 z_Z#>dfHMz`J|y#TVhwg~m{{u(cIo!O2kRtzZo~yWD862Z+{TQkYuGxA#n16w4J^$p z+SclJ>EBy2d_H6?mTng3tqs8*IehUUA9lIMbbEz8!mi=ArAY@Z5ijOnQ0*SHC*78e zo*S`yye;3B@;+v!sp*O8mSd{Wt#9mB?^3sX8UD!oRLXfa$|hjXK>Z^1EMd2{RjZv3 z>IpBvmrS2(PYcm-tns{NSLjQxf{$j{uJK;COkYLMrqC>-_Zsi1_gn(^X?Lk#+?#u< zA!4`i!Y7yL+bceKE;4MvXcjH6K3GOJ?BBo{hUbvBT9&(IT#3B=eu+=tKvceua9aHD z!STN9F+4=Z@J#H(K7ldTBpGT$?D;;bsr-_#iyz4{i00Xyn*A(gj4y0grhSQJvYk8+ zC+%gT6`TieFS0ZfB2(ofXdr$UB09FM#txq6qLk?oKu6FGo`&^% zsh;{PsTJQ!?B%;~){I67u6b6j{z50l358aJu7m#89&X|Rxo7_CoNCWI7**6QUkE24 zqYAr1A-BAo+thFo^}N1YxPe{yqvzY71|w+8F8o(9s>|FKT|uy*RYDj>z9RqU;X>7R zdss`j5Ye&gap=76;hIO;Z?rGOJ{-}Uc;stIRSy|Cm%$GsVTD=_c^PB8u1Aqk!g@-9 zgNw+Q5B~WM9@amEpH*{PM8!pTY^KtwwPCILaMY0dPkVUtwY4?%UH2`;=*tuA)9s5c ztDdIvm09#3-85cN9m;c~EJ0HY<9kuxx!i)w{5{{J#rnO%E*g;^0oJe&)V(jat3kb+ zp$ET$DD|r1bCS*+zK70(oP!^DtYLChSjW(A|4L`ObG-AQGqdEu63s3Z&f`R2?jWs@ zLYp@{L42ub6bOSK64D(h^*rA_5A_glsrRt4GrW2`r0|^ZT_-W?p2Nk&$GfQ%&Bd^m z&$XZ?U|ZRJJP6yp-tax}kOsN^Q@r_~buTC0Qx(1!f;z9YZGQK=7PJj>OR+b6xAOfb zkWl{fd*Y;@FA=1F@`deDzo36_zLc67cMJ8Ououbt^l6MFmBM(69Xd>l(JXEX8zXtc zwmg1`Ggbcx+yR@^a&jIhB%J)3C+^38nxAlX{9{t-EDV5!RiCPtI zr#5Z%5rpA(g71C!3t`Ex$d(sW?lSo~!-oN!_RZzpzz<|OkT{H_6V*A)O|ZMAQJ6SF zsq3j8x>shgiXLTUO?pCQ>?!L}_B#-3At*gR(4*{kz~6c>WqFUXE`z_UV9FgmHwERZ z*SiMoq}3ct&+^I~XB?05W2USjBUy@cP)y8~M?2EKG4a`88B=={$!T4evN9(KmE2>m z8yg>$SN}>&eiyVxq?MxreSFX0ARNvv(htEVMs6*`c^pMzqA!&@T4z1p^tVM*&i**P zWmoz$mwsGy%bNb`+rA(6*)2^a#~?qYWxp=zqoSfJvh#!bUXq`J>oZu5!WRVAOk9UY zUmuAlnGRAB*1or4RW>mOF{%|!%F~D}?6D_Zz<$R0=|wl^X#AXx_G#n119%LFh6TDo zF~2Xhn%!VIpXS$u(#%8{q}`gVvFeNP^Y_3w^pJQt<&7&bg;>WGw86|aId zCjN+>G%Cvkeat_+>;~icRDZa(LGJ%lRzeU%4Z(bo$oCiIOFBXR z_XNmW+j1lAQ_oZ0iBrSuR-5@s|AWt3hFnaQ_YRctbCERA{-IdMi4};5`p7=ZXzxJo zpI}21ei7$>EXMX`-r^T-BaWe*bj7sZ6gl)<;g#a7ZMml}#9mkKSVXYc}Tz-7j4F= zYM!GLCakUkJjFM|KL_4q9xn3dsIY`D;PK~XFXPI^IT{G}J@dkJlKN=;nq9Q*x4iru* z^hb^3y=F^EOAZ$!rwdty{+KM@JIAuL#VSzEI6>@r6=P{rt6@;YdA@s4udzGiiYG3o zm2pD%AlyObY+IN!sQI;4L&zZH;?j`bn_5>W@;Z7~A2++@`v*CZ9o_~%&^PsJ}%U`T3Ze=W| zMKwFeAHroGy~|&yGw0->oTzrs2!ir*!)6iEha4%Vy1SxHTW84H*BTDnD+8}PryH-m z$hXGoj<@O%1576-ck`{fW~A_E>W;S>bchSqYUtMWUZ~6Q>$pwk9}-@v<51feYv$1h z{3_LmX-VgF69!#SwZ^JWqC^Ay{@|N7vtMAzh>el!7Xa1CR$cHdkGCrM?HGIJQREQm zcPk)V2aS!ot^)cDL<^oi%SZH#t0Rhz@m`~Mh?nTCLL3i0zT4~d6aOSEB5E)w7YTA9xlm`QuzsTIaEhd9qE#a{oDj~ z-5kGg6P29P&XO}>SHDTdA4`U(o5SFdyH%~@;n{)Vyfa2{=pFvI_j=TaGl&+-a|`lV zK*fJ@MgDQPc=w39X!x3`63dG!;Jw;CV+(4Ct)pk94(B5TZ!&n_fNud6uSK*L)Q(!i zny)>Bb94D7gxYTmHAB>(?m?Oni|sCD4MR2@;W4Ne6ouTUZ+8G_27920=YfCBi3Me|mwNOBZ0@@1dsK~rY(RtgE zj&-CBw(2BpA!!Qq`>m4})N#J=`G3zJo-{e{qeXhp7Wu|!jW%F+&t@riZ7WS(gp;soe^n93*({so2{GJaC=AK^`M`Fn&GXHtE_ZH>Z+mx?@54s0PNCV`P?IOrg5*Zq5(J7pN{?6|q3i{(t4EKLy_Cl}b>47>zrU!;JTNNN_$2+QU0+ zJ(2MAj97*0;O-D34!lSsftT*X zz|nxl*YtKT7xqLiAC}nscI*>^xktl{r2WbL)&Jps-G8`$fw`kc78VVAbSY{!?g^j{ zkIU~l!{_$g{&;@RX^cO;zQs+FSnVdv6rwIZOW*d;J;>x-phVx`?(8dv8s6&VA>B}4 z%@1XJ;X7#WZMR`=iu#YdUDgd0rm&a0sfVe*6k;!D56nMAS1Rhg8N~xL4pILV4la|oOuEgtA?h=8ra@B$g;WU{=cxtYF~ z1tjM%J7X4pWHn}JNFDkW=VA}zeT{~=OhYo26K8E&`RK5dp*wdqSEC=xET-nR@f&-- zE+oHgAjyp6C34*YxtsE&9REgjU2xt7|6Db#4>n^SSS!4Qdan~0)P+Ti!$0F>e^E2# z&%U!Pp!g1P--b2Ktbx3G6+=vO=w8q8jDNe=IlS%P?)~*=?!Et`cTra^;xZF4wl)0o zjRQrGAMIUxdqg{s_>8$&wdD2`tbm-(H$vV0a251FRUlsk-j;PooYrp)Fg)_X3y=npY}!5e4)_=HIQs# z{qY9XB){i8P_r~wX)K{O{iN6b6m$046>{RVtaxz6b+dWEjQlB2vv@`AW}2P2CcY`b z7`8AIv5Lvzw}KOjdlDZh?lC^{5XMu)+ScC4b?-H|M(3CpnRCp?n^#$4(w@gGh?zAX zI5~{LTWltJ5^XV4v%nb6iEdtOp`5Z^uj8a32eX{6SHqmajE9-d2V3x5?(@YKd#@QW zaT#sodBmPAmYp|4ZcJzCgyDMX@>ZZlfjXxPLe!ykOd$+@%vhc21{f{n`zqOLXq3W|uiSH#DP{pjNVGC+Z3WlKF3W&@Vi-k;aDckpvgj zRN|t!U(u|9PkC7ntJRCU0;~=Y6W7e70L6g%Bf`f#wxF50EYgp7>IOBD-`a6_8#%6H z1q&x5Y8ojg^MDgI2S@M{&>B=DBr3~&SUu5NBGU|pRWvWA5rLJ)azpXF)6K2EVcy(xx}b0&aTw8qop_7 ziCRc4y{~6FW5ybMMbA>6Rs_@v>Qkg&$~Busu3_g5x@e?S;66qJ?k{G-!A$c#ejNawl zd7zR)P~3R$=GY7UqA~gNbl%{49SE94>BU@rkJ&IAbat-D?FkRh?a@UNjkmy)XBA`d z{hq_Ts@Y;mYF-sfEj!w~T$|LqyLUP0w;EUF;#E1W>Tu;2uiUu0z{IiChkAXd`&w%D zm4ZWCEH_6Re5=r6>XG8ipYM&?p8r$YR^Fhk0yHW{OmCu6@j&4rh45b<`Yi#)vImyp z`q!SDbpOPS-cr z`J?f3nm6`*RS3x?%3hKOocq2Wvq|bEsc;d$b4*|TV182wYlLBs7W3N2H|90%|Al$2 z^=Ia_kA5<*nK6%C&)1&M_wL}2_C~B7gISFcXEhx-@24|bgl~<=hf+75{$y6OFk!8f zm-kA$g|5zOE27&4R9JjHvq`_LmF-V*sZO z!+sg=D)WZ@MK|W8L4 zGX&lKYfk85(^~qfoMS^;%d~9wi;A5hh=F61Wb4E+i`6x5Qd*42SomI~B z7DfBw7@Q!@c6xoz=aKe%CpRB^77OBsc5bn#5ZfdcE3p_Msxd@gXoR2z1cGirJSV`4 zev5@WUka<`e>!pcm3YY$0k2BnPF{X1_-r4OI?r7km!g>%eD*49{PU34#|(u(sTpGX zP}@a_ZL#o#MUL9C&@6MUCy>kg&K#i`HTCu}LlK3VA?_;Glre9%$=l7;s@YuYW*gJj z;G8Gm6wPwjb1^rh!CC7W*)Ic2@orBgPWcSV$w8%WQcyYgsyRgi)Yt$s6dg`=(F`g2 z7nAm}CuZS7&|!;37UZrFEuiDh{9Wr7OHunCAE%gN{Wuoy^)o|}<26Hk-^AbxgLrSG z)}Y&TJ8J#Qc5ePOYjbRFk0SRa&qwI1WbC{7pyKLete~jRy=ofCXQS~9C`4FZGEM!p}v7*!Oh@9v$xc#jGLtS(-E9o3|;ZchIHZb zAqIRn7NdsEc@cc5jA1ZpxYifJhaWlZ!VBp8D}Az|2&ClvV*PA~Fk(#9mg!D!t@BT4 zOBLDz*RSfCD4Vwp* zLz~^ z8zW7^YfHObzaB~u@GjXLr??T=mhi*MVg(zA7Y`Pien-e{0 zdGDfkM&sa>$;i)5dz*IIf5pA6le;9h0LyX)PQkOQ7XA?@WUAZL%f@&wU8Sdre|t(1 z!Vo7rOvBJ;*T^@Q#|jkHK#e+3{-JA$_hr&4;+oE>Sf5%tE*&u~g~{zRy>jW~&-Pl9 z+YmRy>l}LP^3~!=t?xlM{kaC%>HGypodsu=CF>mj1o|G&8?ARaUUOg_A^pUjA(Y$i zwG+;yVunEoS^Mjf_gdQ95$n}x5VGu{d-wI+VIuUJQ;6%x^x0ucSE<+d=0M^sW&fBj z2TIqcj@K+wx2BUx`|aN^;r0r_Gl8hiGl;9Z;qO?J7dyT4N?>JMbOIc zvVUd2$NrN2eS3b-0iHEfp}$wPaTb}|fzJide1Wn`QB{J)1E|Yf#d5Dx}F7HtL=Ayt|x;x>6&28Lo{AOCC|f?h95jR zvgVi?8QkzqF2rlW&_pSLr8;U(jjoN|Oaw!j)P(mr;{=&ukLRa!pi<#@JDngd>7!e8lO|XDD9f|Q@)kp z=2xIK91HIJwaCq{cIT-iX?L|pr7?X6oxE=qSHQ>-eS4GR%fRuHO&CcpI`0uVyWGOH z);bVH9WlCo=lIIL8~k{|{x;Q04yv%p)(26md)G|3!8aT1`wA2@81Lc1Mcwx}Uh5`X zi5M?-^F9T1Wd|G5JMoKOzhO5tTN+5J?12XxjNLKTMGlcWr+p!g+GWV~yuAi(eQ7YM zTjN_L)_Z>Ui^@5f19seg?c z=X=ift664B@jzpPs#nRLKwKx5U2eb9eHCNt8O>k2SlE0qsC^EXc zkD_LL+b8NLk&B5+yS>7~x4o!&8rMmltA=M16Fg5jUdH~5_<&C>JeJaq{XJhRk90|k zG(~S(lHBY(#whL71=#z-18n}AmN+-^fL+REH?)m}+5y|uWJkOsL1?fbHoZ?G;e8Tb z;+D+gQ=^3h!3$iTHn&c=Mkh^BfhD~eEZaA|>{Sd!4@1fkaTOQi9_UuDv)~X-o*X2E&yKc+Fo7SCu_{=(U zhIzVq-WRPInd*PbOP8UWuAA52s>zg|UmlRmH{&CjH`pr4RJagztQl>Z4?OGn?0NO` zJk}gkKSgTf`7QEBmku>-aGgPGT4TTXLE1OYPY-bO4fyQzNanSlXXlOPGT5pv;tTVN zatpT5yHD|z5<%X;PGVui7gl$G|+?Yhh(mVjG=m^|!k-UM6b$T98lu<{{F3jxWh zU|Zruno%T~kyZ)tf=!JdAJJPW(&28)klPE|qg2e~)JFOMQyn|B7>C4LcikZ9-l4g3 z&Rc|4Da9;rw14U^g*0PabKWsJn6x2RntjeYS0N`f$GmTi&(p-$AD-w)`XYaTd)#<1 zsu{L+vnB~#nXK#}P+owW_)MBGN8t7*)=0L?x3iT81LHbb?^D-v^{1M*80Xug8o63R z*qT7TU1siZ;X=BLJ!r;dPiP(wLpgPa6Ar9|ePGyPnP3!9)-xM%Hm7hP|0lV<+;-V^ zb{op;lvK*8ghGll7RpyI=F1~rYL^zcj8Z}G;5uEg_XgVi@e%JaX39d>vvRGAD`HZ!UFDWrVRbI;MD(yU zCUrKhXSr(R(ZUrs4=i_f@_OUaPF*7IOygV`&IAYo1Zf=5(B3aBw z8VSynXCckZNjUvYMjE4-=6e?pyt=urYG88Y>e+WRN&=VEtU;jJ`{p?R7+|VHcQSFQD-{7bu#c zqtu$cUC#X$l#l!TkM94?`A-i}TX_XW51AI17s=YFa& zbp5(`t#HpDxjrIZGj4Sgjj^Ar8KU}VvY;=KXtgfNA7el7=j&L32tX2TwF@a$h1#?4 zXWH^xH??y2&$MQP`=W3_!40s%o@spSnL$-mZ0zCHVYA$Rr7Hk!)r6$IL%r{)J7ZUt6ivDW(}}(5m^+m zIVJPy?l?EojPJag&oC}B)oyzJ`bb(zhwHo^mr>AQ#726D;W3eA47hQ6l}G0;tXAd% z=cM5&#wF?H!@Zog*#)_s7J<~`n&Ii6_7dz2BL<4|k0Of3&D4XqVsL`Pv*1vs1sZ57 zkHKm=zvoj8IG@uuCk8crk-2m}x3ouN!e{AjoLFF#aS=VAMo6dy^CcMrE~?qYW;P=d zrHFrVO3!9c{@!CUA=nt6H_;*Kyc8SlKH1358}AwyVDsk3tSU+tc+5R)8frCP0m*8R z25v|t52VtiSdWWFerWuYY}zC*JeC?7?K4CP1FAx%O)$9iG~QRe3F$JaM=BjFj&~!X zT&~kkDALntPY=4;1usWSJE=5DfXy~G&THIj!5%yFvKZGvB6NG!7G5SGoCC{W2Geq(kwcbWU(Uj7tz~7XQbHg z@#_U98FR<1bun8kOs`BnrZxLsU4VBUw@q!GAh1av;{12?nGd>BR*4urElWdh&0ZH% zjkn~Quy#Gx?(|+K^f~k%B1I}kpL*L0_3Z5Dpqrl~;O#QZTR8pKKyS)wrV8tY`>o9$ zASWU3X~I%rnf1J9y-n(3XB_h^wMp=O)y zE%WdK9(xf*%Q0&y?Ma*|_^WA|AnXzpoym>TnhKmWobFZdHC86s0E=P;!f`SQbFgAK z3T)UFZpO6SH9rP3j7heiJP?_*uib17@||00Noh_Mme|5u<-IDtYW27P*U}ih*(P&M zC*ILU;(D_!&CO;mv0XXO)^b(#cq3YfZS6pP=$*)b#z2sW#U44L)%&pcMYrw-+)q5z{eItF%7d>~lRMg}#-tV2NqMAndh)!pdIigzs^rB(^+e2@}Ie|*m=VDFYxn8#x z*tRvd^s1z6@!G(2z+Z$rd;fK5bqTDprd#Ps0;;TX^8!3?GPtq~ zD_;h#DXS4uVB4$emB{CTJIvsYH-KXCuA7;5%Ei`JBYr@hP-lr~SKwSLBB0WFSNBCf zZ<*#+pmd2yu}iC;w@e1T>MZ^?@IrN-?Z4XjDm>Td12|bPszLwr=zk^pAANtXKEN^0 zS|sjpVU>;auLEw{{k>qjw~Z)!rdOhzBfJeBK<_HS1tN_vdp<_r=b`WOZuUKF?UnLn zf*NnM^eVYf?QN)i@xXnD2$w&5VAY`mn5BTk&qSdGQt+iZV;*Xxch5tQ)BPXzdW6`D zD{T+QCpXO#dwqCd_MuR}`_b>U);e1)~v>i1{_HaP)xt@oh44B47ttmlxu zw8Xnd^t&MKz1H;stWD4O9_E=eWrtoW5q%ZS@cg>w_W&c*TQX`rN_MOv`|F*D#|Say zn*`}r2AF+Jf@lS8jI9_afJ^hzO-$ciC0|~O^3Fw&k01Ykni>87?VHEWLP}1V8rG(m`hADI_c^(wccDBZ`+HB!*57*AMETZpo{m7Y^DfMz*M|}R zU>E%w9A*&ZE#m5O@V*&65d-`jvRfBWcV1AJ9TAee2F{jBmaa?!A!6R)Ivcx4P*hy= z?;Sef(`k=2yKuIzQ!rD3-UxIArIzR)*|7^)E+6qLzKJki^Q(Y(FbDGdn*SBiqMU5O zulbh+Ddh=hdzk*T5=AvLh4CJ6!k_+GMa?*9_pWRv`||%@tf*ppTU6wgaLwN}MCV?2 zd(0S{OiqY;S;8B>>6{|f+;{7yP;H}y?15Q_*aYg2N8PGgChga5HN2*Zad+{8WK;H) zOc6CY$@{+rYG&i2AAffK%)Otc`M-7jpUQ`osYzZ|3_GdEi|$HeymK}c;qS~%?5vpW zSpuzzGE9RmeWR>`HL5DU?H=W`PrEnb1etb>d<9pQD7Q58)j6&dSPchF)LMZeF~n?@z`nUm9E%xqkwS9{JmPB) ztHF$`IPO!R_XjswuS{H9ZrRfuE+Fn{YWBb<4T~*Q*W!VX8uY+fjj7|kyRQ?ko(dYH zV=9tX6GqYds9*8Ga6_z+1&b_|uv{Ngz7l)A3{${0(Cr+fVHC9=;Y75`DxM7X7jBC7 zYFQP~132TK79n;7OZZ{e{3k?CoC7U_*?Sh8uY$a1%4F5>F%f8#{C!wmMx&y=R8b2) zH85#sd!7b2sb_C{> zY3r-4sv3QDZLHe5aiI9I3d?)GSt@7W-<_?o6H`z3s#HurTY?prsQ+e+nhI6b9oA2* zpV*EyuYiZF)Vd#ZhW}TZq~i=ye;0eESE&rEZfu;3wuaS6yl;+_TUdG*EcIh+NM1<9 znmmX*vDLV~9=nZtN6~RR-ifW2c-sS^x;Jgo)>s;+(bIpI-RVL+r7uAqF_S2U!Nr{-lfT>}`N~`S4zyar!JY|nU zQH2wQ(~#DsjmLeTZ5-1U!k_5)MgyKOArG@RzC`N#+q#cnQ~XW$ zulha1B+KBNSDnxlnP)Up&fby`wH~~F7tZi`?>c z#eUbl6J9E;;$o}<-uaqsSG!{>L-Mr%2ld6|dEElk5o*@(Gul%0H%GaP7-&Vp-UlgxM8R*bWxzJ4WRx#5D zUn|AdlU)oX(p%8vs<)oJcM~(LTbj1S-B)m ziXDGnm-F?@&Isrp`dUj1@@N(xp3YaO%DD2rE)Epdl(Cqr&Xo{47n8JT8TH8d?wD$7 zzpVTv%!iDMH9P~XTH>T-A|gOz$u++Y<%RkVQI<=_)M%dGDrx z4yT3^%&i|Ckfocwt4i2eOk#}a$%_^%F7OKCdF4 z4h;VV-)F_&-r`;OUW7Buy}p&d#hwh<#pn<3t{Xo3SN-3Lzv=!}{|wRRpRaCMk|6dM z^%jl4bKgX;=Dv34-n_`_YKzYGC;07$X24sz-$eh3b0MLsyl@t00K@)yCnGSY^}3Hh zcGWLQ1U3}tSVqq%4N3f$uR@mN`vrW{n0*%CYK++ueAC$d{ncUrc%ZjZ|IQ3v^=FOL zQiEE4d5zX6G(w@xtodEj`~8uU^-WKS-b~m0S0KBx2l@^kfgdXOLTvS4Fm@ITA)H36 zaq-mWraK{=#%unoV*0-y?Dk;nOjk?+_68)pqJ-9f9M*u00cWIK%+|U9YreHRdtldr zkKktzg}A)pJjXt;gm3}~5$>A5P~`Wd@a%z?4@@-8xDe&l!58EqBfQp3s*11ZP2)sWRo2K?lQ&pseXbHz9TU^c{cmH&oRP+rnfseC@2n1u zFqVAbuKAx3Yk${)L?cmmbd@sf|LqCP_-hmw`D)g;@;CgpwOxwpPkhOIwI$o1d;s+@ z&RP12Pb)>NKXHz}>c4bdQFBKet|dUSL)|*B6O|EX-~{!;xo@J_)!peBk2J!TbuSSZ zMCzEm{LUy02RdElfEFZqGldubEIwu^5N_i%&vxQ_htmQYgki<;-2%hKK(r zJM{f!_ROwBGih855APfu55*+o+d|_YdqR!Aito$HO&oAW!1CsHu8c?i6Hh8?$7Ky) zsoPII^J1Q&2DY!X5=Q%96p=26{hu`*fu(FMR(3jAj*|T3uL zz}IFqaaD$WA=CuKB~^t6x0O-mt~9Tv*Vp z!ruLS<77npJc@P0*tWPaG$Kgmzz(jz+Oo@?oL6I+>zWAJ6KUo_F_J(;rH4I8mGzw` z8k8jJXJ5JV&{5y&;_NGH4(;uZ*%Q53zmNB>4@gm(_TYqCeRZyPI5&5oli@+0cfnu@BK&mX;p=3>rYT43<^!q@N*RW>}@^l`?etqkuRcR#9xD^z>D(v~)@H z6Gg}LSzaBpz*Q|uI}Q035MoN+$)Ujj_N+tEC+7&7&Wv03TVgt%(Mw%so3YK{QVuZ% z?BtQWW&c%#7sA@7g;UTjkkrlhCh}rk%&3c5ZD&&d=~@&2C2aA&@Ep@W zQG|7o>UEC+ZTgbAD}~4VJKPFmokwT9zo=T^W>jGaRZaadP|&h4!j{Kwxw-jl9?ooYa8qYE7B`W z6|ogD6=4+*2+&YME6aET&Sd<(?1Y|-V>^@6B(BJ!D8zk5Bw{!8V$$C?nrhQ)*sN5m zJncj5@t&}!Z#7jg{imIZSz%Qv*03@o&K9vNfaU160PBnuUJksHp{-C>z$+G>;lndj z+einu$7kTNFYo(c)0dYby$^9`_%r;Y;$Qkj|D*T^@VB06Vb1VHT=BpCA5Hhe?=tRD zyhESR|A)lyBIGdo|8DX3p&ykr`fN782=CJWVQ!K5h5~;-;GV|vW;cGd{odUcv}_*T}vE@ONvH!17B#`inV(lfo+jJ?yJ@!Qdux5$sT$ey#kz& zRQNn-O7=i!rc6V`%mlXYVJFtSTSybZLk|&pa=ASR`*u}%i4f~i*1xv&kSul^`q^Oi zxv|GKw`hEF9&v7YSe;39+X(j~)H)V4S-W{j8vi>E-x{3cBWS9m-`h%30cC_Lh}u>pSqyr#MF- z3`BGPbEPM-I!LcJ)qEM)^_r<8?$r$8PC=LaiJ;l>nlPqL*0~?}CX|NpDVXscY^H9y zJT<-Cv{i1m*}WZPgHHXj9;<<3c=?T{rX1(&@myFcxP=o!+)iLwW~zHxjXd>S;8=@k z>mM#L8m2#Xb3G`cm_;qnx=giX)5m6w@x8)AE14#ytoXwv8N>9yu}Lv2qV{o&QLQ=@IQbM|>IsOo0I=WiTz>7PMn zjMmm5VftsHF3S4vq>L}A)KvS1mCXu0pKbq*on(rZp4Y9DFaBIxudXu1GA3(>&Sa|n z5=bU#9Yp`N0-@@31ZM0~!xw6X8v7%BR^p>upfkyQ3fWkyZzk#sDK*>vguSn$K*$m6 zyF;w+6AhFyy#{q{_~ybk^a7jp#*KPH!tMHvUD+`@hBk}utZL{$?}XK@via8Cx=%O)2Yv|_>8WNxFqH)TOjMHbtE9c17lU+;_jVkT71R>^U zMw+(V(M9}8H8+wDfJ;L|nrf@9tLC zzl{+}@5gS-zC5h~G{@Vy7&|1JU`Hs*CXy>@-J>Pxy#|a`^JZOLf+MW1YkZoZtA|z4 zOkL%BD9dwES4SgtvV+EI@&slY_S4U*>gE9DtEI2@+2ybx;=FHxT0m6#gQ~72ZkOeF zvqaEUCiPr=;#?qQ*SSE!E_Eff>QqNqOO+et*ih2BFRj>Bi~!32+0;*B}o^O9!xUHnAkGTc&Y@8k(y^95cfk(A`>m5p8{_+uj|LKxqa_BKL@nHL^Z|yk^hh5|Qz{DK z1I%ar~WF6f*EO8(n5>xHI#cY-+Lw_P0zbjSDO0EsB+il^$P}YAdFTUJz&{P{;$7YSK zAC(C+M`Y8jkWJzBkHGG(*njXKNu}+}%>A#H=q8g)nn7q^yCj{8StMP|{V$f>ltO>F zw2SHMFhe^+Gr}tLaq&Rrfsh39cu3N*re@0^m18H)~KR$Zp3|2FRSi{W*w$y8_VZ!KYGfQmfkAX7SIt7+R~ zcBa3rL@{eDW>345oiWoMU0-FDn;`R@rfpB)>F0Pl+A~-E^1<+W;_xQt!|}ionN4X; z+bH#H`{PLcPpm0LP3Vl6`uDAq_lr5Tn6~}lQVLV-_Z=9O%1zLb6c3c`C$5~+&~LCMvV~QhG!~b;>=g7f1yGvBB z(kb9Hc*rLc2OZYbDapSVJWX>NIO!H$y19SLk2uN6_I2C^iy7jiSz=Ac>>uT%(H5tQ z_u2g(MQ~@yjb?I(2gH?LZ6T!o}{Xr64o^2mXFZ@Ox|<^Eoq6jBZ|=CHrz#AvNiGI(n()f&7N zRi9ip%^F^Rz+!=f_(q=nS$Nf7$T}hJ0Oq%3Xo{%c5By*y^MtsPSxS-xn565`>&5=c z{nYCP%ZmNQhkj086#E}L^q=HKu2`SgeWSe`T~FnWt!J}nw1w7Bp)vQ+A`tDH*sKonU?H%p6_>m`^_Zoa$iw8cV zC!o!+|9?*m`X5JXisGcKi^-3HE`!%3d7VJ9q!U4`!plZytn~u%vV-G22 zC62U`^X?Yw{JW7l%ezc9e}-p&a@jNdQr)4K{rWrV>Xa=Dl$jc{pSAJG>&H= zhi$ZuwgXf$G$SBxpIE~wd(-P^{oLhIis+73uK`r7z>a#@f8X&?-*AZUL_H8W(wes~ zs_Ij`1{FJ#fv)ic)&>%{3P^~+l}T2KdmPAKPm12YY>ACt2y;? z-ve0L)Rr9g3HaVya>8fRs+v{6%e-ID8It!-+BaqY%a;-ueygN{D<4zU@r}Vq_@Bpp z4{GHC=c2xqVjV!cU)t%_AqPP#2VxB4)uSYXI3o}F)j;+$d!;2)YU?br_Kbvk^i#IR z6w=jT+ZSv0og*ndD zr5n48@%EMWY=7MW?5kwM{ui5QU3|^|ZBSRKsyFm>J}nv9xrSP>^G2`di1|kE3Dxg! zBXbq!ohjbe+^G3stdBgq-}!8v!;r%D0%+{Mdq;^<6=DCeP-bML&;1_-N5>;C_Fm(o(IVSn|B(((C48CYi?bSBrEtQWe;gZJ)uW=eAT3E+pM8`F%+DK7`=us*HNxc@?iF=P76 zfgR8%?9`>~53irRFTAcMmQ9b@8f7*2{~2o%CK=^C9#z=`Y}*n+we7n9#Ji(CUy0rM zGXsx+2B97s*Bw=d6^iMz=J$P^giSJ8>0RQov)$vX$5qh@uAwZU94%AZyH)l4$QWTO z8Js@+aEx3URMpFcC%aX3H_~kT){|VXs$$9jjDxt1>O6~8u$N2Vf zw=O$7{@Ee6;7so>hUsCTc>#)i(x1>AJvpkbt4QZsR)K!!S?_L?(aNVza_i0GVZ{(WK zSfgH;EAHzc3HaiH+(S_nl*2So>42D5YWJ9WjWJEsnNlAl*V4SdgHM9)coF3JgAY9L zK*$FZ=Yj8rd^aR{aSq}@#A55m5lg=df%FisOOU$a^Y`*MLCfDuKOJm)8ji57ezObeocxz^9MdE zq_Zxz;;R2#kgt{qTn$^xq<=E1=I8ZH#5DH&E)USEG)Od8u_XG9)lU! z0YXPBQ?o|6C%|P?G_f_26KiamR^+-MujzGo&~cry4$1u3rWzZ3qGtxqpAF~=VCUnl z!5lc1@NyL^;1dVi@rR=wjYpQpK6hl6X0G+aULDFyu)J_2r-#dVjmnG5?*TAGD_Uhx z^*+m&HpNcdYE!quqTOU^Qq2Fka?C==BNvL`kiDTuGxm{MM987I1(WM@8gn0E6Kl+Q z_80BIpuWZ!jq7PHY8SG;KrC(hn|ZN<5?&dw$90L=uvps;`Tr1f3X6_T+L3~FYnGiM zt(>!NQHq_N6DO84sov73eLT%hIy#!uw=YTo+OXGkM%1yt?S!_GPpMC{hf=e~G(=QL zv!8|KXw1H7%+(skAP|}?=Zy^9*AsJxs?6-&;*8!IQ@?Sbblol1dJ9nMODASY`ywo> z;*>Z8OC^jS;MoQJ_YAX>*jtVZulWLxj@!;87Uc!~5!XX;6@vcvhDU#?uFGK8s}+L& z<--q&XY@hD#3m~rvNR3)gVzWTcgSxE&K2ZkOd>o<(eg-9w=tzuzGK`}rZ2H{&Enf( z?e-zNN+64}AwPUSFh?&fWp9;l2ZG#ovessAkySFjNu^A(qEZezwDgTHmDP{gKGVuf zl2vN9C)F#{)7zx!?>9?sNvcfR@ewSa|LEiRHmra6w8S<#Y4|h0gKObyB*K#1ypQ`M z8H(1d6QYIN;SU+f=ORYgxxih{0^v=BP{={FGTO;HJqs4i@|@8Fr93$av)%pcr@(>< z@eGGB%IC6^lx4}4hV|zH3(C~nW3VG^>1%b$cZ5x4`v2-oqlkQDJ%AH-37ZVvbxWTU zb~h5^-M|PQ@-GYw`QI9pf=)*ecR^wd`lCeJ5s#n`t|@Dz&LQJbh3SqN)E^?DbR z7>(W-2C6@7Tt(^vmjr9766hV0oXYx-tjKG>)W<3LZ7H2(7qupLa%Der9}o(lD@XL!he zhgkpHuhZS2|CosUKhpPCQTwp>Y{~%p?NSi~1?x=iPkD3#i{>aRGKUXwq2&%cm)uVYj=wR+yWPU0~K_*F*Z& zBe8|>Kd5Gb+brKPss3?2#!DjY9@Fg1RK}aUNm&J*?%~jQQHvo2Cn$Cpgm|lByKD!W5RV89tXGZN-rp#zVp5bHz%Qr{ z*#v$Z+Y+lN|1MTmrok!sgbp>hf$`q8iJ2A->%Dm**KEg|(-BvJIH+$(RgDNX#7jY} z{zz-o`EIWqXF#u%;%)+q7{&0~Kq=CW9HbjlgLn-%vrnpK5rGT3=E?NT>^)S<8f3M+ zHPSl~XGX6%30p>ziWSdhMYXKvj8D(USYxe<@(EViR)=jt3=G7 z^;RPHFw$yx9}=w#&HaCb6(*JOyi;AT+6n$TEbE+$y3p>N_3jSJVVRtRdE~;?j0|-^ z%CIx{+P=R)=}HCFtHiknn$KF*;9F=cVI4uOU3)c0P?b@PM&#VD+=N~=DXXQO@R;## zDMhcE(5tDTUS%_53#sj5e6*?A1KLCBjc-|aS7;309h@#cyCcYXSjdTsR=tsFZF0TbE|1qF%it3iBod zzSqOj(aTzlq*}~`O_kEoC?t@Hg<)Tz178}OGTSZs@oupMlw)V+2#Y|wTdz(RHsKfR%>rfk zvJj^%zk1rSAs$xbz6_PDoJoaUVMz>9aTTn0;#IDegLe-i9dBiU+sxIZHYL@@HBnzN z-il4UD2Ha0O5I6S(M@XfIpa+)WndM40GewGGc*3?{V7$jl7mIyKtvEIKuB8Or zX~14e#bK=SyMbZaI4FZR(H;*oNxfaZqa(1b^KEMwMlg*KNWIS65Z9xigh?1bb7g}1(EppOztT|zm3}u#Mp$-=5+vx~daV>#@nQ8gc)kG1J#jW9s0+Iuvv*&q8FH&{ zC?vmD0ykntC*bm9`$ATF%l{;?69MiGi9hq4u!`KM=_lR}bUrMt8W6&bcRbp&6 zYC+InEk1p{G!$E*q~tKTvY_mB;XRU<@SW7zVmiNv%^=BdvIm4*hiuoI$!3Z%>_Kib zf^8aAQu&}+SgtTf*;%jJc8?1G9is)J)dF&En>jnJ}zyb;F6I&5_q75p1 z8H)RY&j%<+HO{Pv(n0?eF(NXP@}X<|j+KIZ``j+#m}GF|f)1o8D-pi!W^w1ThiIDZ zfBJyg`yn*-h$fL(f*QO!(gQKqKN4<(-Sg9~Wb8MR4u6*`uMA0mwE<>o@qnyB)1|5= zj`9ww${y+(C(7~TC1n3aqj+)`E6Rkt0Gs$bl$g9-yS)*9Eo;`F>{eCf;5{c+7tL2* zIfzq%PE~an{NO_J45tMcr*i|UvXIPEVyrAE`(0OCK$oHD-NZ+4V7)DY7N3Dx*rlu* z_M1-9$_yvE2Wj;{QuFB&ticv$kI9xY)3OIL4k~J7wd8H6*a}aB$&C$whhzZbfoxfn-rB}(6Pm8^EAunA|YJX&_EpoN|y#IH%< z*C>4SX5JkO9a8Z?-+@)+orC!xBb82t0e~ZpK@pNe(&FCWuXLp8?srqFe_@7D)@LN97P7OZ zC(5_S7DB6e@=*u%(DmzC8>B*wek%iy1XhzVn@5Nl(y#tg}j zKV2mm@`h+BAL^+BpywrZX3Qi>K;!Pe155#=u{z$RtbaJ3?^UQ6L@x{ay@M1RGwA;V zX7r$c(;$u6o2&Bl0A_$!?yy~Q>*^_&{Z=ON7kRLv2F()0*xW(j>oFmFEjBggNs2}$K`sAIM$Bx6IH)20gc}bTz#s?Z2v{S#Zd?#$eN+HyuVgJ`B zMtkgkTs%0ENt0pEpay^b0lXRNwPF8zCyNLE)Ii*rJ+Ql>wwq>0TKkY>K&%Sveun)I zouoFqE@lrD>_6jMzz_R7VZ(Y;7874n{4%|H&Rfc5%BAb$-q1xO0>x%2e0diDx$2gx zg^X#?{m!L1FsZ0-W}01);h*6Xc+0pPx${@bqacl^>Z308i-IQGiF9!(f1UXuWC zoYyWp@BH&+=Y8@oz@-U8{zXWaWv#METn4-aouDD`jzRdXWynAOI-4=ZrOVsrh;dwr z6TGapG&n2vIoj2uqKYE%EwAzLO{obDjBA#>b4c7^?O4`I3xmJeb3 zg!~V&?wN9jYsi278rq@%GEn#)BA!VSp!fM_^aaESz0*-7 z4A#YKZTGvDix^TsiEG{J*k<#)&pW=hzizLye@2Kzm%KSc{-$^C2q;!-5FKlM+%89& z)oio4x*Q+a_t;xJ%bE zO?88&*!*cgXYRD`vQs@j@=UazmCHXvN&5A%UproRXsv`1G$C&xQpY*g+ILz$4JgdV z&d26u025`{A3faQVH1iyQK{-S&bNxmVYYglIyU)P^CCy2kdnK|UgKGr%C|+Ue~mV8 z_8bwhcG}cW;_CN=wX^(1VC__Cp2qbPo~sGZ7#_oVmHMQPKIjv|UE((6g;!Y6J1jIf zij=>HdnalXh#iI*OrGMpD_}IwpHO2-3Tg&E^%>Zi?KUCa@!#edxi%mjKns#rAwC;8 ze?Cq+9|&2zBrDgdw@Vr&S@7fGYjxu~;Wx2{G3KrTjo3mUCthjK!RVuRYb-hVJJ>dq z8)*%_TdPCbG>Y5_f3Ta;k zKaK;ukCT$G2cN}Eo*-hBu(LB#2VIA6JGPpE?_Iw$4fd#vvVZkij9uyV-aa&81KU+@AncS-xf}?wE*wza2Dckt zcsy(PdP`SZbg1?f@TO~Fy}g4h>|7YwF|@g>1e@*Rc|~nrKvFBMIwQ7cKhLjOB;3m~ z-d|spRj0&i9J_E*@>gd|-(@E>Bvq2?O%Cj^fO1B^bMe~=jM95!={)6{^R$CYWxRhV z;qiB635&mvmdLB5)rg=n6jj3*Bkcu-Cq1w{FQZneeG>H&K{EMO&$^;CP;a|4J#C}Q zuE#TV-|EGA%j2V`WMBEkp`0S!yt`KeWd;}mr+m@ch&C>x3~k^jB3`eB8waE}o-9Me zr?2~T9D|wRyLOS{h~pxu(pe>CnVyu9e%wH-2{&Jrwpt?etu|R1)bmwm23B5{lC}EC zqOn3o8tpj-UHz-iV~?_1m;+l!M#)b8SNB3I;L@?q3}_Y^_TB8@{-CveYqSe4ImVgB|`WZ6lw zAnQ|9-4k9ANHm07RIZ~IbN?RHb#FZ4bRs3~@%c%TT3Fs$rBxDmPe`wac@Ssq@b>QH zSZQ^tKpc7KDtM!8Rh*=P_)<~9OuE|5OkUG1*-G^;>6Qr{9+U8^ZrB1$y$fFWk`5_+ z0ny)>)8x=3kUmpURg79p&X^*^TBKDJ@s^Vf`~P}PR=YlKm4i!`R5%gcZ{6xG=#AZC zZ{Qvg^kpt-P2`3hmffbI2n@-t7F{7QHJmS>cI<^~UM$)xx>19EZG$;$!@CP+AS&)(x5rT03f{ z5Bc{FhPZ2JQ2Ofp4NTF>SDwNu=+cmZ4Ur z8n`tJ(wdrVW*0`^Elk>=OKOmiRD~Y`MS45|4`!^jWU>pqBaY>u1BlJ#>>qg+***kP zF|gGZfLm3PIX(|#+=UZGx-(O-3pGG)n3BfrjB`nDShjq4r z^Dknqr7_DaDqOe+b8X?V$Ymx%u*{ZTcHSRan`x(J3ZIePbONDYDqMFtzHks8Rh@-q z3eI}Pt(bAZ;&n^&q8-0n>x{kI9=o<}4I$Np=5bnE1>S;|Xqf{3BcwOK9Z1)o3~SG6 z-=|L{e4RJrGY3x=4rT}eoJG+)gw^x$5i?NXQjhXQTP#K(Z%I0@HcBxLUj}ai8Ba?{ zdc&DmKl6P+h>L2wKYpc{c8trSXN+8@r069ei0%jKEu|qTI*P{!+_6bK;`YddSVy$* znE7>JiV^M@;Vcm{U%OkffHy@0o#!)8l;A>az^_58=Pll2y7rf%cUi`?J{!Fv-qM(W zQ#8!#%h>rG{;t*sL`*Pks&xb*(CWqv0GvAD=8V(L3ZVe%vT_5u)%QDeGjao()u8t3 zTzqiOgKx>|qn7X7PwBxmnmC|k@!A+GZ#A}uVHB(veu1+ks+SGlfwluc5ljMton!_F zJUgQ`0n(}&u?kS1Ji-sEundZ|;bB4B?>^$;1uyWGnbhyx2hf(&j}*Qo6*R(<#@ho) zjI)t-SOQ5pCXrin+FtlhLZT$$|7q{tB$*lKLK4(A3Tg%sa8GbfZ}Owv0$~W*Hf_C;W zRANs-u>?@(_kEtV_gr#8&+qeo-uIs~@MP`1?(134de-wi>#}ib;`6_H(qOmv+X0~k zpMdoi-yaH{SKzz_%I#tBm5=v3+P~TU?%~p1Pj#>M;vO841=`BbqrS&DuRaSaa5p%w z!)!PyUCb)>D&@PdhLv_&nV)t#;~#fCk}-HrwK8a_y5Ei#VHN9~>JQ&ov+E$F;@j-m zuVoE>D@|F{;(BH%FKDb+ZN<%yd9W&$DwrXD2@uyDF8F6*1>vFwZmPKSeT##5XnOBX|Pik^}P^2XLE? znzii7n%p;^8O+Yw;eh;;6sI@lsQCo?(9qVL^2VdtSw{{F>wlq6OTPEcVoUCH_0h+L znm03#zP+(mq-D*|I~t@XMa5Gko(4qPd{L13x?Naa)-+&v=3fu5pAlR+1$Vnyyysxg zY3BY{Gqsn00Jt;D(w>GmcRZ5)`1IVoe7a#v-8(%et88i}+-$Y%4!Cz_rIo#!slI$! zmU4h{RLU&vd33iUo-acV3YCKU4{=WmBno^tI^W?+bLC-tlDs?K_tH?_P2bpAUz3X! zL-n;e&_nC-b;X;V_u#JC>`a&UNA_p-Dy10fpJTSp$Qb-qma|5=Dg7nf%%FkN$K76Y z`d|*e{+5e#tCPxKs1dhfO*s9smvArBfaSJloR{N%uYNfpUT&$ex{1Yl)wbilu$hgWJryVtf{D1W-Z{v}3S8sbH z`*hCgyX-lG(^oehnYQNLgHH~rI}X)k98)tM#OZd__(x)1&YSB|$^*yLtm(VdLwH_3 z?r~)WZVtP1it_@O{MIFIdb0q3Rg++Wp5QDzaBtp>{ZDk`L?+v+)I*-UN&5@D59~^J zzLPoh%3{=V4ye!>`}bWT@9Az&9!6PSDUGuB41ATBwZrQc!)imZ=En-!_hJ9|p~D%@ z*A9xF(GerSx0O62p_XS|Awb@l8w={9j2_T#kFU?k5y zbwC~5s#f?iA*D?}dcio$;PtuI{m&oMV961O3ZXe7?x}Ida!5m)3oOrd*W_b{KK6%> z_MBbW$I>zm4%L-x@hTTnYcpI+sJ%h@4kpFjUgN;uzrC7x{`lbghtquHe0jTHnl|~s zonlhSq*CIW%Awos6KNg12y=P5Q z2K*JY@(;1h^Do`s_&QOb4|cN{_FByImH8$un6z*o&Zo16H2AIDjKS-(gcTNpHQ>^7 zaZ~!K?>H_vb^XbSxlayGs(N-X2iie?)h&S8dyX}Q#oV+vr(y(RjN7MAK4)&un`Lv~-22qA`H+t3 z6sa;(Sc#|L3oH5dQmYjm6?e`v2m8oxh z&%W>2xXi_SF{{n6oyz=F9Gff_@3rC^rRk@{Cw2Jddcj_CQT6f4b5W9X zmG94bH0^=Pp{#l@TC@Rn;{^xq!cK!{h9==&7ks;GR@$s*hNhHY9;$rn@hp5JeaA;- zm5bY__;9xPvvGIs8+7DNX*Xvm<$>6VMV~2mDzh}Cn8c|>@jLr}^3nX->_K5!+Kv>* z7Ko%2c-IsQG^D30#SfJ4=iuJsN!pW`8;(A{@^^vOiMR^Y~!@mN__ei}QmB(}o0 z&_}k<-wtL@xC_!#)ihJ%bb0Ep>i!IJkSV z58qm}C`%e9TEJ_Sg%9CIzi(#bzNE0N<1WM2@zAu%hMi=JO07%3X+M2X%5@gs zYS?4)c7q<&yw@<+E!*u@8fUrc(kZ(pA0pbkKQkNjUhEVTE~Zkk_mom+R_1lfVs`F=3~yXvP|$HrxV@|Jz27^pgQQ?$=gww>e-DGmPYq_~;A`3?WYd}J5Ct9kgGlwkKpMW(_r03SUVqAay>~y~kiC8=>jHdp zyJXGPhS7E_d4$m=X32kZrT6y;m4=WuZI0nT-~1ISk>O*%_^nzElB_Qi64FT`r+@| z=f6g4u%}K;7#e`=_7bqJF57|eH4`?x3dhY@k=`>vZSfyGXO8`#1-qRldZ)Hu;@!}G zi}wfZR;2y>#Fo$Sl|U!gx$)$Q5B9z_q-q(*@^YzOO;g)zmcJInom=~zz|C2}O&;a< zB;UZkV}NjT=YUn>CeKB<$rB$vGQhY=vwF{SPHcC1*Eug~zsLLicIt!3VZx-P-HrRL zI}XwwAl%WN_9(vdk?)NR%6|M{`m4v|DRp{|NraI_J6({rOGQx%buKy}3=+*plz1 z8p!g0iyKUH1~V*VK}P8%8@Wbi>CX+R?Waz>dup+B`r&)Lv*v7Vf5-b&``rBkG@+sf zs}Dn`EZpHFEKYWueBX*2)}lCf8N+!VYT42E?f425`JTtVzhmF`-lx2t!;0NIz~!Wp zDf{z4Wm7D{!};LIQ=qlGd@8<`SLK>^_{TD4-rE#2?<^TJ&4HLX;M30yP0>1hQ_7zk znxS2Cc&YQ|!&dT7gMXe&`sWp+{KZ(;QL$V7TR3H;?%T#~NtACf$`6f_tC#KRCA-C( z)%fO^g8P&q?HsVonft2h9q)Y@cO9w~%W-2EX;P#+6AoSG_0TQM3+}Pw zUgz|45O4N=x`%Z(?mt9~Ik;O^D41i899(<;oX4m1=l2ir4X10*xAf)oecwLqz?-`s z-PJuK*YVvMic>vwk3DxkET#n?(jB+BbyF$4$$otQyNC0fbUP|;Q^VgWuoq2%q*P$o zaBuZ)-FXXSo$=1Ectv4=B(iZ?-tT%Z#|fC~{oCyqIBWj!(6`SyepA4)Kj53~%f!7J znS+1oeR5D_cg*;D-fG8f_VT^wVqeT<=?h+&h<-eIVh!}9CHrUlRy&oOuovp&gWp!} z%s+lphyCb4+Jo2O>nGSDkSzkPxvqlt2iq@l{up;(Z2(0)JMoR-jUY8);5FS4z&5_ZalDV<%61{F&()J5B%t~HzKGA&?F;K#bE~65vxRdIQ~V{ibjF9Vubuag*xvK;3emCB zI!Syj|9r7$W`Q_4t4u7oaG3~RLa+Zxqw#dPH-fUwpf$PyDL*dhyY`8^wjC z|0>p(?GWFY|DgCq`EGG!!LP)WMb8N5;~A7TiXo1GG;#i!yk@wtcz1xM7|RAEYDb;wLE7j zQA^b_b-r4zE>IV$i`2#H614(XKQB|4s~4*))JnBVwX4;tL#PmH$TC1*B*Qj-B zz1pBQs+XwEYKz*cu2nBp*Qx8(4eCbqGWBxxt7@AXv|eQmS;N+dHEP{#?X~t<`>k87 zS6i>KUTgiD_3PHEm_1es#tAob!<(nE><6Fh&9HVVwc34V=b}P*xJ~o zv30Tau??|}F(G~jTz`NbdKW$Q9{Pv+=CA0N|3(izEq)`OMX&u9z4H(B(rNTgO#D&2 zfquG2929>Nwf_~lv_3ak_ zCU%K)wO@(<6!(i0;^$(gctHG2JT4v;kBA+%9azP)i)!J(;aaCyDOQPEv0AJVb)sH0 zh(^&QE)mV5MYM{w;!?3rtQQ-^Mqw3)VsFRZi~S|`PHdl`c0I+o`Yo{e3@}FZeL=|D z?gw685`RD)UjgP0qGnXTH&DB`M4uvXQHQEzC|USmO|CLQ$y3f&CMjQ0rYO^t8Or&J zh7Ag{u$8w!nWGdc#R|4^N)Bpb+Y;u^;~s|I#r#f zPFH8B=c(tb7r>ZnRk4Lkou%5;3)PF%0(G`JN1dw{szqwCI!{&9G<*s~RnyfBHB-$} zv(+4R97O2}>RD>L)n)Clx~(3oZtb*oS-n=D^-Aj|Yqzz>>bC~0)>wXQW^7i>7P~NZ zQLG>~J2odaH&z%ciWSG^#Y$qOv9j3wSb1zgY+-CsY;kN!tOE2s@PnKF^Ls!0=Yg00 z@bbYwz4g6+zUh`*{&L4VM+P_C@q@dz-}S>EJ@&^#AKZ7}Pws!uqAOGYZCx%X*I{oQqpU3j&R4luA#Wi0i zUOKmM>GI325JIt}XJ${xJA2YsrpzFQk4q2nqZsm66%Om6h%eyR@@?UKbN+Bev~HhY z*K8ilBRqBZx_W|bR|b6ku23Kvtk7JMh~5*7&`d+Vnm^z#>WOwod~R1bqPaYtkRA@B zh~naT;gEZtBdSN{)%E&<^SbE|dAS22eV#A4xqKewUF;U(i^_0ycZd7KC^wuafYWsA zuFd+$im~??HT&Xpqm?G{N0{??-NCjFpWjoV`SpmeQ?oAD8rIg;QP>x>nUYd-lk*_I zcoyBdUt7LhE2q5Z`Qqi8M|TH2dK=yhKbuxgaZ1cMcrK;qL_{qf#pmA)LBNxe$?!^Z zd%}?bx^{SwC@Wc9yl_!*Sy>r@5a}XMsDLz)#s5_J^ne=LdVsTlyF!cf2X$?kR$o)! z)K*`$p6c}lIHBZ>lUd?+F#~yPVv3jqH&2KRpWhwQdvt#U1$05IiF%OxaxGYNvBbw0 zbYUK7Q$wF@uQ3L=Tuf?z1n6>|0T=pk*hFVO9Z=wYp@sdhHioib>12ZH@* znJd(#M?g~%Nc>%z?hiz}yfg^Bfo_i$4n#w4T?E_Ukwg#i^aZmuPXHNHaza(F7Ie8c zA-}7ldQ=ZvA)&?Nwgp`nm#*##j6m6asKpt>J+6o=7zr71BCbvPXlYaZ<7p!IjT6@Z zwgGMhYzI65*bUeRcmePRAO~_}HgM9{wm=6>;<@XqYT^uYUwG&vXm#5@UKuFa6l5t;B64eMYV z{3v={edeQ(Ev8xtQCHirhTNLgRaMPRLew_3Ih(6i!o_oSJ^l)@*3l$dtD6MYUCsBl zrfNI+CA)2PwJohR4TAk!YF3KonyQu-M^$ST@}NxHn(S+xcqWv!t!!>wi`-f^w6wL> z*4H$yZ50&U)?DM9*W6f7HNa*W3ZWUw21zk5Q)a zUZKT{HGH(rP@qRkDch(5+T76AQq$0iEcm&(`cely*R-@&*@47WsHd~Gp>17NZEG92 zZTuNLk@MgX`CQwuQq)zow6;}Mb3YO;jbLHP$emKs-p6g}4f!G%r(i3@&S?hG&d7_t zfY%Ya1JQ`Ym1AuUx5ehRg>9IO$t|*#l&!}LJM=gVsJ${CCo!Kzrq5qQv%2aE1zm`f z4o2_l79zV1^227ITMuWpdHms`ut#l+dV*$fJYIty=?#Q7Y0+SzR@=0kwNca06X^95 z(Hrj-TD>paWISGVAPTNa+%yt$`NLpI8Zk7@)d}XH*@{a$ zwJ;`5zeno6@pR6(mdxmviOf=hf$natfTmlBKeJQnl}HC12ct%5VAE?9 zAPI)SkUUzT6Mu7L7-QGvCNVK3Fp+0PMYHbKeVg@KKWc+{t_afdJm6xim;6TtCf&2ohf@G>|}& zB$UDgrNr}2&}}Ncx9H%+DWq=FNQIV2GmO?pCc@n8iMk`poAqF`E9mrvdU{>dUQjK` z{bI8o3Zsvgmll_TQ-XK2>27a8Z3Fox_(YpG5(%dIscoIZy+mePMDOtuY1Oc z;7`Vh<8Z|j<3tu<3SbssRcmV#7*?2&HGG^o5oC0~8Cqz}Vl+%eD`Vx1QN%jTHAGal zsMgU>0xrgQG}s-$sViceJT_~j9Wg<@l46pg$uZm#2!;9!<%Ax9rs(eWfjetGF3j(7 zW&-}T+2_)Xx=)`TdjfIQOJ(rPw@i0&d=_#zCUFlqwr$?Za+-LQ&s#iRaBeoQx_*6$AV5HgYm zdWF_Xii-{ECG=mK-!zf}i5nI`0f7K&zVoyo3|zI++#|Uo(>w_zlyjoHc#7%_ME%rL zLafs}XwpQZ+}&u9ruRVx@DvXVOXbo=S&5`!FHe5VDfA@fpy`{bBZjx2Q0u@f0iG-q zgtT7ZhpQy}Gr>mcFf#yYgfVW;7b9W>%>;tLdnYW>TCbP>LfV2Z1C&TIq7p}>>Fkb% zy_m*&T(DdtDo^Axc_)0r-ci%9W%8w(ayh;&Izl*HKyi?z!#M5F zMkVH4jQPG#n`k>8zMx zY67i>TwOh`L}bdSrY{J-kC9xGBPcgisE8;GYNXy5nHTIvQz@PqR;T;BB3@Pp$dBY% zjCF{xG*RJmBgA_Alcc>&1e z5nv620x4kQfeNqB3;Mh8%xTnLY#wdrY=?E|%Gd zVgyoH@s(jwY~&|v2tT7v#anzqieuth_5+KdDP>bMGfoY71R=aa>wA8W- z7tx3}5W;wa!j+Ir;^}Q3L?k6E3cVu&ny0+GNQQ;$(Fs@ROIHv3dwe0$+3o6b_(Ehd z6lBPv@$B<=a=-QfQREL3i}35cqGuDOfc`6aIfz=~`09K@OMZnddaaP0M&?7AqOF}i z5ZxwS4;H~1Mmh4hLKqLEcpNI3ac7Lb~~407(<2uDS4hWapsPzP|T!dUPh^qx-t977h)M)4rWJ_y%71c zMjx*zG2d`BNVBFfdvKXXVbl+1pPB53XoE%#HI8TsJd#+4)Z>9Cpq7;TBoqtL0fFVJ zC_1szhf%ai??=9bQ;v(*Fb$}91R?}hEeV6fGGl6Du(MYd4}T3IUaRuB&$b~kc7TW6_U_*E-m8g(TfGozC8CC zqZ3Tjiac1zAf^FaFsms}^6O-MmZFKW($XTQj&Vm556MtfEtit81b?l@?_s&A7-qHSydV(jFBTYw@)3Ory(}DN^+=NuJ;h>eOHDJCWyoh?Os&37%tT&7o)pkf z0>WWtBDXHkg$_yNMS;=}mR-n^D2(Hqw9(D+jZQ}hY*B2-Sldv$o<+0@t!^>$aMo0@ zf73dLC|j_IS1_o7)p)OVkQEC!+R#)(ZVTo)H_H&1Fzr6SE7XrsS<~&uz3no|IbFn$PP#8nrm7ae=V(z>^hhq zYLJ>jJZTO?l^78&`6Ca zxjoHnkprHa8(JGt%UXl~F#o_q36xu40^0-IbQ zUvbIWTE_FrK)}<{&t05E@9}Yqp=8Qf#bOoYMH*YsiinQmRm3_N3?=?9LblBv>MfH0 zwNeebDTA$aemBWW8cb0n%Tc}0mM;= z(L`Fq*a1uBD6hbVa#@j^Ep@6YyQC*_Q!$CUK#?L|033$G7;cW5Ivy8E{LMa6DoL<0 zl1QA9U@eh*FhmnuMMYC6K-{5@RtgP;fuzZ}T3SJi1=PkbNQXL+fX^yWimWq=lw&B0 z@oH1Oz)OhZCm4*CC^kWNai%mrhg3#E`WA)5EW@rzCzL9lafLPtK8(^OXJ;WTgs}@H zmCVkNBgh1X9>X*BGCd_^BN@k|gNcXavtbzGv^1ybumF*yWXgqtHot7a*jtlQ3MQtV* zYk=%>WPU%`Y7&x_H6( zLQc?)V3b8kVQsywxU5s#z<)Q=-$Ko+`?|bPyZOZfV`ab(Rb0M?pj$_g2Z#01>|s3j zCp~Y8KQkRjIR;iLSSC7`vsoA|reZ_V@v=udBPW zy5HTcw_>VBtD#F99^ocE1T6sCE94gn3F@v*nt?8up>vG9S|Ks$%egNw^-<2I4-kfp z*Uin;QI2}Dz!MKzZgT^lvV5$|_Ho{9B!R3#<%Gi#w+D@hqOcy92QLxS6&t|VKj;a& zDXa{>5qFu#w;55pS!;pr8s?bZo-HNeHIxSCkZ8Ed)dWS{-a$7s}L=Q|2z~=?QyWo47h*PnaJ(<^#fv>XFvOxM=|e5E3W>Qxx}<>4Pe!yi@zl zF!R~$iL&bORgwB0bOXh3_%>G=4b^%~Pi|2)a6p9ybsd8ss&%5mJwT4f?JAS4Fz`>B zJj_`E8qP!*YzBjiX^_Wjwab4I>{(>!Kv#jS+rovzE%gR3t4eH@@I-@<^k}a{g4^eq zx?xhhFc~t2M>FH0XsR34gl9xH9E~hXhSOr#$PyFw7nzqd@}U(p!xpnG+BD^n?1vIY z<{#GeO^|9w$$ey8nLo`{gsL;tCkY2e8tA*5#z-`>9BD-Qa{06NH)>tbq0nP|o^IH6 z^S0E?UQ>cP%?-JRB28tf#~3lhhXO3zsG}c&Pjk_&ao%DxtPP9&m-+ zUg|`nJzp-pD->c|>xf+bf8_&RGD3|ujTfxw{tw#329L3-^d;Msl*j1R`I7m-*hIZG z62ZgLx5#*L-B21xBj^y_pFF0%s6W7uM=30c9;CU>5M~VJ*_`94AR8I`At}`_S+ZDb zvN38V2)kQ^ZCMev`AZuIf*^B*uweweHQFb7T<#DVPh{ms z8k(0`i;A>4b7}(4Idin4qKhegzaGXs6;G3DfJS&dX&Jncfu^w)TxW1-jL#s(2Z@B3 z#n=W(93FZSEV>1=D@YxXE^4~v#CV1q=v z(MR3T8V#fQx)7P${L!8c=*KXD8Y!S?grJd;nHyF)2=!(n&cdMZq(RC`6vcz3KLEQ8 za&lo>>c)a{5EO;>QFUA$;Xrqkmjc3APQglz7%dMnD~y(dL6u%(@d2ep0==*j5x(lF z&zJ=RwLJf@rITq933RSYF?L4d8TNTRAq@=C*n9-#XuU>Os0}758YOH*9L()dNM{>v zA=Wcyi}e*O0Bw-YM(H4KjV+32ES%$6g97G@&lcq zZtCgHI#H)1>cRd6bN`_vq82^ECUqUeLu*uqgZ2r^E}Tt*@$1O$HbP(b#6o~%e9=*LE~xbcljbdb#{>>?3H zPVC4diB{v2KIThI@-hkyT)R&88tydGet9fIUQh8^MV0}`-X5(<(oQX$`JI|WzO_oH zMLO%?piAuRz$ODU^&n$1`^iCzY%uv?p_zsZmeaa0^CDhyGOby@)k$ZSbU?-)=E2IuHNo>Ug{0g41@A3U4N2n2&r zD`6-BZ}yPhDIX9=vQFk;*mA;@BMJik*_58rO4kp~6Kgt9y|CiSEUf!@WXx|I*M#|lorBGp@EDHNB_Zj1e z=m1enf{|6QvJKa02YU@~K~nA=SRm<=;V?lb+Aq_w0KheYV$$ov)+m|=;Q%YJbIIi@ zZX=i3#L}!;8aF_)RcJ|s+ZKnx1~K7Lmq7VR=@E=+E#8k>Qfz9Zu>g@&M{s+J#N|l# z8t^B&35{f=%CvaK-dq@(DE)>&lowx(!lczXr8wBud2>TFOz1&(Yb^<$%(gX(P6R;V ztdqcyHV=U8d2K5xoa3)E_DukDRAFNJ$@3vM0&JM@YtDmG?xN9C6zDAC7_z(MC?o?K z4C(l__~Oi*%+ZuLR+mZ8ia-O$D=|)NV#8JorrcCtq&McCAUHO-D5@xVDGvm5B?cWx zYH@g8PY)(Z%5*-=EE~*+jpjp5g+_IvU~*eAJ36sek-}JwzLZPgL<1ez*+=^H=wXy!gKfcG zl#52j0;|@n6X{T|!g@>V^WB(*n53ycqipPT);8C#t7@)kYpAM6lh8GBpG#|+TWT8{ z*b^4e>elAQhT7^De#eejj*b29r3;Hn78I2%Liwhhsz?LRp?F+%lXsJcs4p#Bh{+z! zA!(B^PgAjv#u(Xyz>UGjOR-q+1#xH|!+cHYxc7n8xVfu1KIYM9s4De|s}G~E2Wzpq2f5KsjW5irS;vMU-j{(<$zmT; znG2#YDfaZh3I_dV1!;(1tofY7e3&lmvCDf`BU<3SkgG82*^tX!vt{ zW(3$RjxZB%GD~ciB1tOFe2Ya37iIX9+7FdTS62y~UpNBWS z82#lBY}tY#2TL=r*i);ySE>zym9jQ7aT;54*A()DERVQ-6{-Kty=@vTSs^@Z?x|!7 zMvaojL5e2fDTdt1|5<6l0(YvWksQw34~!!UEURI!CoFd1O(-xCPlGNGy6$x`4~}OK zZ&QcB3>dF(eB)+;uNX!^OelU9w=f-fbP^WpT_G%<)7X@HN(;}TI_oA_|BmY^#yW0= z)H)5?CYeLWJ~>vI(Mjuh`dL83mWL}nZRFv%fW~GMi_=mv2D2&BE+bNe?ux%xAbg`H zWAOd~EVZKdKx6ThgHj%dBqy_2k}~ozI5+DsA*2jQWC>j{uDi(<1||gZCrcj>4v;j7 zk$vD5q!+v6V=;xtLU1Qr3DX+Muo!+kWpyAI;^`Qpe`_FT;dTPsqK% zLSpXk@%2$sUmy%T^$s(J)EHI}rbP6ep))7aRB(PY<0plYXv8%oyzqF0t`{XQ8Ucik z6o13eLenxT2MLWVD4=2xBiJOSP!c>LA3i;e&_iUi_K)NsL(oGFa%Iv;|&xIdD^RE z9W6@C(&X)NF3hM+aCe%td9J`(A$XQ#;Lt_l^94GR40lOOX3~U}vT(-Mq{L{UMK_|& zcpMsO>zVq0y%Pg8{yP@Pdf zxz9Py^O(D{IV;ZMi38%iDXqiF?J%SV`LOwsGBDEDRy9c_=1U|s)4B+SpWR|!Oda%-BaT570#V=qNLjB`?5FzmHb)syErNc|*L70VNt^Ad(nq~~{# zoT-}fm@u^=go6xNNln-thS?Q~PKd99Lm+y*J}Z;zlSn(4vxzdw3G>81qoHc}|Q#3dU^6^^8Evj2JHvRv}Wc$wbhzt4}`r zu@aLAflN*E_^>V7>^ICZPJSR^8rro*SlEoRN(Y&2Ife@@{^A#pqlI}V60jJcRR)8O zlEvLl7mohW%9=NkFUv)g2Q_(QghH*=C`_wfY8W+$j#2+44$8GL4@V_9Dc5h5dN8|< zU|${Egh;!MS4i6F3;sM#+z7Y{a4X<;z;?h6z`cM601pFp0(Jv_4yeWqz;lRUNaJ@5 z^(fY!$zWB84f#+fPOFj()I}FSmJ!Axzql*upYbDr`P27slT^P2Sq}x_# z5`+c8jfO&vBiGF#ujumuy5#C zwrC+t0D6!KmEXA#*gu-sJTL81d}^T=yGS)`deLCy!MYHL2g+ompX1AYl-SsT0f_A= z@;{-9bTiqd#vGF*uWD?{fQ}-Cz?20Eny4_2Q4gA$(A{w#$iBU15B7whKUz%hJ5Ma^Bue!cYY!6 z1|S)0L1H<8+ny{#lO#PKk~HNHI}M96Aacr(^QHbnSR7pyBLqvsP$8p}I7YGyj5hlJ zC|Rlvd_B-JniYJwt$f3mjJI*jcr2};&e$oWuis#}8{xuKuZPhCMi`b`g>4Z~1z8{K zw2=Af1u`+O3y$71hS-usHMF!G@0&txA$QNB6qbokCHltsE~0$Ku{S;Si-pz=4(7p+zN}2CTfp8r2L~1=!*k3&zb@cEOb5qCyso#VN#n#(rj~tQ2BL z)o5@H>T?6&RsgQ_q2|SZ`yNnoaE+DxvG2fMXsO6&G>9j|!(P5=BNtC!J@xN)0<;C< z=1ZvSNch#?-}<-D{|0-&y1a=QE;n!zW1T~uDb`xC!slar&`*`;EuyDoKFBSfa6Ud=8&;v7a2x zfk4)!lS0uXTMD@nY{3mJv4<@HG={kDj((WBMhU>4P}(ht-Oh;!W}<3oI;K3aHzYMn z^by--M+7()$}$m4 za~CFdwrI^&Fd|Url=oqtl>P1nP+L1qfDPb}O+G?#X;C=2Fv=vpf&UPvR{ zc*aUb{CV*LJO^pl3C#QC-+?Zmr(U{q!4qJ8$!r*f!xo{3umzW%SJ0m`{N&|QUkBeP z9~~-ZI7QP_D@O(9jl>^`_iceY8VsNcW5JF}+^LMTBjK!RYTL{O^Gm346Q-trb@oN= zyaw>%3x$<0zVO1uqXGD-A}af9MALPngV=$zbx1oBfML`lSVdtd67?Dh=S{!ja+{}Y zo)3XbwVDP;TV2(Ln&!4f`)aIAX9(76LoRnq1iIO{yrF7r<4DiogkqjRStftmzrWk!$L>iDh)&4hdzF4qjoyhjE^j z^D=oT*8FIN2c=`r4)R&rf+MAPbKz1RybACS-18y#E-cm7)V6SVi1cjAm8{LQ^#~?i zc}M|CIme*xn9QT>x88~uFE3=Ov7?PSuV?VVq_ZQa#*`M19Vdn zmOrucc4W((GW1K;&&WS9_wbfm&KNdT!W`9F>f+|P&BA=zI}EPh9WBh4M1vQsXB6i1 zVn5T3q!ZIWiF8aa;?SfzD3N}&=V;R**?gHS|^&ZiG_Bkunnj_fE&T2d@JpI!=(eZ zAM_HBrK9CInu}$(0>g@o&55?orI?_h+lA@6Cl+p#rb9Wu=^fE7Y>A@#zIam&b6hzQ zNVzwRbLO)}jw2q?+;>Ail;v^IeWQ@I>nm(L3 zVRIPb6w{GLid%rKBj);=)M0pFv$1J5#UfiHjTpuQo#;2#^Qfa+%xem8zX)Acg!trb z(kDzXa!(ccqAapnVLLxYVkl~gRN}HLt`+!?bJXYyoPH*fcjp)8y90DQIKSd*1{lRBR|`mitmi z9tnmJJ>*6VPC(@whi@r&j91#PNHxoMMf#dZEHL9?;JW-cQsIWkf|?3uBS?>N&x>bH z)*um^*$dTO`XDpp8vEUUXFzF3LpRo15yX0CWf5i40{8fG1%7Y7>{#04#Xq%jFyMjk=GkcP-DS`Nl4Zk?E*E zd5fu$67Mv%F-DEvVtkm97$0(+N<7JeP)GDL>q*z5!l*AM8kr@vk0_|yQ$s8F9-XYk z2r4b^H2jTS2`T=x?1n8fs0ZarEF2UEh{l>- zy{Iy1u+!Lx!P5ZsD0QQ3OJb@^8V(#vlMxO;j+h2zy5Vz|%&;&Y%0kcD;K;nFkHU3& zCx*w>Jj=x^LFJfpXrf*`)yg>B$8wBdrUu5*qo~AXCB-Erh4DXvkcW{8(;|*v0hv@! zw4FVOjgSw$CvS-{{0v0OM1(Ix53ZrD^H?Ru^O!HsHGu2trBTb7 zfUlzNSoFag+8$@D;6oMkiYun9bU%rOUiN*adp$YXdJ#3U>u=Hk=qw?<8Upk zueAIR)-U~OP2y6w8`Vj?(`}p(=Gd%aB%|;op#euOXt6-<45JYT>Jhc`8smmdFP2(Z zo!6zMvjYc20dy?{-xWcF3(Es6M;<*fP7DF^hQ{H8$Kyl^pc1ei&<^MZTm!fPV8}`= z>F_EH1lp9FkD)xl9sq$RzW)JcPg=ObmIDAj<8)#f#DQCwMcc8GeF~af? zhGSH@_=8^_{h0*dyRgsZu)Oi)nG!ZZ2pOi141Et97biwGGj*AfEW>$ zVTM(X3`;k|w2@(|878#kJZ1aNLPIB14xntbhJHzH$0NcBpCiL2A|~S{i|U=44hfKs zGD=Pt?+1iwV}(&4A#lw8L#AVfp|{5jL*b)_Q5%q_(S}rdp)k~C%rKCa5mticq|#Ys zyu6WN17m~%FTk9Mv($751L=+#Mz}R_Jt7@7YOJuzGlbDt88sdHXaMO9e2yrO5HV^x z&^)!lpuyC12%|QP6-I3sD=hB}VcHqOD$fu$aE34%4`bDZa5icf(KT*E9~EaDmN$AB z^NFm{^W-q~3}I8iFPYzQ@gpG@bWsL~Sjfdrp2peyP4a9NHM-t3QNo#jI&(SCuWiI8R5uCmk7gG zj!0Il94#zOhJhiN=~C;0z9ptO)?AD%wK3}{#u#JN22}J6=}b8}wJuCAl_tH65;ky# zFrg5h@JmgHy5zxg1kM!6my+h&RNAGnB95B#13rP8L=&hdv1X&Z)O3hv{-Qt45z8OU z5l;fH!}BKq1?^@qf3OZ3h`PIxok9{`20Jx!f^L)Ue>?h z?@Nv>H{2(LIP|%__b!z37D=)xve&sJev*CSqWred4 ze)B3XUs($OvdZn7$`Q7p^7VgSgzzPm(|1=O&a%pl2bUw>ipsjLRU&RxWp|z(@$Hp2 z-d&9}j>?D2Ymly{^7-F7k#=R};QCcaUt78LF zS#Z5@{IXbV|6rTgePK{keXULW@#ZC>W$O~L{rD2`-L`F_;N%lx=z^u z5vMmD5f|)g6IoaM6F$s(skr)6r#Sl1CZX;5y;yks2jZQdo+rNQx>;mRe_wp#4qfb+ z)F%F^(kliI#>7S8dXbS)DxSM^vUv7^u(XL~SnPRZ zPNYOX8bibV{2(CO+)KtJ+7!6w+XruZMI5yJY$O#~q)Ybzj+Cx83;r ztY2Jas}4NuDai0nEE)EzZEzx=PSH@+fO~KKqNKEJe))ohixw}bvR6B5h#e&PxjNj~ z_(XmMbTtDGUlC)}hW!#A1@s#hiq{+RQh)dwn(;IItN3T^7)xkBCLJXUJ)27cj@B9no^Jss+D15Xu{}=sm-)`;t zczH(+emAR9dTo$yHMen{1I;Xg`aH7tri1^7WF?>RV{WL{KmTS&DG+WhOV9` zAF3A1Z*G5g{oB=*H$K*P-hWJXH2wWAe|&e^8pkcK)Mxzu=z!xNtKa@zTG3;U-FLm( zU)^`aVditLKmD=Ce*S&uCnr~YU};=jUv^%}$yL4AZ(O!F{Pi~*Cr3#hq%Op=iWquK z>>b*ZwdaTU-uh#Kabl{HB_7|JBkp(rbK1XQe!^Ur90y5+vO8_nHm9?2i2cUL)%50tCz zRqfY#@!7*WCLUGNPaasbYpJ^K3 z=JA2~mi7W?+Rmf+hHje8e8T3;9N3N8gDbD!S(TJRxm_I15NSJuE2;isAMWxX1i=04 z{ZcX~Tzq3Mi#RM_xFYiThI52?Y@K{2#<})Z`FtFWTXI{LF!y)PczB%1M0g2Yl2sgV zC&OJ2_guIiJ~U3`;+cLFz6{^6C;@2yJx&w?$^n&tRe&bIdcfrX4L{i($Z&T2qk?MJ~f+}zSUAG^0HNAK;l(q`gLiQG5JyY8Q zn3W;RH@wGmZqG3!+c9JOpARtWI${2c50#(Y^Zti#rJH)(|M|lHH^=|Q!2e<(1p_3{ znjW`;PY`T3;9j@{4;!!>F2NoHo`y^Cf&nkXC3wStci|FzXuxr}1fLq9W`Z{Yat)XS zmtckgv)~dG8c+_GV3`39xCC_uw8AC0+yD<;f^GvMa0#w4U>jV58x6P>F2QyK?uAS6 zumQW_66`VHX}AP081OP&f;S9!7cRkv1{{Y=@Tmc67TOQUHDD54f*A(Pf=f_nKsj83 zWd=Cl64V*c3YXw=13YjEx($fHCAh|bZEy*0G~iaa1ltX`7cRlW2JD7Qu*ZO>;S#)H zz{_w6-Z0=@xC9>>a2zhdrv|9mXg?s=fJtx(W*9IFE8Q_3RP-j3ZT!PCD z@W3VLHXs6*;2HzA!6mrSfLq}bY&YOuxC9Ryup2JH9s{0+OYnjLFT*8x!+>|;5`1XD zakvDZ8ldK&{eWBpCc!0`VZbc71ce5a!zEZ|fCDZ;odKDriveCoordinates(); const Move *move = reprap.GetMove(); if (doMotorMapping) { - move->MotorTransform(nextMove->coords, endPoint); // transform the axis coordinates if on a delta or CoreXY printer + move->MotorTransform(nextMove.coords, endPoint); // transform the axis coordinates if on a delta or CoreXY printer isDeltaMovement = move->IsDeltaMode() && (endPoint[X_AXIS] != positionNow[X_AXIS] || endPoint[Y_AXIS] != positionNow[Y_AXIS] || endPoint[Z_AXIS] != positionNow[Z_AXIS]); } @@ -106,13 +106,13 @@ bool DDA::Init(const GCodes::RawMove *nextMove, bool doMotorMapping) accelerations[drive] = normalAccelerations[drive]; if (drive >= AXES || !doMotorMapping) { - endPoint[drive] = Move::MotorEndPointToMachine(drive, nextMove->coords[drive]); + endPoint[drive] = Move::MotorEndPointToMachine(drive, nextMove.coords[drive]); } int32_t delta; if (drive < AXES) { - endCoordinates[drive] = nextMove->coords[drive]; + endCoordinates[drive] = nextMove.coords[drive]; delta = endPoint[drive] - positionNow[drive]; } else @@ -123,7 +123,7 @@ bool DDA::Init(const GCodes::RawMove *nextMove, bool doMotorMapping) DriveMovement& dm = ddm[drive]; if (drive < AXES && !isSpecialDeltaMove) { - directionVector[drive] = nextMove->coords[drive] - prev->GetEndCoordinate(drive, false); + directionVector[drive] = nextMove.coords[drive] - prev->GetEndCoordinate(drive, false); dm.state = (isDeltaMovement || delta != 0) ? DMState::moving // on a delta printer, if one tower moves then we assume they all do : DMState::idle; @@ -168,9 +168,9 @@ bool DDA::Init(const GCodes::RawMove *nextMove, bool doMotorMapping) } // 3. Store some values - endStopsToCheck = nextMove->endStopsToCheck; - filePos = nextMove->filePos; - usePressureAdvance = nextMove->usePressureAdvance; + endStopsToCheck = nextMove.endStopsToCheck; + filePos = nextMove.filePos; + usePressureAdvance = nextMove.usePressureAdvance; // The end coordinates will be valid at the end of this move if it does not involve endstop checks and is not a special move on a delta printer endCoordinatesValid = (endStopsToCheck == 0) && (doMotorMapping || !move->IsDeltaMode()); @@ -271,7 +271,7 @@ bool DDA::Init(const GCodes::RawMove *nextMove, bool doMotorMapping) // Set the speed to the smaller of the requested and maximum speed. // Also enforce a minimum speed of 0.5mm/sec. We need a minimum speed to avoid overflow in the movement calculations. - float reqSpeed = nextMove->feedRate; + float reqSpeed = nextMove.feedRate; if (isSpecialDeltaMove) { // Special case of a raw or homing move on a delta printer @@ -338,6 +338,7 @@ float DDA::GetMotorPosition(size_t drive) const return Move::MotorEndpointToPosition(endPoint[drive], drive); } +// Try to increase the ending speed of this move to allow the next move to start at targetNextSpeed void DDA::DoLookahead(DDA *laDDA) //pre(state == provisional) { @@ -350,32 +351,34 @@ void DDA::DoLookahead(DDA *laDDA) bool recurse = false; if (goingUp) { - // We have been asked to adjust the end speed of this move to targetStartSpeed + // We have been asked to adjust the end speed of this move to match the next move starting at targetNextSpeed if (laDDA->topSpeed == laDDA->requestedSpeed) { // This move already reaches its top speed, so just need to adjust the deceleration part - laDDA->endSpeed = laDDA->requestedSpeed; - laDDA->CalcNewSpeeds(); + laDDA->endSpeed = laDDA->requestedSpeed; // remove the deceleration phase + laDDA->CalcNewSpeeds(); // put it back if necessary } else if (laDDA->decelDistance == laDDA->totalDistance && laDDA->prev->state == provisional) { - // This move doesn't reach its requested speed, so we may have to adjust the previous move as well to get optimum behaviour + // This is a deceleration-only move, so we may have to adjust the previous move as well to get optimum behaviour laDDA->endSpeed = laDDA->requestedSpeed; laDDA->CalcNewSpeeds(); - laDDA->prev->targetNextSpeed = min(sqrtf((laDDA->endSpeed * laDDA->endSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)), laDDA->requestedSpeed); + laDDA->prev->targetNextSpeed = min(sqrtf(fsquare(laDDA->endSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)), + laDDA->requestedSpeed); recurse = true; } else { - // This move doesn't reach its requested speed, but we can't adjust the previous one - laDDA->endSpeed = min(sqrtf((laDDA->startSpeed * laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)), laDDA->requestedSpeed); + // This move doesn't reach its requested speed, but it isn't a deceleration-only move, or we can't adjust the previous one + laDDA->endSpeed = min(sqrtf(fsquare(laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)), + laDDA->requestedSpeed); laDDA->CalcNewSpeeds(); } } else { laDDA->startSpeed = laDDA->prev->targetNextSpeed; - float maxEndSpeed = sqrtf((laDDA->startSpeed * laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)); + float maxEndSpeed = sqrtf(fsquare(laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)); if (maxEndSpeed < laDDA->endSpeed) { // Oh dear, we were too optimistic! Have another go. @@ -410,18 +413,18 @@ void DDA::DoLookahead(DDA *laDDA) // Recalculate the top speed, acceleration distance and deceleration distance, and whether we can pause after this move void DDA::RecalculateMove() { - accelDistance = ((requestedSpeed * requestedSpeed) - (startSpeed * startSpeed))/(2.0 * acceleration); - decelDistance = ((requestedSpeed * requestedSpeed) - (endSpeed * endSpeed))/(2.0 * acceleration); + accelDistance = (fsquare(requestedSpeed) - fsquare(startSpeed))/(2.0 * acceleration); + decelDistance = (fsquare(requestedSpeed) - fsquare(endSpeed))/(2.0 * acceleration); if (accelDistance + decelDistance >= totalDistance) { // It's an accelerate-decelerate move. If V is the peak speed, then (V^2 - u^2)/2a + (V^2 - v^2)/2a = distance. // So (2V^2 - u^2 - v^2)/2a = distance // So V^2 = a * distance + 0.5(u^2 + v^2) - float vsquared = (acceleration * totalDistance) + 0.5 * ((startSpeed * startSpeed) + (endSpeed * endSpeed)); + float vsquared = (acceleration * totalDistance) + 0.5 * (fsquare(startSpeed) + fsquare(endSpeed)); // Calculate accelerate distance from: V^2 = u^2 + 2as if (vsquared >= 0.0) { - accelDistance = max((vsquared - (startSpeed * startSpeed))/(2.0 * acceleration), 0.0); + accelDistance = max((vsquared - fsquare(startSpeed))/(2.0 * acceleration), 0.0); decelDistance = totalDistance - accelDistance; topSpeed = sqrtf(vsquared); } @@ -593,9 +596,48 @@ void DDA::Prepare() params.decelStartDistance = totalDistance - decelDistance; // Convert the accelerate/decelerate distances to times - const float accelStopTime = (topSpeed - startSpeed)/acceleration; - const float decelStartTime = accelStopTime + (params.decelStartDistance - accelDistance)/topSpeed; - const float totalTime = decelStartTime + (topSpeed - endSpeed)/acceleration; + float accelStopTime = (topSpeed - startSpeed)/acceleration; + float decelStartTime = accelStopTime + (params.decelStartDistance - accelDistance)/topSpeed; + float totalTime = decelStartTime + (topSpeed - endSpeed)/acceleration; + + // Enforce the maximum average acceleration + if (isPrintingMove && topSpeed > startSpeed && topSpeed > endSpeed) + { + const float maxAverageAcceleration = reprap.GetPlatform()->GetMaxAverageAcceleration(); + if (2 * topSpeed - startSpeed - endSpeed > totalTime * maxAverageAcceleration) + { + // Reduce the top speed to comply with the maximum average acceleration + const float a2 = fsquare(acceleration); + const float am2 = fsquare(maxAverageAcceleration); + const float aam = acceleration * maxAverageAcceleration; + const float discriminant = (a2 + (2 * aam) - am2) * (fsquare(startSpeed) + fsquare(endSpeed)) + + (2 * a2 + 2 * am2 - 4 * aam) * startSpeed * endSpeed + + (8 * a2 * maxAverageAcceleration - 4 * acceleration * am2) * totalDistance; + const float oldTopSpeed = topSpeed; + if (discriminant < 0.0) + { + topSpeed = max(startSpeed, endSpeed); + } + else + { + const float temp = (sqrtf(discriminant) + (acceleration - maxAverageAcceleration) * (startSpeed + endSpeed)) + /(4 * acceleration - 2 * maxAverageAcceleration); + topSpeed = max(max(temp, startSpeed), endSpeed); + } + + //DEBUG + debugPrintf("ots %f nts %f ss %f es %f\n", oldTopSpeed, topSpeed, startSpeed, endSpeed); + + // Recalculate parameters + accelDistance = (fsquare(topSpeed) - fsquare(startSpeed))/(2 * acceleration); + decelDistance = (fsquare(topSpeed) - fsquare(endSpeed))/(2 * acceleration); + params.decelStartDistance = totalDistance - decelDistance; + accelStopTime = (topSpeed - startSpeed)/acceleration; + decelStartTime = accelStopTime + (params.decelStartDistance - accelDistance)/topSpeed; + totalTime = decelStartTime + (topSpeed - endSpeed)/acceleration; + } + } + clocksNeeded = (uint32_t)(totalTime * stepClockRate); params.startSpeedTimesCdivA = (uint32_t)((startSpeed * stepClockRate)/acceleration); @@ -896,7 +938,7 @@ quit: uint32_t finishTime = moveStartTime + clocksNeeded; // calculate how long this move should take Move *move = reprap.GetMove(); move->CurrentMoveCompleted(); // tell Move that the current move is complete - return move->StartNextMove(finishTime); // schedule the next move + return move->TryStartNextMove(finishTime); // schedule the next move } return false; } diff --git a/src/DDA.h b/src/DDA.h index 92053f5..ddb3913 100644 --- a/src/DDA.h +++ b/src/DDA.h @@ -30,7 +30,7 @@ public: DDA(DDA* n); - bool Init(const GCodes::RawMove *nextMove, bool doMotorMapping); // Set up a new move, returning true if it represents real movement + bool Init(const GCodes::RawMove &nextMove, bool doMotorMapping); // Set up a new move, returning true if it represents real movement void Init(); // Set up initial positions for machine startup bool Start(uint32_t tim); // Start executing the DDA, i.e. move the move. bool Step(); // Take one step of the DDA, called by timed interrupt. diff --git a/src/Duet/Pins_duet.h b/src/Duet/Pins_duet.h index b6f2151..79637b2 100644 --- a/src/Duet/Pins_duet.h +++ b/src/Duet/Pins_duet.h @@ -50,7 +50,6 @@ const float SENSE_RESISTOR = 0.1; // Stepper motor current sense resist const float MAX_STEPPER_DIGIPOT_VOLTAGE = (3.3 * 2.5 / (2.7 + 2.5)); // Stepper motor current reference voltage const float STEPPER_DAC_VOLTAGE_RANGE = 2.02; // Stepper motor current reference voltage for E1 if using a DAC const float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor current offset voltage for E1 if using a DAC -const int DAC0_DIGITAL_PIN = 66; // Arduino Due pin number corresponding to DAC0 output pin // HEATERS @@ -100,7 +99,7 @@ const Pin Z_PROBE_MOD_PIN = 52; // Digital pin number to turn the IR L const Pin Z_PROBE_MOD_PIN07 = X12; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.7 and v0.8.5 (PC10) // Pin number that the DAC that controls the second extruder motor current on the Duet 0.8.5 is connected to -const int Dac0DigitalPin = 66; // Arduino Due pin number corresponding to DAC0 output pin +const int Dac0DigitalPin = 66; // Arduino Due pin number corresponding to DAC0 output pin // COOLING FANS diff --git a/src/Duet/Webserver.cpp b/src/Duet/Webserver.cpp index 2dffd96..d335216 100644 --- a/src/Duet/Webserver.cpp +++ b/src/Duet/Webserver.cpp @@ -609,6 +609,42 @@ void Webserver::HttpInterpreter::DoFastUpload() if (transaction->ReadBuffer(buffer, len)) { network->Unlock(); +#if 1 + // Write data in sector-aligned chunks. This also means that the buffer in fatfs is only used to hold the FAT. + static const size_t writeBufLength = 2048; // use a multiple of the 512b sector size + static uint32_t writeBufStorage[writeBufLength/4]; // aligned buffer for file writes + static size_t writeBufIndex; + char* const writeBuf = (char *)writeBufStorage; + + if (uploadedBytes == 0) + { + writeBufIndex = 0; + } + + while (len != 0) + { + size_t lengthToCopy = min(writeBufLength - writeBufIndex, len); + memcpy(writeBuf + writeBufIndex, buffer, lengthToCopy); + writeBufIndex += lengthToCopy; + uploadedBytes += lengthToCopy; + buffer += lengthToCopy; + len -= lengthToCopy; + if (writeBufIndex == writeBufLength || uploadedBytes >= postFileLength) + { + bool success = fileBeingUploaded.Write(writeBuf, writeBufIndex); + writeBufIndex = 0; + if (!success) + { + platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n"); + CancelUpload(); + + while (!network->Lock()); + SendJsonResponse("upload"); + return; + } + } + } +#else if (!fileBeingUploaded.Write(buffer, len)) { platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n"); @@ -619,6 +655,7 @@ void Webserver::HttpInterpreter::DoFastUpload() return; } uploadedBytes += len; +#endif while (!network->Lock()); } diff --git a/src/ExternalDrivers.cpp b/src/ExternalDrivers.cpp index a8a6c92..985803a 100644 --- a/src/ExternalDrivers.cpp +++ b/src/ExternalDrivers.cpp @@ -370,7 +370,7 @@ namespace ExternalDrivers USART_EXT_DRV->US_BRGR = VARIANT_MCK/DriversSpiClockFrequency; // 1MHz SPI clock USART_EXT_DRV->US_CR = US_CR_RSTRX | US_CR_RSTTX | US_CR_RXDIS | US_CR_TXDIS | US_CR_RSTSTA; - // We need a few microseconds of delay here foe the USART to sort itself out, + // We need a few microseconds of delay here for the USART to sort itself out, // otherwise the processor generates two short reset pulses on its own NRST pin, and resets itself. // But it looks like the TMC drivers need a longer delay anyway to get used to CS being high, // otherwise they ignore the command we send to set the microstepping to x16 and start up in full-step mode. diff --git a/src/GCodes.cpp b/src/GCodes.cpp index e1a04c2..be7fa92 100644 --- a/src/GCodes.cpp +++ b/src/GCodes.cpp @@ -2582,7 +2582,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) bool error = false; int code = gb->GetIValue(); - if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 && code != 999) + if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 && code != 408 && code != 999) { return true; // we don't yet simulate most M codes } @@ -2592,22 +2592,39 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) case 0: // Stop case 1: // Sleep if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) - return false; - - if (fileBeingPrinted.IsLive()) { - fileBeingPrinted.Close(); + return false; } - // Deselect the active tool + // Reset everything + CancelPrint(); + + if (isPaused) + { + isPaused = false; + reply.copy("Print cancelled"); + // If we are cancelling a paused print with M0 and cancel.g exists then run it + if (code == 0) + { + if (DoFileMacro(CANCEL_G, false)) + { + break; + } + } + } + + // Otherwise, deselect the active tool, if any { Tool* tool = reprap.GetCurrentTool(); - if (tool != NULL) + if (tool != nullptr) { reprap.StandbyTool(tool->Number()); } } + // Turn the heaters off + reprap.GetHeat()->SwitchOffAll(); + // zpl 2014-18-10: Although RRP says M0 is supposed to turn off all drives and heaters, // I think M1 is sufficient for this purpose. Leave M0 for a normal reset. if (code == 1) @@ -2618,16 +2635,6 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) { platform->SetDrivesIdle(); } - - reprap.GetHeat()->SwitchOffAll(); - if (isPaused) - { - isPaused = false; - reply.copy("Print cancelled"); - } - - // Reset everything - CancelPrint(); break; #if SUPPORT_ROLAND @@ -3724,6 +3731,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) } } + if (gb->Seen('P')) + { + // Set max average printing acceleration + platform->SetMaxAverageAcceleration(gb->GetFValue() * distanceScale); + seen = true; + } + if (!seen) { reply.printf("Accelerations: X: %.1f, Y: %.1f, Z: %.1f, E: ", @@ -3737,6 +3751,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) reply.cat(":"); } } + reply.catf(", avg. printing: %.1f", platform->GetMaxAverageAcceleration()); } } break; @@ -5119,7 +5134,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) isFlashing = false; // should never get here, but leave this here in case an error has occurred } #ifdef DUET_NG - else if (sparam == 1 || sparam == 2) + else if (sparam >= 1 && sparam <= 3) { reprap.GetNetwork()->FirmwareUpdate(sparam); } diff --git a/src/Heat.cpp b/src/Heat.cpp index a33fcde..3be29da 100644 --- a/src/Heat.cpp +++ b/src/Heat.cpp @@ -317,7 +317,7 @@ void PID::Spin() } // Now check how long it takes to warm up. If too long, maybe the thermistor is not in contact with the heater - if (heatingUp && heater != reprap.GetHeat()->GetBedHeater()) // FIXME - also check bed warmup time? + if (heatingUp && heater != reprap.GetHeat()->GetBedHeater() && heater != reprap.GetHeat()->GetChamberHeater()) // FIXME - also check bed warmup time? { float tmp = (active) ? activeTemperature : standbyTemperature; if (temperature < tmp - TEMPERATURE_CLOSE_ENOUGH) diff --git a/src/Move.cpp b/src/Move.cpp index ee3ce5c..9dbb2e7 100644 --- a/src/Move.cpp +++ b/src/Move.cpp @@ -190,7 +190,7 @@ void Move::Spin() { Transform(nextMove.coords); } - if (ddaRingAddPointer->Init(&nextMove, doMotorMapping)) + if (ddaRingAddPointer->Init(nextMove, doMotorMapping)) { ddaRingAddPointer = ddaRingAddPointer->GetNext(); idleCount = 0; @@ -200,19 +200,7 @@ void Move::Spin() } } - if (simulating) - { - if (idleCount > 10 && !DDARingEmpty()) - { - // No move added this time, so simulate executing one already in the queue - DDA *dda = ddaRingGetPointer; - simulationTime += dda->CalcTime(); - liveCoordinatesValid = dda->FetchEndPosition(const_cast(liveEndPoints), const_cast(liveCoordinates)); - dda->Complete(); - ddaRingGetPointer = ddaRingGetPointer->GetNext(); - } - } - else if (!deltaProbing) + if (!deltaProbing) { // See whether we need to kick off a move DDA *cdda = currentDda; // currentDda is volatile, so copy it @@ -228,20 +216,27 @@ void Move::Spin() } if (dda->GetState() == DDA::frozen) { - cpu_irq_disable(); // must call StartNextMove and Interrupt with interrupts disabled - if (StartNextMove(Platform::GetInterruptClocks())) // start the next move if none is executing already + if (simulating) { - Interrupt(); + currentDda = ddaRingGetPointer; // pretend we are executing this move + } + else + { + cpu_irq_disable(); // must call StartNextMove and Interrupt with interrupts disabled + if (StartNextMove(Platform::GetInterruptClocks())) // start the next move + { + Interrupt(); + } + cpu_irq_enable(); } - cpu_irq_enable(); iState = IdleState::busy; } - else if (iState == IdleState::busy && !reprap.GetGCodes()->IsPaused() && idleTimeout > 0.0) + else if (!simulating && iState == IdleState::busy && !reprap.GetGCodes()->IsPaused() && idleTimeout > 0.0) { lastMoveTime = reprap.GetPlatform()->Time(); // record when we first noticed that the machine was idle iState = IdleState::timing; } - else if (iState == IdleState::timing && reprap.GetPlatform()->Time() - lastMoveTime >= idleTimeout) + else if (!simulating && iState == IdleState::timing && reprap.GetPlatform()->Time() - lastMoveTime >= idleTimeout) { reprap.GetPlatform()->SetDrivesIdle(); // put all drives in idle hold iState = IdleState::idle; @@ -271,6 +266,15 @@ void Move::Spin() cdda = cdda->GetNext(); st = cdda->GetState(); } + + if (simulating) + { + // Simulate completion of the current move +//DEBUG +//currentDda->DebugPrint(); + simulationTime += currentDda->CalcTime(); + CurrentMoveCompleted(); + } } } @@ -1133,13 +1137,12 @@ void Move::CurrentMoveCompleted() ddaRingGetPointer = ddaRingGetPointer->GetNext(); } -// Start the next move. Must be called with interrupts disabled, to avoid a race condition. -bool Move::StartNextMove(uint32_t startTime) +// Try to start another move. Must be called with interrupts disabled, to avoid a race condition. +bool Move::TryStartNextMove(uint32_t startTime) { if (ddaRingGetPointer->GetState() == DDA::frozen) { - currentDda = ddaRingGetPointer; - return currentDda->Start(startTime); + return StartNextMove(startTime); } else { diff --git a/src/Move.h b/src/Move.h index 0ff228e..e8b3ed6 100644 --- a/src/Move.h +++ b/src/Move.h @@ -77,10 +77,10 @@ public: void SetCoreXYMode(int mode) { coreXYMode = mode; } float GetCoreAxisFactor(size_t axis) const { return axisFactors[axis]; } void setCoreAxisFactor(size_t axis, float f) { axisFactors[axis] = f; } - bool IsCoreXYAxis(size_t axis) const; // return true if the specified axis shares its motors with another + bool IsCoreXYAxis(size_t axis) const; // Return true if the specified axis shares its motors with another - void CurrentMoveCompleted(); // signals that the current move has just been completed - bool StartNextMove(uint32_t startTime); // start the next move, returning true if Step() needs to be called immediately + void CurrentMoveCompleted(); // Signal that the current move has just been completed + bool TryStartNextMove(uint32_t startTime); // Try to start another move, returning true if Step() needs to be called immediately void MotorTransform(const float machinePos[AXES], int32_t motorPos[AXES]) const; // Convert Cartesian coordinates to delta motor coordinates float MotorFactor(size_t drive, const float directionVector[]) const; // Calculate the movement fraction for a single axis motor of a Cartesian or CoreXY printer void MachineToEndPoint(const int32_t motorPos[], float machinePos[], size_t numDrives) const; // Convert motor coordinates to machine coordinates @@ -107,6 +107,7 @@ private: enum class IdleState : uint8_t { idle, busy, timing }; + bool StartNextMove(uint32_t startTime); // start the next move, returning true if Step() needs to be called immediately void SetProbedBedEquation(size_t numPoints, StringRef& reply); // When we have a full set of probed points, work out the bed's equation void DoDeltaCalibration(size_t numPoints, StringRef& reply); void BedTransform(float move[AXES]) const; // Take a position and apply the bed compensations @@ -180,11 +181,9 @@ inline bool Move::NoLiveMovement() const return DDARingEmpty() && currentDda == nullptr; // must test currentDda and DDARingEmpty *in this order* ! } -// To wait until all the current moves in the buffers are -// complete, call this function repeatedly and wait for it to -// return true. Then do whatever you wanted to do after all -// current moves have finished. THEN CALL THE ResumeMoving() FUNCTION -// OTHERWISE NOTHING MORE WILL EVER HAPPEN. +// To wait until all the current moves in the buffers are complete, call this function repeatedly and wait for it to return true. +// Then do whatever you wanted to do after all current moves have finished. +// Then call ResumeMoving() otherwise nothing more will ever happen. inline bool Move::AllMovesAreFinished() { addNoMoreMoves = true; @@ -196,4 +195,12 @@ inline void Move::ResumeMoving() addNoMoreMoves = false; } +// Start the next move. Must be called with interrupts disabled, to avoid a race with the step ISR. +inline bool Move::StartNextMove(uint32_t startTime) +//pre(ddaRingGetPointer->GetState() == DDA::frozen) +{ + currentDda = ddaRingGetPointer; + return currentDda->Start(startTime); +} + #endif /* MOVE_H_ */ diff --git a/src/Platform.cpp b/src/Platform.cpp index e3ff82b..509b2ff 100644 --- a/src/Platform.cpp +++ b/src/Platform.cpp @@ -209,6 +209,7 @@ void Platform::Init() maxStepperDigipotVoltage = MAX_STEPPER_DIGIPOT_VOLTAGE; stepperDacVoltageRange = STEPPER_DAC_VOLTAGE_RANGE; stepperDacVoltageOffset = STEPPER_DAC_VOLTAGE_OFFSET; + maxAverageAcceleration = 10000.0; // high enough to have no effect until it is changed // Z PROBE @@ -242,6 +243,10 @@ void Platform::Init() } // Motors + for (size_t drive = 0; drive < DRIVES; drive++) + { + driverNumbers[drive] = -1; // needed so that SetPhysicalDrive() behaves correctly + } for (size_t drive = 0; drive < DRIVES; drive++) { @@ -1611,7 +1616,7 @@ void Platform::EnableDrive(size_t drive) UpdateMotorCurrent(driver); // the current may have been reduced by the idle timeout #ifdef EXTERNAL_DRIVERS - if (drive >= FIRST_EXTERNAL_DRIVE) + if (driver >= FIRST_EXTERNAL_DRIVE) { ExternalDrivers::EnableDrive(driver - FIRST_EXTERNAL_DRIVE, true); } @@ -1637,7 +1642,7 @@ void Platform::DisableDrive(size_t drive) { const size_t driver = driverNumbers[drive]; #ifdef EXTERNAL_DRIVERS - if (drive >= FIRST_EXTERNAL_DRIVE) + if (driver >= FIRST_EXTERNAL_DRIVE) { ExternalDrivers::EnableDrive(driver - FIRST_EXTERNAL_DRIVE, false); } @@ -1729,7 +1734,7 @@ void Platform::UpdateMotorCurrent(size_t drive) } #ifndef DUET_NG } - else + else if (driver < 8) // on a Duet 0.6 we have a maximum of 8 drives { mcpExpansion.setNonVolatileWiper(potWipes[driver], pot); mcpExpansion.setVolatileWiper(potWipes[driver], pot); @@ -1806,13 +1811,22 @@ unsigned int Platform::GetMicrostepping(size_t drive, bool& interpolation) const void Platform::SetPhysicalDrive(size_t driverNumber, int8_t physicalDrive) { int oldDrive = GetPhysicalDrive(driverNumber); - if (oldDrive >= 0) + if (oldDrive != physicalDrive) { - driverNumbers[oldDrive] = -1; - stepPinDescriptors[oldDrive] = OutputPin(); + if (oldDrive >= 0) + { + DisableDrive(oldDrive); // turn off the motor current + driverNumbers[oldDrive] = -1; + stepPinDescriptors[oldDrive] = OutputPin(); + } + + if (physicalDrive >= 0) + { + driverNumbers[physicalDrive] = driverNumber; + stepPinDescriptors[physicalDrive] = OutputPin(stepPins[driverNumber]); + driveState[physicalDrive] = DriveStatus::disabled; + } } - driverNumbers[physicalDrive] = driverNumber; - stepPinDescriptors[physicalDrive] = OutputPin(stepPins[driverNumber]); } // Return the physical drive used by this driver, or -1 if not found @@ -2281,8 +2295,10 @@ float Platform::ActualInstantDv(size_t drive) const if (drive >= AXES) { float eComp = elasticComp[drive - AXES]; - // If we are using elastic compensation then we need to limit the instantDv to avoid velocity mismatches - return (eComp <= 0.0) ? idv : min(idv, 1.0/(eComp * driveStepsPerUnit[drive])); + // If we are using elastic compensation then we need to limit the extruder instantDv to avoid velocity mismatches. + // Assume that we want the extruder motor position to be accurate to within 0.01mm of extrusion. + // TODO remove this limit and add/remove steps to the previous and/or next move instead + return (eComp <= 0.0) ? idv : min(idv, 0.01/eComp); } else { diff --git a/src/Platform.h b/src/Platform.h index d097a2f..956917a 100644 --- a/src/Platform.h +++ b/src/Platform.h @@ -516,6 +516,8 @@ public: float Acceleration(size_t drive) const; const float* Accelerations() const; void SetAcceleration(size_t drive, float value); + const float GetMaxAverageAcceleration() const { return maxAverageAcceleration; } + void SetMaxAverageAcceleration(float f) { maxAverageAcceleration = f; } float MaxFeedrate(size_t drive) const; const float* MaxFeedrates() const; void SetMaxFeedrate(size_t drive, float value); @@ -723,6 +725,7 @@ private: float motorCurrents[DRIVES]; float idleCurrentFactor; size_t slowestDrive; + float maxAverageAcceleration; // Digipots diff --git a/src/PrintMonitor.cpp b/src/PrintMonitor.cpp index 6771a69..6a186e5 100644 --- a/src/PrintMonitor.cpp +++ b/src/PrintMonitor.cpp @@ -593,9 +593,17 @@ bool PrintMonitor::GetFileInfoResponse(const char *filename, OutputBuffer *&resp if (filename != nullptr && filename[0] != 0) { GCodeFileInfo info; - if (!GetFileInfo(FS_PREFIX, filename, info)) + + // Getting file information take a few runs. Speed it up when we are not printing by calling it several times. + uint32_t startTime = millis(); + bool gotFileInfo; + do + { + gotFileInfo = GetFileInfo(FS_PREFIX, filename, info); + } while (!gotFileInfo && !isPrinting && millis() - startTime < MAX_FILEINFO_PROCESS_TIME); + + if (!gotFileInfo) { - // This may take a few runs... return false; } diff --git a/src/PrintMonitor.h b/src/PrintMonitor.h index 243fa89..380bfc6 100644 --- a/src/PrintMonitor.h +++ b/src/PrintMonitor.h @@ -26,7 +26,7 @@ const FilePosition GCODE_FOOTER_SIZE = 192000uL; // How many bytes to read from #ifdef DUET_NG const size_t GCODE_READ_SIZE = 4096; // How many bytes to read in one go in GetFileInfo() (should be a multiple of 512 for read efficiency) #else -const size_t GCODE_READ_SIZE = 2048; // How many bytes to read in one go in GetFileInfo() (should be a multiple of 512 for read efficiency) +const size_t GCODE_READ_SIZE = 1024; // How many bytes to read in one go in GetFileInfo() (should be a multiple of 512 for read efficiency) #endif const size_t GCODE_OVERLAP_SIZE = 100; // Size of the overlapping buffer for searching (should be a multiple of 4) @@ -39,6 +39,7 @@ const float ESTIMATION_MIN_FILE_USAGE = 0.001; // Minium per cent of the file t const float FIRST_LAYER_SPEED_FACTOR = 0.25; // First layer speed factor compared to other layers (only for layer-based estimation) const uint32_t PRINTMONITOR_UPDATE_INTERVAL = 200; // Update interval in milliseconds +const uint32_t MAX_FILEINFO_PROCESS_TIME = 100; // Maximum time to spend polling for file info in each call enum PrintEstimationMethod {